From 1c691c8fabbdd06f5e88d6a4b32f9f381180c033 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 9 Oct 2023 09:13:46 +0900 Subject: [PATCH 001/499] AP_OpenDroneID: fix comment typo --- libraries/AP_OpenDroneID/AP_OpenDroneID.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp b/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp index 9aa153706ab3ec..0e643d8d863ad9 100644 --- a/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp +++ b/libraries/AP_OpenDroneID/AP_OpenDroneID.cpp @@ -554,7 +554,7 @@ void AP_OpenDroneID::send_operator_id_message() */ MAV_ODID_HOR_ACC AP_OpenDroneID::create_enum_horizontal_accuracy(float accuracy) const { - // Out of bounds return UKNOWN flag + // Out of bounds return UNKNOWN flag if (accuracy < 0.0 || accuracy >= 18520.0) { return MAV_ODID_HOR_ACC_UNKNOWN; } @@ -595,7 +595,7 @@ MAV_ODID_HOR_ACC AP_OpenDroneID::create_enum_horizontal_accuracy(float accuracy) */ MAV_ODID_VER_ACC AP_OpenDroneID::create_enum_vertical_accuracy(float accuracy) const { - // Out of bounds return UKNOWN flag + // Out of bounds return UNKNOWN flag if (accuracy < 0.0 || accuracy >= 150.0) { return MAV_ODID_VER_ACC_UNKNOWN; } @@ -630,7 +630,7 @@ MAV_ODID_VER_ACC AP_OpenDroneID::create_enum_vertical_accuracy(float accuracy) c */ MAV_ODID_SPEED_ACC AP_OpenDroneID::create_enum_speed_accuracy(float accuracy) const { - // Out of bounds return UKNOWN flag + // Out of bounds return UNKNOWN flag if (accuracy < 0.0 || accuracy >= 10.0) { return MAV_ODID_SPEED_ACC_UNKNOWN; } @@ -657,7 +657,7 @@ MAV_ODID_SPEED_ACC AP_OpenDroneID::create_enum_speed_accuracy(float accuracy) co */ MAV_ODID_TIME_ACC AP_OpenDroneID::create_enum_timestamp_accuracy(float accuracy) const { - // Out of bounds return UKNOWN flag + // Out of bounds return UNKNOWN flag if (accuracy < 0.0 || accuracy >= 1.5) { return MAV_ODID_TIME_ACC_UNKNOWN; } From 3659fb633e257b790376a71b0c9b106bec2f045b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 9 Oct 2023 09:14:24 +0900 Subject: [PATCH 002/499] AP_Winch: fix daiwa unknown spelling --- libraries/AP_Winch/AP_Winch_Daiwa.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.cpp b/libraries/AP_Winch/AP_Winch_Daiwa.cpp index 21da2625214b4d..d80a8f58760d3c 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.cpp +++ b/libraries/AP_Winch/AP_Winch_Daiwa.cpp @@ -344,7 +344,7 @@ void AP_Winch_Daiwa::update_user() if (latest.moving < ARRAY_SIZE(moving_str)) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s %s", send_text_prefix, moving_str[latest.moving]); } else { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s move state uknown", send_text_prefix); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s move state unknown", send_text_prefix); } update_sent = true; } @@ -357,7 +357,7 @@ void AP_Winch_Daiwa::update_user() if (user_update.clutch < ARRAY_SIZE(clutch_str)) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s clutch %s", send_text_prefix, clutch_str[latest.moving]); } else { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s clutch state uknown", send_text_prefix); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s clutch state unknown", send_text_prefix); } update_sent = true; } From a477bf609e001f527e252892d719e4844cc25876 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 9 Oct 2023 09:21:31 +0900 Subject: [PATCH 003/499] AP_Winch: pos control user output fix --- libraries/AP_Winch/AP_Winch.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Winch/AP_Winch.cpp b/libraries/AP_Winch/AP_Winch.cpp index 5a5a7bc9b90744..4a3a41db4021e9 100644 --- a/libraries/AP_Winch/AP_Winch.cpp +++ b/libraries/AP_Winch/AP_Winch.cpp @@ -110,7 +110,7 @@ void AP_Winch::release_length(float length) // display verbose output to user if (backend->option_enabled(Options::VerboseOutput)) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Winch: lowering %4.1fm to %4.1fm", (double)length, (double)config.length_desired); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Winch: %s %4.1fm to %4.1fm", is_negative(length) ? "raising" : "lowering", (double)fabsf(length), (double)config.length_desired); } } From 19b263a2208a67ba1e9787feaffe58b0bff083ec Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 24 Oct 2023 02:41:12 +0100 Subject: [PATCH 004/499] AP_AHRS: check the health of the airspeed sensor that is being used --- libraries/AP_AHRS/AP_AHRS.cpp | 34 ++++++++++++++++++++++++---------- libraries/AP_AHRS/AP_AHRS.h | 17 ++++++++++++----- 2 files changed, 36 insertions(+), 15 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index cf702b9da423f2..4e061a465ec5df 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -806,11 +806,19 @@ bool AP_AHRS::_wind_estimate(Vector3f &wind) const } /* - return true if a real airspeed sensor is enabled + return true if the current AHRS airspeed estimate is directly derived from an airspeed sensor */ -bool AP_AHRS::airspeed_sensor_enabled(void) const +bool AP_AHRS::using_airspeed_sensor() const { - if (!AP_AHRS_Backend::airspeed_sensor_enabled()) { + return state.airspeed_estimate_type == AirspeedEstimateType::AIRSPEED_SENSOR; +} + +/* + Return true if a airspeed sensor should be used for the AHRS airspeed estimate + */ +bool AP_AHRS::_should_use_airspeed_sensor(uint8_t airspeed_index) const +{ + if (!airspeed_sensor_enabled(airspeed_index)) { return false; } nav_filter_status filter_status; @@ -831,9 +839,11 @@ bool AP_AHRS::airspeed_sensor_enabled(void) const // if we have an estimate bool AP_AHRS::_airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &airspeed_estimate_type) const { +#if AP_AHRS_DCM_ENABLED || (AP_AIRSPEED_ENABLED && AP_GPS_ENABLED) + const uint8_t idx = get_active_airspeed_index(); +#endif #if AP_AIRSPEED_ENABLED && AP_GPS_ENABLED - if (airspeed_sensor_enabled()) { - uint8_t idx = get_active_airspeed_index(); + if (_should_use_airspeed_sensor(idx)) { airspeed_ret = AP::airspeed()->get_airspeed(idx); if (_wind_max > 0 && AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) { @@ -866,7 +876,7 @@ bool AP_AHRS::_airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &airs #if AP_AHRS_DCM_ENABLED case EKFType::DCM: airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC; - return dcm.airspeed_estimate(get_active_airspeed_index(), airspeed_ret); + return dcm.airspeed_estimate(idx, airspeed_ret); #endif #if AP_AHRS_SIM_ENABLED @@ -879,7 +889,7 @@ bool AP_AHRS::_airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &airs case EKFType::TWO: #if AP_AHRS_DCM_ENABLED airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC; - return dcm.airspeed_estimate(get_active_airspeed_index(), airspeed_ret); + return dcm.airspeed_estimate(idx, airspeed_ret); #else return false; #endif @@ -893,8 +903,12 @@ bool AP_AHRS::_airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &airs #if HAL_EXTERNAL_AHRS_ENABLED case EKFType::EXTERNAL: +#if AP_AHRS_DCM_ENABLED airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC; - return dcm.airspeed_estimate(get_active_airspeed_index(), airspeed_ret); + return dcm.airspeed_estimate(idx, airspeed_ret); +#else + return false; +#endif #endif } @@ -919,7 +933,7 @@ bool AP_AHRS::_airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &airs #if AP_AHRS_DCM_ENABLED // fallback to DCM airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC; - return dcm.airspeed_estimate(get_active_airspeed_index(), airspeed_ret); + return dcm.airspeed_estimate(idx, airspeed_ret); #endif return false; @@ -3079,7 +3093,7 @@ uint8_t AP_AHRS::get_active_airspeed_index() const #if HAL_NAVEKF3_AVAILABLE if (active_EKF_type() == EKFType::THREE) { uint8_t ret = EKF3.getActiveAirspeed(); - if (ret != 255 && airspeed->healthy(ret)) { + if (ret != 255 && airspeed->healthy(ret) && airspeed->use(ret)) { return ret; } } diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 8ab6bca0457cb1..5ea8ae2ed953d8 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -151,6 +151,9 @@ class AP_AHRS { // if we have an estimate bool airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &type) const; + // return true if the current AHRS airspeed estimate (from airspeed_estimate method) is directly derived from an airspeed sensor + bool using_airspeed_sensor() const; + // return a true airspeed estimate (navigation airspeed) if // available. return true if we have an estimate bool airspeed_estimate_true(float &airspeed_ret) const; @@ -163,12 +166,13 @@ class AP_AHRS { // returns false if the data is unavailable bool airspeed_health_data(float &innovation, float &innovationVariance, uint32_t &age_ms) const; - // return true if airspeed comes from an airspeed sensor, as - // opposed to an IMU estimate - bool airspeed_sensor_enabled(void) const; + // return true if a airspeed sensor is enabled + bool airspeed_sensor_enabled(void) const { + // FIXME: make this a method on the active backend + return AP_AHRS_Backend::airspeed_sensor_enabled(); + } - // return true if airspeed comes from a specific airspeed sensor, as - // opposed to an IMU estimate + // return true if a airspeed from a specific airspeed sensor is enabled bool airspeed_sensor_enabled(uint8_t airspeed_index) const { // FIXME: make this a method on the active backend return AP_AHRS_Backend::airspeed_sensor_enabled(airspeed_index); @@ -909,6 +913,9 @@ class AP_AHRS { // get current location estimate bool _get_location(Location &loc) const; + + // return true if a airspeed sensor should be used for the AHRS airspeed estimate + bool _should_use_airspeed_sensor(uint8_t airspeed_index) const; /* update state structure From a6206bde3c86f0b568dc9d1ea0a17aa316106151 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 24 Oct 2023 02:41:37 +0100 Subject: [PATCH 005/499] Plane: move to new `using_airspeed_sensor` ahrs method --- ArduPlane/Attitude.cpp | 2 +- ArduPlane/quadplane.cpp | 2 +- ArduPlane/radio.cpp | 2 +- ArduPlane/servos.cpp | 4 ++-- ArduPlane/takeoff.cpp | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 39a9461ea63e7d..3c59d8a31522bc 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -49,7 +49,7 @@ float Plane::calc_speed_scaler(void) // no speed estimate and not armed, use a unit scaling speed_scaler = 1; } - if (!plane.ahrs.airspeed_sensor_enabled() && + if (!plane.ahrs.using_airspeed_sensor() && (plane.flight_option_enabled(FlightOptions::SURPRESS_TKOFF_SCALING)) && (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF)) { //scaling is suppressed during climb phase of automatic takeoffs with no airspeed sensor being used due to problems with inaccurate airspeed estimates return MIN(speed_scaler, 1.0f) ; diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index fbb1b3c9fe27ff..839d76b92dc5d8 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1475,7 +1475,7 @@ bool QuadPlane::should_assist(float aspeed, bool have_airspeed) // assistance due to Q_ASSIST_SPEED // if option bit is enabled only allow assist with real airspeed sensor if ((have_airspeed && aspeed < assist_speed) && - (!option_is_set(QuadPlane::OPTION::DISABLE_SYNTHETIC_AIRSPEED_ASSIST) || ahrs.airspeed_sensor_enabled())) { + (!option_is_set(QuadPlane::OPTION::DISABLE_SYNTHETIC_AIRSPEED_ASSIST) || ahrs.using_airspeed_sensor())) { in_angle_assist = false; angle_error_start_ms = 0; return true; diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index cb7e68ff226f32..68ee2cb9986f42 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -196,7 +196,7 @@ void Plane::read_radio() && channel_throttle->get_control_in() > 50 && stickmixing) { float nudge = (channel_throttle->get_control_in() - 50) * 0.02f; - if (ahrs.airspeed_sensor_enabled()) { + if (ahrs.using_airspeed_sensor()) { airspeed_nudge_cm = (aparm.airspeed_max * 100 - aparm.airspeed_cruise_cm) * nudge; } else { throttle_nudge = (aparm.throttle_max - aparm.throttle_cruise) * nudge; diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index ced42525788e83..d193a678e9b571 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -134,7 +134,7 @@ bool Plane::suppress_throttle(void) // require 5m/s. This prevents throttle up due to spiky GPS // groundspeed with bad GPS reception #if AP_AIRSPEED_ENABLED - if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) { + if ((!ahrs.using_airspeed_sensor()) || airspeed.get_airspeed() >= 5) { // we're moving at more than 5 m/s throttle_suppressed = false; return false; @@ -605,7 +605,7 @@ void Plane::set_servos_flaps(void) if (control_mode->does_auto_throttle()) { int16_t flapSpeedSource = 0; - if (ahrs.airspeed_sensor_enabled()) { + if (ahrs.using_airspeed_sensor()) { flapSpeedSource = target_airspeed_cm * 0.01f; } else { flapSpeedSource = aparm.throttle_cruise; diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index 5574ad2c9b0c10..ce2264f8c800cc 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -185,7 +185,7 @@ void Plane::takeoff_calc_pitch(void) return; } - if (ahrs.airspeed_sensor_enabled()) { + if (ahrs.using_airspeed_sensor()) { int16_t takeoff_pitch_min_cd = get_takeoff_pitch_min_cd(); calc_nav_pitch(); if (nav_pitch_cd < takeoff_pitch_min_cd) { From 97101b6bd083d499031f5bce4670c9dbaf7d013b Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 24 Oct 2023 02:41:42 +0100 Subject: [PATCH 006/499] TECS: move to new `using_airspeed_sensor` ahrs method --- libraries/AP_TECS/AP_TECS.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index e049d31cbbc54d..f5892d68585728 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -390,7 +390,7 @@ void AP_TECS::_update_speed(float DT) _vel_dot_lpf = _vel_dot_lpf * (1.0f - alpha) + _vel_dot * alpha; } - bool use_airspeed = _use_synthetic_airspeed_once || _use_synthetic_airspeed.get() || _ahrs.airspeed_sensor_enabled(); + bool use_airspeed = _use_synthetic_airspeed_once || _use_synthetic_airspeed.get() || _ahrs.using_airspeed_sensor(); // Convert equivalent airspeeds to true airspeeds and harmonise limits @@ -923,7 +923,7 @@ void AP_TECS::_update_pitch(void) // A SKE_weighting of 2 provides 100% priority to speed control. This is used when an underspeed condition is detected. In this instance, if airspeed // rises above the demanded value, the pitch angle will be increased by the TECS controller. _SKE_weighting = constrain_float(_spdWeight, 0.0f, 2.0f); - if (!(_ahrs.airspeed_sensor_enabled() || _use_synthetic_airspeed)) { + if (!(_ahrs.using_airspeed_sensor() || _use_synthetic_airspeed)) { _SKE_weighting = 0.0f; } else if (_flight_stage == AP_FixedWing::FlightStage::VTOL) { // if we are in VTOL mode then control pitch without regard to @@ -1346,7 +1346,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, // Note that caller can demand the use of // synthetic airspeed for one loop if needed. This is required // during QuadPlane transition when pitch is constrained - if (_ahrs.airspeed_sensor_enabled() || _use_synthetic_airspeed || _use_synthetic_airspeed_once) { + if (_ahrs.using_airspeed_sensor() || _use_synthetic_airspeed || _use_synthetic_airspeed_once) { _update_throttle_with_airspeed(); _use_synthetic_airspeed_once = false; _using_airspeed_for_throttle = true; From 04c5c336b85dc9205ef0858b1716a32ac66be12b Mon Sep 17 00:00:00 2001 From: vzarkar Date: Mon, 23 Oct 2023 16:15:19 +0530 Subject: [PATCH 007/499] AP_Scripting: add note to miision_load.lua about file locations Co-authored-by: Henry Wurzburg --- libraries/AP_Scripting/examples/mission-load.lua | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Scripting/examples/mission-load.lua b/libraries/AP_Scripting/examples/mission-load.lua index 33d19d66750aaa..76f465b1fbb55b 100644 --- a/libraries/AP_Scripting/examples/mission-load.lua +++ b/libraries/AP_Scripting/examples/mission-load.lua @@ -1,6 +1,9 @@ -- Example of loading a mission from the SD card using Scripting -- Would be trivial to select a mission based on scripting params or RC switch -- luacheck: only 0 +--Copy this "mission-load.lua" script to the "scripts" directory of the simulation or autopilot's SD card. +--The "mission1.txt" file containing the mission items should be placed in the directory above the "scripts" directory. +--In case of placing it on SD Card, mission1.txt file should be placed in the APM directory root. From 617372684629a222d9de642ba820b37b0985fe2a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 24 Oct 2023 14:51:52 +1100 Subject: [PATCH 008/499] HAL_ChibiOS: fail on badly formed SPIDEV line --- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 5a2b3c87d8e8f7..927ddf861d8030 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -1478,7 +1478,7 @@ def write_SPI_table(self, f): devlist = [] for dev in self.spidev: if len(dev) != 7: - print("Badly formed SPIDEV line %s" % dev) + self.error("Badly formed SPIDEV line %s" % dev) name = '"' + dev[0] + '"' bus = dev[1] devid = dev[2] From cd3eab3c5de2832bf170f3391e77e6ee68abe2e4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 24 Oct 2023 14:52:16 +1100 Subject: [PATCH 009/499] hwdef: support Holybro Pixhawk6X_Rev6 --- .../AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat | 51 +++++++++++-------- 1 file changed, 31 insertions(+), 20 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat index cd7183301b9570..1419ab5aa2e053 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat @@ -121,30 +121,31 @@ PC3 ADC1_3V3 ADC1 SCALE(1) PA5 SPI1_SCK SPI1 PB5 SPI1_MOSI SPI1 PG9 SPI1_MISO SPI1 -PI9 IMU1_CS CS +PI9 SP1_CS1 CS # SPI2 - ICM42688 PI1 SPI2_SCK SPI2 PI2 SPI2_MISO SPI2 PI3 SPI2_MOSI SPI2 -PH5 ICM42688_CS CS -PA10 ICM42688_DRDY INPUT +PH5 SP2_CS1 CS +PA10 SP2_DRDY2 INPUT # SPI3 - BMI088 PB2 SPI3_MOSI SPI3 PC10 SPI3_SCK SPI3 PC11 SPI3_MISO SPI3 -PI4 BMI088_A_CS CS -PI8 BMI088_G_CS CS -PI6 BMI088_DRDY_ACC INPUT -PI7 BMI088_DRDY_GYR INPUT - -# SPI4 - BMM150 -PE12 SPI4_SCK SPI4 -PE13 SPI4_MISO SPI4 -PE14 SPI4_MOSI SPI4 -PF3 BMM150_DRDY INPUT -PH15 BMM150_CS CS +PI4 SP3_CS1 CS +PI8 SP3_CS2 CS +PI6 SP3_DRDY1 INPUT +PI7 SP3_DRDY2 INPUT GPIO(93) +define SP3_DRDY2 93 + +# SPI4 - unused +#PE12 SPI4_SCK SPI4 +#PE13 SPI4_MISO SPI4 +#PE14 SPI4_MOSI SPI4 +#PF3 SP4_DRDY1 INPUT +PH15 SP4_CS1 CS # SPI5 - FRAM PF7 SPI5_SCK SPI5 @@ -311,21 +312,26 @@ define HAL_HEATER_MAG_OFFSET_BMM150 AP_HAL::Device::make_bus_id(AP_HAL::Device:: define HAL_HEATER_MAG_OFFSET {HAL_HEATER_MAG_OFFSET_RM3100, HAL_HEATER_MAG_OFFSET_BMM150} # IMU devices for Holybro6X -SPIDEV bmi088_g SPI3 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ -SPIDEV bmi088_a SPI3 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_g SPI3 DEVID1 SP3_CS2 MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_a SPI3 DEVID2 SP3_CS1 MODE3 10*MHZ 10*MHZ # alternative to bmi088 -SPIDEV icm20649 SPI3 DEVID1 BMI088_A_CS MODE3 10*MHZ 10*MHZ -SPIDEV icm42688 SPI2 DEVID1 ICM42688_CS MODE3 2*MHZ 8*MHZ -SPIDEV icm42670 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm20649 SPI3 DEVID1 SP3_CS1 MODE3 10*MHZ 10*MHZ +SPIDEV icm42688 SPI2 DEVID1 SP2_CS1 MODE3 2*MHZ 8*MHZ +SPIDEV icm42670 SPI1 DEVID1 SP1_CS1 MODE3 2*MHZ 8*MHZ # IMU devices for CUAV-6X. The CUAV board has a BMI088, ICM20649 and # ICM42688 the ICM42688 and BMI088 are on the same SPI buses and CS # pins as the Holybro board, but the orientation of the BMI088 is # different. The ICM20649 is on a different bus -SPIDEV icm20649_2 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ +SPIDEV icm20649_2 SPI1 DEVID1 SP1_CS1 MODE3 2*MHZ 8*MHZ SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +# IMU devices for Holybro6X-Rev6 +SPIDEV adis16470 SPI3 DEVID1 SP3_CS1 MODE3 1*MHZ 2*MHZ +SPIDEV iim42652 SPI2 DEVID1 SP2_CS1 MODE3 2*MHZ 8*MHZ +SPIDEV icm45686 SPI1 DEVID1 SP1_CS1 MODE3 2*MHZ 8*MHZ + # Holybro6X 3 IMUs IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_90 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X) IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X) @@ -337,6 +343,11 @@ IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180_YAW_270 BOARD_MATCH(FMUV6_BOARD_ IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_PITCH_180 BOARD_MATCH(FMUV6_BOARD_CUAV_6X) IMU Invensensev2 SPI:icm20649_2 ROTATION_ROLL_180 BOARD_MATCH(FMUV6_BOARD_CUAV_6X) +# Holybro6X-Rev6 3 IMUs +IMU ADIS1647x SPI:adis16470 ROTATION_ROLL_180 SP3_DRDY2 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X_REV6) +IMU Invensensev3 SPI:iim42652 ROTATION_ROLL_180_YAW_270 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X_REV6) +IMU Invensensev3 SPI:icm45686 ROTATION_YAW_90 BOARD_MATCH(FMUV6_BOARD_HOLYBRO_6X_REV6) + define HAL_DEFAULT_INS_FAST_SAMPLE 7 # enable RAMTROM parameter storage From b86774789b9c3cb3a79f4baeeea25daab83516e4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 24 Oct 2023 14:52:39 +1100 Subject: [PATCH 010/499] AP_BoardConfig: detect Holybro 6X Rev6 --- libraries/AP_BoardConfig/AP_BoardConfig.h | 1 + libraries/AP_BoardConfig/board_drivers.cpp | 23 +++++++++++----------- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.h b/libraries/AP_BoardConfig/AP_BoardConfig.h index d0a89c490df4c8..f1321c93ecf78c 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.h +++ b/libraries/AP_BoardConfig/AP_BoardConfig.h @@ -67,6 +67,7 @@ class AP_BoardConfig { PX4_BOARD_FMUV6 = 39, FMUV6_BOARD_HOLYBRO_6X = 40, FMUV6_BOARD_CUAV_6X = 41, + FMUV6_BOARD_HOLYBRO_6X_REV6 = 42, PX4_BOARD_OLDDRIVERS = 100, }; diff --git a/libraries/AP_BoardConfig/board_drivers.cpp b/libraries/AP_BoardConfig/board_drivers.cpp index ed365120a08cf3..c54f872bb94a80 100644 --- a/libraries/AP_BoardConfig/board_drivers.cpp +++ b/libraries/AP_BoardConfig/board_drivers.cpp @@ -106,6 +106,7 @@ void AP_BoardConfig::board_setup_drivers(void) case PX4_BOARD_PCNC1: case PX4_BOARD_MINDPXV2: case FMUV6_BOARD_HOLYBRO_6X: + case FMUV6_BOARD_HOLYBRO_6X_REV6: case FMUV6_BOARD_CUAV_6X: break; default: @@ -129,17 +130,15 @@ bool AP_BoardConfig::spi_check_register(const char *devname, uint8_t regnum, uin return false; } dev->set_read_flag(read_flag); - dev->get_semaphore()->take_blocking(); + WITH_SEMAPHORE(dev->get_semaphore()); dev->set_speed(AP_HAL::Device::SPEED_LOW); uint8_t v; if (!dev->read_registers(regnum, &v, 1)) { #if SPI_PROBE_DEBUG hal.console->printf("%s: reg %02x read fail\n", devname, (unsigned)regnum); #endif - dev->get_semaphore()->give(); return false; } - dev->get_semaphore()->give(); #if SPI_PROBE_DEBUG hal.console->printf("%s: reg %02x expected:%02x got:%02x\n", devname, (unsigned)regnum, (unsigned)value, (unsigned)v); #endif @@ -161,7 +160,7 @@ bool AP_BoardConfig::spi_check_register_inv2(const char *devname, uint8_t regnum return false; } dev->set_read_flag(read_flag); - dev->get_semaphore()->take_blocking(); + WITH_SEMAPHORE(dev->get_semaphore()); dev->set_speed(AP_HAL::Device::SPEED_LOW); uint8_t v; // select bank 0 for who am i @@ -170,10 +169,8 @@ bool AP_BoardConfig::spi_check_register_inv2(const char *devname, uint8_t regnum #if SPI_PROBE_DEBUG hal.console->printf("%s: reg %02x read fail\n", devname, (unsigned)regnum); #endif - dev->get_semaphore()->give(); return false; } - dev->get_semaphore()->give(); #if SPI_PROBE_DEBUG hal.console->printf("%s: reg %02x expected:%02x got:%02x\n", devname, (unsigned)regnum, (unsigned)value, (unsigned)v); #endif @@ -195,7 +192,7 @@ bool AP_BoardConfig::check_ms5611(const char* devname) { if (!dev_sem) { return false; } - dev_sem->take_blocking(); + WITH_SEMAPHORE(dev_sem); static const uint8_t CMD_MS56XX_RESET = 0x1E; static const uint8_t CMD_MS56XX_PROM = 0xA0; @@ -209,7 +206,6 @@ bool AP_BoardConfig::check_ms5611(const char* devname) { const uint8_t reg = CMD_MS56XX_PROM + (i << 1); uint8_t val[2]; if (!dev->transfer(®, 1, val, sizeof(val))) { - dev_sem->give(); #if SPI_PROBE_DEBUG hal.console->printf("%s: transfer fail\n", devname); #endif @@ -221,7 +217,6 @@ bool AP_BoardConfig::check_ms5611(const char* devname) { all_zero = false; } } - dev_sem->give(); uint16_t crc_read = prom[7]&0xf; prom[7] &= 0xff00; @@ -257,12 +252,13 @@ bool AP_BoardConfig::check_ms5611(const char* devname) { #define INV2_WHOAMI_ICM20649 0xE1 #define INV3REG_WHOAMI 0x75 -#define INV3REG_456_WHOAMI 0x72 +#define INV3REG_456_WHOAMI 0x72 #define INV3_WHOAMI_ICM42688 0x47 #define INV3_WHOAMI_ICM42670 0x67 - #define INV3_WHOAMI_ICM45686 0xE9 +#define INV3_WHOAMI_IIM42652 0x6f + /* validation of the board type */ @@ -503,7 +499,10 @@ void AP_BoardConfig::detect_fmuv6_variant() state.board_type.set_and_notify(FMUV6_BOARD_CUAV_6X); DEV_PRINTF("Detected CUAV 6X\n"); AP_Param::load_defaults_file("@ROMFS/param/CUAV_V6X_defaults.parm", false); + } else if (spi_check_register("iim42652", INV3REG_WHOAMI, INV3_WHOAMI_IIM42652) && + spi_check_register("icm45686", INV3REG_456_WHOAMI, INV3_WHOAMI_ICM45686)) { + state.board_type.set_and_notify(FMUV6_BOARD_HOLYBRO_6X_REV6); + DEV_PRINTF("Detected Holybro 6X_Rev6\n"); } - } #endif From b3f2945dcb8707d5323cc5459d6d24b08ee7d0a4 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Tue, 24 Oct 2023 19:32:42 -0300 Subject: [PATCH 011/499] AP_HAL_SITL: set bw_in_bytes_per_second to 10/100Mbps connection --- libraries/AP_HAL_SITL/UARTDriver.cpp | 6 ++++++ libraries/AP_HAL_SITL/UARTDriver.h | 2 ++ 2 files changed, 8 insertions(+) diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 7b43217e67f1e8..9c90928630dea3 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -987,5 +987,11 @@ ssize_t UARTDriver::get_system_outqueue_length() const #endif } +uint32_t UARTDriver::bw_in_bytes_per_second() const +{ + // if connected, assume at least a 10/100Mbps connection + const uint32_t bitrate = (_connected && _tcp_client_addr != nullptr) ? 10E6 : _uart_baudrate; + return bitrate/10; // convert bits to bytes minus overhead +}; #endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index fb0476550bb213..d47378a8054dae 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -46,6 +46,8 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { void set_stop_bits(int n) override; bool set_unbuffered_writes(bool on) override; + uint32_t bw_in_bytes_per_second() const override; + void _timer_tick(void) override; /* From 60a38a0ab12720137b3e176aa585831e6ae17614 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Tue, 24 Oct 2023 19:42:14 -0300 Subject: [PATCH 012/499] AP_HAL_Linux: set bw_in_bytes_per_second default to 10/100Mbps connection --- libraries/AP_HAL_Linux/UARTDriver.cpp | 7 +++++++ libraries/AP_HAL_Linux/UARTDriver.h | 2 ++ 2 files changed, 9 insertions(+) diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index ec2974faaf548e..2e7d3c61d7d70d 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -443,3 +443,10 @@ uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes) } return last_receive_us; } + +uint32_t UARTDriver::bw_in_bytes_per_second() const +{ + // if connected, assume at least a 10/100Mbps connection + const uint32_t bitrate = (_connected && _ip != nullptr) ? 10E6 : _baudrate; + return bitrate/10; // convert bits to bytes minus overhead +}; \ No newline at end of file diff --git a/libraries/AP_HAL_Linux/UARTDriver.h b/libraries/AP_HAL_Linux/UARTDriver.h index d456d91db51eaa..fa271cb08add09 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.h +++ b/libraries/AP_HAL_Linux/UARTDriver.h @@ -54,6 +54,8 @@ class UARTDriver : public AP_HAL::UARTDriver { */ uint64_t receive_time_constraint_us(uint16_t nbytes) override; + uint32_t bw_in_bytes_per_second() const override; + private: AP_HAL::OwnPtr _device; bool _console; From 7ce9febf9fb099273e3f7697c195bbf3885f282a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 25 Oct 2023 08:11:22 +1100 Subject: [PATCH 013/499] AP_BattMonitor: use a reference for AP::battery() saves a small amount of flash --- .../AP_BattMonitor_DroneCAN.cpp | 27 +++++++++++++------ .../AP_BattMonitor/AP_BattMonitor_DroneCAN.h | 5 +--- 2 files changed, 20 insertions(+), 12 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index d4b7aed2a9cab4..8036ac4e5a16ae 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -61,28 +61,39 @@ void AP_BattMonitor_DroneCAN::subscribe_msgs(AP_DroneCAN* ap_dronecan) } } +/* + match a battery ID to driver serial number + when serial number is negative, all batteries are accepted, otherwise it must match +*/ +bool AP_BattMonitor_DroneCAN::match_battery_id(uint8_t instance, uint8_t battery_id) +{ + const auto serial_num = AP::battery().get_serial_number(instance); + return serial_num < 0 || serial_num == (int32_t)battery_id; +} + AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_dronecan_backend(AP_DroneCAN* ap_dronecan, uint8_t node_id, uint8_t battery_id) { if (ap_dronecan == nullptr) { return nullptr; } - for (uint8_t i = 0; i < AP::battery()._num_instances; i++) { - if (AP::battery().drivers[i] == nullptr || - AP::battery().get_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) { + const auto &batt = AP::battery(); + for (uint8_t i = 0; i < batt._num_instances; i++) { + if (batt.drivers[i] == nullptr || + batt.get_type(i) != AP_BattMonitor::Type::UAVCAN_BatteryInfo) { continue; } - AP_BattMonitor_DroneCAN* driver = (AP_BattMonitor_DroneCAN*)AP::battery().drivers[i]; + AP_BattMonitor_DroneCAN* driver = (AP_BattMonitor_DroneCAN*)batt.drivers[i]; if (driver->_ap_dronecan == ap_dronecan && driver->_node_id == node_id && match_battery_id(i, battery_id)) { return driver; } } // find empty uavcan driver - for (uint8_t i = 0; i < AP::battery()._num_instances; i++) { - if (AP::battery().drivers[i] != nullptr && - AP::battery().get_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo && + for (uint8_t i = 0; i < batt._num_instances; i++) { + if (batt.drivers[i] != nullptr && + batt.get_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo && match_battery_id(i, battery_id)) { - AP_BattMonitor_DroneCAN* batmon = (AP_BattMonitor_DroneCAN*)AP::battery().drivers[i]; + AP_BattMonitor_DroneCAN* batmon = (AP_BattMonitor_DroneCAN*)batt.drivers[i]; if(batmon->_ap_dronecan != nullptr || batmon->_node_id != 0) { continue; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h index 6b6151d4778c79..819ade73164817 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h @@ -63,10 +63,7 @@ class AP_BattMonitor_DroneCAN : public AP_BattMonitor_Backend void handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg); void update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc); - static bool match_battery_id(uint8_t instance, uint8_t battery_id) { - // when serial number is negative, all batteries are accepted. Else, it must match - return (AP::battery().get_serial_number(instance) < 0) || (AP::battery().get_serial_number(instance) == (int32_t)battery_id); - } + static bool match_battery_id(uint8_t instance, uint8_t battery_id); // MPPT related enums and methods enum class MPPT_FaultFlags : uint8_t { From 532ab09c726ac5c6b4c18a4b8b2757fb1eda4162 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 25 Oct 2023 08:31:50 +1100 Subject: [PATCH 014/499] AP_BattMonitor: added option allowing InfoAux to be from different node this allows the CAN node providing cell voltages to be a different CAN node from the node providing the base current/voltage --- .../AP_BattMonitor_DroneCAN.cpp | 28 ++++++++++++++++++- .../AP_BattMonitor/AP_BattMonitor_Params.cpp | 2 +- .../AP_BattMonitor/AP_BattMonitor_Params.h | 1 + 3 files changed, 29 insertions(+), 2 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index 8036ac4e5a16ae..ddd5976c5f056b 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -217,7 +217,33 @@ void AP_BattMonitor_DroneCAN::handle_battery_info_trampoline(AP_DroneCAN *ap_dro void AP_BattMonitor_DroneCAN::handle_battery_info_aux_trampoline(AP_DroneCAN *ap_dronecan, const CanardRxTransfer& transfer, const ardupilot_equipment_power_BatteryInfoAux &msg) { - AP_BattMonitor_DroneCAN* driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); + const auto &batt = AP::battery(); + AP_BattMonitor_DroneCAN *driver = nullptr; + + /* + check for a backend with AllowSplitAuxInfo set, allowing InfoAux + from a different CAN node than the base battery information + */ + for (uint8_t i = 0; i < batt._num_instances; i++) { + const auto *drv = batt.drivers[i]; + if (drv != nullptr && + batt.get_type(i) == AP_BattMonitor::Type::UAVCAN_BatteryInfo && + drv->option_is_set(AP_BattMonitor_Params::Options::AllowSplitAuxInfo) && + batt.get_serial_number(i) == int32_t(msg.battery_id)) { + driver = (AP_BattMonitor_DroneCAN *)batt.drivers[i]; + if (driver->_ap_dronecan == nullptr) { + /* we have not received the main battery information + yet. Discard InfoAux until we do so we can init the + backend with the right node ID + */ + return; + } + break; + } + } + if (driver == nullptr) { + driver = get_dronecan_backend(ap_dronecan, transfer.source_node_id, msg.battery_id); + } if (driver == nullptr) { return; } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index 01ec3bbded590d..f1d6522a6df0bb 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -150,7 +150,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @Param: OPTIONS // @DisplayName: Battery monitor options // @Description: This sets options to change the behaviour of the battery monitor - // @Bitmask: 0:Ignore DroneCAN SoC, 1:MPPT reports input voltage and current, 2:MPPT Powered off when disarmed, 3:MPPT Powered on when armed, 4:MPPT Powered off at boot, 5:MPPT Powered on at boot, 6:Send resistance compensated voltage to GCS + // @Bitmask: 0:Ignore DroneCAN SoC, 1:MPPT reports input voltage and current, 2:MPPT Powered off when disarmed, 3:MPPT Powered on when armed, 4:MPPT Powered off at boot, 5:MPPT Powered on at boot, 6:Send resistance compensated voltage to GCS, 7:Allow DroneCAN InfoAux to be from a different CAN node // @User: Advanced AP_GROUPINFO("OPTIONS", 21, AP_BattMonitor_Params, _options, 0), #endif // HAL_BUILD_AP_PERIPH diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h index 9366965328cd7a..fff2719f8f3cf1 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h @@ -25,6 +25,7 @@ class AP_BattMonitor_Params { MPPT_Power_Off_At_Boot = (1U<<4), // MPPT Disabled at startup (aka boot), if HW supports it MPPT_Power_On_At_Boot = (1U<<5), // MPPT Enabled at startup (aka boot), if HW supports it. If Power_Off_at_Boot is also set, the behavior is Power_Off_at_Boot GCS_Resting_Voltage = (1U<<6), // send resistance resting voltage to GCS + AllowSplitAuxInfo = (1U<<7), // allow different node to provide aux info for DroneCAN }; BattMonitor_LowVoltage_Source failsafe_voltage_source(void) const { return (enum BattMonitor_LowVoltage_Source)_failsafe_voltage_source.get(); } From aaa4e0268a7a08723d8937e9bf09884c9a706f8e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 28 Oct 2023 14:54:42 +1100 Subject: [PATCH 015/499] AP_BattMonitor: cope with InfoAux without nominal voltage allows for reset of remaining charge from GCS or lua --- .../AP_BattMonitor/AP_BattMonitor_Backend.cpp | 3 +++ .../AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp | 15 ++++++++------- 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp index c137aa2c146ef0..1aef15a6efda3b 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp @@ -47,6 +47,9 @@ bool AP_BattMonitor_Backend::capacity_remaining_pct(uint8_t &percentage) const if (!has_current() || !_state.healthy) { return false; } + if (isnan(_state.consumed_mah) || _params._pack_capacity <= 0) { + return false; + } const float mah_remaining = _params._pack_capacity - _state.consumed_mah; percentage = constrain_float(100 * mah_remaining / _params._pack_capacity, 0, UINT8_MAX); diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index ddd5976c5f056b..281831f0d18390 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -153,21 +153,22 @@ void AP_BattMonitor_DroneCAN::handle_battery_info_aux(const ardupilot_equipment_ { WITH_SEMAPHORE(_sem_battmon); uint8_t cell_count = MIN(ARRAY_SIZE(_interim_state.cell_voltages.cells), msg.voltage_cell.len); - float remaining_capacity_ah = _remaining_capacity_wh / msg.nominal_voltage; - float full_charge_capacity_ah = _full_charge_capacity_wh / msg.nominal_voltage; _cycle_count = msg.cycle_count; for (uint8_t i = 0; i < cell_count; i++) { _interim_state.cell_voltages.cells[i] = msg.voltage_cell.data[i] * 1000; } _interim_state.is_powering_off = msg.is_powering_off; - _interim_state.consumed_mah = (full_charge_capacity_ah - remaining_capacity_ah) * 1000; - _interim_state.consumed_wh = _full_charge_capacity_wh - _remaining_capacity_wh; - _interim_state.time_remaining = is_zero(_interim_state.current_amps) ? 0 : (remaining_capacity_ah / _interim_state.current_amps * 3600); - _interim_state.has_time_remaining = true; + if (!isnan(msg.nominal_voltage) && msg.nominal_voltage > 0) { + float remaining_capacity_ah = _remaining_capacity_wh / msg.nominal_voltage; + float full_charge_capacity_ah = _full_charge_capacity_wh / msg.nominal_voltage; + _interim_state.consumed_mah = (full_charge_capacity_ah - remaining_capacity_ah) * 1000; + _interim_state.consumed_wh = _full_charge_capacity_wh - _remaining_capacity_wh; + _interim_state.time_remaining = is_zero(_interim_state.current_amps) ? 0 : (remaining_capacity_ah / _interim_state.current_amps * 3600); + _interim_state.has_time_remaining = true; + } _has_cell_voltages = true; - _has_time_remaining = true; _has_battery_info_aux = true; } From 069507c48e929d4bdcd81f527517bd5b702fddee Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 25 Oct 2023 22:01:14 +0100 Subject: [PATCH 016/499] AP_Scripting: fix easy lua check issues in examples --- libraries/AP_Scripting/applets/Hexsoon LEDs.lua | 3 +-- libraries/AP_Scripting/examples/Serial_Dump.lua | 2 +- libraries/AP_Scripting/examples/aux_cached.lua | 2 -- libraries/AP_Scripting/examples/copy_userdata.lua | 3 +-- libraries/AP_Scripting/examples/opendog_demo.lua | 13 ++++--------- .../AP_Scripting/examples/param_get_set_test.lua | 5 +++-- .../AP_Scripting/examples/rangefinder_test.lua | 3 +-- libraries/AP_Scripting/examples/rover-SaveTurns.lua | 2 -- .../AP_Scripting/examples/set-target-location.lua | 1 - .../examples/set_target_posvel_circle.lua | 7 ++----- libraries/AP_Scripting/examples/terrain_warning.lua | 2 -- libraries/AP_Scripting/examples/wp_test.lua | 3 --- 12 files changed, 13 insertions(+), 33 deletions(-) diff --git a/libraries/AP_Scripting/applets/Hexsoon LEDs.lua b/libraries/AP_Scripting/applets/Hexsoon LEDs.lua index 142e1e49b7a3a9..29b0cad6e94b44 100644 --- a/libraries/AP_Scripting/applets/Hexsoon LEDs.lua +++ b/libraries/AP_Scripting/applets/Hexsoon LEDs.lua @@ -25,12 +25,11 @@ LEDs should now work!, if not try swapping AUX 5 and 6, either by physically swa To get colours to match either change the ordering in "local led_map =" below or swap headers round on the LED distribution board If using 6 les add two extra colours to "local led_map =" e.g: "local led_map = {red, red, red, green, green, green}" --]] --- luacheck: only 0 -- helper colours, red, green, blue values from 0 to 255 local red = {255, 0, 0} local green = {0, 255, 0} -local blue = {0, 0, 255} +-- local blue = {0, 0, 255} -- led map giving the colour for the LEDs plugged in local led_map = {red, red, green, green} diff --git a/libraries/AP_Scripting/examples/Serial_Dump.lua b/libraries/AP_Scripting/examples/Serial_Dump.lua index 926a97353e7a73..bfff5392e8c35a 100644 --- a/libraries/AP_Scripting/examples/Serial_Dump.lua +++ b/libraries/AP_Scripting/examples/Serial_Dump.lua @@ -1,5 +1,4 @@ -- this script reads data from a serial port and dumps it to a file --- luacheck: only 0 local file_name = 'raw serial dump.txt' local file_name_plain = 'serial dump.txt' @@ -11,6 +10,7 @@ local port = assert(serial:find_serial(0),"Could not find Scripting Serial Port" -- make a file local file = assert(io.open(file_name, "w"),"Could not create file " .. file_name) +file:close() file = assert(io.open(file_name_plain, "w"),"Could not create file " .. file_name) file:close() diff --git a/libraries/AP_Scripting/examples/aux_cached.lua b/libraries/AP_Scripting/examples/aux_cached.lua index 1e514055a97e6f..e029c44e985c4a 100644 --- a/libraries/AP_Scripting/examples/aux_cached.lua +++ b/libraries/AP_Scripting/examples/aux_cached.lua @@ -1,7 +1,6 @@ --[[ example for getting cached aux function value --]] --- luacheck: only 0 local RATE_HZ = 10 @@ -11,7 +10,6 @@ local MAV_SEVERITY_INFO = 6 local AUX_FUNCTION_NUM = 302 -local last_func_val = nil local last_aux_pos = nil function update() diff --git a/libraries/AP_Scripting/examples/copy_userdata.lua b/libraries/AP_Scripting/examples/copy_userdata.lua index 6e68c97406015d..5f186e3f100584 100644 --- a/libraries/AP_Scripting/examples/copy_userdata.lua +++ b/libraries/AP_Scripting/examples/copy_userdata.lua @@ -1,7 +1,6 @@ --[[ An example of using the copy() method on userdata --]] --- luacheck: only 0 local loc1 = Location() @@ -24,5 +23,5 @@ local v2 = v1:copy() v2:x(v2:x()+100) v2:y(v2:y()+300) -local diff = v2 - v1 +diff = v2 - v1 gcs:send_text(0,string.format("vdiff=(%.2f,%.2f)", diff:x(), diff:y())) diff --git a/libraries/AP_Scripting/examples/opendog_demo.lua b/libraries/AP_Scripting/examples/opendog_demo.lua index d518b95c6e0e15..cefe8f17360d1b 100644 --- a/libraries/AP_Scripting/examples/opendog_demo.lua +++ b/libraries/AP_Scripting/examples/opendog_demo.lua @@ -1,14 +1,9 @@ -- demo of waving paw of opendog --- luacheck: only 0 -local flipflop = true - -pwm = { 1500, 1500, 2000, - 1500, 1500, 1000, - 1500, 1500, 1500, - 1500, 1500, 1500 } - -local angle = 0.0 +local pwm = { 1500, 1500, 2000, + 1500, 1500, 1000, + 1500, 1500, 1500, + 1500, 1500, 1500 } function update() local t = 0.001 * millis():tofloat() diff --git a/libraries/AP_Scripting/examples/param_get_set_test.lua b/libraries/AP_Scripting/examples/param_get_set_test.lua index 07e84764cc7a01..29baba29b60754 100644 --- a/libraries/AP_Scripting/examples/param_get_set_test.lua +++ b/libraries/AP_Scripting/examples/param_get_set_test.lua @@ -1,5 +1,4 @@ -- This script is a test of param set and get --- luacheck: only 0 local count = 0 @@ -21,7 +20,9 @@ local user_param = Parameter('SCR_USER1') -- this will error out for a bad parameter -- Parameter('FAKE_PARAM') local success, err = pcall(Parameter,'FAKE_PARAM') -gcs:send_text(0, "Lua Caught Error: " .. err) +if not success then + gcs:send_text(0, "Lua Caught Error: " .. err) +end -- this allows this example to catch the otherwise fatal error -- not recommend if error is possible/expected, use separate construction and init diff --git a/libraries/AP_Scripting/examples/rangefinder_test.lua b/libraries/AP_Scripting/examples/rangefinder_test.lua index af5058d8a58343..b6832bf54be351 100644 --- a/libraries/AP_Scripting/examples/rangefinder_test.lua +++ b/libraries/AP_Scripting/examples/rangefinder_test.lua @@ -1,5 +1,4 @@ -- This script checks RangeFinder --- luacheck: only 0 local rotation_downward = 25 local rotation_forward = 0 @@ -8,7 +7,7 @@ function update() local sensor_count = rangefinder:num_sensors() gcs:send_text(0, string.format("%d rangefinder sensors found.", sensor_count)) - for i = 0, rangefinder:num_sensors() do + for _ = 0, rangefinder:num_sensors() do if rangefinder:has_data_orient(rotation_downward) then info(rotation_downward) elseif rangefinder:has_data_orient(rotation_forward) then diff --git a/libraries/AP_Scripting/examples/rover-SaveTurns.lua b/libraries/AP_Scripting/examples/rover-SaveTurns.lua index 58cffa4833d2a9..9e530f23313350 100644 --- a/libraries/AP_Scripting/examples/rover-SaveTurns.lua +++ b/libraries/AP_Scripting/examples/rover-SaveTurns.lua @@ -11,7 +11,6 @@ of a vehicle. Use this script AT YOUR OWN RISK. LICENSE - GNU GPLv3 https://www.gnu.org/licenses/gpl-3.0.en.html ------------------------------------------------------------------------------]] --- luacheck: only 0 local SCRIPT_NAME = 'SaveTurns' @@ -33,7 +32,6 @@ local WAYPOINT = 16 -- waypoint command local MAV_SEVERITY_WARNING = 4 local MAV_SEVERITY_INFO = 6 local MSG_NORMAL = 1 -local MSG_DEBUG = 2 local RC_CHAN = rc:find_channel_for_option(RC_OPTION) local last_wp = Location() diff --git a/libraries/AP_Scripting/examples/set-target-location.lua b/libraries/AP_Scripting/examples/set-target-location.lua index d40ca3c4c17b77..b7c2776b5db9fe 100644 --- a/libraries/AP_Scripting/examples/set-target-location.lua +++ b/libraries/AP_Scripting/examples/set-target-location.lua @@ -5,7 +5,6 @@ -- a) switches to Guided mode -- b) sets the target location to be 10m above home -- c) switches the vehicle to land once it is within a couple of meters of home --- luacheck: only 0 local wp_radius = 2 local target_alt_above_home = 10 diff --git a/libraries/AP_Scripting/examples/set_target_posvel_circle.lua b/libraries/AP_Scripting/examples/set_target_posvel_circle.lua index 45c12a0ebc14cf..87d4d953826340 100644 --- a/libraries/AP_Scripting/examples/set_target_posvel_circle.lua +++ b/libraries/AP_Scripting/examples/set_target_posvel_circle.lua @@ -7,7 +7,6 @@ -- 2) switch to GUIDED mode -- 3) the vehilce will follow a circle in clockwise direction with increasing speed until ramp_up_time_s time has passed. -- 4) switch out of and into the GUIDED mode any time to restart the trajectory from the start. --- luacheck: only 0 -- Edit these variables local rad_xy_m = 10.0 -- circle radius in xy plane in m @@ -26,7 +25,7 @@ gcs:send_text(0,"Script started") gcs:send_text(0,"Trajectory period: " .. tostring(2 * math.rad(180) / omega_radps)) function circle() - local cur_freq = 0 + local cur_freq -- increase target speed lineary with time until ramp_up_time_s is reached if time <= ramp_up_time_s then cur_freq = omega_radps*(time/ramp_up_time_s)^2 @@ -57,9 +56,7 @@ function update() if arming:is_armed() and vehicle:get_mode() == copter_guided_mode_num and -test_start_location:z()>=5 then -- calculate current position and velocity for circle trajectory - local target_pos = Vector3f() - local target_vel = Vector3f() - target_pos, target_vel = circle() + local target_pos, target_vel = circle() -- advance the time time = time + sampling_time_s diff --git a/libraries/AP_Scripting/examples/terrain_warning.lua b/libraries/AP_Scripting/examples/terrain_warning.lua index 4add211232381d..553804f35f7b7c 100644 --- a/libraries/AP_Scripting/examples/terrain_warning.lua +++ b/libraries/AP_Scripting/examples/terrain_warning.lua @@ -1,5 +1,4 @@ -- height above terrain warning script --- luacheck: only 0 -- min altitude above terrain, script will warn if lower than this local terrain_min_alt = 20 @@ -15,7 +14,6 @@ local warn_ms = 10000 local height_threshold_passed = false -local last_warn = 0 function update() if not arming:is_armed() then diff --git a/libraries/AP_Scripting/examples/wp_test.lua b/libraries/AP_Scripting/examples/wp_test.lua index 7f1e5e889b7f82..a52d483343b854 100644 --- a/libraries/AP_Scripting/examples/wp_test.lua +++ b/libraries/AP_Scripting/examples/wp_test.lua @@ -1,12 +1,9 @@ -- Example script for accessing waypoint info --- luacheck: only 0 local wp_index local wp_distance local wp_bearing local wp_error -local wp_max_distance = 0 -local last_log_ms = millis() function on_wp_change(index, distance) From 7e4b5b0c97e8bbaf23b122dabda6b4004d68aad7 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Thu, 26 Oct 2023 00:25:23 +0100 Subject: [PATCH 017/499] Plane: rework set_servos_controlled function --- ArduPlane/Plane.h | 1 + ArduPlane/servos.cpp | 40 ++++++++++++++++++++++------------------ 2 files changed, 23 insertions(+), 18 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index b8d6e21db733c8..c4c84cf7511d3e 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1096,6 +1096,7 @@ class Plane : public AP_Vehicle { void set_servos_idle(void); void set_servos(); void set_servos_controlled(void); + void set_takeoff_expected(void); void set_servos_old_elevons(void); void set_servos_flaps(void); void set_landing_gear(void); diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index d193a678e9b571..4237fa9bbfca9b 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -485,28 +485,22 @@ void Plane::set_servos_controlled(void) min_throttle = 0; } - bool flight_stage_determines_max_throttle = false; - if (flight_stage == AP_FixedWing::FlightStage::TAKEOFF || - flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING - ) { - flight_stage_determines_max_throttle = true; - } + const bool use_takeoff_throttle_max = #if HAL_QUADPLANE_ENABLED - if (quadplane.in_transition()) { - flight_stage_determines_max_throttle = true; - } + quadplane.in_transition() || #endif - if (flight_stage_determines_max_throttle) { + (flight_stage == AP_FixedWing::FlightStage::TAKEOFF) || + (flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING); + + if (use_takeoff_throttle_max) { if (aparm.takeoff_throttle_max != 0) { - max_throttle = aparm.takeoff_throttle_max; - } else { - max_throttle = aparm.throttle_max; + max_throttle = aparm.takeoff_throttle_max.get(); } } else if (landing.is_flaring()) { min_throttle = 0; } - // conpensate for battery voltage drop + // compensate for battery voltage drop throttle_voltage_comp(min_throttle, max_throttle); // apply watt limiter @@ -516,14 +510,16 @@ void Plane::set_servos_controlled(void) constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle), min_throttle, max_throttle)); if (!arming.is_armed_and_safety_off()) { + // Always set 0 scaled even if overriding to zero pwm. + // This ensures slew limits and other functions using the scaled value pick up in the correct place + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0); + if (arming.arming_required() == AP_Arming::Required::YES_ZERO_PWM) { SRV_Channels::set_output_limit(SRV_Channel::k_throttle, SRV_Channel::Limit::ZERO_PWM); SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::Limit::ZERO_PWM); SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, SRV_Channel::Limit::ZERO_PWM); - } else { - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0); } } else if (suppress_throttle()) { SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); // default @@ -573,6 +569,13 @@ void Plane::set_servos_controlled(void) #endif // HAL_QUADPLANE_ENABLED } +} + +/* + Warn AHRS that we might take off soon + */ +void Plane::set_takeoff_expected(void) +{ // let EKF know to start GSF yaw estimator before takeoff movement starts so that yaw angle is better estimated const float throttle = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle); if (!is_flying() && arming.is_armed()) { @@ -821,6 +824,7 @@ void Plane::set_servos(void) if (control_mode != &mode_manual) { set_servos_controlled(); + set_takeoff_expected(); } // setup flap outputs From afd85c8613013de0109d466035485acfa2cb9060 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 26 Oct 2023 13:52:52 +1100 Subject: [PATCH 018/499] GCS_MAVLink: handle MAV_CMD_START_RX_PAIR as both int and long --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 9 ++++----- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 5941a2e46f8b92..97aa0b42ebb893 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -590,7 +590,7 @@ class GCS_MAVLINK bool get_ap_message_interval(ap_message id, uint16_t &interval_ms) const; MAV_RESULT handle_command_request_message(const mavlink_command_int_t &packet); - MAV_RESULT handle_rc_bind(const mavlink_command_long_t &packet); + MAV_RESULT handle_START_RX_PAIR(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_flight_termination(const mavlink_command_int_t &packet); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 1d69f42ea3fa53..5a374081741ed1 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3287,7 +3287,7 @@ MAV_RESULT GCS_MAVLINK::handle_flight_termination(const mavlink_command_int_t &p /* handle a R/C bind request (for spektrum) */ -MAV_RESULT GCS_MAVLINK::handle_rc_bind(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_START_RX_PAIR(const mavlink_command_int_t &packet) { // initiate bind procedure. We accept the DSM type from either // param1 or param2 due to a past mixup with what parameter is the @@ -4724,10 +4724,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t switch (packet.command) { - case MAV_CMD_START_RX_PAIR: - result = handle_rc_bind(packet); - break; - #if AP_CAMERA_ENABLED case MAV_CMD_DO_DIGICAM_CONFIGURE: case MAV_CMD_DO_DIGICAM_CONTROL: @@ -5167,6 +5163,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p case MAV_CMD_SET_EKF_SOURCE_SET: return handle_command_set_ekf_source_set(packet); + case MAV_CMD_START_RX_PAIR: + return handle_START_RX_PAIR(packet); + #if AP_FILESYSTEM_FORMAT_ENABLED case MAV_CMD_STORAGE_FORMAT: return handle_command_storage_format(packet, msg); From 78475cad5c25f593d64afdfe14523980798e2de2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 26 Oct 2023 14:16:03 +1100 Subject: [PATCH 019/499] GCS_MAVLink: handle FLASH_BOOTLOADER as command-long and command-int --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 15 +++++++-------- 2 files changed, 8 insertions(+), 9 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 97aa0b42ebb893..8a863fff42a552 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -629,7 +629,7 @@ class GCS_MAVLINK virtual uint32_t telem_delay() const = 0; MAV_RESULT handle_command_run_prearm_checks(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_flash_bootloader(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_flash_bootloader(const mavlink_command_int_t &packet); // generally this should not be overridden; Plane overrides it to ensure // failsafe isn't triggered during calibration diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 5a374081741ed1..fb46ac9bc06ee6 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4311,9 +4311,9 @@ void GCS_MAVLINK::send_sim_state() const #endif #if AP_BOOTLOADER_FLASHING_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_flash_bootloader(const mavlink_command_int_t &packet) { - if (uint32_t(packet.param5) != 290876) { + if (packet.x != 290876) { gcs().send_text(MAV_SEVERITY_INFO, "Magic not set"); return MAV_RESULT_FAILED; } @@ -4784,12 +4784,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t result = handle_command_run_prearm_checks(packet); break; -#if AP_BOOTLOADER_FLASHING_ENABLED - case MAV_CMD_FLASH_BOOTLOADER: - result = handle_command_flash_bootloader(packet); - break; -#endif - default: result = try_command_long_as_command_int(packet, msg); break; @@ -5122,6 +5116,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p return handle_command_mag_cal(packet); #endif +#if AP_BOOTLOADER_FLASHING_ENABLED + case MAV_CMD_FLASH_BOOTLOADER: + return handle_command_flash_bootloader(packet); +#endif + #if AP_AHRS_ENABLED case MAV_CMD_GET_HOME_POSITION: return handle_command_get_home_position(packet); From 4b4c6e8696c7cc1aad4e907f058cc50a179794dd Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Fri, 27 Oct 2023 07:30:32 -0500 Subject: [PATCH 020/499] AP_Scripting:add README file to examples directory --- libraries/AP_Scripting/examples/README.md | 5 +++++ 1 file changed, 5 insertions(+) create mode 100644 libraries/AP_Scripting/examples/README.md diff --git a/libraries/AP_Scripting/examples/README.md b/libraries/AP_Scripting/examples/README.md new file mode 100644 index 00000000000000..3543347b0c8a71 --- /dev/null +++ b/libraries/AP_Scripting/examples/README.md @@ -0,0 +1,5 @@ +#LUA Examples + + +This directory contains some script examples. For simulation the scripts should be placed in the simulation's "scripts" directory located in the root directory from which the sim is run. +Note: if an example uses auxillary files (mission list, other scripts,etc.) the user will have to determine where the files should be placed from the script. If no path name is specified in the file name, then it should be placed one directory level above the "scripts" directory. From 2be4c0e3f5d3f83c3a92fdfd689cde75cab7da89 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 28 Oct 2023 17:06:45 +1100 Subject: [PATCH 021/499] Copter: correct defines around using payload place functionality we need support for the actual payload place flight behaviour as well as the navigation item support --- ArduCopter/mode.h | 2 +- ArduCopter/mode_auto.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index 7e36797d64cc9a..3de08e4766a69f 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -501,7 +501,7 @@ class ModeAuto : public Mode { NAVGUIDED, LOITER, LOITER_TO_ALT, -#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED +#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED NAV_PAYLOAD_PLACE, #endif NAV_SCRIPT_TIME, diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 1f769d93ab8462..b79b008c2e6b64 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -149,7 +149,7 @@ void ModeAuto::run() loiter_to_alt_run(); break; -#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED +#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED case SubMode::NAV_PAYLOAD_PLACE: payload_place.run(); break; @@ -661,7 +661,7 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) do_nav_delay(cmd); break; -#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED +#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED case MAV_CMD_NAV_PAYLOAD_PLACE: // 94 place at Waypoint do_payload_place(cmd); break; @@ -871,7 +871,7 @@ bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd) cmd_complete = verify_land(); break; -#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED +#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED case MAV_CMD_NAV_PAYLOAD_PLACE: cmd_complete = payload_place.verify(); break; @@ -1923,7 +1923,7 @@ void ModeAuto::do_winch(const AP_Mission::Mission_Command& cmd) } #endif -#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED +#if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED && AC_PAYLOAD_PLACE_ENABLED // do_payload_place - initiate placing procedure void ModeAuto::do_payload_place(const AP_Mission::Mission_Command& cmd) { From f1b6a7d58650015afcd7981ce321691d6226fba8 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Sat, 28 Oct 2023 13:51:03 -0700 Subject: [PATCH 022/499] APM_Control: Allow autotune level 0 to actually reach the lowest entries of the autotune level table --- libraries/APM_Control/AP_AutoTune.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index 0cc30e59cb6269..14b14b618fb27d 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -556,7 +556,7 @@ void AP_AutoTune::update_rmax(void) if (level == 0) { // this level means to keep current values of RMAX and TCONST - target_rmax = constrain_float(current.rmax_pos, 75, 720); + target_rmax = constrain_float(current.rmax_pos, 20, 720); target_tau = constrain_float(current.tau, 0.1, 2); } else { target_rmax = tuning_table[level-1].rmax; From 220ab515b7e5de061a7ab40e04e862106abccdde Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 28 Oct 2023 21:03:35 +0100 Subject: [PATCH 023/499] autotest: plane: add MAV_CMD_NAV_ALTITUDE_WAIT wiggle check --- Tools/autotest/arduplane.py | 47 ++++++++++++++++++++++++++++ Tools/autotest/vehicle_test_suite.py | 12 +++---- 2 files changed, 53 insertions(+), 6 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index d3382aece5c780..81dba2f8cc1b80 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -5061,6 +5061,52 @@ def MAV_CMD_DO_LAND_START(self): self.fly_home_land_and_disarm() + def MAV_CMD_NAV_ALTITUDE_WAIT(self): + '''test MAV_CMD_NAV_ALTITUDE_WAIT mission item, wiggling only''' + + # Load a single waypoint + self.upload_simple_relhome_mission([ + self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_NAV_ALTITUDE_WAIT, + p1=1000, # 1000m alt threshold, this should not trigger + p2=10, # 10m/s descent rate, this should not trigger + p3=10 # servo wiggle every 10 seconds + ) + ]) + + def look_for_wiggle(mav, m): + if m.get_type() == 'SERVO_OUTPUT_RAW': + # Throttle must be zero + if m.servo3_raw != 1000: + raise NotAchievedException( + "Throttle must be 0 in altitude wait, got %f" % m.servo3_raw) + # Aileron, elevator and rudder must all be the same + # However, aileron is revered, so we must un-reverse it + value = 1500 - (m.servo1_raw - 1500) + if (m.servo2_raw != value) or (m.servo4_raw != value): + raise NotAchievedException( + "Aileron, elevator and rudder must be the same") + + # Start mission + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + + # Check outputs + self.context_push() + self.install_message_hook_context(look_for_wiggle) + + # Wait for a bit to let message hook sample + self.delay_sim_time(60) + + self.context_pop() + + # If the mission item completes as there is no other waypoints we will end up in RTL + if not self.mode_is('AUTO'): + raise NotAchievedException("Must still be in AUTO") + + self.disarm_vehicle() + def start_flying_simple_rehome_mission(self, items): '''uploads items, changes mode to auto, waits ready to arm and arms vehicle. If the first item it a takeoff you can expect the @@ -5259,6 +5305,7 @@ def tests(self): self.MAV_CMD_DO_GO_AROUND, self.MAV_CMD_DO_FLIGHTTERMINATION, self.MAV_CMD_DO_LAND_START, + self.MAV_CMD_NAV_ALTITUDE_WAIT, self.InteractTest, self.MAV_CMD_MISSION_START, self.TerrainRally, diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 1f7145cbe4a54e..3b71023a03df1b 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -5669,7 +5669,7 @@ def create_MISSION_ITEM_INT( y=0, z=0, frame=mavutil.mavlink.MAV_FRAME_GLOBAL, - autocontinue=1, + autocontinue=0, current=0, target_system=1, target_component=1, @@ -5682,12 +5682,12 @@ def create_MISSION_ITEM_INT( seq, # seq frame, t, - 0, # current - 0, # autocontinue + current, # current + autocontinue, # autocontinue p1, # p1 - 0, # p2 - 0, # p3 - 0, # p4 + p2, # p2 + p3, # p3 + p4, # p4 x, # latitude y, # longitude z, # altitude From 8061b1b4c20b7ad606de3f086bf82c97ec57b415 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 28 Oct 2023 21:05:57 +0100 Subject: [PATCH 024/499] Plane: move set_servos_idle functionality to ModeAuto --- ArduPlane/Plane.h | 6 ------ ArduPlane/commands_logic.cpp | 10 ---------- ArduPlane/mode.h | 2 ++ ArduPlane/mode_auto.cpp | 16 ++++++++++++++++ ArduPlane/servos.cpp | 8 -------- 5 files changed, 18 insertions(+), 24 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index c4c84cf7511d3e..d2fd912d4d293d 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -494,11 +494,6 @@ class Plane : public AP_Vehicle { // have we checked for an auto-land? bool checked_for_autoland; - // Altitude threshold to complete a takeoff command in autonomous modes. Centimeters - // are we in idle mode? used for balloon launch to stop servo - // movement until altitude is reached - bool idle_mode; - // are we in VTOL mode in AUTO? bool vtol_mode; @@ -930,7 +925,6 @@ class Plane : public AP_Vehicle { void do_loiter_unlimited(const AP_Mission::Mission_Command& cmd); void do_loiter_turns(const AP_Mission::Mission_Command& cmd); void do_loiter_time(const AP_Mission::Mission_Command& cmd); - void do_altitude_wait(const AP_Mission::Mission_Command& cmd); void do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd); void do_loiter_to_alt(const AP_Mission::Mission_Command& cmd); void do_vtol_takeoff(const AP_Mission::Mission_Command& cmd); diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 52152ec61579ec..823f1e4da93bb5 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -23,9 +23,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) // except in a takeoff auto_state.takeoff_complete = true; - // start non-idle - auto_state.idle_mode = false; - nav_controller->set_data_is_stale(); // reset loiter start time. New command is a new loiter @@ -93,7 +90,6 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) break; case MAV_CMD_NAV_ALTITUDE_WAIT: - do_altitude_wait(cmd); break; #if HAL_QUADPLANE_ENABLED @@ -519,12 +515,6 @@ void Plane::do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd) reset_offset_altitude(); } -void Plane::do_altitude_wait(const AP_Mission::Mission_Command& cmd) -{ - // set all servos to trim until we reach altitude or descent speed - auto_state.idle_mode = true; -} - void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd) { //set target alt diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index a88dbec5b6e3c1..2f745074c6f270 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -225,6 +225,8 @@ class ModeAuto : public Mode void do_nav_delay(const AP_Mission::Mission_Command& cmd); bool verify_nav_delay(const AP_Mission::Mission_Command& cmd); + void run() override; + protected: bool _enter() override; diff --git a/ArduPlane/mode_auto.cpp b/ArduPlane/mode_auto.cpp index 6ebf3546ef1690..f1a9f5de5540b2 100644 --- a/ArduPlane/mode_auto.cpp +++ b/ArduPlane/mode_auto.cpp @@ -164,3 +164,19 @@ bool ModeAuto::is_landing() const { return (plane.flight_stage == AP_FixedWing::FlightStage::LAND); } + +void ModeAuto::run() +{ + if (plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_ALTITUDE_WAIT) { + // Wiggle servos + plane.set_servos_idle(); + + // Relax attitude control + reset_controllers(); + + } else { + // Normal flight, run base class + Mode::run(); + + } +} diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 4237fa9bbfca9b..86078bb082abac 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -373,7 +373,6 @@ void Plane::set_servos_idle(void) SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, servo_value); SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle); - SRV_Channels::output_ch_all(); } @@ -815,13 +814,6 @@ void Plane::set_servos(void) quadplane.update(); #endif - if (control_mode == &mode_auto && auto_state.idle_mode) { - // special handling for balloon launch - set_servos_idle(); - servos_output(); - return; - } - if (control_mode != &mode_manual) { set_servos_controlled(); set_takeoff_expected(); From 5087a4262d8da3fd6770e9b3174a8512247cdb91 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 28 Oct 2023 21:16:14 +0100 Subject: [PATCH 025/499] Plane: set_servos_idle: output left and right throttles --- ArduPlane/servos.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 86078bb082abac..85fe2689f3765a 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -371,7 +371,14 @@ void Plane::set_servos_idle(void) SRV_Channels::set_output_scaled(SRV_Channel::k_aileron, servo_value); SRV_Channels::set_output_scaled(SRV_Channel::k_elevator, servo_value); SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, servo_value); + + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0); + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle); + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleLeft); + SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleRight); } From d33facd884858e38ed33b183c0af150500257a09 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Mon, 30 Oct 2023 21:03:25 -0300 Subject: [PATCH 026/499] AP_HAL_Linux: add newline and remove stray semicolon --- libraries/AP_HAL_Linux/UARTDriver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index 2e7d3c61d7d70d..fb0be43ceec478 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -449,4 +449,4 @@ uint32_t UARTDriver::bw_in_bytes_per_second() const // if connected, assume at least a 10/100Mbps connection const uint32_t bitrate = (_connected && _ip != nullptr) ? 10E6 : _baudrate; return bitrate/10; // convert bits to bytes minus overhead -}; \ No newline at end of file +} From a53d5839638556ea111ad8f94d412fcdf27d38c6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 13:22:17 +1100 Subject: [PATCH 027/499] autotest: assert_received_message_values gets timeout and check_context --- Tools/autotest/vehicle_test_suite.py | 23 ++++++++++++++++++++--- 1 file changed, 20 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 3b71023a03df1b..427ebb5bb6103e 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -3895,10 +3895,25 @@ def assert_cached_message_field_values(self, message, fieldvalues, verbose=True, self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon) return m - def assert_received_message_field_values(self, message, fieldvalues, verbose=True, very_verbose=False, epsilon=None, poll=False): # noqa + def assert_received_message_field_values(self, + message, + fieldvalues, + verbose=True, + very_verbose=False, + epsilon=None, + poll=False, + timeout=None, + check_context=False, + ): if poll: self.poll_message(message) - m = self.assert_receive_message(message, verbose=verbose, very_verbose=very_verbose) + m = self.assert_receive_message( + message, + verbose=verbose, + very_verbose=very_verbose, + timeout=timeout, + check_context=check_context + ) self.assert_message_field_values(m, fieldvalues, verbose=verbose, epsilon=epsilon) return m @@ -4298,7 +4313,7 @@ def assert_not_receive_message(self, message, timeout=1, mav=None, condition=Non def assert_receive_message(self, type, - timeout=1, + timeout=None, verbose=False, very_verbose=False, mav=None, @@ -4306,6 +4321,8 @@ def assert_receive_message(self, delay_fn=None, instance=None, check_context=False): + if timeout is None: + timeout = 1 if mav is None: mav = self.mav From 29f5bce61131c9ca5e5e983590337621eea4fb09 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 13:08:47 +1100 Subject: [PATCH 028/499] autotest: tidy testing of SentToComponents --- Tools/autotest/rover.py | 22 +++++++--------------- 1 file changed, 7 insertions(+), 15 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 3f97fd9e2eacac..2da688ab124107 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -5619,6 +5619,9 @@ def SendToComponents(self): 0, 0, 0) + + self.context_collect('COMMAND_LONG') + self.progress("Sending control message") self.mav.mav.digicam_control_send( 1, # target_system @@ -5634,21 +5637,10 @@ def SendToComponents(self): ) self.mav.mav.srcSystem = old_srcSystem - self.progress("Expecting a command long") - tstart = self.get_sim_time_cached() - while True: - now = self.get_sim_time_cached() - if now - tstart > 2: - raise NotAchievedException("Did not receive digicam_control message") - m = self.mav.recv_match(type='COMMAND_LONG', blocking=True, timeout=0.1) - self.progress("Message: %s" % str(m)) - if m is None: - continue - if m.command != mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL: - raise NotAchievedException("Did not get correct command") - if m.param6 != 17: - raise NotAchievedException("Did not get correct command_id") - break + self.assert_received_message_field_values('COMMAND_LONG', { + 'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL, + 'param6': 17, + }, timeout=2, check_context=True) def SkidSteer(self): '''Check skid-steering''' From 2baf9c3adbb37b3694f1e5e69723ca1780dbdcc5 Mon Sep 17 00:00:00 2001 From: yjuav Date: Tue, 31 Oct 2023 14:16:47 +0800 Subject: [PATCH 029/499] AP_Bootloader: reserve board id for YJUAV_A6SE_H743 --- Tools/AP_Bootloader/board_types.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index 013f1b21c83b9f..ac08818115171a 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -252,6 +252,7 @@ AP_HW_SPEEDYBEEF4V4 1136 AP_HW_FlywooF405Pro 1137 AP_HW_TMOTORH7 1138 AP_HW_MICOAIR405 1139 +AP_HW_YJUAV_A6SE_H743 1141 AP_HW_ESP32_PERIPH 1205 AP_HW_ESP32S3_PERIPH 1206 From e3e111ae8bf5bdc30fcf2bb1259a94d688da5cfe Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 14 Oct 2023 19:52:24 +0900 Subject: [PATCH 030/499] AP_Mount: Servo get_attitude_quat fix --- libraries/AP_Mount/AP_Mount_Servo.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Mount/AP_Mount_Servo.cpp b/libraries/AP_Mount/AP_Mount_Servo.cpp index 6d1d45a7668a0f..196b79edff0a89 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.cpp +++ b/libraries/AP_Mount/AP_Mount_Servo.cpp @@ -125,7 +125,14 @@ bool AP_Mount_Servo::has_pan_control() const // get attitude as a quaternion. returns true on success bool AP_Mount_Servo::get_attitude_quaternion(Quaternion& att_quat) { - att_quat.from_euler(_angle_bf_output_rad); + // no feedback from gimbal so simply report targets + // mnt_target.angle_rad always holds latest angle targets + + // ensure yaw target is in body-frame with limits applied + const float yaw_bf = constrain_float(mnt_target.angle_rad.get_bf_yaw(), radians(_params.yaw_angle_min), radians(_params.yaw_angle_max)); + + // convert to quaternion + att_quat.from_euler(Vector3f{mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, yaw_bf}); return true; } From 24db18db326d10460fd70b3dd8cd8baae5f8570c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 22 Oct 2023 21:42:54 +0200 Subject: [PATCH 031/499] Tools: correct copter mount test --- Tools/autotest/arducopter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index a582a330089567..8703b161d142da 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -5121,7 +5121,7 @@ def Mount(self): self.progress("Pitching vehicle") self.do_pitch(despitch) self.wait_pitch(despitch, despitch_tolerance) - self.test_mount_pitch(-despitch, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) + self.test_mount_pitch(0, 1, mavutil.mavlink.MAV_MOUNT_MODE_RC_TARGETING) # point gimbal at specified angle self.progress("Point gimbal using GIMBAL_MANAGER_PITCHYAW (ANGLE)") From 245149ded4717b999c4393238c27a51bdde3e038 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Mon, 30 Oct 2023 18:18:30 -0600 Subject: [PATCH 032/499] AP_ExternalControl: Add WARN_IF_UNUSED Signed-off-by: Ryan Friedman --- libraries/AP_ExternalControl/AP_ExternalControl.h | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/AP_ExternalControl/AP_ExternalControl.h b/libraries/AP_ExternalControl/AP_ExternalControl.h index 7c3d7b7e35728a..b72190d9c4da81 100644 --- a/libraries/AP_ExternalControl/AP_ExternalControl.h +++ b/libraries/AP_ExternalControl/AP_ExternalControl.h @@ -20,13 +20,11 @@ class AP_ExternalControl Velocity is in earth frame, NED [m/s]. Yaw is in earth frame, NED [rad/s]. */ - virtual bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) - { + virtual bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) WARN_IF_UNUSED { return false; } - static AP_ExternalControl *get_singleton(void) - { + static AP_ExternalControl *get_singleton(void) WARN_IF_UNUSED { return singleton; } From 1fa88bacd99745053fd05ebd31ba24d846af0a59 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Mon, 30 Oct 2023 18:18:46 -0600 Subject: [PATCH 033/499] Copter: Add WARN_IF_UNUSED Signed-off-by: Ryan Friedman --- ArduCopter/AP_ExternalControl_Copter.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/AP_ExternalControl_Copter.h b/ArduCopter/AP_ExternalControl_Copter.h index e9a879106ebef0..e7601c5552fc6c 100644 --- a/ArduCopter/AP_ExternalControl_Copter.h +++ b/ArduCopter/AP_ExternalControl_Copter.h @@ -14,13 +14,13 @@ class AP_ExternalControl_Copter : public AP_ExternalControl { Velocity is in earth frame, NED [m/s]. Yaw is in earth frame, NED [rad/s]. */ - bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override; + bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override WARN_IF_UNUSED; private: /* Return true if Copter is ready to handle external control data. Currently checks mode and arm states. */ - bool ready_for_external_control(); + bool ready_for_external_control() WARN_IF_UNUSED; }; #endif // AP_EXTERNAL_CONTROL_ENABLED From 8f130f962e867db24e4012f2d3e90bac2f86bef3 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Mon, 30 Oct 2023 18:18:58 -0600 Subject: [PATCH 034/499] Rover: Add WARN_IF_UNUSED Signed-off-by: Ryan Friedman --- Rover/AP_ExternalControl_Rover.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Rover/AP_ExternalControl_Rover.h b/Rover/AP_ExternalControl_Rover.h index 28647968d67d70..434972833e45dc 100644 --- a/Rover/AP_ExternalControl_Rover.h +++ b/Rover/AP_ExternalControl_Rover.h @@ -14,13 +14,13 @@ class AP_ExternalControl_Rover : public AP_ExternalControl { Velocity is in earth frame, NED [m/s]. Yaw is in earth frame, NED [rad/s]. */ - bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override; + bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads)override WARN_IF_UNUSED; private: /* Return true if Rover is ready to handle external control data. Currently checks mode and arm states. */ - bool ready_for_external_control(); + bool ready_for_external_control() WARN_IF_UNUSED; }; #endif // AP_EXTERNAL_CONTROL_ENABLED From d25d1c253e9911fb9acfd700c7ee690a03b448ad Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 25 Oct 2023 01:58:32 +0100 Subject: [PATCH 035/499] GCS_MAVLink: MissionItemProtocol_Rally: deal with alt frame --- .../GCS_MAVLink/MissionItemProtocol_Rally.cpp | 53 +++++++++++++++++-- 1 file changed, 49 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp index 8ba19415bacbe2..8c9271884537cd 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp @@ -26,6 +26,7 @@ #include #include #include +#include MAV_MISSION_RESULT MissionItemProtocol_Rally::append_item(const mavlink_mission_item_int_t &cmd) { @@ -57,10 +58,6 @@ MAV_MISSION_RESULT MissionItemProtocol_Rally::convert_MISSION_ITEM_INT_to_RallyL if (cmd.command != MAV_CMD_NAV_RALLY_POINT) { return MAV_MISSION_UNSUPPORTED; } - if (cmd.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT && - cmd.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT) { - return MAV_MISSION_UNSUPPORTED_FRAME; - } if (!check_lat(cmd.x)) { return MAV_MISSION_INVALID_PARAM5_X; } @@ -71,6 +68,32 @@ MAV_MISSION_RESULT MissionItemProtocol_Rally::convert_MISSION_ITEM_INT_to_RallyL return MAV_MISSION_INVALID_PARAM7; } ret = {}; + + switch (cmd.frame) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_INT: + ret.alt_frame = uint8_t(Location::AltFrame::ABSOLUTE); + break; + + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: + ret.alt_frame = uint8_t(Location::AltFrame::ABOVE_HOME); + break; + +#if AP_TERRAIN_AVAILABLE + case MAV_FRAME_GLOBAL_TERRAIN_ALT: + case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT: + ret.alt_frame = uint8_t(Location::AltFrame::ABOVE_TERRAIN); + break; +#endif + + default: + return MAV_MISSION_UNSUPPORTED_FRAME; + } + + // Fresh points always use new alt frame format + ret.alt_frame_valid = true; + ret.lat = cmd.x; ret.lng = cmd.y; ret.alt = cmd.z; @@ -91,7 +114,29 @@ bool MissionItemProtocol_Rally::get_item_as_mission_item(uint16_t seq, return false; } + // Default to relative to home ret_packet.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; + + if (rallypoint.alt_frame_valid == 1) { + switch (Location::AltFrame(rallypoint.alt_frame)) { + case Location::AltFrame::ABSOLUTE: + ret_packet.frame = MAV_FRAME_GLOBAL; + break; + + case Location::AltFrame::ABOVE_HOME: + ret_packet.frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; + break; + + case Location::AltFrame::ABOVE_ORIGIN: + // Above origin alt frame is not supported + return false; + + case Location::AltFrame::ABOVE_TERRAIN: + ret_packet.frame = MAV_FRAME_GLOBAL_TERRAIN_ALT; + break; + } + } + ret_packet.command = MAV_CMD_NAV_RALLY_POINT; ret_packet.x = rallypoint.lat; ret_packet.y = rallypoint.lng; From cd621f05033b93b7252bc1d0f2ecbb70175b658a Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 25 Oct 2023 01:59:20 +0100 Subject: [PATCH 036/499] AP_Rally: add alt_frame to unused flag bits --- libraries/AP_Rally/AP_Rally.cpp | 6 +----- libraries/AP_Rally/AP_Rally.h | 13 ++++++++++--- 2 files changed, 11 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Rally/AP_Rally.cpp b/libraries/AP_Rally/AP_Rally.cpp index c8c586e5b01aa2..d3b8284a963aa6 100644 --- a/libraries/AP_Rally/AP_Rally.cpp +++ b/libraries/AP_Rally/AP_Rally.cpp @@ -129,13 +129,9 @@ Location AP_Rally::rally_location_to_location(const RallyLocation &rally_loc) co rally_loc.lat, rally_loc.lng, rally_loc.alt * 100, - Location::AltFrame::ABOVE_HOME + (rally_loc.alt_frame_valid == 1) ? Location::AltFrame(rally_loc.alt_frame) : Location::AltFrame::ABOVE_HOME }; - // notionally the following call can fail, but we have no facility - // to return that fact here: - ret.change_alt_frame(Location::AltFrame::ABSOLUTE); - return ret; } diff --git a/libraries/AP_Rally/AP_Rally.h b/libraries/AP_Rally/AP_Rally.h index 0eda3e2fd826a1..0b4f34957e5489 100644 --- a/libraries/AP_Rally/AP_Rally.h +++ b/libraries/AP_Rally/AP_Rally.h @@ -30,9 +30,16 @@ struct PACKED RallyLocation { int16_t alt; //transit altitude (and loiter altitude) in meters (absolute); int16_t break_alt; //when autolanding, break out of loiter at this alt (meters) uint16_t land_dir; //when the time comes to auto-land, try to land in this direction (centidegrees) - uint8_t flags; //bit 0 = seek favorable winds when choosing a landing poi - //bit 1 = do auto land after arriving - //all other bits are for future use. + union { + uint8_t flags; + struct { + uint8_t favorable_winds : 1; // bit 0 = seek favorable winds when choosing a landing poi + uint8_t do_auto_land : 1; // bit 1 = do auto land after arriving + uint8_t alt_frame_valid : 1; // bit 2 = true if following alt frame value should be used, else Location::AltFrame::ABOVE_HOME + uint8_t alt_frame : 2; // Altitude frame following Location::AltFrame enum + uint8_t unused : 3; + }; + }; }; /// @class AP_Rally From 9ed5dfc768c6f22474058e1cf6dda47c606734ba Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 25 Oct 2023 17:16:42 +0100 Subject: [PATCH 037/499] Tools: autotest: Plane: TerrainRally: test terrain alt frame on rally point --- Tools/autotest/arduplane.py | 35 ++++++++++++++++++++++++++++++++++- 1 file changed, 34 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 81dba2f8cc1b80..50cac72819507d 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -1908,7 +1908,40 @@ def terrain_wait_path(loc1, loc2, steps): accuracy=200, target_altitude=None, timeout=600) - self.progress("Reached rally point") + self.progress("Reached rally point with TERRAIN_FOLLOW") + + # Fly back to guided location + self.change_mode("GUIDED") + self.do_reposition(guided_loc, frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT) + self.progress("Flying to back to guided location") + + # Disable terrain following and re-load rally point with relative to terrain altitude + self.set_parameter("TERRAIN_FOLLOW", 0) + + rally_item = [self.create_MISSION_ITEM_INT( + mavutil.mavlink.MAV_CMD_NAV_RALLY_POINT, + x=int(rally_loc.lat*1e7), + y=int(rally_loc.lng*1e7), + z=rally_loc.alt, + frame=mavutil.mavlink.MAV_FRAME_GLOBAL_TERRAIN_ALT, + mission_type=mavutil.mavlink.MAV_MISSION_TYPE_RALLY + )] + self.correct_wp_seq_numbers(rally_item) + self.check_rally_upload_download(rally_item) + + # Once back at guided location re-trigger RTL + self.wait_location(guided_loc, + accuracy=200, + target_altitude=None, + timeout=600) + + self.change_mode("RTL") + self.progress("Flying to rally point") + self.wait_location(rally_loc, + accuracy=200, + target_altitude=None, + timeout=600) + self.progress("Reached rally point with terrain alt frame") self.context_pop() self.disarm_vehicle(force=True) From 1bfe83bb634d19f47cef28b2a9d7bda0f2655089 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 27 Oct 2023 00:03:46 +0100 Subject: [PATCH 038/499] AP_Logger: log rally point flags field --- libraries/AP_Logger/AP_Logger_Backend.cpp | 3 ++- libraries/AP_Logger/LogStructure.h | 4 +++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index f432328a160490..57f8792bdb2010 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -519,7 +519,8 @@ bool AP_Logger_Backend::Write_RallyPoint(uint8_t total, sequence : sequence, latitude : rally_point.lat, longitude : rally_point.lng, - altitude : rally_point.alt + altitude : rally_point.alt, + flags : rally_point.flags }; return WriteBlock(&pkt_rally, sizeof(pkt_rally)); } diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index cfbfbbb1780314..ad6632a24cbe79 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -548,6 +548,7 @@ struct PACKED log_Rally { int32_t latitude; int32_t longitude; int16_t altitude; + uint8_t flags; }; struct PACKED log_Performance { @@ -968,6 +969,7 @@ struct PACKED log_VER { // @Field: Lat: latitude of rally point // @Field: Lng: longitude of rally point // @Field: Alt: altitude of rally point +// @Field: Flags: altitude frame flags // @LoggerMessage: RCI2 // @Description: (More) RC input channels to vehicle @@ -1286,7 +1288,7 @@ LOG_STRUCTURE_FROM_FENCE \ { LOG_DF_FILE_STATS, sizeof(log_DSF), \ "DSF", "QIHIIII", "TimeUS,Dp,Blk,Bytes,FMn,FMx,FAv", "s--b---", "F--0---" }, \ { LOG_RALLY_MSG, sizeof(log_Rally), \ - "RALY", "QBBLLh", "TimeUS,Tot,Seq,Lat,Lng,Alt", "s--DUm", "F--GGB" }, \ + "RALY", "QBBLLhB", "TimeUS,Tot,Seq,Lat,Lng,Alt,Flags", "s--DUm-", "F--GGB-" }, \ { LOG_MAV_MSG, sizeof(log_MAV), \ "MAV", "QBHHHBHH", "TimeUS,chan,txp,rxp,rxdp,flags,ss,tf", "s#----s-", "F-000-C-" }, \ LOG_STRUCTURE_FROM_VISUALODOM \ From 935ea02a711b88f639690031f1766ee13e72ef66 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 27 Oct 2023 00:17:23 +0100 Subject: [PATCH 039/499] Copter: RTL: ensure rally point is in absolute alt frame as RTL_ALT_TYPE takes precedence --- ArduCopter/mode_rtl.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 795e483e93423a..7c74838a3fe742 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -408,9 +408,10 @@ void ModeRTL::build_path() // return target's altitude is updated to a higher altitude that the vehicle can safely return at (frame may also be set) void ModeRTL::compute_return_target() { - // set return target to nearest rally point or home position (Note: alt is absolute) + // set return target to nearest rally point or home position #if HAL_RALLY_ENABLED rtl_path.return_target = copter.rally.calc_best_rally_or_home_location(copter.current_loc, ahrs.get_home().alt); + rtl_path.return_target.change_alt_frame(Location::AltFrame::ABSOLUTE); #else rtl_path.return_target = ahrs.get_home(); #endif From 2bef8f2cad98308fccbec526d3e42b0fd41ca174 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 13 Oct 2023 10:32:57 +0100 Subject: [PATCH 040/499] AP_HAL_ChibiOS: add support for SpeedyBeeF405v4 --- .../hwdef/speedybeef4v4/README.md | 100 +++++++++++ .../SpeedyBee_F405_v4_Board_Bottom.JPG | Bin 0 -> 106199 bytes .../SpeedyBee_F405_v4_Board_Top.JPG | Bin 0 -> 146093 bytes .../hwdef/speedybeef4v4/hwdef-bl.dat | 43 +++++ .../hwdef/speedybeef4v4/hwdef.dat | 165 ++++++++++++++++++ 5 files changed, 308 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/README.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Bottom.JPG create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Top.JPG create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/README.md b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/README.md new file mode 100644 index 00000000000000..78405c62291b1b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/README.md @@ -0,0 +1,100 @@ +# SpeedyBee F405 v4 Flight Controller + +The SpeedyBee F405 v4 is a flight controller produced by [SpeedyBee](http://www.speedybee.com/). + +## Features + + - STM32F405 microcontroller + - ICM42688 IMU + - DPS310 barometer + - SDCard + - AT7456E OSD + - 6 UARTs + - 9 PWM outputs + +## Pinout + +![SpeedyBee F405 v4](SpeedyBee_F405_v4_Board_Top.JPG "SpeedyBee F405 v4") +![SpeedyBee F405 v4](SpeedyBee_F405_v4_Board_Bottom.JPG "SpeedyBee F405 v4") + +## UART Mapping + +The UARTs are marked Rn and Tn in the above pinouts. The Rn pin is the +receive pin for UARTn. The Tn pin is the transmit pin for UARTn. + + - SERIAL0 -> USB + - SERIAL1 -> UART1 (DJI-VTX, DMA-enabled) + - SERIAL2 -> UART2 (RCIN, DMA-enabled) + - SERIAL3 -> UART3 (CAM) + - SERIAL4 -> UART4 (connected to internal BT module, not currently usable by ArduPilot) + - SERIAL5 -> UART5 (ESC Telemetry) + - SERIAL6 -> UART6 (GPS, DMA-enabled) + +## RC Input + +RC input is configured on the R2 (UART2_RX) pin for most RC unidirectional protocols except SBUS which should be applied at the SBUS pin. PPM is not supported. +For Fport, a bi-directional inverter will be required. See https://ardupilot.org/plane/docs/common-connecting-sport-fport.html +For CRSF/ELRS/SRXL2 connection of the receiver to T2 will also be required. + +## FrSky Telemetry + +FrSky Telemetry is supported using the Tx pin of any UART including SERIAL2/UART2. You need to set the following parameters to enable support for FrSky S.PORT (example shows SERIAL3). + + - SERIAL3_PROTOCOL 10 + - SERIAL3_OPTIONS 7 + +## OSD Support + +The SpeedyBee F405 v4 supports OSD using OSD_TYPE 1 (MAX7456 driver). + +## VTX Support + +The JST-GH-6P connector supports a standard DJI HD VTX connection. Pin 1 of the connector is 9v so be careful not to connect +this to a peripheral requiring 5v. + +## PWM Output + +The SpeedyBee F405 v4 supports up to 9 PWM outputs. The pads for motor output +M1 to M4 on the motor connector, plus M9 for LED strip or another +PWM output. + +The PWM is in 5 groups: + + - PWM 1-2 in group1 + - PWM 3-4 in group2 + - PWM 5-6 in group3 + - PWM 7-8 in group4 + - PWM 9 in group5 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. Channels 1-4 support bi-directional DShot. + +## Battery Monitoring + +The board has a internal voltage sensor and connections on the ESC connector for an external current sensor input. +The voltage sensor can handle up to 6S. +LiPo batteries. + +The default battery parameters are: + + - BATT_MONITOR 4 + - BATT_VOLT_PIN 10 + - BATT_CURR_PIN 11 + - BATT_VOLT_MULT 11.2 + - BATT_AMP_PERVLT 52.7 (will need to be adjusted for whichever current sensor is attached) + +## Compass + +The SpeedyBee F405 v4 does not have a builtin compass, but you can attach an external compass using I2C on the SDA and SCL pads. + +## Loading Firmware + +Initial firmware load can be done with DFU by plugging in USB with the +bootloader button pressed. Then you should load the "with_bl.hex" +firmware, using your favourite DFU loading tool. + +Once the initial firmware is loaded you can update the firmware using +any ArduPilot ground station software. Updates should be done with the +*.apj firmware files. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Bottom.JPG b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Bottom.JPG new file mode 100644 index 0000000000000000000000000000000000000000..acc3f8d957bd7f0a08b6ca037ed3c0e31f47b6e5 GIT binary patch literal 106199 zcmeFZ2V7LiwlBO95y_GyXOIk%B-0?0MKTBoNDfWTxd{T2g9HW1Ig8|sWJN?WHc4{M zsez{X+L<{sbIzR`&VBd3ci;DHeg###YuBpvueGaI+FVave+TX;$|}eLC@3g^C-Mil zUbq95@wB!80A*!>4FG`Kz)ciU;0CgWhHNN?SpzqbbrfV>^=1kjP! zu#s&EWC18Qk-u*LsQvu>MBpa^KN0wez)u8zBJlqr0#f#7UP!*t;!uClBZ!dtLPp%p z-|O!a;(w{5KHvp_goHopf9Mpq6Mo?KQ>XZUQF?yz{1btn2>e9gCjvha_yYmn`@DQ2 zJoiO-_-K*8`FKS5d4a#W1^`lkJzxg>P(ZF1ut=<2T^&WZx$RxJjLjTO%(+Y*?6^IR z9l3e9?sEfTAWuhQQ?R)!t%y^DyaIQ=i9iy-SiE_2gMh&h{Ch^Rl3{jCSG zB~Jg_Ts%BHxIFl{9Goq=d4z?9x$pCG^YU^cdvLmV*}EEha@xBv{5HTNa~D%*Ye!dW z2YcEd0~(t+xVehcySZ7LiC7q02$-0e32>Si^OW*&Cw!hFeGvzk7HMcXjcXdIc!NX0@{p+Ovt7sx2`km-s!jI$;*+)d$ z+1%LG{1LK9{8&&kOt7v z&~BmKM8Ac0>oz+2ZA^SDq>h0}jCThcpOl!KjFgy^go2uxj)IDbiiDJ&i=K&vm7Rl~ zoR*u9n~j&5jh*esASmd!Z)0L$5@BHxu~Cvzvi;Ma>ka__Hmd&3I#d*T;08VlDn80} zH$a07IHDm#ls}@BzkN_{px#8gg?<|Y6ARg)_6~3Z1r_ziO;j|ro5=ViiXZZO;3hsA z0UeLjEkZS8bb2Qu-oW_m+YAq@J`k%9?=$k5I0s>1-X$R=BWJqD%)-jXFYrK6NLWPr zk&LXIyn>>Jrk1wOQ(Zk%Gjj_|D{C7US2uSLPcQG_7a^fxFT*1eUL__ar@VfXnv13UcvK@c|HUAsfMx zbt7(MgdAYWiTGLm0RvWRRx2PUg5_V7JpP){08EygpXDDh&{Nd=OEF@_;iSvD@k82v zmcPd!IU)J4#YkF7{;#F)uO#ySrEB?l`F{`L-$d$v+eRkcqyFmYyYNr7oe7{O41|_Z zH(!gM{g}`Zg*C%Sqts*EzDpOCYalZg?mB$cSa=N#^&v#Su{i;vcsqk2gg@wDRPJ;& z^BMrrz&0u*B7kjBJ^wXu4!Z{Wlxe0@A#gZksi5J41@#?bX7n0ZTe=3Q_#yVz*TB)i zH4u}!w4R0A_5TMN#SHOG2E$EFr{=;$DBu3X;hz9;I#xwD{vAfEKM)b<8u{Y6dv911F{JL2t&nm-5J zz+H$Drkr@toHYZ}69o|{ml}edHq_b0D{>YBwCNtdl)b+sd^0o)_i#i>y(%L3TYII~w)cHvG53^@$Sm73`^Ft^>*%i{mA8CCb<$(u#EP z&I$Kl+cBx2qpt#I#bR2PcKKjxn(<>8Lwz%1Bw|E1{D#-pk8%A|o1(GOl2m9#4cEYn zAecnatDcpf_Z_mR`mZuy*ExImTxfduvwXE>h*8?H=$&O^lpT4JC5()Wrfs|=Ze*9p${78U&VhC|&L#G_HzYYu z64FE*mx4MLpJ_As6;em2V%74{*r&+cOn0F}cZtSbxxG`xX-ChDxL;iERwIN)iSFwT zhiTG6toj&jb;cthW5W8+C_8aHu&=ku>%(0|2Omx8f$#DeveHiXiKL)!=oB;t&E}F2 z%Hb!~$x;Q(%sPs15$f&NMT0`^ZF5I=%1uLWS&@?_ks9F-kYGbt}~DQGs$ky^#Fj6AJM9*M-zM)diL8o_qP_ z8+yFCHW$(5aj$m$a#YjW-c)$6ewpi9?2R~8&2MZQ-OX*pXHjF3B*Q>0MsGD;ClLvm zsH(8pT8Q1TULIqr)6ey|;ic9Wg3l5k%(BKD<1!Z@jtSkwnl@{w&Jg|{XU-TN%#LTm z7Sb1f%&z?CsR8)G{W-!K{npN~p#t`3t%(-Fd{~!eq=LcSFG@0vHT5L;@(c~Vlh3OX zh$usM`YTf8_6s8MLY}|#!SZ=oSg#>ENa~TEE@fdMmY}dDd8>JG3y1L8CZ^`{8+@6SV@J;j>h%1#)oI1p)=lB@7GX)Jen{JwrtjKP7b#)7}eGr(=m zokQ$~KI76%s>912<1t^Yg?YRg+2F@Xmd&X%Tm%;3QjeaCR6KE-3lOZCzq1bgoFJEH zQ|B>6Gq3LzoOBVW&2_>~fqm6r`ShQbVkc-9l}$|+CrEjs2*6u-`rZ^ZeQsaqa>UQU^?JxNDU1( zw_BKAUwQScNuPzQeBM!Ji#?R8Gl*|mfUCWHWA64>JI)=$i5UhNqPvG}Gkwiq!8UZp zi!nX80(x`{%?qu7X9o0aQD|}9_dVg(^LJ=Njj(e+64?)U*`k=;3@{@jLize_^MOdB z%7Zj7oEf&B$8injH+>?C!HWjCXR2TSgXF?i*q@YNw(fh{nMuovpbSkR;W1@ z+}(w$?XZwstBI!8)igWtknTf@hkan23$4lX(>Djb7TKF& z0kj`D@JkYWR%AU(E;3(ipKvPI8c3XOJszvu1~-#Q9`SS#(4iSoFG(Du+>10XxAuN} zIth)m@z#Gtjg^+3V`U`7(j$r8u;z|tHZ@Sc zc!Cf86ZyK7q{r95`)_)i>`B3Euts-{Om3N%3NhWEr-l|Jsh*a%Vqov>zWB zMWyK0114!}J?-^AUGzFRS-ZX@?S_5$l-ZK!D3@=pvM>uVJS_LsD4wcIql{#j-q;tR z2r8r%Gh_&6!|{Ub-f&_nuD(QK4s$Bd-!;>tgMkt9ao5fO2(je zA5rO7uDdD0GRA31?(>F|lOxA0+KhqP^zO=Q?C*|f_R%6UU~~;k|1mqnXMHg*pROeu zHSHo)kpU&J3ehHcRUGeZpKXwsbDOI1s(YZl>HAH&-QNW6BP}T(gM^h&G($ z{rA8CA>!d-Ny?Dkz{Pa+;p0J5!)g)N$oF35c6y?3Mw=3zjP-BI`jwhoN-Hc6%M>el zx|Sv;nPPp=GRT(82P3CCcW;=+Xn5q4@Czn;<4hke$avkhzX0e|AJS>?pn5g>{nJPl zcFG{8`DReQwVEUuNh-U6XSLGA%@69mSTCav3ijhdLOQ=^KfehuwgRTrXNk{JJiRj#Lx z{zPHD5%J~&-l^$N)mTat?oy(~pWcwgxCeh3o^J&Y=JU6))s4f4>nMadKYOl3KG{n*4%I}!bWS8}UzM^g0f zo|8S{3%c(oKbRWg=Hw-w5P=c+|BPI?Re2T2O?J3S8iOV9EeF$dA z3%SDt{J2${8~2m*!FD*yq1I&%&$%)C{g1LWl9(Hob+lvvmnKlyUhc%S{sGRhPHIa0 zsi!uSf%3t@s{|qf1;&$mS(#mW8EHkchMr35LBkG|1LD!k_vFc?CuE>f4}AjTz{NQM z!h@o6W6#IZ^bhV8aP1lg=0;!%y`c@n<9N87Vj5Gpjz&#X)x^6gvRjNLIO~~-B};=%%q$Q@TZOPX;S0D3kQkC$G*)E*XH?AM%3h4tpPO|qW{*SKBE2=MTSWA zUle(3YaD<`P3FJ72#gyjHelyH4-%Qs%%FVl!BOxC{eAt7+Vz54f^Y`y%%c&9%XPJD z;P!YS{5TD9L0m0E%hSFjD^XTgVyrq&%TzYvY=8R@Jm(BHw3SaS&(Ll z%_zcK`5N%U{FW2&Kj|K}^nyqSCod1emO$e;w(l{oD-tIx(yjqIP9;P$-pb?KkiX`S z6(#x)Ac!EH0!SZ-_`PeOEyNbN*Uj%o>p_MT+V`^Meg{r_km!HJJxg8g&kv7i?7HCW zPv+*>tsbe;KB5AOt^V3~^*0~Zf7Rdr1??bi!VG$nr%r^jJpI9(Qk(dI-*H3aeeFOL z6DWi{QCkkqs6Bu5#i$<=O|u`b4;d1M&^^n9zUDrMMV=D-kRSii11ZB8#P#r_ltUtj z&GYuPMLc7js!AC%NT-b5H6XSE5BYrrxzhqHgg@>7Edy9gZzb0g-bQ#1P~vn2fgkA@ zP|C0!tmd=l3O`hJPq-VwQvUIGj}R*cV3xtobq#bwx!zm@G)+k@mY2;RKyk&1xisNZ z?hdBf5laQI?1iFmEGMzH4OC4KQk@sw@VEy2!Q5qP2;)Pgs_Efpa&XRA+zW$iU_Mp) zz_hC^1#-5UGGTQM+;>*0no%?K@i{2$OeUdzyn5#Ubw>ZyhmvbxzqN(tYHJUEOW>=* zhNey`(&=!v4>_xB-zOcu2C$Ys%+Ix510AN4)JZa4g>ddnbcpxmHGmRrZAC*O#{aZ8ub)=eq{v5-`=wu4QHY(1}huo0jlJl<)_Oqcg>Dby0X zQ)Gn6I70U8;eywIO6J*O3gRwulxtw)2m#lo(anYTAkmy1e#Q*vL{hp2M%S)jxrn=G zzjaYNNdav%;~nM)2>S7CeO7OsvH2i`s(XOSCq`^MaEN zqM@usTlAr_*oE2X^y&Hpe}BZN4f0A6DzMwhkTH%ptLgaMx*$-~MLrgKYcE$ACU3;T z>EzXtxfl93$if^ zde{W$D~8=8q?8N_r2gt)S5i=tL?crBmxV4rkN@A&HBg8@(od)h(cv9dFzVR3Tm#ha zuYm?gk`sL!=w*Aj%5X+9mIcz-Gve?F`7u6mKm18!#%PBJq23@PL1da19%0gR>~%bb zjL@c~u`6Y(4QOhn`{b;{5p&wyJE-0Q(n{zl^OfE2edBHMpjvOPCB8?ruc7E6uV!!$ zcnXH~aMU5Yr7md4BBU$Z=iBQW;!?IWy|u2zz4(cFyW^)v;Pw;~uQWSG*DS)XgvUhG zB0=m!E2H$2{_LBl-ce_v&}o(W1eWa9WMXZL=TGp%@|DZ1>*vtl`#DIqw=`DOUag#_ zc?rK2GwL3$_C>lH4&?=mbfU+ETUS$*1vY#TL2EwK(v5j#>8dt*1#ggh_U+YdwAT%E z89R$dWG3u!riN)Ta)v;eQP@`nYvz~bOf5|QnU!2u8ZdJRN- zo*eA7J+*R`&D0juIq+{RuOjgnxjl7&EoTyIi`yQp{i@5mMU_miR}z@{bYEAl*f6JP zdTmF|E~;NTigt76xO~BTa_&KW!)SIxePi->ui^f0ABGqoFyS_Ls9lBMJHVXpB{1Mp`2r0ys8zn?t|p?bjGj zTe0y9!NI;@Z^}uv{-*S_PXQs_xeNjy1-bm|SZ$vx?=LAdzEH4qa=Wz<-;5JmBvc8S zsHq>Wwca*&qIytjz#n^Kk$TSf`D_UQIwSS^t%zp)xWJ+jcL>1r7#6*tt$cS2ARiCn zkf<{c&N@;CYeokdwO8=c#Y}=Nbaa@(yh@TRQC&?E%b>k$mV8UM zcAVg=3ns=BDdCQFo|#EJ!@&JMy_OLYwYx#OH^0j*_jcP`s1sdD2}DB{6lWu1yQ9HI zxHcYwar&)g$#d@V32tmzD9MZ$D0+81eUw{ccEv$j39GAf_h+Q)9-Ig5s|c-))UAvu zXVl(`EE-~!x6K$?Tz#l-I|As2AEV!Rvyh2nqbIPle0I=V7dqJS##~#QHk9N z_SDwbD)9bcFB6SzW2(h2AtsxrFJ~4-Y;|kYI_%SVPw2rWd;XEubKUfD)uQL!5yd`> z(e$!W&y1j9u|jm`mBNa-PtHU*iH?QwNIXrtlt*OdGASMn(3f&8O5J*26MNfWlTVU6 zUs-~6XcvBP^l_doUB1shX?$yreRN^OpysmKCoMrPv4Ox2G}l+_q9?O5^v%uTj^UFd z6(S?c@Y(ksAN$rDD@wS0GY%4W{4gI-GmN)@+_&;JT^OxaB)_NyfM&&X@;n_DuUbDS zLGE;O&K#V+Ml4*!jQ7gg@uy=wj(2^{z1X6DmZDy4lKB7=+iwJ2;NfJKUD@U&I2Uwr z(;1)gFo?G`tXNjl@`Dn-Lxu(kHnDRW(1DPjTNYanl{X|3x@&G
ThGSusY0WEsK&U8ql^!!?=!H~nedu&_jpd6`lR*iAM&QH z^3rou2hoJL4Ay(^D}4>nu3Q5Z!RO>hN1!v2jLG29QOM(Q5XHhsM6EAy^qxrEII3Sxy9`e(b4yh9CO?Ws?IMSSyUi01l}0vZ%kF)hJ3lGcE@w!AD!t&!b;-6%AsUqyU z6V`4nQGD#v7-@(NnG>55*4)x_9G&+1pUl%|x@WklyKk+7f^osXwkK4P_ri7)KQw|)Ti zYl&vlmt~k|*tK9NHt~6-BlCPaBcwbeCxR8w+PM>7Digzt3t`LEIW{`Sl0gQ(84NsW z&PpJQMsL!M76!g<_8^bdLh3tz_2B>KEqIwfpW)5mOxQ`vRTsQ8ocLfy2CnEIb^K1B z$0{e{+@?%qPwLH=&2|fBqadW#!#3@NzU*Kp#)Div zBZ7$|(&>P(JzQ|ss4uH|{(SxniC$C!EiK2{5Itp-b7AmA&V(4-MMZA@Cce#?wnvjI z@1s}UFO~K%N#kUNr!Pj!U2*iV`pwgN^g_Cw8Z1Hz=C*@6(ud+7^14|-kR*xAvA99%8SXk0{e?Hj>ET6C@f@E@{efT^#R8?W#!?Vq{-WKNnFe`!0W=xT-);W?>>yX_Uio z)l!P_Xqn5$?9~P4Y`SssgiI6G^80vN|1_V~aB>!{wfH1rja8R#asn&^QRu#WCKGUs_{72G`uv2KWW z2YoX(;t9+4)vgbfpxmP7jpjPh@uQKoC0#&<^kX&F#fP>G8?#`{T?q1U*`$Il$_UUT z?{3`Xt{CEJWnOOJ3!U~-;e55$*o?*c1Leath5govu3_jcUxa7TZVmTKmKPuMY}5+X z8S1ZrEuFEv5Hi!iO=SV|=osR$Obg;!Qdv=Uvf1jT(zI5WC$GzA>L(Ih=>}vW`I?AP zqzRh&@fz4$sC+Mg!_}ujmu#5A1WCG;a73#!F2U+A+#k zede#Ofe82p%I=s3eX8)HuCZH!AeoLvT-O-6-@ocAyj9HsTIMN&w6uS!8MJr`={Hrq z2D~6ifc5ad;oekNeS*UH9k+HFMCdP|yY4uY=c%XJG>&VUu;LXnz3$ED<4V*q06RIj zA+&?{qNccBnTz~dFVgO4{Lcra^ zy4I%mb`vQC9pBJ-8a3kQBPwM813y!>_;1VYjTWW}gRG3H4yXBNJ|DxbY6N_`sENm0 zj7lrgbM(pb#hNn+m=H(QoozAuMjyEGJZ<YC`PaF6?~_fg8RfbWC$5iXc1Ng#O*?mMFCDf|-Vbv^2UMEe zeCicE&fgxQY-hPrfxo(rSH~)cxQ=96U>y<(lU@Vl-^I-LV|DhQrfBWI7%|!?!5Xq= z<|aQALeT9Bmt|sjHgvt&es3~#p`0eDavBChxGkDGpF1CE__&G`O(=ZJ$Sl>R=)S90 z9?3yyCdc*NajwNxpx62g8r!u;cmqqpcG(^^kQef@0)e9}pe#X_lcDFOi z@`>~+8|f7KeD?Xnu$r@~2PoQ$zr^{=@YH&u14Z?eYq|Qo&ZtRCjpM_B4Iw{Ddb zF#S>+a+ewXXZnh^&Wg?0cK#ua?!BWV@tHEMY->vMm* zV?>QmI=g7=o%34d5mNr+%SWyKm!&8CK{%RGX$^tL7$cQZ4#X|Sw33nQYDkILGXQi*ERjBa`_{4mm=*$u&yXF-S#zH4Cpq~cTKtZ8Ru zv1jPKZq0Z_&2)oZ>KOm+=ti=7%3bsZnj}}_71EDKq6PwI@%+%Q>k8i|(>yJ^+*7}_ zE}rk&JLH&6GD&h)%rP;TP)lxlZ5fz{hLz~e%LxpHSMHfS^w1w5GBygjFHg3Y*;!N= zY;WgACA+0`Ky?+dNuun=p(aPcbqFjuGG`IjlF23{YMv<>_*~#Ku2>A$BLnUiy!_gu z28xVvJc5EatW@Y|O_-|)0?5bvBiFzj(uplw>##v?ewxl7>r*~!V;lfY!OwX?dqN>u zM#a~m<1LXwomK#=)~c(Hs(QL4|DLxyJ|XYqUP7WdMyJMj&0ggrcuVIX{|MEhwahgT z>&u<5Z@gBQq5NumBFMN~D!yuu7 zdW1+$Q#n?bHzX`KZJV8a$nir3R|O-lGS9Z|kWp3#byA5Yb=P6;bSHZ<+vY^uto=1G z@Ku=cL`WqpbrNb{+iY5}>Es0+oXOEG*ENmhPLJx_eYa6R(LAi1DiL`r`gD(O7BTI^ zxwMD48~<{XnG(^AJ z%!H+^TI#@@k42hTa@wDW(f(Dk>VH0|Gs2DAfxc2b5ARdM+vne-@S)AQTIQo1YjG{_ zSWU+c`ObC1Qdg>b4?m?TRIF)JH|4v2c^I(;s@evv%|iGP{1DTpkfA1oB^=y+4d_%E z4bt?%W7;b;w!b|2(XH$syCHp!zx4{X$LK$y|V%? zw66zCJp|!{c`P5-+ghIvjy%NUy}!$zt`Dvx@r;;$!Wn*IJuoALxUG|XB~+PR&S_j# z9WgN?5J9TSXq6kH)!g^0 zZ;>RTV3^+B2zSFCR73VeVp34;E~H6x($CHT zC%?r}U$&};Jmis7K$bi4IvHi25gx}bBOw@?oL~0X|18s4o!2k^KAM3Mil-fLcs%~t z)htzp;Q%LfeLe3MqX_3jYT+fj`r8W6po5m>zATWZpEFn%x{>d|w#b0}-TB3`U{l6o zxdvnOGwc&|+6(gMP7neKYN+R=tVOssr}nHuU1q`3Rqu($h0cJEd-c?u64--6MvP1S zk$p*5QDvQ4IH^O6kihp$YWTgn)ad$`+e=tf!-w{DvFAulfTn0^p9p2iHHq>5fQyKf z1BDVt6fyoS-SBmwd{(8ypJ{}DvTcmN*t9;D8hi`eWaunF*r+!^7|J#SHCQG$Xv^im zuJhpfNc3&tjsN~dgaZF`LrsGlE3J7=hIRz2ikvywbBQ;3Xo`v>P5X#)^V|<5hEJ8z zk_NUztx2rnmc%UUTMb6xc#Fz93W$-><2MC0Y`T=s$$(8wYJKW46mVxIev91q({K56 zUdegO&}TOe5U9dN9g}5N^EDDF{A^9TNltd$2jW!(bZ{h>JkpG3JReA}mSgaxgqGiG z_eH>IN@0TPN}M)K+VO&YjF!$qd%@e@U(tu-e8Kztn;7GU3>%y^5s)NgBm^tAWB!;z zU2R-*A3 zjdye#rLT|{2SUtTZ7d1--y}~!uxA;!u7RvY$UHKG6%(}J3?o4Vha*X3!r3FLU?>Z- zPkPx0LERq6oIS4fm1v^UST)_$%ua4ptI2D?WZc)1vwWfhp;WR9^`^uGjv=sTZOFjJ zUk^9{S6PnINmipq%BS^Z;lA>`;t1oi?Ysq>MmlhV9?|4!ewE8I1^g7Qy%W<&E#eB+L!4B4i zX=Ggk&tmhQp z05CV`uhRL2vlUDxD-8uzKYbv%NiDS{NfrBdH__}j!ZEG^sj+LIT?IkBsxyxPM=97O zn40&Tljq8&Rls7~eSEQ$FX>P2D+s(=>O&nX%EHq?uFlYRl?&XyUxenzV*S$m1(*s7 zB^btnpM#3h4s-XJPV##K0;?p&Iw2te6&)Dg_w*a9?0%NLe7b|YDKWxY(jvi8$aRZE zu3KhD<}uZ;>xRVT2WP)MCtj9tc2F42u>|O9pOp)72WGg}c~Mck03mM6y_b&fp<1GO zN6^mJnU@81>>ljfcX`dsodm@2bbsHuj(Dm6upxC_bZ>m&+`Iz(o(w+S#aiY_n=Lvm z_0*tiYI~r-AXevu2%->E+S<3{5mJCWd3iAmzY(ESF78DlSPpEJ?U*{Jba__ihS(dt z`P@KR6$BO5A~J}^;-12d2SYAytmmdi_IVi{-s3wyoqBztIrV9pK|E+5jj_LeexDmZ zX0I+Qmk*c>>*NjZ84uHque@MN>MqAtzf0zB)EYR6I#FgNK{5_kVjRfRJ1@1*E=ZbT zbV40^iFehyV(v*33Cxq5o3?_Chjo8#S8NbZU)p~C&WQK2VN6+@O=15h& z1x=fX2A%YYA&5{uPQ(Oe&%s_js~xH7|C~aCOXSoUv+WnKT3xyh`L@&XB zO51Ve6|jyj$r_mGiesu9D?vM9Uax%(q$qQ?TC2!(MgD`Pby?kLZLp*T>p*GmL+A z?3&TBmX~BekAI9gA$XdaALZdr*yrTH@~Me3*bwI+a^c9+;u1lKhuyO>UGt_j(0`K$ z`klM;aKm4(h?slAr-u$S1WDRX2pl2p0rTG6grRX5JRv0Z7RTfWP{ z(;t@0N`!J`5x!Vj$_e^1GAkAtqbT3pQok+(hRJo`oe)V{hSroZHlh;7XGjU7k2EBX zTJG0J)v90{61dCz=0GATi)pkf-fid^WYp$CjRxuSsyOQ3^Py?Y&}_O$>)nB`|xGk&ksD~%UN1byKo8aUiutGAdcsBJ{fGI zEn;?oGS2_fqW-CU+aRO!$5s1JyV$sB-XtGp9}g5hn-aC`f5pCCK6G>|87uk466wyn zk~!--@0U4&GJa(J#7T>2oCPbg5Bo7rDJRMW67REh+>yO4zLiNRH$9xh4qb0hN>G%; zW(Aia`ra{vEdEh%KF9l;PJHa&s8TH~!d~_#CHE@Y_!^MdI?p`Fy)x{9@Iz=0Y5wE- zu9|_ve?Z^WteyDXDEQYEY=wVsthOJsXVd$)ZHTacLJxO?Jk+++x=n_OA<;#OsBQiO zi{hOf<68B)gOVFwecl_LW?IEM(TWM$PcDoK`@a-$@dhgpV(LjL89np*@ShEktB=(Z zjh1)4o7r}Z%xJ%|0h(o;?H1V=yNjdcvJ_Qd^4!QnfadDpF>YPNa{B^pI|2?l>!I0? zL*{GvgDw{XM4;>mKi-?U1}>3C(L6GjOA2y@v@!M~fGw*EB?JKlvW`3weASSN3pm%n z8SD*kcij926_T6(02y@U15{;^F3*zu7~;vmOeg)$I1EG61MlzW+V|I1 z=AI%@kpT+Bx8P3_+?G2JbT^KWNp;Ui&n{~>!Aj0yp>U>RC9}@sM;zQa1G0lhm2Qrr zG#k1iXTjXAq5@6Ho|aJ!(knrjuSUzgIYbhkZitwfkXa^sGT`^!S%wEQXN+eq1r04E znnX3ElO;7pc~1^$B(AA(ZEtw9zlPi{(?06e`;z0R-AlT|aLW0S;gG(SyC=2ODuZyW z_ICdfU0{^g?y@mN!_aU4uGE9ra^*RtuiePN>6owj$9*N1^|Rzp^U`dSQ=G){ore2& zqnZSRw{ygXMEr6*#0};XR5lEl}e?bD_CJ(wCO@! zIWF&h&*@8~KSsI%!nQ?oWd_lJmn65K?62n0WY?x3bx7Ay)K!{LR0K0LF?mVwV8f*~ zpijbnu5>SIu>@xHI99KETynCqT!5)I+1hU60lO19*CN%?*ai7&nS(w5R+`TM>)hNT zK_z98qSi`$3ws|UmxZy4*!+pZ}oWhMfg(Pt=-SuhOU;Pt<0riDcmZ$kHRMO@r;uEJiQ=dOZ{js2~&Z^`jHj- zCzZj#>8Jz4kOPv%d+8HL1O#}*pZG#=Zt(^D0qdf||NCh_9P)Y_C9Ei#yliXkO zW_-_HY<(lvKr5du^GF6oOBNvAh&X@*9C1hx9+*}5KZV}2b?K13*NQJ@o;7HnAXf@a za>M4kC#sY5+Qp|%b}Ydsv5lEg1IFf_AYd8cN&bL=N#%7*FtnAR1=5FL8R7EfI(3J> z;2Uys!tA3|ZpfTt-7);2XAYnHINzY9pd^i_7(?MhU=od=mo)dV1jT*EOQIlJ`cuRE z4Ax<@=%wfV$de7vW-v^rsxEqGmn&H~Cu#g^jLs_a#h8xwX>#32a?6tOdgG3vvRAFP z(r4%$ZKP6u{t$+$ptYcljk1nPp30JKL|~(F4qi!1>)2WaWr{vN>%8yVTUL!t-nmc7BUKDb zr;Rp^z0`~=xqnN|rAPi^^|jPB@Yv{6&c5fDIMj)^E6 zLFW8u8|m4vv*UJlYvVN=mf?(^kE6-VzjW1;QJ*lr!ptt;y8EEsozsQy5ov#fJEf%q zM6u{%_cdhY*k4NsI-I1`6Y-XREc>QvWzUvZZuDIR{&3WH&+c{ylbw{OHGA5pX$5Tx zB$FiEUtgjNl~a4FXSb3x*=@CJw@aqcq{Z zoXuX>MA&$_pY7*0k}tMm5y3Y5=m6%5uNEcmra$?cTn!HIF%(9IRaLD+l(W*E$_=~z zRzts18m%$@%N-r*P>KRCLXC*$#nhgvvwr9T%fltDHTr(aGvX5-DUgFD!7CSsWiYp5 z3>GK#1jW+?(g~gyGJwzcbmWxbgw}v_l*C@Gi@PD+NJb}B{cC8p<0q+`P9x0+;|nYm zx(sZN9%EuQakDV)rxA++NfLdm&@QnMM)LJz319KTHH4qZHSiV9DT8r>zp+KINcyz% z@x&hK?T~Or(?A1vq_C0;ywx>*KPT|fNQUS+`$L`-u`q4i&F;JRKcMx%tGXjOCLfzQ z=DIAAe%#YgqHq87owxobew>UMm5Xxd#VH0?lrzWn=dwJvUY@PTem+VxJguaZ8SKIM zS|SP6o7T5~hH=50(39WE}u+mef4!>diBOM z;;XEYHSq4m+Rc+n5bBpLnqW?54k-LfCpIh*dyI_>EpdiaYLKi z!>J`k;2wGFlUT-#r&A}NSWrQFNDGO?liWb# z(HLWmk5RHCbs&p?S9{G1|7N+Q7Tl?g z)TQrZ73DR}_~Cm5#txzB2j`of=w(y=7Toy7&+ zrcne28}$#2t+>%TYUtWNF%6|e!KYD{Dxc}7EG8MjwC6C-bzbf^Lq;`p+c=vKWL8#M z=D3vlmoeVY+SB2)Wo<_QfFGLq%;sc$s#|*WV3&fO38{XsWVcVu6N!QV)>k2nZb0g# z8^_R;HLQQp(~h31dj z3{@lQb6BKL`|0PDKEW4r4TUwLmls;JMjY^YDh;AxbO zZQ&c!Vcwra$Tg?8iiLYaT51>6iXY4iN*6dOSow71#JT2IR*LQaRm9|Yi z@PO=IxZ|&#RHQb>BH#2sHaZzXp2@w)jGchrvT#svW8%%v98KUbvK~V1NXZ4?yLkAD;#!|O0Oz&`M1iE0zIPBJIIdlX- zFpC%LTsQsi)Q<@e&^LrWh&kp#Mq)S~mAyG$QMe!n8oAmFx;!8b0{zi7>)Jl`PA?a< zzwplTg)mbm#rV^1L;@`dT~C$yzeh{eY}_OjKZ;tKtIFQLS_}85*sQ;;EiT~_CkiQ`^zaP^uZLQcDD5L<=K+) zj1V_XT;Q}qADPdeP_@8)aomnPEYt(Ip|JT!jbjW|$@*znZ(`_URcn19_b*tDgZxTW zG{?)1!2*qAW>$;VcWJe-s6IR1LT@GSePvy-!M6cTqz8K?29?8^tMQNyiREJm{^lLu z2cr)6+)__P*Im!^;w&K-sxRs%9fVI-14K*M(|SMQ zWs;k0GJ~?Mu%Wec;^!hW!C@<=#+0;79{JjCublq=cG}ICvlt*x)F3=V7SxgwLGrQ( z7vmYP*H`r$mg7lHtuUh2j>`0}jP%B8FUuLaaIEc4Z%TXkc#*}SJ0(TmF=eJqP@(jm zuoV=khjXM;_Zi5OFS4_z#B7c$_KBpocY0~xbQW>uk)#?Y{*4C3xYFXZf;&U zc4z@OW=^$Ee|jv^SCnLR2noq|c` z0}>U%If6!La|Yci7wDUC1&6JJ>{T>tyJz7-Bf(i$llcVi7NF|KbC|iJ2J6KW{Qymi z(YsAY39J zbFD9e`fY2A&$EqJXHTzzZ+q&RO%wceAig}0+u~uLAg?Pm4%*&c6b7BJdlLFC5^_ji z)tslC5Fe=o_$nZ?vg@Nc+>oZEs{W_9kashLFt^IG;fbf?!@&&LLAX-XwI_x6X$$F! z;`&`8e#gp5sc6hwQ8Z)P(cQ(=X2j`IN2#OoJc;j$=E#2*{xJveMvVV5d&^{q`6q_y2}dpg0lt=B4cju>E+)DJwm#vUF21H zE~lM_q{f&M$jBz&O51rLD*%=JFy}ok z^xSILEN;p3T&~>HGh*CSH=h&twTw{A7 zKdPlF*cptik#=k-EV5k#e7N$b;ug@+$MN{dBcDZGvB=#{%h6q9(Y|RC2EK|o@B5&R zTvjZ;&do2~{>S(Y7dqL#jutA|8%(6dh|$>WK2yW1dn->kPle5MMafc`8+>bQdtx0G z^6(4KNDhe?Gw!%ch`d949a}?v4d|T?kF;6j)V%pd6@cxU$5L1ld_q*CZH{v|dWrO$ z`$jmbieUSpArtF}(TmVGS;cA)i%9PWeYy<5&lVGamsRpLz+snfoo#qSD;pUT4(a=< zecVQN;a?PPA4#nTaf0l{E8@$^s2w9mWeO1-P}${PW*t*UY5V27R6S&}|I{x;Gk)!? zLX_C?)J%R&s+A~|(*8!Ro{#pz%8M&qa7P=h{MOP&XEn;p26SkPk48hXp|Hs=`hqcju+lEr4Ez(ll(iV!l6em!MQ{1%$io1KD z6n7|4C|2Al8mv&2_F{gQ(l&V7xwmRh*L^lA4)nZ)& z(6l0i){R25rTL31r1G{7mr&2^i`4ZmXyIL$mDDSlKzp}n&`L+s{Xe`Zem z8^odsYbQ++Ca@EH>atrf?Tp;(LB1^?26$|vJrbimwtP0MORX!dW76`0Hfov)o){d@ zSJA=T4uf@X=Fxuc=#ySGtgI)W7nKnMym`&iVol#xKM6;7=VQ*JJLaS-c{?)%#$C_l z3k~38d;t`^pGAvx z^|4Y+^YgZzuby+L^o+XAi76`MImK6S7Wk9qkEW4d672ZR_7y!!f{4CwGqAL}#P!}N z-vjhoA7?j*J7J6DHL}F;E+=U&nZQuTpho1H21M0*tSFE0yKz?48LbloI=9}BhS3`P znjPSNoLWfu1&fSre=KGj*o3i;cU2m(MCBoP^ycdUd0E~sf=+i`B39ZIu=_x_yIW70 zYa*z+_Eu>YqlVhgdCOD274QqPKqvXBsnzK2fA;mQiUC`8AWl3u1#?wHsa`ebxHOY! zNq499sW78!p}w@OT^+1{tk)qcQ2_@opR?PcK{6fMbs^u!>b2!IQs9mf(aQTs7J8Z; z{aVmoY#Og zbbpcE*Oc#^I|&9kOpRRiIHer@QsUH~)ZW8_XCZ8}3@b4LGX(ebZTM#BO6Ow)=;%2F2;|y>0}> z-a#PKvjKd$1G8X?&|mIPq-HBg$B*dY05=>-_|O>d`(n}TY5| z!iJaxrSp9vHiA*()t60`q_7y@f%t;yaL^)9tS0F`06@lOq?440bqTp&t~#`HwDl+e zNSBsr9KC-!(?@~xQGmKu{uZJN1eH0^C3GaCW`_#SBP*MZ`e}hXCVC?N`j#BUp{)eg z+Ra$rD2RgOt!?wF1%kY~h92ThQzyM{nTmS|b9HqTtq>WvL;zM655gYKyuKGOzkXIe zY%r1)s42f7@%}^5ya6#&|6_B?C({YqS{c6QT}8GmR#R2{Cw8pm3UM&ep1|`8OhW6| z**+CgE)9}p!LcHYyW9mFcy8u=Lnp33Zg05bud8E03J^IGGA?ps}=C;)ezY@pCL!U$lN-@j}a~ z)Y?yVx{(inOle2=+OyxFfXi|>9t277!>)&rP@c+5rxm+pBSnu`{I-_bEid}+0q?K% z2encS9yz9Y!wYwg=t`_$<$0wxEs~luUP}G#zPZlml;e=(ua`7obM=CgHqS~ zs>3Bj%3QKypgZOOgnbv4P{;i?`_flMUVR`j%qWoYbwb>ShDPFxF&e{zVwOCyG`n?9j1>Y~w!w+gJLL1pb?J*W%D={!d5(`f| zy?|}dGyMMQ))o5Wkh=#Q&}E>`2%+xpmk#I#sUWEO%sXs&p23VBIH(RLg^fI8Ab#7* zfpNXr;4Na^ag?Vk>_;BXKg*>G;cXF5=+T8!bJl)UGT_+JsnUP)Bw>Se-TS=a=~G3v z5}!Um2DI+d)?yIt6+Vla7;W9g0N)}15F_SC{RW8vGK?dDWh39Za74KRX}LHp-$>nr z{qbvR_jr`n9icRap34>2Ow=SdgUFH*6p+v9tr0!gtv|QmtoUPXnv8_+eIu<`Je-9Z#if01zmo*N`i*c#7JDdj29^p^_A zr_8V7tDWbTL9aB8o=79x@&RZxj~FP-eC>-EWW!T&D#ZSuet)F3NcIQQ4Mf8fqKhr?$*vL|IwM zfvc=>OI}EAbgw;-h-=%4GqhrOtZ|30+kAWhvo5x*B0aRt#VZg7EBl5nPd;Qo-v{c; zJeCv@LjhEGf%ntJ^u8MVSr}2qIBt7S9+-3-@5Xnz-yb$9{K<*C{>)wlZiyAFwxG0Q zL~-Tb*;oT%9Wuv50Bh`n15Y3!)4$Y~}*42vP|JL>L5H!5aH;ip2KpZ^AZX!6D7 z5aO@3)l*uchUM4vX1X0IVM;?F`}G_vV8uJ5&$`sZ>7le{s-!KTC_Pe{yS1)O$5Dts^S%_sLj5{ zk@#SY@4HGL4;t(w`{E&n&k6#z>f^Ovwo-;^d-1sSMt|2Mz3nz$EI0@2-DttT@2$)ZL!(UyFjBA}7qn>9CwBBF29h2z@B5H@n=$@3OuMa5 z-(_fDN*4UQBCcnj(o~0Vi^=;MNXxCQ-^a;>7Pn?0W^dmz?>(7*LIG^eQ? z037$8p3^#uks7{4pwDc(-5f@_Qw;`{jZrKy<5AypYr!vG=UdTi)+(N#-X4|CmB~?_ zV56z2wy{G?J3*~zIr|Y6(WRTSW%7pA1=*TONr%xq%;jiX)*@QIWtH=FVzxDAB!)a{ zztB9X|5@+OuY*KU{JGe55GS3CyqH@&Id$ctN{&}?fPbSQYd>ed7R&5P!HG#mks#Yg{ zmts1bi$!%G8_^dn^WPEFVdIw zNR*H(!ss!DtJW8*OHtj1pRBbU56(){6@8&HV~4x~J_eSr@~j`!C(ALC2KbX%z|+@8 z`1CId?vgbU+7{VDqzR;k3ymPF~orYA=w&FYyCnv8fi9AghRNn?v#-p!$Er){wJE6y)ue3V& zZc3@2`KtFkB8gs|eB3GXGwxyLig2QclxLaI6Kj|oa4Tx2JK9@%7loL(J4YoUUVPj~ zd&X_*kLj48Ey{&R%&1(?Ey&U;Y84-QCf#bwAVH@pXku}8&?+u5GWJoo z`mvTk+j2Cwp1WXFyT_d3_}XU*oqaZXSM(!6*~e;`IpCp&*2h=j@NRP9MXKXte)*Oy&C5R;VJ^O!XIrA1F4D0?M!D>>BXO>}=-t$5UNvA}3Pc}DeG zfSqScd}Gn}c8$Q&WRn`MnTM3Qh?$p^Cgh5MH(uUz-w`3U68m%3ttxXY?*cR_M z1fHbP1Bt@9I@6lg+Im>5*LBJ8D*m31@{$MjuFSi!W>%^NWHiZsL>~5f#6%O9zdxRn zlGPLiki%IiWKZ% zR9;eM-ie8*3=<{Uy(XJ2TuKNuVr#R1IXNbdJHorvr7JC7wvTp;?rYrM4cx>& z*Yd)G@F$E5{|9YKw{J+E(mLRUme_iS(2ws{ji?<^Umv0n{S7M9A9qccma0FkDcRXy zN1bsI4Nti6Zr|VqWiRP0E$qg!DC;sMtam;T;4h;)-ugtM6nxd;e&PA07%~$=>q=$i z_e1)Z-;gx@2gKLzI(gWw3Y&Dtp|v}Z^;V(ao|f~T;#?IORPwP z0+CU9G}{`#`rX;E)pHrEx~?uIXFN@x?)(vj0|&mq&4j84S@uY|t5$^46TOc*uc&&c z(~Erlf({&S8E3cR%@Sy)nkuSi|8^FnXAU4+-Akye;+q3@PH%w+xe_clxG@P7eO31c zE1d)CPc_RtzZUN783rETt%VPckv@xY&7a5Up@^bKKCk)>a_TtYU0LPiN!Jld=lIm1 z$bjz(K;j_MOQYLutq(wa41{XHK0KMnpJeam@O!7g+IjQknvT;zDVXY7bjcqseEX0U z?1bAoa9j@RaTv701fbhfMJwg&uTB5h?RHx=h~?+K2Ks30a#5UjGLV_&%U+(VW~wTW zh2V_W^)~mUC8Vbq-SKoNKTlPQwVA#B6zShXq`lpklno;xR_6JxM|Umv{aVtCJrYUf zyqf-+dG1l@^OKyDg_rbj0nC)FE3>r@YO1NA^RDI$AKId*#`jA4Q^j)dHyO6ytckry zVuX1MtyDwHOw0*nyq*c0-fB4`zIJ)h6%<&^+I=l-^K^puacWcYtD_guz;%jXxSFPDFkjbAp5uW*PHlj>O2X*K~H5M zi;$ZKWdQ);^Mi%}cHs+{*xgx=wmkN*S3uy0+LhLZ=GE5)!(AMGvn3z8n?!PyKl~xT z%m>ULfFJPIZ&0-|x5R2lh|i-HT>7oxi=mU<2N)?IH_b4`BklTVh)&0agoxuJI5)xs zXyMJMamX%G2!&kg)%rL>lb5+lA70M0`TeWTmpL9k9kF6jBZYvB$)LM$-oHVRWXR=R zYj??*^8IlGeZ_C)89HJDXzOO^r@VL;6;jpXrE?cv6YQx|Pu&`;7&6~2V&!|S&H4*p zvu?WL#0jB~1SsCV>_H-+{k5gtENi_zWJTL#ffw>I*FerEkxOQgCXBF%<{Qz7reYC5 zkIADB?y*>k(!+UZ(!rWdRTsgkBquvJTH@d?zzs{Po|>lK-aVQNdPcrln1xq-x#}Lp zi#;opNnk{1R~%UgL5$!!KUHGw9Ar5WuHs`k;WUGUZKnLoV$&DxmS?A*#dSgEZZk>f z{h7u*^i1$l#Sn7Km%nt+iuLY5vh_??>-%3jcK(%?`Tw--|03w%UVY~`^I+ekXYV%% zUY=UCtLx$w)Y2nl;3;*Mg-3ii^=MDl)^1fNE9IdqMP#trgzD^ESzg+!QJyGDh9|;3 z^V8_)^sQ5MdL6KDp_s3zn<`TwE7UD#F{s;oOan6dB1pOwv|Yq^2Yh!4cviv}Q!iE&~mQmWcj}P9UA0Bpdc|F_*p=b4EQI%-@#o>0F`PjSJ zxXgEs{pFzr%xGCPVVvQJmD(yP)HflhL%gw-=(=TRZR+r-u_S*U4LscY$GOY-=kTCk zEWbeJX6RY8X{vuYEL2x8lE87=>n~pnnlGPnW8T(YEt1aH?J6EFV)1Os;EmcaiGSkx zPz2NSl6T}EzsSG&VUwD__Y{`jd8nL~vhs;>C{`O(RjMUQ?qqr`{%LdTzvjmR?PH&U z?!^M~k076!72tw+`g385p5~+?7sc`$^zUBGyv7CJtp5h}=NmmDpFd}2C6O2OODd3W zo?vHx=P48H(CV^$Y&GvkH8zNRmE4H;%@~e`YDKP#6gKNMN@ zSZkF%y56s`6yfT?xJb2Th^OQGl{>%9ASLGX=OQlC?)=)+{0XN z(iQSp+}g8ffk%NdmJ(;hNl1+s*I8W@Cw%MRH0(F1W+UPkZs2zpqdY3HO6p2aUweDJ zg4{*Dm!%u_WBiDlGTvQF=wXh&RF&y-2MX$x&6?LdHm`@GR|)`Rj4sgr*_$ z_Y9{umh7}RsKkWGmu2CT7B1+DQ_$_FMbOOd6xO6N93|RDz=bZ*nR6c^c=mi%gb(E< z3)DbFX-pvH^Vt$y6spiR_(Xy0?%MJK-0T^0aRxpEY6EdHO}K=N_d*PNrhlT7UXrEO8p?^|0)IEblKd z=96W&^P<`>83tB6Yf`T49Sps~4@+?DsV3;&e4yxgDRZPhlxAPq=tX57N-SjbX!lgW zw{ljd#}Ww9hpbm`1zvRAH3U$8ydK^&dgD=NG5pbWUhdOZGRF`~gwcx*RH@eJJBPD$ zDlN5-xp}{=_HN^5RGO+z(tL2uOuF##1FtA^`;=6xIq4w3yGIgJg-}^@MaePq9vr@l%B!Dv zDKqgQB@~3;pGvG_cJgiF0}G+(LI*$K_VXF7NYboE?R9VUE;qA`TlOKS@?!NXjys8r z;gWLPXM$Entov@lu35Np%yi-`@}dWdZ;!Lg^Xd@DYqynf>2V)`QKYCk+&| zxuQDOhZPWAAX^Pqx#v8bB~EcJ!EOvwm&VU>Mj|QU z4arEH&60)?iqLgUf%aIBGNl6x5%5V#>nt_US0M`zKp%kshuS%M@f(Cmor?L7|KYjD zOhmSrZw=C3HoL!=4!ndVE{u-@#)SM=aXDA)`VBu?qP;(*;xn)S)`nZcsc+F&@q>kh zatyR}uQaWL>Ql@hHubU}V>#mzSIeR8K(Cu^`D$S8dhr{yYH=^Kt2N9^tMe&!D^HRu-~^ULD{*fv@D|&j=_nu^GDlC1%4K z2Uo`+L;0329^2ocS;I?uq2}Q0$M&uJ&z5fPX;u7F_4eOpYX1OK|21&>yF&E;9IRWp`2HAy4MN2P-pj%yDrDvygE z{mFaIk$#kC#ZSs(J*?>QscVaw@gnP{Y0gWk3_Q$~@O$!Jz!4m3{f#0AMDw7gs**p^1NelZ?6|Qqwq&B(Nm0zG#p> z{Cb6z=Um7$sJ~{?wR&3%%l9zRoh(I-=g-!}9x~U9E=n4Ab6}tG?i=Ak)|HHI4grxt zOl5ZiHs>Xph@vwR5ew4W3`(ytN66-reX3s6f}S z4Y|>W995i_L#>V~i}OnzQ)2>!B|hXV%^T?S#&+3k41Z0-@iJ=;B4qMs-m3t@wBCdY zC_J*YzvcBO)V?qC_IJE9KXW3Z(D*V-U}*t5@{|t%OUuJ9DjhsB8Nd_ckV_=FZFVpt zY?X0qf?8(PBZFhR;aTbq9fCN(F@~?Ru@8g@>V`Zwl(k>gdsG-`SUoo!llh=Q`zF$* z2wHa*bB(mWJ+tm83M~1xADyWBN>J!G=<)6&DA%+VJYF~C#jChp zCI~8Stb#{)D~f!xl>!ep8Lq7fR=A1NMvCg8)Prm zZ0)$lstFt4=3ZQ!vnCjDW#*Phd0=viSgd*hueB%}BRzi<6s2XM@*MCh!c1Iy%Pt3N z4tq&(S1j_W#^%*+_%HIsSjfg7C!zp2=6>oik)iIRgYQ>hg?haL?CJ#a=vQFmu`uKm^V+^NA^J>(yTLu_jT8Ps7;t11+B_U+X)@S4yKX_82{?>3&&X_O=1 z6I(xv#DTb?;6! zY$|-zKzD*2rDoOri~nelE@VxFSz?m-obGf+y}Uche`{X#CePXj66-CKj8|DSJ+DMm zdxoe;?F@246A+%t`;-i$emZrSdeG;Fsh^g-GXbaJ3*`wbr~SO}ol5}tVv%W6K?PAY zO>Z$TG{be7J>3Gk`~&@Z}r&snTM2fi zZb)OqCo9VBBePP>h9Av4cX_s6Yy!ar1h4_|i(>!V-$3Rc_`7KG0QhBMoO4GDlGPEx znRHo8fHuJdPv3VX~dR>7wnCKaCr1uI$EZ7aZN1X?Qa()KLx{yP5t zbp0K3I^2#PfpOK;qURF(OhK>xg(_ARA~lL%MX|j7A&qqKLQ1H2y`peK8F{aTv(8+e0uZR+bxD8um_e%`>fmQBYi zYSOLMS|`4~Z64R8ueB(c_A{I9nOGAk$-9Crv*THa;=`tD4&tbQ2y*gl2|6v_dUn6U@DH)){~SU5|3nW4 zWl;E&Kfyx@03OKy4jz~h)+kv!U{3!Vc&PXf;Gs}o-jX8Rk z5k<*uevJK!BzdZWesr`(WE_wue zb@=7l@3V>!XN&DZFcwu2lRwi?dZAL@F2~|*;?vi2$qv266Q9xG(Dp%ik2nzO`0d0a zW#RcjtFE=PyXvc=-3@Yb`h}QTGy)ZxSKcK%Q+`B`7na0vKDxi8b-=@8?%%=2D*RRw zum`IYEhyC2-&s50;Q2xz^)v8iu^M{5zSt$;Y_I7c?t}$8H8hTwC0GS~?y?)e{qa(k zj+;%Qg7(Ia*HeaF`s1@g+7~fI*0TyI+^Mxd)!KOJs?SWN{s~<^Iruk~hJjq{)8+Nx zT`;WH;UPz}R%?J}-YI{vk3i;YazWW3n7W7l@FYQ}$11eoV`MG=h-R zl>?28xN_!r1b3)<{3@|@NFZ%%dxx(u1rObr5O!WYkT4vp@$SHwm`l_Yxs?K~M{}Q* zdn?rG4eE}~Dtt;cjjG(%MmI9h(P_)qkud*2-f^D^Fq{IR-;7}Wir3TEg(bV+kCnli zk8`kMG#ZF(;f|i1N9riIaFHI_eS%{-$b4F+x zH^0qhK^9K0k3@;K{;wp#psuRm?iaqb=BTIa1ke$uTNI#r@k?L+;cbv==~D7k&~C^* z0J$fPA~KJ}G61A;OOsjBywIY>-GtKFs0o;A@c}-w-7_yOmE)$js3}DDY!A7tkY4Xd zh>g!0l?Wnr>--10>hZyQ^8`X`Gj}zWVZ46_T z(Uq6->>qmdbj9ErS}fv4`zm6unYfd8z6pqtS{R=r+N$(G?>q&nKr9J7onQ1(aAzN? zjhr|KYSdPc0+#5ntZmD!`P`4Y=O*djy{;2H#&FZB)}HoxJ7VuTz{ut@efCv?E5hwF z-wh|azrcF9O8Cbr%G~wCp;sO4f}4d^wLyV$&ttpjXvJ$oRQifjTOta#wLXq()q3m9 z+z$X#7HvxjX*szLKN!f_J#Nd9VWX?@IGERYT4m5d865(e!jIO7SHdqT(jVU0unO$@~Rzr{d*mJj}qMB0BODE@1q z_8-Eqzj~O)Y;+HK&ORvT@>M)sHK9@1%Lp&?$I5f#gCO?UZ$qxN9wQkWw9>79Z|xy`0JU=V-XDSNLJw;iH0mFAHW@G94JX4m&W8 z;$r=RYw{CWm*XwJ&^i{m8GC?m62ypG{`Gxg{y7$4L9Ri*7-CtJS5w#LPMY}Q%f~jQ z1$ycnEJW#nbSLb|?#YfIUIJZ-_dVu$u)zCp+$9%o7=rR?z^uO@^q<4z9Jv4e05eB~ z-!x7nC&7r-EN_AWi}hy}BnaoZN=Y61#rSE)zOH5x&Ri)eh9BNAnh^|adpb1pI{kBeha`B zpvTIyz$cs@UcQZaqJ3Cj_wfN8XI$k;%KRsA2@&tU0NxS@qw1%B;JlCBA2W_`!yYidzx(Y4#2XRtJU731+ zt|SI*i<7?ae|6w0Ut%3(FR4XeKaDA9UNX%iId2tv~r`ylchH zD&*|B5wC{{N`{>a&mr|*C{^yU9MtlzJ zrx#ssSANiq;Xl^v&!DaS;fh~J$fgsf%0H-@dSFun#Z|mO=ohz%8h`$vw@G9!JDEMv ztdbY%vZu!yeSLzpc#W@n?fiYUfV4gqS_e(nr@|U5)`#{?w4RT)rt5)Sd>Q>~RDlj| zvhuQGzxF~{eSXF?a>^<;*up!}qDlha0={l)0qV~Rx@>u_PhNO(0%Ch+uQ~Am6U;s5 zRtG##*&y{!4e91v5t@5uI4I+zbsY6mw5}*FK=L{Ov{V}e&$xF6TGZTa!>r&TDdX(Ssj8sWD{Vjqu5S<`GT^Q zJ~nRDi~E*rC&ly6(`4*3oA3|wR;-LJSFdH_LEE{%EzT@N$q5fSJ5XY@^@7~X@WZ)x z+?EJ=c3cOksSM$_EP?in%tNOiv4Jd_)YdYp0x#3u6|*9H;Vy|dWv#9W?^fOPn0dH5 zmU&iK$TQ2(X!l@c2~W?WxRDB;vcYMVu(3u9xUlQ^t=?gPcrYmdn_7m*l>@8B_A=ot~zkr!{YtJEbtXLI$E53jo$=+*Qb$3<+Hw_bt)Z z=2}2TxOI|2+(eHELCH6Uf#xgx=k?8e=CqfLW+gVKkfbQK>& z1miV*$?_Syv)0zt%$Tp6k7bS)OZT$CLB!9h3cFJuJ^e}M=a-1vRhtOA`2Ky;hWGI- z(TrQQu^VLt)(d~;S0TBQj(I>;%O^YDlD%{;p*}KRtk?4Q^d4e@h}@M&eE9M`D6RQ2 zp45jUt<06YNhX%opP38H!Q;BbovmLkMYu4mG=7|HT><-F!=8q!`xIP7=_6=y@!P>K zH^McIp7L`^KXbAF>_kz2nT5UY!)QPWFDf^GgGwo{eJ#+3&gETdrr2$>hm&zTTzx*;pQ`Ezw_{YL2#p$K>u75)YRvyDDX?YttICN4Y9G%CC?w!fp0=39l?Xp7)n zekP9YRI=mCeg@6>1-Q+ZHGUCX4kn~71ffHJ=l#-w?+x~Yclb0FO5Ke{WFFCTUF55~ z#1@F24JKQ^tne-RdE@6&N{*3;vs^BI#hKJsCw<)qqmh1?1;tZ^+lp#daq*myV5R=j z5iHAP2*tJ`I9R(@K0oZ3UwZ(`wBNd7>j6Q11Qz6FA+4c!Xb%A7kAQZIHCNwO0fM0A zC9G+5!}7iSdkXI7Mqgwg5m3FA+e4^u~Z@M}v~C{CYZ5 z`?Gy|TxC_F7u12mH~{F4(b?9m%fU~7pKmbVlV%@I`~kUJJDE3_*!J;cQO`4(ELxqZ zpsO^fS`N%o;no5!x%mz(|=&}SPg)ety-|3hu$~Z|A_WFfEKasQ; zA35j-eBl68C1Bp7+5vO0te0MQo>==p!NLpN%ezk$fZ$y2{BPISUm>vnmu-xej23?h z7IS%Og8vq`{3B5L56>@vg+E3IIuGfu7awbC`bT$>PgINnzpi%M5BH?2o5l}j4{g~{ zj{xE5w@ufms$LO9JXT>Tn9xUT)D?`QzvCrP-#p>UKbZKV2AwE8X}6T27*KKCAds)U%S0;q;Qj2xHYYIa1gONcXnT-Z5*k!{&N09bmeS@lsEn0 zGo~^ormC0#Zmf(5w&(;}%5q6EfCb8T$xGk9FX?>|RntcpTo>SOBd~oNM(?ofQuJj8 zaEM6-JX5fyYf2=Hi&(;&^1qm=ee`U%HM$}zv?)Kd_fabHXyBRa<+(Lrn4O~?wN2d* zIem10m(UhuUc~bognxxDoh$)sKv2inx)(2?J9@Hwi|~vm*zo!d!gB+Px$J+El-}T^ zzU|D`ODA@#bjNS1h@Sigp($Qfw43N!bxW_jp5SKN;)Q8>OHtSZ4sE`{7ff$d z+|iJ4)7GYyF{)|Z`g0Bk=PpM^=uk?nUwrWw`$P-!+lkT@wAmBURCa;SgXSZ3l!7w zUH-Rh`(RY}hCPcPoGgax`LmM1UK}n6IcTS+bxS5L_g(0yGJ$rGGMAECkJkoC&lKWW z@NdwYsj_p*cQdRBGV)%`F`omcrw+qJ^PKafU)9=D<;@3uX``?^naE6(MIDn4@ehJ5 z(1XFcd&vglA7jpfc6Rhb|G=}2dKPXm3)17aAN`r2_LfVhC#{L#xmkB4vSLF^bPykj z0DJ=peN(~LYhb_%7DzWqr1LJJS$WxgUb1M);Hd0wCKe!Cxgqgymj6&pX6MrL=49HA zMKI2A3!y>0v=Uv(TK`0*5=R)yjQ_=jCiS|fLpNw|?~Ta806yaoxw}Y9P2TZ$=@O-t zy}boyi5lz|-WGW}GuKbzXUMwb^RA4KWDpopzv88N7=D>rv{8tvVmj+^TBk}*MVQzY zi{>WGmN0r-a<IpOQPJ$o5O28SUhl$@Y50UV1dwdSN!}MG$%wtqF00WMOAWPXFLmnPx+&{<9ouGTofOB*t`yG01%XAR(9e?UyW3mbvF}XDF)W1Z!DHuE?u+3)0kpaY zl2e&!oWOMcQOnw$P9hUmCEw1p3JPy<`i2zkIDc6 z7SR^bcB*LE3P9S0q#DMQS;J>V4l_M@b}#C>UrQ|G0X8QTe&A!X)|FN&54$y;@x?_l zUWQR4hxcjJ{AJ*M`iGpmw5$c6=+U*F&AXfWLNN~mZhY8)8 z&RMD%O<1}qCA&m);;Qwf);9Bmi{9`(4@F$vEky*~w?h2|%dy!WoH}alfoMEuLw$Z_ z5e$$Z-^qq7)=N?jB%XEY1kxbenmn&Nr_e)DfUR85r@Zk~IN5hhu^uYsxNLtR>lpBi z!A^*L!|^*(9^0-kg7=$pVzb5cE#=ZlOKgBSqo}7dV8Uq zmp#*y^mfk6TMJzhFiC_&2*3Q+=W;C4?ojXUNlZvga_ z6O75UW*VTrQ=@T8i$vD;sE9pX(!YZ#H#9QW40HFZyUlm5ofrOnt!Ld4bZKmSm<77_T%>95;iN3bTyinm&&>t~`Xb?sBZF-H~2f zTit+^#n;f6=8YTIQ&CE0l$cukD3h33k* zqdnur#~yiZ(p(q;Sm2U!J-W7c3KrTdUwBoZEWeI`ZsK-EMq1 z2w&o?qOnHN1s4K2-2(BVHAsxF{}IRtrPbi1#N=}MGy7x-7(L9tE`uqMby zQEd~Dt#}|bFpk-$l0bO^bRq+~P>b_$*?;!V|75%0ChFABC0$T6<^m76nuGz;j1c;6 z7kt_WJp$Th-hRCuydHDi8?*q7@BhA4`d@pZr9D6g#foru{U@V){IPQXSwJx`d*!uL zU{n(n&Ee!QL)RD}24qN7(Ic;5zd^LsxYY^`4?Agv!e3hb$bEdFp@SvC~y|A3z|m03x4eC!aeT<`wDS|&*nX0>Ub&l@XQ3hk$c|n%(eFrq25NR8i54n~%jTro=db;;gV{eu{*r#1*P3TR zE_;@nAl)#5oFb55$`a#$HtN6)(zwmS&nk~-chedydelTZ`inu{GsGX82IgbdFuAU! zvRtNmL8Z5^IZP_M`T@%6{8QEAa!+FV(OTAxsxpulQc>o7kTvF>?N1OpnhH4F=J0$5 z&9ts{U!s};>^_3)@xpiV=HX?-zuiRs=Ozbm+jZKc--};X28rqfzr;Z9bUz5d0U3g+ zgt3+v#Z(d)-nBT~yF%ory&pJb;-%&cNVzg!<4JnwUK$czy!&3nnOPpt6&piF z#4nP@{p9g$741HUTebU=U_Elz?hDZ5+$2TNnlBvY)KuEeO ze@F=@KczBOsEXn6>JRYBV$r`?UzuRz9B&!nANS9LzxnYlZ zd0ZCK5m9D!G5JYy6y>Q0+DaHU{K0_UQ7OG*h*)E`4^G7jqJOK@;dbNJ#KXFwtv9^+ z_L0ek**k~UD3ylM<_E`1?Tr*yIUOg~v%v*+bn(j58q1V8u~>$m(bjce#kp5lYc?9D zgI|z~j zDlI7?C7^^LH6YRr!XT*v(k&fBNQi`VGe}4dNK1E1m$ZP?kV6hIjQ8j_e(}C*-S@ut zuDkA9_m5d~7*2l9IiJ1vv!DHJGZJq)#!r^m?c5ga81hM7regr++AX@9 za291TiGFCx`ySuiQd6#57kl4da?fj}-XWw}WNcUH>dF4f^{bPSRJy18tg)a@^gMRA zEJ#k0#79A=b$kNrn^B%irr<$zm^i(sjl+t}oj#{qu>y2$-B@in7wb*M7_$AhzQXE2 zi4gGV0t!x zumfXcio%(W_x&=PGUI8G0Kw|v(mK1~0DxbgTy{gv@2k5~(<2s(t=#e_foFWWG z&H>;10el~zXkhpsd70)U6o5jpmi@zCf`8ddp`RdI*!i=8 zWmAI;HU|%HjI`*+l{Y&kf+D~G13Vue)PSvw0itEjb)Nw-!e>BIh>%l2S&9Gx!#r)0 z!8EfJ33&qhQ3gaR%fdFX(@pBRp>423K?A_KeGERv)+0KTb@wB!80o5p&n`Zk?E4@{ z^Zf?HlA4R^4vx%TbXN8U#(3ZBGzHXJT6c&+IO8tLzf2vFF|}<$uKkXzfLQUb&}#m# z-+o0~xBiH>82^a2wv4G!CCzjPyQT3yoViO^>9$mGvkDHdGxSY12ZGss~VXBW>F90?jL%jy8szD3X5OnW z|7>ME`yi4gjrO3IHr*-H5<4Hs*yVZB;QjDrmenlJU`GFZm+Nau$AOVIbP#E~OBw4A z6@z>s$8~& z`6?>_LmORaIqO$ToccCUxz(Nd;?3iW>9kQPh6+iEg*ku#wyb)md+kG!;Zu?y!+t?v zrK4if+XyfBa26zv@bzl)^dWOU_wsF+hA%g7tiNP(6Dsh+y-Xqe%EfcDvcC6Y1XU^@YaY?X#Vpp9KS5Dbj1iJN*2Y{T+VVlFm7_aP zGi_sLHqIg*(|kA0w86&QqHQ_90P<|jk&Fjn3qXQ=vi9oOS|V5M<4lHM9CE+Q%lz%5 z@h)?}kx!kOK;DU z$Rv9!xJ$pb^MI@@g`wFUgy8uzd$xHAd6d(fb*8VJ-7-5QinHTR!;o~}j^0FaBFCK{ zb~!>1!WN;!gJoC8fcyMb?g--tWE*qjt3uyUni=0mN({e8OW%WgJ6vxp4G$4>3dWM- zrUd-qKl5l z(;k(wHqq3GBc8RQk|gH`H&85@Cjf^K9}PRYvig;I|2=leNi2^lHees7#YIW;+@}5L zQg+RrHC4^afk**%KvHz%05fIX51F=x#nPOaFTyfl6E;Z1}bP zl>rpEsa7PL_lFC?%Z?s+m=JF;+8fOQhy=EMXS|@Y08J?1pwSh+s)}|;M(wm8%rxZ7nEfT&>QIHt9JaG7JaWoe zRL;4S6_w!ewX&F#w9!JF>9e*Quhy5>@E0KLB0{IR&SAUE&(5VH9r37FnxCK|ieR^0 zm+u6d)JR^7zyjD0UEWqAbFbDY6NcYhrGtM+H~$2E4uWnH7`GTpUkU?AMi8JN^^y{> zIJcYp8u0(=^W4q)74QF__>l1ZiV~atlPIwmD7l9nDxLhv zd=NmHU}Q{A0W+AO(o88-HwwH6p)EhiN}2a7KtKGl zo6R$VQ@L8^nCK0Tb9O&Np~ty6$FH+4Z5bEA35<3@mrHpdbqMgNbx}cof=nJxsn5N@ zoNZ|g7tZ@;8Ytv4zD@|@-$lr)S$@9Bw*YW+aiP7V4ggaTfK7nn+3hpgH)c0hu$Q@9%ygf16>)GxtV?3~Kx3 z88XCprOz>jkYS=xzrdz>(gQyWA(OD=H$aakcN+SZw~=EgC7BoWrE;})YxvVHl;6I! z?i-Z_!ywT2ysoJAsO?Jz!~3K7LyPku?x9AplFidahQ@KB(1{mTysLHLzF_+`j$G5s z46pD_aWMe?CGv35i+iRVeG?%}Y(Mqgm|R46dq{D`|89L;C-|VWnnIxzT8{1u67lzh zZj<==Sd=xr^Z|w=W_BM_2YhF1m8ttK6U17!REulW95y`kCqKlzQhT&Pf5lDKm0Dd> zyJAy(NuI#-1Hb%Tc?)5Hvr~^Xs3-RqV+#%=M)?YD@uhmBc9=d_3kxVAE74g2{&=iM zy1*;o13daNUeNC~0G+p>w3Ly+3UYduuZR?cxXkJ+y1lgFWLbO{u^dgaUZ({5cCeU6 ze{$64+>ljkw9~RA5$sxa*X=wEJBuE~5LoVW54@t|;eEadM$Vo>L%n!2T$g+5>MKJ$ zGhb_s@$TVC8%s*&XsvC&(b6|Ox)H4jsHl1qHRSQw*$MWO5IkiiJY!j2pvUNr^El2k zE)X6`uylDv1$f_!dG+d&)|lcO@`t|xj>VR-bHb@m`7qSf+T>^%zz+R@#6CEMlBZOq3Al;C2DC^UPKQ`y5p;i@!G=E9;r9^D1QcF=hcovj- zvXv>90Vpy<&jC+8@@^;)-@w4=Flcv_O>h(xLrL6oML6A(kJ2jZ2W@ia4W8^hzl*Qd zwv~D+O_D6Cw~Cn+MvdE3wi+nu4&$)AI1deqhD+L9kG^r3?x-0+?@^|TvcRqhdLz|y zq3#mBOrbTW*0=Ix^<=ZUm3VRQ_Kl({IZ>fXEvt;8b{qr0q!ZXsU z8Neq3q$@ixf*~t?@x{;W@e24pSZ>fq<6mEW0paqsNk^(>-0}2^tjD?is4qbdWZ#1< zGeyOms_$GfR_L=5uh%@6qM@c(YrYG-oc0bE2-sB94PyD>fzgy_`i3h-3e@sWw6$1< zWXHHU*-bgg7l(Y*o402=w@PLxEGMFu3U*B%pcYSw<$LtI*3ydw$&AEU-;aiPg}2SN zEHEZebcMEa-F8+x6UtCCw_#NE8)E!TR|ixAaLP=|n63af;1A37{;g!4jG{5%M;XfhDu6Q~f}t}1sTO?8N zM_-I(os1-Kq30bf9t-2Dp3pY*2Ka{-^x`7!oQG44NgQ$3t{)uv zBXO+6b~OEVSzCd2hx;&d*3;`zkFAd-d|gTnujCIY9;}LcCB+9JH_Fb}oJ?Icu?8=5Y{JuXz zzLQ4}nZWqW1n5>vwxHSkoQ6>N#E#{wTI(*p8RF%d0zLIkZZ2Murr=RU~Uw<-&=x@9vArl&lSWf zSxfVmmc<_gcKX^5U;h2)fFB>HHva0Uv{W!eA!iFemD(HLdg4jG>SMr16#T+m4Z3Tb__?C)*HKLn!VE+SLH2k zGA})bX~?nWtc_`=0jiJAG~XM>onj6j{!`m#>qlnKutiMtkys;;g6Fe(Tg~jvwWBAT z`*5>^#&LyVN3(0X5tIz+3=72rJqtirm~9_+Kwva&_yVPVh1=AzJYdwbtie09%No<7uKTo}_+jLlMYs&W>m*RH6l918#cQ7AW`QOkjK5gYk?10&C?DTU zqnYmRA<1~G{!K^LGci^gjfih2%uUz|;ozO#qdN@hItP5i!0DV@kNaXI>$WwbH5Wg{L6%-((PF`j@ph7aM7kV*AaS^lG9=3UTow@BXW>-9<;y9yR$NPLm-kwiA-8mjRCLy4hC-!iL;=T;xi zD+R-Q?o(*WIe+c($8#}S>I9=s%YlHbTO%WVu*^8qU4`65vuE-!3j%^q{I zPxr~3hba%}*9WyA{auU9{JR!;`oq6Y*Z)VH`)hw;jsGG3kWp6n&xu_Bt7$%9eeCzB zhF`Fn!Cz^p!{!vWp`tCq(mC6{ZKdlw3w{|J>_^cex1oSiY(1yTA#bU%@b!LVSGhFJ(^4%8yklXSXjR#YpJBAVj10a^~xwZPY6b5sl5fM z8Cg&`R3u|wp==X5DPsz!dGr%h?9l%OwyS*f6T}w>Joc|^kE4lE)5handy(b^#s-ue zY?0mkqEV`r6{xZ*`D)+DGA{M=b%1%zp1_Via=2Wt^L@S4>BrDS={3?=@r8pH48$mmjHhT z@OXf$`1cJg4}tJH)9xH{!}YH*`cKzC|MLKI*|`SYOJ<{r&5>s#Nf#^&&dT^$<;Ie&t5oBGa5 z`Qv}-z3r(#&MlpNv#KUu&Tm)iMjl_4kQEqSp5I!lp8;=7nGxKgeQ^}n%D7?VdessF zuTHz91rs2q1BWc$WpdBZ?xmaUYDcX2i-dEJ`6y!B5E94P4hrb$MIG1SUK6-7qCzVhHbe9 zo9DR^-89EkYWOi3qLZyA2dfE(La%f*>m?}0EeTued%Nb0E8(J z^(-9qQ&{GBmvSoCJa>(8!KfvcqNH}4R3&1HjnsF*7flw+B&P30h%n<`sST#f3y-=NOey=g zNt;+AVr?{ap7~^v=J8NnD?9bg+OlK3I#TuJZR_Q;Ai6cqski5K2&+8)g`W2tT2JYO zze)kg_h}bERa*Rh%XTsJu3_doQ-{KBeY=DmA}0rlV=Gn_emXmQ(zU;4dOJ(ZjghK> z_1L*5u+A7F&pmL>dW!M1SN9O;9f_PCl){s;p=`+`PV3U`)5{|_{PvEUkw708LJ{iH z2HDZ-U6zj2z5Gx5h$;Qx>K#spAM(s=)Xn=z)Gu30A)Toqg@uSE%W1pdrj0~^F10A_ z2o5X71%eD?WWQNB&}~?XQ3dnw?)hK1(jVUW@47#r4)uTUn}>}D@WK9}Dfahr2;fot zx7_`It1tVt4?L=0?zb)w!2Nc=e@sN?CB3?)c)Dexhc*VhcAdYycA)(^ezfT-?i*e6 zku@%bK9l4($618N*BaDGJjMoe8e_D$eLG`=&$;BK2facgBspem{75GS8PjLQ$AIM$E}BMB5er?&I_LFnzi zVVr<%sq1XyB-#G#;X}_Mj)vjRV69E)9TF?-u`Wbv zQLi+Nh!>0s$o z@D_V+8XQOCiN(U6)tb*(Z&QGzgtG_Z1)mV#qn@(ay=(ma!MT~a8z^Qw9JJCXlVyyu zFoY>jw7*+!Vtp=HPB*4md1Of3`>>gYpYivJ0^n1Hr(7yJZ`GhXfk!j_u500hl{+0%bX9iIT) z8T?WpyjN-2Z^2YE9)w$ij|VW90FwRZY8?ru4>{mvC|M!K3v<9Y0#u?dd{XLkHIw!HIl)Btu6hLHRWSTE?6wT*}FIsOt){l+J=f8QDH72#n!qo}MR^DrNo zJ<-W=38HEo@`M+_@(&rtfwd8QS2rNpo0{8)9z9*KgQz}d*p`+j=IKX%VTQ(t>D1@* zzOk6a4g39jI&luAVMC6A3x(FH_g`vt!@5M$oK*< zHt|@9rEA?jPodiY@-V^;^q&(+SN9uxC`_fLpbpbA((aWP1WKvBtx z7(^bgDTQzOt2Fpm2mn0I@gU7V){$icIYDoJGU4qfT^V?M;m93aH-VdALw_W92ygmo zuk~2PR$hYInN-3C+D!$sL9!x9v~E0Y2{oCjw53w@ebVN-&@!`*xhwe-R4*?wT;l|@ zo&Fez;o>hm2p3l-4KrhZf;=t%sOF`QIJ>9NclheGex9gqXdwae*Gl76O|cZU6K{HTR8uhYa~`qcrV`tvE9QY#Ufpq~ zbTvo5FohZ!o^ssB_$H0`+nIG`9%~}Yvi~Lb_(QtZw8RScnXZ9CaskVmx9-Q}ScUiC zreq1;@x2JFLE%fAUr<^CI?^dSF_}L4bP9lT!OG`%z%^BX4|HMDJ53L;D8Y03Q1lhw z4@=A}@KA1SL0Jr4$+5ou1la-a&(U#9OwJ$s$piK?0kpNass_NM;W3O{^e!BX@k=@s z0yvTXAMJgH*g~BZ>rMKV^-6v3$Cx0_P3a+<0Jy~Mt6c}J+b-nrsv>^>)c)+{$2|5zYp3Z@~k=G3N&G32|yUhRWwr70O>ou4#h3@{%k|lMr{I zfgK3^ExsSHcT)%Yg?8O2^t_botIf~2k+)e9%-og%J z;7ti&CiRQ`((-PJ@V@x<JcrQcn12wX{@oa4SjE- zK1@{e$#HgLj^nRragba~1MB2d+ouc@{pyP6vDmy&kE`pVIjW+oI+J!KJIDyadz#l)l3@nr&{3aqP>mjhCq9k7R47aAZ}Sw{ zvr27-eTS3kz|Bs_G6=sX8!XfL?X$2{gdu@FC*`0(wk%`kp~h2MBh@ zpuj|~zDyNTP4A#GQCd~JR+%`35F#CN);R9+mW#OoC|fPkz?wPt&sz$H`4-&Kq<+5{*UM6<2vY4!g)=Z9CogU6^9ke+;%v6{rzPm3qAQ%$P z35pL%1PskDp$VW`*8g_Smt=!EMS(YwL>L(%wpXZ{jh#iBI;Q2^PE#bnp7st{=kFa? zIea`IM#;Xd{ajDa+I@;rzvFF1<^^kV;#|xy&2C%(%&UZ3yW@0Z0TrZFTOY|9qKxV& z3F4BQMsSa`LusfdP)cW+cSi*CnxUvCKp_p8{sNK0eKSbxBj9nSy(|9ZyG6528YxRb33^|xC7(65=t&cP+$48AZd$i^*!B)BW1jjU` zjM8-ngVCY8Xt5PLetQ0$r+2@EW4_^haXCv?ktY6f6f3=6y6xrL1Sm?|Nl0fd($27$ zR51!xytn99+#Yd}qE}5U&PM0k59q6@F#PDS#Clx&ROYaR#EOp|sj zR&e{>oLd$3fl_u~=JP+|mBWolwJ_5Mr?A4^xzho&G|SyO=`14Qq?&r)2166W4m-k= zSgUIsXjR#K#H=5jRx-uc!L7itn+DtNA}R-2>aJcJ+UX}axpzWt5GLrE*gv$Wb0elD zv5YlM{rbBXSQ6K!Hcm;>g~Egs?4}m?$Su#La9+uR+rI;GG>ZfWwo>@|zL3N14&sHA z+Rz*uBCQRx%7iZ|WRK0U*9=#g7#g*!!Q{zIqf1H^Hm6hkJn=Qd-{*-KI%wFpr06Li zv8S`#-++F1x+}{@*XhQ)t? z@K`s-Dj^yzUr^B>XRS{at=x(8R@Z67d-LQDrMT3Y0&{QrHEm+olzclUh>))Fd82Bnkjsvu<(_Hve0)rOUQlU(LRpSs)qh)UVbOxaD{;Mo&rEV5Eu-jz{{ zmQVTcJVwnBE*N(Firb7g^2T%zX z)c5D!SdmjbWyBSg;^mURw5WeF7eS*Z!w~@n7xv{>o3#KMeYiBq0)DTSq$c z=!%8B*BUpg(gxua-^Smb3kMYe@VO=VKEbRpDz1yN{@JU0-jUzt=WwNl_4j?`4=N!e zXd!5kpsu&=cdIliwkS~FD&5F69|kZIVhsHzYO-dy)Zxb9mR+~8CUV+WAjyE5A|*nF zube@`74OClDLj*^d(r8Hf;e4DTHi5`_d1{Cwc{CRWRo00)KS~6f`e672Wcs&`uB`V ziB>$j;9(~&=q_KrtCnTh1>u$n>J}qvIuY$VacnS*J$Em|(^R}2N%D8C5|jQ*z?31b<}gyBXw2Dmy44{Swd3GQ~U&!MDMg~#OUA5 zVC2!#VO8{+TsLNQKuNlPwRY9$9^MVW1t|L`7eL5hg(TAT`#uoOnq#&C0?ct9+HOd; zC>5`QZvw3%olVlj13-^0Ih%fA z%3q~qzsQYTjQ0*#wQ8ePZqp{>y@*(DAx!;9MU_~e(Ku`6~ z#M?jXR*kKtZ?pq z2z4~pXHe_LREd?>WPWfny@ym!_MGu>aUZiH>tSz$8X7y8WvZ%CX62o@aOwOOB$IB; zEOFl7SnS>DXBMU_1gH(uh0I4YdBH-#%Y+j^JZ=%?3bQ;XJi&1mg(y!J5wS}I(GhP5o;8S@)9<$5xDmF+t;xOL=s-EoP^4h~1ZAx@~D>ye0T z>=t?@^;#tp@JTuVv(>uWNLpz8&GKwz2w{nBc-Mgk2}=YlQ^(Ml$D^(vufER5da_PO zq1g`nk#azZK+~mgjO(4%*Sj+^#>2S=S8*MWPA_ZEdHWis@o37hA7J=;xAG2RQgnj6<@0BKL)vK_9t^CN3JZG)(!7dIjQs!v%RmQn zVsZfe6w{Q&^(U)#Ho3_@lV>0eJBhQvoHJf|ZQHy>1@k)CW*vXhS%tZEmTU2x7AXH}#=FUC~*Un5J8iBc$IpRV4HzJ)Mxs1KRK{>&_E zbu&s(a|8s=aLr_hHXIQbDn;lEAQFXjr$2O&JK^DPcAZ^&`?7g+*RU*1h`Y()nXrCj z{3G}K{tBPx&hHMNgtR;iBI8zaLH1p6)h^%p;c_Rnt&U=TpH5NIen zHu%NTo1i{A226ab{$J($Wj@o2FCAxnoCe;Mmj|=GDj1H!V##7}(#!1y#7b7XXRj|N zpQf(C`{((0(iAiM7UgVT6h-D4NMH@G>8a8WhrWSfDVDyA|7NIQuOJ`a{t1r|UPacu zrhmN9X}T`%_;~9{xv^&W6$uA+)I_7w;@$Dr<34P5u1+p*LMR&&7qUYp^UiD3 z!hz}gMUb2`-ec_iYLMqM?p&iy=lrm7jRvGC>wC6J&qa$=Y0y1Msf-6M{@iZe1c{^| z+z{!tr%zL44xu@w>&F{WHecqUjb5f@*21pm^(Px}kaK-g&naod$Ekgm4_nie%tKbI z5iK(dW)`|H_}wyg`0;4v;m@LVjoer6y?4o%7EHB$lw@5SNyOZ{(br1@`VM+5(l;au zu}Oa;g0`GjKqy>{T&Fko-ZtX0Ixc?JSRa9F;O5)>qIVt(b2`6T<7Aj0=A)Cfy-3?I zF55J?c6?CfxHW9flw!_8H0k*E5y|)YR}HB~J(oS7L{9WMHm3=n36@!{f_dJ0Z9kTp>$e*)p5p0f{KMTMHs(eUWKXJ4`*y z5RWU7j2y?y136N8xt_o}fJ~c_z5*{TL{;BgZ`!3Z1o_$w6Hldp zVffBz=o&S@2&{dGJYE!OHKRUAT3MF-@A&`O6byNZclE|(Lu2CaMJf780M};v+w1=8 zS^f3>Pl?U^0_%rX2cdEIzd9C(rh@8ZU7!bXeX}!AfJBUD1yIxB3IN5F^A}a(P6LPu znI`9_e{fw1#9NMbTFyqZNMgf*BC}=oB#dto=0XtKuFi+P( z(qD|}xB-B}1$=ygYJQGV2h43iCFcL*BfX3p`lv2I%B-vvL0Q;h3@3$l_R!CFy3x7 zDzd8lX0q)vZ0AH1rT2}OMjhu(seY_KWvY~f6j)PP79{v2*#B0b;&-g65`eY0NRny? zq|9n90KW0)fj{x89r*(s+HV#3+eeTBv<#|pWti0C^4VBbL)x>dniyRnZ=F|IQeJ02 zM)2PEk+t28(pwZZEkiAPX- zO(u9s$j0jRM9tkmF}pN*E>SwSLO*Jh%yXLz8RL=a_cq)ayeyqlpEQ=^jg1)L%TE;7okr7D7We5kF_AU?n;UUzMu8_5kX(Kz!})M72Sr{?;CEf=u!^ zpPZ5iR-g_vv`Pc}8jDA#9Yx#76O#Dot50TxrF5O{r}u zh6buo2ek6Rbenp%YJOwAP5+U+i&xA|pRWNy$AvyJ%j$PfamIC%_A4VSiQfaYBy=8t zsITSJA}P*7nrTt@BpA5KeU%ioJlQK1^)N>u^pbwlN;J7gT8A-9{aEI{(w9d+{E%t>RkOeP`MhPZzs))K)slECj z8uF}-hGG&%iGpEn8mV`_+E(m}K(;brdf#vG%)?Y5oX9YCG`khEEV-PW=q%(GlkEM` zAL)dk?*-Z6FWeYNQuV6dFLBAM45iF=TCA02p+yuAi~=6BMx-9{y_IAbs~#lP6|Fv- zxdGASB7F#PNMB?`+RXHmR_7&>4YiS|n8DMbvis+-V9(4G+@7vtG z-s3CFU!Ola8-H+-?6Ax?^YW`oG1$ILdP&aee=hEp?Ff>&%95rFo^eX0w-KmIvCeZ*bK4!eo(0Ep!u1E{f!(dAqRNX4! zG|X^PewDKveSu{JXldvH?{VrZn8+rHa@KUyUD|$6>wa1@`SmTWh=G+K>gE%DoC!4Ym&%_bFhX4(V?ROaEt$AM2F=qaw+`nK!UPqM zKreNL5K~%1pwK~gfldv;q3k`dF~P*j0Eu1ZC+J-k z>Fd7>3I0g<8fzZBG5}B;0wcv`1NSjI*;TxdHT0>)Y|Ep)2M?npibo{}i=o44ld}z= z&P?i#Yp>1HAx+ZNBu1z1)Xo3{1w!K%@Rip_wN8om6*_>t$~tmOOlON^*o#zyg#avp%Uat~r_R}lo+Nl>-5+L&!EbzfSP1Ly0GaLragNz?vZ{wG(y_-KKW_`-RUZWKAOP|r^ zjDH4Yp;KSu8z*flUS1=)eP5*&^FoK)nu} zDtFipniSsWsKob;J;Kb@A~FGjc<$fRWd14Gm(C0D72ItY;GecInzapDy~xi-J)k|A zgzja)cM0#%{XBVJbv?tAqU#H*VE8ved5xJiL+_O$JyfOi#J=uWhfbj9lGsgLBh+@) zXRMZMHZe$sk8IPy)$gqYFMathxGxn>GzdI$P?DA&KB;p%QYpIw_)fCVOch1Nb zRkS|q-HVj)W7 z_7t{qS>ignLrD5fFFK8D-xP~H+RP^GPCSp{>|ZT+#s;4$ix##e%pc^;H!^c6D55S&A@^o(Y=cgsZq0ZM2%xltD?WPj-hY&1N!cXKSJ6{CN z-q8A*-j-7&Pqr`VL7)K6v!`X zrhzjXKbx>04L?p6QjV0I-%@pMpXa z<*n;dt+%`Up&Yak6QeORFSOseEBT{yG^J5&om@QOYwJphk93U10cw=R;rL45GOISs zcl8}b3i4`FhZXixiZV&F0Vt^YaPcxe?O`rkYc%8G$XA2`Sc+5Js?cc5m{B>6Kt(HU zz;eJ8%>A{f1BnyfGf@>*?GTPpnTAZYOAzwk>EHTjdU=k=>dG*w-JMBYGhW4E|7ybZ z-HZ^C3folHVYiDY$+IX+?2l7I^iTFp-gjKEZd*MJ+7)&W#!hCwuk)nvd&A9d!&12y zT5Y-8spcn*HM8>9%kw)E+Fzw?$`4Z?ep}Wj^XDlIyDW;GUSJYQp=+w#Knd9KGVON-W5YPrP$hI_Rx02 zHC8?bJoA#oQ|9BfM7iZD*_>xVI3g@dV;T8+mK*Jfi6heX7n-$lQiwaqxg z)NgKy-VaNKqjmS0?ic7}gwdZCurr{#)KcMZ>t7)r8b3X?#lDZ2(GrMiG3LHr=1RLy zX8i$WKdw@n*emPc;_Fi(pwNZ=RwG%2@Cwx@G}s>-9qK0-^24CyU7<>8P1;-Q&Ta!s z@#y5ZXe~?Z`f5Oo&8ybVrcj#sdBnT|0RiXgEp? zaX*<_CmPV(#qIdVXu*cuC>yS%P9N%_nSK?w{F4x8S7)r%s)8wED;ZTfu;)K;MG&oi_MmykN;To z7b^k^;iUd1F8wo^>2DH~Vb8mFm$odQqw`mdB%BwyT*J3mU4j+d$u_YBv4)lqZlZ?F zc50`KL;Q{mo;p|;W=AOPl4>FerKREV((euLMV4@izB8%>bvYXojb%-jgodB=-rl>^ zzNe?VECVm0kuZHlR_n*xh=qA>T+Qya-WT4l zlIepNcHzNwnHTG{mXMM-grjEE*w}X0C4c)_X$9FJn&lfz( zZ(2R+Fprq#(q9yVJ=kCP_RuJctVe(I)d42PsYKsq77~Xu8ls!nV;QwZxN5Vz>@ULd zh1s8PxWvkBTo59f_x3j5VwAy`(a;G>9Gx(Wko8+URpo71DDI(=&g^8XAQHz`K?w}WCEZ&0uVlEPmpmeeF6iHt(V)xS)X+4I;& z=uZ9MA+o=#SI_varMj9Z)}>Qqb$!r41S*9%|fS2t2ZsI(2AhNk4IH+L+QOVLZPIRmar zo#~}<%5o%-O;rWKYGj#tPw1bsh=17*ib;1;Md~&uF_OHV5ES!Yn&qT#D#;1FQOYtT z8Ys*lcGD8uU2$@^I+^WD`Qp@;z|%_pWpnN}vlGJ~7InC#G}&bMD&^;S?)YbsonEV@ z5(sW0T3-S6+VV<`#M99dO}^}c)~oBDgF9pNx(;DngFp0^-V4z!mp~r&x4K`g3RqxL z!a>K%8QN+UALP9YX66*+zQ@h?(B9e(VOq(?ER9wIJQV>+nEm^opz!?pEm8ZA9I2=6 zV_T=Yx0MO&da_vGY@C#;FJppp)t4Rk?YR2oFYQL=PdC+Y_V7e@u7lo88?%hs+Goz5 zLCR}01wz9Of_04rdf8dvk^_cg)tnLfZh2PjOtj%`qIKBQpz%^cBd)#W{Q7a*^^_rf z#TUA!C#;Z%-v@}4TW)Uq-L0w&TqIz_3|AbQ;@{9@%=ofhuX2Rx0@Tc?Zq6Dso@wPi z$Qn>&xvsxa!d zl4*je+KWVbnyCi%3|jsb=fQ4q>1U+_op;t?A>tA)MaIi7Yt$3)Xw$N@E`S)WxmH7B zeD3~e6|%r0;=%o_V^+5zF8E$U?p9owE4|v#nAXQYbS zO+YgHGJQuIc!FhO6r z@6!2*8i@8yg>c$nHzsdv<=kz`i@}oEIlRc_gpa8-5SuRMOr6jl@&!y2UcRM)Nn*zZ zZ`wo)2lUU){l%fAOu9gb(OI?<|B9D+>iEp+*_)#*7UC0*uV5@Gdi|@li}3yFz34ng zqO;Hmh+oSa03f%_4ww2jSVmq#)z=9L#VD%P{>AKcmQ!ar0w}o=K=tLAnOF3XKV`UT z$Aq72Oc3#R%cl8beQPBjZ8`9j;o8Fu3gqxkB@(@#8dnMMGBN6ycY+rMzU*9ysR)VPz+M& zbE7Gb>Y$rWL46HDc2_+Mlw9D&e~h;-MA@=#mB~6$!c)epqFbx=BzVK_n=X?D%({;! zR?#+YKD9!X7-zLpmuBN^+qm*x_43(4(erx=wVE?QE}vb84X?QS-rR0Eh|x2P@Z8R{ znOyi)orK>m=&X8GUK!I=vp1Ztmaz7k(PG^}xez8x!%$`B6@EAv7%s4XG1=hDb+I>- zUsD~ckW|dE3dD`7vI9@AE9r}kD&XYS)K^wc!7V1>m~q>>B}#$%3>AN?-4X-h7hfvd zjtFm))+&MQ;hyH69{c$QzL|VHpObq`jWvFga}0Fuyl8OBrF!6L7x^P@ad-HH3IjCZ)V+{=yIh$9eZ~L%fjqy2S zU0t{`?o5v~(*h-%?CKYg81&uG2Mg=(iWzSk;y<^~x#frYB-fFdVe{=cI9U9lePU$& zb+=pT8{CL+G$>89kG{S;Z$Iq>IzR- z{Wi>VENyRkIqKLMv+wWptf;2Y+bQ1)YF828<>cT(9;48t6To_BAE4UMJVU7^sUQ;& z@}(X@TGK-3Rbt!;)fLrLT(QI479l=P{``K`-Dt(DfijuktWy_A$KzsBgEo??g3}se6_%g=~bO zgQExZbmXpG-vLo~d51oXlO?bE&j~jze`pf^PY5^E`lV^O<#~pBM)rrLWG}hT;!kc! zw1J`>xvq~B1Cj*OYRKDdKKc*o)}93?(bLjLgD&p`8BUej^4%A_;-3;L-d<%-tW>NJ z8GAq^aBCRJ0dgI#w$`uOw<0r^i!tQKW_4;_)7`_`lh_J)=kOiQKvZB6w_6*s5Y$1x zwmL|sB1)m%LtnH9U%sS&tzceH*5!oH%$@c;g8zST_tsHy^y|K7BZ1%~KyV8X2o~I- zAp{Q|TmvLXBf*^}L4p$?K!D&LEWzD1xCeLFMjL4Qy+yL$efF8TbIx6RX6~#tf3O<5 ztGlX;s^|CU=bIre`TEzjb}BJS((9E2LDlg?_Nk$w4J?(|Qx%uIY z?w6XzOU&@h3EX&aaxTihem#;!gCXi#f@H}+D>Ip@t2w3#Su~Tr*n@Z~@aP*DH@*|_ z`VbI7D`mu?-O^G$&Ti4r^jQYoV{zT359F7lhT)gJV#KUjQC^jdMIWvzT=l5@ON0sM z;{A)&qBB<6R*+j8SU=Nwwdltxp0wh)7}&Ky zAbsPiyysm=oeMt3{b6ZI>U)EYf(c`D3!QOote<0rF|;Pm(RC!6QAbJ5z;k)kkpWC! zr%NxE17dC}x-oNYtaUDHV7(4!p_Nk_sKpiRLATwD@di>b@x&0$DoSsz-6^6kUs@DM z8L>!jW2I5fGSDX*pXNbC0^O&fHcDTzPPCOE2_gGKjy=XUMr<7-+Tpyz=5{HGWZp?% z`=8RJqp zw=NO5Elh9?7E;0uns43sF4ekyKLd|LNACO7KC-`XE;JjLT1DRC^=SM@x|^`<*DKV| zR9m7hZ#hpk>0W3o8S!nhAG_HvYbp2`J{d74E8l8Xgt}i}HG_m)}G%dlu1hAHa3wKg!jQ zWmcW+AI`aq7Nw~WTZ%&iwYxa2P^->^N^{LQQW03&m zxG?wg_3ZBQ6Tj`B&z8B3NH{=dyAmYhu56o)ZjDv7G0*#%;>RW5pk?^@?!R)Up^l^< z-9O8@p)O5#VjggcZv`Q0k>Ybv&H&M_#-`>XsOBPR95H&4dH-wA(rdFiL|X=q7Joj% zuML>mBE6bIwQ+y6$ZE&=7sxvJkU>1+TkXx4hc6a$EV#tmzzZdN;D2;jW#AwF_ia@= zY^%KhSc%9I()wy`K6$t33rr9Jl>uC`zd*nor7+ytNvDH*TSwPONoFv2fVx#P@SRBf zn^~y>0`1! zKg-+LqM0}#ZNCP8oRu5f?{rq=W<24J)u9QR`|7QUDph2CdA+b0#Clj4#vh-N#vK|{ zaY_gFz%{+5*r+mkGTxrXGxFqk-Q;zmW~0ER8}~zoWa@~)Cqw>)pmncl^%4(fMHuP} zegm1LOvWzO9|{cTvmG&7XAbwR>hZ>ntS^e~_1q{!H>@piZbt@39B2J`8p)y-IbmrN z=772|Sv@LrBW&CU>Pl1iHtoT8N6y^B-cUv>C%a{Q+*t6XBpTH@qju!hdl#IWo0R@= z1)rO|1zx##JB@2p{=WCDtZ8V+T<)id)3j5XaBa#;C42(J(tF}0DHzw|_6+@Ec(&6C zt4ajU10h9??o;ers2YTfAq1E2wS><2e`!%0$c$Ibfy;L<92cZhe^NP>?B*9ptoqY_ zvvEu2Z*;bCx=m$@e;xf!*xd{Sa%E<&GPiatgh#GE#g1GZ>yq}S6^psXPE1y#*3|_QQ~VZ^1u<}|5QxO~ z{o1qfr5e$|9a($U1u};>==ch@*AQ9v3^dfw*}bW}y?R5h7Cj7>($z-d!<1Wsr=P15 zTFbWCAqUiU0uNuBu5T5t$L&I#6^_Sdb@lXiRcZ=zRZLW3Lgzz>0~dCGVi{h8yr#}U z&NQIL+Qbg%OnrcT%jkxk#PZp~#%)heHofN6xF0pN7g*yQrlHqr=S>cIdb7Ja?ia^_ zbxkuDA2Dy=wmy#)mlVn!ubfk69p9gNa6fbL#10e8`{OM*lyL+@Cz9W@G8$)|KT7#_ zoFg|mD$g2!vS(cQ8oMEP$6WGwvNp58lZW+;>HCn6whea9tdVReg8pQV}?5-4Jdh+g%a>AJ!GM1IqP355}#ppXy6t6yrovQXa+tn^`U!Hu^I ze@xc-gJ0J7GC&d;$!h(et8e^lE;LW#!}Edw*gBE~s(c(3le3h&5usV!OZL<|(XqE} z`Kx>Wwike~AH2Oq6iQ?kC^cIX5*CDaI+l8~Ao`y83t%$(LW+z?E~4RIjQq^%wEn3C zhLU(2cE{taM*y5@V4qTyWdqtJ#QrOObe%3>R2#4Gx(W0L!2;8UJz{&xT2Bem(Gy13o01`{trFY4G}f@5m5Y=DJWS=JCoRbjAao9_ zVsxU3RO?$90Ly84rNlbcsIP2?!f!8>SjPPw$uVUq?^t5@JKvNQ`*@UCVV@G49kJdo zJk<|mrKqJcu+E^N`ZqI54w)X$CuS@B&N(#9$(e6{t(_M20l_Buua}XeAJ)Qjeinwl zW%o|6R~B3m3_nxGY12oh7VSFD8XDE!h&eQD{d_Qiz2n0H$Yog@(?$788`Q|V2`$up zL5t3{e9F&QY^Y(~kml|QqmXG%xsh(G7ph-;nPu@w;_#;2IXM9N=mq$nC(hhs7dfp3 zyQqTZ4{>tXbI!`=f>tKp5Az4;6M8+0hhb2r8jsP!U!3VS_C3D}DXa7C;oly!5kZ9; zIgD`#?cNjgjiWvtpK7F(B8TDm@7$c1X+iG?9=Go?Xx7-~0ZsL5TYC|%$anw(ph#8y zc4Ex^8MIw7{S4zfA~_NH5SRjL?&xOh3~vAz?X1!K^vdBVQl)**_sA)fgbPis`qbF1HbR%9hm7kifx%qhzpP z2CNP1vvc1?H^{D_BCb5tqBjP*)fJ~>O9PmfvG^EIK?~YLLqmu1#hj57W&$0sVa&0{ z+~3_7rG?X0c=u(o`8 zPf*;dMW!<>JP(G0U5k{l@oe^#Yr~am>114f3J8mHIUne`o zUhfUSE|sK>l#wK5p5hn%vL3ajRv#;j#TogOwe!4p=hZeaeG;axXzJPwEPtP5wr<@4 zAWQRy;}%57tUJ)oBXVLAsN+XjJ#zkfRsNASq@b~6G@2(N%nzd}}J>LG!G ze~jC2yi>z*dbg~W1d*jez^fLxceXy<+xX-2gr`puR&m19%WsP~9eG+{{uuLaUCt(i zRg^|boiY4Xvo=IhK;ysrHW%lXR!6V6llNseFcM4)kAH z|9idQe_%-Heq%@g2i^}@EB*|(7zH^|Tq1(s`~`A_#)CW;f8^klh3cz|Botw$ymnjK zzAT{`%zF^nvw$fUwMD`s<-BU-tWlk!(Ofz1QU~-+RMv7Uh&7<`Hblvjx6*W8mUyRf zS~nWx?}lyDS5?)%pSWGM;Ql06(`yqslvuQrys((NGHNYivJWW|&F7Bh*0G8qb77K1 zr>Py}dfMS#V4dCRC3ZP(L`e-kNN|s(T|#$xM-uI(EggK;#hD6mCkV)!=B$F;M9TVd zD(EH+$5DE|3GTf{<>K<1Y;Yi0Y|5)}E*wVNO)hDW^!fBcjZXHJ%rGNrXRKGO&55=1 zvw)UzrTo+jjH(5MXv7=mv%U;`Ikj+|AIDlXVI1fETa(oWy)Y$ifpRQrBFp#@g0EBn zqo|5=|FBWG*lOC*<~rzCbCZE+ul?5PLuFV4hSqkFqT9ZF(e(Ab!Rhy}M;T(dMdWOA z`>vqw?Do(X{LY4Bo0E)V5u9P{=VXU~=AZ7m24=IN8U}3$=hlVkN+WfZzvq$Zz&y`Z2pJ0u@l62B^q6&Exf zb@kP-dniiT;H$EBz;6G>YLRr7I3T+5s|Csj-moCCr@qVquD+}%*MdzGoNw!H6f7f1V}u|5r1+xbw$9Glf#(yU{?DOe?uo5@@o&)~e1nR;J5$p_bYFdgMcx+?pf_XTqKyjCb47MlivR!Z*ihz7M_2veuoE^(s{o#YuiW z?m%Un;z$POwC!X(Z=$;}(==JJps=ZgCi}BA=(_yVuB?}{YW-MM$T^GaAn!h;py}J( zl3wos{Z~}Qc*ov1?7x@`g!l#Gb8ViLNK}>a*Vdm%3_94^C`8@wn_uGIND3hr=gPna zEwEA^fqn^-lb1f6+S03mhp%R4?`U7{DyM&W+eBywwtQ(yB3yd$!)1`h`x!AL`EzOH zqpYb-CgY-w&H`t67$_4^?NJ-^A@%nCW+0Wf7`JY~YIwERbo^}w*7g1@#q)XxOX8XvH6>!Lz3G!!O)#tH;Sk@f!tL*&QCvj(-b zJQ5`&$ARkfnY?QY!Q##@`81D^C@o1`dtq738GmpPNDUUf0GP#nUI$qr@i9s6iYFs!>UKo>}34GLGS`6{MUlq<36e{^AU2# zwTB-wX{BfVg^kSYbUm_Vp+s{A(%D@;62nZNgHGSI#XjQ`r1R+^Loy7yQVbPYW>}Xm zEEjmK2B z2BXQko_+CVejJ)r@jf+8b>Y4$O@{MSnI7EQKx*==Nv-%35L!6ZBzR)+MRaVp3U0Ed z{PJkG>Dy1btg%#d6-i~>55P@>lcXU1y zOPqorn!zF7UqqU_Q`6eBEg#QBskMOm5typ5$uvsPPx6to zSIb%Ebg)0>@tp1bmf{~K$YljmPq4SO z6OWfan}#^&D_Br>v5{Dk3%um{Um!w@SXt(skF+IkP2eg?v5OeO}&)z>5E?Cn&lq#7+Nx%m`zAsE%8@|&F8ai3m!OpmC zI|&$41!*-IC{I0xG3pNmCb;9<;pL1N_4abNIMshYV|q`0Dv1lTnkn$GaS?r^Z1h0> zkm9K{K_`@T_W-8jhZTuQppQd$aqZk)CC@ zCr{tE9@1o=X1_b9O?6*<2|XQz9>vJT(IQSwZr0T>(PDPNB7y|!SJS@hJ$Gmu1@vxi# z8J08%aNUG~mYte`BLfcIb?HC$N%N0ml%&F60gjF5zuI@?T}AN!`n~_f_Y(f^&dGnd z-~aAA_x{gMHqjevrh}hy_j`vqW@Oya-apSOTLAgq`!ir5lnzwRPZarE{^&n5(o~)I zbOHPbCW@_FN7`$`vY25_NuXk+hN^w^0U<>j)M#Q}tZIMxU@l>Sf(y5`kc#NMn3V;s zKJFFVoV|KhtpD(Q4FMO~p|=&P&OFLtZwPSC`kuE~gX*28BnMn(9!> zfV|{7(my7fg!}Lo+04cd{%rn=kbZz-LFxR#E4sa&gKb487$Nmd<_)Ov`%3D96 z0VqD>s0g_8_~_(xWWXCnD}a+1;7L+W2cB4&*(Qd^w@An34b*-JoK zj4h*NoMZUHem?jV<)!7gMAgP7P`b2JDkRL!p?(UC2LglVEGWOn0~yEd`R%l4hlU+e z=|tTHFt;=&9^>?)ffzpNcAOB4BIHXMlDxfk2PAHR;HU=?QvWA7atIVb#$;_L11Zb5>wT^dUdmE} z=!f+$@F;Y*j!TNabN*VGiE)fT^&nY!`zJh_04D!|I%N)@`W<)1*O~=|pb8@ln4V*L z3NSl9Ym8BV6oDZdq7o(!V$kQ$m1@9zAW);clN-P1IsA8Va(i-1LIenbLZN$MlRb{S zU%y=k7338YlA`NMw)IdtVZDg?Sb#Uc@MF}G#N4V|JijR3^9K(Z znN=cV?-Sy(D^h*}mC04X+-g>ruorf#q$9uu z(49R@xU{L5iyWhCGdaQrZL(xebkAAbQ_aTJum>z#9_pwdqa%W-htmMf5hi`ahT*Z-&fJ#MQ-Sy*PGK1EyvFAt5l5qE2opK)t%e?Lf zX0>*#t^Z*s|4+kM|1ya6=W6{o$dbRW@;kz07`z1_OlAWa?mt3jC)|4`hJSKu0Dm6H z4rF5ArPM&bk+Yv^P$VV~n`v&-D+kRxlKrwBOBZ{X7V2O2Q7Kfp<1Smg^%rA}Z3e&+ z!M39<+u#D|QUQ>PYlN;c2XP=s*RWh5N=f$FQH)R?EtF9Ec{R*uGG3(ZEx}VQgccLc za|Oz8tG&6`vwoP(oL}o?0Ry-E+e>F$Hnf+!;NuK}w5M!S%}hSj4@@#Yn^n1dTwDWCB4Tvmiz;c?VYEuNOC&U(5 z?Zu~>lo78BYd-48x`gNl&ZOqM@g|>~5>%WD=1vrdXpCX&pF{>`^HH#X?o7eMETTn& zUAL2+G|Smn)M@$~EvyMik8&mAzRfMp2Jv*`k90636A~^B`Z_ut6?&#Q$_{_2702^* zy6w8gK37(HRXbUlQ(LcvZ~pou0{?D!XZv5$M5V*6EreUgF9o@~EUACa6UsZuf?3zt zijN8WpZRzf7`9ov-^^YLEyhfVAHzRFEo@+?Kz{ zdDKc%iL!Oqq3Vhxj9edk=EfkvtXdB+H1U9fX0Q|u=J1mra1YpMjpnqu0|iUEpc|@zUl;gffC;hV~=T!>7>~*0URZ)Kl!Mv zIu51oI6a$bfta1a$IrXa4sUvtw7`ZsHnlM=RtiUyid{-G+}+Iv@MQd{xl3-0?n{_J3Ne3 z#`$OtC*8EFL#l3SVj4UqkT36z5cH282L`}^0`xeVP2kcn?3)h9j?6hdgTZ^78M*5* zUw95@8_lC8&+q*nN#yH}aQc~Z6Q;@vK70oF=VxkYVt`esz4O_BM&AHVpih`DF=+VD z%Pc3^NMPJ%>2bOYi1+W8|K2`-R1){^*Q5V`_HkS?WWx6|ZtqC|;HQ6I;q%VD`(OQ8 z_2Yu}u>i`jfV~FfyrR64uh-Tv5wVfZe_+DBz;yN9{c&FobH_v$F4vP>(h_i1@It#& z&Nc*peB>Qi%0yVF+`~);inFu+0GWf|y!pM1nQVblL!n7k3aE<(eFFk3N{5^E>EWdZ zu0>7WJ?`#_i@HuEpa|1@@jcp5@E&PAWg$1e)Y<&E427m_R-(k{}b zD%-?H>?gfiBc-e~N0`IXa=*dNrrJH0<#TH1yNI_osB|I;8jM3>VgY%&%K^P9iOH-dHcbQte<^d8S6;Py6Jad+1xYE zo9zw-ItN3(i>Qet%=?yE4LMJXLx%4LKI@GX!^aXn(Xf=U|H32wto8>CTAF(sQ#@yU z#Rg6wIGoEIBuO7k zMj;g0PeM)iHW|=A@bwK5yf)TxedC&MNC~;|w9Ajc8+{q12SxjP1hfv%Z3)khPHvfU zP}bAsvgyVamF}Th%6;Ksy3N{Twh+f#V;88&4gn9Fs=a zI@mrluWxCH-XBfT!}1}D71}v6oNhaf4ojB0{1kn&JPl~=`f*P+3a)Zk!231*tw~uw zkeEsr5iM1-hH~4Um8ek5&g!|$tx!34A0Wf&m${g0GD>@NqYNS;tH${xjeF+KIdbcR zjO;++kZaijdt({q9>K}E^4`a&=xKsX1QFeuGfG<8`MA*{WU6D86lgg0JJJd6P>_|a z1$P=+yq_EM7Xxmy4E*Uf0aEvR{;P`WFA#OKg5!%#>{EJUx#4Q{4OO*Tv75Z) zrwj{~H0{Z5C_mdi6Prp=nNDju)b2c3bHC0shCT~A$D;Z^VM@MFPe(9SFuXkYW{!JL z3WJNp{XJr5=KdL{FF>5Ib42UVZ)chNMuQ1%e64gFx{7|23`iMJXromm-WvF_mN?}r z!UXM9Gyqj-;9hdkelRbc-$A{eX1iPKKICLYE>5e+l7kA6P(Yv6tboc5P}6z%FU!*T z7R_B45(xcMrQv@i2HfqB=ak0ID2d=Hi)&MsM`)BA{d$Zip?}P@L!C`u?ukUhy69yPaM_k5t*viM$I|I(9&`y{W_CB5!N)EfU?ST)!)P7rJp;J8&H-s(-`0xx zLPZ3kCQuHb6`iv#&q}LvnZ6ON2i{1t^lk|adb`gdL;*Obh~+IJ8Ub0g;XX%fj}T-x zi_UMK`iP@;Lr7B&6yD=x+B&CwgN>3uMfz#2Mc=;g4!K>kH_#7L>K0u zOI>9mtrsQAq#YtXA&aj@Drb(832{G=U|Nau%1u~%eyofEutwUsEx&#*aN8KIIb1*DC%Cx)ci(Bn0bK)`=4!yCusOo&I+Al=JSS?a)lXzZjJ~XK zw((}l>H_n<`)-xaiZX zHNn|~Kw+HU?#XnIU?E1X#LZ_Bn;%RH%T({!V&T9|%A_fO-3Qb#D5j5#lYNX)V6jX5 z^^5%bP>YA}TZDz@(!A8}6&y5Eckn3DMm_83UI92ume0_sq877i-qs!;7Ug*C>5hrX zNR$;USSxa>AE2{-qk0`IzBgRF8GZA7ZrJ6-XZ=*roYEb4YmU5hP7NXl!|a?M$9*!e z4ZD)Xwe4OR2lSM~)q%tY^^$+3vYhs)E5>+Y9lkeU%f;8V~Cz(-#ui-W)r;(s8koy&X9L zc=su1pX<($u2kcU5BSQfNn{nugns!ly%7xMJ7;oN9Kc-AJ%O@ME>*>5237U-4hi5Q z^)j$_SOe=D-~9zDu56;c=m7UlTEh6lpv6i+wBdycF5%+eE`GgQ!gt1-eq#v~sI!p| zQ$>-$wYpS>Yz;Exi9_u)tp2sj-U1)P&t)#TS+xl;U7#9cm3(n z`Y)sPL3s4Jz2`ZDfP+|U_rj*Lx28${WP5&l|3J1U`5O&A zV0E2-*T2gq2?(M8M=M(}-|EuW4jl|u@nx`*p+3W(`9a&ong~uRB0>lqySCdUc6fQxjJ!t_ zpsm>`UVk)%W35oD2#DCI<|@x*_yTvKPqo~JvGAH|AkE|B4}C5S$kFk{I9L0YchJfv zx#<{5Dm?dVKteDb4Y=C8%Wko2QH)D+^{uau{KZ(pOSY>oDP%gwlp%#L)g%n)sGP$< zxyRFJs}hkB(4N*E!$$y&fc`)Z*}VA|Xf)D9Qg`>by5hA&eu2lM*~QuAmnYUI^@BaH z;{uXTO|bNIcMI40EQ8sC40K|#u(#|jS3X}Xk6^wzM(aqHsLI$Kx4AYd*<%`G<%40e z3Y=g-`X%V+W@mh4r|pWf!*D#x$j!sJNM4z~yXQhf2rDgGE+RkR`>0Meb`@DCwMABZ z0mI1QXWRRgLrXY^hQ)+03FlyQ@92Fvmw!A;S}_ z@%)|RIS?wYuuO4B3-td50zC%k6yefSM=rF))PAGcH`e%A4}wg-n6Aj7`irE`qREb( znGjk(uzn;krNES3QT!kf*ZqB5Sobmeseun4Y@&Lsk%yy^(uk~(7FsD4V5xx-lPLnR7n*m@F@a3`GaWXNo~ z?6G!IfA!=tZt|(uVWatKGyzZ^?0IoK?-ljy*_*}$gWHCr9ICU+(ntP(CkjPP0=68w zjHsdp0dvuV=ayjdP|W$;PI76X`I{_CaZX37{bNvn>^sM$+;>nMhZ4S}P!X-6Oh@V} zKoT%PGsrL#?McG|sZ8}K;@K)5okxC0Y^s^-C#8!qv5cIH9_D0FK5ZA2T!}}9x;l86 z0bTvVKIbdSRr0R}m|V!w8I%eR?Yy}5;kCZj0C2}-w7f!V;_zZh=zW8^MQI_JL-4Pz z$Gw{ttN%hXxsj9Qv*;rw3!keX4VAO@X(lBNN^);VCZya2`i0mgNp5TnV@B? znxNB;3RPP)OODRdJbkKhYSpCDNJ)TuQ`pwaVzcpAPu-8Hp49`+nOP+^(G<_GcGhT5 zg%C0tBDVqZdQn-rUt=wdp^BS(uU#lztEv-D^(w0%A%R82AsZjkQZZQfKShQ=Bh#B1 zYzoe1Jz#j9Bzb+z_R2@80)%G%uH!aO6Vc@a{pBVM82bq@A0$NLz(G=5h$kIxN<4=kw{8t)9-De8TaVn0pHvjfbB?n$L^%gT2@{|(obQ4Ola74qj(Wy z_V#lPP9fuCVF5z(A&()*K$olELzqlnsHJ$*zSE}@OzjBEYHo!RKD3&XJ2_1$;2u93 zq)`n4Z}ZdMUKK~fbw%VZIiW{@<4Yk8LzC~Bulwy+*|2xNUGkXI8n0qY5k8`x#lp6K zf#xPUuCq!#4O4dVdk=1}Q`UyL;u#;ph_i;DzRNGb_%?ZxN&N%<(Qy_4Xfne!p)0SA zpu=6mwNGGwNXL#TbylW0jwIPp1G(aa9xl~tZj|i|+CKAdeELsd++8&I@BV0vY5dPMQRJ=f zG#LJsJn--S9-L5)koy)%+HslKQ_LOPyqV{$79O|FSGw;r2kS5pS?bg?tv;n$QVuad z`yl04Dz}NbV(h#QtSVwl$SeNsapQSau{b6AXAGof-my+lP4%YEP`h{gGgvr+46}9g z5rOMjaT7Jlxz0mHKj6;C7pFb-O9?mzJ5%fYlS3i|hh=6xXQd{}F zHli=TTuPkFb@~a6`f%;wA&xlK(|7kv%z1|X0==MGn_n$Qyk7N{zR@SZ_E3dD+(Vm{ zg2|Q0yn8#QN3;Pt3S}PLjMRg8ewPR_t#gVPS6S#YAF<4!!ZtOl2^Dkw_ADtA{v1aL z8g%Zx5YaJhhAOwF0%THFEmSDBo*&<~yURaYmqp+_C7B0`=m??4s=q| zfyseUj;GKw(=u@B&5G+{3Y8zj_ep*wAZ`7;RhoF3e6GPmyr}@~UNh`^44}i3ube>F zp`*|vAlE>#)o74sjijymVDzlh%kTRMHvx6|cNWl)inkhu9h3X)R!2c)8K@?Np~;iV zKn9#(PVZ-mwKd1D_zctP;q$0P@lmz%53jP19mh-1gxTKVP0&R|^9%h2dJnW;lO_9> zMz8t4{R<>tKKXWho{xL+$@;xqy0gu)HX#3kCnKT+j;{O=le#WPc__3MkzBYe>TocO z3*S<%tgDLJM9}*isyx=dU9r!fegCi~B-Mpd`Asto{FUyaJWPgOr|-?~{bAx;TBAgx z$=BnR!ylW85;o1AKh>cY`5LEBGc{mfV>^Smf4y|aX9Goy0Y98 zC!S>jWezaRj$uM$AF=YWgVl;y7{7N)PvkSTpeUd&B-B^Rh9o|UXxaKX{TB$$3^>D} z6|2$;eK=$lO0a#h>y`Rh$r?+YF=n3Ops#hAVtxB}Npf#0&gPonXF?cAxo8{AYLwxE zc9N9<5ZKIsrxd4uz&Osovf+drni-S4C1=?7no=fCR@Qqz3T-!DI>Qe@-Z%j5{tqvJ z2-gLCIR}k&u8gPonSN4M>oZ(83X~%6w)%LtRq5*KjmfL=Gn@qmxtfN+ol(-q2c(c- zVZ%r0e*Ej78@{-hNd!l~QN7Zcry8z1#e5)sxen94lMrG+Hs>8pQ z>Srgk^I+b(8aA(BbD~6$M%DQ;Cx}Ubnr+}x@G=FUTLuDjlk?ntAUnZ&^KsxNl@`Ht z0OU-!p-0ugc`<=2%^}~90CA)pl7Dbibw(4Zb%~R7DFXhN7XU)$KMvhyizWN_CYZd3 zF3{t|np-r$Eoz>P{Ec55o38y<}17kEzE!)%tw-*!X|FO@y*?;*I(*O8Yx&N{GxhR_e0b?@|zj&^p z{4(G&boYlhlyofG{O(^TVL9L8yoN_?QWX^gaV;?_mCj2g{qiGS_S2{AQ$Cy)qF$-! z_5{a#lcn8Shdy&5#9r?A@dLhop##1>tCEs6qe5aul2^X0gU`&B?yiKfLsR`-irjkM zCAdeYxb2~~^A%xLk!69w5c`8U``nLjXGnuhx+}xfwO@Rp z;XQs5y%zbj#8nq{Amd6<9y95|g?LYuPs$oC=B_dJ^!hmet04)ix9TSYsb8QUZEl{E zM<<)6psMlQ-(H)5201~A5CjB~2qyme$C0x0euaRn33DHZJ)tE8BhK95zVK5s9GuZXK*U~+dayB9<8#Ko0$S21Q= z#=H4PR_a?(oCYIRrKmo;$6+Mi-^IQYI#ya@^7n<;=gb=w8-YV&IqYvb(pW|xr_Jk2 zThb<;)H<@(U47+R{-6TIzBKTBF~Sh=HSB86D45a#_t#8yF2vUv{lrvqqguArF;?99 zY8se@nWEG_j%-l8*$nY?qPa5WMMSRa5bdR*e-I-xG(%`EiqdK!Pf@Be*| zgJi3P^c>A$$$E>%9 z8P*YdW|~1nul@^M$sy1!Sl@)q!&&BIo7VtLR~mhErgyYaq4KZ?Eo^eEV|M3S+K$7f zx_^^3;_GKJu!>D$CziB_;;K;jqvd__wFt{=oq?74w8sydPed*4WgDY~fxZm>2_IL- zLdEyl<0XC1WgQu)2mn=z@F{*F7o&%#8g)X!V;D)uFkWMs8-ezsmD{)PB&<2jHP5i2 z-3{RIaWN>~ky*srfkub@(qUs5!H$WQC!maO&5K6?eQ1;IR#@6=pKIPHKRh2nE6LXI zZPvAXW+!2)ue}3XR^q*65ug8E@$u<>bV5(!O0|1z_x(DDtpW(k2JfF~PWWM7P2<6O zq>W5gau?dWDeQz3HYjV=fQ%b_hkskSvp~)#;7Z#e^dR=M-K+RvL{5Se(9hwMZ0e&h z7S&`;^jX8ZAU6lq)XVR4M4c=e8eJHmC$*P6-5t)Mvr?HxrcARcY~083V)G3vb^&>} zh@-KLzp5f2w!$TTk5+YLR7nymZWk(Ygd~i+Z7Oksu4B0_-G(i*jWpvb5c_dXC=bY5 zfy?b*#stqAJwHJ?h*|Wf9~BcdcRo&l5~@7$-gdoLgE?rId!M?=h8E9i%Bv^LWl&^; zQP;jygZU`~Mw{4L@_Z$XAaDaP<|BxE#i`s(TlU4P^z_ujFUJh_kPk@JZxdU+YSL>x z{j|S#)wp#F4}z3E&G8eLmqNXKzqnRcO_XGX8ugQ?`6_$Ld0iMOX^d4p3-%LuL_x9{ z<4N6B*F>5qYZ?0z_VtWTC(=CwJ)2lZCc}eSWBTl(CCZzPP3l=}+|qoAwjQ{)ZWkCW zajwlNIk0T29}38?+RV5A@z|&;CybVZ%HN)xCeVq%D`%Ez7VgTQf4@4`kkaZ>aNrO_ z1@oO~GH9raq$~q&sR?5o%S*y0TQ(XW=KCO&NmG2#TIeIS!lBw>jb4+r2!X`D5Y&z< z9u=mRd~*m0jo^pv0^@GfN?ihdoJrofp;WbxPL0tMaVGY=9iyD(5Nr!Jc4l~@DiCo+ zJsod_H%{d}_lI~H&QyG@&=RsrY?5uSB}!cLjqef7{xtjav=>)od1@+j*;meJH04$B zkxFG1(HFGEg%Eck^48%hkh6>S*&;R!U4q_-=te}r!3aI%2jT8EG(u=O|3 zLZZuD znKRfIhI6g*J4^_h3mq-`EXhC2*hicgWwpY%XQ?f=Wj!+R6~lJ6;Lx(RBI_xMmk+D+ z>BGi6>>tU$F~y=2S+_7NcS*&+(Vxy5-G5+wqDR4}ZHwCf^%PD4Amrfo7^bN7f*cqi4)`$4iOKUpQ?%BBWm3Mv~IDvcJV;cGVYK50^!rF zo{THo$+8(qRZdMDNsMrlREm*kMk(0|^DF)ZY9&3EvUbi{{I#cDql05pq1!93U~pIz z3@Y^|lBCKdnXySH7>dv9FM!(q+I73&W%T;&<(&{a&5VA+wa_g`UTi{a#oST9o}k24 zS7V`9QVMEKenPH|Xwe7t{N0&`)H)w-TOuGJK=6-GPTOAkFDUm2+XozzmBqAsezd%- zMZnAIU3xo3lyj6?qtMmiKylWf`=qbfhQczCBb;?ND7VE$=&8+@d0yoBYrmvY0Kdm( zV6|KmX%@zGKO`IF6)uSF%NXV?@`=ZXl`8?asi~M7RNRl}4rBFgFHyr-ekZW+QENZN zOG=yPPFuQ+3EKU&+Y+*NQdq*7)m$FDiLpS{OD%uKFI=pO-3zWbw2KR@Xi8qd%qsdy z&^wN{X%cBn8!ZWsce9JLAl>F1m2AD&e2EmpbNLH|dsf1^*ILL|Jvt1Y&3Q;pD(VYD zux=f2SY-jE+6J^utBsI!Qz_b^4ET#z9wz-?V#w<_f1NSYjx{3M0omR7#ui>1Foobb z$HQ)APM5GTvS0KT7Lxbr-j@21Houn0d^>o8h($ScA~+$*E#hySE=XWSfBd*qveitL zq~GW1=dLw!0BQR^6hQ`!^bpb$QuR$1v9XDEBUWQ6D-i;|{{KDAYk;Ki&*b9YNygug z|BrPd@~?x*KV4nm9j={`>{V?pk=aJnQwb{auD{Gle|ry_#uh-;;+CFN!qGKSb-=SG zTZ!Y1THhYhdr16&7_IGE+awCmoF6p}wP&#OoW_o#WT;!M(> zaK*$PuHWNvvXzy39kfZ6mGlum*F_)IACRMuv%$kncIE5PIRU&|wr(W#9yi>5^-R|N zgRf9d)(t{$4FEP-_VH4uVuh!ZsVIA-TJhnqvV@2Yee6hOza3R z;J2@PhVk;++z|fu{D(l=`W$fECRDF)$e#ntrQJUgBnpza(DTr9@XsFzOTT){5Bw=T zLb}B{VE7Kn_ZHrSgAtv0?qbwCnmdyhW?QdCEzCX>{l2lDOL)!;<6=cq?9=O5^3CecN)Butblb2W8sG<# zG;LWPnt;i}cHqN_#@~H@y?Va$Z*Hr;0qdd4DH6cM!$<$qUn7{`;n@lk#XyGzvwF+-+RB=VGSlRleC0fu-o7r6 z_j}rw6J@35-1Cd`%Cs8giUZ)sHs3SQ%U&F7?ih286^qfAcDNIMPc!H(<4AJrc|aaF zfcMM1V6*Y07yuL`2wZZ_%=h8yI9@py+eLHprsmJ_q3o!8gb~nq#C6Uxa>obg)@Y5z z3@eoM9EM)L0Ybk)k85@FC-EyG{y3Sl_w##ThAqSN*8l<0W~2DJ$+0E10^B%uN z`xcO%t3FvN&LKgo2k}zw&XQhC(W9@&X22zKwCHIe3Ci9}PJ8ct(L`|p5r$P(Do1vV zLzyh_I?5uBhtSxtyaA?1Mes>1KQqM!$<%>tKUNYsxpP!Y0FPoNdlQS5olN?a(UzK8 zm9=%90<;8wKiml=1ac|QO}304MI@uA-#^goJo2WlfRvK#x5s|$CuigmCOa#|I6PcM zoaM+ZA;IE)i1bdiDZzx}*jfM$$LGn>g*JU7e`oH0baad#?K+ zhLD-@S;pX#%tB+E=}7lN!#>w{Kfk?+Depw_zk}~ZP7vA9-s2nIuk?KUV{MC)#<~QI4`+qgYPjXg_*ne!b0Eoi@7?TOAXoc& z3=lrmyVJg!s5@O{LTJR%T?G~24-+Viuc-7w8BxQOS{YO^0=Kyz?@^%HG*i_#s0zIJ z)IBm()TT|1FD}dWy?oRqlCtA^aNF+rrR+qbL|hMqH)JbRrh6f&jck~1E%{WLp!0e< zI4@S2NG)Nc7Zjrt5B-*gXAs?!#_~}o{Z+Jn9cj&jkett-ocz~0ML>XC1t_-&Bzfk+ zRn}fq)sCIr3U<;z2|HBf8fN_Q9ly+9sQZ48*E*8c`ck`v!d!3JV=%I-vqm&nEJw>H zZd;h-Cq#mE+DFn1IWx)08OZFScn~DL3tFc2s`33F?Y(tW99_CT+5}4on&27&!3n{g zh7ddi3vMAe1b1yDxCICh+}(l`+%>p`#$6kCn$E3!Gv9pQoHOUF-<>;i&Ry%?KYDeo zs$JV^SM9yu_j#Uo?GS%gKxV?msW{O}^JPN}k`qN@5DOsHJTc^ESs)UUeYGUs6lhhH zWL<1XNBg4bW9HmIJ<3IU8D}@CikS$@2)@*gX8Pst4wTsBPjqLGK$eBFvKB-BS z9qQNNzIOD%5#5}V)_`||EU~gD-(j?o-Kjs;D}(_JQ`oDnR-z^;J2x^N&B2x0L^WQh z-eZh+Xs}-QEhpmA!xrM%?xWk+iB{H!iWYVxn00vbNWq`e4{%+dV7t%YfrHNllOGDI zrxa8Ll&-~zsK2Nfi3hgfk!@4jtg^Rn*zVHZgv;R8Cq~ST6r7=;Lr?LX1y`!}OG+xg zo?Xj1Sga*c2ii%d#Kt?d9_$B$yrssjKS6jJuCn7|VZ~n9&r&FhWLPo~C~A1el66lW zIu+?INYoPrx+TWECSUR0<=auM@lrd~nJVL^kQ941)M;&x208;_`(T4IFy8-l+6D0@ zoJJO(dh5(AkiN}Yld4L5qb7~#ds9#zu(zk+hoC0C?6iF5vS4SBtSRYs?Y#q+WI(o& z{Rq7})m!MDdsr`DjPp*4wRUZiPhXIpz6xb5Bn=*%y(`k%3ChqiylwZGp- z)BJ+)uS=bKq+6bZ9bR+?=OP<0_-XG!ZXeY^LXSZ4tl3Y{`^xJY3YnHci|hiE<<>Dt z8SdhooiVc;?!0sxL>cs1h|Hny^cPCJTiHcs3wMeyU=9h|9FNCQJBo1O7%~cKtF5^A zvHg-v`{;V|4panAACDp3A(_=S9E%I_!#w1EM2FF^)G22 zi5jLp=+kXRcj#jF z|LTG#X&;XyIV(JAV{^ua_Vbq%$;6eH{=VnsV6rbt?ayG(=k~2+!;9ebsuK3%ngI18 z4cPr|=OSi*KP>0HGw6h{wBnrd-lV?S-eV|JxCIQy2oFH)Br6IAz)h|Xe>vK~)8xD- zgGT@Y@+RdryCmxy+aK5T|2X_l$-sYHQ~2ZX?~|2gefvL5_NPL@wE#DIs}&)@@DrqA zyEMqw3Gdu>IEbtb1$>5oyY@#zvwv?VPT@#{zyNdXpDz8W#pgj-@JcvfTgw;u)fswo zx(zZjBL=ia%Mlr*JMDet3aC-p5n+yp`3@M>#xl1ZGvGB==3D(v7q#p|84}eC>+Exa z(YFp#n_Yvud^a=l?%w0cAt}14Bk8eS7ty?_PPu}+av!W{KgrkJe^~d-%dU4tSclmUCV8@0EAFb z&mu|0W;9x%#Xa3F9RB^a+14~mdex)S_)Nnmfs4e}!@9<*J=&u;{(8@7_NcJo8VzO9 z4Oo$?*#;-KJ!|#C#q)!9(d7zp+hc=T$^PHYE`uFOxM{F1l3&zJS#elx(L9OV?rcc1 zj#zaq&qs_*W+O(XK6zfmq&FkRDZ_E2!kl!z-(d@W;(CJ;n;wf3rDEiJ4v36{sLW4}U{ROQ&M0YVOY)oYjeMmT`I?6^Gc(b>i0Upp3-w}C5Ml{&1sMW*MY*Nz!_4McPfOC5vjGRpaX;aJ)7r+r9C z6p(yHd`6`yq^Tm@H;an~9gaD0FczR%3+6j!R(^iD&ex?}w*1K*eN@*gEOzV3fPl8TNla?}*=_<(|6egtgfpU6rli4F1rH<^C z9UgmoKMFQ;o}86n7b(Rw0Iy1cR#!m90KNZhp-QcFt0&9%+TA~~i&C;lI76v?Xl7_z zBL#Z{N}a?^zkSBr!0Jwkgas@+7Q2H39ks9bxgnTCPEPm&F|^arq%5YM0wYrsrO|+$ zNC5{?N>5jKAu{83+Z~n%PFQJzPLTZ62kV~9Trt&SH)m`<;Ck>x;bc(-* zP(veURh3<8Mfu*br?G25NBj-OR;GbfZ}dK_i)!`+#A$CrmH?LM=L5_mFF08ODlSX zE1HRL1*6Jz_J=3sr^vmz>NBR%PPfb9O0Rk`nvl-$y}Ws^#Ai9bx3s$famW&=E;m{` zqV{i>eyduNFAU*!Wg`y)mG>6diD^j}3v zU3eYBuje64@c@|VLio+gmV4u=FH0h*7oHHC+$6PEq^V7o#^u;!_T6VijArj0BNTxi z$jo1ajHLG7UE3UG--=u!JP#m;gOC6Z^{(s-2ob*jrObuv@Z_>%k@x-2{j1!X6-;jO zCw;s)ePef-Wcr_lV}-*0bQ{&*J%J66!sq!XP1E-zSCIJDZ&ak473EmlK=!gV;PT$D z9&~PN8VgzR9&!OnlV3EDZr&1X58ClSrYmkzX6RSLG)m83#h~1;!wbQP^f}`mlfok% z$_f5V{u)p!Zjc6IlKz>bs0Fej&Q}t}0$jGjYnjVSgl;b51QXnt68!YRb6{o!N&7`P zILk-m@R}~{N{{!Kb2(S(<&E;b?TCrUUgT?<+Z-3lyT+RtKRDf0AD49IsE{f%89|5E zLUb$$v3FD6YH>sPFxVP4?qRNMW<(Y}=Fg0y=rMsb))xaX)YK(OF!P@vxNb%gWP-n& z)W&GbD5wQ|CELySzgE@!P;*YJZE?}<;RXcIyV}9`fesn&rO{T7-IJg;KQvi=$S1jD zEYkV)Qb^SyYfs&>5|9FaL~B|!D_Zdw2u;aPb5!gu738>p%c&`LyLEdy(7g^RrZhta zi;l7BD|>l#X}`&3a>dm<&`e?UfP)4aYJ;i za8KdrGSJGg`8i*nFGcM#8VMBKby<9|$x5Z1bgEo$>bokP6)&pMfdpn0wmZ~ki|i@v zKVhD;0W__dS>LE#c7;36!I%Koc1`4}6s1u#)|Y67MJB!xy|`U4CRh4bSCiQVo_-Ni z&)d7D@p_L`nm5NLtpuB?UJqZD6gwu%Rw#NOo%gLar@sk!TCMyA+Gf?8v7_!|(JV1m zs*Dki5dYZoBqtqz#lEZ17Mww7D_&RfdmDrx|SC~f-bLF?rd z)lrNL@OJM3_;EE>e2AqXH&BY`(O-4DPa+%!M$ zxrEckKt>t>r|#Q7s^IiS*HX^UB-HE806*?Z^nsG5LMF<(ie{NGjQ5i5glKBJbnK5B z1CbQ}nuY2RbeGVjyE|^9x&O8GiHZ7LT4Fojjx;y(qaQ@IU9sVAg9t8&h2f#K3y=+t zfm8*67W=*7f66B0M%AP7Rt^Qn%LTQPy`%c1EXDgUi2 zetC@l+Cc^qPvuDa9~Wn17BlwIOyW(aOI_3oBD}pH!h_D;btB5JWN3l*1L9pR0GR7z zjKcM${_SpsS@x|q8NfdPqawt9B}@M!SrH<+IQRC;ET%ouC(ch2_UFHZS3gzjN1brb z_zhLqcfI6{n=p6WHCD%w7psme3uP#85X$)7p#10mf1WKDx`hx1kRyNxifL8Cc?NvE z$95ZZt^SC4tv>AP^Bu{~yW00-5(Fn(u7Fz+DZONm&>j2Bb(6vzTNrL z@|zj5V{L>CY~;=h3fXz7ZsL7>lLS?i{cJi_+p-5qe9&SNj)Uvk(Ak+V?VMn%H?O0Y z6NTyQys1Xb-sl5?5}*b}z-$gzs-t9PsLfNJ#CY*X6A8~&0dWeWh;|jt!H=7mT^#Ay zOLLDzUa>LT<9bb^AmT=M7Fj21wAZU@bVX&CKbcHyg}9=mR6Rk?FLi8S;>v!8c2EvU z)@=&jw3gQiQ#wvd%-efpZZG8_Jg-zz7GGQXeCoq;iWieSefNz>h3kjXGD@;3)QH?k zHkA5vj5Z@LPEAtH-X2{DI>NxY^@eO}iOO7QmlD6RL1AHOXDqpqIc{Y&4sBWNjIW(C zFg9O8mTTc$PWw`~wC+29t|^Uz_Ay%e%B{x6r1856Z~`Vfb&O2|U)WBg zp(?_3RV~cY@Khv}_FHqJ`zs2JoL4us4pCxB!76zZ{%>{!Tc!~)=Z5z2TSklkh2EYt z0H82}ZaepM2kyqs%J7}2w06-x%SN5;mEZ2GkFRqU5~;)p%{kRM1QBMzTnr_?JdJ-3 zqLAV1Ht8>vai9)+9rc~YpV_up?kJRn6}03t>zUz^R7lS928Tr{!dq)p_5zEDI+N`UTS- zl)5V4zM9On;?H5ThL>2~_C@L4-xc1=Jp$;-_}e~WMQ-j*%DFWRvGUT9I}WGM5ZNj)jA-R!c(NB*CGM74G8in}(^U8RN}o6QX}s0b z{a4Yc`7jzkFC+pm9N2N<6Lk#b#UU=C(sw*F%H2xt4o~@?{n)N4hw>`b2V{>rx|aM1 ze^6$0Dt!q8frVy1?=8|z!R0(IN?ib0zfwmC*@oCQQAWA^1OlYjm$R$&9j}6%waMei zJ7>~C)3W8!kw`jPg5kRvB?}^+OO7E+{6Nuq2K(7HlGQSTOkT4JzM60Aj@Jh9M6+Br zWbY`-a>%`~+|!El<;+d9uLk8tKhR8C$D3KR4EUp{6kMCUqNm{ReLbz;9U+47a-Y*o zd!e@Wx+caH1!s|fx}NepcZ@!5OhU#6S!Y4wp4YX}Tm3@5Jaj2=7lpN2j9GVF&1A)W zqb9#GLTAxTyH=8IP@c?Mvq9RzDxotBtIOr}s5X<^Nk&K07b^C9wd-Gxa$CcCKWfV* zwxwu^lwJfqe$YVpAT=4;F5Hx2R~M&K0FZLYHE_t0?Uf6(soTw3KMXZmsFuP7bEIZp zDX7FSAcur$H3iDczA|1Yr0KPbL#Ljz>&@r7W7C`DGJF1hA{RF-Fe25@Pb{L25xwqd zL-~U%Q`yFe5+aQ{H#YA32W2Xc2p(W6QRE{}-FaYadGhD*lp7ZA*G8IC*G9xkeaZi< zC867f(>z1Wg;Z>FjQlnULCrO4UVG@C;4o-t;@i}o(kDe0(%-l3Rw``R^VM9-Dz`ka zywo(6jdUlcW+I>(0|TEyF}A7JZG@tzCaQC%)amLGVzc9d%t}&F_~qiF2`k=vQFPx= zc9V}au~x`xryOsc**lyB^WimGvIEdzg8w zKaI#G{iX8hge_LDY;&RO(>Y~xnxmm=c5SVBIn25Vokk+u9?TL&?wqJ7)uld-b^OxKybf{}NheKl)H5bM33-JLl z8)rH?gE(|1B+9+$Bv4x^6%Ihy>^1-daC*;6cEUnTa<@9YTmkaf}ZzfM}^o@NE~e>Nmui_FUcV+R&{xIiGhF_(|4a$M;xE{3sO zs-(7Fjm7t@ghx(pkiEsOC(d<7C&|4MSd*xjhFPsYVx1Q=;M?n+F6cfgLbC9aYv0`8 z+Ta@&so8$3viZ(d*;N_f$aK1^1u>iq<&;dwY&RE?MFlc{C=`xpbIXd>VN~V?NxCN; z#!w{SJYSXbVgK>=v#xK?Udw$O+^cx)!NQNW!8EU)P)d_u7M!J{0gErTRR*?Yh{$}; z&XXRD*wND@*e-LhL>C=Lx7YzgBl4G{rNDCvreQ;hdE4ZWBsHmz{3P_`cg$LHSfX8f z!f-Y+Mr_otD4|oxARMvK4+C06By-W>zTnCcT{<{Ux-~-950mk=N>pu5}2J z{hy${CE(GP8(n38co!un;xHJqY^_QR4{+TIn~LA<`}%~tMU19=NH0(K7%WaYM?wfS z-hicUER;6NpoX#}aNJ`jt$;q*`nDE|o$T76yeo-zOZNSpX5|Yb0rG?s@r zS9LNql*Z===_Iv2R7vk+4vh6xBJFgs{WI?i31*uko~czxbCaA~e%aI!(3TA4P%oJO z0ivwgPuW6Z3v>#0+IH0ZKr1h48_4X;{LLS;oWGZ5v2j>&+YyW}Z9^h84>8eS_bOdYdQFZ&e~@F4DetmJwt${Rl)tTHUcKl_Yj^s# z4M8=*EoX^d8>`X~{@{tIk#R7Wg?<6c59Qf@^0(7!cJh{11y{wL?q2cPB#jTuSYI*Q zJ$gk<81AgL%nNY`oivg?ES0@s78XITuTQM)#W!T>sji_y--9Z*%_KScnkMu|WI2B3 zN}nHi9C*Rqyqqcz091BMumC$^!H!D1>BiGe(t(#NZ!uAyi6QSDYNcU)oo-^!wy-J? zze~4s;jY&Dpyhkgxj>s-XV3uRW1UE=MjDh~#=#e(Wu%LyHqR&AeWWq>2=7xwprB0q zN`)%74Th!rvx0AvXP1F!UVf^M(Y)@2l251%^>Q<|H}xNjm+0^C>QS`F>)}1COOdbH z=59J*Z4BWjwVH_>cB^KF5 z^uz{6(nXlvhacBDHFi&95j*WviDg+-k&9??ydv2`QdCZ`WN@Bkzwy;G$b~eNLJ}-g zrc3+!xmPfE{1Up5YV8KbO*<4?#9U_*CS*OQ2j}M> zY4)Fu&?4gY(}<2D@`GS+i_pG=#|x$0-XyKDt(~ytgjg$YD6SZX2})m-HFmZz$OU(o zkeK;4A&VE*D99?aKhEsBFXG0FO!Mw;-XZ03$kv-> zx@B}}))@l+j*{!vzn_&i16O`A?Jj2%-J+K0)?0a#?!Jwny26%oGo0c!i-IZ)q5N9A z{scj7+?R9Z2V~{lX*6XAdS*Hg?_*KDW_2S?F8)O78CBmL(=hwNnl*>hywXtEz#$H- zAlr<|jA@{LEK>8N+?)8mfcH;O_kwjZN#AbcPQ}Z)w~?Ac$pJj4mr`qBarJI7CsWjU z4^z>_pnAAP#<&hvE0joEN|Y>DIsSP5HE>Av~20-%9I-g-U?p;3ky z)xm#)79dOS3oHrgpnd$`()3fXDtV;Db=(594j*zeIjbE+F!V5GRk0W3;MW|{m;Iul z5cJFgrksaW3M6Z{Xx?C0!;GL2Jroad%0%w(a9~Rw zW01RcI|13A&MT5pO39{ga@wo*k8{YGk-EXE^@S6x!g%GYlGI1f{b`l72dN z=u^XyJ)479t2d8oqwgx*N-TTGc1)Q*C66|;W$CT$KLg0l$Xx<5fApeD){z%wHLceX49scb2cEm%16eg!bvyf2cJHa(jl<&+UW55ZVG{W2 zj2WtTM2MGT-T?dVXEpbs)V2k-*{qO*dg5HwW1F8)j=`!e_4Gx|zc#ucw*}^P@-vLu;i_YOMOch^i z*z>}pUD*1&qB^ylDsm9Y&X5Hag{ul+?hcKW-GywNfR9TzC7htUBnpb1PqS~I)xmGY z0b6(ioH_HYe_kfnnbqOqqMoERThjIlT%p+fg6dHdO@W@i_8gQuZbv)h8AgzOo`~U| zE=6lNoZroXpr$;SYiBF5L+X)kHfIGN2=m0!U?o%(xhou9v=5sxYkEP0!0(CFli)U* zvwWt{Tle!)$7>N*7pJHsbkJQ}aV>y#8!j-ndlOL_I+&-8!uy!XnmV1Ye-rqM$Pk5d z%{B=yZ}E=nv&GtZ1}~Y`1m9h-wVCwTW(&>O9*I+bkCxn;`b27P0g)eD=myM>|V$UE5}bEl4{78>x~617;juaKhJg6FzSfmo4`Vn}X9 zSFQuV4+`idu2P7c9IWb&OIt_hHKs-jHCgs;S=z1Qf=*Sd;I;+ zkz#m0QadWJjGYtBrLxA>de6$uZ%=ZwLN~a6Jr1NvFUxQG4I*)!I87oo^W_UvvNyxz zi{*poLU5Z|z}sG4Dzuy@z!Iw3BbGlVE>rx1FP+F0dqg*U0ODky{lGRmJsW$qsY9OU zC#e0B=*8}hTf^4|1tv8~Y8}%j#gGSmhx#v71)Dh*59lHQf?p@ibJdotrlcQ4&206H z+=6Ljx$|>-(9Ki>OQY!q>-3i84voHH(SF)XdXTE+kjVW*(@9Sy`>`ReK!vXzVu@9K z^X^aXEXNPMDcey_bj+$0a$oN%C5^&!sH~R)Y#X9FDXbY2VR?Q>k7MNU9nR6=mcyTo z(ao7j^U`{vIzyDIZ_k1WBCL^A4P%hd3*pQqr$%*?o->m13)yoOlF}c}%Q^kUj-7oD zF5(lEtZx^UFv)h23Z6H~tXjTT-re0qM$CKQoRsk^#TJebM!Zd6P2AJ=C(rtXBXPhy zbl$8j%}dna1y|?ANEot>uzFh1uXvxuGgkVDXL6@Qcs&qEt%1j1##^e89-I2O7Zj{_oT~6l^PMAvGpmmR^A}p zCQ%TCOZWYc?`SA_ET+Q8jU+H7GX%#3S6-AdqC4??J3HEYvd%To)Dv+ceLU#d>mw>; zr%RW*0t9DLGArlGYxNsg#1dJ_3a;RdwLc+8MwCj!i;3PG5e&`gn#FSG)_fPJsIg2m ze7{#q=bdpkj%F8rmVx2y%@>M8q-{}UK78SP0XB#n=lA=nz-BI35gsGwcqm_aEE$k3 z;h01hCGG(ZIGf=-C56oI>rTzq6c!1|>h|B%lve##+ zy>ix4wnz#$u0m&uE|YS7>!-*0GizEO1)QwK@?q9rhZ@0XC@eNpm&shuzaaXHW-an2 z6mJRkA8QNrgo|5&J+|}{=FloURWrAtda>C$=1E}+b}lAWa(KR<$z$VDDtccV0th^u zk3zci0iBG5K-w^q7z$~G#&fMGNRJ3HlX&$|#D?`@PB7*|B^Aa_BYejYJzwq01 zHhb`7=ib$IQxZ;hIa^HMRQ`~mC>iT(5e3(qK;JwdA)khXaEC1jb`V{zbv?EuvMJ_r z=Cv(moRE#5Z=Cz2fqO6VK0eY0M>pT~ri=&HaQ=1D%a~x~I6FLRZ0vDJyyds6xboc@ z<(+uWU3Ctvp&Y0JEh{zj1i#;2*kLhWU^APlvvKQ~Vw5l`t_Zq)W2Q*N)X52WwC)qr zxEwz+L-wz$ZfcBFsBE_rcq!C-5}hImZn7Kon6wcZuf3*=o+F+gmg&uP*Y|_L$`Mpp z+*ng34S`kb@^&bIRt7CR35>LZGy>Oec6V)G zEYULqnq*gYean$w3ZJE!_i+x==1L;D&{L&4E|QN|>*Kk8gEbWw>+-YGeJS`N^sy(P zD#b9xv6tW*P5_+sd2HUI&cO78V(q5w)7^*3iX226bBP>M!t7}b$RkOcD;G9tYA1+I zozzwZS*aM!ISv`xkJt~{Kd3ugFinK4zaKXI{ms(MnnX4mDq;e5tFZ25Ae z^M?Gf0#8(daLwe41*vCEyn~!_q`j%L7(81jc-M;PUzGIXa^c)xC!I8afKeMkuP0lE zx%y?ulE1%%r7IWZP}wtHEMgtS?Zm4#xek@6v$5t7g$XwFWE3AjdDhqQpguz1oyuR1 zyE7%Q92-~joc;)g8C2CL(fn(3jgU+CI?{#ki+y#l2-(5d}Hp*X)gU^hB1cISg38#L!|WtGxFM zmssfuc-x+A0P=#!WsvT_k-ok^!d;WZl*uo)`24#(efEoe zA$o&+eJLl@>0+85nTK|TLrmm;{A%xU^v?D4?`@yx>n`-t<=e2X_qcV}=5om%xYtg- zW6sH{zBsq>HhC_6!Eu&)Z$=_shLyfGE(b(av)Io^EbJc}+8eae8U%x>O`}cG)GAB+ za?5lX($jA&MCLUNFsSb4L1SmW^FO`8cT6RFGg=~%7i~(A13F+PU9&rD2=i!^LlePOUM>0$tCjIZpdr(Schepw@}u&auq`uq!C7C z2YNEvx8Jv(MNL-+;J+PEj@^uHB$Z*N{?##s#5I3-Fw>JJMl;>G@t#o8zKaJ3GS?vy zvFLKOCVHEwrWOv4?lJ&7&KrZ3zkK%p!`=aii13dU5dz~s{bLaYKuhnJJ`*yn8109k z?0Z=DD&{V>(uy4ioSh7P+&`4`Ou*0cBjgfiv)#FKWiR+Di~&Eb2;d`LLQB|J*FS}^ z-5pt0Wi^$bJEz0p5WBJSS!ceH3P2{Ky7jU>`%g)t{*uDh%UL&)^Y`;+w*)irTVQhW zB;DW6zSGSI9KKZZ02|#f{EsUl-G3{y@fSo;9biL`^j@OR82?!N)3vDIOD!7?1y4aC zr^k2g|FgAOw{k2l+)`!dvP@6>VtB7%tSvXI`2(810xDtF!R(M$Rna-HF=(d2{oMtf z$7Ke<2HxIDh=c-z{vNV9Fz?5|^Ww|nNw-)Ip;kjLu(p^YNUz8RxX#Rpm;9;XE0=*z zkF=~f_~y@DiF+V#YPv0#(6=Pag?NQH?V?fFIAZsSAxe665|lj&0CgSUU#~BC+&XkV zc5~kfqOHEJEpB`i?)AkMBCu5sm%3OGkyA3OcyNCZoj!BOE5XCqvH&Vvde`LgLi)wA ztZ!V<=**|9iDm3`Z`!7#@T?9`(|!9#?;Q~RyR8L9Z!?J;Kb4K7?oKDWa>10LXKe{o zrk|vr#tLdgO4_MdYGLQEEXb5_7xS||e`{*wUvQ3MD^*`|Q$bdB)u|r)CUSgnQ%>n3 zqzvE@U{sGw+iSL@f=b_B#TKxP0ZZBw9c%S?HP*zGmt)q}?s3*$ZDl;6pvKJI89k~g ztMiBVS{#u<0vo#0?aG3Fe5LJcuc`w1xF`r`Ui-t?7jz_J`l(a1`6Zr(P>by|#{;7L zUYxzWNxCrDcePJ~ditz;XsiM6G+^Xs*Ab?>r2FoX{sx93>A2r26zBxIqy4!wX&H53 zy9#_mMu5(<1Q3__pP%tL`uId^hP$&9kLYZebOb zI%)0xI!%NMy;bLU(`qQ_$FV}F6BW_k_-;~lat*q;%(s}o=(6Gf zph8WzCR10`uk%t0tThQ!%>>LGvU1hBfQ`)#=gsDXYee|&5M_tpe}GOdUqy|Q1{e~d;FEt5izYzuaM z^8_3l2RuO|{YkueD%q*VOC;=|b}Bdc@&Y2EkWE zEd?t#j+Z5^cG%FVg{-pr*q6QNOjoo(q_4tkiOLoio-X|c$vn3jCIPGc8;X#B%*Uaxh|qi z8)O`O;8udcaPMlSMhRfGl%5S@CvD1ctM$fot$*^a$#hvu$6c&7X%@TvM)Q;b5BUKI zTN*i@k3`t=X-~(VN=xX7LS4+}rb_T?h#V(Xu7`^s#B_X+;4p%YdH8VuitNmVs?XaI zX^m9Gzi4mf<($OC0h=-LK*vYeO`894xzka4J52NJR^pg8ej0!x2o-4b)1epMW+0sQ z8s0?YZL2YxX3vV7-aC_4WZT+PFO+4H9YWo=Pl9ynKis*p*wZC7-L!5&&CVY+V)VY&_7^y(AoMZW}dDrme{s1FtK%gHL@+UYgRbl?F@WEy^d zrWM8j@*Kg?wq82o{&Og!NI!rD7oq`%CaOG;Tj5`YFFxJHEFoN_fQbU*?^3Y+MXSNw zh5GhcEBq)55TNq4}d36JHWTgZzq-hBCO$` zq}%8HN4Zo+bpW^?518ZbL2_gQ+1^gjtgn#)yQy* zrA-?4iFh8_%ONpUDuXaToNIPdWAyo~3}_)sJZI?sO;-FjgQ?l?yJlvQYDb*kw%A{D z{^REp)h(gJACX)HsZYNlaM$2IiM@*4_`1u;DQSVmil3Ox1)_}8qPo7Xselm8x2qhT}y8uCmK z2vDRX$&i6kmJisIan2zW7J8B?X{sfrmzVa)mFznQi&ObWGb?e2k>|)<-KCDfWRK^4 z2h$JeTMM_DcXg>Gzm9U%JHqH@SxXIwHAcOSZesUDi4mAbgaGXw+&`YNWV`G(V}DAU zzxTrfK$Qc+3jY!{&cDth|0%Ek5tYt=XiNXAb_WvqQMUtfr;sJBGUG46E{>vv9sTl% zFG(20prC&kwaW(w?%r6$fcy~l2^>_W*wl>A`lloBiN~ zi!zU@XXIl9t``o%GY=S$Cy)rLBmZs4=?3o|P&v3|V^+e2J;J8Vd!}y%vVuMed>RMz zZ-0X5uf_n|g$N*OC87+B@M~}n&{v3I{h=%LniD>tv}&NVq2J?$ek58W;OHy-Jy&? z2GpXc5U&RTKO}&7#n5kqoB^l$6Cqbc2Y|utF)*rp0M{Sz$bTCW0H8PFi0Tdm1TQoB zyI}^t0S3wX_dksgFg)?sxGXye1^r$dL!je-6<_%GwbR|eM^bq`zF+MnK!(M!z*_oF zx1z`2hiTz2Tf6`ClKxjO?>}??fBl93?>+{9yG9w8_{WIMb5}DCf(LTrTqayAqNV;f z?zi7&ng6Nl|Mb@VU-f+Nk>=7>7(9;ii0j+)Q8*#c@8WC{u>LVD)B}}1D^pZKu0YIB zv~I0KmH-+J#M*r6^aOnPi-)oX4D`-h2f)0R9u2I|>aLXTzU4zk`hX=Iz|n~s!bke? z=j7lzuEXnVs!M=@Vh4QF4E~gu;g1psddEa5f-W`zHv^ak@f&mHPbH{R0s7@sb4f06 zc+~ALQVnbf0F+DJ0TdY>uYXN>MTAMIDOz#so%l=fi z`Wpu1uYWY`|4!Fs`3U0t(K4w&^+uUU=)b2tq|%-Jwuf6Q#QM0~ zrY{3c>?cIuD1zGDNkQ8MS)qT?g7{}8H~&xW`=|Zp|Ed?4xP=bbiW9f)<)4+AG}t_b z^oHx71CUM5*Y^r7Ir}X$_2)(Bj6xXJ1+1)SVV$ z&D%{s`eLD^tE)}ht+lwYsz!6$q9+ZvR1lj!$AKkB;ao*flYVA@uu|_s5P3qr+~DV} zhF-Kj*#gWYFN%g$5A0Q!kk*c=6sg&bhOP=31-h$UGC$$lN-1AHOkON5~pb< z8`%}Q7|x3JgX7%FgWxaes;0`$aWMDlAak)zQO}yQgsf~Lq61i#*Q^!ZoFVNz>x$o4 zj&pAEh|w{67an-y$SwXlWzI}3s>tGEX8Z+)&1YJr;jT|SKF+uAD5pl?B9pldM~*jE z>ka_dkc5>sa>cn1myw;2MCfzxhQ{Ue(uXVNENyEBy87CeZcKOhn_urCHRCY+c< zmM6|1Y8P4!(@C4Cv!~nQ5G1Y+Nglq@C7+es@XA*8d*F)hXq6IaX)^Jqa>DS$@m9ks zORPeT_Mwje#wOgegPE0ZWtb*NyXLtUM;Fetk3iMv4EIX2*6yM9v61==QpQ9LCqCI% z6s6!!N-x3n8QD$}ife*SGsCT`h!>qw&+d9ACV5zcxsb-^U6aKDVKHl`R1p$-#WCiE zC(rXU$?YlmF~l5?7we}VeTVZJqa)Cq{)#a-aUsX3KJdk`y=-Z_QtXlsD#%HoJe&*0+|Bb# zjXS?BmUeR^ui=#$1_J}OhSmHV{yk_N?0~wVP6lQiX=bF`Py2>M$K8+b>9-;KVW@rx zDSEQaR1p)iV~qpAbGE#4IgRvDoCSMpgTXP8ZA;-@_;8zE>Ybb zDw>aa0Z5=fZbJ_(w_7>HHNO~g$-auexVT_%+=m87WYqVnUcbd3c`x8GuKmJ)4K1q* ztJEd?rBy%TMGVEV7Y_IID5^Qz`|64A#avo7vjS4Jcu_*mNHN1+Jx(R_hMwe-j`1Dd ziZUeXyGfMa z^2ErA3>8BMlpY1#zT#LX_~6vT0VrYQH3GIUyZ z!(y$wY`NyTrXW5JF$Pex(k3lQLwEd;7Jjy&gspcwi?=5ik;brY-zRLwEP$g&uobUCai- z=}vXZW;Mk$-(X+6lB67a8}j5#x>;0G6 zb@l27hd%Be)2elmTp^zFkbIe9b8}3*E`wND#io=^Q>zDxe-FAyO(A_yb%<$I`mG4@ zM&&0N>!b2`L%v>AyBKU-_W zWiJjRA?WB!pTSB5sJi4SbvbB#xr4XrngY3@Wrm77)X4SyBpKL#hx%jt_lX)xKcfs7 z+>`sLvWZ;`2+KrHWnjBI=(v15^Wf(Oq)vzkkL3mTT=25{e8VkrY&j?BllB8Z1a&Lv zSGVbiZ&6zsaeo|(Qn2DHN#Fb3PV?{j|6jHL{F2>8ChA%`UL(45M8ticQCgLrJ=-uQ zxxZXjV?WuZRa~f*410bsra@gFu!<>ZSC5xeBLT8&FbP=0;uWtNx2lOCCAKoqP_r|j z>Gu&>9;^cgGTr5WR34F=G?bTx)yT_0AjOdDS|OzPaW<}d5o4@urspi zCEH;s&tqpt?(BRJ;qWvnE@!?Agd-^0Z7!41l*U&#({z5a`qe`mdr`&&tC9Pg1jyJm zRxVxZ=zKca(w;SG=amhk&dP&ppG%sko@#?YAV}A8oo@6iKfXx_hOZBpT3Jby81mzh z)aqX8d+3TX^Bh%`uISs;;Z}Q5he)I+$3v>XW>pJ_Wazl?7$(y)V3xzN&*v3G*u&Z5 z5V}*40ZOS5$>$c=9A|Y}pj?x0!8AyW)#6!vQREb%F_ zSxfv7Vl1+&z$>8nxPOZvH{aDBi@xL3?83e=G3$$r9WNVg3?mkeVPXFrvjq^eBS)h) zIrGO4!4T5vS?cF#$OMX!ijnlKhT%!#b+f&6J4oQqSA&%%Nd1D>3#phEQmRQ>A6Qw2k8}YgV&{t_j z2j5JoId{>#n9H(!`0w;P?MEDp3(Qu5FLS^5OLvILI{|D^SyCuyuy$N)sS6rdV60qcD~=mQUe-P% ze5y2gK#|)U-21n20$63pty1mNVM0k7^?HQv+VOt6H zS2((=o%9srp2#_}dS zjC)re+2wnfG&%|AaAL(6A3G=M$$US^U7I7yLECxNw=LF>>W}+6v4uL{Q2fusD~G0({OP& ztmzEu7h)9E#?&=0?dQa3V>~LragJ{l(M+Opc@pUIMi^pY(2p}=z7f8Cf(nJids;66 zyF0T@C;0dheCI$lT*2(nd4I_)_4ow#Fx_($T}I+b?!P8>&wpoF_}@1m%&0msEptTs z-QUwxcD3%Gk25!<4DCcdB`B8w8A3WZ0cW#tK78gEQ}Cn71j2pfy8KEF*wjV<_N<|N z_<8!N{!umpFInMw54_pBqRpj<#tWz6Nk5&23_&`gt|YC%TO~h1Nr1ue!x0ge_R>{ix4)~x(jo&O(+Dfn++di=YVH2)~y|Mg|gZxIImfeY;awdenNWrJV1 Ug8wi67|j{Y{^R3B{yF=90Xg;*H2?qr literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Top.JPG b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/SpeedyBee_F405_v4_Board_Top.JPG new file mode 100644 index 0000000000000000000000000000000000000000..020f1550e41eed28ecb0c4fa648fec6ef706944c GIT binary patch literal 146093 zcmeFY1zcQ9moK^rPLPB^u;2tj2oT&ocyPB6+=9C{5+qn70RjZ~V8PuTf?I-HaMupf zyq$BtoKI%%-1+9sy>I5tX?{gl^)6fgTD8`ywQApfygk_p9uUYcd zME{mYcZR*5|Bjye!Xo zS=cDR|7_2B*|~v#?Kc1r0c-$c;HLp{yL^|x+{wv~mzmkdk;%Z=*3g8>$kv+K&A^VC zh3Ppnz%S%xXJBMy;zVI+VrF3@KzGp4LPud?EI_BhA@^L)PRzvILdwIzM8!j1)yTuj zh{u>tNDvEy-;LMJ+Roa<$$-Mm`i+evubTkXZ@u$^`JX>CQwj1r7@P7czmWJ#4X`9Y z^_RK0y1FvCvN72@m@%{P@bEA{XJuw(Wdv(5I=b698MrapI8y(mgBK=_Mh+HsP8PN{ z6hAvOFtl}c5}aRs+;%4RKXa0wJ{LDYW_?wCT=g$1!g_a<{u@SG)&$-(= z{64&jiT(e()qZ0k_|tU$ojS1adj{+ler(|KzSe;rgc#_@^rW$zA`=;QFhPYhnXhwyvNFdpiq=0jS8x zD9A{tD99*isHkWd_wRx>1_nOPJo7n2&tH;9zUUHc*a0X z!OX_|l$Gu&!_%LgAfTe5VW4B+-Mx$V^bz5sr~mZlwiURKhNy>>hKN7~+_{f{cpu@m z6Ceizj>uq$@@JItFCTYCcR`u2{_uI`@RzW%ZCiOH$yuis{tS60`)uWxK_Z66(!W~yIA>Kzqres0E6;VPpuzx_s>W79W8l6$r zhEC0DnE!u>vOfs>D_t`HCL#j3c!>7_A>dLX^hx@i zsIf6(;7MlapXnbkKxU-KNx$Uu^S#0;*3J70Fgaxk@o1Qp3geF?zbP zl&(plohK*vUt;fvE;asW*(gf8_?9)C0Qcy-1-z4h1M`x*f0X!tKz@6kj(z^K^6!QJ zFDm~&&2;P&_NpEW*Nc1lFZjEST`>9wKdv``8*k9WDk<#i?5B47XK#HM=gF$RaD3VA ztQ>m)|M9bp2J*(>Eg)cg3p5Xsd9|EODO~N2pn8hiz4}XGbYtMxbHKF{to}#w&+30b z@t=i^dy@7t?)nPnTx>7eLF2SamVVP&BI_+s6uxK3cQt|%N0hy%n_2V7mv~F zZh;ch+WOb{VJpM;aPGovR@FJzH~Nf~?pZg4J%7~_VXZ-MWWKtbn=U-};`2RJ$U-R| zLgq|bnA!(OJBvje4Ww6zzJB^bsrb z7I|-AING{(LpF@CjhpQ+M=n{|2}jiJ8VOch@zv9#FOL%-ZPgrotC~=r-zIPw#CQ??**c#j-Z320j(2iipO>psj!m7MvAQH!uKpBv z!;A69cSran@Ww4nTMzL?{B`>@E{fEOpFCzcAF>*`veiptoMhmlt+zy9m3)>=aO`w> zusN1!qC|kd<5*Nk02Dk3B_C5lrMAAF)Smg5GMh7Z@)t8u#{uwi1d zA*qY%Z-s|eP2FR~u^$<^0|oa8gSHN3p~5YI&K&W0ywCnzR+b?e&5xzcpfcXj!M$}$ zQ4MriSUtw0X<#P{$e+$?yau!%v zCMfGv;FOmyJs?PcibZ@Ia?jg|_h^n?PV~~O-#fA7EMuIg9;CQpkc`r%B;!K_Ye<+Q zwqz#a`D-eRBQfN^#>pVc8$p_a9NnPaIFS!Ed|G~U3#?w^Ty6@bxT+!y!Lkl!y-6xHxdkrKOSxd)D{|_?%ll#0)=M|)mrwTkbH1>N;wr5RQLvdkT1}Gy zPDxokcftfNi{HCwkn|pBeURZi=L;_7S8I;z+n!k{aH|(gFu<(m%qnaQoUtpHw!k!U z{0!_plT>&)Dfg=Xs!iL|D#@p`K!0|Yx9KJ~gFDV7V-$p;4Yc>uREcQ$5 z_hmhU+@I6gq0cf;ay^gCHn@5bdK{AJ&%eZ0b|wIC@W zJQSpy^%%Wdt!xNKJ4|!b*%N{bX%}0rW6Z9L`DR^GRMMxKg7;mf_9|QeR!~`r@13U! zm6~!Ih#*&qlMdnuaoY!WzV|kA3h<7gzTnv!Br4@5qZn@#FR)~_5`5}SJ2bPkSNz7h z1PObVo3(dVn&#sYHh^y=eU$dqDGm3>^er%JZ*E?pvw&$+8xh=JB#9jG8kbKI6>^hN8mvy2e)$~H7wdOKc{yo_{U=K}Rd7etHjZKSxvX=6 zo;FY}rMagX{&5d!Ew=BDFYiGyes}pRH$LsLOg)(s#W4;BXt`9vF*;3kT#(Y_A-b{z z8db7Ac0sY*h2~gyv8zeW?5uY0j%AzivrQj0L+lZcSbuqBz~#O3mTsi~bdpf`ej}fK z{@nIMIpdn@^7+s120zYO9|AU{Jw%`C#d8iKtkU@NI^N$|HpWG`O9>*`xwS5}{XC{Irk*eD}@-tWvrrC_M zq76+`IMFy?YG^<_ZF9FS2x`jF_V!j;`!~v=C!xSl^YlwH+VM(RDdeuM{>lraYUIYd z-6z}9OW0?h8T^6{6i2*R+*e6?nUG0-}Z5z1gIkT(=g{sZzndob9{z zJfh2Yo-aA`hh|tooX+7a%yt{Qj&qEl=uZ_fc*b(dKZ2?vZkMDHeCF-iKBb*=3%qld zwU)Pf5p&;~sz@=WPOq=>K%kGtjJC>2;h`9vAN!5#t3<}eNp!Zr$1f8ZT8a4g1_7r@ zzfxGq>UKYimI2Nh1r^BGnq-{7=t4k`3e@r&5R1Nryp>B9g$eIzZSQ! zltGF0X$7>Wbfb9Tdu2&LnD8Wa&GIakVkae6)U({@v(;wRo|DNtX=Pi}8al2wspzz` zA8lrG$}ZJ~d|TF1H}%if(xxh%hkp<_3tb-7-U6d?!jFdHRv-jB!~(fFX3O5(v-6$h z-8!nko&YOLm*p#1l<5Vp(R@VsWZRz(4d;!@H0K=#gs;fEi-2Q?g}#jwzEvGL`)IFq`VEq`qt;kx+my}fGW z^3npR+TF2T^{GLh7Fb5Hs!D{t<=Yi_=XtvIe2y_MBcDX&Y;+9>v2^6*hL7uDu04!- z$p-aKcia-jN$wP+8{eC`P&sVWHw?E;d~@)kqC23_dh_d}C~T|T%KD)5A(BFk6Us!S z=vuCYYfh}fF71h zPmVor+I65!%T7i*MkQ#+I5txrkuJm*S$LSHDZ1TS1UK#a0(L+{ww%$*df;HAgt8#o&WBj6*3uy)K9thKdc}g8)Y(G+~1QnG^$DS&9yfYZ44R>(|&40t^MLbBnMJwegr^&DY+< z1R({tfbs!Nz!$P>=I_F!j~N{W36Ji|E=@N~lUq-{e;lkt=TG)%-?kGITKrlU7N9cj z#gWlfuw9s^@8-WQZPNJh&a=$!<4?TC3{S%^V};4W#NBg->hfS7+uaAEM{h36`&{w3 zT)4QXARMICi3AuJ@#K|WB@B6G1;&1%w4{3s6JMHGakq#h>d$$4eCm=9nBaVh6UKn>sufaS*w-iko`IObd%$ z4%=kR@zl}roJ@7rkEa@479;z{kFjmRB8>V z$As(+#VTU;Df@<;R_k)+2LoAj>Z0yQPJQ?pxjP=!6-BdEC9(E-7A%GACzdR4;$6D& zjpWl2`;4|iH_IfRAO?&)j%^?CG%J9)DmF~eHYDj+Yis@3@gOSC?wdut8?BVy-kbP-1yYNbHegNy!6TW~V6PHzgZffdUj>VO5MO2=Z!n=iwK^`fA#f`Cg1Gzt> zF_^T{EU(i&Mpp(%z$f)NfjQt4**y23Pm=Gpl2wg@4UyDCmHUzH#GXl^2}F*nfU-l* z>=qy&flP~B@6?w(9EJ;}gNKiRAJfjlj}AhGrgUyV>k!M<4YU(~%K_pJceP)BVjXNxQRhb@c=$i@&Gj*ScK~Y4Z>e5eneEBp$b-_flIH(C*)nvBu?FGdIw} zLzg)etA{q6AoS>J$c3^9KMHIKt@0EQcxLOx{7JU3i!dCGYTlL)A!6lKXkNiEb&~Tn zZ%Ooul$RuS(#3$YaeRG5PU0esxcqmwwyUK_{=BP6JN6*O(C7nxgW@gudXw)#(RsRe z`)HcO`aKg>y+ZQcXVCj>+bd6ZWJ4NlOZB8N!)*B}YeOw&Y0XS(+c~ z$f(w5y{AK^jy}-XGDjTdH(Gk4(;;6kx?STc=tUUvN}6t99jnJeAV{IgRonTkHb;Z@ z*Fn2cbfN%RKB*qMtDcyr-E1;X5MD`>O1YB;XBb+=RgdqF&34O7jRm+1bm-h^*$EI< z#Xsv?sZV;Th+-SO6hGU3Y0}hb{b*FH6H0=K|JwJS_lYV$qJ?X&8=XRRQxK@JI{jAd z)Dl=(HV!#P!1Z;Hmmsvz^V_}~tHyz3!QN22syuXl{4{@CS`@h69()WK!Z@c^dfJEu zig%fjJ2^vQ#3?$c9oxvNJT)TLN6yePM31E{SgD@$nX-HaJYy^mEM|q> zr-9+Su&}*{@$WE`+1D9rvF$vks>;qq~6K#yP{L<fvGTSzFCSQ@F>+4{K=8XZu63I*?O_3CZT=G$*|Hyz|5}Ew!;{ zizOwhuNcG__6Y3mapfvV^!CTPaV9h7CZT5`H)}i_K7) zj;tD=c{eq5-)-x0tMFsDY0C;}0`K_q&tNFY`kcq25E|0jT_X)py|a z#Cr`I_kR_VfMU@5fy!92b>T`Tbl5e=SuSmDb)F_@qFbaBg*@kJnz9l>d&FejD3&h1 zZdva(Gr~-6?R&GS(Bgb?IsMxfaVfBNHd&G4m$S+m%-7NTR$R505QEjpCvEI3u`MBG z@@OhP;!|}-Axin->AAW+rIEY)8^&*G)EMu=qo-+Wj==2^GP-Zee;=uyaUmjqQL~4w zDdPKEl-Iqxn$&*%wRB`bd6T)`u9{9bIh987B=}nJ0iSXF|pF{ zba1+54R7%v5B`?kFN9yfdyD+$LiUf|ovkh;$Kri?gkX}TP1K;ndh-@|>v1(EbhTgK zPmcil=-Yp9B6&?cy%2p1EILmq2|r5vRdRy-<++{-9>TE23{sgM&GgF*BOZ)A9#Hs* z11b|vrxT2gHGGS^9k@DS#Vrgp?xrl;x&TOg%1Tivyam*Ou(IO4({xj z;j40R53?hbi5r1iTiWdA8{{DA|IZ`jRZZ33NcDxV^H~m1&uJ|PTj}V4d{l&F^ z^3CZjFcN5?Zqo$nl3Y*}3!PF56Epl2jL|-um;Vs<_}dW3zm?ZYBDi)3mqBmw$5e`` zx&F}x^NlNHLzvj*m;sPuC@^VcGv7kedr%_SZCg1zbsj9R&&dCWF*f~jlAV&?6Xm75*r zX0nt^57Cbh8v8i*ycN`-snr3lz3&Id@Ciy=3Ql_{8{rO25mi=Pd7>%|i;8f4qC|Ot zUVlIX((v)&+6}@d7cz!14pPn?#h~w*6;8e^xvxxDRGBTsQe4W2`&pygS z5oHp807l(41%EvHCZLac8)b;6#1WBdp8}B*b$P+3LaO4IBPb>Z$5sd)Y4u# z+401L(r;7J;{^KP+Un3JigceT1EOu#==B}_q zVF&Pst`WDurul@>LDemQA+&7fwg?Z35QAUoALgQdeXr32Ijm^3z6HbtGeC(_dJ8;| zyavTJ31nnAAF^l#$3wfq{jDF!-}Y0JeXV$uw8JT3i~DMTJT-YtLb-^omzwkm;!YBM zS#1o5{irWhiZC*s(*HXBRn}-bCuTr;KDM0A-vTLs1!xujwhMpl#(()O;>z`HcRd+8 z-#tA1c@R(#_wp0!yakAp-^sWo-KaLaM%6`#-FtZp1g5OoUJ{+*TFi+h*_!C7IlolKvr zmd8speW{vAxX6X)v6Sc_;v9N< zB>$BGobWV+K)o+~3#6%l%%}7>dBy)JZEV-$Kcl{zwwr(R^&qG?+3Lf7x>m-ULZ8%$ z)}+uU*#Nx-GUMOhUI>bh`s0EFD%Rg=u&15}KhSkS&1wc(3K1eNe_bxaJh%txtttQ? zWVc)*l(4n?-2FV^g_zxV8T2{TJKQ9mR3utL)eeQ5Y;s{?ruZzdE2~T`l{VsoGZ1cC zmrRbbon(`Ul4iDwCBb0jHuYrEISq z^lPh~Ep3gR?y&IubMVnI|=ke#f{$=k%Ox$Lzx?8{NX*v|) zP>i71LNonWTZvm{$?qZ;$~}nvqD;}xn%eoCu;|;W)h$5a#=5HXa_({X$!CKx6=LJn z30#FT{5Ni#EBjKhon%zaQ_ohMqpcsmqn0$`K@n|i#xe5K;o?Rb&@(CbH&=d+GKFj1CnV<|mO{*sc3;zSkD;hqQ4T`_m}!@* zqucuIonlhgve}5ETyUV0r2(}IhDbpBFp62O5$UZd_+=xdkEfGpb zb8MxHi2-Q;vRC;=CGF4Bu}io)AdD{av#W^Y_3Q`K;K?Vg0djR}B}#rq58s5VUJ9H1 zAnv(_>wqFMOT0OM^b2DZ`>`pU0FHV|Jf2^|m|6d}hZj|4XXXR$dIATu`atTcp`@tC zb`^RpZr}2t`ROc7Qc}t(T;bCK{jn?a00t;3n-tR1v7n^aGNX-mt-`9gwBH7>XuXg) z766AwyPO_ueh!1K;1KJQ?~zpCr_-6F)G-i4AqV7+I;js1NE2NS3^|5=r z+s=l;a~DYQ-u96fjrw9X9N-V+|dEnrUMMx z>7p&(81_K7ui}eAR6qguf!|E2<&1iwD-9^B~A11Y+WGBSr~8sTxv@ z+Ug||Ry-A8FV1+_No}}S>Z__I^e-H7+1@6kzZOB_!WV#sa17w!f^HvlvXmT{>CjwQ zgl2IGiIPg2FwbIx073YPo~by*zwC3xWH!y-iIE~(x1BV1sl1g-LlV36<98Yx5PFek zO+6e-yc&^oheJ8}Y1qPrdGjw{F?dGTcGvN_leTgftHHWTgOH1NKX|;MJ}W^V|Fm6W zy!tKW{(BzA3W0i6sSnw#jb*FB_WnMZjb`0scy-fW*2R6Ok0;0tcBQfH!o!*%VUGFJ6MzFZ52H$LS1^ z6(RJNN;Xd09N6-!nB^rd+yWA#a!ntPX=mTT4K`jrN9ZGE8PPyr)}UX4kjynaWVAp+ zij9r`010$`v_UG4T9BQNoX#Rv=Vr3zZNVmfM{wfMrGTtrY5pnv;T&z1sKS--Yk2z9 zyj$?@*~&zMLfv84gs&_j(Vi=r7S4jwDL| z&gSzG<^OlihC17j%hr)*vK@j%1o)7V$oB9tbVEFC(CE-7Jc64LJ~Dyw1E;=JMAzx!fu6i+UEF$H zePg&5bj6YvI4un(u38N7vS**!>sXXw)XF+(HW5WzV;1(loGzdFdJ9;{og2ALB?pP+ zBi*35l_v93t_Z=zuSJsrgv}HfGu_(Sp4yKuhVC5*vXgdNTyi7AwB6mW1Kq1OC*n+K zN+Ro>sS1v3Og*BiYb)w%tLmdopEu(w3SO@ATux)H9AIk00=m!jZ3(cfu@eP4%Vzx6 zWvF<*=9TdUbM%vkdo1jRF;ECRpOo`5@Lqx7YfIbYR4$ZpA@40cBMBWW>f30a-S!*}|J;zZK%B%9GUTPsXU*P`CX5sK*--sw_Oy#P# zrPDL?_yEg`Ypk+~rt8zJn72DC{A|vc`HBI~(E|%>uP^m=eldN`?8vIq`2#y|J>XkQ zW6Rn!2frTAa5RZbcovz_cBuApGx4=l`O!kWvS|EeRXwzF7IDJG`3&{6WTpNKa%Lz! zppF`fe!LfKICvdsJ1w*Vt+R%oKqy~gJ4hP^v7Sgpr*99n317>J+!W-2ww46wK)I83 z3#=3-!1CYGbRbx4CA5a*(H>pLTiQ=a=_~l}}2(uzl%tZF$xc@tQbgAtiT9J2KDR zjHz#>D%>jo`k`zIam1CI9bw!wbfc7C>-+YDZ(AOmIfb&8qI1botx_Mt_vYpvwrw)V zN=`9y%yTfmA^P&>OL#fcbi~AR-1}3Ca6@0Fh9XOC300-Z55A}?7SZ!MU#=)?gCyYF zGDQ#yt2kJ}a0jW8(0uSMAlaj`=tk0^ViBp_P0ITM>aj5UfMhm`t?{`){Ye+#G&|8e zGEj>d*E=Nmp8p;3x}+*mx0Wx_>3ZX;_(Un$PFpI?ggm)gr8VbXZ>xhN4fEM!9r$J8 zB5rZX+1Fiuf!y9c`zJ})<<4ZHUI9nZ^W#XPQE1U7MTFNX_hBCV zFQ2Pwdgqy488}w#G=#369bnIkEDNESAL%s}|7cd{qF5_hr>A-5?c>w@EgeTGH$k!W zp`uPYUF>O*E#^+1*65d-km~94k`evcSa`0<)uP`vP6mFrxTkB$^~=NkT4R&3_4sWp zUb5s>%{nl|)T}_h`)LFV{Wc;L9S9#C ze<-3vnh!eEmxg*BpjdhY#aei>b=p{0U_^|v8%*>sy~Ph-ee5p8LW)L;gP*|_ zdfIzU&HRqiwf1u)HT~CGFGPRN)NmXmvJdH4jiYL%rPQCtOPEbDjcNjOUpGmq(X1Yq zsC2!0QWq>Xdca;tDk^ng^JeXYLg|7`^#*iiSoqCCJ%HU4J)t1!E6kR&@k@+V_JJ+u zyDIFL-czY9zfYhSAMCaN7=-!%d;Pazb$LgcEjz z9wj~KAC-j4*l&R!=lWkpP)WsIguW(0uCJKa&EcKnx4_0X2%GRDXM9kc8(Q1~C%Y|) zSyvB0uV-B>HOk7TWEDLIJ^IFB$7hXk+SUOxEmmePm@m-U3-A;h;k z@NWjIfqdf)I)_Yj(xQ)Tba~vHRyPIsq$_JDiRC1=vMNIFQTt(!C@gPn=`M!zo8`GF zKb%k8H}0#c9{$q7|4<-M1iSz%Gu9|{lVj$HH5ZeAOsVnx-5IGc>5hNWq6{pNZO-E0 zCV55TWuF!G!_W=$?YtWNF8P>Jd}rf`?_6>Xd~-P~Ligyx8i}kt^A(7<&k2U_v^N?1 zi_}_^o|ms46_esDLnE)P%uH>Gb-V@fXKiV-C~sy`8&nPqo2-`8+V!YA)T1r6{eo2{ zAEBI}VMdX^AZuQ4BHKTnRj9TKn+@4pRyvVputq%M*rJIk=Si+xah2=&m5Kd? z3h(MARvnRoQlrMy!)BWDlup+>oSFN!OBL(0*3MJC? z3=k%NY7W8G9k5BIm8SD_yo!+jx?3M`1gG4EJe@cagN3Od4)%@O?w$=kT#lDstE!aR z$IIwFxwG_Jy^MAxa5@0{ecYKbH2;p-~!ne)pjf)IYnPcTPZz3vLF z7M2B_lq2rT^Gjl&BQumu_~B`>^1+MA;wnZ?Bdoznf2lc-OK%*R%f(hQe$b7c!8lm) zOrs27DwbZSJtO<%NesK-fV`M?Cdb|$wbT|EnAPocGvR-}pY4h|<}0|EQ%ZNJ(4$A9 z8_B0|e{an8(w6Q5m)sOio>8jm?^a@ZWx=GRg4Uwmf|0*tg4vAW{6MDA;v6Rt*~tJi9)Z^xf4?j}5(GHTk}F~IZ4 zbavdDo${rEB_2H-Z=GR4OQfAF!3)!I@E|{^$%IZ!4{-|O9g&Cb=T78C#PEFV<2YM& zHUM&P6Ir z)rF6(`(itI{}4Q_Gz}j?kd#qXj~ADkXeh(@ltmLef^mtsoYuzuY&A^tD4c;~0Bcn9 zdB6Ck{$x`<25=0$d(C+y6s9Vhv-O>^BEZqktMZy{`mj`fT*wsG7-wyyAJum)ZG|@b zqlRPuX#t*r>QgFA0OgL~b)eCl+oyIOOcx9L{N6m|H<_$P+a5lZo$d$MY&Ah%jSzE7 z@TA_<1c_&$Q@%-FK2EHR@KK9}DR1A?IC*6?uHSi?d7O$jF)!dMf%82n!pl2PGy>f<%clHK1NEU;^2e^`Uxh4(6vjea2+o^|YH`U0SyF1?=!9$1(QV2T(Sw<{X|*my1Z#)jZ_9MLbJ{&v6HArwD7)Y;=~)sA z8;V$|9%ahzN-b!&;eXcZ)$(EW5PwlNE!uJ4Q6V9D{_7>d6*l<~Sp6-~(hc3^hHR|t zz(H64IG*}jqO`Aepce0%zJYVZmVA92(^f96Z~x{;qz)-VK?$Ub++lWmu~!9gpqV}$ z5j8Hg>LqYDKyri7Nbs8Z&#EYcqCN5GCzi1IPNI9Axv0Y zz9r}#DD82OFJ8Z=EiJX&c0iR`eBR_#vQ(d5ljRsJZuyqsp2J+Gpe!`QZ&LqJ zWmcksciReqh*|vsf|D0I^^jc$?6U_LGt+o$H|`c@%jcZzYd@RA)^3-%Lq;F1Y8$J; z2Q8rze)=U9XI$r%w>CX|u?5ux$koydKtenTwMhZjTShcR~x zL-tMeYz$~dDa2i7>L?|IFVzEw{Z9wNcEa*aC!T3<)yzqnxEV&8?tiJ}PhB&tWcR+S zFv7SVARVxKBuAIjOBh80*uxNn3CZy#db=pM%&l{cHRgr}8nrntn6JmK?=?aUItK)?wR4}2?X`lVGV(tOYB zkl3%8^V-O|NN!Tj0QN_E{q6#o{G|{sEI{e#5jjVF8**GBxiI(w5&SBa{19WOMZZ{a z)JcaNXUigQOYsM1@0b4Ujd+?=pIl%58v@fTX5SxZ&SehoW_KlT=*Z<@3S;&9gpgj_ z_7Ar}dJB9crur5rdnU9@MZ6IUM#>PZ&-J;4j)z@#jiv>*E@sq9vg}Pb#@GbH;a*6b z&#z?GE)TnXc^2=(csEq11V?ihZbD}j!*wi=^4C`$^B^mjb}Ods*HrQ82Jt~i+*k?k z8-;S!zYr(HK%xK`ia%*+s}-;37(sZ;Qrl9}DL*4P&wL|=rQc0^71!^@-#Sv7@g9;V z{z>nqlDv_IjRomOu>>cVp|FTirR~zRAiwI0<9pm}zBJwEy65blcu`s@%T5OY<#Csm zu428STVPT$Z&uPxQbEWw4s}jKec`1~m_e@QpqZIXfi-)%%n_LeE6X!r zmsNo*E{r_z8NWc5C8~Vtb2~@@K9vYu9p}{v%L{Mc2(uKww-k+x zL><9;Oy9P!4 zUW%YPuGx2rZac?=Xx+Ud#O2b!Z=ZqMv3GPe2bskrkYH`B`jD3K^{SUYTpSlF+6Zzd z_9DO0U`*E?!c*LrM>FQyUv(Ku`P)+Z>RMCQuf2YB848S1la|3W6hPg1lnk$ji0BGN zWOig~H$J@Js-c{<_nZx2!v)V^X9g|85XH>rYccn+G6z*^98;@C=G}XVUKq5tTG5YG6G%?kPu%dwTm1Iw} zl|-D|eJRdFYB&p@jy%G~O=9R4P=i?&ZY>ZYS6SF*aSI1f8@mY#$AQ)?ekS03@S?>Zp{HDJA<9@TJrMb=M*MeakaB?|EWnWSS zMW{pYtJfi?O8XtLd!dJmL2yz9JTKvK_HTZi-@lCGoZqvdKI&%Jef^O85KvP(1r$-) zRv4~??z$7$e;Ji^X6+&^vTFR&Gb)*5rU`Qqu+oj+>6(`F=685tZAA4x2!HPwln9>V zUW|xtd0kwo49z5a#q-5Z+0@@vQL!j4=rT(BPZa#mfH=E>3q3cJYYRViB}pW!M^DN! z!;wXNg)n>=C~fvDtM6|EgQ()QO1)s@L%ql$yDT^&fPPbCM;I$?wZ-I}H(89*%fm7OYdsQDFadUZxHiDBNe6WO((N0?6`=giZKxChBh#+SP<&m>-g>%s)>)IMlcHjB z@M?gs@GRX7-`2w3sZ&RUCL3b!s17M}7W#2m3p!I6zU}fqu*#q5qK(MENtU+{nOvdp z=M9K#(QW}RHdK3oejSCI3d<8K(|g&wQz?Vgauw}=(^^Mzg5L#=+9TZBzYu$}Qe-xPx)$aA9t*ebBlx2^3u0{f-nJDUJ)sQ`6_$K)M zN+GNTw>S%(hTZ|#;rP&ZEmEj|ST9Hkx&WEL9uX8^(~<=310A@DRhpwmCr{M5g|wx8 z2=t2H7*0knl0S`mjea==nVD#S=-YWdbX@#P+o!*`9R+1()(ZK}oxPSryjvi`aQM;G zG_DAXNet(c4gs`cC??GEqO%6K=z;t5cGN@$Tw%I&#HmX6aODR5kfvDDU(JhuZ%+OX zGm{2!Dqn>M+`R>SX382Rmy#E8zJ|5AFlAs>_4{L(Wn8L0n~HUjy}SzE)lz{INOlTc zBG23cOZ1?xo1akM;1 zBXVQf#*$9=2QK}~{Xa+2sf_xb6@P|Zs(tURp;etz8x(?>GZTR39wQ(8n*0cK-?ZNx z1Z}Jg%G`J9B|TJueiT1nATH%OtYk1P2j98#6s1 z(l{h#|HSgdO$67@55cZ+Y+0 z9FS=*y32xfXqm&+-uX# zZ__=!eyUDdV`D6oKe7L=W!VQd4EHXA9O8oqg})=VD1x@9(_>WV^@B>Qi(H3?9Ar6A z{CNv9j4N&}=Llt;o}KT)E8YwGyTwdto@?<&?S2zUJK$~X-xwTx zqi~Qb$bLRu^J&WHswo%Z<3~8o?29=b3pvYJhTZKtAF4PSjuY%ddM*sfEz3|Nx#*2ZueHJ=JLtsL83FKr65!whR;3zP+?hU8b zwgY2s1|h$#?U}>sH2;GGVKUdFjaIa1P$X$(x8tobUYql7WT%b5@zkJJWZJP*Wa~aR=#A)hj!Fr9cs<=a!*1s$xguRN$+(hI#FPrg z8fT595!$8TpRm#KeCLi^9je+Z=BJd!QZCiyNnKq$@ zSf3^*x=I)J*o;_<1qah&rbypqf8LmSB)a!{N4>FO z3HuZ1AI6p|{8$w@-Y)Qdxd$HjDofbE%uCvuW~yv}@EMg+EsogYY4N9*il}L89;4Aa zdW+u}hiTDH;7eJ%E{iAa%vVb)h;Mt(vZ$vTTFPc2!)PrBev)7JS~lM5U$mxUKcJop zhidP`d%*jN{8XR~fJ|-#p1@M?Ll*D&a=(OXvkF)>T#?pXABMqUc;1n-a5r&Ktz!Vo ztODk}XC()}Mo~KFv;DD5aC7+Nzt(V3dlUiwXlCg>B=lCAKcRs)0b3gCrdH9W&uW@rLV zBd8&81}~%mkW|;@vQ((1rUM+Hvr9t`h8 zfn>@}?CBo_>OU`HN+CdVya90FD4(@Ea9iZRU6d;Y(*2i+oPT{ScqUsWJtq588O_wl z4dhyMi02mA-f=DBk^1#u3Wz{N^OZ+=Je@DQe)^gc;~YS|-rn_I!vd)1fVFyZ!LW@Y zR16#W5Bf0k3D?rsCM_{WZ}{6LlZgC4M5mSDD7^j;+XtS zz?SadlZKG_mmaEFJpaRx|C6-;q{07ZW>bgt8v+qNqc4)U?0yE(Zfk$VZ3zdt{#yH} zG7cE1DrpCi>q^;Zh9amjM{ejG1?Y%1+sZRu*-%mw@VP3#ns~`%4Boz+62B4}d9X;_ zYCu&p&T60_YLb$nax7e}74>+_8=8EXh1jQ67%8^dV;NgQl!%n~C=Kw%`p51YL?dpr z&)iRU-8PBN_sz?DF8is!zQZ)zf7py3|l+3t(#|4 z)FcRoncfg4bX+&>f^^8$!y%OX94No0=}yP#AR znbeN&Z$!q$&^up0!O_Y_*OtuJ0QmzyK9kDi1a_?2kCo&rQ z94Y!QGJPHaHe8+Bq0@{l$0p}Mi;LQ?kYdW)^JkBo)vq9JdhCl}Lpe~LM;9j+T$wBE z2H#)9K6=m;O3V~L)u4#ro!|^}{9d|I38cHdi-2~!La z{iAV|!xV35F!JDeVwnZCkFoD%}m5SV-IkJY|4Bzf%uo^zw9s0f&UvMKD zDK5?f#7v)Q=r#!r$!0_ae>8si&}GfFgt~qCn9E}M>?m!h3B5b1YUyh{zILt3P~T2F z(<L4VsmZfY`Ok)Xi{dXeIoUbi%H(FirNcgG#BFcgfC1m-+gCWLrAI&i%S7F1 z<;U^jUj@&z7kjR!!+BqcX)|+YGKwm%_|R^4%thXL@w!rDM(`}kqZ)Eie$W8q)8C+w z*muBYvajFLwi+(141Dbc+>NADC=BC()9~qXe2Hzhb=pG!{nQFeu_Y>T?8ZrZWB>#H z;eNW@+@z2+a!hr0iW3X#sGmpG0#cbbcP{$*0D!l5&7Hl{-F;0P)>+zD%<=M?$(JKU z$Rz6_pRPx(y~AR0TPB4;Q*1QVmkDMf2hRldj|V()iluc9LxOkUcE5b6C@#zTojH1w z&iE{kTR{A`>g7+|jzO#qj-JkyEwu=JuwA^4w-4>1> z>hkeZp8;bz#W%2Dg?&4<@NiFZu;2C%QKQ^2(buuRN~!roPK5_-R_-k+w!ko3_ah(8 z-RWLUAuU5l5D;ep6Z%txHPONgC|U>z~GouK%(s1Z;?5IzhnnyR=~AvN{7iQ)zt( zZF7pT1#X49Lf`Ed6eyPK10}m2ua_;4)hoQ<3Fm${VRb6}F|yB@Tfn>Bo^(zuZd|2& zeNDdX=RV8>LFi)jC?!yl&|9ZmM9CZaV+(%)0;N1}dlX^wX^*9a&-4 z=4z;pavr4o7|ZXJOYhzigDSBT>JF*0Hsz)q?2TAJuUR&>!S#}DIr|A^ z5rMy(%B+;R6%;^f-Zk{zF;8M?e!UeDKq}oew4B1bJU|KdK`IrI77-l@Z%cN(z`2FkvFgJ9QWYAM?T!_SH_wuaQZ=-vxGq&>^d zg`j}&o;_^W14Sz;VC-DQG-_aJH^(2(&C-3)@jVtrsHL@N$wI9HV`Ix);=Uc!s~G=P zZn(&%cehO*Z`)NI0*ZKL?8gz6E=36gj^Ud-@H&Q-V_8%>0YC`38w z+Od7=M}NDAbH&|Oah57ziiKQNtWIR0UJVpZ32S`?CPENZi8gh~C4*#W4;A*d(QFLn z?oyr!E8v^NAYt_tp2WlV5<9x}p=_=#tGMCq;Hb<))}fw$e}7(V`#GL-(T%HZ$$f6o zB*uu+KKkUlb73<_paO%`bg@a|f(%Zf)wiT=%9QlNmJdiK+5H((LL`RR_Gg-(UQrXz2g(^M4E12h5^J zfAYS7UG?vH{Xe*UTxi!Y{nR(x^tt#O=_-NBE3sqA@Nw|3Pc6@wn!>1$!fz#N$Kzl6 zb?ej+^YzwXR&?Bx4Lwr;s&vqJRd(N0BjMrf*^|#4bGNpt(1J>n-bD8p>)|I2Bhyz@BAwgTB-_&o2yy33_Rr=m(d?&49H?7tp)eyEt}<@q!u#yQ zti*azb#|pb=in&Vh2e25S7%I4A2{_N&z1&=P#2iCI#~&L@BT07CNom|NQ;V(rM* z|6w*8u_V#?s@hYV`*;;N$>+E8{HrcZCFvsU_ABf-)R@{*EKxgAl@}V(-~=*(`pkf3ZFfoKD?l0H!f%}%tM}f04(BD*@|c+&zJQ4b;qan4Wf15_5`E`CjrNq z-pbaN#{T5Dmv_YbR);M|LBvA-{Jmx{%a}A~c7*ToYa_;-P=}7#9YyG{may7pi)zkP zqqXs<&qJsr|&>* z)%weT_AJ~EijW)j)>M{iWWwiSURhGFDgA_}{sRt?jd&+iT}|kTv2ENWmDOWr4EsX5 zci-BbUx6oUMoPf6`VWkDrih;`%M@8ans?}Dc}QF9LQ9q}g4DsvOK^+1oRWO&O&v%r zdeul6kM*LK3+$d&&eKj+!f$0vOb|DViV%^iih%5BL%(d? z#OujoYPnFE@u|6&7UcBn-%zLJRNC_kXj1>JNe*(8&E1ELbi?Fdv^xBp8)s4)L0fVvhf2JClcPrxe*Zh=$XK-JrIai?x=^UAuY&4^JgdRaiKsRp~c&U6ERQ7Rv0lrWuXJ{XlSz zGXfel#vpHPIb;zr5n*B~=FjWc!B=Y0)z?dVZ%5ef!ok(d<~3M6q`#^L+R$UYdUISW zo~B~2ueP11x=y3g0Hh&hUn;Y3GYs~Xmu_V8zvSGIrztWnKxG zuvInmB80PIOqsj^G$RiCJ|g0JOk15kdU8~2)eaql@C%KW8%(~;;`Gw?5KeQlynlc1 z%j2up=yhj#r z39}%6v&KTYnfA`DyVy|@GmCDX$C<6zIC;?1CpJ&lz=CLOejuz_C9+ZA`TLOL;iucx z$jiDtr`p@RkLFYKrwbT{LvVv7^Xr$nFXNL`7Jj0;J1+2q(Yv5%vh6rLG|uup)v9Q? z)nBub64SnGn_I9+Rwv;4++aEJ6aXe`^POj?o9 z4o^iW$;QuVewlRsE@q@1N|SOVH~*C~=((q9W$TB#R2r_@g5e}SLHI)haf_A4Aq0_> zlZGgl65)2&N7OZ7@JKXfwYx;=U;4=&SWm4Jk$!(O+fH~tA}-@x-gBQ2&d!o7V_rfV z>A@Wkt##WDbw&R^z2(e-8eQ6iKR(W?o3!2EcWU@z`i=07mDthRYL1-`&j#iF-=GOz z*eR{*Zj|`P8jeAL6D<7!&D1q1X()wVXSw*Wy()AJ$dvg_#|Iw$2ASlAP#|<97HrPX z^8=_&=<~xZP87l1(AMb@aNz1E6GJ|t_dAM@dP{-_(v}Txwlp!XO+pN}OARe{bC)ci zK*(D^f5P9qun}Bks507)_j}|lAFiw)-^cwdi}PpVceG0f3ni?1_F6x4Fk2)PZ-fTmQW``NuWVkA*#gn%7t*x9XU!L3U!78?obYrQ~_ud97 zN8~muS+0pyH8LJce(h6fEb$CkXr~E^P&2U+$L6qz(d#6OcUM+(fPCn5k1N;NCc`N{ z8*G_pgOfG}e{^}8$=D@J3E@@Jj{C?_Z*gLA(C0PNYs(s0;6GNEig(ksG`EO(ozs(` z(@O=uETm}eZmRMqahJ?JD9kyNjcQh>$DbDm?`oKSwa zZUhe6)mO`!S`S*8Q2PZdZZKjCFXS#|h4|wOG#M{5Peb10s9BO({t(j~V zd?=t5-0!1B1E1eU8dyvd&)IyzIZXB#ZKoKri_ZIn>rOWzrP4m*7 z{wW0n)Ck@x9fMJw4Z8$pQN|xihw!^o<^d6FXTs^=#8yOyeF2ebbW&MlP#Lo%sIrA7R*{4-~P5SWYj9RAv{UfiNPF%&;rtVDJMH3@K z^u>0I6*cIW`<6&9M&nPhVVZfQu{S^x!W$E*%bd7xO-&Sj!sgU)L~2mglnCm;|TsP-h8R zfTzGW-B;s|@(kBNz|Rffwpj+2zdtXl2VeaaOXb#8%=OlOxJ=DOQc)r7}(pq|KM<=0s17zO8G6n2kNAOE@u z*|}9mjKj6wOeIhoPwXuZl{KIzW>ZEMq<(fKXkE-Hfwmj4=&P8HRk^_`s&;`gKG|}| zi`L(u_~^71$sHjl-myOwi&;Fr%-ouiE~PWlc4l@T&%qaO&?6o+iSN*e5f@Ti8W0H8%PyMXXz`$iHgurOR=} z9|oaajiFC9($a^xDJcXFtuQ`)|IThz@GyEeY4Gx!Pj&O-x=^=g`dl4ZBGKQ|)(zZU zf9cLN%ID6QClopx7ruyZyM6YB<^jum*+|LQqZ0k4jUB`bi;uP5H?-L6<&f4cZv{IR z$^ysb;-OpvlX*kVIfp6NNf=88+oA4VdiX)eV9K0rLn}W^B zvUu<}-WvVQSO0&)f&UvJ!GHaKOdWCg|H^ytA}1RF-~5f&0IeOcTY987Q4L_!XG_e* z$x6u5_GYF2?u%Z%V;sN}G+qWG>=iyni3E9tEi)H?Dh!qrvu*%N0+e_12?3g1NW)zu z5M34)uz!m!%5)wj4s4m{44nn(B{|)-bP5-7yj+FjC zM?w9MSxCoJQ(yjHTBmcprxv ze+aI<0%t6MG1s6AE#}3XY_ub{lJ~;oimhKzUyPv)dEKm^1C(|YUgC{ML`|D{7N<91 ztc#^!Hy4xB57(z9LLs1=$T!nGhfggyc7&w*^yc4k73JoZQ3jvp@v`HId%DzAS15e& z$-1{OTdL(DbZS2iuz&U#;3G?Feho_Q>(I}J>rz?aoyfepFx;JL+HG5|#0aXAonn8I zwM{IF^~8Yanq$p}r*%K>RzElYnPjfz7G9sRqxB1_U+XZYFsKi+gPNNZt!S!(3Rl)K zX|X)OM4Xh3#g!sot;GhLIl)1MrMfV_wRI6))k1KXY|Beg?@) zZg2owVe$A8VNLedIT?M(+;;WueaYA%?cqYs^~k!SVzU*DfJy=e)oGSh0mL(fJ=lXm zcj_>hx$8H&$|LK-H+a<6bp}2KDJ^86Q`i^kXQx0lorRTePFFD(ENjkx{I2Fy`Fgtd zIyK9+$kLT8FpFEs(QX4m8L0xxt>U^y?W#7#AHJ)N*;vt7q$@8oHCEq7vsIjc^CWK_ z^2~o>-3(jT#|5MBh!$4r-eGk2m07N^5*yM!_6QATQ+mHzc2ROK1T-=2C7SQ%aI;rm zT=ymN)vt9rs)9uvgFiud;0OD+D7?-{qs`P5tt^th=Day$FBc#}t231QlU*XKt|3z)Yfd3|$I-IpX}_r}#C$ZKP39x5 zFAl%>)SmH#?YO2i5r3E|Qzq|3ca##D2k}S+J#D+RokWo%OcD(6bV_TZtSDqg_pH@~P#={RX%o8kDdg^9+ z((d}S+ohMq!Ou8eEQnGXPg0ws?E;^UlhK0ieL+?oZ>B|I2Bq0Nk7tVUjU|qeH5-Hk zB3k<8Tc{ZeVbFbQkIky&iHWMh{+_rvhPV_-XVA1Raa*xMhDO4>sxLk3d}Z_d(Gd2w zCJ3!DRR)yyQ=7HP;(n~QrzJFRZy>F5JLw?71UJjW>8AhHZ8Y;6efmg2O2PYT$Xy|g zfL#5Tfnt-q9iimpJvEHs(va>3C(6R)8@iR7Js<5GnQ!Y>hYbRq9#pZ223_6Uai?8o z-8<<;nR#}0u94QwOG23?-gy~3reTHX0L!CHI4#X^rv|@uuHH^DPSxP&fr3)0Djg!# z84q5^T>S^ zT>MNo9I`L6+PpIGM!Vm2W|2b)E*FVV+`|VhL2Z9KHYJdx&W|) z#yT-|vdc=UKM!87P8C}e1SvSHl4qY&9IAarOWo|?|=foE3+e9#m;&g%89q=!l^#SS`CbtM)_{#r}A z+emp*Y$_}smG-jxE`?d2?DMj-EAa;yAvy!APRWJV>^iaUBE04x*!=`$Cso1E(IY;S z(N66?t8vpct-EUSp9j%ukWOuo3 zZXt@t_N6a68!k^3#tA$#f<0QtOpV*aUL(dVUdM2ojB8N|S_E;vKhkKCTlw*smVJYW z{SMP~@Wa$iNd-lB*3rtG|Qb4__nicE_XO!yQ#FWa%EFE-LAyXkz-FES2Oh>ohTG7JDjg(l) zNsy&KjPs@zo1{Q1dvc8Wypwv}j2r5mYbnG+=924VwNdF{eIRk5pS@OyHf#_WYdFbz zz;i=R!k&6pEMKuu`4J2cyjafZ@z=%RXi$h?fPg{hb|rD8RadNK3!vs*|RDl&+!l6cLC z9k=FLA@dAuoS^(QqSI5sejj}>S?&+E1lCIFL-qI}Et92p z`ObhLYeq@FYtYXgP?i6|d`oB7fyeO=myU}tp#qz|e3EXEV)4;UD+$R}^ zixw8tBC+G^Y4jnsS=_}FkuP~B7T(YBg*jpPNLzXfia_$;B!%d@d32g6#gOt$!V=2F z&c2_JNUq3ui%8}dDG%i=2RY-|^Xf}%bvE%2TJ~s>2DMx$>G=@Gtvt?bXuQ$c$%nDz zZeTqQlg4<>JwMmazay1Kf%t88 zIrN7qPV=Hfx?yAYjAl-nzric@ey9#f>*gI=em_?Zh6RbYJ&dt?H+CC;8#%Y_QIL~U zz9DS;!e8!gHn|R*V`f37aMxwfHwHP-m(%UYis>-6KSiIIwrRnw!V&#ZKXIljTqvwH zryZE~{>^8!7&P#B5`yj9RW=9N~H;4Sk6=qrKnJlVLo_7jH_%V>R z*w{m9Xcz)h=PiJ!m_4fb0>7nS!SdFX_mY3wo^ey2u~Q_9w*}o*dgwMUhine3nbS-D zsP}mP`|VLp#`&q}?yAtpDDR?Dds33&)^v=H9s}|PA}E9M(K!#=xpWI6oV_EymnsMC zgjP7CHekR}!dtzY_DVy<0~XF>%50K93v~(M_>%V`#0xepg@~*p{OKlt9#B>bBv+gZ zb>2S2S*$+@kIXkHye*t?f|Fi4>U@U$fNH4b@6ltzX#L+}LQC8V?KF@4Zt8cUSFcQq zUjfCPDjVHzgO7hYiuliqutL4-$4PJA3Y?t~-$J?7kU>F}=5Om$D@^W1YJUPpZTPay zY}?Jm+l?s*-(7834=qQ2*kk7JL~)Ka5@$AN6v{_rk`UaU@L#CG4E!3WJJTxJQp_W5 z5yBeH$@j6ob@hC`{xn(GR(1Gfr}^askUQ6HjM;J7(z?wPC2+du%X-<;>5Ae;63mrk z&#)eMJ_55a&dOX~l!VHSYAPN@*8tUl)~E6c7Aj6s0ecsvym%PVs%^-M%mJlV7{h(!^xg`iin%X5(GgY}LO{yz3 zu|M2@Ka5X4?6`$--P`?8O$_VO-b)-wG@7e$KIf5~&pi@{K>H2)KDQt9O2f0PuYmLO-y;y%$rHTOLaCwc-;4i? z0%6H%WF?kc{H|T8SVHIJ!ck?022iRbm^KQJCZ*Tj7;DsuBU1qIq%_87; z4YU9ZWws4~_w)^RSO7XOFCpK*fSsJM-<`?K9{|4AhT+YQuW%A`;EnU&?^Zs)X}P*e zKwYQfZiFD3mt6ti4`4PgtNrUq|4;J&q20gBkL7K@tN*+Hg|4qBOzSM3*BY&BI+X23 z%7GUCFjxF{-s}JDk%AJl2rA#9g>V86s!`o5cfTN)d|#m{4f6ak1ACOE)EaZ zoJ?Pl&=pi9{h^=fcyydX@t$MXft%LMJ~$p4Re6`DvD5c>_=~#N%+y;f75gYWc#|h} zB+ti5FEG zI%DKG?a3`474;NdS+d%Ri*Mh`Gk$a(G5pKdBFdBlg++Hs0wio3HLSI%?b{&-RqTY4 zMOLV>ks=#R@3Flr>Iloh+=%SbYF$rOnxRLk2btU;X8#)%9~swkG1{7y2`e=%qKInHme&>gQnd8VfU5+dJj3@ZX&UHENb@X^I>*qrN~SMEv4{E7%av5s|iblcvG z=&%537eApp=3pSkb{m!iT)}Wsj8IhDcIZ*~aVol>9IKqLrm9`XOLZVK)fhPVRf(zM zqhY8rPZkp|#V_n>^`jMO`(oL(cxYpcXDak-S(FUYlvp@eUxvZFwja-Z)z=F8_^B}d+iqVo?f1(}F?&=*<8&?&ob58$aplc#5Zt-Q z?%?cUT#y$48;S-h_b?w5kG9-IU zrTf);whss&>+iUVp;@_cjqfZE)f0JaG(MU+@`g_WP@se&OZg=;(FleWe>25#0M}Ci zz<+3J;W$9}XgC)(-8OBELo9tKSir?s&q6V7<%EsI z!QSf$lfq9u5Gv*s>MK%S>g!9(eH0Oe_73=L6dY#<}HSRmM38;_To2N&qT&`<7toTGVi-*9!S$t?9X8s7Q6BR z`aNp^09>q+LHMvL70xHcVh1 zmCBsl^r3IyGsLef%*O6|8Bp3JyVygm-08s(&0Tu$Wxvx(U9rB1@DI1XwoUDL`4sU~ zx{xKYXVi&4$jF*^qJ?QVq>hVOB}FS)CWVY%jOC4?D}lMi;bP8!BOn{DSHd;W8bH;= zJfB1!x>|qLSbHN8bd`iW3_>wXRJDX%*y-yhRMrHpzyI=Z0>p7uw&M+*Ba_qWTN=vA ztU7T2x;hY&R4dyk>J$A+ov8d5-UW`=M~|c%V%=C29kA!0?XshMp{rRFcb3Q7f{grY zgz7~=3rUY3e`uWVZNvaaQVs?NEj%wf)0h6{%}jR+8_)|8#Y?)jcI>UB1GLw$km5_= z0g#w~D)S*JoO*b?LZc zAz617xv=3iL*Ve57jnJ5>jX}j zbgH#qc#dz!oeKdg!KHqjx_oXym$jFhgG%RVTH@(1P4)sVw|@0H*%|pv^SpySLHWX_ z&v_SGKZkF+=gNN=R(eq%nWhc~^FFp>wZXVpd0uDO{hk1Aw0#xpPJ+G4yqR!njNVy=P`9{V zZihftWE&UB=#yS=^C9)u3tpF3V!2DcLUVoP(;u3VMEP0W1fhJ1rIj(9y#008LQQOv!`1 zDDxuR!4{z*TclG0{XG&);R9N~ULD5jt+#|VkGm6qk0PL>?&bGS=*#EwW5Z%oL5J@y z+sr0yibWXAUTE_^`Pk$v(rKQ%xmo7;nfizcG&91RjeHoD^p$Vyr!6yolnE_Y7w-MU zJ@Pz^D$_-`^7Sg_LQ!<_`YEwCl>Wr%Ks1dQm$AySd!Y2|?J>Cdb+#tiK~847RjE`C zx!XuSB5qX!ggZ0DOpWlo0E&uFH3FT{;dNz<9(rjahB36 zs*ZZ&6?*Rfn+=7Q1}mJO;ec=*JI^#VSE-_&L19-2h7D#cWuxnqUgOw}(%T58CJrIP zOGq(bMt*L|p+1V$1uV|TFu9F9P+6OwQaWimZo=PgWZ#y#rJDjm|80h2b?p=(T%)yA zISSH4d37%8r06VmTy6wt<3PQMf-O)QL4OBePCh3squk`LHF>2#PA&hG3`V@H0RS}5 zP;rCGuPNF8DH9;&|GO5BY5?;%K)A@;a(k3;3b6M6(VKl+Z;}9Q?7x3N5>zOY*hO8P zl%*Sl=lGfup!EN{rvE1O^=8h062P5gxWc^PAY=a@6nZehq0&cMf6pB(uK3?iNXcwB zRptMvw$k6`g~?OFV`}FE5gEU6z~Tssw|C?*_M;s<0<Th_4Q|l8=mfJDS|>xgt4cvwf)O)Mj@{)WNAt7oBfc{ zxmw-prmxiGSoo4)CvQP#Xo?jD9d6VIO1sagWl%;-4q1C zs}tc+CV-2iBruhHB7aOV>N2g{R673J4h`o#V~^VpReR8u!9koo&xcyT0< zC;G2=anDPbBSAAk2+0CZv~bWncZzFGImjtE&K)N_FxeJy=`1R7jCxpG8}p<(-M$h% zHmz7eEEzW~k7L5QKe8;@x%N{Q>xLqErmrH}*`Sy8TXvr0w|@a*a*)kUd~xl>KQ&mvi{(IHLWpd^6=F1LmonLu-7ZMwezbGftbg98tu!TL12UlXt z)(X66$tc?81~mpRHs(LFs*ns{-A+AQl(}%a`(9-@)unQgGZ5*vL>{-1czmDy`@V87 zgD-Pn(*#c};!e;RtKmvxUpu4jJ&~-hz^1KEt}DVVSvCo(uX5lJMf$nuSNn5H%@XnM zVh4Hl`i;*eO}qv_3TmXo_Suf{kwQy*-~*rK2G<(i(Oa>m&w7^C8?WhORtKaQ;wd7) zLI@}JE4&%NApG$5o^&(w!$Zz&rUpe^NT>HpL#3p!Ot)_lNV7U1uzp-(*3GZniTIWo z-Rk~Lomd30Ym z6wG0!e#wBfd6B`Xa;-F%Hb4arv%_chQX_!D#%(LvkGAc?x8y(28>x9sZLcgmB& zSEXFpxVKZ27M@bI@cdou?h%ywdb4nS$Yw`SuN_KFE==tRFGtH3dr{IeOJ{L;p(p_n zhR{o+!(H@PDLs>|td$5CJWNvPcAblQMLS_skrU*!J}`3?%PaE0nXo1Vf5jj4}VS4>S$aJ7BuUiI#FnusueElG5w zv+|;IC7Dz8G|P{#2-Ie%ZHeO2CM zn~zwkv5#JEC|3a=zzPk`#8pjBe0eZn*HuG87kEDg z=pG(H*afN9ode0CXsaA*Bv;$xK`r5LX%c4NG$4S@&lna#ZP z2&%hi$HA>avtbN?j?ngba=i%}9PUFzptEt_jT=m`ReEdN@R7%Lj6yJpp63h8{&HZB zKe7$VK=Owej~y_?JX&J>-b>~u-N7OtR$I)GXju3oxv5hnSD3?58rlGRbZIPAITqU~ zRFd^zDc`2%F>58}h;AVT+lsrbms8&Jqv~Yq^m&Lg{~QpqP`4^#qoHGJD~vD#~dP{oKlJk5!R@E>0y`g`#E()vi>7d85S>axrYYGgoo8|m{y zyj`}>iWShp<|W9M7JKMqUWmkY(>bN%lJjUP=b3BR{?e*~5^yeAToixEe{NM6JK%u# z)>r&mlO5T*Ayg=@UAl zUfonLAMzg)wEhfRF+aIO-tNX+x|)yP3XT`s7SBQ;M6x+=KN8tI5=);}7w_G1Fh^$- zeK{<1G*IsnYgMY-ecw+Y%9RPm1u1dpZy(>Ke#E073aOf4-P_Ntu^^^WL;CjDdb^2r zOxubBd(a35J#_~bR4bkmrZ7=?2a%?$(dCcRZc?5ORGrTex*k?X!akibd(KOZ9k6|Y zzFHG>!t6tS6Mo2&_1x)U{m4NU<{n165o0A<&rjsTzDFuJP^C#0XZm;LbD<2e8`O&? zh);Wt8ea6q9&EhUt{T-);bI+U=PE1WK!VrNg~peqTs~FfLC$*2rBt87`Ft6-g|dZ) z5^(N{9J>ix_vM4bY&h)uQf1^eZ(+8)oj@FT7{7mgcPd7#lfm-SORa0P)T*f%NH1NQ zDx_!2{&M7AYVNMy`m}#$nqI?XF+d{RwXv^Ee?vba#pI94>F>)0aCCRTL)`~bPMZ3JIG0WKJ=@d~3;xb=_8H0N3zgyCI(8>knXC>BX z94d~x@f6DT1#@#d)gDemZ5yYuAKukryzl>b{%Z>VyO%+bh?#gS0EXIrItC2`BTU@h zeKhN968H_OHuB}EvL)EAms-)5KTj^~)?blybTeZK6> zV-jrsx2xz!g_=u3qeZqqDwVxG=^LzS`S`+xT9+c)eP!&pLxO%rzPfa^c`x{t{-^l& z+a;^SI}4ze#Vh;LJ&U)(k-j!Y8YBK|%twaFnoS1`|*iZu-}`|3$G$O&IRL>bX?DFF?v+z5zv_Z`w7ojtInLKTVtnc zSRg|>2@qpQ)ArZ8bX{?+^gBi){M;W}==fMrGRzDvx0z)O6nQi2$j&6o4lcNuiI5PP zK901q6D=&i^qp^}zKl8;zLh@^-n>)*sn`Y!5hewEgJVC9rbx&)9kdD)5R4t6dfdgF zFQffLh{NPVlz0#ARQZAR^U$B;+APrXkENWC%8vIRhZz-KQhvKd&)|O6v3=wKTOdGF z?YO8(@R&+Nq%f`T(>Kec9_)Zy9@M|5Y!2%Pz^Hkd%-){zr|VcpJ>wqxS5sCA@&s;X z7b8f!_oIz(`QUTgPS%&lKF=qL=*Pz-M@?|cnKmc=qL_=!)KvyvV?L%!_45^2v^=>X z)<0_MYH}wvXFZVWY*Z=(ODS;U25fS9V&{?U%1nK}vaBj*$B9sDeES zQClFcc-j7y3NeT8b9bq#iJkG_RMTDkmhRr z2KCBK!S+aj>{f=7x)^D3qtCOrVp-hlfZ1AFl*i*lN1!@v{%Qn6G8@V#bdXw8ueahx z636gBu5<_JauV@ta%Y|AIsOWJNX&u}O?8YMae89b+MQg$FhXA+MBqxGyo^l8J^x2% zi@r!%W3sdwy|7PRJFe%#u;IJuyE9oFkz4(=rsEXDUaz+^t7Oa4hJk5U=$(9T_+17 zI_3EH>3EKYqDhdhqK`E)qifM&ld}D$5kt@$VaoS&I~p3xv-2W7+BBPXYZMW6B2){L z%;YyI4wTZY^3ZuYoLAnyk4U^1vwgIREl#1z*~Lw}k8uhJPih>3@=33eA)9-y2A8Ji zV~lGu)wY!+G7E7+)E#!vSVF1sm;?yGUI5x@Q%upZneWVjrS1-%akIiEmtfQ1m#@*_ zf=Jg}&lzv(tB_MD(D@+kY?B{|0}pxq)1R+DZu#<^^e?v^Xo!{cm)|}}fM%;O20shU zvdz&^aOF_h5J;eVwc`_)CxW$-X~%=L;(g!v))IDqd0s2UNq^xkZJ+FIX@{h>nF}pu z?!>evj}SxPtv;fmfqYSs#Al8SaaiI?lYZFAoV`cnQnw-TI7#D+QFOM7Buzfu`(H;) z=1%k5n-L^M2UtBn)!g55L0UHncc~vgdt3#6s?U@a>wGL9wl2^4>zWG3sJ3)4tv=2cCDkknC(kZh6`@)R zD$8DXHVx`?)cII3cPZ8?lOvOFH9>!p=~fd*LY2b3tGcs9IeB>23ozC=+?N+kPq~Ma z70I4T0MFRfQ~KNpsc7HMUDg*oaZb#n;qPdpW-XT~!4;a?D1>h(DNN;CShG%)iAB@- z8V>gNMhCnT5Ydcd!TwrI6t1qo)_ZHTPbc)D#Z6cJDM$U2Ql>2MOZ!%V(-J-BBD_oa zAc1isfO#}9@>0J04jtIrTEZn-Ck_JkpDtS-L?Y7go<}>B$x&kn`}nNXQ{u3ll3Prn zcKWQJesGo1Ciq4Y0itvl6^B0u;&ZjI5kB^tOAEZvQZao#iu3*|H9K{qgCsl)B9DN; zv|P)Cs2w3vj$wS;n4iOf-ABL?C)XMX;n_E3Gz$yzdw&on_-mu__z>_84vZ6rMiO7XOoye?mpmlfY#;?R=DP_m~{9yC5_Dcq@`p2<*G zj$hK*d|;dA8aZ;KVRjx-2DCbv?7joieh7WBDF)1+6Z#4qJ|E5qXLrPC75F=dd+DAo zziwmvpwb$={)l7sI^-m6pVb%@P#AfG0Ah-=WTAj+W+vJ44 zj-Nw4vQ6Hn8x*|%(DZOi$!eVUijBB!R1&U0Fqb>$Dp@tTXw)spJTJ;TWaB(2F$Cs1 z6pwk-+qI3JH#{+^bomy%LrHyi%X3#iJdwLdx%_$27-{-_j4Sg?9g7_XMw1o{U&KS? z+&~tZ(M)p4eL_e7^LwS>Z8Q8YmDwcU)jxr&IFe;_Eq!+>nF2D zZQd&=%36C>bG=$55wB$wG2|dJCWjJHgm&m*I}h{v?*-qZdaSMBA;~XVZo{@(;w6Vg_)fL z-RWMpVtk7_udl>;_vo(BTFoIqN3jCgU$Pa|>3OpQ5xk1*zZEzuvZi@sh`HN0kn!!s+~c*|yC9E~ z-=NF4oWDUFKn(Q|k@c^Mry9kW*t8zq)$z29{IxI0V^+mdK47AqBog6{q3`V#$IOF^gNXTT)wdPuD&i8%Z_kA7%=3u4?;&+AqBV(5d;My_2eeo^%^W=(?KzWuH z`rC%p)PMxMf-svfZ}VcCQi>ivMrZQO#%BSRtjNX#saHF^ulI|e`{#PBYyye&fb&37 z=fI)w&oQ3|@{UV+&1?waSy?;q_3{b-;;lDr>r>T8ZY)&n;GA#kcxc6;W-$luEAm;D zydl`w->4l&zf9;;9uQiQ2Suv@9OV@NuKNadaaQ~jIEv5RaQ&prGx=G-zcq2 zdpbZ1dv}4p62+jCYVRRl5L0$(_7W}xIqssGSG--JbgjF$S*RasEN-+WO<#Ak8kDz9 zcQcca!77(xEW&oqD#|(9m}w*RvgDb`{H)#_vi1G8lN(mXqX4~UE`m};IMZcl6+Fbs zB8?4|wd!aUVX>7mqXvcc3oL6l)wR`4=FVL$ptgiqzCC~vGd3z4HS`%V+)3uU^~H81 zF0h^VcT}1$ByP3FNl7L5CiggtWZ5)9?h^bx0>eHbtQCUYAc2m38%^q*)CCP2(5-7} zXbfDSPgzian;$Q|@``dz!=6n={G)V(fS5LK*T^GoNi4722+}d7oU?88CV_OJe=ltE zgIEbSH(YL?*PeH+Hsf`0v~aKR3}^5u_`X~XlW-k1q_)qNDkf>@R>-j(ncalytWL1G z_WWr77uL@#(=h%#+S+f6pf>Kvc=;r`cpYmGF)QxQt$+Sg`pP`*6N(1<=nnRv(8P(sw2y-}Lot$1 z{(iMsndk_@TW7%$jrTg=~Y8VH{J?`>V}X2hk;cswZobroA?5ErTu{ztU+B@ko( zuL6m{=l_=1N*3$=)Z#ID9gyBK1Z+cef$*IljdXd-t@LU2nQE$b`OgS`qo{(NR#Zs* z`HmIMLagNY$=dIfF_@#&_1yqo*cU;Y^^u*vD{vnh`Y;xQI40DVF3}32CB$vH;_?mB zF7;z{fR-BUOud+@xsJpRMLOp7T5>@g@d>iX0hNlJoDa{cz=W@1--$K)t`C*QJ?<^6 z4173=b)g(Tn%>Wl)g5u8sf0Z>~15RH@t$=H>v^9LcGV?U!mw3+nd-d4FN91^WT4 zE;%2bpAL|>D~!s0v&5oW6j_fw6r{TO-Eq6(n=tvK`$JARj-^A{F4eVSkGQ=j&C9~? z-2Uq(rpWrfCpgmn55bx3hdEXCWf?%^%<9Q#5-J0EAgA6_aUp|E^Ax{dszS>xGn zu+t>NwohcotIedETin1IKTevl{ON1OY2Ibd=H5zE}`ua7X@ z*|~>x9?^|hnYnwK7R0yC?33_2#Uf|8xi7`x-$UZYwWhQ z5FC&kYF1p6GMcT!ysF#+62S1)&vMc!z(TzYc6up4aIrk!|1DfRrsfa@DZ_g@{((y@ zD|&^Mp@)%FO;%AB%UN3Z5C8Tjot>fm62`QAEZdg#1Vn+S-=g3SUt_`2 zJU4q!ye5N{WOM?M1^G{J%(Y%V*l}(2QS|u^eTm*xxYBNW$7#3V5YOb+jU4%jH|7OUmHumx4lmZ_Hd9aykyHqWqsiC*pbil znZd7a5*g5QvT1Dnu%+1|enwt*xys%vnI29Q1D#tYsgtG4@s4u?Q)yqvRE)T0&;-+* z^H*<~*GN7Sd6=AwPRq_AXm`-*7HcZas{tdmCmn08k}y)ra}>x56R(HCVD z8WX^dkJcGu>!F*Pk`jM5sK+Elu5m5|Wj4Jo%6SKg{9EkbKbXxr~; z?%ez?kW@dXKj1)-U1J}&`q+!nbqv|m&5@TF^OU`BrrS^Gh$&)KLPbsms^>4fZxLlq zShGoVpEEPx0{!Z!DfAN>e4CkPB6W+1jlVxl+UOeB&0to~{0YN2?q0&Hq#})*Xr3f& z|AR(C#qD}Bv#|U5*23d4a)Tzp(Ovat)Q>IIse6=3og+0g{LX)*8rDdz{z@W*anu)d z?^kr@sqhHc^LR$SD`MEF|H?M*r@cx_+UmQM{G&SL>}~$Ll*Hkq*N!xuucaegDKj#? zbGB0h;&{ge=1M1%UGa~nGw0JXE;p(MOWtRQd~3UoN>1jSnIGt^&VTQb$?X%DaKMG2 zy2Z7M`+2lt^uVSj*4AS|C)dgSS+m0@{M%LUcTAT!OcND3UB0<&lQyk+>@LlcQUBr0BeITD>|;mLX!@;(4TPxcDt}< z7jhKm@=jj}GqXU+Ha@3xl(LdD#rzSMl1uM9;G_Y<5+Z7wRayICF;< z%{l{{uluAzf{*4S-z%MUnh&kE5a`?1Fk4S7eYvuK;gfo?)M$;7i`1RJc1&0DFR7OYPC`R2O}liZ3T`qVIl)6y*^W z?wsC579?(zB^J%i0H33O)>z6oboJLsy9bN&Cu>RY4;c!a#-98j5=-hnKI> zfUoe982Ev0g61BPe3)l!+j6hbm#M^5xHO7^U1x#JX4Y;ap$&kbIgzlbhk%hg&NbbNNOR|ZL6BO49+^%`ezWo9{<1Pc#gEIzI07h;`T}wHOv;`Q$EBP|%^CP9&>@rl+iIb(Pp60|2Gi`ia-4 zYT@{PfYi_;GUb&n7OBdHLZ+0&@571_tVh+!c?-Hb7s#y!Uw`p=w)-|arJb2hn#iWe zmP_#XW(kVnjMqmyGq6&*4sM<)gW}61USc6^2s0NrnAY;~YTFB-REb^K+r?HeG)nCv13rpuOtOKAPxdcV6-W=4KL0cVozVU=@%>K1J!|(4h zNK&i|ihJvTPYk(S#RU7yV{T(m`OJi9AQRV1Sf>bm1%3N=sLJj5AcWci?Z zlKb2_jak2~7T|Q`X#`V+o-fV)JlBrf*>&x!qe#cIZu*ZK z9|UKYFCx^dn?HIKmXQFFg`a8x%wCm`%(IMw9YfcEKXjLrOzfXF9DaUY(2NW+DEnrk zr3Wq#@-{E?>V!0fPnr;U=^(8esW>%Sbnd@6^uVW~1rodD)sLcE@}`>(^7G~lW?6A< zO>DI}vqU-J=BQoc?kruKB|DK+JELAx_KoyriL1Mj-M{TmS1I=)bUI&N;EwTxfVSsB zZM7(xe3`t7fyel)tG)`8&}mjj9Yu9jQnO#oo5ty!A#U4eQpUubZBz-fww}a<{m!M0 zZ)YK5t-Ia%t{D#d0S zd(oo!+eT{1l3ES16Y0_NT~t2)rPqenDw)$OO=GLIHhyD|bi@YlZ!+j)h6X&m%{KBC^>R`3EOF=5xt7v7DyR-mkmkGI` z-d??&qd(mUsB=b&$M!LO!K8`cG+EeJn(l|;EJcH3Kf~~W8h=s_)OoqPo z(<^r4<4aD!9$uPj97R_mjVpe@`?@N~h`vqX7m89YqVXp7gqSJqp6^mS>vi&Gz488r zl|Iw?8dY}+hjilWk5-i^4{S4VAbFD1s1G*_B-HSeM}dr3tmm>cLrR8fSWof>bSuj1 z#~nwJZTI;&W0%dNTvV_ia0IEBrZ$SF!}iDw;5;#KeL72FK3-lHEXkkaB_~{qs_Ln4 z>e5uG^s9z#=Xx+r0HVkAcKUlPgO5@JQkco6kx@nXHzo@peJrGSXow$K;wWp3$z*bn z_cK75@?*=i$%=5#&hj!Vh9S6CIe{%VL^0biv(U* z6d(YIgDnc<6|WEyKThP!GiP;O?-HColTJ(r5Sq#4+y0oFb5K{Eo%yrV_5P=M1FNAW z!d{)z)0mzgKzWNo%V8?0f(NuY%73!~AbQKEqJIK9xO^Dt?e1~9k z>|qwVu%SGYivi{tD&~`I>e~|l$U926h0WChi@G`52G~n?l`-qxw>QkI^5-GcSHu1q zEyqB1FiShep9OF~ZT`pT0L1nmjnSO?CKr65!|6X_1C`HO27`7I|H4ZA_V1D8&t*f= z*Rnv8@g(TKH2yC~ew!VPabwm(piBQ(&ogG9i2o$(Iv=)f)&1|GM*hb{$NcA{#9XRY zwj3D37Rxb0FdI`?I{pOrUs&8C|DMs9y$I5)(+JE}DeOO+wz=p3h2^sPXK(oDyh<0F zTSF!%tJW;O)~Sv9xRF(Nn^4pbEfncR^PzChspi-3`3d!v+aLg z9LzAVJByS4pL`{g2)UtF91C|NGxB9kVgE5fB|e_vZu3fOG7lSFUd-!3=$jMOyOs;t zX$A~6+I7MkB1D2I2)Ii(|D;R;=tj87F<6-NpDqtLAJ#+FjcEeV+F@K7lrlzfBO7xH zyQV2VO#tjM1Lo`V2*8%2T(JUm7>BCxMm&6#P%uNyT7LR{wxD9=Z9l%%K~?Yyj8XT} zW!)i?-`zQ~f)$IxH+A@EF{~7=QdrfQWwY?STGwLd)9Gey*%K|G2)drPtRsLY&hjYg zMD8^X&M{~nk%~6K|mUaTiK0{Rkz3a9@d1+F4^H*=DbOBpE^Tdf2ne2e6Ua zoA{L{B_YHixt36Or!|EI{?&eP`ZsYPK^->;?i$tj3cmz&zH(NuMSn)woJPYc^$mF;h=BdvFw_!ZFQ{L^kiZf zg|ydPcLkL!DoZCj6FCug7JiZOK;CeF(8MdElZpMog#Bn_fup0%Q{|_IM`n9)6$Eba%7sp^03-^Vr5Mbg0v8 z{ytkAT-24Bvhkt3i^Bq^UeKOE;#H6}O?Md-hN1imE228k?@we_5H9s{bJdpt_S+N; zJ`eU+baw9dn;-HKpy^f;uyqWj^Be5$O!i2oqSi1l{&fVVZSQ7T{&Eu@(g2ExYFP0o z^7nuN#Ygpfh0COkN}n%f4-GLg(+~2 zA`xHh$sP2s)fT1U1hac+LI+cCa|aZcE*y~~F!v_a>yGTjY7N}er>QBp=GV7cH{W)D zvsCd?YIctlYVS?PhN+}Wj~m6HU(I|W$14L)92K2EJd6gS8=%9v?_gF|k2W!E=5c>v z84+VSY*C+229T8-q=-;Q;NXb%?D!W;k5~wN1NNZ95ClWjWgVNiHaxv6?C!?=ovRGj zr)GH1KLWm4+oB|_BT!l#me=Iv`fI|)L3dl5C2qIHz8t7)VlH2U{g}XAU;i>(FYika zEYt2D&w5X{jn$<2mLo_>JLv1E`PExGKgGs8Z%1XgJa;<-slnGk(1$fB8`GnOT~9z% zt{6c-0^k^E*3`eSrhl`{?v41Die7~ut~xbC=j|VX9yU|<`s^W1*Uc%K7 zGForWq-|!@@RS>Qs83ia^^4^5mEma744ov~Mgz7;m%)?VhnK1GQ-By1oJ}VhOhrM?S}A8S zy{=$d>$wK`I`T3`Z-RdlWt=SClxtI?A4$C8Q3utQ%eK({LAq+f|C?U-@fIVhXP;P2AsTPps-FFv3jeF#3mnDdSbAjE9>zas6Fi?*wvEA4St%~qG zIJr=yuPsA5h;lN1_H51vN8qup`ak*=83!}}rOsHPWxw=rZi)b(a@J4lUB3JqYnecT96jx^CEWIok*>30$4K0HTzk%O3oqFPM6wHtSw_YWOZjD)XrD3NT^) zVdCK%Z$$QR?ttH_;fmw3Lv8fs&(qr__j(;jh$5R5_i`5!Y`K3($^UA`J-R*o#B*3h zf49E2&S-Bm;rQeiPL+clGl?HRU*`LATW1;0q)v;l&z7P~lZ%0l_6cnwN#`mIW(!iK z-|i#*1))ktW+SU{`UmW$X~ZeL=#u1Jt$oj$vvLIM^bs-lulR4^ebB=Njbo!FAdco|Ej^xpIa|4H&%aju)1?5F^v`)X$0zHz|UNW^;X<-Hd zoGR0%QS)t|gJ z>ZrMwAn$ZXU_L9Fsp2H5#|xkPI}>bpZ;pVB%-sy;kyLzYkYH%&~@PyfP-*9HuP>r;Ic>0U#zw5BZ~&U8m3Ch<@j>nUmA>8xy+sm$Cl>p_tzv9}kW<#3XWUB``-bvP$lL+N139nWwbd&2 z=0tDzdr6|>tp1a66EFM)y^GJanP<$;V-GZQ3T}XKf<09ThhG1u;~{*{e7%@AFZr8 zyI+*gvmQm~3TMOM^R2}Icj)ZhXlq$!YgH^We7oAQh)~J&s_KqD2j!$EoddLRe=2Z| z*JnkSxH_9Pvj!}~Pok@Zb{~a9MX5!S61se{Kk={0vjnS3HVzyhXRBI%i>>>zS#N|l z6(eQw)Ti5_)*&1}_gjp}?V2cADK zUFA`E{Ju*S)jr`-CtD}d&v(qEx~rTagx+@h*6y2a=JrA)zeSiYe6`eucq_Ms8)GQS z({i(0HTR%fq_O=&5X`JNJKRyZLbzrt~&Hlo2(`lK3UbSFt zast?dBk+)V1Arwg;UBmL@XX%ClHS;7uBzFC4@SyC4f5yu7^h!i{gXbbKMNN+J9qu7=Gut6&CO$j?V8#`VsezFy+tu9=sT%w4tn z5w{~o9H|d)$h+oag*zJ4NgRHu1K*H^7ciO;>T@bbGvS`#MQ^Sg<%chQ_w=kG#( zo>2BENWN)R_@=1nfZ@pLH@GXLX3YK$eMAT{!`#6*W$m1DJukk3XG>B7#j1Za86p(% zq?EH#FV)hZL_3*i-Z?WL0D0P$r&_k?vjOSFYS2+>{t@xEB{TAxtd{|1gFuWnL=-)M zX0Vlyp+UqvoL`@LBtc1_eOHDhLDXns@DV7Gmx3!M**$<%L`f;Jp_ zkv`bQ?#A%trq{1)k3!-vRElO7W^xU@W4Ru@^q;wVEGA6JQQX>l`joqYp3bvU6C8t^t822#$D!)X2zrWg^2ux>221x@sJcYWr&0c6zl$gVUT7e zW+X%JOv*^p!!%y%+n~?E5ObnzsmZiTf$sEnrmaP_Ep5iq6CT~5*==L~Dd-~X*Vg%a zu~~l+?l*5LTgJ0=7k|r!FBRzkDSm1y%eUg*8G7rD@$wQW3vZL8^HN7Y;|Q77Q)Ase zHx62Hcqm_4KcX>8p)S><_j0yxwV9ZdUeBG>`e7eznRc|v5q4OvBq^NFjq@#oB;XPO z8Fy2m<7eDXa()$v)J^Njb-X{sh*HK2&8dkgD@D>^`jTvRTKMKS5q|1tJM--`Z?acR zK9hMRw;o>x_zSgD#O2Ux7|YGUg1r%FR(%M3==Pj@vXYTht`0@jK-}?U*kBI#6Jrb4 zYDPhc7gT`q=;uKX;rdhP@EY-Fl*lR>TTlMEobb8j+n7s#3OCjc$e{qtCj zQ=IZ_RgPK_NcJ12SOZvp`por4vcafO2@FTqsFge-g~(vqp?Ao{=O4X@W?24@Ucy0t zpRqAwh4-OcW#%iY;hfTo$5yj7iAYk(>#;LlLb=dxaqYbKS=C9jbh7mC6(l`7nT<>4 zq|(6bz_SlkIs@`UnmYlV4O`%=hXA}M@?@wKSkn&<{Dnc z7zeIU*uW3&w2{o=o^Qk;v=5m2IH{MQ{rosyAFGrNyd90QZK@SH@JPgNxxh?zIsuZC z@5cE6i3%^%<5%4rGPHxx;-iCzy!kEh%Bg21%0#237W+L|4B9qs=>p9(ibXVE7Cujh zUb&`EUyuCbdUPyRrt_;p*R_<((LjcVvMlP zHIg3maKOQCb~)tGjA8T9v$6`|i2+Ql8=}hl)i!#O4Rzs*p==aLd~7)!s`5Mo<;Dumw21aswjFf6HSzM<;kZLKBpY(d)W|PmQ5@-hEqgt^HZ?%k`sQEfl^?{pkr?6 zMRngQ)LN1`3-L8KZY7Z|Ec{Q2!GwYs{t4U&+?k50vOYI5(Q9g|SzzwV(CDvq6FuAb z$|#TK1Cs-_VATKs90;IuZRL&1s{`hp9s>GywidCSoL_OPzIP~giLum`HF1}Xpz(#0 zShZ2Yqg$yEb+-14iW?Sp^cLA~J>7Y`7q$+jPV5~A@5{UDIGQxy9L*;O3u!ZPI`hsd z02P+as=oMA<%R>B(GHd0PQ*@~`d20qyPO)%{ zR}9&t-5oIfoXpG7AJ`ZJKB^SFjClP5m!+!agh2MLIl*^OIy8o`Xsh>1i|O9yZ6=!V zzT0@QQF%7Jp}T9YM%1(Lmd%O)_mhOQLhfq!d~<3H*~i;cbP@0f7{dHPT*w>u8uU4M zFs8-;He`X`!83!k@w6;}`(iF-HE%{R+BN69PFH)G>CBGR0M9`0)i542nx*(peLR=? zvL$m@W}?F_Ajsv*xhen8vD~l$F!kOq;G2s9el#oV4GJ*rg@67}-Msko9k4en0$a5p zsEPUZ!~pcKF-HE?7|Z(JTYK`d7TVU#GG&fl+Wn_t_GL! zXVz0=mk-osDN{`KeMp!v%6`jbyz60N7?wiH6s6Lh*4RW#vAgbgWocI&`O_)gseCLC zWFAF6crTxC`-@1Ly1{zMaEMO+u!b#jJitu^PPAvyJZ4&(b`~qaakBI4y^3~IOVZWY z?|X4w4d&qj!7^L8_H|De6c=lTRA5Vnp#u^erFxV3wsd_W>*ke_Pk=DA?UcymB*sub zeV`+u6#6MlhU^ZY?L8&RR3*2wUY082PFNuvXu|{oCvusK5zb=tq&}!i(@UjZTz>X6;M?b zeeTc8)cW>$6U3(ztxw@sI_mHT}oprT99YW=fkf?{Q8heivMHLEhLlZ-gXj|Hrx-O}P+ zd?#a5qh8>0LpL#Rlz4|yx~{!pDg2>ny(?I2TuITI!8AB)j)CPjr1{2G%!%Xs@y{pdhbMM6&m6>k>Dx=T zc5g-oI&kv(cVqN5J{=8Z@b*b*PFy37>Au+Az}c=rBWV}i{8wx~h?^sTY^xIyU$T=K zas7p^u+>3nW2S<3xi90p-^9{X-^A>FIcJTCdTYs?mA$rlDQW`Lobuy1^ zpdjyp&@%d@ZgNjI(|RTAj7c&iO?pOAuy{VkVnivqszJ;n4b$T`@Z0N)P@L!3KVkde z7ri$ka{HK!#OzWu2n7zUoNSqN^WNvx4x|Oht9(d^J)}9K+zvl8(M|3-D(_J5O}%)2 zFla$SoxT0B)4hHp+jS-V4yN6x#nxdIsW>V%>)8{obS!n1x5GAiAT2j$9cz<;jRJi> z9f9T8J~Y-(7PyK_>{^bD1~+R@D(!gr7@FTy ziNZ@*Iixbu-O5#~p2!VjNtM{5)Z!R5Nb22^<@6=$svN^GnAkXRz)LPeRipAA?;p_o z=-HYfjEw7Hgr;0(Rd28Mj`sG?@>bOb_x4&Gca8e@z;|aPWmfsIdrb?sh}WAo(>QPJ zUs_TW86(@O=PnKy`NzQ(XEeR7OlYZKeq+uZgT1Mk`8jXHuhSVMa=! z9o{6Fd3NGC4Yt*qMt2_xgtM%Z(yITpYp1zUoo}c*{X%TV9KiwgZV5_vLEnqpAl0V_sI)!uS*3} z8^}J)iq!+p(;Cj#;$GO&ek(0%sxE5d`2f#La*B!1@`1NRi{}_kzHf>#d(^ilO?XeI zNlrSceJqlhn4Z1-sIf=;5+`w5eC$lQiMRQY&8YkxZ^FAdFDc%op$zXPyDI-^Sj+Ca zQJZoV>gSd=lE6Qn=`L#k&e-)SYv`g4ZYgN_R>v%5st z`-Tr1zP`00J&6l+eq}Vk5WRJ2y&f$-@@{w^&F@*zodacA!R48HNYTUi%vsz1z#hNN zJI4#MZ*1_PgJ{!Je=UB;W+agwJ6fSzU&i%G&9ji(nf-7cd}wLEx$DuwB%y)(jZRM! z_Nv%MohZWn(t)))L|$Q4BdjWci}amqoOZ^B-s1-imiRK^5j8SbnhN(k6rt|)hEMN` zm#;A_ZC1G@dmufs*)eduI>`q@zv>A+?ow@uIs!^t(s!J94fItalQU?V!=Lg_Dq2V8 z^onOccFkzfHxod6n_CtcdO1*S>^qS6bn^E6@c2a(@Gc8IQ%Wq~I!T3;&iAw|1q)rf z$g)*W(fR)Bv=F^ZuHw=Bcv9F`_6QS0SrsH!ZIkQKgsn=GmXOB3sd@3jGC3O1t~&s{9*rJSh_ne zb#Krer`rZ1e_;_yYC5|Uy&8QK&p`XBHBMkRX5FYJ(1|yILf=GwMN0J^0^og^j1A&$ z!vgs-SZq>qWTMPv=_b+=`h~0Vp5r}i=_0gt$b;g-_>YStt_fw$IkpeQjfIYTHzZ@OGIz1~C?;UwC za!2=IN5y3o^pStJ*bT$xq;E89Y*2b$;T;E>w`8EpBmY(I z1z^twDt-SSUMczia6$h22ton{_PWn)V-oUqr|%x`a|Nk(hL}ygiQN}S?WDZ#{0^fU zE$%UQ1BAgCGAVkDU-#`PbiKr)%2K_LT*rUNCBs}r<|(J^?;?Z>;L(BQ0FPQ2fHk6+ zkHWSVPc~XEMoL@C1sJDRF>;wmE#K$=O~c%qhh*~spf%?Io$Ur#y&uO}gv~IjYJXV@ z(s2|vxT*Cki6~~2D3)YKzE|5?`joXL`R zBIS0=zh@!$pVK#mxfTXZe~sP+d{UN{%A#}Y6m{cofV-Lz1;n7B06;|tT7EdvvN-@d z%#}aqV68{PdO-h2w9{M;+sF{j(HPvj^FciI6mj|H)amL35PO^W#!IR?wtm9PtImeG z&;W@SStQma3nhjnS*kAVc=EM{h?0@AYmxS7Zc#uc@-59<36%7oegyQcDf|S8yMqtW zC7l&DjRJYUjv6kafO+ya7e2w=2rbrKRIwFKTdU3!FFG`S&3!9z%rYi$FU6b@)nZH@s;#{KTk3mW&cD+lBmEny{yFU*a8xSc|%!_3Z z6mKSs|5(}sGXRh=XNmzy8Z!vZBmRy*+3rvA;+&W7SKT*@n;vRgdzj`@SJKR0KAG2S zBzNnu@*>xVw=wex4o;z6!keE{ZcrT*d!@+9>@Qjx6%L=H0F$od^G|e5k+%tNS76I5 z0Q47})yyqU**%lAJ47Yna%VLWpN2Wn4I_RT<_yGY2&&U9;(optk4f~M zvRsBSE$#-eR*fCl+s8i*BkD+3!JSQ^LT^dGTxwq}rn&8FGq_o@ zGpUO^@DB3-G9lwQvJQqQ)*fjek47PndWrnNosehTeB1d29yIon_Dg_ z3xXV}Hf3+GT&P#f;O&?8Emt$moR;}bqSCAo)XuniBZGeORstjS*C_4pgHf563VSDG zo&cT>TUH*4aazexh3Ac?)yI@MmDdE=9e zhNd2oq7%V%e__o!-7*{J5;=pd>1fz^lX!&`l%MY1+mbaubd^9yQIAV;#wW^h^P391$VdNfy z&SJ<7y+W9A0E(0NzCka{n8@4X#7FBs*m`ECxsM7_H1(evTIa*x| z9fg;pbbPPQ93*$b7+h{MAG4Zi5uII6-CcBV4rvZdY)W&OUQgOPO@GD9D{1Snyvt9Z zYdkl{!&O7=>53OG|FWYTe==!GCHmkRD%$uk$NNWK*;R8I7VF&_nBC|^cW`JloMvE! zed?1AMt5xWa}kWk-0HwJ+_GdV(=mB3nMvqIQPFQ8wza{L1dX8`uu<%~-05oT*Br|m z-J9&=9uQpE&XVW(eo!aMnFbLsD(pC{h=M9$1_i4M&xH~3R#;*xX^!2rWr80F&VfRn zEuSwyCZy2JGKy#trF2~JGA@ZM@^shuvGKqXjCdPjj6HT>IcXiPXA#>=4yOAgwjDI! z0<2bl%%wbOHct-$u(@5FirbV1zuwn(HOr8W6=m<&o9}U)HU}WXLi-}KD#y|b$6R8_ zgVu-u*6=!a;!B zrv7V2$5?1|;0AfT!0ZN3D3`qRl}<=8;j4G#psy=ZrPE!`3xIZ$Tlox!1yLcpsN}8x z)707G3}O7(#$i^$aHS_SmH({eeMD8yPyC0&x-9exB4)%K@+Uq%^%`BGZ}JDlH6aua zf0EOjw@ffJQAN6Uqt=6?ut`7)hTA|uD=`fYm=oCJm$cmm0j zy=4)ZoT_1YkW|Z=8goiV>0F$taI9@u^%?2a zjx?UrrTm05mlls-N0|@z$^;Kb#m`5CW!$Flj!rTQ=RNjh!15Q%BKdX$RRcD(peq7U zbrsMdD7H*`w(I&0@)MP7#O(btdV7##m5q)ZX3J5|Kbkuyi*WH@1FGLv6~TsD(ZS9T zjMSJ=N2>BHud!&BsJF_;X|XQXjFjRWRAO2&H(yHWM+%jv^Y7$dMaD`ys*01GVo&{r z1>`rK9KjyTpHBjzToC>-WlX`2NPYD;Cz$DzB;ZV-=^-#X{r*aQm*rUpQ?q`%#IOSOn+v-tSc(;1x z_~|90^5*M-gO$<90KKKI8eYr!!aoiGb43CBS7(OGUKek@*)T&tC)`EN94ZW_XJ}dO zy0??Rc!%nOIw?-jmY7WBD3iX<~jh9Nbw zl+J2~NI=da$!hnLOs^;!7t0Ma3zWm7nQzwqHJ5;SEbDw8AT(Ace9yjYzlu@NH)IxT zoYyb^>oxZsIp^t>dOEC@zvunmSDpqVG1|GmUJ5`>{WGeQC&Eo}?hxZ#u?xz=TZw zHAd13c$PAU)$ry4qPhRhN=C*mjkwc^O>@sjX>l7WZj&we}=fGniZQ>md3dkI)yowO{bk*=##c^&dw@=J#mh z;AD%TOTv~!H;g7fFoyMZ7oV37QP_cy)zbJ4H;nM4OZMA=JYz%X&GHDe zq~>UUJn2Gk+9q``LWqPdoY?pwYgc>XOpRppL>sg|A5c5Z-WJh!n9N9(v7wWwd)=d# zN96L7k$c-yj7Xy8ipUsPLV??0xcJNNe}1Yu7sA|i4W>}n!lC`Z8a=^Vx_=in07wUh z0Mda)7JGOgvQ(E?NKDrUsfQha(GTb*)d@`tZPX+!VM{cA{6doVq#NdQ(k@Gx$n`9r zN%wKh`x0?!*fQ(S(>doWZN~{~IcAjlOxl@aMw+?_fSA6k5zPCqw%F$1wwN9{pfw91 zsc;xRtOo@w2~%j$^#erQ3#k{sOpdiB0T0Zf<RMXA0DiuQ-n_opnHO?K$-rr?eVXeiQhj|JlU9Px)` z9&4gyfZ$9hAXK4$5v3}ZG-@3eAz{vTu?7i31F~ZAnJc8%z%kqz`-l0J)U#eP8}Lxy zD+G4e`pr1+e$LI?Iz6*F#lDMuV|L@2qfD9l2}#logI$OY0iPxPV^;jcT|INqN5K4I zbgP$-7>sGEnwD%l4kYo(IO~8ub!QxfpO)}^U`~;HZj`q``qgFudKr&CiTc*HP*B@s zHnZ=TB*sVQN5WV?HI!RAm=n(R0pLshzcINee_AeY+Tbq0pZuuYt?M2HYE|J{rcWCl zi^L_~C7=6UZqPNVFi$C`;z-QVE~n1Xz@P3M3ID6MMf17+YawPZ3tpZPfSjGX>2IdWH6JN$k*Se`Tk>x z2z4s_X>IM0LqkVC0j(Z=&IDOsdC{q$cmB(nZ!`1B@p3tE4fYt0^AQrO8mo~&~2 zuwaqyEyW!Sat2Je=$ND2t!PERw`b|r3gJ`T9`$?1Plxv$v%--UHI3GDk*qXxcUE$% zyzLJ+8zZ`!DNn2w)sK&t!mx?a(x>&wAyrA2$>xB(v6OeQtxfePD3PwBFHj&BNPe^z zGPrRt-q?WMwG)(Kb1ikgO_6@J^NOh{jIx+h03|Z-ARNWAAhuekTM5;A_(o9?3*7h| zS=(w9)A7x=w91HXaz`ZG%gx|TyvR=EL%=M`y3-WVs)HecVQ=pjiARjFWq5g~2iRX@ zM<=dU?HLnH`3XBLN!;T*9rrC-i&c4CL)y4m=4x2mvZQ>yV+&r9cg`(KOZ76Mx2+;_ zu8JVKSUZ92gv5DT`xb^(PQQ6Z_2^NI73nAfGMFAXlIFG&pA<_qrPZK?WFM-d1*L0y z+S2@A?7ekV9NW4F*aQt42oM|+2rj`1){q1b9^683I=E{?2<{%--GV!W;1Jw`Lu0`m z8ff}V<=lJjJ@3t3^Jcv@YyOxuf7I&LUAuPe>h9Y0?eF_ZZQKvfct9V5INO#Ezb>J) zSDSF5RA5_w@!`q>zGaHE=RHfSa!yfQ&jl7 zledl*{kXE!5k$8~{1N9Z6I zx$C+6b;SN~9W}+VK3s&lBb^>n>>_9TAu&wGM>Eo#H64HDGSs-+~CykjsTUu z6tnJY-LS*5_N8vC7f!6qweXK+k5w3^=ZPt$?~@!AJUu;?qajG2ya?*7~D4u!1d(4> z3ii^xIJqiVUtAVg+2v15YocNPSP@%jMeUEXh>8{vC(WJu3n2z^F9c}$o2Zbx;ENAhinO=D z?C%U^1+8&jK7qTGtmr*2PZl;W*0tdw>vJ{8YPUP6R9gS(y^`2mXc?XBE_`Xn@OV#9 zb=b)VjJNp6Sl4_y>0%zAoE>*YT!FXJ39SZUz zKwF?>2dpoFv>$$;My{xc3y7u{;7G(SK*bmIw zRR<4VzplsB=ul)lbC&Gh}j^@PULzo*rm z^&v;Zd6d^U#&?6oR&<3BgJ_AG5~h<8#}(@EJLP^u`k5m?D|QP5o+;5A=IXL$BgG## zUG`4mm_D;z^~Y-~whWvrP7 z+M_K0j8MVU@iKuFFNScfDTD-+`!kTEBz!8`!y+-Mcj9qBmThWktUEyrR;(zq7A2a` z6IS|Kxb+dE#E&r*I4?(n>@)FaotJ^?L+?JcWPU;L3UNT>l@J*+Pd54xEs9mhr4sIDQ=PxEH?&l9aCha$~ zs_piQLdjD-O`*kyt}{-qvESujtSGmYTWD`a`~j-t=@!q;A^-?T)O?B#UYiD`zURu$ zc6DWcfb3-=;$x$P#Oos&(_D%WEI7qdTLuQ!Dh9)tM$E%Llm`gZ_jlWX@^G3Rv0#8p z@-#mlzoCMb1FmMdCd1jPr!5n^GMSypz9s?>qv}b}#q6}54O2aY%sXV=FOTjgchgQL zo1W1pg)F>1*Avbgv${k=8AlaAFt3g{<|#&EiM!j|>YC0Vy;d)>p4m0z*|SoT0Im-N zRO6V+27*D*jXt~E-FtK={weprh50l8Q<%@fjLM`j+nbR27KcuhX|7 z51`j0s?!f`>PhSh)RhYWeaRk!Tc2#{@Tp)lA{gAVmc!2g#~6{Z zquv`$MPd}-E__J6bN%5@{8-faUA3>q*q&};Wo+RXv{?RWL*uKnmj~dItCIBuWi-d^ z_chG#$=>@(dr(J$0CBYMG9LFoJ6ZoR3Zq2RnU^ji?k?dr+}HQH+vJSVIA@2ia%#M& zT99=p6VU(O8n6hR1#

p7q^ddk06zv+?ZyIcmUB=g$$Brxq1iC*5W@3$y~0hb_&5 z;(m07#Hg6e4`3}G{?E%%{p(W7GG_So#3+>^%ksu}Ej2lg54+5I2jv(E_^$xe8vcDPK4R?VCkSH53SFEN`Q7@G{zTza&{;1sMof&N0n|0nS(w z)T{sP+tea2aUYhNbPiwTCi81USW52$uMrt@IpFT`=2|FZlqhhOidp9Q{ zu@+qc@&x6k5Hb=o#l3s1{11nmOm8P3Abwp2Z6`oR=$>r-0g8qg-ChHzNJ)|-FckoJ zi`iQ}215Bf(zX$A!Gc9Ainj}yEgWVoU&G8I^myNs^sD%kg;OKAQYye9i*T##-PAV0 zGiz6eWj@=m%=ZH-k|S=haFOl_*&3<*#k`UMGkrpRXuzc%KHQKpANdnfRmanyIUlry zisYZ_-xztIIZx6v+F!HS3?6DDH>fS3>Wma+Pr7mvtH_mO6LQ~C4gR)QG#6H|Hb%6Y zDie6j&Q)aEoFr{3@p&gg^E#wWE64iQZr*q%b5bMGl!($?sB1TD)3)xAO+9n_Sb6$g z8#iAB=`*x)%p%p)RHN4PcO8`XeUtZlHr_^GIv&B3*CUyF`nGS6WItfOz%Qg)i=rZHzCz)7seWYtk6N7YvRvojQ&zKJF^EVSFX8EI_nfpaq^CRgLXp<@&)1B@ms4ldFl z6XXhM;VGZXN2XC@dz}`8ixK;WEC`(OZPGBsZU7f(OOtnAhC=?@Wo*q#0=0k=Xt4X6 zB{Pm%BA#GNwg(n|8+}YL8iSKso9F)<+LA);=5*MrF>pznVP}=Wh1tP(nLnd!(nRp>n|9%`umF~usH9cZ#+LEh_X2NQdWkB4CT z1;PBWd1P7f0l07ho_ox5l69lU(9L4^0Awct@>4w^+5B{Jr_nv9Ei&UPXmBUi@a3r> zQa(5Yy#E`!#im3xXLZ1$y;U~fLHcWfCT}f=vBGoq3@23L!T#`(hSZS+D2i1qoD;!;Rhe zr02G8z}IL*Ae~%qQh%r9d1KQ`ehC;_l-!4psTY|H(nr>x@9n6{17sf1pGD%|h2lTA zIIQQ*DIWm7Q)~-sM5-Vmwc(VrSG(%id|nUaddumv>JdcFISr5eP3l31OCL{zN+bA$ zexbx#_i#4%6Um~Db*JMB4Y7|8#8v@Y$RpgD^7HOL%zM05gWD@h;t$Ivyh(v8aE+IJVT0BvLKf+uqt=Wpvi14C21XTuBvd5o1 z1%73+--cYDlEUOMIGlZfYLRB=C6Fg&-QLeXnOpi3QUFna$6me}Ubj$}BG#Iwda6zH zPxla#PMwy~%!R<3n>QY@>BVCAQXoe@AJ)|?4fw`Ejc)?f%m`TblxM{hVtDFFQe~RD zp5$k(Y9|P8V^~Y}>LZ6bfmE^%7)a`B0Q~XW!5eJQsGgp4@`!>vsq%5TJmqSoEVfq_wi3KnvznX&)WMn2~qx=OY) z=smV>^S{m?{jZiNSE z+K=I_@*2ZC?iZ$GZ=;dP1$sBzjK0D}LAAE?BD3y9=~{*2^4L^2}M zeUg+XTWlD={nR;dN+E9)5CJ4IZkcmqKn3~4b^pcTS&c&X^}m27Q~Jy^!wu1?H>PXXe3;OEPRZ1;7fiy{5*g( z_UC4to9BC!pC}qgN^QesIK~2p()Pm6+or}i{zh5(CJbr31C?pt7ob6H zBT6-2U(+%3*b`T8rCf? zn{&63HGC7Wn@Y7u(v#Yo#SDU=GwbUB<-tl5WB|~X`9X3o_=ahY_VOCYzT{1|GTt3t zf=8QH!^)qmZ%uJy=k86%0d9|CY(8xY*++Kp%v~{MM9va*lUuvd`bhKODYA1%M`U|7JACHGAYW8J00iltup10CT z#>~iao51$a-D3rwT&hx&Z6>O#%2W=hbW_UH0G%nbBx&r}ey_*8kHnM6lxi~jbG~s6MC~9LeW4r(U646UXE5$qVdSdRp$lOo#dZP#t zN3D1N3wrTkF4;X9DS>?Q2k0w1_{Ur^;_or{*)hOF8ldc^y+RMZog)>28}Z6R33rhg zZCR=(2g*Lyv32jIKWE=0fKVzEq{AGGvu^_*)F60^7xskl%5<8HsaPmYYSBTn4UnDr zX@?H6=G0-u#PT&Q9+~Qsyg)HUkL!R3e}F8FYKtAHKi7bK-kAc>*V%102zja-7R7_I z%*_ju?G9WZ@^4p0cEtme41YaC{-l>aCFGrM%aqH*HW`lX&|=}0F&o=P6&b-JTF1F#Z6HJ6HQqR5bBrr^^8#$p&aGZwLcd4zz5*V=kmI}C&UFLD+2kUtaUK1= zl?T)16?W95ECrqRRjp_ya{;NVr!xM|hm?lxbrT4}(!B=F_jYYjr&l|cAMnL^H7-j5 z9jNX^8oTXZ(DOqej|tU6FrV{r-CP0Kr_M4Y$^1Ort6S?z*tdcv*@>9w=c@AaA|R1_ za<~}0$D3+7UN>x@r%*R1idSM)y{BHTs=$ATyVG>pXL&mV-8LSI68SOSxwCMGL{`C7 zw=IqSItMGxK4$Q{j!&~JreP~E*#I;SzeY`OnF|sVg0leK8m`_nUFUUb= z7I^6M;=gki<_h(GnZMA+>+W{go8^`w8eo5QtB#P`XmU~Hqz21Oz^3RUUhuFbeIQT~ zVXhEUcs*4KPHK7b$wf^49v>&=t>CD4 zC$}7+Y-koz!9UC*g2^h{SJ2R$I=aV}rbEG!V}IImsY#9JN%5-%?Up9P$!wkSF7nmY ztrxhOAj!8wv$pOXdW%jE}eJE5*vbv#lU$tgm)&P#wcjbue5~Nt3#Y|~@4rdnkom~n?_ou+5XT)+36!dQ+}KOdx!%+2+%%Z!x=S)_z(S_u>La?{-c#q1#A<=$eq>hJ z&wgo`X=9;m2_CK9I)&`z`_}7M5s2~yzh_p%*XMVRXdsip5Z6VO6;;3-Nw)AOv=;dy0`v?CCw|!u~+$u>Z%XQy=%fzF|rJ9tD3_ z!_3F++VsM8s=@lNUa*d&zlv0QRS1rCgJ-AgfaT5}j>i^5RE(AHhfhP4pkwm=U5&oz zwOo5qxw5Rg0O*y=a<}1IvTbvH(lXtyM+={&P=5gWs^07KIl&tI z&$N_d0s{Kw8|BN0BZ$_W$k(eSaIzH`&R^BG%HkwG9d+cMtmFR@N9zAfC9GHi_3MbG zUbt+IW|a2m#PuRd8Jk9{LYe=TV=;G@E~r3?I05tzOpzSmkIWR*@lPC4T4j8Rxy4LQQv9pCbzrIWw~*Yh z99YZ^Nbew9!2mH7`@O}kXSrvYVaSFhvfuTpqG`uLrHFoUyX<%l!=09uBnYSP9OGqr<6TJ-|EcrSiJj zN7N{M$!z>+ev+AKQq3Cu<)N=#L`fc0Ys{DYqxzDtyU^!ZcY4Z`PV_hs-jB5pi67Us zMFzxS`0AU8&xFEkB3S&5qOzmeGH!$CnJk}5!z?$T{RXHsD)RibaTK>PVwBP;1?MaA~e4)gmlnsk2&YP4IM z$OY*}P0jOi6ResyWONsxi(jnFb&9OyaoWzqLYuG14LGJr#Is@5F4XGUGon)Bq3g|u z2fYcF*Nx}B+XohdvJ(VoYeaItxV7pMPD#oPUY8GB73b1HAjJt1lY%d0BwmPkch41o zEcJIieKs@AwjwLKHz*4NwKw*pI6u}6m`KpoMahveyi@Vdh$68UiSKo6oOB;np4^(@ z(xo4NE_Ol+t%VwQ+HoN`?W%O+*2L|5-j>+PWWnylSE zU4H4M=di6m-*5iZEE=9FNEL@E^l^t6WnL91XkQ*mQ&tgluWz7bEu0Cn{b*Jxe74V2 ziHYYw?VzVC)ldL2SJ$3aS4nSv_O4M|!m!&KDLRf3_?&~ff7Va<=Y;}ks9b1`1lW73 z^Xmb4CmysIR~Xb${20rmVg&X)qdePO6IMlnddH;EKL|(0vb?@nyDJ5Nq_Wf5>m1$sr&e zX-kAZZ;$GKAS+bKrJruKfFCjIsaRQNjQ-hyW2@&)946gq!~-n;-blsC@yV#QdQI&*xJFDqmAp<3?BC--74Zh=XJ?9t? zx@#Ano%ZFo{gv|3>?ZZr{cImenBU@opJ=ijZrOmV3n+^kHtyC528HS3=prxPa`qE$IVe_0MCUyw0bU zWHw43OITe42uOML1fS7EpeB|P6j-s^7AxBnwEg_uN`ZW$*#I4_y8iSItNOcAu*~Y< z4buEPEZt-M+^DK((-?B~q#+eQlw)fNK=6%wIP`nQ)z}lTk|o00QF~ldi>?|&6-Ud= z%S}Io*-oN14wF&hJWvuE^IWSC<Yw%ZA;LGZw|R62~4@}z5T1|MGb~i!_d6?%(w-{D!jz{f|<7JF$dc8 z72lVbwlBDMb#!g3*9>?y8rth8y(P{ThH8ohW7ZO1lHV_@GRfty+y``fUcfdq8fZ`A zV@3+3X{5|7)XU)3?YAo=2(`>53 zP1LFU8}jb%Ta5MRj;AN0E7T1WY4UTvV>S-YzY8uJFX?mVMbE3>ew_hfa93wHM%J4M*l4_du&|9eGz-h23!*hRB&vlVew6d>lw4F`4 zrg_?z(A{;i?@1=iz;o9m6hncQEj#;RcHN1-FVi^fcg@>Wea<4xFLN~yS`}PT+s*b@ z9?yE~ohtNPEug2gCgBXyNZ~)RPU`cxuAt(Aiz5Eu9_E^&x)N|%<{O7;+d4J`GW&fFe`kjLMZyOO% zhycxwo6QiNcGl#C$^3MDE<{#Y`Te}_p$SEo@rQ{o3|%}_hl7K+b1d1CC5oQiip^2W z4OGdB^CUArtyWkeLO&>aON-_==_u{(n_tpKDiD5i57%!R_k9Mp)0sWIslj2BK^Zh9 zMe!6p1`RMnbsM%YBgKCy0ko1BIefdOM}2)Z0N$@iDOm1aeP5 z$f!!bW|vOC>7&=w;fKs^fjAN?EmuLdOQ+%QU=I3Lwu3){{Z6C1XlV_$Tzgpv zI937m$1&1u>^hCC0{}S-o9>*SgP!*mKd2yq+zB5e-Ro)p`hY_lIoblq;BYA1XSe|B za=L!3lQY0kRlreD3j^ryZt5rDkbB*K&>0@z3GV~P+qwI)JjISH(LCo3xTs)(5{Vb5 zd>l>ve?zI}zd49&L`o2r=m-1(64OT3>wcla4}`JV5$qwKh8u90S&3J$C(YSWk}Vxb z49H@ly(i3U7CqJCOACN;Q7l7l)wsVlOhrbv_Y|wznp)uZN_Mff5?fHk`LI=+YO0l& z4tajc4uGrq`+-297a%HZ(AgorG8WW0==9@*;~sXbj-WGghGvf%$I_-vsGA*GKfj6M z*XH;&yyXPaxQhPyV-lO{WHe>2;i#RPx%`jnbTPTd)U=iZ2+v9XsB|A@)J&sCR+(($ z{LB|@1uZERdd~9YKZ=ve^=dYv6`w#R*#aZBRo74WQdSNrK5_^ax(Cc;-tz=rY0+9@a4<5 zC>{Z+&s+@fSCAenwvq=Ok%m@Jo0`xsX+2pRJoc8XkmM|lU^rQ>)t1$UmbWsLHC^5> z1Z3Sp49x3`tz8LwoHIxjRW}(PCF48_x#DPY6i-;i-R1dp`%KDp|M|h_^%F-f>6B4D zn(javzYOR38uHqz)!!FuXFoYd0vhisFpTfyYFwW|N zyQldy*AYhs5!Sl>hoSVk6cu9T{Y)?1={c;`d2tLB%B|)GcJ6EF#F&x%!K-I+8pNb` zJZn?1Br{1;A3icL4aByQ+KAX!HM9P0z1tku2p`A`^gdY=i zw65RVyNg+5!d9m5GY?JJsN!OLwE?<6uBXXLOKwg=83_1u@!&D5ls@pwcE)~z4)QQq zfD_qaj^PEyt?o_f#>DdR@GrjAD%fv^tslJ~u`jO%h<`CW!JVNqbyc zd(G+F=A1pf#MXB@^Sv%<<>{&FKJGs5Fwh47{+*AT;uQZFzTABoO?YudPxT_p^0SYu z>y8-OY@7J-US9pvq?Gbsg2F~YTf#|2K7@^73qt8+!?>jJbZ8o5FDqvVO~@iOFmwID zi6|u6iBg)j`OIkdK9;D7O<#q5o7d8wGfLIUW%HO6D+s9g)Q0V|aF0o*0z7gcgbxFJ z;QnU4ZTk9AwwNnWTlfo`12F9Wh0R&xSF}Et{(3UJ03KLir!iIHiNp5{J4Oma2cOP# zt^jCvX%3IzFz6=9di33cu6sx{ITM9d<#xiQMVX~aWlCZ1Gd-;AW{of9HnHUI31|XR ze?}dVo6b|Eh=1AFroo!Fy;R1Nwp%|7Lm_gA90GyPb!QhmKCOw!Vi|s+h77i|#>QvH z8MLI`4gPZK09Om%n&b|daQAOJAhdT#b}|Y60O^!Nf3iaFG1_rpcuQBQCiQiUY7+;> zV?zY$y&lKF1T+hwy}|~{mXhVaycK5f^+>8*C?moBS{Mtnvuhp6AF!J1b-vN4ouOco z{DAlDbkR@?;iR=otV@ILVb0WLHM4wGM0)Q2F0}aWMY5CPGldIm`3rH~EDxUF4ZVXk z+tFIhQ5Xe?a-$z^6IA%`OLsCfSSwQqMF_fo?V?X=mR2eDHLg1ogJNIY3+jc95)xk}=X_#~ zp*zByZNr@;VOV`;_j>xf5_eR2YWLfzr>&u|hS=w{E{JW>dsfP0e5;sGCSj6Ye}IxI zb}vg{GY6VJr}KNy{RfO{A4kvTcFg7_DlLkvy(EV?zU-fEvnD<@oLW(9{Bcks3^qMo zr8QmEj*~O7n!dd2YaS+1e?m6qx!dMM90ws4nCLqeUIcy6VE-1U^g^sGgF-qNUpmX3 zpdLWK1^QHooUvVrvUtBWgXIpjieHIaf2yEnQzd6oZo6g#o_ya+XJSY$X}{aBDFDs& z@@20`tJnv|=-VVy(j3Sc?%Ddi*^Jj7BE-;Aky$WE_?g~_7p1FZ%L#F`_3|tNLJ;K5 zWn=MM&PIoU2QgeSkK9$c!kzCLv)<~N%+Pl1O2&wvz8Z91=0f_9upB4nIAMK&PU@p0x`%ettf?03EE~e3`?O%AE=^ICIh2K4FUiR( zwP3iO2KPV2nI`gEx%b_k5Q%EZXZH<#bBO8}+wX|7Avo~NC#ZybQN-DVhBc;A(dI*JDyM|r?!-l^G5hId1lU6g5Lr2)4JMO%{s=e4`(A8~SG(5kCz z+q6cHT@>l8>WvPvcjDJ2*6F~)tUkvZ3pQY$UW(4eMfFM-bfuqt!YPs+ zr#e(|CrOk*cl8CV*kfI}ZV#V3B+k1#AD!%>@5MLSeFW&~S|_IZ;tZav{-UZF$?Me+ z=ZHnK4}m_w3}@J41Xlv=mC_TpS7@h>EvAP1arnGOCzZggv&g|#4fZQI>V375&}8$h zEA%8C@Kt&Vz@k3Gx{)4(hMt@@3Xd2x=_@JuI-D`{2u8zEeu4kpXhRvfnYc4_$_-4U zWVi8391kMud+6M5B1us@fj(A&-3gs1X}f=bmg3rO%o^MtQk@QrOsIx3o%HGk_38O} z7wd0SN*e8ivHJl9qIJQkKS0gTY5#ddQ;GBN7ZWQQD%Obj*6i|&rbcKhpT)0f$851D z$j3e+cX4XKykJ)Zb(B9}9;dyr&PpjgQ!2X_x63IS3O1SS{IkDSrY*e|`~uR_>ZNa3 zuePLp%6b&9DA7PZBc40m7sl)RjK-gij^`Sb@C<~IXMaY#D`Ds)7dwC^;&0on|NVxo zE2;1=NX(x)EKdva`Tpt>CA`ei#*I63x;VDutPylKt96B+1H|gd$Xk-RiMRN#?=V$> z5FVKA05#gLE(AB5o!8@)9bur&f4$55Ta*1?+5i6`|Nh2Wi{PG88D{OQBucMXMt$qY zC&vLf0JY!9N7OOEFy-F?h`nb+fLocRI7RA$!aI$LH8rLt?NN^dNE;mZ+cE?Lh%-;x zd$Rg1Byd;6*ablk9@^bQg8zvg-hJP3T2bF-|GIdWjmnx(CXE1uOR%M@D^Lq_zkF_E zeXN{01u=V?O4qXyye1E-B9T-8k)ALXEQrZaT77S@s&@TwZLxU znyZn{8JKTslbk1WR$13&4PR$o_QS#Vwm_BVeaRo73yOv4zIIifpE;#VI(qKgCQ!g< zwX`9{l*9$g?X$SrSw~Rw@sm=52ky>N6w+DNoeQxMtkK*;sFN)jatK8TjO!5mP`RK^ zP}e12>3rnl4hzL6?xzEEvw|Vc97d`q9f3ts#Db|AO&x75L9>>d%z?3u#!6!DBo{^G z<8U_F1~djHWU=1HOQs^D1gfXtF;&;E2K%FBK2Ool0!{o#=Z5O+K3wT38>uZ_=4 z$aNkL4-ov21^bbV!PSuxbK1wkNH9y4>WQOO@)aX#{R3I8>*h7EAtc~>qHZl}S02SFmMwM?EW5Z|LDMfnlpoe^O9W60d;}zegIX2sL zaGOOrdC$4Yy6&Z19U20+#loyeVGpTndrWYT!iNgymF&CG(4ICY?bQL7qonESgG_*Z8 zY#fD*sS*djusx*1ve1*;O)k~bWi0%{juQT1QS+4JaFe3+;SXtZR+S@4ZJKtrp(F6d zp55)Q)gNI(AndP2CWYTPCAvlZbGi|J#5cSP&>KTWf)C?cB9H6Gb!d^LW zj;m%OBnD?pwK~v96>D9`jO?uLpzXD|A`lsFPTpCKI3p+!f$c>70jl>#5eu2>F?1df zyh-W9_x#Yz6%0LNiN3vwzg6>o13a7FL+8w@DEBpd>kp0#Mvu)1Oh#-z0^DZ&rxO;Z zpO```@RoyPpIZ72E=MO^Qtwy7({kX_VC*jF+M(z?fBR5D|Cb`CU^0Co<=6U+-PBxn zMtz~ywt4j!E1FzPN|;LZv))=$wB1O``i6jab!|as8$9gV>;)K-qe|$WBg0t(8*+{} znX+s%e6*Nyuy82aea-i68!BC;WZv&sSZ;AIsiGVVwG0ET3YQ?`aC+$gH7^twGjUUV z3H_HZ=?HgqA6f0LV*khmjAv2>vV%lk8ZI8=ouix)^iMW-lI&{T3i>0stx6XZEbJ)` zBh)G>(dRHp1hUrChA%t&I)y1kgICBr3as>gwB2Nc({{9v zfE;HIvT#gK;^1PKp@EI5wr2gQw zT5apWYiechIogsjI|qA)`iQ>IvF3(HPtSLKn9RcflI86b-m8S?MZqkZu#@$3{Sxs937 zJGVlPCu5?Xz;vb-Rlf>LkJa91W%&8Giq3)8EzS@|dCla#7qqwBkX(3%8~Ra^F-JKb z8q}h%PqB#Z%t5~)RMd5aZpxO)KK8X6Zd5<~op2oVsgaxvT=hbRp@Y#A^Qu1p@e;=2 ztY@(QNiUDTzW5fO@7`*BWjM= z)RdU|nIFS2T8iaVy%-|TCD|;cHbdqD$#%9csKg_O3qmkH|Qz5s}@VcZ_8BnXE?|t5(ZGH|TJ@W$+eq;Pu{<$acJRjqz}%?8FRnCbBXG#;?)Lj z5k1Y!X*NS<(Ro$1I57ddUL1&&tE4Kd)~%+Jd6tp|W}?1_F<0jPiG%nH5AnZv{lBeP z!NQE?)^Cc z?Oe~`e&rhm;l{gh08rXn#dRu!2=L|yA}9suzP|SAy7veRLgp*ng~Me0V{eQ^A=a=B z@@gU-$zRGAexlJApJ%DMm|?i0!|*`b;O3_+l`l!PVA#d919fxKk@~e7*5HUcshdEe z_G_3K7kMdv1kw`CCnIFw*wAWi3=W@x9*_&3RYvy;Z*_(|AUK;1t-3D zcV1i)&*sR1KpFdV+-wJZ@_)L zU`t|}US8jzIWEVx^uslK*=0YUl1|(<=2_oov$VapOkZXxj59du$!e3BwuHp9X&}F7 z>*^Qf0AT3clH)>t%TH}PK0Fzf=_BVah~CVdQHZ5eysT--=XUp<(}@1QLLG$@Y?(;<^GFR$lh9&bms(kXm)IFphr%#Y_oVSX=DwkU zobjH>&|CFy=lhHng^ecE<0;N}KUfA{Nuw(kyC==5HCoy_4+lw8V^MoiOxI=hYc+I) zZM>RX^Adp@6WBd8SnD8AUnLGLk@A2oj*xbD>pprxE-(6(_6yyZ5PxvZcPA%-vSCBnrCV9%P^rN4e5N>z8`ta1%_39EwE_l_ z=ywbB7FV*Ds{?Q7xe{18cog({tY@GYPp>7td9mm{Kcpugj%aR)4E4f4#<(3G&Zd>@jqmEFUun^hp6tuv*gWTu!@MjB;`}Vo>=?1t9C^~& z1Ayf^(O%oYyrzRy&NnU87)BqGfth0u^+wNr6@`!#G=?!MDB$S1M>sS^3HhnWZ?37`_EDy#B^yc9 zE9mY-V07K+Vg7_QUi<+EAFY%yI5lYi1NW-)=m)n@$y*!m}O^*}xp33M>cL zmFUmy9rY(#>qhq~5{*LI<#EdNEZyTQ>LZxR`}LhGnRHJD%3!p$k%k9K906Dfti^BB zGchZCfJMNS%n4_9W$}=PJH6QccelUB|FL@7$O&vgKT;zmvt!tGGTb)-x9i%)`AJzZ z$CDoV>YApnM)0r3&bsO>6VL8{yuKd$CV8k0b8s$@%74c)C_4`g{VI@hWpofUdT@L` zM=iJ8&>Vg*$xq%h(Z6+D>11G*qYRhgCs^u5c7WGt5>uMTc_Z|}Kp zHG)oA>$-Y#$i^u9owDS6GexP9h51wEWk?7H=4EG8-Y-WVaj?DfA09V8WD5LGb=YH6{ zayOctfpzpSBVujKVf%*dGb64MwpKf|9qL;Z3`LR>m;o`|t(PJwYASRj;gB$fa~Xad zHItkQVy?{kMuTTZ?VfG9>)BxX?cAeK><^F|l?nZ9>o)vxK^_T|W;bleUQz>%_U_0} z)H>_}(Cwzl>h7ROHkhn$6|){)@^^d>BI}~F_$0X}v~TEzo;Wj<)KH&khKbhy_yuiD zHWqVPu-vqaf%q{Xi?@nkZBtPY&D19pt-9|~>pvq#p(b&WW{!@)k+7gu8JOb?( zW(wvEtVbNok)ics+nQnKhy|aQXTkM+fwFPY*xd;jUfQRzD>XkzU3WrO8mk^CFm)!9 z$_6Y%0~^=JZoPp}5f$KEFYn)2j6B?6!f*d6^(t)t5)kfyZr zU&d~(kQ>dpO?Lm~ z?SHbm{}6rtRJ4&S@jmS?YBJ2aWgzTVS7MMPCS90|t^J?LzyBu0{6A3W{&mQ64q}vb zBt5XYP6Pf(Rmn(~6kXrHy>)hXU7&3DT;@#nW^2(>K1NgfiEs$Jx#6@Z2%?Rgi zC6g~P?wKbuZ8i!2RznHI3Rm!CsoS>FyC4y}n5mNYBIm3=_x)r;AU2zm)>K_PtJMKw zu`IkgvOxax+ciJ;K_Sr%YOC6xyTbabrqi3PNxKr~9iyt6MA8leBESkUSh2{QDpKsN z{zU3e83m;NwMMVGBWj6?XNbsng>Y0za z)=Z1sQb9(^3pK&bH>~r#jpG4JS9B5GMF}-kd|K`jiNGy+&H|8&j)hSn({1{NK`=YX zg$^xVeZz%rhEjWlxCfH%M|zNjdDZ)e<&cwIsPos{!wu*wAEGT9IjF2m#GnJg?m!py z>lMcPrWgkjOUE9AE4CNlCM9sbQSIk_quNjx<3zzBTC$%zgE>~DDRaA9zO~3vUGXeZ zYw!VU?L@9bt`U&n7-j_)UynncG)hi`LpAafG$Z)VMRQ`xdO`kz(LU?i=Q>%**; ztCao7hI{KW|Hpu%eCp4m?OfJ-!LPx{Q0uvx34wbF_c@(*ye7JSq~%ZTYUMNRDZl4l z_1!qOHefu#M<=ce3tViq=6dz-$Ue1$=&wX*qn$*z1{OY8Mmjz8U~~PQI`>_QlT=LB zJM}UvChJ_$&EW>X;Kw5kjn-oXR&XG{304q*NdcEev&Ym#2DinD5THNSw_7G~Z(wJV z!1Gu^RPjgBa1Y<3zEz6J@ylpA*n2B+9*2UAa#Yd|FJnx)kk_7GCT2}r&FQ9c@oQ5H zw2l6eXMusY+De9;@pDfcLp#d6RIalGb5)poKiggx>{vbR-6p?V@i{9Jz|rlvme3V5 zAeis|1FA7MdH$v=zP^y9sV(f8foefRP0D~-tjk68;G%YxrvSQS8J=wZC?HKLI_&*p z&=_!l-bXEnE!L5N#UX~8C^r|;a4Oe4l$UKI)i8!`NzE!n{>F-gL$3{V6(V_<2YW%Mm z36_i2didltT0e6d(DuC0ql+OsUi&cajg~nbFBzFDyCx=~e5aPzoGissC$C>LDnc!d zo}S5$<_cHVHfJ54xCLJzVQu+3`)Wpes>S^U3JwL*0-thPw9KDA-t@EiaxTz12#H1P zXCYNs;|n0}Ko1)r1xEM=x9J9G;VbhM^C(m`UNH$c(Wywn^&JX)XPt^$UuvDW@)q%0 ze6*otg&V_#)?yOe2qaGsjX$99+(U%L4Nu$2Ipj1hOXN};4I+k=NyMb9UOI;}Tm$ps6t@IK=I$m$}g>eFV{ zBC+*~7S&{!x|*Xyt`Sn6@Ag2+4Lf7XCa$8=%HYT!59xqy5*0sT1jna-~0b=3}# zYe%~v3c`zap%nY>!}ewmvyE}35L#9BvO;R*OSqr7(v#bIDZL^jqz^s_!1F!LbQp|d z3h4v)G$*Ww@MI>2Tjsg8(r?rj#1nGa9aTXZkg9S3HlS}dx?3wvitQptKhi2?^srp8 zw^ls@JmSt1QNTTXS^+M7jo^RlD!Y#DL>f-q7iwF#`OqTsiNd!`F&1kS9lBkmL%DOlJBe__buNUY|ssvbXS;RG`{AeS{6^ z{n{a!JMm-8mwP@r7~-i%YmxAN9~=r^Q#oB%@>}Qf9v2vl+;dT5A*HssU z+7-pJ^bv#AK_;P{s2#mD(5pKbNUC-}W_7bnU;`nwnzujZHul&De_1c`Oc|Lx7GO#N z8uZUM6=)nbUfN}!#bjxy8b?wx)6dqF4!AALXem0Q z9A(}yy~Ns534XHD(-q~egBi(_uc48z&)gcXoIenlE`&x){O=J0v#PJO8A)T|l~ z&7J}2ljzK#1!C%otWu^bRWmbBs%K~YRJdM;(%sH&rzyISF(D)5Bic2Crw}TnnuQfk z-PgLhahV@PEz%3ERd)zB8q z&=8ed`+`FV@7<$4gUseL^@~m#&}l~77nqoE*5MECjrrTU)wo=9{7v;_s zd|w6V!AzX;x6dvv~*yr zw&%#5756?fbQA7{P!FT`Uf+4%6jLV5$>KRW%{1EK^<>hWUN>_?3#`@ikJ?#0;!X%n zcXqH&T;AY8PNCr~pP)UnO<7-D%W0J(zgslaB@WTK&CxEKe9+zgk>@K7Xe})bhB|kjGOJS67_A8A5a;%#T=q<7qVDM^|feCz7&%hDEDc2e6oWF;6 zq?uccg%o=D^2Xj}Tm=!t#&XLtZ462@;$hUvLVqn<<564{B3)B7wr7-l zKh>-|cxkEX^R`fgRNcU1^%q{*c(2=99YXxc#>!h5*B)IpoN#IBMXsTJZC-U_d)$98 zN(>HaWq_v`oEanqj|Qp(#?`m=@-vFa{PvyaASlD>NjH=fZlV;cGU-NaqZq=Vv`*k< zGDbM&qZPc;3#K;E?Z>+Q`r?F)2dAkNa7!mbTim6n%P2vrpJfHXARKxs#$NtI-O>we zRIB$O#wDA`Q=^Wb>Idt_d%DxnU0Oo?qz&KKKT$=529(L;9*epUdmX{C9@Z6a z(94>dSnAt;kui4#^=X7dU93*^7gr91Qd${XF#$b{B1_^1jL$dNqf-%}sJ&M)#pqU45-ZgRhY6nDwIg%X}AbmI|w zHoqmI=tiXJA6x#2lBc>}ifMZtBo9wozsGEUUi;H|UCgqFG5mB5D|=L0idNRZGqT&C zY#d0a?F#zWag0qdxGo1(Dy31Ep^0$3fkvapO2t-fxPs-7PF?1oy%F|;>?G$a1C-?` zlk?z%fEP|Dh8BSPQc7>uB@N{6JZtSklShoWQr`ZocXCFls)LIUeezZuvbyS6`$slj zj;}JsJO{v~( zlf`YIY#KbcF^a$g-`}d9RzSK8IcHjQ+;Do@yzRGwh2*QevYV;%J;xl9Vu-44;o|+zN zSxhNhys7a=7q2@@HRjp}W?v#W3&&5mTBJ+b^R0F5(v6RhMLV@$UY$0s3J-QZy~3>I zI^?!LksP$b9u-o=CR>^;M)*uRj*A>Po9G_(SP$Erqv8!C+KMbwW0E78uWA%1GfL^` z$Ffug6h~nc?x98d14o~%&vU5wH#vg#8shkmloPbK>hgW8ebbQxOD8{MBIcW_lLtGw zsFxZ;)_ATf-8#{>K7(j*aGc8#&~vVfKxb*)wNg{8TT=?Yy2nYZhwz1KtCNFykES$E}b#i%sCxmcgXl9WFn{ZZ5x zn>=V)E>Z-+c%E)?Hw-MBLja07w)MZZkf13mvI98S|E^)i2Feqt4f#KGn*4p6IJgUP z&TnmWb^Zr5k~8iw`(}pgIM3iLmpI-}El}(Jaj~z$9}uHZJ|Mi!18Bxk3_-IJt?epy zf?2JWC}zDeu4>l}B-x={-;O_T&tZp9x1KCXW?u^0sOhB{VK3-ezd3Nd2{DV%V(zd- zXL8?}sruO52pgTNU=Ee=t>;XQUdk90BQcq(>KC}pNvyn0c-vFZiZY6*$a^Vfj)k>A zTvKLXLtw4yQm~LeoiXVZr%avNALrFhNBhl{4x!C3G}2YYl$n>BK-nDWX7<^OLF=xa zD!{5Fwe5w*%Fy0(hZBu1{)PQSS?Yzkv=5OShtXAy?*lfVSYxTCF7Q;&!tR`f7ErU| zwRI$o*fAq*xr>CVIARLw;ljkg&duyOo5P=gwWd((Z*mUpm5A)V zl4XF7>z*rA6*Boe0-=LGdOu;eEMfZ#0MdA!O`?==%TbqLfH5(M1j@X0|3M{+d|m!Q zwZBls*Hd-Lg`0n%Pu3KDj_xe~!PG*6^Is~L`GC_Z;9h=Uv|vaRqRQ62S<*RMF^vw+ zcNN?cg~Yn~iS}?>ic63wj&Z+oj#@QgU9JVxn3$-?^6m3 zwZe^iY1jLgOYvDlv4doXs^n0~QwyZ8b=&pRv|Fu;stqn}Egcg(LRG4-Uy4E;x+Hf*~$4F0CESh#Azr=CP0P@P;k6b{j5SDyROv`HApbG zH711plq%{P%K3HMg7L2RcD5Kv6rvmnA(VYUnxHIElv~V1!?_F8sh=1|ZN+xQgzL$m zhC(h-_>tYUNfA9eYO9q83*{ue(k)Ff%d?%r>dN#T4EwB1sP|^I(XMd$UPV+#%f-j< zTOPMgeZSCC?Spe|n%*|r_;H7NG05CU+kTG@^s<$(o~a0{lF_H8pvIV!#dL3p4~>z#)&uclzlMy3WRofB)V z1_=-Dq9LYBN}XcGVx_anA21R-C;^nh;jDWP)oqUKQeC}=(?{fC?+NLd($R)rNZbJ? zOmSQ{_s$MG`WWus%g{nOde_bW8IWa_ zLJ`~G3>PC(@W#y>z->bn*=+|`ct6=aJ#(<&cK`csBKYJ)|E3!d@+}<}KAh|p`n@8l zA6PXCvw9PL?D!x#A!0EgpW2FDLG6tK=Xy@_x3HarOUNA9z~(Kz zzK4=IW$=2GJUiqd6~dAB<}}Tkg26h4qBX5huU||m%Qn7KjIICIdr8=3-v-;@I+wAX z4CkI3WoXkEe5!7gDOLpz2R!zJf!xWgdb&Z=qj|eOAYQdGiwS@uSUyrQqtGR)C>N!4 zoy(M|242E4_wXl!eyW-lM_+6Ea&3&7@6>M5v|+a|J8Btv`~Dlj2+<{DD(FlPf`34g zB1}p$AKj&)U$>WGgekjkRo8S~YGTLrGaq@{$!i{ue@d0vh?wysLi2JPRuRZ8V7~0= ztC+N>-0Ur2x0n@FPJ47%!Bdbh^PDI=jiX^NP?KGXHG3Fjxd;!{Zn1H1nzCmW8g3;x z$>OStieNsYsS)}?eA$%Lxg?Ws@~v$s;0iS3q>iZwPNLKsLusPrv@*;Ps{2X1Q3ks2 z;uox35L4I4wS`?p0;;KzcJk}&6?(1{oU46)Di(GxdjJNhKUHJxBvPf&V84?5FuOrJ zlPj%0d;f*^*hBaE>rx8`0h0O)Iik(lqS%1VE0)xznY<>oNs{YNrt&zgCvg{J}YLfUe8$ygj7ls!{81PobvVWD9Sb?w)LHt{Bs+o%C38vD)E*pAAITvjw zfJai8jl14L-_Vgil=96^f4VsV7=L&M>D5gdH`T+09|j5z9!7hPveee%$ougjHsp-B z6^|>{30_A*wi0sG zW0b@bmm|*dV@my=yK-3WfY%6s^f{{(dUp*IYztg%TH4gtuUl?>)HW2clv8*B^9?;* zH)-peu#+Cg=5u-X0PJC)jv8yNn>sPGjyM+6V>8Y4(zA7vZ~h*ejb09t zm9x~})rDnjYSrtSZ3+`o$r1i)2S_`vCRrUBZfi&81LhGY%FV$ujJ(>xp?#wDV-|_? z0sNN5s9u*%S>d^@^9rgw)yj2wtcU1}+Wu zqqqm6enm~K6Hu;I5e6MPGed8{gH>k(2D0xqDOj+&PB3T}IM-L$-ZKA9WEy2cGu15M zfWTUWtO8Pty7jfpp@UU6-$=~#Kr)r1V#9{8>PaqpmXyN~)fa$@NH9$&al1A_@n}-b zuA`U53>!y;@a-Q^yNI9h$nu1Zb}ep|z6{f&qlEPMsGB{bcb?crldgC{t+Wl(+zG^Y zWb;3D?vuPzZznbDVAy6Xxx8VrxTDMpBRfvw-ncfqc)_iB6BehLi52=?vwXu3YI#RI zn44k(04qEVy^`uwn1n9^(k{XrTqv)yPTef$tBP#(zNO$j$b4}|Ng0c`ca881_yf{r z$;Q3?`RfooqVhKUj6`TqDQ5uOg)l0Z*YFryF8zXk^#bTHKfF9n)>RkK*)jPD#RqFfYs0t6>HP=&Z zEC{}?ZTTB0$`=EHVgf)7GOw}OWB>gc8Ytg^4)CEQ3bUZ37FN!wtGj_3%ksJKVA>q{EW{@G(TLAkpha(Y&jwh zDqLB#^8O;6>`-l~=bYI)g};d3P7_kGa1d$Z<7r$K_S+CrUggfrn;u1z9W(~0Dcez0 zxjPI)+9%ImT7;%2lxVb(|`=?PxBwKc_F>m<;tGb3j6!JJQy z$~2>q>?Lc0s=Dg=dUaqsW=%2Ed`;uH3_+B^bj8Bm@E;Hrr0=8zGV8F*zKmg)$rTt; zY8T=H3z5DbJhc*}eP-2EkSln!9QnP#ZbWPE7wg{p+Iw>xenUW!rxKeWm%iRgX=Ibb z-~Q);UbogxYf78OcbVJ{A5v0(J=f)#V@8|o&){m;@yvBR)K8t$8)U%WUyLC;K$A!) z1%wPOS1uod;UqvBrZRCA=DGo)oO^t9Vsf6!$gW=6@}d(jJD;4HX^Z<0DCLK9!IIDq zOqgn+e3lE_14Z;iJrvK7@U@UL;m+LNsq71I$DOnG=_1zJo5(JbIL!Qs#eQ zPX0e-MgEnvIzJ)t1Zz+%b#DbX8|W>*OuX@}CY-{*D&v96yFn3{`T+Nn_^1}v{hW%K zb8#b?fWV`19ef&fV04My2;9JbTazpRLS(kV=>3`DlAP+)r=`RzksEOZ6n=&cD$oOb z(@p!|FXvn+%H4l)+_~>`>=}z>6rH_)a11$#0I!kHwC$1t_oJ_Ny_y0rM(EVW;u-C~ z=76yX%z+5f!Cwv;bHdEimgJKdjp3D45H`{kDlZUmPnjp$cl*a+(vAbg09b$^gbs!M{4` zas|}iVP*L`137~NAn6Dwmq+W~Hmksc*M}K;#JIo)O(FC2bt3hqbeH6NMk+|TuLf|* z{rPpa&G7B;*VQ|WL&O_uaQm5?9s z8bJJB$9#TH5j!m^YfGe^&b>IJA?4%+GU|#u#%Kr%h+z)Rh(gG0i7%PCGMI>uS4)rT zGwvgR@KIuqJd z`V-LWQpaqSD^Tj;i7$nnfOa#fUO|k+ahkuzK3WCen){H?Cc5rO`d+gVL0)E;ag>_8 z4R44!{ zPM1qCRla^h#Gd8sK27D6y#v-XlTRNI?IIW^NH;vYY0I{N=eCbSr8C2?{)No%fawg~g#Bd}Xo+j< z%M3d>j7HgWOXW-NR{BTpj}hzskU1J}zr?3imERQ%axu%SQ=t(&zD}i9O$uRU0;PKR zWQxb1b5?Us+t`Oqo~OP__GdwLOr^d1Vj1dFi^)(pYWPBFl&EQ_NdQ6stQkkcYPDA^ zjQDyk+!s}zt5NST%a@yrrPqRIF$RQ+n$TGGO!O1DBX$b&#iXZvHJG;(ok~0tRa>ju zm}v&Y$sNaE-iC}vnatGiL}Z1m_AGpb`ySbUr?nLkqz&F4+nlP!Hz^hD`LXSfm|7ry zd{;O^E55NOMPmv?My-XnfZ{Lvq__Zr>;5KEpmvHeVeM1>tq0$;Mu#`JHiKy=!c%_} z_Si2%b>6L!MRWVQu!1z=pB)3y{3SKX`m`;bff3)0QkFP`T65q7cbz08P4`)$YZUq( z$y%S;9whNq4=CfuO22PD`m2By9z@k2V?iB^#@p*AgZXVyvAC} zt*P^eWYI3apNx+|Ha`MsLPaNH#u-woj{qKN`}ZRqWkF-4#}gAgOZm`mJ{kE({0c48 zOEUv6+OdX)95J*3$(^3PqvKrOfeg(VXlRSnHsWj4{T^xC#@AS9BxDIKFi zMop4m)p?d^U+W?my$6c z1@Ulq)%EYIKXB*OG*6kmTX&xqZ@A-D)1x|95$>E^f?ISxTktF#s=u=@ikGu z&av9k$ZRD-)nQw6beoQTR-=r4bMbQv)87)MXu3k*!V*#VH>u=wr#i~3w`3W=BrRzg z69?~YNR2}L^xB)`Rwo4Y<~ApmQupVb8KRPnJ=mx=4h-!Y8*gJ&4ZSD7Oq3kzm}2iz z1>U~Hg2EGggj>#D?^PSH7P8ckwv(kTJyPkr+b8j zyA<+MRn_&gwv9|*X?MilGE36_Z4*Jk&I`jtt+K9;0GbWVPy63xh(Dl%aY(t38eHv+ zIL(b|#r-c0Q!P%NFhch==(eUCUtE%F+9dvUWphfpnKyE_msu9 zp;K$lWyqQ~TpQ&J+}*zbz?}m8zZ}-sco@z0f&c$D{J*byVdv>&N99lgccy;vL(Y*y zyeYzA+BsM=^k9?rfQ0bY?1txp3;skn@>i;QU%pbPBi2}gG&0&%bNXEgvD6bx5PEi@ zcH^V-Za|&DY(p?InOCK!+?F#R_%7vNU^+b$aPAURI`Z=dmh`(i3uS>gQG(*S>W zm^ie=X4ua0BkaAoA$eNWC9y1ufb#@l0R*Cx=%qQ0s&GYU+g{fF1>l>cy>dBc!g73BgffQtsqI7s1@KO_y#FGlkaed4ZAxuEW7L?L7r&>M28yuhTjUz3;E1+8gwt z?OLSXIu4KKxH+u)r$SO;bO1+Zz-s35=Z4|O_NrZ%O+k*IZF&e?XJ`-cHV8 z5aE8+GQ)7D;WK!#B<1GzrAVJXWj6KTfY#vjI-|UcQawEXJVXsORJPCqVE<1ARFeWS z+Q$=eqvJbbZ+`!(Hq6kcQXgvAsAs$-w* zNjOH!LSO%{BmHBS8_leIkiiAvT}NH5ohVlDm5N%O)hTU{7HYTb9!s7g9SSIvkdSP+ zbq)7m-6%BX8qBo8SQPCh`zq@x?bfJ6i*E#5jB^^d&QZ+-OP6x@%H1icQR?m6Oj;vO zTRBljhx{{*b7`)5LGf>LYQAm>dx=Fe)d{$AQK5-W$>cpov?||6)_q4M*1#=~SZSR)zTQx7)sTWrWdWTx`@~;bHn7Bv z>w(-y1h@mU^c?#BGTJmXqxQhSBj9s@az=Yr)(0yM%g1Gmid$$LEw@mUqUJ%e+_YUB z*a1)Gq6i~bZm;T*z}wVJAHW0K))=Pf;H457@!amL^A~-PJphC6E^i}+^mX&xyQpq`NV<~1rOOp~f5fspVIaQ* zQx!f0Dhhs^akLI~K4TbEQhY?h-<3 zoywAWO_F7jJfqaIK|P)45&-X!Uv=tsT`>jZ}BbL>Fc;k>UJKeu$x);sS&4dpXRgNC?47u-bgJkW%4 z{;#3mWaP|VtJ=@^w)!;F*AoJ%rQxB_w0K?{f}DlJ9K1@oEia#X6Z55?UL))#@W=|8 zyQ8&%=|@pLYosF7hY^7+SXtWy)Rd(N=k`gPd}@9hjM@&p=plcSAc4y< z36IoG5KKj`)!y0LeSm68b0Qn=0Q&r9}`o->XiB6?B3Cjsb%+2K|g{?E7M zRZdSfNskiNG*t(6kwA;A*ch9o)6%3@?(-{jSB+l+tJpF?(VlW|Wq?&TDMuP;k!{Jw z{St<2jpR#YMO~)#`@R^ftBvtcY9Ito6*p0ih=H+nTKHc08uIyZ&Q5KGe?_4Xy`J9(Gx)6d7>9F z6+83|(YM0yU(kZLu@izDy^%DXEmb#P;vhoxSUUs>2SJ_qPrF1IF6|$d&%CdNf5ssvdraW9ex_L=R-OVg5Tl3wIP+u6f^KqZD_EI zmvbX*hPcUoR^2iP@?2lu>8XeMP^WvF^*06`3AwXV{a_};RYXf8!@^n)c`i}-7_Jg&#LzavOi^{eX#zapmjbHXow3fpGsEMht6UZ-iVcl#E{oR-3vjFvi zj_AvovXT_7sINTy=Q{rS!jiC5v#4K2)G(&WJ3}pXX=BB`^wlSuZEH53{{n9MAsy97 zARJ+w0T!4~kAW^={troal6YM0y?7Xhxz$T7POsHlcZ>iskzUWr<%=bMWfXvw&79TW zKNbFqjt9G>zWwf0ZhhTk7pLLmMi=p-7gV)3Y!~}rso!yC22mF&(Z{TX(e~clcEfTJ zG~&0v|8B5YIoUD7KN1=2MFRfEOk&}>%K+j2N65js(P^0&7v}jvSNv{5;hX~ngg*JB zLh^D*%?CSUJd=nC5%H%PNg_9MZnszh%^4m@E(c1;Sf|@9&)*C4-%};-Q`5eBN{d9q zq8_yMz06-c0M_mQ{^`u z{d#7bjb>fR-jppYjIS#W&wAv8{zI!fg}36(%Y(?z=fCHG>sh|xfFQH~%X512&ujA? zfEGC*V{>b5NE`@CSf`0L_(bqP?5^4Ci0i2K4~Sk}a7l2k6v{h<7o zy?dem$vHrX`{&nFT!!NDoS!&i5uHj5e#tu&(bqW^1>v@d$f@;m$0-#BzJ_1#T$CHH zV}q}{&v=3_?+qBwTW24+$G-f%^k~#6ededr$`il zZH_H$-GDxBZMKg8ci8h^S<#HwJKzi8N`5cm0JihnM*zG#3;e>zqNU$F07k=XiKMbU zb}V_!I;Jhs_6*5!_Lx*Ba*&Z8S?sYg?D#RzDBxe}621IN ztz`mj|2=US(n-HJgeN3vHI~5U`h}ObiHZ}XP&z*FS(G#A?#K5JM@Om4r&^ITiEE`+ zRF8R1)a;@5AI!GD_iQsE9ym$_gRHD5j=xtdw9LyLdMHua`F(#HI{r0az&~5FDY@7r zPX{(r>_J@i#L-ae7web@>u(qR(TG(Q$}S4lu(Gdm0x4C$4Zo5RO0&-kn-pttNCQfk zItwg6&p0(3r=BU3e6G^dd9}fjpqOczU~>1HBm3SGUA?nsnPv)_TLYWY)K^B8y!??s z$a>dmTyc`UU2dJpG~ud~8>!Jka>8)@&e$D@f&z*Q4^p`@+wxQk_wlh}+I`Id^?fX3y z3Jil3EfyTVh(-2soLkY~3pH)Ohity|`0ZWp7F3jt>+e7Xx5xfozBO$^&`uxo9$#^R z%L#j>dBbIecZnf4od6_$|);t%bMqAm?8}f!tJzaF|+FWmIIy1&qK&aj;y8V>Z2sH>*fz{u=&2YCfA?zDS;O;W+3Q!a=0Zb5ggD^os zaei!1DSwPkG-RO-u7lySwnFn(1@u;^sGhYOF?$ibUUcZ2317(+LmO67_Ze(shZEm^ z0uMgSi_Jbzl!*tm_d6`7RL(>i`dPQ)LdX-VI`t0=17r6UD0gYc0mo(Cq7k&dMeq1u z~pMA7y+A3X$mvS3SD1#RteVYE@j0gBZ*qKMH3yczZ7IsnK)K%qJYB9_! zzDlz{{%-nhWBU>47kM8>(}wtyJzsFS>^ctStVX>;xP?X&>)m)IvyN)RM>&wyzZB9I z{Va1E5Mx+Ac!;n6a#i6v7j~(jmPpDEc&Wy73{Url(E!I^6@mYKdlV6R#f5%rSvtL7yxR z#%h7vf}|$-)`DhE`5?p7iW-xADSN~HFs>IAr%*J7B)QW1gC{5Jd7uw6x z!1j#0*zEG+ZoO1Jf7AMLe1QKFq8Y0^QJw17R;Z(Q*E>^bJ(6ad;+ zLR^XgyVY(g*RNU|Mo;(S3$vsksyp@vIr+-XeMP-F;v*4+THTHdi`uY&G^W;%|J51moa@WH)V_Ag z(q_{H1@U{E%vTnUVfo)<9u)NpP9mj3^i=WXEL^O6_qnrHlM&vEAX(+2tD; z0n2Rete~efms~Ky#rEWR%NOP$iWigK_*o;lP+RzoL%wXj<#7H;LRF^Jnvn>loM-aB zF-gH4^JvnxU#8u+k(1{eG>s*9rF)b%egsB=RsGlBg8RoWD%-^B5axkdB5I1E9Fkuf zv!!)g$xp9lBYb7;a(^okd5|)Fu?oljH7bHNQC;fLjsjAMFRI<{x?`|AHJEV+^__<) z{%pEiHg3Y*n%u~DC&6+Q)HdZ^P?N}-g}PH5x+#QX;LM|QNxQwtKFgyYD{FsEuzD=+*Qu{!G%jEu+eOhLY9EiEdTe`ZNyY8R z=OsC9N-F~|m9LqCi4A(9`F#5to#0%L3W-xn{Bs z37xfh`03<%+eG$8R>}!px67@zY=vj9)alZ6c^#~{-9~WoFr2y(k?u;f6Y(2^C6Yty zl~bGoeIV-VFSuxO6ExhAT$1SQ`bS|7alOSwdH)HeGnhMRAVSK)lT)>N3aMjfS0Xh_ zlF#DBp!0-uj!=X$lrf2TV&V7h4Fz#sMJsllo^r8i1dE^XDnb8E2-;1VYUmTDv#l>? z%uWo$=q+d#Gb1eq*YA|B7w z>QO6n;I{+deW!qE?XgUBrwHq`H^qfpV1A1wJt*T4^qe#>b8{mbYFl-hDpzKuokG!* zTSU$2F;|XEQ|lp1B1@A{5?r@t@RKEdI^H!&eOTI1wA7E@hzgW``{ieJoz}?M z5_@3&dMHL^v1_diA+b7gRQOH7)q8J|HhTb&B2%cqfKB>$PK7PaXjf?U& zyIG+$4^HcfPj_DZoDvWN+KrBal%9ttyX@O+oZ$~9c@>T}qYP1nn)>M)Vzh8oaRAhn zr2!DOKqZs_q{C}X6+w2{hJ2!WR?>D_)n_FK-vO0?l+Qq@s#gU7Ic~w#%NKt@ z{g5H3Cs0y+yb}!GH36#9r|jUK*#8U(WD>xTg4+LlqbqHQAvTbCIrpOO$8GCdP`iIX z-+XokX`W|tLdk6i7y7EZxh_XyLg~LY(gp455SOo)TG}E%l`iP^RLSBT_EYf4z1swF zvb33YF8uCT(D7HGT-@`ghV(0qfe#Qo_fMeUKyGM@tbl^{I30mLc$6idcJP8`Zp5!7 zw6pH<8LgB#9hx6G)Ae>?%PDPmg`iI&O{|F4_dbvL$mrgTt^lkJLp!f?-|8JkOT_ig8$gbDf17nVYHg`5WVc-wWAv>Ah6(&NVW}si zD-|P+eahh#p>D?z>F9YzB*PB8at^%}$7M3DP)RU93EZeua8EHi=J&=AU8#PmOt8NK zJEU@Qcu4Q9Bt%GXX93rGJ1gHx*CCW{1}RJ3J>HVEQC%G(O>+7TkFoXfLSg`@pYEJj z7Xc1+!$I#vvH02ZRH{mT)uPlv>F7URXRf;fIn9!flDC(7vs6L%X&y{oo?uxM%0UX0 z`4&I4(-Ejr)?LM;-Th|%8kis=vRzvq_O&tNrJ;Dgun(v6jnaZ1C-j#R)pB|Mo`*jr z1uBSYX1v##%l>fttI`%fyQ!(|1I^%1L4AzH!{(koD0w@6R2#7Rk99kEmTdH}=eCnZ z3UUS{DmS{`eTR4p#kP(EiRflvI^igB(Aq^T!QPj@oMa;eSw$1KDjsL;4J_mGYGU0d zr3Kj3nF+hV*Mz|CIv%at_VlB$XiwFHYEGpe%h^_B9G^{klq9fzs%-FJd4}Bd>TV5J z#JfEwv?lDQ3j2;*AR~=67GZ>DrCpcFG;=vvYQ^x=4)=%zi_CbGbU?C@@uK2&Qt=?q zR#eiIwvqJ0@{8@$=&2V< zMW8K1R+<)1?Sf~1oZj@f3%wJceQR6Sk>$Cr%^GXnBKM(5*o~;1&2DlfHVvb($7()! zIjN}Aukh{l%?lCFP1(Q)=6j+|Sf4F)<2^yPp*|3j1b|3-%7|IEpo+2x;3-Z=pr``~lzCLpu|x@fXf zwyY z=97i5cDVe}1HVl1dj%)EpSquxy_1iZ&wUb>4U+s^yzh-0Uv7)~J#oZS=eJTT1FgTv z#+~D_t*{zgV;%E{WHDW+%50Y^ z@l+^&w_{{wPjAlgyF9{KvWn_~j!Bg|5`U>ero1>`zU_%_vP?8_w{`-QNL4t z;kQGB&{k}G`1@#Zr!GzW%e2?yhqhZ1rk^piz+uFNQdH1@wvAZ;p0C_mxzOG3Rl6$s z2>U!GQWqlfCC1b-GJ43n>P8aA1#(<|&{Q4lt5~n02ZSXZ((Y18Q&h%a!zl&HERQqm z4kH|KzFT(}97AP!Oo>98cgAh(cAbH<Kb6v6?v&I^B$?u$m}m>1}nbIKNVcm z{eog|gfXwDX}U*OMR)ecKJ=l4JL;7rg6@x#8!>v zO|tnqbAyUHLMS{P^Qnb9mD}#GnN14Jc)JqGe7pR4IX@PU#XLI2xr5|`VJxW$N-c^X z6Ne+&q6W8|+mIClOZ3cBk{?!|*75+MGKRV-fr13eZ!B?)cp2YBuu7`qq;GONCkl$! zX^CvyUkPQ2D%d?7ys@WX@;fdBT26yjFq?3cI}t)v3`(U|S{_i^MVqkq1NVjt7Y!qTbxQ!kR9tk#fFRZ`=) z2^yXc;K)puA8%YR*qXUSZ2(;qLT5DD)B%IvK9&=J~{Kl=HQZ)0W%mfvVsJV47Rd5n^2b($^pIN^sT zOT@ktRpUd(JoGx5`QNyE%dj}MbzQUx2@rw@w@#2iaCZv?4-g>GI0^19jW&S*!7V^= z65QPzNN{&|CqRJ48|!&%&b{{DbDewkI(P5$@BZkgdOTHKRb%w18lSx1`_}&W(T$!* zlBjf6oGdz5*e(CQ(BYkUX|XpC0gN)W+I<+NI&MFD8P)s6fF{VAFtJn$6Y#tX7Nk?GW{&k~(C7}<~f7S`~gzv9_+f&SME#hj6OA_&Df zLn<)dAtEzrxp%bV@kcrvwkc*2Lq9~RoS!x98GUg=6otAZ?eUTcQp`WPigEj3%@wX_ z7W+->6$J%@&n){Ivsq*FwEeo_X@7wTUCf4<7L3aJCb8f%W7az?0N#6@lgiMcz`eM- z&~)w*)gU)iFs;fuTp-6cxxH`yQrN*$P=xIBk(gw@b=I6K=Un1P7`MNPqByTyXbv<~ zdU~VXk5pc#^CgBBHDPp9aV9n3T3+Ud+>~`6c6#wtr@5O5evH1C*W0(_^HIpR)hA7w zIkIZAE**@DMS&5j1$=S}yD5n)Mjs;tU!7wDLg~}4n!4;4 zRB76cNkF;cn-*Fp@2M5)x4vrmA)p|a6wCuH;U;f4B5hXvZXet!m&Ko)snHbN6k@y4 z)04p5>~QpR-Zhvv6y2ma1y!h@fF6HW?R!x9ED!^0r*RzS`3Fc+6Hsw%%2Riji;M7~ z_Ae+wh99U=YUfaY$NK93d-3pDjITCTH^XbMxN6J%^~l+Jq=tOTQRI-BBq#f@OBQJW zS+fTS-0UB;Qq0rDqisRfIeJZ%jB5QeOp9v(V5Ab&){pO^1_4ZU4Pe`1l>dpCDrgM; z9uD~bdAR^#+)FDo7S;;ndGh^2>Nj95icy3ue{%pL0RK^+)K%6FfED|C|2;V>j}`K7 zoO8Rs?zc?~O5vo2cQ+aLVk<7`*{>H|)&C)oEL8TjOM zRj(!AN+iF!S|Hh+u`e>%dza)>zYx)FpBi+9$(4bwhi{xS)x14Q zvX`N}Mz`GU^-Y;v)r{TgY2&VQV0A;spN9ema>#Ft(WQYS>*wMag=9Ta zba!AFb0_By5aJg_E==H)*v#ITB`kJ&=H7?t34OBA_4o)cPG@Fvz8vNZy@TNee@FTc)1CSE zvyU!HdbEt2J5Vz1mtu-}X5&XvkiVi^#l2eGS_#tXa}_P$gFQR3)|C&wSpbOF$1(D51mmLn#gY_RLUprF`<*MZr#Wz zbxn@>OvH$a(KN`<;tq{0WnaJlz9=g!P&%qOX*P*s_9FFeDNAa{7{AO_<)nM)@DS#U z1L#1oPKd!y0y}?tSg#*rOV_Nv!tUMS*$_2f>;-qNEKAg#b%zxAIUnKFU0>*w>;Lbih zRlvzs))eKLh1bTppZUbCx^1=4`r&53#q~OEp&BY^a?jvJUcTY4n@{y3k+_e#m~f)* zejbVMmw|kGd(0-_j%z+(3aE>FGwGY>jf+<~QP-W(#WLQ2f&!ejd~cx}72ojK)M>oe zoiH5QoLlI_b1soHHvRlZHeTBLFQ%TPA2-lNh2*Pz9*pOBc<$Vveee~YrZtG)jouA5oq6`0x^&k|H z{RgPK2zck;d$W7hB&4Tj{vNmb6Kp8;=s92Qr?;3r{=7i!^Waa@4{)w-xMmo=d%KK3 zWikLkxt<#!Do|xFJ#u4_@rJD>ht1_(puDsyejdR0QhWzwCZ!KoQKBgRTZyOKKL_zK z4^6B0Tc}le+Is2J-3lnEFD&j30B}n%1jsUy0fka0s{kB@#5k(`mthMK7KQaRx3vcW zuofVi@FV#;BJom~HiP+LP~6Y*mVY`704)0dnX2^wrWFkUFqHV)uR_^cs1ta(2f3N1 zQqfpka)b6+%l_3RlV=gIvr9=N(H|hLZNF&6uT_IYYDKyKhbzL20g{~2xj#T_%6FYf zhS6$6u;YeZ#ij;JCW)rx zv($Kpy85>Z9|Txqu`7UVI>#~)l5XGBSoCE$sT&@00!Ro)NiRY0(&CaMRc{Ti5M0(< zpyc<@4klho1pk%uZ;$~TFW?rW`RBCdgWb3RI-b1+q2v*P*iY8nQNz=pFZ=l`j3YN$ zw}5QYsZfqh4Y}};UN!CdH05W>ndDpug0uhjr{%D_U1O#nwXZ#AZZ&* zuR`a~3!I~shsbUyqqRjd<5D-p>kfkVXaH{{FvqL%m(+@o zdlT;v1LTPwxsyvG#k-9^Dej_3{iHVFT0YjW%YHiyx?2k4riQrm6N83Ny!Xk4I43*u zy=%5}cK&!OJ~(4W`+I~*bfE*E>UodU&PxQ0AF$OL3ame$IbyKZ)kzL^;_h`U^AYm# z(>CVKG^P}$k?hVBlaz=l)rVQ>69YjTwmB>P28l$uQK|T&o)uXALWcuIJoB~*#lWU` z)k<^3aWG{hvtG{)Rn9!c8#7dX+1}fNP(J-v8>G=wKiP5y>u-SKdl#SFoD^}>$od_Q0ynizIheJySA}@sIt}Pn_D3F*llQQchY>9z zJ31Irg%cfOAJdP_+?b(jXK7aHZ&LG;2I6ub(kFh2;r}eQS;=sc`XgNTSqfwDfI_HC zbvl8c4TjIv=k~2f&KKa3#<#4I$p*8WIb6yxFOi0KE4}=jmrP-jyPfJlh}d3NDdQ%Y zV(vl>%W2jaLAl+=4(mP207zM~u4k!ebIPoF`l&qylcH5=JbBV%^eX%cS8aG$_XT+k zL?T}%hW#jx6qaT3aJUoyTYhf(HfQf03ZPr+TWY^JkVFO8Y}}8Zlc>4K{$;U$Pl|o~ zCrDb|5Z0U9el#_W`&Z^}FF)WE_7{HfHVjD8)!zY8S$g93Bc{_*rJI~jxQ4ZWUGIFs zuT*AzrLMpH+F`@GEU|{cYEd^dTfFeWFiF*Y-MaA&nlWt65lGI(99Ce%#;|VzCUV%# z6i)AVAOc4vdKkA=Trb5BNe6dfg#Krulgx zWtXS%P3C8G_HaCZS#X&wB2BAuVslzzx!5nDPt$6Z^0@bQAExx)8FHeSZ>((T9U{CT zO8rXjom!@2`*@z!@m-?Q7~PA z^WYV28jIs@I`?L{McR4{-o9SzhH}};o;LS)Dld-ntGI0wiTBb@T()x(*vPC`6aG}M z>`QIE-QgV@CY7T+^xu;H#_9WPVeM%N)AQU7IK7yHd{eZ!BEswq-!^1 zLf48`NV()|!jKzk#JyveVkIoo{pgQ$;*$9L3L51Lt7H6;v(+Z*f7LLq#!D^0jRJSn`V&2 zg^Lz;`Zse%c5iQIySD7b|I1k!8+)J#Ki=X~)MOwj5xyLr6F&83MV)7= zJ>GcW8Y|6nFha@Me)y&4Y#v+f{ zZb7xx-la3w^@k}F>fvL6KV#z^M0P_B4VlmZn6yt@Ijl^W9=Km`N+O=eN>W3_frvJ? z9_ZCfTMJTDC~IBdvpnMUcoy;r;XUh?-i^Rni-s<=1gj!MN3IdM0a)J~V$x zk&T~);z3T#i+R1scvRV_Or9k8;iZ9szXiB>hBkQvms^b9xp)Z)UG1mY|M81sS?mjQ z7x&`66!k1xk@0Bpelq0Bl6P5YqR($`Yu0hCj7i-dZ|1DiQ^nHL-HU;2woHgnuj89i z7(pyoS3<)5687NSBueXwWSC>Cxx6(W|H*>QOf$}mimTfRgNtEJsH{N}1;tt{E8c3? zs!e0`%A$goMOgwr&KNr_~Q+PwxTXcAMkux^|T>4KuCs|+{*`nTp3~WPR%XSAX zxG=U_<^rJiQaUI6U{?%^0l9%vIV-X!%P2SY>c1mE6c$Y1KQ3h{4WI^_XL?i0`C=CZ zJoZi`(7@-@p=_{uOvl+W+K%MYibeneYQGzHCz|s{!(N(G^jkR1WS`_3GkMHFiDcBd zPl=+^eH()Ynpf@KCOGX`dEls8&E%Sno&AS~C~r0^V(hXK!)vDq=*RdC+VcVx zA0{kTtH%c(AEK0~<`QlNw33H^9gKNTjpi>5o6R(E<(>$2hEgnR?Tj6AtZBg`Yr{Ps zlZ00b7ShLQ$xiPC)Abe&%zFC}ltAT23C|O#P46p4+Wd3l4PqD1P|Y-o?v{@>IYSTg z==UkPtl4^bUVB-!-gi4Co@bIw*0ACi(!m{jQKW|Wnq=D65v<>pVy<`YmF`8uM|ghq zxRB(nZ|V9f7chj==xw7tG$TwM2J&IRIz0{u%+C(MMCvi?Y@KB7b5+>k>fLm)GIRm* z{DUxC8}Qk+;QfW6 zp;&&ORNxPCvLoMYEK>r>QCaiRs3oG zV@n1p4GEl$k=_At^bP0HZu07vX0_WF5ddtYml1P2;$2Bo0z@3B#zPUJ^luR^b zuxAL5EAljXP)Na$IbF12J+awEhD*3q@~Q7gs;oU&gz56CYxu={h)IZyE7NV!=vlYl zt1fdO=K6Hw;~yZNoe}^>sR0YNkVx^P&AZQHOh52xx13)PAaXcgoaH~J6^+@b%P%Ok zB^8OS8h_8upwz%3@H(fQd#3shoV#LWBp+6nNS4WSf)nhPW?M7hKs~ZqxB+Ng+^WJS zIVmUK)+H^hJ2$_4TY_^-+3vh9NuawYqtQHG@vZt9SbXh$HtnaAA6NW)C`?4!&&@wT zM7EiHnXFd`q;-Mc;)HUbpo_w9$vitGSx;(v*d60$hGy5Sghyu5;r8nRf!9g`Brvs} z05SPDh@+Y^>C-(C!|mVB^|Q86ijK@i2JD!3N4uVWyUja6R6)$CoePtcYu+JeUJ zI1BeyaoqrhSJSQ}J%K8>@0VM(IU`@Icd^k%L|jLefM^M|0W?I7$Y2gxf2llpKx9AI zas+Z;yP@6*;5n}KQ+^Xp!A~QxKOy?@YbsRtVGzYYyzt#icD^!c)QZ<{I|qm74OIE@ z%qdCS`&~HrJ*`0-uOYNAkcMlI*-WgDEI&K|id;>}4Pcvf#$6sYRtwr$h>8x1#;FPl z^XdE;Wcpcc+#P+AfiCqk9O1Ot98Td_;9}BV_Ts&nYz!`8nUk{B-Mj~!Xcy0 z602%p45!7|*CJXzIOg@dIKjw0CE@LlyjGGD-fS3yghtDPUc7V$)MhnI0AHIm2QeGN z4@~2QQQKSt*-Ps=(Vt?hEDqo_<{F~}dFx1)DtvVVZOCOITHk>xuB8&iX()SiU3 z8sw#>+AN(9&9K)Cvq5fut(=h>V<0pW5Cy||g&Wcw!Ou~)KI3cs)Xs^LMku3+CRG){ zo`6Ru3VpGW9;vPCClXZ{x1x|mODa6ZFYYFy!6=y04c*2Dm9jMlhq=PHC}pu|r(#SE z6_BM$L4A71rlM4MIQk+d_JBBMnXK0)F8-UkXnQsFkg@(NlUNiYZWfD2ZH@H-Yldy_ zh*@Q0)@#IyQ!-&x17zhO>%uw9817?IKiL^;O?tU28-X$J@hLGfI24vr?fM2g48WYk z?r{^g0{mJHzl_~AKEn%8~LfQ%LLD(F>w}!gGSUK@Ri&HuI z7R9BXl3bMX_IQU8P=b=I=$byRH%2jr^-$2bV4c&!c{eP7%q2api+S`~E16Ru9q$#5 zV$AA&*5E{IBD>|pbzQu2g!;^5yq#C5PFl6G-9-}rml{xQg)|qgKDq!2!e=EU?_W_9 z$kT;ij>bsh(^saUh+1iBDo1V|b6#~c?J?DRgJEUR#Al?fF_&($!3E)*=hmvEH-v1k z;{x?-@C4kU_D;A=ZGDwU$L6wtNKdue50Zo5tw@Y^^@!wA;u2(r%W$z0S`cL>NAr_{ zMEpO>S^vGP^}oCQmu0a3SuOkDJ?)>zlWfCkNlRzIcu6CI3k$&$ujj{!KT=ZE2U!V1+y6rGb~BLhfWKc+{+DaB+E`!w`2 z&23dvFFs%&L-Wva#CcdJeDMq9J@FFq`gTZcxo&$z4l&VJQ@fFMR8}jr@G1_9RI>=D zBO%9aBby9Me%4>}<5qghY8(iQAkGM1+x$J8p$;$kuU)%@73??Ix6)Yj^$pQj1oFf- zgamF{=pcWsGvnU}1&pIHoQ`G`0!i{8&Mn@z5AvUDH+b_cV_zcDy$D2O3aS0;_R@F! zlJ8V6`YX&H&d&*lOe?N$f&Jh3_>BW`!?OJ$#Bxd{VkXPsuCMZCZ03<15Efj0Jv}(s zSX#DV9fO`tqjQ4|GQU67=}dQwi>8lsH&wTu;e5(JJiqGBxgxnl8<u~8<;Iq+ZX)TglCJuxECD(3 zQ^B**b^Yb0oFws34`00%jw$sNqm? z^&2C3bJ$_XiLNyneXjoaKDG4MD!!Ozg%0~sN^U=6OFBcmLfm8g@5k@;5qX2O9sC?^ zT*&5AjF62}fvDz>w33NH7O|se7NGsAhHb8HDw-k|yB8u|Tg$@)o_*5*3eH=$M;2vUxF;C}q7yMuwzUZF7|1{qG_>ltsxt zjEMi zu4a;BCsTXjbESadUEy}j`xZ`E#|Ib?IAw<&2ch`d5noq<;OP_NTc9{Nin9HqnA$ga z>eT!&cWfo6@@$32=L1iJe%n|}P$S#enfH0D$Rg~DcAkE0a2z9Zp#8;^S1fj?i@q+>3q*WBr6GvN~g zn36E$J%9T;S38h+B5l9=`4?lr-&-xth~6H7qz&6Byw`Fp7?z*2(hAVdR;tQh~iOzT0{WA&}G-ATqFR7%&B-J~{yE8K@pG?=kOeSYt@`H9N+?MT0sY zeK!D)))}-Soj2|!RcsGh9~_CgQ>6rGo73jKVv{7)fz5mV0Xo}s2Q=uY?wGd~uv^vm z_rTb78T6f$j-M~mZs$y<9;F2KkTUsHQ82=&Atd-A7b)kr5x;5&lN##Hb&UtnJ31GS`Wvl)J&1dLai(%yf7*zkCbEDQF? zZt6N-73e8DGei?gb3V)rVhaD2hlFe@FhmQxy+rRr=`m*#DSJDeqpi-*`wAkA!=83) zx4pDiqI$P%ULc@7OHg@Z3Jg?@Wp2~1``qj@x1|aemyIaZ%~)R zk?-XMGwPPU_r+@Y41=~WE&lA09f#xliE`SNDSQzr%>K-bQy4brVlgHn)x4qesk42) zRo22y)KC2=0p{r8^t&U`%nTK%W>dVJ3y7^d8UvGm<|m@0Ct2V?jFLEtiuwJj)h8$K zr^%Zq<*x50D)t~BHiq=~Njkoo?yE z6duLoD?SKd88-xqA@JZ@wtUVid4voR^mOb)Y&vvD4(OSIReZx7SGrU5Rg=$bBT{&@ zxup8gnc}6$(OW^9-}A#)tanb|hixYaEd)6qL{Co{+;N=b<<*P|h8_vfIoij|{l?(U zDDFaiLF?OyglHAq37mKonUX9=M=-<=@dW3G0VSaUH4h{Sbwxr$-J>|)rViYyG)8Zb zF48?*4Z1K0LQ;Z;y2(r8_9(wp=Q__Bl6hd~^nZv~#k5&%MVfE2i_9oTls#CJCm71q z?|rU*RQTt$2Gk7=V>&s>ZM2=1b*hrXzk%3vJz_v$zGzYlRhp%xNz=)Y&nj6S_BdQBG9mEC2IXUFf3Eueomopg_$?Rc zJg=Midn`r64AJAZ`GVMF)+vuzZ_3n;drng^yF{UQ-f0#6(%XCS+*m{1ERH=9+7WSF zE@`pn9jcSpv1*){XQ$F`B?Vl$-Ln|22IUmZo z^ql+?9W-p6(Vau~f7 zDc@L3o=)R_rQE=ewU{pu&XafWOp1?lNs=}X<6YDSY*P`~$e1q5fJweX&)?cJC&#X= zjx3pBV2GnEiDYyJzab^AjKT~DXYH+*|ERMgG=g~i4chepUh&fAQt7e7d5fXQ&5m$;^`=g)!lG!5sN(sxRCyl`o>2CKr0|!24mMhH zMPY&pA-I)cy!c)@QaeMlCCs6MeZxVU>FlddOv}v~@?ArNv-RcE$$wB5IK_H%7fjNead*>RL;un=r>XYM$Y%k%x135 z;^!J=D4prI+3oBckL-@8e7?tZn=xXV`fX2NAFYrZ&UqnirLD$#KOs-Dxmm#BmLQm) z7&S^L<5d8)(6?=wZA#?VOo^cG!_mdevZ=|}H?X-O{gnEp+{3VMeajbI!?JaDzcgh; z-f$w(Zb(8o9)D@XBU%Wobh_*# zDoo{)(nhb`s@Yj>H0=5CY~G;7e`8It9#afG`lBjq24bf|BB6w;inxKhRJFR8`{8qP z2HLrc620=65~T1l19V8Riacd<2V%4qD8wI^w`yd4^U2kEMBDWgEiwc%lE6DiPtLw1 zpOq#n)SkWEf&GZ@PGw|zoTFx;T=Q$64(Q#tGBv0CMO*jw1|`?y-mA#3u(ce|0M*N}O0c4how z-W+_a{onTcWHTr_)NFfoJZk1>TDE7;a;X|5)g$>STHI!=G3iRZ`h;(C-~(xyc>jvi zi%5IWZ9)*F!k2YJ|3LRy+S|%^$rz^8K9mM-OHwO&~&jwF0B9`=NpJnt4q~X!%%@4Rg z|1d;-9gyTWpo}E6(RP)$LU#yW{%j)e{88n!S6eCkH?OqMvW9Ie>N&iw&CNw~$C2+5 zWA$Q)L}CCZhm+(4@F2Afd%td@I-$=^b8u_SPgLr6CZ;lT^4<<8$J8BnIA>k0UMUWQ zxbRSy;J>wIQu!6KmMo*J+6v^+KJn^-t<&!9z&(B{D(gNow-`;AEhTwDzfHZuP*2r0bsrscRx|1iHMV|Cjr#5>t|$}fASMWaMDSH`+}Tn;DfbE-?$~> zr@uZR{V$(yJikxz@*liZyz=`N@a(rZmyI!K#lXneXfHLgLL$!HlFqP~)j?}>%fXw= z?)^+D&;dRo#%cJ%hg5<^ZDtZdv-dGALC9H7+fp0Po3i{2)?D?v304_mTgs&6Xz6IL z!sMDSG@pyGPDOJ}rJ;O=E?r&@_NCjHW~OX&$I&}=JGR2V%}+358w46iA)gHylcBLy z3xN&=5Oz>`MU&svS)fip zF1ACOkyD*;`4~wOaRQr2C;^6tliq8l3Z|6xySYTD)^?M+A$8cl4q|FO=dZiIS3D4!;jgTh@!z zg_SDX0s|wzwmqh(M;$S&!VKra7d9y{CpU|+kYCA_=-ac8Pnyq6qslzBdzt)(8%=N!=Vl zk*+ZR@pMw`oB?f#3}|s1{di72f+M+b4w~er_w#7$qkZnj@A_UI7`_jBXDNPEyhiMH z;8R0Agk>|!a=iqV9t~%7@Qn@r9)Mud*5OB>NTHh=6NET7qI&bBN$jF(5q*YTzFoMD zY<|PeekRFhw0S8T{Nqr3NbQ)fscn%Bfq@#%OMi(I=$UCY2QZg7{7n-m}c|r$EnPhA0v1Q zJMb3e`o@|uJMA5&usMo%B5R3EEdC*_+Pw-V!S}VEWzHY0`N9QSq}r^=*S0vRAyH9< zn_A0rzw%orGb+OkK`RF$2@Xjso`DnWONxS?;NKNzIdaKr&69Q3$Bq@5dxuY!!0f6M z24+Re{WlxU9{|BC#`L%RJIOrKSg+U{O++)5t}4W5P1+h}9O$NU6dZ^H4v2y^L>I~f||DtR%4b3db1@F3sC zWPqUO&Mn)Bl#(uZJ2qNA;vFL#QLFRTgnD+D4>M2k%~{6!PRfHIyZ6~mcUBojhSY(* zjQM<-w3E9t4qJ|OHE>eyq_sAu2|r9n@6qsu1zUAjiFT}vsg|D%8rAEX%=rCQ#|gb=BNQQ z6sD)R%BOVkrq3_SSJ&Q^kahb!TkU<=C($C0givg7UXxcy9^@GzILe#xqtE^1Wa@<+ zl7}S1S6`ys&vz*<-F}%h#F3S}L_aMBgVvx=6x4ebopQYi6!^!A@IHPC#D5lj5%W#D z*>|@2y|z}gMJn4lcb}*8Z#)PhA7h#r`z1(2V_b^j>ISwzVOj6UvL|s6jp`{h-j84k zt>bSpX4!b6`z9_EDbsgZw!eL6ae0)a4YnjB^ZvAIsncoyf(P$X;)f=>az}XoIxeHx zdT=^WUDqb-yLxgmjba|iDb{<9znyvmQGpwNA225v#ln7Ch5n7?6c*+F@WipZr1z}; zr>lQb(F^~52P~@7omiTR&e*}VG&`clNd^P}qh_7^wgQ~L@Dgm1(0==(>Ep%$Cl2yf zqsoV*cKm#9D+E{k9SWsIt}#4CD$Fng>teT1QR}>+EwFeod01za$7{V~vXA3J0tlrB zMQ2X`WaC>}Y)cl@B8rOMy|l*st#{_Jigo8?yBrMN{k?8A4wZb@Z2lwj7TZs{C+B*n zHM(W!|H>o>%=v%CN?y1xk}Kj8wFZy6dJ7Y2HHdCgoM9L>e=EuI-UwJvvtgs(0BBU! zy^ZAhOYqq**zqoaCu%y81-XF{Ut+G$C9lo^QB?UmMtYPV{{0<*C4xx)&v(8XDJyvS zyyEZ`=0l3v7@(qO6saVCcLTn?1}HHAn#MRFlNpLa!7fVDb=6PmrW-icgVJM+^CSX9 z@c*kLGa%X{6L@%d_}+Gt-HwDwUPR2ZB`uH8ff9!aScit>pSr87qo}&S_s3vKkkFuu zu_2K$s#(mA9NeWjA6UdDgH+k_f`3sslf%n!mM^uLa-#`3QlokbIEsZ7Qo@XApRHk4Zpffs%9}XeD$P# zS(ibJ{rusXHm?*7=HLDwz`J>@0N|Jbv@A^WW_on||8}=SR#~SX)0em1OmB0yz&*7G zA(Q=-iA~i0C$J1px&Z96_NW`G17jRVBeZ6H4E=1$dE-{V$xSc{d%LVJ?`6$jyHEKt zwrB0?;rj{n?I=M#MAULmaM}LsRjS`n#6xvOQ+qqA!xwZ))e2aP>1V07hMgbQTV1bL{ zwKAi<8GlLyAjB|TSL!iyX27&SOOTWFc9q37UUlhqY&mg`nrCi*!N8-rV(zGHgD1$| zX`H8|am(J$#Xs?4Bn;-YkwMpe%)T;2PI#2#*b0w^+yG=_2mKu9Q8I68Bwm~deDm6% zI#9S;)a`SnRJ>nn4Y&jcyGURn%ZdR$lCyoiFEL)$g+jM>x_2p?&pOW4Sr)W;nYqt z|3F0;f2$VZE5{N(GEzR-Gl-r#Yc}HEFg znKR+bAtq_fd~1;_=}poUO*oZRM1FTrdomkcyNYh*=;eFBI2fs~R{}b1I5*ZbW`Kqo zx1R{KI2Z3%r#LX#WkO|t=Kz(D(}=7)FJs_E1ZXlBcmJc&3N)HeoL9TAX^2rz=On1= z#i+pdo(VS)4ZSALPTSs2+=bZmaE179UvQ?^1+%JViI`4e4DpBeU2h$e%hEPZ)| zB7ld_OERuv+@%2ZBg(0zU32USM0hhH3u^`c3YOu>3lZJ482wZZAloHJn%6n~Xd_~p zM_*LfA!k2+F`CnZ zt944A^6j->AnJZ^m)ObF$bFd}yIP>!jOXx z#EnJU7I7MhLyo~&?~LL8`S{U`68P}ZTgef)SKD5N!AYlOhhP>0ylW)qO}W=8+LaOG zIi@Nm`scsZ3}a~?)orGNb&G!hfOiLX#p^bkU+Tb`iYsz!a zc=+IE$?iHpEK$)1K!+>n@mXhLipH52*fu!%MeX%w6*GrZ;zfn*7hN{-f^Z~7uAo%+ zq?|W9?R}7t{kVl*ylA#0lE}TwZFu_oCgU`r%H-lQDi`{s!WC66?47e zE?ONn`&cs1``UZs{MT;|u@9sL1xt&P$xphSs_GS)a-3%;`De*SWl|@>s_%-uJYS?~ z$T+0klRDn)toF^09-^w+S0qPTkG9*#&HtK#QPAgqfOJ-m!Mn;B$IesQLVpSo^>z9H zrS!NKap^&0CwfM}5pjTmT{GoKMV;8@0XS%dPmL7HL0<5MMqW+*QAa{Q`ceDX$Lk=& zvgs219DWXNF_m}(^y}@v; zJY@Up2#xVwBDqc?IknNJp4v1qXZaYVyt(~N_%ea`S`s0-!`h9tXF7^FWe+=%lhn6d zVuUC;mM_gA1t#r#dZtFq2aE|gS$>hPz)~t8+i`<4WXCe5h-zKSZH{Uzs#Q|2+*hW2 zU&bP0y+3jJVU|hkg0J(!+Bn7kG&k69#9`JAhO%zw+TS zOOg_z8pujRkG9P?0e?QaQz?pQnGPq8<|ZZ`P^VL6@R#Shs zE?v+654$b?g$Wz4qCI11VaV~qvMGcy>1|0Ixnnc=B~v_RfkdLcp`j-|2IejkT)Nr-9vzOZ1m^h{Q&jPXN zs{r5{J~797^K`(`>l9RCovk~~a`W)xfrcIYJg3A-s3l6w0(f0!jlIQKCRSJYS3X=5 zjSotO=$`Bv`=BIlwtb76a~u|%k755eeiH&C1NOYgD-y`>CF_8hJ9Pvhk#vXNWXl%)1gK?QX>goxApRsMO3KO&&nuVEjUG+07lZ6a&)i@ zm#dBk*(5Z2@D-x_WYyK$Yk(LpkmkF#t@$JoA%rZf}DAu>WTp>Y*=38e1SunY(sl#%{<|^$M zLh~S2mYB7EQB|OlM5_vz*$Fx)s%0CvXy@N-jBh38R(n|mlL@cqJ-EoNpLp-S&&CV- zNf~*yLLN?amUb_`&~v<^&}O)bU|d*5u&gHEzs@=mJS~4JhngGnr&DNqW=oSv7wSSq z;vT7nbqr5PlJ+^Pg?Mt_gh?(rZcEX6B5pfqsiyoX_Q+B*g9}F4>bvurlIA_LQkpm; z&uLs2>U^JY-rzOaS~@e%#92d6tS3d2hfKJ1Wx(*_YY-~Gs*M)P)G1QXnL&H-cHEw+ zF?A`0(e3){(TCYztdP#4`xo$D_zHL-5y#oe;+A{)lkhdT6gP6`3 zOr)ne()IiDDio&L+?cfLmY{4AJ>pr}&)_=I0PtYZK0)~XL|kS$+OqalE-ZEuygti& zACO4x{wyoc6^3_5wqB;Zz7pjL`#wMF%-*)g7|*2}eMybds@r6zv4dmKkJ(K_lrmZS z%Dx$4_cF%?fUm}H#vZjw{_v)$E22z{q^#S5FB=*4Fvfd|tE#>Fl@q{%`j}l1dU(Wc z?_d!>oWJV$u)uTv%f~MoUaYYSnEB9>8Nr!_#7M#Vr))E`SPbE^Vmz5&lA5FPeqV7d zjKud_GbM^t+|~G^2OR^NKEr=|@Se`W`s7wo&75cDJB`ZkIK8kjn00?F6~rAI%3r?8 zIwyhyUdV9CU!xcBdbv!s8e^avP)&lks!K(fF?T0OL8p zUJwZP>4o9vPaYMtO+07EGTmJ)?EkzQkLixmnuYTA5FC7b5n@p@{o##5T-!wFly{87 zbX~Dc(t=@n!$Raby^-$Mtt#=>{tDiV$@uE4=IacxV&%S*b`0dL0YZE|Ss}|E{)wW@ zd`DOkuXoASSPE*qnH5|&HzTfOnzQVLZIIrhRue5L1{rFu+wu;naQDP9dgH2OXo~v9 zUzQ66>(A6qPdy7?Ss7k6b6qi%f6%uQ0gqY@_8v6-a!WUHGlN1C4;~Wa7L*T>+J_Np z&UT4pCYL}h-`Ubg3zwG1V*Kzg_U2-7dUZka)Rr>0r0RmI-uNg5a1ixCx60ZlctG6J ze1@M@AIM4NPXsgl63Oa-7xaK@Y17Q9liCOaRt?U{G+*i@FX5HlKtAg4c_)1b{KrdA z2>UE6mEeJvS=f4FP9mkCW{5WVv)gcv`Ug9876y2EYVTeaOWcj(LiAWVg>U)Yc7u);{2?ZCzmxfDMXV09Q@YcK@y3u_d zj)r3+YMWYKKcSvv!TYGQron$WSp;cH`Ev1Sl)v|a>8>Yp+C%Uto3iKIMq+&|mTL^) zJy&&z(->e$&iXzczz*jDDV4D2i{=Q+@t@MSc0&at-U zyW)MZ*fM91En|9A!~(rBX^MEVEHE=K+ueHd<$gEhw_F+0UUH;1Lr~Yz%tdB3nXg{l zx6W&|OZoHGR2iMzqs_=;bfgQkRNqiz9H-sRP}-o)^z`__p|Q+qdX{$>)5Ho&m$9}b z9s}LvNgSMZt9}K>@~-lTXvc0pLzdC@arQ_Oimo!%0xL`;$#kLhYrVIt5idit+M?-8 zbGQ0+wG=9YA`9`)_Hci#DSfEPvDU;P$GO$fvk;kC)u4#8z3mx{ zgd+XwDktpZ}Y+W@gQ>7Eo8}-Xr^*v-duG zKhMn;t@Ko_2|`8do{uDm{5QHDvjq@vy-(*HVKjpJ&xN+D?`}!3?KDC}ya< zpPQDDg&bU^>TRm;SxcLD5$a4)KVD_?HHA^e3IByYkGxdSsPe=OeW~IRezmf#a7VLd zcQ5Lc)fbP(cb~YZ)?u1sJTnnwUaa}$h7t-5{vV2&B+%pV+wKTxQ6_1QPA%nSkQdY5xw1q5%J9wJ=XS(woI~`I7VWZ1aKWyiE`w)Wl;u@zT<$J|=Rb5_v zlzx<6D#o&LIeh6}%C1=yBkD7Q)C(YEclPSrj_JH$kDn_IMe+BY{4pXr?S|Lr z&F?Psko^`^uRV>-pL!#tF*l7wyTr++KH8>ajMXIb&6CYxoZ*;1THg* znR<2;z81IF@;)WHA_PTjqmywNxjtTDqKFLo9n*U*z3UUW^xmFbLL2H|zvxx@EAxz0 zFt`vklyrLJf@Y`w8l2lWt)+wVfkVi;TH12IQm(z z$B^vs&`~VDl+o#w@nDvh1Q1=y>ezOMh;JVvpOaGDr8u~3%+4u$L5zv{_)3en@&Jis zCsF?F<-r7JYz*1UevMAUM8LV%1A6dD1+&Uaet9pjsDpxvR%*oIFenav(R@dm_V8wV zv})H}X?(XGp?TW0VttYMk^h!?sYzaJ>?F=(HMVcROGDiyoQ1h<{0K;H+sg8Q+8XX|)(kox7RAca zl_(7CDSOZjVU8eKE-n{$Y50Q0w8r-iUR10;QQzx|yTI>k#O$DAn|N(rcw1>u&-EN! zALt)LiHiqOxbgb$x!{N;ESet~XYwW6e^~ zoF5r4HL`0VQ(BTgTY}ofVt*BA&=MhRQ~#{H&}q`Asx6S#fddbiSH+E#`Ks-C_T2+Y za$g3cW=pwNqm*R%k(%qqn4+Z0rCUr(We+<$d#JxxM;g^|TJOi)4tbx8&bawdq!rXG>Js@=DGj_~M0Qdi-vZmIP|ORhcPZ|J7dd+~ z(8h&s&4nGn^$MQMI6r{Cx7e;Ww$R}a9(7Tr4weB#oF;YzTH7L5y1r+ zG#^k0m%eKE@NpxvY&YjU_uvT0eH$#LMU@^LsCOT7AJ=PxGdW_%)XopMsp3)X-T$3 z?3V58&B%?MGOvZL?(P{eM$sQWj@IAkBs$gGl~B?fw5^kXc^KKjR` zm3;5zGpAwX_t$17mevIBC9SWl=lyCcN#P zM?HVn40+VBfcA!@=wJqFb8*}etxG+pm?v)UB)+_hZh(@pk7hBrm;!1!IAVa}=x^2V z^XawctE4r(Zi}ZDYY?LfsDol}t8WM4oQIC*Ae!2Iid#Vbv^#U{MmUl=*=*>k1nxd5AaO;;ULxNrtq# z9@J`Q!`z@O`y$%|K?1qcpWCpngHrACey_rpx!X_m1g)7fd-NZn=>gx`TA zNcP8eUxcXaYt~}95knoR3O%J;2bl7lqla<*{12+rf!DIlbrbgctZtWjB4EjcxqSjgxO+3*kON#_h`FE0YuEk59V#FmpE&^J_S#*Gx_~fZ2}VYVxhOIo z&Nfof<8Z71pnBPoZPDy?jm0X0+*3MX_E|Qbf@zzgidFhk>{=psqFiK9XD6iJu|&MD zinSY+ylpCalmi;eV(jVx21wqI11j8*6iWA&fn?Pr3c!yICvj%9^wEubT%KG{+9ch z_`zP}#Pggd8Y@JsvHG)E{RbZ(*dn*))YeD%4f(-NLcP`Hx~8|DuF@u(6)pYjIUN99 z1#;C}tI37D;rbxiGR^{Xn`4@Qz-#MdkmJtdPf$W;iGv*dva4_0>8B2!<~~h03T@04 zf?YaOogQN?wU)+F?5KF{v24#{g(adn&kNyqh3N0h;v~7NJ01Y~UV$UyZR`Vh> z=QCa%e}&$87f(qLPk&V{0}A}KPPx@|QsEV)chDSHhDsTK_USy4XtrohDGTg2pNU~L zvp{i@d1q}wy6SKu5P*OV(3AE$;%|yHe}bks4LAY&(~Y{ ztmju4;b5wJ=TQrtb-uVd1R)uB)dBoircbi70}8jeTv@d=I5t=E+T~} zyZv~T-_h@GKDJ+Vo8njabU;$=l6~^=5PD7?0zjU?_~5v>N|b;Aun-#VM$(`>a_KD` zmf<&uY(?VBFunfZcga!o|QXd%xs@ZrYmG5F}5z(yt?|~qZLm8(vqrNgnO zFAi2y?q)(gZ=z$q?ct@z#AXE#U0h^i+*qvaV3R?%KjW63WL}9q*&%64@2W$lrAscI zQE-%*lu)2H)~a0kJCjj>sYh#O@hsWeBEcgis0O`=Z9ITg&s~zrAET9GqBAbjww^E! zv8h#z=E7l%x71JjAV4>iKB|rk~U|!hGanEbLC>_dt1HyysZvA*|ec;)a z&gNOKGov`BALsfCga@553f}&Dp4*#RyLTq40Cu}&9=h>KII=S$*6(2mZd;h<-Nvcj zY(b@NMBD>a@2ptGwYQ+ZHeNhB61Ti9e3c*is@bEf-fzE;Coun_vK>kEZu84*pZ&w? z{farU(g#g1y7O(X)E{itQ-u=67tiY|`aLZg(nBO!)kWbFsL}FAk@9y@r@0}FQq4VK zGt;sZPN9KjVu1me%7tZ=2MbYo`vJ-HXhgGu&Z8tt_1?`48xI-h?7c1o zsA(dh`$flgqZ!p}@Zn)nHhF^+MQtTy-Z-u#u2jgj>Nbst%R$Srf#hi}>+ND|f47nDMdlUK+?&QQzNb$z5Gd01cc zZn7-GM}CBUlqUSB55io4iL+EFKk;6%r8u=VlPzN=`B7w7y5p#HCfM|JzbyqLGgjKw z*_#(D`JLBG%tF+%<3gU|501o;30^%@mLmLACk_ANv2^d&JGBV7X`zv=Hiqv##641v z1f%7VI(j1|ycAiQOU*sE(FJlth|AqQ{Q z6)0s>ZJuxqnn2=GgbXSmwhq=K-2Fll6T8{<*R({{GjYrhWzoNg@$VXtGyP2er+Bad z$*LOPar4ejKC%9wS!Ec=NvOE6U_mQXciLepO)!}#{zNLlR{yXvqol2ME8FwN|V+ZDk8uIR(mv=C{Vg z2GTb)&iYkm2s=U8?X1VdTe<{^_o`UGfr8~W@+MPX#!f0!qzLTe^qdv@2igb)_hLNv zV-`GH!pG6APRr}28?z*-uQUEZJ*%#(CmLU{#RqwsX3aVoN7G=x@!T~)nY6TUGL3P% z&)6_TRau`BfIfx@E=00bSv9<@2wP3Ad}ziv8S5G)mkZG8_7K?VxzByRGHaR6zTXLU zf7@!J-C}TF7?irieW*BJQcn;;IqXb_OLG+dTuOX2laIaW z^J5br*8$y?MNw)e|01!sffPEExUdj~yk)=8R{U|RubDz=zT@&Ok=X`EsXL5dk76bK zjeGl~a`s03(k9;$E{(T&OU(n?SYk(k0ernevuE@r8S`wKQ?ug?6Kt&9b6{0p>xn%F zQK?97x);9Xs8mbU3msRHF($({_<0MuI`MA@CXOG3b}sRwJ=z?pYXCeu)4B-ndWwo! z+oS#Jr20=%Z%!<%>8R%8W1L~Sh&EU2Jljg$9`|Rr`2%sTjJRoG&p8ImxHp&VT$$y5 z{D76$K@YjwxdvF=`C09sUpqVmb=j?>SqmSk8|WB1jFmd<)A-$c%!=CC?c#i7f+s$x zx8i$+<25IWuSny^QuoQG;eK(tb~$wD@NDt9f{{?&I4 z#b;TLVv25R5(Mo#?H)m@*)+p=`h;GK|Q`MP-Z zyAOVzpEsmO<}Ugsw5XA$V8_3V50)|=z^7PBoXD$*PJdc+OhJDehuC`b)hR&0JUUoX znCXNtKYLobaMR~~kpAvHYJ`0kMf`Q!(OULoc8j6alD*bAEWg(E$&2R#Cn6owS386_)9hhTC3uoFR@h{ih;fdN=rF1`D7Y<7+-P-Nd6d3DB z=H8}ncBNUwHfwsDz4=(59$MxVaCv%{+dDfz42>feqaF2a4|Q*e@rFMmLh9?F# zvwP4>S%Ty{pFWvS9u|55aVgJPG~KI$4W_@^XR(K7%1+phJ!|jg?PB8Rbh~a&KkfPI z>FntAG{~&N;$}wL2SLT~3BvbqUVpzTS#*#-!Ks*JBWEZ|udAji1$iKDiWb}OsDg)- zABcC^tUnd{Se}$#X>|sNdSk?W7M!iSw#@Pl8o!KO5)pYOl&_zGPX10ZgnlE`T$5y` zrmj=A*e5EuQNqtWUq6D(;+lX;)_%+LNXh4LqR4n^t6uwkLqe-;E( z`7wYs;0K1Wh1wPZSjiFapfuLr*>~zR(S&lJ&bJLuie$xk2TNNg3WbF&84B}D=0syC zLt1n!$2t35DXdpHGU{T5#>n>aohc(@1cBUNI}0abf6oUUvff#c^DD(FVm)q{`zw#! zuB1AfYi8F0A+nxHqgC_Kow8Re@PyulULcMribY9!UGLiJ%-XRk!&TzNgl5N>C!Z?9 zpdPjrl<7Q^Iomy!+w@N zT6FbKj0T=mr|Ae}^3%-vw24GoJ2?r?P-pB~Bu(vLGnYJ~rV`&)bZu_+2VY{fkNpi% z;-O)EjO+V{`3H;T{(cdzDILf{`vO_?8;-Axs4fMIwOe31E6C|T*Z_R2-$-OWah&ZZZJf^GMd zHTw7Og9G7FM6=suXT`-cGDn!H^0BS=2vFKh&rNV}EF$BnqI{Z#FAA=jv#6)t8u**X zxu11Cm}zaHd9=WD$uT3r`K=Y6yAtxA0ihAoY_gZCCq4BMbwhO~6zzjROx7 zu21GLX{f=68=roB<)c;pS!eUAy*h?PJ!xECAlymWZn04|YXeah(Fis#>}JVs@RX$w zM`yk5V94xQ7GCC|fIg~X9KADt;QI>mbk0CK{6-<2Zfr4Of+39Lk)7jp`#Rm>NM5|a zv)PFXiqCbdeo9A!iihy{)9(oSgw)&_xm@kGxbG#C9MWG!)m>KJp4T$KEhI}XIM2V; z-)03Zzi4QDZ@lxE)P(QBr(&r$M^ri{hk=t}#fyF}xYF$$7r_P@I^)9P)-*gYSbVMN zb4e7`=PURIc#<|YE$EGgOEB^MQ+c;x*q$Y4gMrgBgRqpq{sQ5~r**;{uYA1`d%Z!$ z+9z~i7E9E4^V``-_|^hm^S#+E?R%wOo0Mj*YxLp4>q)2I(*tkQ^P2^=b1%3Sm4k&z zt9@;7cQ3ZR-B1AtSB~l%Wwf2qj*to^7-@hXY%Cxs`{AZqm_rKiPhxpT=hd)w0wC9QD;<8t0KR zoX#TpKuLK3)QQD$Ss(t;XS|76s&a@s$!(4UaKp(HXqmNJBnW4?YHwuXSvjI?N-fE{ zU7k`hDqOF9P->37yCTvf$&a~#Zb(HqJlUph^Bi%v>T)SJejY=uj8bES#9sVqAdeyS^fK?n==2 z;216Q`Dt9bT#zfqX*Z57HH_Prmg#WsLkjwcZrn(;DDc|g#v>tsal51SenwDBowj@MROWyzTSG+)nDv&WXPjXx7q7h^kM?{d%OD{Bk`252p%z-kP(c)pERx ze|t?RLV$uf1%s|5sISi$uL;X;u7Pm4Hyz57An`M16Zm~_|2mJeBh48i3%FE832=$VFTTt`v3IfUt^_*fy|_0*rtY6d>A`Kf5Dt` z0jLPcMd!f2Ug_)0aTz4V3i5?Nizf3ewZgc%Rervn5qoYsGs7_<=2^)(0}+uLzX)C2 zsxh*OeaaoX?Bb^J=;Lo7G*oKXa{-wCVq)9ok)xZukPCEuF6GhX6YAdDCW#-=_xrPH z=y0#l&EsMzFp&WgzI|Xzq;(S_QFH$JGQzM^PzCb?_^ZwdD|m4DVJL>d7LLn&v0J4(3lMG2so~L05?I^vTpfl+R6Y4Rt-kyl6%ObK7h4gPQhq z9Cn`7FZEwAKg>8LgMUaAA!(`B{FyG4k-}vy3sF}Sb7o$E!#mqJ@;Z8A&TDFa=_WD^ zdRHZfg=>p3*SNVw)!=FVkcXE%w!5nT6EV>4QJ61}cD3UPKX^M92#%roq}RxM%BLzE zw{#!1Q+*d?#n{v38rUy?Fs*UX$=N1k5*>cFly%|nx^&sH{Sn$d)`FMB@If=xpLGSP zxy4*h=D`Vlusz5qNgoL+xsILW9qFFd(3vWryx3M2s52RCH#rcoWt+Lhdj%cjMM`~f z(Xq5VL>d`2UE{JrCB7!DPQ?K~+eUQ<DICV%_*2i}dno=MTNC@k4YXK<=47Jh^03ig{`RxMZm9`QqqFvk|CN=D^g$ymK zOPd9xx<<-HGeQR0i=cB*mUUao>-<FR zc!)8H;KETIy~RtrGBoe0ocRfdZdf%1JC5()(|7;crJPdt8;Iz5sb3mdpRuYBU}od- z0DrH3v|JH-$Rf8_%+5r(;TB$ruhPlJ2*;iuk^Go=Yu9&(4ebzu0vPUOwHi$;bWvCU zUe*f9!hZf~nbd&{Q2WRs42`(Rb)I#>jGI9G>&;upurS%ep^VONpjv2}?}*3esOsL+ zHtF@t)Yam_Hw++s;joEFc=SfMh>l zo+g`{{t6fF%O@2faA!CmEi=7Vcw5B z?R^i+fQSzqo=N*C83tj#6VP->`2RHb}5C2@z zX3lEzTc4v4M#9#?z-Nk8LXW+{x_)aNXxHQqh|Fu532HI{kL%r2o~-O`L`LvF`aqo9 z0r(K5xAw$Rm~2~^`rt!*I=f}94n{_PIm50eEqM_1y-&@C$oA}O<^%n2&E!YxwbjV+ zCgV$c4^&3co^$EtxP4>(b5Z9#@2AO&GtkhpC}*Nj*UwvWoRbMdTzcPqS3JOFb(>lz z_|w0E)W$Ld6KX79`QP;1sfxP1UwaGLB#591r?V>vdrl|?D)LM*;8R?C@_ay0o*MJ; z^fPV0+y3mwM}qfL9laLGrPt?6W;Q)MYL7Av7v>$4kZ_kUG5WvP zfT{EY4FSNui9=`_Eh!iVIyQdrnrdV{9Y7gxlc^?F&pKuezA7Xa=%#Lc^U2qK-qPs_A&(eHWtaN4P&YYky z*ZXs``g5=`EUKb@$MCGM6 zpul~Dlr1B{&?B;+yiARUQsvNB6X$&4X3jyHDs|NUWwcxI?8Va3RiUxU-<`LOiVqIE zZfNXKRunF8nR}hJPv#s|htDHKSF^QO6F~ufPLO&ypBhC$FWaE{jJ!7SA^q23dkpVu zaR4g{k^m$COd9P2Sx(WDH_Uvh<7IGL!u>rmwLmO<(3?ATwx-ti3VCgxg%;Dm>N>u^ zJbB1|Ot>%pRYm+qBy(%A-9iUq6;>}nxcy4}{d`skwHos)Nm9)kru(sx>t8A-V=vlX zHS^SxcC&>!U#OFJrW~S?&o{@EU1;$ovvw>b?F}+FFRdIYm)e>-9p|gNBpzZSO~BtwFc#?rUf#s?*Krt3_+ zNz9ZC?VcFl+O0DLT29CoPmYMy;SByy0i{E|?3B4*&6M?ImzlA35QJ~4=|jbw7teRs z<%@M=!%f$gUE=~LwQ6@6LvROT_I`=&Yq^5f*{n#>&*~YSWXpx>zTxM0ffW8{D_8KB zd&#Pa%=NT~dKDMhC$+S`dsIIn;egs0uvIgA`W6ssKP{^wrLx67LzT2iqV=6~hPpif zeth6;UAa#GgFp(CwtwGEajEKBes3`M$EvCGho^~4_do}yXELbWcE?c{3UDA-mpuo0 zTXvxds4@@iQsP@;yxj(gTr?O#x6TGJZOX~K-SyAi!Iv0(KQ)u)1J|gFmpflv--8Eg zDRthD`imHL4sVCA71<)ra&z0w%Ij^G8R+k#Ss#|!kGeC_MOF1tvyl-a;UXb$r;GEJQjh3{RUb=PRA4lJOB86h11{Kzd-;~Quq4_lCDPjWmT5FW> z3cCr+Sf~aIRwLOaR$ks16}{hN2$WAU5tTMes{FL06IO_KwBu(8(!n2EBQzgVpsA$JfQC6+i@v zJ{NvG=BeoT@H0E5TP0g{HP0>EK>%AkSN8_&jaOzTqhjt3{O6$~fFjhi^>G+%e3Q9T58k0N0of=4^o`GG3hgEcIx} z`uw{8Ii=)NTid%*D!mdofn#Lf6Xm?tUw2>DCP{%Fm<8kQzTLrxOuoY;{ zDgNbF3*b<=hN=Jvx5dCrjRo2+D3$)(G5F7$GXJ0dO1}&B3?lgE6u<=58i*)@BQMrL zGJyidO9Ut|$=}(+{wskAK~+G)?+his`xJi$mq^IV*!)A$`n%HgA3w)&Tlo`(nfJ!9 zZBnZG>HN^V=iXp)&Dx&G3H6}w2idCYjuTWyXS&lZ6DGH4)nCVSSp_$w^(z@Z6d>U_ zIhy0k;UzxG#O#OZw$D63SnrhMP9x)q5j^r`r$jxkf-mv}!0|Q`_PF)C0d(Qe3Jx{1 zB+@`>F4qFXJ|}2B-uO+?4w1)M+x-`zdzj!fWy!~n2&(?cVEzwAb9z<+l;qM4UZW?Y zRD&v^hRTc=YrM#VvPTUUrpq#p^pTVDqkE>>Gy?A@`nRWcg`;wP&zMN#fhrK-#QJK~ zJ0)y*+Fb57lV2>Ji%Xh~L**svq zg&$7df=&RGW?aG(HpUKiOXW-LS&G5BV_-=%ri2dRD+7d!!_t30Fn+NVuDS#4FFm^s zOgAgyAV)of_Ac2($7Zufw$l=o6Qk-*=FdCQTL+TJ)}a)NCaGYzk!xKw}^q1d81O z6#Mr|K)^Tnzqgt8gx&egeb?r`J>!+vr-1r3+GTu#Q30b@LAjw!XmR<_i zWHGcT$@md5!B(XicSC$h%@6(d`7r+$=VhwXRZyg@uWUzQohZss7h9jrVNrOlH+%V_w=|K*lNv{YmuCv+hP z;8oR%j9J7MVf$eq9N{W>RI&`BHqaKAWHM(S5H2;2;q27@h>eKGR1YSs1xhp@TVPZn!1>g;uzFm$2!gySvEP+9wUp z=vDx6Q}@_rgN}2md!hp1Njz5`Q^82EDaqKyZlJ)GTX2C6dU*r3Ft%@jL(YODP3@To z;~hIWgJBsg&lC&dcS5KXIeXooo)=}P-0kg$$*k zva{M+CBuk^jP>Z}Ywo$$YuG74^j01d8rdhPbsQl1sBgGY3MHk_LZItK(1jOKRe)Pu zL>+lW;2#V4kqG?y9M4lPv1YGdf{(|+`&l}oPh%+Us|BmEtuaO3gG`1c30i;JQ|)6n z#yPfRNu&D?Pp@@D6jvpzxw}m1tXCu=#q&3fo(;o`Yv7~%d##<@OnsYJjJi=v-@^461r{1cZL?z2 z47vcP=Nvtm_~QL+5VAhql=V)*yvX6sCl&CTGzx21QtSZySGd_Rr^$(3_czk@ydT>3 zdswVHnLeHMF(*KQr*IiSLwFn?Z3x;=WO3IsOfP{Ol%JW?z57H1B2S=ud&-kX-F|H2 z!6{X5*_^#uzbB9&^^(rbfZ}k08>JydVUi(pJ7xDg%(3eFFi+MpzZ1QqzoB<D8UMdqx_^HDziQqW*qjZmf$S!_8Vx2ojQ$=tZ6}=FojwVJ2qLYvR#*FoL*8F zDU(_7+M6Kt4UvNQ1-+y;6ef${^H}^#8$W>2O7fw^!>)(#B}qUYc_a28;yzf4E6A+#czQ*g;*H*pVhG0g2~{A%pI?XPmb$%} z4YIwf)yc{(6(8G6TKeG4u=8-<Y)EDn)6ckwC{ zl1aBRqCh}2AGOH=YPxBBg7Z@$0n{z5m=hqaI44pbTPsp{N9w(d!D(w30ZM3=bmq(k zt@tn;B9v^zfVb%sMOWIoALB1T7b{z;{0-sw-h9aH%cLV4_pP>KxVWz)Z>2K^K((%U z44P^~BP97+CLJjM1^!Xq-rOF?-$dB?S+g!*S3O}dCVPIvWkGaICY@F zXeg@kA0EW&*E~S*`aSS=4AQK;*t*U5=zbisE@KTy;{F-@{_mjK|C@mLe|P)e&uM91 zrrWDw%j{8+%wcmV&5{g^j$y@wn2(NU7%FuyFHtm$-R*@KogN`BzWeZ19Ag^ z#zAs={{t}hic{D?^$@0|?AqOnJ&qALGZ(Nm5fuSOHcKCIqht}t;>c6T5fYf7ATs_3 zF!aBpeabXzhf*-y(eZqK`uG&4_Z@u18Fh6IBusDopPl|tp5@Lb+j}3&Q&Crz;XGT# z%mrE5;xqB7$TQ15PBg1@@35V)ivJBn?GttTntD~w?e|X6l4>$%U9I58Zd#(-rThxO z_GvXeWke0SrX0MvRs@V+GSMzqVDujWd*v7nMNDtM-A1k>{Z@h9Ra|OwKyk?M2B>Ka z#|cpW-+CeT&*C~en+|F9DO1yupc{Y+5x54lw% z)06l+O+d5jZ9jSMYDiA;0YT-_L#S2eA?)X9Fhszn6KOHlS>PaaiVhv#nGy zcoUw3Y#Ka<$^F|R{Hawie*W8@LEuOjz8vWLNXzoRD)5}Zn_{I(?y`&PG3YkHQ1oo{ zpSuhHp%{1m7w7*wpr4;#EwDR>nVVTe?N_3!M+Q%x6rV;cIbLE)1ADN+$N(GEbjVD; zS-&$A!)>KBVh_B&WPH6d#;tzG5k3n9kF>X(Pk+8P9K5-a2mF^QVdbX_4*-u7n$^91 zc84h-9;{+7)=Yrm6DX(QAt)1f;n$aPc0IwzhwQg!kjT^yy@6zW#OWY*9{_aUCjv(p zaAV&B@sF+hH6Ea1pYt%hc+q(Dh(J4ayVAZpU7VSVp4P0L9AcDwh&|}<1sXo<%ecHq zL|*gsWDpOUdO8w^a?7VZBTq(CHB8P)xxey*IbJ{^{av{47$QG3H&9Pd^h2I(k=?!f zDV7gQRK-3=H_V>%^Mf7%D5?vPpW`wVx?d?h!}dpgC%N*x5|->uYz5cipT_&q*|VVb z>zbu$lULX7adkhYa8)&i)He-=vT-}&=^|v#ROu46`6?=C5(nBfRb=Uy1U5Lf#VC#c zYiS2BtPKLPa|*a5LCR+hf3zjHU+FsX&F}d65|SXre|K6|?9uJ7 zo2Y*^oQhTW5ZZ5`U&nyp{LxQi+{u~ukU!xv!4H8c(JJb%H``?1lbq`oApZS)y&<+r z?AhFeYu(ag2jl@y?*w44{{~uJN21=^pk|dcxgh14HSasq1*5doGpl_ORz;RB+%Aie z1Rbq>N)2^IUjC9VJ2J+9$f{-6pR)QzSOSP@vzJ#G-Q}JfV}n0>97<#vj{6}lcGe95 z0v}5Ci$HY#Fvz^&+{WGs2Z}^KQAA1HG9hASDcC?pwb0V`DFxQ6ob(-%tlZgr4c_ zo6|U2{%&#?8`OfoUMN+YeAsMDZrk1WC{R^x2(9J6cG(2CPbD}ke?&N%h?&0b;oeH@ zwR6~L|KG$U15*310i$7miVZ1lXwadX<4G-2YLJ=IvA{`h^wEswbOx&Om!!P zRl!vKH}dS_dXcF21@~#rBKabk#bpGgZ>BGAl1oJ zG!NQZZj{`A^B7>XD6q4|zts;Fr`}E3a)YclSIn_rwF~LIot&@3+7#yc4MY_OomAcw zBlDaDTT~>xwkSFfQFM8@FxUUYvo?-lID|Uh?P~qz?b;1E&4mDk{m%h3@>e7NV@ziJ z>Nr(RTt_u~YKg`%ErfhoMZ4wmPNxA(1K(wagG^lIU*ioJAAg9qU0T{7G?n~b4m7%| zZ?{S~!D-fp+j*?M0OnDDY3ZBxNqhLWcPQ0Gu|7m1jHsS}&fLJj_;V~R?F*a2bPNHd z_(DxH0cnl{GXCbtZ#cyu?7XeDCoEm0voWa`nX}llByU(U+~rD9It-AFgIeY&04{iU z@UO!EnkdGF@e18oP zk!?IaULZheIO~i0eHHlI%;nllJm$#LAOQCbT%De)<0ZNlW4_Ce*HviM={$s^?oLfK zz1hq%TE&zTliO^NoVfQw_6dO5@OXJsjFK4f^qB8*#IcjlL7+qE&uagiP@sQr$3NDw zpQnwh4WPd-iN9ta2$`a8T!+?`^hd0It8-C@J#p=saIM^bJDZB9=z$Xde2eXyNnl6t zk6E(vl*D0=dvkfzK@v8@zGrEHQ#4nBZ$5NQmcQ6!13>_M1=KP8RzYhx>%H-Klu$v? z?B7PpUvo;EWT5~^9*q(k%d7RMt~FcLb}8RJ;b|}^0{~c7=oWr=niy(=EW85F z^!05fFc?S5(SudcU7^2vO+Ot_gS72|D6c05ry%*iM#QhV%dDeRYMwdcMFMe{23)?t zf+2J$78Z3b^R;*~(OE}l)^N6Z%6`e#!ckI1_7)vvaBcagM)9|SUiWVD^g}8(c>_Lf zpP*rD<^4(LPIJ~_8HbCnH+GTn%edCMRghwQtloo?5iy;Gm(RO9bWAc-#VE`E96iHl z4Sxs-&wJaYyX%Ma6QS;?h`BbBbjlUNx{y-~(XId?b$FAH2xZ9+8LGXbD^uL2DhmvU zo%S0Ox*a|WO>3AF`d;f?H1Rg&3{cpb%XcqYE+GFuXtm(Qi3v9E^|Gxz0@&e zIcARttivN17W?(Ji3T1i#4hng zIrUxA1&Hr{(ge_wiFtk4QkP`BMm=&C^q-@ZsF`@btzW%IN_m%I#9wg#mr&BL7=K|r;d_RYkvtE%4XfxXO0dl zp*|Vl(~4=~?YccSbazSV56b%NmE;vC35Tqtpx2DCm_L@KDWs=UI52dP!dJ1mgKSvx z;%4GC*i6YCd!wB+g3uKn&RiEtauT$vDB;TW4Yo)C^pEza9H5rCO^X}(aPJ0J-luFc_Fx|M2-}YRJ&2$PnhY7P}uXh@;v?SLI)Wqnq z0pWkL55K5xU<*;hToG2u1sh0as;7z=OCnFVv_rYazQ;{pHh3C%L!$WzFF#tm9V{pf zLe2w0NpG0yC%Lyt;pDio_l;-t{YNEfaEqU@AL2F=QXJrOqfBrXhjRvzVxoCcGJmX3 zRXt=6h2uW$QcaZ~J^2#q%35G7>TT%xUd!Y~QRzMYo~LO*RJ7$9%o)8bnES)-?z7N6 zIJR^E2`%Q@^%Tq050vdVRb~3Y_rlsmcAQg&Mz%iXk=6+#w9GSdp^0{%*W{&&y%N{x!R#Q= z<*&yh4dQX`oX|_>aG44?JF*11RsDS6LY38-xn&Nz6tND;yW<@NO*K)zj zS7Sv=f^88AnYP`@wMC6BWB%~kz@6yWVc59M70S5_wv47=;JFlzd^?pF$th>DM#pV~ z)O`t#UKXEeOV`iSo)8~oVfBl$5X@^uBlhkInI+T6eA+aK4Ab{!$N`3UM+WzlAt~LN zgz8ZXk~JCQ;ph_KI|$1NO1+qlhxdZAlM++p#h@$+k$T-6`a^C#6z`!RBis_LhG6b< z^BMB5o8@}}gk^h8bdZ3sF#&}d2q8E`#F=J1gG#3 z0pQHMY|l3i+RG|l^ew7u>IEx-PmwQM9#fA|U73931{T&BF2xA4TbG!)CR`m58fku^ zeDL|Wmr{F@PIN}O?nWqP?dX0ao~74~Qka%&&~Z3^M85Lfz+Ew~=d_@pYUX?IkThy^ z*Vh+t5di*x<}ZLxpT7Wr2UrCB;OrMbN*0l314$k7Oit_T$qT-LmhMRDUH=S-2$ggT4KD5!vwBLT%U-6QGV zBdXbnh(%^<0<1g-^as)FRV5Or;~%c{&83O^6ux5DntAd}di12dWuO!b5N;y4#>|Z^ znBTHX3l{LA4Wcq+~Zl#3~)!kfXZjL6uYT5nR zrq#2HZi#d@@`mLVEXrVx<$5|=PZ@U$5?T>h19g_8cx3q8B+JU$EwS1A}Rej3>C)bY%_T@DWNB01kIDqCF>usznPd+W1u9a zp(Y)!I>4rldZR0b7p!mXN)|cxZRcMEa&R7bFo-s;x;Uc;6Pfpyev7VC$u~9@9Bs1~ z&VKHb&2s6k`8It7_?^6n3jyW}IoiI*ZM46ab{S`k!r?HKoN%c?mQzX-QiY4sJw||> z)g@>$SmA(xbx_vRRNfSK;82^r_(m$0R&sfdRveezk1lmx31YJ9PRwUad_WD5CSQ25 zM1VIO!&H~|x-l#hW)b5$b#buEe1?V%Fuz^1nHoPK1xkCS9vYvGfv$p9`TVERmQjen;DNIKI;{Dg&P}sg6WPiISQEYu? z)lT0iB+Kuqij!#F$becx2mYy8iS!Fbifj~>zid6EEtVMH-{rGwC}`5P$!|H%C$zf2 zj)pNZu(`ak<1iY|d%F>Hf|;MW*5|j4+FPIT%Ds$_A0NGJFA6G>ZqE}Duswq#g(Y9U zb8y{#`z&fb3^z3=L9X<~gkI_hkf)jgge+SBTsW^F7J8|ANC+znR_-#KNM12d8=G#M ztO8ci-V>8%$2brQAhe~Wkz$nY{W(!qIQQgJmZjczSf-u~qJ%h!aoJ;PWGE;4sD7x3 z@^!|tKrJOLTR{8jCgQG~@ziP3KM-}Pe~$sDL=q>YX|RSOf@5G$D*xU4`I?<>Cp(rKz?}EA47?N>SV&Bo zpU>m~G=E|1le#0}JzOHEWE7@tux;r$FHZUpO>LZ>(%Kr`9)?W5gwsHX1=lK?Dgw&! z_jQ_~?6DKn@0z$vj6L5#E#q9#RCbjvwcv+>38UvY*Q#flK;voY%{cJeR4`!^&8P8n zG2z&9WWYVS6P$J*b0W7c0DHeWgBN^%9Mx|Qxi&D8;ug@xrGj-NrP0c_!#Vx%QX?t< zc=f=oL;Gunou-w(sv(_>$hkz4MUXqWtwTCpX*IpZxyrb#5xWx!@o6_Xtm4`*UlrMb)NTncR07VnM|-SN=dgQ)bYwVz(><3zi< z{8Hv1N$xO7?FF14sW>ww6-MI}K$f?C>22V}6?zgwdnU$rk1HNTNDNHSf5?0Ajc!$dPOMJLU3a#4qV53zjSj#JZ?+d zjdMqvBFl88zfO|}@loPvMIRQbhgX8Th505|z}hHMV^VkmHQn$Rbo&(;ZAo{cpz7`# zY>RSQ0O^u`r+E=2Gy1~)PIC&AYX01!&)d&vp&hvtimVH)$fDhbK%XHyem@=K)y(3_ z9@E%?0MbUBVRQ3l4Tr$J~rn42TwVGOnisY_-ZYstg7b?ATMU*NT=BCT zU4_VOvfy@x{QQSSip`qred|l%n)Uq}eg*XWoU7ps&mH8wgDV@(<9VwphcW5`ds365 zZ>=2(Gae42gw~ppr|Q~W$D}`21CD3{Tr2t1TKPFyvOX3i`W)<(m$c58}Rrzb`;0H#1B|_K? z7u{huS;G>uS`3_0!z=JqiCl7A=&jahx=%-M^kQpcD6K1Y$g#P$@i#|`f*9=yOrFcV zr?E+iW~XFA+Gsu~F|kq&O28MeBNCnTAIchcr9ZWu22$|J1bR>Ods=Lnh_3n7d;t_o zJ$pluBd1h3=k@e}B5k(RSI4=StRfXFET%hNr6h-RPdMmUg89;-y~vBu9g)FC^)?gw zEMau^F`q#ffP*A}$sd6*AbPTK`dk?=xlmyUYs?>U(XP~wRGcPFOL~QV^i05t(lML1W$h2Mk1j*i} z*gIasyvr*gs4&$<@VMl1`U)G#)Q8Y~E|qPnaWBQ)ANJ=!Os8v98uJb1QfzeZf%1u3}#6PHb|-S_2zo%fc~dhWZx-oYo`9jEozvm=7^{=tIu4PSa~O#RoL2aP>rB z*>ZFe)34j~>}lla92AosVaQ62Cch_p94nvE6JDqHdx1f#=hIq~@WE4;*Um&aNW4Bvn%aIsnZPz*{xn(xtrA_l6ajDx-O*}wxCQl+^tQr? z>{8rz-|K`VsX+FUQv*JdH||J0wHw%vSz~&o9gsX=fZZjFXO(;%X(F)Wc%o$ytD#+$ zu1+k(CE^_OoUM1RHgT0dk0%w!vIu_0;!G+&5{}vR(`m+KWK0!BzzxOVMD-gg{$wDc zt_e+j`t?eKXyZm7#{|CXO5FN;HoWC>3zPO{gCUydD&jgjmR=0+@{kbc(K}?EBf8?wr<# zS{*U=6%WCiKbq~A6xkGsGpMM!_9W~0#>=YmWLW~#NeI@hx^TK%Ku<)b;Uv%0{zPSEkO3S)b==r z@o}WUk}EJNLe!{nHOADN6v*@=d69nG*vbvq8UtAM-@*ob8=P}+a%qL6IV&}Qu2u$= zDNzkwPx5Fr%#+e+ym$K*cb5aj%2fIFe{}o4D)L0h^@yP#y<&b01o6}TVtVaid(I&_ z*+K*ObAd`&&nfW_)&e5p(LlH=?)-S<+LS1b?L~YK&i#$*uav zXs%0&`M`qG*(DGO3bIJ}0>Dc&>SE>P-I$$(-G_A&om7-qtmq4UWqoN_4Y$UAnl}ad z7fJN@a3J9=0b7xVTT-g6gxwc=W#eAZ^_X=x@eHXX7snvXo=LU3#E!|2RH3?|)qy(w zTqdQgl#P^TB!!1ry(~axt919^FrzJM>3|7e#UbF|6zA|YlQc*x*Vwj3WzN+{LlyG5%1D9$KF+gcqt(va^(WL#`YA zU`#K$-Y>ZEi{@W230)$Hl~pC>Zr*+n#&u1NZH88jEeP0Ae0cX?nn*n_%r5-ll22#0 zArE$JM%HrMC*&9?|E_3e6>9v4$^1d0K(PfHm4DjofhVi8qv~X@!&0}y>>q1WXj1I? zv>(hL=y9?0>K&H>A~e+h4El1|`#*!j{0W-ouqpp&Bg^{*_UH%j=YM$r6;&7iEv@)J s8SuT&`SaGue*szjjPmN&FX5LB72EFF9ZhX#fBK literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat new file mode 100644 index 00000000000000..743300b3b8c81d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef-bl.dat @@ -0,0 +1,43 @@ + +# hw definition file for processing by chibios_hwdef.py +# for SPEEDYBEEF405V4 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1136 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader starts at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +FLASH_BOOTLOADER_LOAD_KB 48 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 + +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# default to all pins low to avoid ESD issues +DEFAULTGPIO OUTPUT LOW PULLDOWN + + +# Chip select pins +PC14 SDCARD1_CS CS +PB12 OSD1_CS CS +PA4 GYRO1_CS CS + +PA8 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat new file mode 100644 index 00000000000000..3c23f669555b29 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v4/hwdef.dat @@ -0,0 +1,165 @@ + +# hw definition file for processing by chibios_hwdef.py +# for SPEEDYBEEF405V4 hardware. +# thanks to betaflight for pin information + +# MCU class and specific type +MCU STM32F4xx STM32F405xx + +# board ID for firmware load +APJ_BOARD_ID 1136 + +# crystal frequency, setup to use external oscillator +OSCILLATOR_HZ 8000000 + +FLASH_SIZE_KB 1024 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 48 + +define HAL_STORAGE_SIZE 16384 +define STORAGE_FLASH_PAGE 1 + +STM32_ST_USE_TIMER 5 + +# SPI devices + +# SPI1 +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +# SPI2 +PB13 SPI2_SCK SPI2 +PC2 SPI2_MISO SPI2 +PC3 SPI2_MOSI SPI2 + +# SPI3 +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB5 SPI3_MOSI SPI3 + +# Chip select pins +PC14 SDCARD1_CS CS +PB12 OSD1_CS CS +PA4 GYRO1_CS CS + +# Beeper +PC15 BUZZER OUTPUT GPIO(80) LOW +define HAL_BUZZER_PIN 80 + +# SERIAL ports +SERIAL_ORDER OTG1 USART1 USART2 USART3 UART4 UART5 USART6 +# PA10 IO-debug-console +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART1 (DJI / VTX) +PA10 USART1_RX USART1 NODMA +PA9 USART1_TX USART1 NODMA +define DEFAULT_SERIAL1_PROTOCOL SerialProtocol_DJI_FPV + +# USART2 (RCIN) +PA2 USART2_TX USART2 +PA3 USART2_RX USART2 +define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN + +# USART3 (CAM) +PC10 USART3_TX USART3 NODMA +PC11 USART3_RX USART3 NODMA +define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_None + +# UART4 (Bluetooth) +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA +define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_None + +# UART5 (ESC Telemetry) +PD2 UART5_RX UART5 NODMA +define DEFAULT_SERIAL5_PROTOCOL SerialProtocol_ESCTelemetry +define DEFAULT_SERIAL5_BAUD 19200 + +# USART6 (GPS) +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 +define DEFAULT_SERIAL6_PROTOCOL SerialProtocol_GPS +define DEFAULT_SERIAL6_BAUD AP_SERIALMANAGER_GPS_BAUD + +# I2C ports +I2C_ORDER I2C1 +# I2C1 +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +# Servos +PB14 CAMERA1 OUTPUT GPIO(70) LOW +define RELAY2_PIN_DEFAULT 70 + +# ADC ports + +# ADC1 +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_SCALE 11.0 +PC1 BATT_CURRENT_SENS ADC1 SCALE(1) +define HAL_BATT_CURR_PIN 11 +define HAL_BATT_CURR_SCALE 25.0 +PC5 RSSI_ADC ADC1 +define BOARD_RSSI_ANA_PIN 15 +define HAL_BATT_MONITOR_DEFAULT 4 + +# MOTORS +PB6 TIM4_CH1 TIM4 PWM(1) GPIO(50) # M1 +PB7 TIM4_CH2 TIM4 PWM(2) GPIO(51) BIDIR # M2 +PB0 TIM3_CH3 TIM3 PWM(3) GPIO(52) # M3 +PB1 TIM3_CH4 TIM3 PWM(4) GPIO(53) BIDIR # M4 +PC8 TIM8_CH3 TIM8 PWM(5) GPIO(54) # M5 +PC9 TIM8_CH4 TIM8 PWM(6) GPIO(55) # M6 +PB10 TIM2_CH3 TIM2 PWM(7) GPIO(56) # M7 +PA15 TIM2_CH1 TIM2 PWM(8) GPIO(57) # M8 + +# LEDs +PA8 TIM1_CH1 TIM1 PWM(9) GPIO(58) # M9 + +PC13 LED0 OUTPUT LOW GPIO(90) +define HAL_GPIO_A_LED_PIN 90 +define HAL_GPIO_LED_OFF 1 + +# OSD setup +SPIDEV osd SPI2 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ + +define OSD_ENABLED 1 +define HAL_OSD_TYPE_DEFAULT 1 +ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin + +# Barometer setup +define AP_BARO_BACKEND_DEFAULT_ENABLED 0 +define AP_BARO_SPL06_ENABLED 1 +BARO SPL06 I2C:0:0x76 + +# IMU setup +SPIDEV imu1 SPI1 DEVID1 GYRO1_CS MODE3 1*MHZ 8*MHZ +# SDCard +SPIDEV sdcard SPI3 DEVID1 SDCARD1_CS MODE0 400*KHZ 25*MHZ + +IMU Invensensev3 SPI:imu1 ROTATION_PITCH_180_YAW_270 +DMA_NOSHARE TIM3_UP TIM8_UP TIM2_UP SPI1* +DMA_PRIORITY TIM3_UP TIM8_UP TIM2_UP SPI1* + +# no built-in compass, but probe the i2c bus for all possible +# external compass types +define ALLOW_ARM_NO_COMPASS +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 +define HAL_COMPASS_AUTO_ROT_DEFAULT 2 +define HAL_DEFAULT_INS_FAST_SAMPLE 3 +# Motor order implies Betaflight/X for standard ESCs +define HAL_FRAME_TYPE_DEFAULT 12 + +# filesystem setup on sdcard +define HAL_OS_FATFS_IO 1 + +# minimal drivers to reduce flash usage +include ../include/minimize_fpv_osd.inc + +define DEFAULT_NTF_LED_TYPES 257 From c346694f71dbdc3050543224463601ee8aad43fb Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 13 Oct 2023 13:31:42 +0100 Subject: [PATCH 041/499] bootloaders: SpeedyBeeF405v4 --- Tools/bootloaders/speedybeef4v4_bl.bin | Bin 0 -> 14272 bytes Tools/bootloaders/speedybeef4v4_bl.hex | 894 +++++++++++++++++++++++++ 2 files changed, 894 insertions(+) create mode 100644 Tools/bootloaders/speedybeef4v4_bl.bin create mode 100644 Tools/bootloaders/speedybeef4v4_bl.hex diff --git a/Tools/bootloaders/speedybeef4v4_bl.bin b/Tools/bootloaders/speedybeef4v4_bl.bin new file mode 100644 index 0000000000000000000000000000000000000000..980fe284f6a03a4cb68ea0e05c1c70f152af31b2 GIT binary patch literal 14272 zcmch8eSB2K_4nMD&ECxhvdKnBHUT!ffPqC^NRTL2HoMDB$bvzlEd*_E641NBz!t?~ zUw$kvR)kukvHhiqwv_Y*wFMI0)~In2u(dDNT`)F4{fVz@Nd5JO1ombFd!O&@28wN; z=lS*d(%C^0d3>9fzzG_ZVx{;%{jMKFhttW?5UX z!E$%OhSm4htzEsL?(Vt`b$+)JWb5kd{I>Djf*P{YQg1;G%?tgTepREKu{(>8s>1TO z2gv+wkl)kd4(Pq9($q^16Tyl^^?{VLE-LrdL(lq1i`AwTXYPMmCdzwbKd&}#>FoJg z6;sSfIe|2n(>$(7?5o~;g~!fu9+M7p*V8`IZjqj8!UVxE8L1IL@7>?RSoG9mR_#IX>-Y_N`Ry3JG7* z5n)CK5qgl;qkK7e^h7Wlh;W@igvXG6jr1-OZU5VNUXS*t$NT*hWdq8WziA)J@82d# ziAy=ZjdZZZFAb4wAzUQt_Cx1Nf2rm{-=^^^3`AKwHnYp97&)Uu2$Shrd`ogoOa#U^V`T16 zBk7hOM=4E>Nxeu)IwF*dQxdf1*(8}cE%9xYjyOHRi!EKGn3m@zm>WpRQ1m5{uF+gG z3ySGnZ$aBTqmCGZzTZjC5T`>&pL6R^(v^B)lySP0d$#clhGTXgnK30`^}QtCCEX(a z0+cKskq)M5**dc3ARYVOCH8mIe12dQ8qrQ>YZn$AWIDKZPGua-!p~wPO!f9otgC-qlRWAL zq%7Kw^adz6eTnj8@re20wCi&EUmvov?j@Pe%}_W}5_XF_mNHM|d$HycOnb0OD<(=~ zqUP*=?psTl);ES9X6c+85*aBB&7eXzxI?!vMrU^L625E3lFXRvwEZ06Qh!QLDf&yE^I#V zGNiWYKsltQA2g(-wmvn|oD`0A2QW*0jkjmX;*n<#RAEjZsF+I&T>)LHVTd;jrPhuX z&r88C2Ni{wmp4LrWQ+*5%xCBx@JrO)6iM$vMET*U7UwS&RT0IbnGdDTA!yk32QF*a z>;sfby8SwE>3)?;dFzNZMb-NkgDHs>9MIw)Uc~u>^;@jzz_oLuBB<*fy;*$u;|y`- zCvuN1RO(s~R%_moSr9pMPh;Xt5Gy3PDqj|3L(B& zi+5>3g&~K#U2dV*`GOAT+q-_=mnr^2WJIgzd_}4xVLEndE+IyFZPak9VYxF%rkBX2 zyLPyRlZ?_e>X3OaQ~JVrSB*nDcLH>TzYkhvBu4q-OJs;h5#< z#-gw$tdGp-q4WG!-EoYuV()pAE25I}d=X>X$6|l4Gi6elWGsDLo$f5{B6gu^8%lx= zyagFPUyz|)YOzCJ0Cp9sJm~zu7vv^V0JG*_7NhcEeU>dq0m>V?F6bID zg-pv#SmzJI}5l7ovZQIeV=;Ui^%eJ#vnR zk+`n>O4`>P@~(edeX`6V=WO9;T@x+-COa!PTJT`*BaD5I%k0jIGSBcs%Lt>WNx*rT zj^YPd(JB)qGRht@_2xMl=}nENW;yi zaAuV0x-x|#S197e$x#M0eFW(GSm+o!vq7ugo3l??4EcfH z_7!wg`b~EfqI~6*@?NZuVqWC2UlwV^ZvPsfoOG_`*l)=UO1*fA_L}iEM!6D*BE_P`SB6_uuai?G&I-%FMO|Voo?W95j_aQ`JENcS-ZpzIdU#-BDR+je-rlIU z9ckp&(j6xUy1VdmaSCUurFSoVUTZ=scgP8vl@J-+ z#yxcChkjn1ASS!gHa9=`klr~(0L{-O$K*BsLOBETDePie809yYm^SViMtLD6cdla= z_I{!~s;0dj-65rSOs@0i%4GKWNa1c~k=ZpA<%hiN*_dHod1!@N?E1_2D4=M%Szbw{ z#+{Zs{CCMqy7*!#UyBElRN8sa_FrGLidy`oWEy*UFO?mmOnQ;Aa{*#MJiwG5t>4kW zH5_g5G;oc9N-Bf&9LS8r1Kb^l2XuE-NQ^Q;W$pIBLn)sU=K#)GI&Yo0!hcGdDCUXz zUDy>c-={C_^Mb-nPA-QObLi7l4PaeB>jU zneh|_$M;E%lJW|p)Z*Mq!{}2mYf~_~&%wM2m_UfNlNr3o1+X?iHGjwJ zYagl)s%0ynLu#X3DBHUzrzthqF?zWzI)@2!&5Q)q6;2(v;Q@>h{AC!w2WMba&ZkYZZjI+o5K z8l!ZWyE0JQR+(YniN1keS|%kQMP5*=ogb`kckc>+*!bkA*ZJ{!;;2!aT<{#Xja&yi zC}^;uhn4#Er1e;$^4Rb)ax z<5(PF;k&g4iK81DwT#`@$l5+=w6A?F_Wb#6TZz&UeEz&^>rbLjs-lx|?2W#lE_2e| zeEyl|&y$VIBa?w^@5XtN&hv*G8AnThqYOyvm+@O^dO@vnTE#<{$kn2B(Z_A#T!^ASsiRb=}Z<(b4U5qWtk@$40-^9L?N?Tr+U zLv2sA18Q^PKVx}UWb6=Ui&SH^cynq71E1X0b9kDj(lH>=v;gMg7Dpdk=Rn*F{%XES6pm z`b0V(9sT^e_;ZZfP;`yuIbe@M?=l>^2-9EKW$HC7VjW}s>3*@%bbj(5`WKwJ#xW2z zrq<@w)M)WjmoBfCqu4LkK;C`P%T&?T_@@}LbDOuz9Cqv<$d9|nj@QYYqK6OhVs^wK8meWigWNVMBN;#5OX12x`epj1LKTDE)gD-flfXN6`6QtJ0D=8B0^OppMDg};)wjvD z@)}ELj9iY0{nv=awjYmkD51!^?OwB95;Sla}3oUb^4qmvPaFI z!@`2knnUnwoWrBuG^caON+_-=h~=ed55XqVdOsCl3Dm{a1hm(U@0LPu2KwCC<(Bgy1GD6jc(nS$)MHEYhXcPdA{LpIR!Bdn&j+XH zgh4~fMwtM+ai^O^%X>N5F5M|T1gTEZMq;KACqIQ4VOIa0@@~l}Et86+)zS~--In&W z^l_>b%DIJqh0HT&m4`EnsfRg1%$z9|Fv=4N_*n_Q@TYFBe{<1XM0kc{nREG*sq@py zC~v$Jz?r0m@_ZA-ll9z?iK&n>XBYUlOTc7fq$(-Det&)*&YQ0!GOuNnRS8dFr#nN; zIPuM*65wx0Tq`aR&&4vYr#Mv?1Drp6Nren4&(u%`C}ET@B(kf`Vy$Z0`XhHnbT&Lw zC-gxDr;miA{+DI1Wllj!c#hZ!4{{c`(xKVJc_LSphWU>auKmDgdI8pho!AlY^?AUb zw;&5ss9>4h-v;|WLgSk<)&F)m)7y^oo=b74v){WTUqgS~xIj^S|$Z0`%;2e{?bj{;J7kuxRnxaC$z7k5;~?z7iCMO!_&u_Nyk? z0dI}=t3|G7Wv&qM`~Ey{AEt9G!0}apMI8zM5q^~w_HK~+SE2SpI#CdrXY#OD98sD5T0E?J ziq??V2S^#Q*#n%tG4Pvi<~g>^Bu2Zx>*j}8p6R#1S1`jLp0#Yk(%G<^1)|08(R4$M zlBPTV`%U~%K4KYZ59CYGv&d{>rTitpk%@E-5?#>(R+1JsslVxl^;gDiG4>!b(mNm0 zPsWGfUk@W*d;v10I;s=1P@B*kOMlZ{f?n@wLRZEO7rIN9(yxAenef#(*VzA_`kf$B zi@oMO^~t?+w}?G615{ViR;^OWC{MpUWA5Cj-c|wqOU7T(0zCyjo5&4iF}34&ReNxY zQMkn%&@Y%!_HInDElolGTx-Mq&%UC9Ed~QS|95w>Dqlop&cKqXT|&RPA|;w%CM-A_ zgAS}`7KCGe9iK0I0})10Hho>2R)j=v;n?aE@@ekk+f)b1&8$lZ84#1ZuSbh3n%-ye zliA^LMs=OU4(*y>Cs}0MNU*^o3B7Z#11|w@XYN@dgpBCZiazgX2K2#gi5s^ivU?=B z(vt3z%JKcVzQz(IG^sypS=LhfmT&ZAEuSc6*|EkO?ojz}h$`=ZKZRJrP2LMp1~%Vq zDh{n)V!arXFt!sZ5A$Jsi2PzD(Q+16lCgw(3d~9DYB*j0q-CIex-;K<#A57WtRt~p z8LJ}7FM>?Nv`-qo7+SqW)8aubyL#AuLOM!LcY8+2ebk~h*PH#GkzlDAJLBDe`3d*} zoF<~2RJHiFl%H!#?YVSJ$`guL4dp5fmnXWT+w;4Jn2lfRzYg~?X4I{WIF{r5(uVDW zk{17h<~qk*%gwo_f4ai(cjr%E=CYt>a+llgCxeV`den|Sc8tADW2|Z~e>3ll#dhdp zQHS3?;=0dK@9;13IO=i3xjrLxud2n(8YlnIJrDr|`Z~~eu7=yl7=^dj+W~K{H|}x- zsrVzr8dNX{-yIXMPntHuOq?^iz-p-!s9s#};CB&8ObB2mGPUrP+ z7j5*8ko$}7N#)+6domGc1+VY3ORQHI$Kp(3!Ti>ERO^Zq7D`iqxF{}th_NwxLzoYGs~;-KNpl5#5_P*jW}>KgZSkODs~LaxK+mC)IroYo0}f z^YE|>^P}|?p6=U)uwRl9(OstEh$dM?j{=HOgL3<2u&Y zxei(xmN6F@dKn0DTNnpo0nyn$Z*!ZwFgnXuw?1{_*;v<{%GcF3|KlC##A1(ijh`sC zi&K3cN>hEu5J84Fr;=L^+wIbZ=9&@S+}T))6ZhgN#$H;V1zIABQvYdvny%lYOxwuJ zpGkDDd_Y?-A5%@Rc8{rfNJX-*C)3wiPwno;`cBycz3r3&u>7dbP}->;y7GvNLx_{y z>^v+WsUdH(P9*RFwfKYDGtIb_M$FyDElra{ieB6|H8#AI_nLXwW%Cb zmuLD0VFw-d;CqokIkE^PKk^#~n_=;>&|~x2b)5}ruNQoG1&PVs+@juUIzEosbCxlK zn(}n)m_}%pG@p_u$r%clao<$dp&P6)XNf^EJF#uF=4^!tGh&Xarb5h-!CA+(g@45} z32yjt|98Wsw`L3lznF2Jh-B7HkuUA$hgLC5nT4K>EBe%;e52=eXpAGD;J(^aQ0r%| zt)KdHSI6__-B0Z45SZD!!nK}$^-gPBzWXfaVTN3+4za~I)H_MBSeug9?~}sdBZPXF zp0hh^tIF0gQ$2HU1Mc!^6!#Vyfz}N!o&0B&6c&$=ir*rqBNw0LxWn-G7jwAT<1%rM zl!(QU*1ja5O}K}+(LO>vhmliU_Op6D{K+r@uLw`r?ajIJk#$=9D~Q{!n&)X=%B)#s z9w9D1g5PObVc2r1^;z|QXairFKgb15M%gU+qs0PDnH zk&dc-OPUkKu$#2_;~Mo4@|9qA5&D*uGc$kYDs@kaP;NIjpHQ<7|3%HSGG!ligYq-F zLB8yI?``r|mt1qA5773r85ysuWir+CG$$P?PCB;j0Vhv@lhp5cEB1tIFYakqtNdf&P;l>{L1^>7IK*e4@6Y!dy)B3%{5D4Sx$6ev zHT#yWYu@00&Og;PX(YI6L%lvicl5QFIC@K4LzK!_$lTmheb{~5syg&j!?Z*-6+Y1| zeYnk`r~d26lkxj6E!64yzDsTBi;q?%<8_w~@mYO+&|0&Skv%BeM*_83Vb6%E)-$rV zc2JrJEo;QCT-fs*>;Qp#uHKH=YgUww@U5!$e;6wn_gg_G>sc&?VYq3*h8U`y*OcSeQbL@zc+YL;3qZI5u@48-y^4MF5 z4OBPj&j-KM;%L%){%F-jErm1F}-6#CamyMF8WTMknAuH=oe#^(3bkM`m&htAT_+1w$2CGqfB z$CAYtzC~YC4EoGC%?p?jS8*3;orV=d3dpR&Q#7woS}Jhf7o_XPPOlcFW-Xq7vG@@~ z!Z=L#OglKThu#x_Bdf&~;0UwukFm$~LKr)2P(QmZjC;pD>=47Yg=@~{m+XwOrQiZf z=f6@uuI59V1?yi1NYRf6v$9C>E_Wv75|5a-zg=eG#n<7tPHKwfC>-A6P^{lsvMY>R z+C5mM%&rtx8k3|t>1pN$D{`WACmSK=*N_J)uhiW*UU%bFb&Ig8{}bGJ9pK22}0UZ#$|6i>Ynq3~^5}oA^?GjKdvAMlIjLHIiao$7{G( z!`ngJO&lH&+=mA;b3Bc7f30Xr-B{$H#&$&7h_f;oAH(?(8Q>9RXQD^s%%1!ypaCZb z=P!_sz#ljw9r2sJ+x=X9t9yFb)5O(Ni|*}L>HW$C@k4o0SA*X?C0FijFnd32fRB5| z{`Jxx>dPge3#8<;Q{}xFiQqOJXXFt-v*@VgNn!MiWAxO+&u!q=r*9#?^7GIM`Es57p#v@R(Lw~8+hxv~pS zmWuSOr*9)YNRPwc>}+zCx^C!fa4kR&d;9qK-_v#jQ?I-KI34YGF{fCEnXghio7Q;0 z?Cos0%Ns*HjZMjk8{>;1Co_#BWR`M}7T$YUZnu z6UL=-vcVHyq4JB2^vt&Bi-}l@x26Arw~*E);QYJ1?0(CXeGMN#2LC9plXxL>wYLTHRE$z;)W zec?&nkc)$F?0}cyczRq~kkt)oS^a&~?`c%>;*yic=_qf;W{Ee6m*CrWHZAgg0rI-V z`*AGI=gCpT*1L8z?djqdbyy}w%+gW3+&n5B^;^6<{A_*u<@EqwFpvS21hian_TUAE zXH`?6lIFy=s?k!<+D<`I>2F%1F)+a3o-!2^3l;j9MtbY_?L(`ihZ-g#vK3aT9eZqm zFQs<>v4M;Q#|DV^r_#rGC-Ii%z>AAx1A?6&Dq|*8&sZ149a=Je@FHVBBV|@|o5>TK zWaf!(`ON{=uJ_5}n*;oUWc;@mGY|!X4T(6>{jj?qM7nex-i=hBXv+6Q8bDVn?&*^~ z(jIw-^auHuLbQ2BWI_bA^!UWN}k6c{hRit=~H%P*q5f4tm{ z^0D#qFHpt{;uOxGrK0FW`R^A~J~?4sLClT5<6WId#+i#+yj7*%crv~b`yHLb--Zo4 zbW5w(Q>v>Q< z@6M_&+|Zix3|rxM1wFO4_6F$9{8J6Y)?Q!NcnVQr##UEPPYvLsF#;=p29Rzcl;b}k z8(k;6f9L7Y=hW-_(w1Q|{>`y8KZM?Ch+Azudt~Ltv&T~}eUA(akTmrkE&e+HDx3&) z{?&LBY-wsx5Y=k1G_m7(UDK+Dx~A1glw!1{C`Nv_WrMNWB)dj}0h5%!k&L(kht89& zQ^PeQL1+Fw1^3j#{v!7wcCOsslcE!1=Trn0p8IUMP27~xfUs}+6kRCW%W&*CTr1!rSKwax zCpi8xK0omJFXP+)PjJFze1MBwfqU|w;7phCH347KWqiRaaFcLPcc-5p*|MpwzB7aG zGgr3)G6F~mU#4pFdh}c0R#}X%tm;;LMey~3j_)&6o9{*2y|8@orK@hmR|H@5rbLU^ zAhvdy2L?yp*WNfK}R)l2b5lb7P_E@|Y% zyRN!GWJ*nrBLgId#d|pwukJ{g>H#O>&6$I~9VD|yQCoZa^3wU@;>C+ex>V-ea=A4B zN~!FIRjYuOv6kX;tAa45I>MP&6TN93Y6-a$_o8N=kh_r=AP*ofM*el=wB3)lS9c&i zj`S_0N02rn)gvuOdK!tsG4uz2jZQ)o^i^;-M9-p%O=~x=@ZY=felo*dQ?b%J<2pAU zP1P=0xwK;048XIgUW7bkBDe-ayok8SUffw6Lb}|>jl(R+Nsnd1_hGct>dWI&d!1oe zGEhi_Q49Vj3i*Rb9>DBE?BBq82+NSe^9`6B!=k90PE3e1Glb!%v#f4<24VEN?Hn#v z3_L^FOmx)i7}iCzZ8RgfNN)pIE@Q$-#AV2>_!5w^9EjjK13x}Pa$jKGy0s5BtXp?? z*#l+7Id6Vx*@7Dumfu+6_IQ_wKthpSol>))v;E&CLLST|!n|wnKL|)JbbbT#rHRhJ zA9)bD3m=qM&Gr5b#J~35btn^N+iaRWi$4rAT}#q0{OzR^ObwiFLs`>k)s;WW=F4rS ze`reqrEsG3|En!UF~+;B4=E!4FFyf@JN4(vPGuVTKFx*88EyU)GEFu9i=Y1mIt(>( literal 0 HcmV?d00001 diff --git a/Tools/bootloaders/speedybeef4v4_bl.hex b/Tools/bootloaders/speedybeef4v4_bl.hex new file mode 100644 index 00000000000000..3ae7a03fd43d28 --- /dev/null +++ b/Tools/bootloaders/speedybeef4v4_bl.hex @@ -0,0 +1,894 @@ +:020000040800F2 +:1000000000060020E1010008E3010008E301000808 +:10001000E3010008E3010008E3010008E301000830 +:10002000E3010008E3010008E3010008752F000860 +:10003000E3010008E3010008E3010008E301000810 +:10004000E3010008E3010008E3010008E301000800 +:10005000E3010008E30100081D32000845320008F2 +:100060006D32000895320008BD320008E301000837 +:10007000E3010008E3010008E3010008E3010008D0 +:10008000E3010008E3010008E3010008E3010008C0 +:10009000E3010008E3010008E3010008E53200087D +:1000A000E3010008E3010008E3010008E3010008A0 +:1000B000B9330008E3010008E3010008E301000888 +:1000C000E3010008E3010008E3010008E301000880 +:1000D000E3010008E3010008E3010008E301000870 +:1000E00049330008E3010008E3010008E3010008C8 +:1000F000E3010008E3010008E3010008E301000850 +:10010000E3010008E3010008E3010008E30100083F +:10011000E3010008E3010008E3010008E30100082F +:10012000E3010008E3010008E3010008E30100081F +:10013000E3010008E3010008E3010008E30100080F +:10014000E3010008E3010008E30100082927000893 +:10015000E3010008E3010008E3010008E3010008EF +:10016000E3010008E3010008E3010008E3010008DF +:10017000E3010008E3010008E3010008E3010008CF +:10018000E3010008E3010008E3010008E3010008BF +:10019000E3010008E3010008E3010008E3010008AF +:1001A000E3010008E3010008E3010008E30100089F +:1001B000E3010008E3010008E3010008E30100088F +:1001C000E3010008E3010008E3010008E30100087F +:1001D000E3010008E3010008E3010008E30100086F +:1001E00002E000F000F8FEE772B6374880F30888B6 +:1001F000364880F3098836483649086040F20000E6 +:10020000CCF200004EF63471CEF200010860BFF36C +:100210004F8FBFF36F8F40F20000C0F2F0004EF638 +:100220008851CEF200010860BFF34F8FBFF36F8F8C +:100230004FF00000E1EE100A4EF63C71CEF20001E4 +:100240000860062080F31488BFF36F8F01F034FF3D +:1002500002F02EFE4FF055301F491B4A91423CBF21 +:1002600041F8040BFAE71D49184A91423CBF41F896 +:10027000040BFAE71A491B4A1B4B9A423EBF51F83E +:10028000040B42F8040BF8E700201849184A914281 +:100290003CBF41F8040BFAE701F012FF02F05CFEEC +:1002A000144C154DAC4203DA54F8041B8847F9E7A7 +:1002B00000F042F8114C124DAC4203DA54F8041B22 +:1002C0008847F9E701F0FABE00060020002200206E +:1002D0000000000808ED00E00000002000060020FB +:1002E0008037000800220020402200204022002009 +:1002F000602E0020E0010008E0010008E001000895 +:10030000E00100082DE9F04F2DED108AC1F80CD066 +:10031000C3689D46BDEC108ABDE8F08F002383F3CF +:1003200011882846A047002001F076FAFEE701F088 +:1003300005FA00DFFEE7000038B500F069FB01F0C8 +:100340008BFE054601F0AEFE0446D8B90F4B9D4228 +:100350001AD001339D4218BF044641F2883504BFCC +:1003600001240025002001F081FE0CB100F076F898 +:1003700000F004FD00F0B2FB284600F0BFF800F0EA +:100380006DF8F9E70025EDE70546EBE7010007B05A +:1003900008B500F075FBA0F120035842584108BD94 +:1003A00007B541F21203022101A8ADF8043000F0B4 +:1003B00085FB03B05DF804FB38B5302383F3118867 +:1003C000174803680BB101F0F3FA164A14480023EA +:1003D0004FF47A7101F0E2FA002383F31188124C92 +:1003E000236813B12368013B2360636813B163681A +:1003F000013B63600D4D2B7833B963687BB90220F4 +:1004000000F036FC322363602B78032B07D163683E +:100410002BB9022000F02CFC4FF47A73636038BDD6 +:1004200040220020B9030008602300205822002049 +:10043000084B187003280CD8DFE800F00805020804 +:10044000022000F00BBC022000F0FEBB024B002299 +:100450005A6070475822002060230020234B244A12 +:1004600010B51C46196801313FD004339342F9D1CD +:100470006268A24239D31F4B9B6803F1006303F506 +:1004800040439A4231D2002000F042FB0220FFF7A5 +:10049000CFFF194B1A6C00221A64196E1A66196E76 +:1004A000596C5A64596E5A665A6E5A6942F0800203 +:1004B0005A615A6922F080025A615A691A6942F0F7 +:1004C00000521A611A6922F000521A611B6972B651 +:1004D0004FF0E0233021C3F8084DD4E9003281F316 +:1004E00011889D4683F30888104710BD00C000089E +:1004F00020C0000800220020003802402DE9F04F03 +:1005000093B0AA4B00902022FF210AA89D6800F01A +:10051000DFFBA74A1378A3B9A64801210360117035 +:10052000302383F3118803680BB101F041FAA24A2A +:10053000A04800234FF47A7101F030FA002383F3CE +:100540001188009B13B19D4B009A1A609C4A009C35 +:100550001378032B1EBF00231370984A4FF0000A34 +:1005600018BF5360D3465646D146012000F076FBB3 +:1005700024B1924B1B68002B00F01182002000F088 +:100580007FFA0390039B002BF2DB012000F05CFB61 +:10059000039B213B162BE8D801A252F823F000BFA1 +:1005A000FD05000825060008B90600086B050008CF +:1005B0006B0500086B0500084307000813090008D5 +:1005C0002D0800088F080008B7080008DD0800089B +:1005D0006B050008EF0800086B05000861090008BA +:1005E0009D0600086B050008A5090008090600081B +:1005F0009D0600086B0500088F0800080220FFF721 +:10060000C7FE002840F0F581009B0221BAF1000FDF +:1006100008BF1C4605A841F21233ADF8143000F0B3 +:100620004DFAA2E74FF47A7000F02AFA071EEBDBCE +:100630000220FFF7ADFE0028E6D0013F052F00F2B3 +:10064000DA81DFE807F0030A0D101336052305935E +:10065000042105A800F032FA17E054480421F9E714 +:1006600058480421F6E758480421F3E74FF01C08E6 +:10067000404600F04FFA08F104080590042105A84F +:1006800000F01CFAB8F12C0FF2D1012000FA07F7A4 +:1006900047EA0B0B5FFA8BFB4FF0000900F064FB9D +:1006A00026B10BF00B030B2B08BF0024FFF778FEDD +:1006B0005BE746480421CDE7002EA5D00BF00B03E5 +:1006C0000B2BA1D10220FFF763FE074600289BD029 +:1006D000012000F01DFA0220FFF7AAFE00261FFAF3 +:1006E00086F8404600F024FA044690B100214046C6 +:1006F00000F02EFA01360028F1D1BA46044641F244 +:100700001213022105A8ADF814303E4600F0D6F9C8 +:100710002BE70120FFF78CFE2546244B9B68AB425C +:1007200007D9284600F0F6F9013040F0678104351A +:10073000F3E7234B00251D70204BBA465D603E4613 +:10074000ACE7002E3FF460AF0BF00B030B2B7FF4F4 +:100750005BAF0220FFF76CFE322000F091F9B0F1A0 +:100760000008FFF651AF18F003077FF44DAF0F4AB2 +:10077000926808EB050393423FF646AFB8F5807FD9 +:100780003FF742AF124B0193B84523DD4FF47A7027 +:1007900000F076F90390039A002AFFF635AF019B2B +:1007A000039A03F8012B0137EDE700BF0022002078 +:1007B0005C23002040220020B903000860230020B1 +:1007C0005822002004220020082200200C220020B1 +:1007D0005C220020C820FFF7DBFD074600283FF41D +:1007E00013AF1F2D11D8C5F1200242450AAB25F0E9 +:1007F000030028BF424683490192184400F042FAA0 +:10080000019A8048FF2100F063FA4FEAA8037D496E +:100810000193C8F38702284600F062FA06460028D2 +:100820003FF46DAF019B05EB830537E70220FFF72F +:10083000AFFD00283FF4E8AE00F0B6F900283FF421 +:10084000E3AE0027B846704B9B68BB4218D91F2FF8 +:1008500011D80A9B01330ED027F0030312AA1344C8 +:1008600053F8203C05934046042205A900F0B0FA55 +:1008700004378046E7E7384600F04CF90590F2E788 +:10088000CDF81480042105A800F018F906E700232C +:10089000642104A8049300F007F900287FF4B4AEA3 +:1008A0000220FFF775FD00283FF4AEAE049800F07B +:1008B00063F90590E6E70023642104A8049300F09F +:1008C000F3F800287FF4A0AE0220FFF761FD0028B6 +:1008D0003FF49AAE049800F05FF9EAE70220FFF7D0 +:1008E00057FD00283FF490AE00F06EF9E1E70220DA +:1008F000FFF74EFD00283FF487AE05A9142000F055 +:1009000069F904210746049004A800F0D7F8394695 +:10091000B9E7322000F0B4F8071EFFF675AEBB074A +:100920007FF472AE384A926807EB090393423FF6B0 +:100930006BAE0220FFF72CFD00283FF465AE27F0D8 +:1009400003074F44B9453FF4A9AE484600F0E2F82A +:100950000421059005A800F0B1F809F10409F1E7B8 +:100960004FF47A70FFF714FD00283FF44DAE00F00D +:100970001BF9002844D00A9B01330BD008220AA996 +:10098000002000F0ADF900283AD02022FF210AA86B +:1009900000F09EF9FFF704FD1C4800F043FF13B080 +:1009A000BDE8F08F002E3FF42FAE0BF00B030B2BA6 +:1009B0007FF42AAE0023642105A8059300F074F8A3 +:1009C000074600287FF420AE0220FFF7E1FC8046B6 +:1009D00000283FF419AEFFF7E3FC41F2883000F045 +:1009E00021FF059800F0F2F9464600F0BDF93C46BB +:1009F000BBE5064652E64FF0000905E6BA467EE63C +:100A000037467CE65C22002000220020A086010000 +:100A10007047000070B50F4B1B780133DBB2012B20 +:100A20000C4611D80C4D29684FF47A730E6AA2FB5C +:100A30000332014622462846B047844204D1074B80 +:100A400000221A70012070BD4FF4FA7000F0EAFE27 +:100A50000020F8E710220020082600209423002020 +:100A600070B504464FF47A76412C254628BF4125BF +:100A700006FB05F000F0D6FE641BF5D170BD00004A +:100A800007B50023024601210DF107008DF807305C +:100A9000FFF7C0FF20B19DF8070003B05DF804FB2D +:100AA0004FF0FF30F9E700000A4608B50421FFF7D0 +:100AB000B1FF80F00100C0B2404208BD30B4054C27 +:100AC0002368DD69044B0A46AC460146204630BC2B +:100AD000604700BF08260020A086010070B501F025 +:100AE000C1F9094E094D30800024286833888342BB +:100AF00008D901F0B1F92B6804440133B4F5404F33 +:100B00002B60F2D370BD00BF962300206823002025 +:100B100001F056BA00F1006000F5404000687047EF +:100B200000F10060920000F5404001F0E1B90000E2 +:100B3000054B1A68054B1B889B1A834202D9104447 +:100B400001F08AB900207047682300209623002016 +:100B500038B5084D044629B128682044BDE838401E +:100B600001F09AB92868204401F07EF90028F3D0FA +:100B700038BD00BF6823002010F003030AD1B0F590 +:100B8000047F05D200F10050A0F51040D0F80038E5 +:100B9000184670470023FBE700F10050A0F5104015 +:100BA000D0F8100A70470000064991F8243033B19C +:100BB0000023086A81F824300822FFF7B1BF012022 +:100BC000704700BF6C230020014B1868704700BFBE +:100BD000002004E070B5194B1D68194B0138C5F3AE +:100BE0000B0408442D0C04221E88A6420BD15C681D +:100BF0000A46013C824213460FD214F9016F4EB1EE +:100C000002F8016BF6E7013A03F10803ECD18142E7 +:100C10000B4602D22C2203F8012B0A4A052416881F +:100C2000AE4204D1984284BF967803F8016B013C30 +:100C300002F10402F3D1581A70BD00BF002004E095 +:100C40009C34000888340008022802BF024B4FF091 +:100C500080729A61704700BF00000240022802BF04 +:100C6000024B4FF480729A61704700BF000002404F +:100C7000022801BF024A536983F4807353617047AD +:100C80000000024010B50023934203D0CC5CC45452 +:100C90000133F9E710BD000010B5013810F9013F2C +:100CA0003BB191F900409C4203D11AB10131013AA4 +:100CB000F4E71AB191F90020981A10BD1046FCE72C +:100CC00003460246D01A12F9011B0029FAD17047D7 +:100CD00002440346934202D003F8011BFAE770472F +:100CE0002DE9F8431F4D144695F824200746884601 +:100CF00052BBDFF870909CB395F824302BB92022BA +:100D0000FF2148462F62FFF7E3FF95F82400C0F16A +:100D10000802A24228BF2246D6B24146920005EB05 +:100D20008000FFF7AFFF95F82430A41B1E44F6B2F5 +:100D3000082E17449044E4B285F82460DBD1FFF715 +:100D400033FF0028D7D108E02B6A03EB82038342EC +:100D5000CFD0FFF729FF0028CBD10020BDE8F883D2 +:100D60000120FBE76C230020024B1A78024B1A701B +:100D7000704700BF942300201022002010B5104CB3 +:100D8000104800F0B5F821460E4800F0DDF8246860 +:100D9000626DD2F8043843F00203C2F804384FF40D +:100DA0007A70FFF75DFE0849204600F0D3F9626DC6 +:100DB000D2F8043823F00203C2F8043810BD00BF93 +:100DC00068350008082600207035000870470000CC +:100DD00030B5094D0A4491420DD011F8013B5840FD +:100DE000082340F30004013B2C4013F0FF0384EA86 +:100DF0005000F6D1EFE730BD2083B8ED02684368BC +:100E00001143016003B118477047000013B5446BEC +:100E1000D4F894341A681178042915D1217C022958 +:100E200012D11979128901238B4013420CD101A9E7 +:100E300004F14C0001F0F8FED4F89444019B2179B0 +:100E40000246206800F0D0F902B010BD143001F065 +:100E50007BBE00004FF0FF33143001F075BE000080 +:100E60004C3001F04DBF00004FF0FF334C3001F02B +:100E700047BF0000143001F049BE00004FF0FF31C1 +:100E8000143001F043BE00004C3001F019BF0000E7 +:100E90004FF0FF324C3001F013BF000000207047CC +:100EA00010B5D0F894341A6811780429044617D183 +:100EB000017C022914D15979528901238B401342B4 +:100EC0000ED1143001F0DCFD024648B1D4F8944450 +:100ED0004FF4807361792068BDE8104000F072B96A +:100EE00010BD0000406BFFF7DBBF00007047000043 +:100EF0007FB5124B036000234360C0E90233012534 +:100F000002260F4B057404460290019300F18402FF +:100F1000294600964FF48073143001F08DFD094B83 +:100F20000294CDE9006304F523724FF480732946DF +:100F300004F14C0001F054FE04B070BDBC34000854 +:100F4000E50E00080D0E00080B68302282F31188B0 +:100F50000A7903EB820290614A79093243F8220050 +:100F60008A7912B103EB820398610223C0F89414CA +:100F70000374002080F311887047000038B5037FA8 +:100F8000044613B190F85430ABB9201D012502215D +:100F9000FFF734FF04F1140025776FF0010100F032 +:100FA00069FC84F8545004F14C006FF00101BDE875 +:100FB000384000F05FBC38BD10B501210446043054 +:100FC000FFF71CFF0023237784F8543010BD000086 +:100FD00038B504460025143001F046FD04F14C00FC +:100FE000257701F015FE201D84F854500121FFF7EC +:100FF00005FF2046BDE83840FFF752BF90F8443067 +:1010000003F06003202B07D190F84520212A4FF0F0 +:10101000000303D81F2A06D800207047222AFBD1DC +:10102000C0E90E3303E0034A82630722C26303640C +:10103000012070471122002037B5D0F894341A6887 +:101040001178042904461AD1017C022917D1197993 +:10105000128901238B40134211D100F14C0528461F +:1010600001F096FE58B101A9284601F0DDFDD4F843 +:101070009444019B21790246206800F0B5F803B042 +:1010800030BD0000F0B500EB810385B09E690446D9 +:101090000D46FEB1302383F3118804EB8507301D24 +:1010A0000821FFF7ABFEFB685B691B6806F14C008B +:1010B0001BB1019001F0C6FD019803A901F0B4FD38 +:1010C000024648B1039B2946204600F08DF80023D4 +:1010D00083F3118805B0F0BDFB685A691268002AD5 +:1010E000F5D01B8A013B1340F1D104F14402EAE739 +:1010F000093138B550F82140DCB1302383F3118831 +:10110000D4F894241368527903EB8203DB689B695B +:101110005D6845B104216018FFF770FE294604F1AF +:10112000140001F0B7FC2046FFF7BAFE002383F35A +:10113000118838BD7047000001F016B80123037014 +:101140000023C0E90133C36183620362C362436267 +:101150000363704738B50446302383F311880025B4 +:10116000C0E90355C0E90555416001F00DF80223BF +:10117000237085F31188284638BD000070B500EB58 +:10118000810305465069DA600E46144618B11022F4 +:101190000021FFF79DFDA06918B110220021FFF783 +:1011A00097FD31462846BDE8704001F0B7B8000011 +:1011B000826802F0011282600022C0E9042282618A +:1011C00001F038B9F0B400EB81044789E4680125E7 +:1011D000A4698D403D43458123600023A260636084 +:1011E000F0BC01F053B90000F0B400EB81040789B2 +:1011F000E468012564698D403D4305812360002337 +:10120000A2606360F0BC01F0CDB9000070B50223AC +:10121000002504460370C0E90255C0E90455C564C1 +:10122000856180F8345001F015F863681B6823B1BC +:1012300029462046BDE87040184770BD0378052B4D +:1012400010B504460AD080F8503005230370436877 +:101250001B680BB1042198470023A36010BD000058 +:101260000178052906D190F85020436802701B6868 +:1012700003B118477047000070B590F83430044649 +:1012800013B1002380F8343004F14402204601F009 +:10129000F3F863689B68B3B994F8443013F06005C1 +:1012A00035D00021204601F093FB0021204601F0BB +:1012B00085FB63681B6813B1062120469847062307 +:1012C00084F8343070BD204698470028E4D0B4F844 +:1012D0004A30E26B9A4288BFE36394F94430E56B8D +:1012E000002B4FF0300380F20381002D00F0F280DC +:1012F000092284F8342083F311880021D4E90E23D5 +:101300002046FFF771FF002383F31188DAE794F892 +:10131000452003F07F0343EA022340F20232934266 +:1013200000F0C58021D8B3F5807F48D00DD8012BBF +:101330003FD0022B00F09380002BB2D104F14C027D +:10134000A2630222E2632364C1E7B3F5817F00F068 +:101350009B80B3F5407FA4D194F84630012BA0D1F7 +:10136000B4F84C3043F0020332E0B3F5006F4DD0D7 +:1013700017D8B3F5A06F31D0A3F5C063012B90D877 +:10138000636894F846205E6894F84710B4F84830D3 +:101390002046B047002884D04368A3630368E36312 +:1013A0001AE0B3F5106F36D040F6024293427FF454 +:1013B00078AF5C4BA3630223E3630023C3E794F895 +:1013C0004630012B7FF46DAFB4F84C3023F00203AC +:1013D000C4E90E55A4F84C30256478E7B4F84430DD +:1013E000B3F5A06F0ED194F8463084F84E30204605 +:1013F00000F088FF63681B6813B1012120469847FD +:10140000032323700023C4E90E339CE704F14F0348 +:10141000A3630123C3E72378042B10D1302383F384 +:1014200011882046FFF7C4FE85F311880321636805 +:1014300084F84F5021701B680BB12046984794F8F0 +:101440004630002BDED084F84F30042323706368CD +:101450001B68002BD6D0022120469847D2E794F88B +:1014600048301D0603F00F0120460AD500F0F6FFB4 +:10147000012804D002287FF414AF2B4B9AE72B4BA2 +:1014800098E700F0DDFFF3E794F84630002B7FF497 +:1014900008AF94F8483013F00F01B3D01A06204675 +:1014A00002D501F0A9FAADE701F09CFAAAE794F899 +:1014B0004630002B7FF4F5AE94F8483013F00F015E +:1014C000A0D01B06204602D501F082FA9AE701F06F +:1014D00075FA97E7142284F8342083F311882B4699 +:1014E0002A4629462046FFF76DFE85F31188E9E676 +:1014F0005DB1152284F8342083F311880021D4E9EA +:101500000E232046FFF75EFEFDE60B2284F8342012 +:1015100083F311882B462A4629462046FFF764FEAE +:10152000E3E700BFEC340008E4340008E8340008C6 +:1015300038B590F834300446002B3ED0063BDAB282 +:101540000F2A34D80F2B32D8DFE803F037313108B7 +:10155000223231313131313131313737C56BB0F869 +:101560004A309D4214D2C3681B8AB5FBF3F203FBD9 +:1015700012556DB9302383F311882B462A4629462C +:10158000FFF732FE85F311880A2384F834300EE029 +:10159000142384F83430302383F3118800231A464F +:1015A00019462046FFF70EFE002383F3118838BD4D +:1015B000036C03B198470023E7E70021204601F0C0 +:1015C00007FA0021204601F0F9F963681B6813B19E +:1015D0000621204698470623D7E7000010B590F86B +:1015E0003430142B044629D017D8062B05D001D847 +:1015F0001BB110BD093B022BFBD80021204601F096 +:10160000E7F90021204601F0D9F963681B6813B19E +:10161000062120469847062319E0152BE9D10B2314 +:1016200080F83430302383F3118800231A4619469A +:10163000FFF7DAFD002383F31188DAE7C3689B69BB +:101640005B68002BD5D1036C03B19847002384F865 +:101650003430CEE700230375826803691B689968FC +:101660009142FBD25A680360426010605860704734 +:1016700000230375826803691B6899689142FBD84F +:101680005A680360426010605860704708B50846A9 +:10169000302383F311880B7D032B05D0042B0DD051 +:1016A0002BB983F3118808BD8B6900221A604FF0B3 +:1016B000FF338361FFF7CEFF0023F2E7D1E9003269 +:1016C00013605A60F3E70000FFF7C4BF054BD96809 +:1016D0000875186802681A60536001220275D860A4 +:1016E000FEF710BE9823002030B50C4BDD684B1C74 +:1016F00087B004460FD02B46094A684600F04EF9E1 +:101700002046FFF7E3FF009B13B1684600F050F955 +:10171000A86907B030BDFFF7D9FFF9E7982300208B +:101720008D160008044B1A68DB6890689B68984225 +:1017300094BF00200120704798230020084B10B56B +:101740001C68D86822681A60536001222275DC6028 +:10175000FFF78EFF01462046BDE81040FEF7D2BDE0 +:101760009823002038B5074C074908480123002575 +:101770002370656001F044FB0223237085F3118818 +:1017800038BD00BF00260020F43400089823002054 +:1017900000F044B9034A516853685B1A9842FBD879 +:1017A000704700BF001000E08B60022308618B824D +:1017B000084670478368A3F1840243F8142C026939 +:1017C00043F8442C426943F8402C094A43F8242C3E +:1017D000C26843F8182C022203F80C2C002203F8EC +:1017E0000B2C044A43F8102CA3F12000704700BFD3 +:1017F0001D0300089823002008B5FFF7DBFFBDE8B4 +:101800000840FFF761BF0000024BDB6898610F20C2 +:10181000FFF75CBF98230020302383F31188FFF784 +:10182000F3BF000008B50146302383F31188082078 +:10183000FFF75AFF002383F3118808BD064BDB68CE +:1018400039B1426818605A60136043600420FFF7A2 +:101850004BBF4FF0FF307047982300200368984239 +:1018600006D01A680260506099611846FFF72CBFD5 +:101870007047000038B504460D462068844200D108 +:1018800038BD036823605C608561FFF71DFFF4E7E6 +:1018900010B503689C68A2420CD85C688A600B6033 +:1018A0004C602160596099688A1A9A604FF0FF3342 +:1018B000836010BD1B68121BECE700000A2938BFCB +:1018C0000A2170B504460D460A26601901F092FA05 +:1018D00001F07EFA041BA54203D8751C2E4604466F +:1018E000F3E70A2E04D9BDE87040012001F0C8BA20 +:1018F00070BD0000F8B5144B0D46D96103F110011D +:1019000041600A2A1969826038BF0A220160486072 +:101910001861A818144601F05FFA0A2701F058FA76 +:10192000431BA342064606D37C1C281901F062FA29 +:1019300027463546F2E70A2F04D9BDE8F8400120D2 +:1019400001F09EBAF8BD00BF98230020F8B5064606 +:101950000D4601F03DFA0F4A134653F8107F9F429F +:1019600006D12A4601463046BDE8F840FFF7C2BF1F +:10197000D169BB68441A2C1928BF2C46A34202D94E +:101980002946FFF79BFF224631460348BDE8F84051 +:10199000FFF77EBF98230020A823002010B4C0E9E1 +:1019A000032300235DF8044B4361FFF7CFBF000022 +:1019B00010B5194C236998420DD0D0E900328168E6 +:1019C00013605A609A680A449A60002303604FF0DB +:1019D000FF33A36110BD2346026843F8102F536004 +:1019E0000022026022699A4203D1BDE8104001F052 +:1019F000FBB9936881680B44936001F0E9F92269AF +:101A0000E1699268441AA242E4D91144BDE8104049 +:101A1000091AFFF753BF00BF982300202DE9F047B4 +:101A2000DFF8BC8008F110072C4ED8F8105001F0F8 +:101A3000CFF9D8F81C40AA68031B9A423ED8144438 +:101A4000D5E900324FF00009C8F81C4013605A6015 +:101A5000C5F80090D8F81030B34201D101F0C4F9B4 +:101A600089F31188D5E9033128469847302383F359 +:101A700011886B69002BD8D001F0AAF96A69A0EB34 +:101A800004094A4582460DD2022001F0F9F90022EC +:101A9000D8F81030B34208D151462846BDE8F04787 +:101AA000FFF728BF121A2244F2E712EB090938BFE8 +:101AB0004A4629463846FFF7EBFEB5E7D8F810301E +:101AC000B34208D01444211AC8F81C00A960BDE82C +:101AD000F047FFF7F3BEBDE8F08700BFA823002062 +:101AE0009823002000207047FEE7000070470000A8 +:101AF0004FF0FF307047000002290CD0032904D0BA +:101B00000129074818BF00207047032A05D8054857 +:101B100000EBC2007047044870470020704700BFC8 +:101B2000CC350008202200208035000870B59AB01E +:101B30000546084601A9144600F0C2F801A8FFF7BF +:101B4000BFF8431C5B00C5E9003400222370032367 +:101B50006370C6B201AB02341046D1B28E4204F1BA +:101B6000020401D81AB070BD13F8011B04F8021C5E +:101B700004F8010C0132F0E708B5302383F3118833 +:101B80000348FFF759FA002383F3118808BD00BF0B +:101B90000826002090F8443003F01F02012A07D1E4 +:101BA00090F845200B2A03D10023C0E90E3315E03D +:101BB00003F06003202B08D1B0F848302BB990F81F +:101BC0004520212A03D81F2A04D8FFF717BA222A52 +:101BD000EBD0FAE7034A82630722C2630364012061 +:101BE000704700BF1822002007B5052917D8DFE885 +:101BF00001F0191603191920302383F31188104AB4 +:101C000001900121FFF7BAFA01980E4A0221FFF76D +:101C1000B5FA0D48FFF7DCF9002383F3118803B010 +:101C20005DF804FB302383F311880748FFF7A6F91A +:101C3000F2E7302383F311880348FFF7BDF9EBE7A0 +:101C400020350008443500080826002038B50C4D22 +:101C50000C4C0D492A4604F10800FFF767FF05F117 +:101C6000CA0204F110000949FFF760FF05F5CA72C6 +:101C700004F118000649BDE83840FFF757BF00BF20 +:101C8000D02A002020220020003500080A35000854 +:101C90001535000870B5044608460D46FFF710F8E4 +:101CA000C6B22046013403780BB9184670BD3246DF +:101CB0002946FEF7F1FF0028F3D10120F6E70000E6 +:101CC0002DE9F04705460C46FEF7FAFF2B49C6B250 +:101CD0002846FFF7DFFF08B10636F6B22849284646 +:101CE000FFF7D8FF08B11036F6B2632E0BD8DFF835 +:101CF0008C80DFF88C90234FDFF894A02E7846B9C3 +:101D00002670BDE8F08729462046BDE8F04701F07F +:101D10009DBB252E2ED1072241462846FEF7BCFF4B +:101D200070B9194B224603F10C0153F8040B42F829 +:101D3000040B8B42F9D11B78137007350D34DDE7A6 +:101D4000082249462846FEF7A7FF98B90F4BA21C68 +:101D5000197809090232C95D02F8041C13F8011B45 +:101D600001F00F015345C95D02F8031CF0D118348E +:101D70000835C3E704F8016B0135BFE7EC3500080F +:101D80001535000802360008F4350008107AFF1FE8 +:101D90001C7AFF1FBFF34F8F024AD368DB03FCD4CA +:101DA000704700BF003C024008B5094B1B7873B96F +:101DB000FFF7F0FF074B1A69002ABFBF064A5A60B7 +:101DC00002F188325A601A6822F480621A6008BDF3 +:101DD0002E2D0020003C02402301674508B50B4B27 +:101DE0001B7893B9FFF7D6FF094B1A6942F00042FE +:101DF0001A611A6842F480521A601A6822F48052FA +:101E00001A601A6842F480621A6008BD2E2D002004 +:101E1000003C02400B28F0B516D80C4C0C49237836 +:101E20007BB90C4D0E460C234FF0006255F8047B35 +:101E300046F8042B013B13F0FF033A44F6D101238B +:101E4000237051F82000F0BD0020FCE7602D002039 +:101E5000302D002014360008014B53F82000704745 +:101E6000143600080C2070470B2810B5044601D921 +:101E7000002010BDFFF7CEFF064B53F82430184466 +:101E8000C21A0BB90120F4E712680132F0D1043B09 +:101E9000F6E700BF143600080B2810B5044621D819 +:101EA000FFF778FFFFF780FF0F4AF323D360C300EB +:101EB000DBB243F4007343F002031361136943F48C +:101EC00080331361FFF766FFFFF7A4FF074B53F85A +:101ED000241000F0D9F8FFF781FF2046BDE810403C +:101EE000FFF7C2BF002010BD003C024014360008BE +:101EF000F8B512F00103144642D18218B2F1016F15 +:101F000057D82D4B1B6813F0010352D02B4DFFF710 +:101F10004BFFF323EB60FFF73DFF40F20127032C5B +:101F200015D824F001046618244C401A40F2011719 +:101F3000B142236900EB010524D123F001032361A1 +:101F4000FFF74CFF0120F8BD043C0430E7E78307AE +:101F5000E7D12B6923F440732B612B693B432B6141 +:101F600051F8046B0660BFF34F8FFFF713FF036850 +:101F70009E42E9D02B6923F001032B61FFF72EFF6E +:101F80000020E0E723F44073236123693B4323618E +:101F90000B882B80BFF34F8FFFF7FCFE2D8831F8A5 +:101FA000023BADB2AB42C3D0236923F001032361EE +:101FB000E4E71846C7E700BF00380240003C024093 +:101FC000084908B50B7828B11BB9FFF7EDFE0123CE +:101FD0000B7008BD002BFCD0BDE808400870FFF76F +:101FE000FDBE00BF2E2D002010B50244064BD2B21C +:101FF000904200D110BD441C00B253F8200041F8BB +:10200000040BE0B2F4E700BF502800400F4B30B59E +:102010001C6F240407D41C6F44F400741C671C6FED +:1020200044F400441C670A4C236843F48073236023 +:102030000244084BD2B2904200D130BD441C00B2E1 +:1020400051F8045B43F82050E0B2F4E70038024056 +:10205000007000405028004007B5012201A900206F +:10206000FFF7C2FF019803B05DF804FB13B5044607 +:10207000FFF7F2FFA04205D0012201A90020019440 +:10208000FFF7C4FF02B010BD70470000034B1A6891 +:102090001AB9034AD2F874281A607047642D0020D8 +:1020A0000030024008B5FFF7F1FF024B1868C0F39B +:1020B000407008BD642D002070470000FEE700005E +:1020C0000A4B0B480B4A90420BD30B4BDA1C121AEB +:1020D000C11E22F003028B4238BF00220021FEF70E +:1020E000F7BD53F8041B40F8041BECE7C0370008A9 +:1020F000602E0020602E0020602E002070B5D0E9F8 +:1021000015439E6800224FF0FF3504EB4213510146 +:10211000D3F800090028BEBFD3F8000940F0804082 +:10212000C3F80009D3F8000B0028BEBFD3F8000B9A +:1021300040F08040C3F8000B013263189642C3F8A8 +:102140000859C3F8085BE0D24FF00113C4F81C38FB +:1021500070BD0000890141F02001016103699B0607 +:10216000FCD41220FFF716BB10B5054C2046FEF735 +:10217000E5FF4FF0A0436365024BA36510BD00BFB0 +:10218000682D00206836000870B50378012B0546DD +:1021900050D12A4B446D98421BD1294B5A6B42F0C7 +:1021A00080025A635A6D42F080025A655A6D5A692C +:1021B00042F080025A615A6922F080025A610E216F +:1021C00043205B6900F022FC1E4BE3601E4BC4F809 +:1021D00000380023C4F8003EC02323606E6D4FF426 +:1021E0000413A3633369002BFCDA012333610C2051 +:1021F000FFF7D0FA3369DB07FCD41220FFF7CAFAE5 +:102200003369002BFCDA0026A6602846FFF776FF2C +:102210006B68C4F81068DB68C4F81468C4F81C68FC +:102220004BB90A4BA3614FF0FF336361A36843F0DE +:102230000103A36070BD064BF4E700BF682D0020CA +:10224000003802404014004003002002003C30C02F +:10225000083C30C0F8B5446D054600212046FFF724 +:1022600079FFA96D00234FF001128F68C4F834384C +:102270004FF00066C4F81C284FF0FF3004EB431207 +:1022800001339F42C2F80069C2F8006BC2F8080926 +:10229000C2F8080BF2D20B686A6DEB65636210231B +:1022A0001361166916F01006FBD11220FFF772FABF +:1022B000D4F8003823F4FE63C4F80038A36943F46B +:1022C000402343F01003A3610923C4F81038C4F875 +:1022D00014380A4BEB604FF0C043C4F8103B084B76 +:1022E000C4F8003BC4F81069C4F80039EB6D03F181 +:1022F000100243F48013EA65A362F8BD4436000877 +:1023000040800010426D90F84E10D2F8003823F44F +:10231000FE6343EA0113C2F8003870472DE9F84321 +:1023200000EB8103456DDA68166806F00306731E3C +:10233000022B05EB41130C4680460FFA81F94FEA58 +:1023400041104FF00001C3F8101B4FF0010104F1E0 +:10235000100398BFB60401FA03F391698EBF334EA0 +:1023600006F1805606F5004600293AD0578A04F156 +:102370005801490137436F50D5F81C180B43C5F875 +:102380001C382B180021C3F8101953690127611E4E +:10239000A7409BB3138A928B9B08012A88BF5343A3 +:1023A000D8F85C20981842EA034301F1400205EB9B +:1023B0008202C8F85C00214653602846FFF7CAFE37 +:1023C00008EB8900C3681B8A43EA845348346401DC +:1023D0001E432E51D5F81C381F43C5F81C78BDE8A4 +:1023E000F88305EB4917D7F8001B21F40041C7F823 +:1023F000001BD5F81C1821EA0303C0E704F13F03D2 +:1024000005EB83030A4A5A6028462146FFF7A2FEDD +:1024100005EB4910D0F8003923F40043C0F8003927 +:10242000D5F81C3823EA0707D7E700BF0080001063 +:1024300000040002826D1268C265FFF75FBE0000F3 +:102440005831436D49015B5813F4004004D013F434 +:10245000001F0CBF02200120704700004831436D6F +:1024600049015B5813F4004004D013F4001F0CBF63 +:10247000022001207047000000EB8101CB68196A3F +:102480000B6813604B6853607047000000EB8103DA +:1024900030B5DD68AA691368D36019B9402B84BFD1 +:1024A000402313606B8A1468426D1C44013CB4FBEA +:1024B000F3F46343033323F0030302EB411043EAD5 +:1024C000C44343F0C043C0F8103B2B6803F0030340 +:1024D000012B09B20ED1D2F8083802EB411013F4E7 +:1024E000807FD0F8003B14BF43F0805343F000538B +:1024F000C0F8003B02EB4112D2F8003B43F004432A +:10250000C2F8003B30BD00002DE9F041244D6E6D56 +:1025100006EB40130446D3F8087BC3F8087B380762 +:102520000AD5D6F81438190706D505EB84032146D9 +:10253000DB6828465B689847FA071FD5D6F8143839 +:10254000DB071BD505EB8403D968CCB98B69488AB6 +:102550005A68B2FBF0F600FB16228AB91868DA68EE +:1025600090420DD2121AC3E90024302383F311885C +:102570000B482146FFF78AFF84F31188BDE8F081FC +:10258000012303FA04F26B8923EA02036B81CB680F +:10259000002BF3D021460248BDE8F041184700BFA8 +:1025A000682D002000EB810370B5DD68436D6C6918 +:1025B0002668E6604A0156BB1A444FF40020C2F870 +:1025C00010092A6802F00302012A0AB20ED1D3F8D8 +:1025D000080803EB421410F4807FD4F8000914BFFC +:1025E00040F0805040F00050C4F8000903EB421264 +:1025F000D2F8000940F00440C2F80009D3F83408CA +:10260000012202FA01F10143C3F8341870BD19B96F +:10261000402E84BF4020206020682E8A8419013C0F +:10262000B4FBF6F440EAC44040F000501A44C6E758 +:102630002DE9F8433B4D6E6D06EB40130446D3F88D +:102640000889C3F8088918F0010F4FEA40171AD01B +:10265000D6F81038DB0716D505EB8003D9684B692F +:102660001868DA68904230D2121A4FF000091A60E6 +:10267000C3F80490302383F3118821462846FFF7DE +:1026800091FF89F3118818F0800F1CD0D6F83438E8 +:102690000126A640334216D005EB84036D6DD3F8B6 +:1026A0000CC0DCF814200134E4B2D2F800E005EBF1 +:1026B00004342F445168714515D3D5F8343823EAD2 +:1026C0000606C5F83468BDE8F883012303FA04F26E +:1026D0002B8923EA02032B818B68002BD3D0214660 +:1026E00028469847CFE7BCF81000AEEB01038342C1 +:1026F00028BF0346D7F8180980B2B3EB800FE2D8A1 +:102700009068A0F1040959F8048FC4F80080A0EB88 +:1027100009089844B8F1040FF5D818440B449060A8 +:102720005360C7E7682D00202DE9F74FA24C656D77 +:102730006E69AB691E4016F480586E6107D0204662 +:10274000FEF764FD03B0BDE8F04F00F047BC002E7B +:1027500012DAD5F8003E98489B071EBFD5F8003E18 +:1027600023F00303C5F8003ED5F8043823F0010335 +:10277000C5F80438FEF774FD370505D58E48FFF718 +:10278000BDFC8D48FEF75AFDB0040CD5D5F80838CD +:1027900013F0060FEB6823F470530CBF43F410538F +:1027A00043F4A053EB6031071BD56368DB681BB9AA +:1027B000AB6923F00803AB612378052B0CD1D5F866 +:1027C000003E7D489A071EBFD5F8003E23F0030364 +:1027D000C5F8003EFEF744FD6368DB680BB1764840 +:1027E0009847F30274D4B70227D5D4F85490DFF891 +:1027F000C8B100274FF0010A09EB4712D2F8003B9D +:1028000003F44023B3F5802F11D1D2F8003B002B05 +:102810000DDA62890AFA07F322EA0303638104EB03 +:102820008703DB68DB6813B1394658469847A36DC8 +:1028300001379B68FFB29F42DED9F00617D5676D5E +:102840003A6AC2F30A1002F00F0302F4F012B2F572 +:10285000802F00F08580B2F5402F08D104EB830370 +:102860000022DB681B6A07F5805790426AD130036B +:10287000D5F8184813D5E10302D50020FFF744FE30 +:10288000A20302D50120FFF73FFE630302D5022019 +:10289000FFF73AFE270302D50320FFF735FE750345 +:1028A0007FF550AFE00702D50020FFF7C1FEA1077A +:1028B00002D50120FFF7BCFE620702D50220FFF718 +:1028C000B7FE23077FF53EAF0320FFF7B1FE39E7E0 +:1028D000636DDFF8E4A0019300274FF00109A36DB9 +:1028E0009B685FFA87FB9B453FF67DAF019B03EB3F +:1028F0004B13D3F8001901F44021B1F5802F1FD1FB +:10290000D3F8001900291BDAD3F8001941F09041DF +:10291000C3F80019D3F800190029FBDB5946606D94 +:10292000FFF718FC218909FA0BF321EA030323813D +:1029300004EB8B03DB689B6813B1594650469847FC +:102940000137CCE7910708BFD7F80080072A98BF66 +:1029500003F8018B02F1010298BF4FEA182884E7BF +:10296000023304EB830207F580575268D2F818C08F +:10297000DCF80820DCE9001CA1EB0C0C00218842EB +:102980000AD104EB830463689B699A6802449A60E5 +:102990005A6802445A606AE711F0030F08BFD7F87B +:1029A00000808C4588BF02F8018B01F1010188BFCE +:1029B0004FEA1828E3E700BF682D0020436D03EBC2 +:1029C0004111D1F8003B43F40013C1F8003B7047BC +:1029D000436D03EB4111D1F8003943F40013C1F802 +:1029E00000397047436D03EB4111D1F8003B23F4EC +:1029F0000013C1F8003B7047436D03EB4111D1F860 +:102A0000003923F40013C1F80039704700F1604326 +:102A100003F561430901C9B283F80013012200F0F4 +:102A20001F039A4043099B0003F1604303F5614390 +:102A3000C3F880211A60704730B5039C01720433DB +:102A400004FB0325C0E90653049B03630021059B97 +:102A5000C160C0E90000C0E90422C0E90842C0E941 +:102A60000A11436330BD0000416A0022C0E904112D +:102A7000C0E90A22C2606FF00101FEF7FBBE000050 +:102A8000D0E90432934201D1C2680AB9181D7047D7 +:102A90000020704703691960C2680132C260C269D0 +:102AA000134482690361934224BF436A0361002196 +:102AB000FEF7D4BE38B504460D46E3683BB1626903 +:102AC000131D1268A3621344E362002007E0237A17 +:102AD00033B929462046FEF7B1FE0028EDDA38BDAD +:102AE0006FF00100FBE70000C368C269013BC360EF +:102AF0004369134482694361934224BF436A43613B +:102B000000238362036B03B11847704770B530230D +:102B1000044683F31188866A3EB9FFF7CBFF05466A +:102B200018B186F31188284670BDA36AE26A13F8CB +:102B3000015BA362934202D32046FFF7D5FF002337 +:102B400083F31188EFE700002DE9F84F04460E46A5 +:102B5000174698464FF0300989F311880025AA4698 +:102B6000D4F828B0BBF1000F09D141462046FFF749 +:102B7000A1FF20B18BF311882846BDE8F88FD4E976 +:102B80000A12A7EB050B521A934528BF9346BBF1D7 +:102B9000400F1BD9334601F1400251F8040B43F8B2 +:102BA000040B9142F9D1A36A40334036A362403509 +:102BB000D4E90A239A4202D32046FFF795FF8AF30D +:102BC0001188BD42D8D289F31188C9E730465A46E8 +:102BD000FEF758F8A36A5B445E44A3625D44E7E7EE +:102BE00010B5029C0172043303FB0421C0E90613F3 +:102BF0000023C0E90A33039B0363049BC460C0E95C +:102C00000000C0E90422C0E90842436310BD00008F +:102C1000026AC260426AC0E904220022C0E90A22B4 +:102C20006FF00101FEF726BED0E904239A4201D1DC +:102C3000C26822B9184650F8043B0B607047002365 +:102C40001846FAE7C368C2690133C3604369134495 +:102C500082694361934224BF436A43610021FEF7C6 +:102C6000FDBD000038B504460D46E3683BB123695D +:102C70001A1DA262E2691344E362002007E0237A8E +:102C800033B929462046FEF7D9FD0028EDDA38BDD4 +:102C90006FF00100FBE7000003691960C268013AA8 +:102CA000C260C269134482690361934224BF436ACC +:102CB000036100238362036B03B118477047000070 +:102CC00070B530230D460446114683F31188866A99 +:102CD0002EB9FFF7C7FF10B186F3118870BDA36A44 +:102CE0001D70A36AE26A01339342A36204D3E169CF +:102CF00020460439FFF7D0FF002080F31188EDE76C +:102D00002DE9F84F04460D46904699464FF0300A9B +:102D10008AF311880026B346A76A4FB94946204670 +:102D2000FFF7A0FF20B187F311883046BDE8F88F88 +:102D3000D4E90A073A1AA8EB0607974228BF1746B4 +:102D4000402F1BD905F1400355F8042B40F8042B04 +:102D50009D42F9D1A36A4033A3624036D4E90A23E5 +:102D60009A4204D3E16920460439FFF795FF8BF3BB +:102D700011884645D9D28AF31188CDE729463A46CB +:102D8000FDF780FFA36A3B443D44A3623E44E5E770 +:102D9000D0E904239A4217D1C3689BB1836A8BB1EF +:102DA000043B9B1A0ED01360C368013BC360C36928 +:102DB0001A44836902619A4224BF436A0361002373 +:102DC00083620123184670470023FBE700F030B907 +:102DD0004FF08043586A70474FF080430022586399 +:102DE0001A610222DA6070474FF080430022DA60F5 +:102DF000704700004FF0804358637047FEE70000C3 +:102E000070B51B4B01630025044686B0586085628F +:102E10000E4600F0BFF804F11003C4E904334FF08C +:102E2000FF33C4E90635C4E90044A560E562FFF755 +:102E3000CFFF2B460246C4E9082304F134010D4AB2 +:102E4000256580232046FEF7AFFC0123E0600A4A97 +:102E50000375009272680192B268CDE90223074BB4 +:102E60006846CDE90435FEF7C7FC06B070BD00BF6B +:102E7000002600207436000879360008FD2D000871 +:102E8000024AD36A1843D062704700BF98230020DB +:102E90004B6843608B688360CB68C3600B69436198 +:102EA0004B6903628B6943620B68036070470000E3 +:102EB00008B5264B26481A6940F2FF110A431A61E9 +:102EC0001A6922F4FF7222F001021A611A691A6B60 +:102ED0000A431A631A6D0A431A651E4A1B6D11468E +:102EE000FFF7D6FF02F11C0100F58060FFF7D0FF6D +:102EF00002F1380100F58060FFF7CAFF02F15401CA +:102F000000F58060FFF7C4FF02F1700100F58060FA +:102F1000FFF7BEFF02F18C0100F58060FFF7B8FFFC +:102F200002F1A80100F58060FFF7B2FF02F1C401D1 +:102F300000F58060FFF7ACFF02F1E00100F5806072 +:102F4000FFF7A6FFBDE8084000F0EEB800380240E9 +:102F5000000002408036000808B500F059FAFEF77C +:102F600001FCFFF793F8BDE80840FEF76FBE0000D4 +:102F700070470000EFF3098305494A6B22F0010214 +:102F80004A63683383F30988002383F31188704709 +:102F900000EF00E0302080F3118862B60C4B0D4A40 +:102FA000D96821F4E0610904090C0A43DA60D3F816 +:102FB000FC20094942F08072C3F8FC200A6842F004 +:102FC00001020A602022DA7783F82200704700BFEE +:102FD00000ED00E00003FA05001000E010B530231A +:102FE00083F311880E4B5B6813F4006314D0F1EE89 +:102FF000103AEFF30984683C4FF08073E361094BAA +:10300000DB6B236684F30988FEF78CFB10B1064B5B +:10301000A36110BD054BFBE783F31188F9E700BFFF +:1030200000ED00E000EF00E02F030008320300088D +:103030000F4B1A6C42F001021A641A6E42F0010240 +:103040001A660C4A1B6E936843F0010393604FF0BD +:10305000804353229A624FF0FF32DA6200229A6173 +:103060005A63DA605A6001225A611A60704700BFE1 +:1030700000380240002004E04FF0804208B511699A +:10308000D3680B40D9B2C9439B07116107D53023E0 +:1030900083F31188FEF77CFB002383F3118808BDBE +:1030A0001F4B1A696FEAC2526FEAD2521A611A694B +:1030B000C2F308021A614FF0FF301A695A69586169 +:1030C00000215A6959615A691A6A62F080521A627B +:1030D0001A6A02F080521A621A6A5A6A58625A6A66 +:1030E00059625A6A1A6C42F080521A641A6E42F09F +:1030F00080521A661A6E0B4A106840F48070106095 +:10310000186F00F44070B0F5007F1EBF4FF48030A0 +:1031100018671967536823F40073536000F054B9BB +:103120000038024000700040334B4FF080521A6468 +:10313000324A4FF4404111601A6842F001021A60AD +:103140001A689107FCD59A6822F003029A602A4B0C +:103150009A6812F00C02FBD1196801F0F9011960AC +:103160009A601A6842F480321A601A689203FCD599 +:103170005A6F42F001025A671F4B5A6F9007FCD5F5 +:103180001F4A5A601A6842F080721A601B4A5368DC +:103190005904FCD5184B1A689201FCD5194A9A605B +:1031A000194B1A68194B9A42194B21D1194A1168C7 +:1031B000194A91421CD140F205121A60144A136850 +:1031C00003F00F03052BFAD10B4B9A6842F0020271 +:1031D0009A609A6802F00C02082AFAD15A6C42F4FA +:1031E00080425A645A6E42F480425A665B6E70475F +:1031F00040F20572E1E700BF003802400070004075 +:103200000854400700948838002004E0116400202E +:10321000003C024000ED00E041C20F41074A08B502 +:10322000536903F00103536123B1054A13680BB1DD +:1032300050689847BDE80840FFF7D0BE003C014009 +:10324000E02D0020074A08B5536903F002035361DB +:1032500023B1054A93680BB1D0689847BDE8084090 +:10326000FFF7BCBE003C0140E02D0020074A08B536 +:10327000536903F00403536123B1054A13690BB189 +:1032800050699847BDE80840FFF7A8BE003C0140E0 +:10329000E02D0020074A08B5536903F00803536185 +:1032A00023B1054A93690BB1D0699847BDE808403E +:1032B000FFF794BE003C0140E02D0020074A08B50E +:1032C000536903F01003536123B1054A136A0BB12C +:1032D000506A9847BDE80840FFF780BE003C0140B7 +:1032E000E02D0020164B10B55C6904F478725A6129 +:1032F000A30604D5134A936A0BB1D06A98476006B7 +:1033000004D5104A136B0BB1506B9847210604D5B6 +:103310000C4A936B0BB1D06B9847E20504D5094A70 +:10332000136C0BB1506C9847A30504D5054A936CF8 +:103330000BB1D06C9847BDE81040FFF74FBE00BFFF +:10334000003C0140E02D0020194B10B55C6904F4ED +:103350007C425A61620504D5164A136D0BB1506D5B +:103360009847230504D5134A936D0BB1D06D984748 +:10337000E00404D50F4A136E0BB1506E9847A104B8 +:1033800004D50C4A936E0BB1D06E9847620404D5F5 +:10339000084A136F0BB1506F9847230404D5054AB0 +:1033A000936F0BB1D06F9847BDE81040FFF716BE82 +:1033B000003C0140E02D002008B5FFF75DFEBDE8B0 +:1033C0000840FFF70BBE0000062108B50846FFF7CE +:1033D0001DFB06210720FFF719FB06210820FFF738 +:1033E00015FB06210920FFF711FB06210A20FFF734 +:1033F0000DFB06211720FFF709FB06212820FFF708 +:1034000005FBBDE8084007211C20FFF7FFBA0000BC +:1034100008B5FFF745FE00F00BF8FDF78DFEFDF750 +:1034200065FDFFF7A5FDBDE80840FFF7CFBC000034 +:103430000023054A19460133102BC2E9001102F19D +:103440000802F8D1704700BFE02D0020034611F8B4 +:10345000012B03F8012B002AF9D1704753544D3347 +:1034600032463F3F3F0053544D33324634307800AC +:1034700053544D3332463432780053544D33324630 +:103480003434365858000000012033000010410049 +:1034900001105A000310590007103100000000000D +:1034A0005C340008130400006634000819040000AE +:1034B00070340008210400007A3400080000000085 +:1034C000690E0008550E0008910E00087D0E0008D8 +:1034D000890E0008750E0008610E00084D0E0008E8 +:1034E0009D0E000800000000010000000000000028 +:1034F00063300000F0340008F02300200026002094 +:103500004172647550696C6F740025424F4152449A +:10351000252D424C002553455249414C25000000C1 +:10352000020000000000000085100008F1100008F3 +:1035300040004000A02A0020B02A00200200000025 +:10354000000000000300000000000000351100082A +:103550000000000010000000C02A00200000000051 +:103560000100000000000000682D002001010200A1 +:10357000E91B0008F91A0008951B0008791B0008D0 +:10358000430000008835000809024300020100C022 +:1035900032090400000102020100052400100105A7 +:1035A000240100010424020205240600010705820B +:1035B000030800FF09040100020A000000070501DA +:1035C00002400000070581024000000012000000D8 +:1035D000D4350008120110010200004009124157C1 +:1035E00000020102030100000403090425424F41C7 +:1035F000524425007370656564796265656634764A +:10360000340030313233343536373839414243446F +:10361000454600000040000000400000004000005F +:103620000040000000000100000002000000020055 +:103630000000020000000200000002000000020082 +:103640000000020000000000791200083115000897 +:10365000DD15000840004000C82D0020C82D0020C6 +:1036600001000000D82D0020800000004001000073 +:10367000030000006D61696E0069646C6500000004 +:103680000001812A00000000AAAAAAAA00010024C1 +:10369000FFFE00000000000000A00A000000000182 +:1036A00000000000AAAAAAAA00000001FFFF000073 +:1036B00000000000000000000000001000000000FA +:1036C000AAAAAAAA00000010FFFF00000000000044 +:1036D000000000000000000000000000AAAAAAAA42 +:1036E00000000000FFFF00000000000000000000DC +:1036F0000000000000000000AAAAAAAA0000000022 +:10370000FFFF0000000000000000000000000000BB +:1037100000000000AAAAAAAA00000000FFFF000003 +:103720000000000000000000000000000000000099 +:10373000AAAAAAAA00000000FFFF000000000000E3 +:103740000000000000000000000000000A0000006F +:103750000000000003000000000000000000000066 +:103760000000000000000000000000000000000059 +:103770000000000000000000000000000000000049 +:10378000700400000000000000400F000000000076 +:10379000FF009600000000080096000000000800EE +:1037A00004000000E83500080000000000000000F0 +:1037B0000000000000000000000000000000000009 +:00000001FF From 26e6a11ba39ce724c72dc7471f2bb3f1ec7b100c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 9 Sep 2023 19:53:57 +1000 Subject: [PATCH 042/499] AP_RangeFinder: remove more code based on defines --- libraries/AP_RangeFinder/AP_RangeFinder.cpp | 160 +++++++++--------- libraries/AP_RangeFinder/AP_RangeFinder.h | 76 +++++++++ .../AP_RangeFinder_USD1_Serial.h | 10 +- .../AP_RangeFinder/AP_RangeFinder_config.h | 4 + 4 files changed, 168 insertions(+), 82 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 425ae116d7562e..5636656604b352 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -26,6 +26,8 @@ defined(HAVE_LIBIIO) #include "AP_RangeFinder_Bebop.h" #endif +#include "AP_RangeFinder_Backend.h" +#include "AP_RangeFinder_Backend_Serial.h" #include "AP_RangeFinder_MAVLink.h" #include "AP_RangeFinder_LeddarOne.h" #include "AP_RangeFinder_USD1_Serial.h" @@ -271,20 +273,20 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) const Type _type = (Type)params[instance].type.get(); switch (_type) { +#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED case Type::PLI2C: case Type::PLI2CV3: case Type::PLI2CV3HP: -#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED FOREACH_I2C(i) { if (_add_backend(AP_RangeFinder_PulsedLightLRF::detect(i, state[instance], params[instance], _type), instance)) { break; } } -#endif break; - case Type::MBI2C: { +#endif #if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED + case Type::MBI2C: { uint8_t addr = AP_RANGE_FINDER_MAXSONARI2CXL_DEFAULT_ADDR; if (params[instance].address != 0) { addr = params[instance].address; @@ -297,10 +299,10 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) } } break; -#endif } - case Type::LWI2C: +#endif #if AP_RANGEFINDER_LWI2C_ENABLED + case Type::LWI2C: if (params[instance].address) { // the LW20 needs a long time to boot up, so we delay 1.5s here #ifndef HAL_BUILD_AP_PERIPH @@ -322,10 +324,10 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) } #endif } -#endif // AP_RANGEFINDER_LWI2C_ENABLED break; - case Type::TRI2C: +#endif // AP_RANGEFINDER_LWI2C_ENABLED #if AP_RANGEFINDER_TRI2C_ENABLED + case Type::TRI2C: if (params[instance].address) { FOREACH_I2C(i) { if (_add_backend(AP_RangeFinder_TeraRangerI2C::detect(state[instance], params[instance], @@ -335,8 +337,8 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) } } } -#endif break; +#endif case Type::VL53L0X: case Type::VL53L1X_Short: FOREACH_I2C(i) { @@ -358,8 +360,8 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) #endif } break; - case Type::BenewakeTFminiPlus: { #if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED + case Type::BenewakeTFminiPlus: { uint8_t addr = TFMINIPLUS_ADDR_DEFAULT; if (params[instance].address != 0) { addr = params[instance].address; @@ -372,193 +374,193 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) } } break; -#endif } - case Type::PX4_PWM: +#endif #if AP_RANGEFINDER_PWM_ENABLED + case Type::PX4_PWM: // to ease moving from PX4 to ChibiOS we'll lie a little about // the backend driver... if (AP_RangeFinder_PWM::detect()) { _add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); } -#endif break; - case Type::BBB_PRU: +#endif #if AP_RANGEFINDER_BBB_PRU_ENABLED + case Type::BBB_PRU: if (AP_RangeFinder_BBB_PRU::detect()) { _add_backend(new AP_RangeFinder_BBB_PRU(state[instance], params[instance]), instance); } -#endif break; - case Type::LWSER: +#endif #if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED + case Type::LWSER: serial_create_fn = AP_RangeFinder_LightWareSerial::create; -#endif break; - case Type::LEDDARONE: +#endif #if AP_RANGEFINDER_LEDDARONE_ENABLED + case Type::LEDDARONE: serial_create_fn = AP_RangeFinder_LeddarOne::create; -#endif break; - case Type::USD1_Serial: +#endif #if AP_RANGEFINDER_USD1_SERIAL_ENABLED + case Type::USD1_Serial: serial_create_fn = AP_RangeFinder_USD1_Serial::create; -#endif break; - case Type::BEBOP: +#endif #if AP_RANGEFINDER_BEBOP_ENABLED + case Type::BEBOP: if (AP_RangeFinder_Bebop::detect()) { _add_backend(new AP_RangeFinder_Bebop(state[instance], params[instance]), instance); } -#endif break; - case Type::MAVLink: +#endif #if AP_RANGEFINDER_MAVLINK_ENABLED + case Type::MAVLink: if (AP_RangeFinder_MAVLink::detect()) { _add_backend(new AP_RangeFinder_MAVLink(state[instance], params[instance]), instance); } -#endif break; - case Type::MBSER: +#endif #if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED + case Type::MBSER: serial_create_fn = AP_RangeFinder_MaxsonarSerialLV::create; -#endif break; - case Type::ANALOG: +#endif #if AP_RANGEFINDER_ANALOG_ENABLED + case Type::ANALOG: // note that analog will always come back as present if the pin is valid if (AP_RangeFinder_analog::detect(params[instance])) { _add_backend(new AP_RangeFinder_analog(state[instance], params[instance]), instance); } -#endif break; - case Type::HC_SR04: +#endif #if AP_RANGEFINDER_HC_SR04_ENABLED + case Type::HC_SR04: // note that this will always come back as present if the pin is valid if (AP_RangeFinder_HC_SR04::detect(params[instance])) { _add_backend(new AP_RangeFinder_HC_SR04(state[instance], params[instance]), instance); } -#endif break; - case Type::NMEA: +#endif #if AP_RANGEFINDER_NMEA_ENABLED + case Type::NMEA: serial_create_fn = AP_RangeFinder_NMEA::create; -#endif break; - case Type::WASP: +#endif #if AP_RANGEFINDER_WASP_ENABLED + case Type::WASP: serial_create_fn = AP_RangeFinder_Wasp::create; -#endif break; - case Type::BenewakeTF02: +#endif #if AP_RANGEFINDER_BENEWAKE_TF02_ENABLED + case Type::BenewakeTF02: serial_create_fn = AP_RangeFinder_Benewake_TF02::create; -#endif break; - case Type::BenewakeTFmini: +#endif #if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED + case Type::BenewakeTFmini: serial_create_fn = AP_RangeFinder_Benewake_TFMini::create; -#endif break; - case Type::BenewakeTF03: +#endif #if AP_RANGEFINDER_BENEWAKE_TF03_ENABLED + case Type::BenewakeTF03: serial_create_fn = AP_RangeFinder_Benewake_TF03::create; -#endif break; - case Type::TeraRanger_Serial: +#endif #if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED + case Type::TeraRanger_Serial: serial_create_fn = AP_RangeFinder_TeraRanger_Serial::create; -#endif break; - case Type::PWM: +#endif #if AP_RANGEFINDER_PWM_ENABLED + case Type::PWM: if (AP_RangeFinder_PWM::detect()) { _add_backend(new AP_RangeFinder_PWM(state[instance], params[instance], estimated_terrain_height), instance); } -#endif break; - case Type::BLPing: +#endif #if AP_RANGEFINDER_BLPING_ENABLED + case Type::BLPing: serial_create_fn = AP_RangeFinder_BLPing::create; -#endif break; - case Type::Lanbao: +#endif #if AP_RANGEFINDER_LANBAO_ENABLED + case Type::Lanbao: serial_create_fn = AP_RangeFinder_Lanbao::create; -#endif break; - case Type::LeddarVu8_Serial: +#endif #if AP_RANGEFINDER_LEDDARVU8_ENABLED + case Type::LeddarVu8_Serial: serial_create_fn = AP_RangeFinder_LeddarVu8::create; -#endif break; +#endif - case Type::UAVCAN: #if AP_RANGEFINDER_DRONECAN_ENABLED + case Type::UAVCAN: /* the UAVCAN driver gets created when we first receive a measurement. We take the instance slot now, even if we don't yet have the driver */ num_instances = MAX(num_instances, instance+1); -#endif break; +#endif - case Type::GYUS42v2: #if AP_RANGEFINDER_GYUS42V2_ENABLED + case Type::GYUS42v2: serial_create_fn = AP_RangeFinder_GYUS42v2::create; -#endif break; +#endif - case Type::SIM: #if AP_RANGEFINDER_SIM_ENABLED + case Type::SIM: _add_backend(new AP_RangeFinder_SITL(state[instance], params[instance], instance), instance); -#endif break; +#endif - case Type::MSP: #if HAL_MSP_RANGEFINDER_ENABLED + case Type::MSP: if (AP_RangeFinder_MSP::detect()) { _add_backend(new AP_RangeFinder_MSP(state[instance], params[instance]), instance); } -#endif // HAL_MSP_RANGEFINDER_ENABLED break; +#endif // HAL_MSP_RANGEFINDER_ENABLED - case Type::USD1_CAN: #if AP_RANGEFINDER_USD1_CAN_ENABLED + case Type::USD1_CAN: _add_backend(new AP_RangeFinder_USD1_CAN(state[instance], params[instance]), instance); -#endif break; - case Type::Benewake_CAN: +#endif #if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED + case Type::Benewake_CAN: _add_backend(new AP_RangeFinder_Benewake_CAN(state[instance], params[instance]), instance); -#endif break; +#endif - case Type::Lua_Scripting: #if AP_RANGEFINDER_LUA_ENABLED + case Type::Lua_Scripting: _add_backend(new AP_RangeFinder_Lua(state[instance], params[instance]), instance); -#endif break; +#endif - case Type::NoopLoop_P: #if AP_RANGEFINDER_NOOPLOOP_ENABLED + case Type::NoopLoop_P: serial_create_fn = AP_RangeFinder_NoopLoop::create; -#endif break; +#endif - case Type::TOFSenseP_CAN: #if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED + case Type::TOFSenseP_CAN: _add_backend(new AP_RangeFinder_TOFSenseP_CAN(state[instance], params[instance]), instance); -#endif break; - case Type::NRA24_CAN: +#endif #if AP_RANGEFINDER_NRA24_CAN_ENABLED + case Type::NRA24_CAN: _add_backend(new AP_RangeFinder_NRA24_CAN(state[instance], params[instance]), instance); -#endif break; - case Type::TOFSenseF_I2C: { +#endif #if AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED + case Type::TOFSenseF_I2C: { uint8_t addr = TOFSENSEP_I2C_DEFAULT_ADDR; if (params[instance].address != 0) { addr = params[instance].address; @@ -571,9 +573,8 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) } } break; -#endif } - +#endif case Type::NONE: break; } @@ -816,19 +817,26 @@ bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_le // backend-specific checks. This might end up drivers[i]->arming_checks(...). switch (drivers[i]->allocated_type()) { -#if AP_RANGEFINDER_PWM_ENABLED || AP_RANGEFINDER_ANALOG_ENABLED +#if AP_RANGEFINDER_ANALOG_ENABLED || AP_RANGEFINDER_PWM_ENABLED +#if AP_RANGEFINDER_ANALOG_ENABLED case Type::ANALOG: +#endif +#if AP_RANGEFINDER_PWM_ENABLED case Type::PX4_PWM: - case Type::PWM: { + case Type::PWM: +#endif + { // ensure pin is configured if (params[i].pin == -1) { hal.util->snprintf(failure_msg, failure_msg_len, "RNGFND%u_PIN not set", unsigned(i + 1)); return false; } +#if AP_RANGEFINDER_ANALOG_ENABLED if (drivers[i]->allocated_type() == Type::ANALOG) { // Analog backend does not use GPIO pin break; } +#endif // ensure that the pin we're configured to use is available if (!hal.gpio->valid_pin(params[i].pin)) { @@ -842,7 +850,7 @@ bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_le } break; } -#endif +#endif // AP_RANGEFINDER_ANALOG_ENABLED || AP_RANGEFINDER_PWM_ENABLED #if AP_RANGEFINDER_NRA24_CAN_ENABLED case Type::NRA24_CAN: { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index 6ffda40ff9f130..1f3353656708da 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -57,47 +57,123 @@ class RangeFinder // RangeFinder driver types enum class Type { NONE = 0, +#if AP_RANGEFINDER_ANALOG_ENABLED ANALOG = 1, +#endif +#if AP_RANGEFINDER_MAXSONARI2CXL_ENABLED MBI2C = 2, +#endif +#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED PLI2C = 3, +#endif // PX4 = 4, // no longer used, but may be in some user's parameters +#if AP_RANGEFINDER_PWM_ENABLED PX4_PWM= 5, +#endif +#if AP_RANGEFINDER_BBB_PRU_ENABLED BBB_PRU= 6, +#endif +#if AP_RANGEFINDER_LWI2C_ENABLED LWI2C = 7, +#endif +#if AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED LWSER = 8, +#endif +#if AP_RANGEFINDER_BEBOP_ENABLED BEBOP = 9, +#endif +#if AP_RANGEFINDER_MAVLINK_ENABLED MAVLink = 10, +#endif +#if AP_RANGEFINDER_USD1_SERIAL_ENABLED USD1_Serial = 11, +#endif +#if AP_RANGEFINDER_LEDDARONE_ENABLED LEDDARONE = 12, +#endif +#if AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED MBSER = 13, +#endif +#if AP_RANGEFINDER_TRI2C_ENABLED TRI2C = 14, +#endif +#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED PLI2CV3= 15, +#endif VL53L0X = 16, +#if AP_RANGEFINDER_NMEA_ENABLED NMEA = 17, +#endif +#if AP_RANGEFINDER_WASP_ENABLED WASP = 18, +#endif +#if AP_RANGEFINDER_BENEWAKE_TF02_ENABLED BenewakeTF02 = 19, +#endif +#if AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED BenewakeTFmini = 20, +#endif +#if AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED PLI2CV3HP = 21, +#endif +#if AP_RANGEFINDER_PWM_ENABLED PWM = 22, +#endif +#if AP_RANGEFINDER_BLPING_ENABLED BLPing = 23, +#endif +#if AP_RANGEFINDER_DRONECAN_ENABLED UAVCAN = 24, +#endif +#if AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED BenewakeTFminiPlus = 25, +#endif +#if AP_RANGEFINDER_LANBAO_ENABLED Lanbao = 26, +#endif +#if AP_RANGEFINDER_BENEWAKE_TF03_ENABLED BenewakeTF03 = 27, +#endif VL53L1X_Short = 28, +#if AP_RANGEFINDER_LEDDARVU8_ENABLED LeddarVu8_Serial = 29, +#endif +#if AP_RANGEFINDER_HC_SR04_ENABLED HC_SR04 = 30, +#endif +#if AP_RANGEFINDER_GYUS42V2_ENABLED GYUS42v2 = 31, +#endif +#if HAL_MSP_RANGEFINDER_ENABLED MSP = 32, +#endif +#if AP_RANGEFINDER_USD1_CAN_ENABLED USD1_CAN = 33, +#endif +#if AP_RANGEFINDER_BENEWAKE_CAN_ENABLED Benewake_CAN = 34, +#endif +#if AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED TeraRanger_Serial = 35, +#endif +#if AP_RANGEFINDER_LUA_ENABLED Lua_Scripting = 36, +#endif +#if AP_RANGEFINDER_NOOPLOOP_ENABLED NoopLoop_P = 37, +#endif +#if AP_RANGEFINDER_TOFSENSEP_CAN_ENABLED TOFSenseP_CAN = 38, +#endif +#if AP_RANGEFINDER_NRA24_CAN_ENABLED NRA24_CAN = 39, +#endif +#if AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED TOFSenseF_I2C = 40, +#endif +#if AP_RANGEFINDER_SIM_ENABLED SIM = 100, +#endif }; enum class Function { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h index 7fa2d2642c015f..3c48c38628f4b2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.h @@ -1,14 +1,12 @@ #pragma once -#include "AP_RangeFinder.h" -#include "AP_RangeFinder_Backend_Serial.h" - -#ifndef AP_RANGEFINDER_USD1_SERIAL_ENABLED -#define AP_RANGEFINDER_USD1_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED -#endif +#include "AP_RangeFinder_config.h" #if AP_RANGEFINDER_USD1_SERIAL_ENABLED +#include "AP_RangeFinder.h" +#include "AP_RangeFinder_Backend_Serial.h" + class AP_RangeFinder_USD1_Serial : public AP_RangeFinder_Backend_Serial { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_config.h b/libraries/AP_RangeFinder/AP_RangeFinder_config.h index d3dee401d720e9..0800cadd3eae8a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_config.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_config.h @@ -157,6 +157,10 @@ #define AP_RANGEFINDER_USD1_CAN_ENABLED (HAL_MAX_CAN_PROTOCOL_DRIVERS && AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED) #endif +#ifndef AP_RANGEFINDER_USD1_SERIAL_ENABLED +#define AP_RANGEFINDER_USD1_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED +#endif + #ifndef AP_RANGEFINDER_VL53L0X_ENABLED #define AP_RANGEFINDER_VL53L0X_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED #endif From e162e74c0cfcd5929d50441b5b05898243897246 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 13:37:52 +1100 Subject: [PATCH 043/499] GCS_MAVLink: allow MAV_CMD_RUN_PREARMS as both long and int --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 9 ++++----- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 8a863fff42a552..a505f760b9c49e 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -628,7 +628,7 @@ class GCS_MAVLINK bool telemetry_delayed() const; virtual uint32_t telem_delay() const = 0; - MAV_RESULT handle_command_run_prearm_checks(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_run_prearm_checks(const mavlink_command_int_t &packet); MAV_RESULT handle_command_flash_bootloader(const mavlink_command_int_t &packet); // generally this should not be overridden; Plane overrides it to ensure diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index fb46ac9bc06ee6..d5c407ed2fa873 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4435,7 +4435,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_preflight_calibration(const mavlink_comma return _handle_command_preflight_calibration(packet, msg); } -MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_int_t &packet) { if (hal.util->get_soft_armed()) { return MAV_RESULT_TEMPORARILY_REJECTED; @@ -4780,10 +4780,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t break; #endif - case MAV_CMD_RUN_PREARM_CHECKS: - result = handle_command_run_prearm_checks(packet); - break; - default: result = try_command_long_as_command_int(packet, msg); break; @@ -5148,6 +5144,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p return handle_servorelay_message(packet); #endif + case MAV_CMD_RUN_PREARM_CHECKS: + return handle_command_run_prearm_checks(packet); + #if AP_SCRIPTING_ENABLED case MAV_CMD_SCRIPTING: { From 6439528d6aa453e816bc60cf930bf69929924c3d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 13:44:21 +1100 Subject: [PATCH 044/499] autotest: augment tests for running the prearm checks --- Tools/autotest/arduplane.py | 21 +++++++++++---------- Tools/autotest/vehicle_test_suite.py | 3 --- 2 files changed, 11 insertions(+), 13 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 50cac72819507d..a580e70d5e7af4 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -191,16 +191,17 @@ def NeedEKFToArm(self): self.context_collect("STATUSTEXT") tstart = self.get_sim_time() success = False - while not success: - if self.get_sim_time_cached() - tstart > 60: - raise NotAchievedException("Did not get correct failure reason") - self.run_cmd_run_prearms() - try: - self.wait_statustext(".*AHRS: not using configured AHRS type.*", timeout=1, check_context=True, regex=True) - success = True - continue - except AutoTestTimeoutException: - pass + for run_cmd in self.run_cmd, self.run_cmd_int: + while not success: + if self.get_sim_time_cached() - tstart > 60: + raise NotAchievedException("Did not get correct failure reason") + run_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS) + try: + self.wait_statustext(".*AHRS: not using configured AHRS type.*", timeout=1, check_context=True, regex=True) + success = True + continue + except AutoTestTimeoutException: + pass self.set_parameter("SIM_GPS_DISABLE", 0) self.wait_ready_to_arm() diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 427ebb5bb6103e..41289802504939 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -1898,9 +1898,6 @@ def run_cmd_reboot(self): p1=1, # reboot autopilot ) - def run_cmd_run_prearms(self): - self.run_cmd(mavutil.mavlink.MAV_CMD_RUN_PREARM_CHECKS) - def run_cmd_enable_high_latency(self, new_state, run_cmd=None): if run_cmd is None: run_cmd = self.run_cmd From 40cdb5d01e8c97740061165d04843f8b5e3b590d Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Tue, 31 Oct 2023 20:37:31 -0300 Subject: [PATCH 045/499] Autotest: improve flapping Sub test --- Tools/autotest/ardusub.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index fcc622ddfba76f..d416d8efcaf75b 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -457,6 +457,7 @@ def MAV_CMD_MISSION_START(self): def MAV_CMD_DO_CHANGE_SPEED(self): '''ensure vehicle changes speeds when DO_CHANGE_SPEED received''' items = [ + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 0, 0, -3), # Dive so we have constrat drag (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, -1), (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), ] @@ -465,6 +466,8 @@ def MAV_CMD_DO_CHANGE_SPEED(self): self.arm_vehicle() self.run_cmd(mavutil.mavlink.MAV_CMD_MISSION_START) self.progress("SENT MISSION START") + self.wait_mode('AUTO') + self.wait_current_waypoint(2) # wait after we finish diving to 3m for run_cmd in self.run_cmd, self.run_cmd_int: for speed in [1, 1.5, 0.5]: run_cmd(mavutil.mavlink.MAV_CMD_DO_CHANGE_SPEED, p2=speed) From 37109e649e98d6628d263024155428f91c19af40 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 24 Oct 2023 20:53:08 +1100 Subject: [PATCH 046/499] AP_ADSB: create an enum class for logging --- libraries/AP_ADSB/AP_ADSB.cpp | 8 ++++---- libraries/AP_ADSB/AP_ADSB.h | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 9d82e541a4f928..9c3e9dcee58bb7 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -828,17 +828,17 @@ bool AP_ADSB::get_vehicle_by_ICAO(const uint32_t icao, adsb_vehicle_t &vehicle) */ void AP_ADSB::write_log(const adsb_vehicle_t &vehicle) const { - switch (_log) { - case logging::SPECIAL_ONLY: + switch ((Logging)_log) { + case Logging::SPECIAL_ONLY: if (!is_special_vehicle(vehicle.info.ICAO_address)) { return; } break; - case logging::ALL: + case Logging::ALL: break; - case logging::NONE: + case Logging::NONE: default: return; } diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index f9210a559a6b6d..91ecee728c109b 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -288,13 +288,13 @@ class AP_ADSB { void push_sample(const adsb_vehicle_t &vehicle); // logging - AP_Int8 _log; void write_log(const adsb_vehicle_t &vehicle) const; - enum logging { + enum class Logging { NONE = 0, SPECIAL_ONLY = 1, ALL = 2 }; + AP_Enum _log; // reference to backend AP_ADSB_Backend *_backend[ADSB_MAX_INSTANCES]; From 5bd5aa87a728ebae468e3c3247467d8971a5d6fa Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 1 Nov 2023 16:29:58 +1100 Subject: [PATCH 047/499] AP_HAL_ChibiOS: add CubeNode pinout diagram --- .../hwdef/CubePilot-CANMod/CubeNode_PinOut.pdf | Bin 0 -> 160345 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/CubeNode_PinOut.pdf diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/CubeNode_PinOut.pdf b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/CubeNode_PinOut.pdf new file mode 100755 index 0000000000000000000000000000000000000000..212c08ffd844b7d980d6a8478f85f76e72fdfb85 GIT binary patch literal 160345 zcmb?k2|QHa+aHt`+E=a9B2<`tMpQ(LB_wTVw`Ym8r&Pc8g(O-OEz*X6Wl2h#6iWMo zD734z@990~+!=G{&T;3``@WywKaQDup65B=^PJ~A-{+jG>u5E?kZUAp(OmcTvs)iq zG#B%EYz{kchHs1JW@g5g!5-5?0)yH57JeZ!W0z85ZS~MsA<`WoTH9f?G zt#37m$KmlgCR_;z{U7{wbQqA3L8JY`)O~_!o=0A>Qz@j@~|gKC{_Q zf%E5hz;v2$nmddv)A>%(7cJr>Rn40fL*6A82p8PcM; zM}Rw$nM)GhdEsmiwz1=MFONC!i$35>t}U8F^_*HXpA4ET1Lp>Wu(^s)5c7rdXMnE< z2hJSp5yEyg1{$!9ojn$Wu;F)yF9;bqHUz2;%rw%$LQ&EX0gTa`LY)Kz+nIB zeryS9a}J&!FlYAkU=Pr#32cFa8;=MCznYnWpPZe!Y%yN||3ZjFRt!E?HY$W-wGx1@ z4jaujwwfM1%OgNh8Q3xXx1BjQBjBVt*o~?@V++g9l^;!x(}_ zWCSn@_}$54PT<_&nI3b1($M5UY2(q;LxO!4uw6Mu5)%Pz1pg0z1pjgcTq6?^9~pnx zut4}B&}ss{DiUzvh}d}qc!hYgC44au%6Np2UkE^+@d!UKMphm(!SE2G&ItjS2K_IH zEuHLovMhaW=!1%wWYp%K9&e>eDrOZkmz18bVG}bkxT#lF5+G1 zo?heq`)Q{Pvn9iad*)x*wI<_6oQGH9cE6Kr!vd@08V?8Ee7)>2>TFS_DRJQ(p&rPdNcXaXC zG0f(9c?+}eiGgM9s~#`;@Vm(LdCwkYzY{-SX%cw)b*X;D3r7R}-MyU!K_&?^V!J!e zI4;&r+xcUAV*6-zw=2UnHqV*9C%VY})v5V!tal&CI5hj3>wyVx4HG=W{+l|dV_C&M zwZK*G%bORCFALV2dt{Ksz(*hMPde)xXdo>48g#+!$7=}bA@`ryK5$6ud6{$@rK?y6x)oM*9j_S;v-`CIJm@U6r@EvhX4zJ0&k z1=h#!O$xBzDm1e78dJ3PvU|} zyL~5)zO%V`c$io%W%Sa!ug-2Qi*(tNG4Jl6a>ME+rw$gqP8u|R=%Nkz$%_gmy==Nt zYwPugLx1}ncrk2Q-tlK0mhCWjmg;tA;Gk9mx0h;2Oi%gszx=;rhbO$4q_(KyW1w)6 zTS4Ivtr}t8_n&j&j|I7Tr(BZKUcTA-U&f(hojO+c+~yYhJa%75$8EcXtxr#%x#Y{h z{-!^U>8>$Y7?@Cb*st%$k)3(Qx&ICFJhSk?E4M}Ooc>(zx%d6h|K0TL+%;v@<1y2( zI)6_e_x*>Tu4K@D$=v+i{zg20i-^49%5?I6f z`}f|tlxnvGu`mC^R=?O(IAQ6j5y(L94g^Nzk>_M-T9iBC|%ovU{u?T#$E z$eTa=Zgfp#_j$|LxQ}fyzyIb(FaP(t=2x{#U*Fs1afRHDWq#gUU3NWUzc3x@&pn^& zdvJ)`&5P;Y+>GYCgrz!TW3*fN%<*`2{qlg&Y^&mx#+$rXoDyAl5w~oO@ch6HgUli( zzkji$Tx>WsG-#b;KL@V5NxE_F4OipUFW+wd88hp@V&9YfKdHxwnjJs)$A4wF6XGQw zVpdn#Ha<7xYf0eHzo+l{hdwy*alT<(Mw$82(r0{=YyY*b_O)4XCwYEg=xyJJf}q_V zlOj_?H^wB1Pp(~EUe*8ST+8>S%e=Wy3hozNY1wY_^pkOaFKv6^{Lw38@y6-?HIJ8t z4~g*qIrr$^SHee*%`(51{Y`&lo!a80hw1CbH~*WT*FWy|(-w!^4su1?zk3&Yy^QF= z(tKh&@ls)vF6MitUF%fU<4lu@ZaVr&E2EmUU^(whN^0Ud*?hHieyXc+ep|;)@7_nUIF&BiACFzK)jW3R zM4uUL*)c(;EfWPJG;Ta^-Ev{xmpf4#O%CYZZ*_8)&3Or1cfyUEeJU2uFy6wu)?=Uf z&2ORV@qH3lFGuBt9jTtvi`>VB4>JbOG2M_73s}UAuGHIEWjat~2=+Ph6MrpI0 zR-amMHYO~paM1i58?~zmL(@m5_BG$@u_vg_oVe}k5zD(6J!mmMa=VBBgF*ZC`e{Vv zxQ9hbhGVNHJcecb8EXsht}n>tnHR<+TQVqRcBN9+tB6j z7iFevO`P_7@vgz4x}J|FhYje(>Hcw}+UZ;SST9Fx(7w5;-3V;YpqN1Rb?hK_A#~^Y+HqvwT*wgx8zKClocm zd1oUl(zDZ*Wn~UQCha_R*q7ei5Qdp$T5cZmw(;t}J|?lk=H{`(3`~J3q7A0oy*ty- zd8o;c^_PMWT*ol-Rsr<3ry$+b7;1 zwslXm^VE4syEQNV>|kK}sm+m;r+x2DaB5pMOUL@lw*PW|x(sm&)$M*bJ95*kP@&G@ zZ0$!^mgu`_m)+O#P0ZYG?kTx7l4q{-QYXIIXXmb07i6rxm(;UhpUaSb#%j0S)e9{b zzZuSIv?$(o$U$SZwj2BY{@@tSYW=cP<>m?9I{z=~(2;5Hn>W=>xLe`k5q`1J?5(cX zg0D?iKi{h51C91({g?O9ozeU&CB=ChM7-V zEwDA)Gm>jQFQrprRgt}c@gxU3&8zRe3~n6X+tX`OtXlr;8?3bsMhTXC+OW4B{{J#4+2!POa(KjTd^f*{XK)G{>TF zWKR1qPC}UNuV3H??J0xyv}pY#y;bG$@~`U*SURhnKY8wd+n3wo_o)Nzz(g?O@qxTo zo@w8l8>Sxbn$n(Cx=2?eq-xu~?0~b8YWZJm)NUqCXltG|#efxDJZFn%M@{|bIZM-6 z`aUCA9{6-Q47-ClefHkl?_#}0e0S%JZy(!PtuwP)WO_u~ zw95<8$wes(2ju#6FT0z~TPDt4F?9Z_2TM9cN4jNA(m2v(|0}J>x2pro^XCu$d33g} z*N)edVsg!16-;mTCh^N2?PY8BT${Nkr1g2b%En7uIb7~>?tIjI!^q>$^0vkF%({Pa z-qiaYzE*Tv8)) zwewjc%-1`32mU<%zQ}X?n+ol7>GOXC6(60b@v10mV7rZLZ+!h#(CSfj<=gga{tRjH zK`kl^mpDE@S zv}8YO8TI_S=A>4Ro2M4}2iUfn)-Ps8vE6V});YUdrK5*04&#N~Sjsnjr}o^yHKVlh zEvuW|?_tHB^S`p@n9Ov3JmOB{hmvQP{bQCaW{D@A^ovOX-^bRmP)@_RRyGC2u#P{Q=rCRk1>w97X>n`{=`f8(_ZFSUqd$%*Ubq8M3 zj%B!|S$tpK{R!=Mup+M>xn7pFX4Q#4GxH5Bb+_m^wpn;?bYqt1kf>1^4(@7UH=nK? z>N{4``OG7|6RZXApUi8OJfUZ%l zFyoZ_!JmD(=N}dB4d~QlF>7e%DU+Ppk)tE0=b8+FB zkF-rrIiRbS3K}D$8{NDesb=HS*4)-sv#HAztzYHoO;UPhJB11jj%P=2ojBF$!~-+n zg!&xMj*OT%x!_7#_Rh@{rxxUbe>Z}EFN1&APn^mblQwex-$R$93)-#Nv%b;I;4Nx4 zJf8Upu0G3U5YPO|$mEp1ebrJof-WP$UqP2nZOsd8K$k~&(?Iy`H?V4;@Aw&i)<<=( zJT&Cc>)Dh08@yim`jye%x#zMSp7Ey7zsfl>)!yaF7uW79#{3Dsx1;2_=i3M8N~f>h zIN_mINJ!M=`_nt!H-51@^4_nW{VZ+IH=Df1b>d@INxQ-qM)MYO+7#-RjvsBL?p<`5 zWu4M;a_4D!4$VeRQe&;ycJ$(1^=X@1Hj?z~tKs)5EnFv$RWx#*zBTK`^kLn?P4dDP zevHbx)k{}x+U9J>d20`r<|l26TJ~VCu3G-4RhlUePd$8*8Qkhqw=ZY4&n*lsJ!Wd;~VxH?<2tgmf2YU=UXF*$EM_(T4^IcgC{U+m6os`2#o z!Zq8qBTnva$!+Gise@@wUsg!-%>h2ITW?j%u$^(O7gvWp;Ra|nPg_*htDna2sDUE4 zHQO776>SLjT)Z@;NkqYmPL`RO-SZ{4X2R|?N6na5yjB_+0Ku$ThA3+p#Sa zjA!1K@7CK>FpuYREAS4-JnQjQAYUZPmp8+=2Y8CBU^mto5RP9>W<*2HRmJVmM!p^igHYbLy7HN>!CS5CL zaM+oaV`hdJEzY=-5fB`@aBb!si#{6eum9>@@wW+&PmKQdV_s#<==TFRB!=HQeMxX& zUay26X~{{+%_l{S8g_bKZX~q&i?VTB}vx%e|6Fz*jKE8xE>c?{Z8x>wmUfY)fr94XG`Cv4A2VO zRk2a;Z;GMa!p>WNp0IN@bzipeQW)#)=m`O5ZnF+pP8qfD*3Upul)CjR~0rP-6=+;>)<-8EACP78}{q#e=sVO%BG+*&=^SoG4g z+moL>i_}YM>dw0ye(}vTSxvf?&i%ecv-LrfO2fwIPUkKUPBL%Qqo`w<4dCq5z&^meH!>GhLUSVsj zzn88}Y_h#z!uyVAx8`s6H7Og}iM3YTQG8n{GG80V=lvCT@)_T9`l@G*u8$AfDNgE4R2fT`iQM367 zT*(y8msf4SY76^13w zUXYnq5-@-Bpqhg}ZRXDmP0Bc&U05`6@~c@#l0$^|dsfH%_`2)u`2op&io&NJ3pjq| zamk;EMV8zu?=nZ;p<}V>fAxjO+O@3l?2;brnIHO~JYb~P->60!>NojMeooNquukpZ zz*T|mnhj$0Ol&>dBWvsW9M(d?Q_IHZw;8XRImHfsV&3}HF-xvLyAU&FX4c4uCNV3% zY-{=A=b&X{Lld$xvkOa{r@rz_{@W;f&xUIYZ<+35xdZ||0@S_#TxTU*Y8L-RqG6x) z+o;>+AM^HD{4MXIb~AMGSk}`Fv1zBmw&p)9{M6p-T35UuyHlNQtW#a8vzgVoy~L&D zRjH0WYlqJ5tV!L~#(A#IwapINZs&+LlqqjzV$9ol2Ux&*<8Ya4!@dS=`FSyaf`@L!3g zYx}Z3xgS6IE2Z-1!6lEoSzcY{{rXp)&c?%!y;;-z&71As?X7-ZU?kCA34YRKUFvwv zt*YoD!H+2u2~@~;Yzdk&yoid7R9RBgts%V3evn9*zfG(yvpRhK2Ni% zHL4f8u|j%yg%wur%Py=`XAiEiQ5&^%=d0p%q2XHQd+g57G=Cs@H!ULTR91M=S2KH7 z(v>z~9Pd3?6w7i6?_>TpNPSdzpDR6WoC?%0vDdETj9>EkbLga*tJ}nH-8o%fZ}sZ8 zqYIy3-8gUA=H%Sx8l8J*jPQ$HKm0M^@qIQ^hG1$%ey&V zm+l^&Z?LTC$Fsf{mfh(+b?X+-*e&0iEe;%LHzC7d&)J^^?FTMRNVT+9k8+)_9enVT zwdTN^dOeoy*`yY*=ftJszH7E=>u>0^;K!O=@1YLKeQnBEyIZ~Iv2sglHnupwgg;=2 zWOP_?$mP8)ditit6yLTaU6K%Q}`W z>X$WX)ccGiuVLjeH{wD+Y~6R+IKjzm-;yuoKjUupYjfuJpX^1W_m2Lub9Gq1l)z0> zZFd)>Eq{C`eEb~x#wUpYCcbH|qb`_11nd)(xd9m^+p zXy7s>NmQ2&)bCM4(~0GE%xc(t&gQ}=PcjF z=`U7KFNi7_ZY0 zjKB52@m$~5oW(w3ynWL?ZMCw;<8S}Y?KrSon#Wnk5rJB22MqHMjp?_;wrIv7zr7bN zT;KQJHbd*${q*^T-&mX>UtV0avp!(`?8LSF_WipF8XLDBBi7PzKdG;A=WW)*XGgZ> zckJISweg*cvs}NPYi`WC-O=N2|I8toA-%U5I!nB@_T11Pa(zArbja9o{w zV&0y1+Z{_*tlFP`AaB>gTN&VSS^8eKLlT2Ck0tp-5%QO2IE24#Yv_4&u3s-!>ISZ) z#xeIDC#J=jiSzT^B%Ze013N{%EE&!MU+lA(vy>N*oaJuRE%ow4UIKrYQRYl74Xc=A z8-HFX4lWNW)tyrwZ!mAqurrxfMFX`@wf?d)tNSnXg*1=JpYN3n3)31iRMMG0FvyY% zb!m0skU?(Pr!hm@_wxKy0U*#TW3f%?x)IaQuiD=8;@jsNirWsH<$5Bydk@#PZ&J6r zrf!Qq6>8ggcCU&x-g<#=bAg>wJxXnkX)L|c{@60zvNge9t~?h`+Atz%6ep*pp38q~ zoo0kijL(`qr)=ViRV&kvjXeI^@iDh?)ztN$b^Q$wUe|J1wKCdl3ajc%(#5a=TZULJ z8`JW@gmlO9c*CNLzm7j0Eq-)-mD-Cwp|Sou@*fHL7Qe z&z)DrK>Pa^?0l4xv5M8Hcc|d7+qo!F`ZVy6Q{N6JY-h!Wf4-R(b@(@wS8!RgGw;!+ z52gn>Plg>^Q(oxqcVt3!@6T&Y4wl}_I%v3Q_sqb4F$Kr|=W=%c21BEPW+zX3bPzmu zJGx=j%Gdb`w+^P~$6qgw*7e-#mIQ$5>zZT=fSKz#zSE#-{2N{89-r-4`X(%4JLi`3 z1f4MJ(vqbs9c&YfI&41d8aPYgsvm4Cm)}X`#Sww zzWq_xx7&pG?ya_Q%6MaZ@y+q^owSY8_1brTuftUVKCRNyXBEYt2(C&$d{p#k zOY#}D!qX!0d50<&|1j~k!Ch|z7-&3eneI{o9$z}5$AyVzSn0U3bB~ z!Ch~WTCl-Dmmp`LC{=~RNj$=#jlppKsY?9H;Yog>( zz&4M2K*++`XR4g`JP$Tm*{#v9qDx(8WEij#n_Ng)>?cwXVek`o;_7q1v=o@S^Wk?y^}uYJh?*Z<9a7(LfF8I0KNj&DD5 zk`In@Jv94fM;Gp`;@+@Hotqpy4vgU;!&8ytO4@$&pB|PvJj-h1tZ?-Bg45>@iB`R~ zwJkJk^I+bi^&^tbcbJ-{qa88NJ7#TAX!eOlT5J3ly8ZWH*NQI*y2ZK`bMGABxf^y( z)A%<0?rM&?%f89%DdH0W(K%N#2Sk?+T<-Jd<@4y`wwi8hzoceP+yUq86U}|a9Z|z8 zS3-rZS-!3S{rB&9F7eRn*s|nAz^N+#Ugx(>3^!>@X#L#ckpFbpkU2owka#zJ;IDKD zw#3-pK3W}G77tr!>Ehbx$*|N!x0HP7o*IA31h#rIEGMzsnd0a)U>V^Jd*H8(a+c(8 zI_7ub;uu%X-!cAL8b(&3z*iFu#^Yc^PN}rBO zUIdfze}+{Z*lC7`XF?ZRd}`>6Jg+Q2ze!q6{P)^MrlvOqBh&R;fzASPNik9Qu^S`o{r}i}Y`#mmYaJz%mLDu3w?B*M^ zG#r+_e)4`7ze&$SWj|u?-gq_Uq&2|I&-dy?ql0RDR$7zTK!X-2#_1H@M<8B+h(&#kDHX5c?xk z-C%v68xHK@L8TYkjWRiN`bjf){p4N?K(lS*+yw8ImxnBGe|h@-0w?bUi?cd**X(_k ze@MgWelrWhgwR2sPq&X9HqL2Yq5qVa6v@M>Hu+GMe)E;}nW}Ngt<82^ zdFi%4>cpIfLFUc(NRAyy4evE2W|)^+Ley@J6_wov#E1uNH~c!@H1}}~c)*~X?^#o= zizfBzTz$pY;BDqF4})0e-Ur@z?0jUq#ngAOLDaim32&Z;X^*;Kwb91L)U@(+dz&p0 zPV+wYGqNpz+PIg8@&0nqGypUOw@9|#+hUo4ho06n^Zd$rOLX_ASuUHb?!VPm$8_2N=H5O*j&dbYk|I1b%Aov^hM_3|RP8v|hwMNz}(iPAzXlnl0aW ziO+WERr&p8E*zy(a5z@Bg`;$_yx9T$mi^p%R!?6LGr(+drxzQ;r}j56olv|n{4)4A zYTX-r<|Rwi!$5HFwZ~zW}L0h<9oBg=gI*PlE<7HxN2;lr?DP-Q!9cWU(D<4lyAQ} zFRZ=Yxx)ui=LCZx`cD@O(FUIh`9BAgd4&JnRe<647DXM$~7+*0Re#_pa`P25j&7^s{9MG>yBTw(;91OC^N?aF1t z2f!vLSY_kN7mL|EiI^?saM=Qp0RF*(&4tAl(y|m;$6`LI+@k@NGJN<*N~H{{elaFj z%AnE^N~O#Q38)!CUngoh*v8T_6QYpDdIX0JMU%=)E~9~8s=KJAt}+@Z75%sBE~6n; z6B#QP?%>O4#C&qOkF>CbC+09LY`N!VJLl=C7TH<(e=V*&<+x<`OpHnjs1CUtK4pGM z(bNcMr)|Z4n}2*+Ze{berJ9q*+`#^ew~RdbNr$CYq0#j9gOXiSvwF5{wXfvQ?LQ%l z=Pb)Ud#m)v;|#G=?v&2er#~$V2(;5%)a$?M?5ByZQomJ(r}K-y+N^r_`$oyGo;`-? zWqq0&7+5pgOxs~u+Y`TL&aY__-;Ar~;n#Ih%BuVnEA^j|af@Gl+f+RC?UVjl zYu<>vk_unjwWC}w`bCXzTHJPC*YwRFU2RYKN8hx#6aBtx!k5+QRuAtBH%-T>wK~x#uGfc~-or*%SXQ*T zC9u#I^zG5q&>-o3-vbvl_Ua~Vi(Z{mdal`F?H232Vh>ih+=*CVB}@>cwlgr>x6{d` zcwPG*BmJ+Avi!L3%AjK74m}2sc3m{mvf|dAD4z50w&8mYMs1nb`}&3+dJ+Bst8?}z zCY;)uI@Q-~(M~6u;&lS>af1$Tt#)=AY=39huIC=Tyu9^ppLrP+UG_*|{7o|9gYA@e zLD>~n?VD{l`!#xomeDo01GycwFXT?^zT*DQ8DgE^8E+0Y(tG&O_kH9hoqa5qSz3Mi zr?a=0`3B9pcGodBFyTqu+K_dl?+%-Fd}s$2zxNoeB+>AsDO@XV>i9=4yFJ#<@J@RY zmw&NsY||X@Lse1cdfke^1j8fuGDMnTpLz!bLp!O zFDI3<&a=ho2Aok-J`cR!9zE8ur*>q_s_5MInt26-ZGUO6eDv_?CHBHhFCUv35eq&q z@!i{h3!DEpOz#ZW*Xfa6#O>Cli_A6_KRkYZ&*IO{EhF>Cv*xnZK6Lh7@7->tx4czi_g1cAAj*){bo#6ZgdNu6_H2F*11o7)owxVyC*ls z+YMoxHX9Sqs_6Ri#g$(%G5ibHQWk7%@}&=_k;&P0d3TL=70*4sHDIIW_g}YenDzZO z>`nQ*N$XR(w)&j?*LzOdqbG%_kHXLW-FwyLg3x(b)RXl*$&0W!_ah)_xqvAv1{P|fH z>n?rT^3vAruY z^*q~HFw|@kcZtUd%VRnE$1FQ`HOftOeU*C9C~(62|HSt5oNR}-#T z%?^+F&s~pbMxI=5H1S5X=EbDI#r~nZ2pdfvH_PG8lTDlYls;&ECe7`?)~_iJ5Fjc&Vv*1 zCaTX?-@6t$e@~3vJlD1$bXU=jA2m}R{~h_FiH+6Fw!g;uT(&FB0G(tyZHgFUl`{Fb z`;BmiOS`^*SokgL+b}odKQD(xJsq)g_0t=__DGvmho4fY)+SELHno^?|H;Zfs~dfQwZ-rjg>fLVI- zhU!?KbtzsSGVV!YU#(6Xw{}bOl%UP?d+K&c)0?e1#HR7u74Avu!^Sp$*s8Ip<&^uS zaT6!6H9R_CT=4s({yz#0yEyWDZPaS|Ec%Aa^6=!@uRZsTZhdR_<|c-#@1*ZfU6i}8 z<-Mo^SFaNruRmY&;_lDR4?0#%{CQKOyT#=PrLT;g+r2#^ZYF47R5<>?w}Xaf)n2`7 z*=c6PfsoKCE3X<9h5Y&Ow%mHl;-OwgQjS>%RfU%hHhA^*_oHF++fdFHRcX=WSV4(Hv3BJf7yj30;Ru^1pkE zYI1*Vz1PP6V)Xz$-GWIjsZn=+y^CkN?w&WlYxu@|{=9qE!np0Ec4-NJ z)@f`_bKkmCB57H%(vR0Q@8RSFC$`uPikPrN^Wfm?UT`K>={4zcWr%xV$=FH+rbr|dDeeJB;^VBh1KuFcg!+#@$)c>tZL=t@nNd{8h`)Qr>nQ7jSsD~ zTl3-GrgrxY7XNJ=Xdd0%F*N2^6{v0l}9@53yQ?t6p1+caOBuD)pe zlNDkQ+s219&gM2h5PUW{Y)6M_Wd)Z5TE#SX%y{3m`KWv2&lfgt{r1d&rOiD3HRE@s zExvVj_q!=KEY8%NIsW~~=<4!WS&_fDURrzwjN;JB+b7>G-u5)^z@9G^1%j?=zw#FL z4Rs2-*LD9F*J`zg}z|4lH|A?`yyEZ()CC20a~= zU!5g>-_v2?(5ix-3E!W-t9%}+wry(W!QZ_K9KH{&vT?K?YVf1$i;z34aY>cwao<1;5hjZ4y;X!jc5?=~g_&Uc%3$!PPo=A0`ATmL@jaPy@4wH@8x@Fo`t54fba zXuL6Cz%NbtG(3`)Nxn zoBgVA$W*_ZaQd|R!Y8MXgiUUL>dCW5Jk7P?cAsy(j?HP?r1=hwRUeK81)RUo%5lKL zO~>P#{0Mp#7PIQs;(H02ImfT+j~~ABk=5Z@@f}+%s9gK<+thr0_VXcKXFWM%-(^&% zQ7u06R$X_~c(Y#uK5aGJR>P~f%l6?bwWdrn+^Q2~d&opjwA)RC+x-)7klxp&e^-ZV z{cp(BiF>BCHgwdt-#GEsl@)#)BVT?iwSPIkEK&2OR(3+(;iK7`dU3se{fv01e>${D z_z%rxAYlCQ>g)4!W@mqm!){r~M+}IV7*^?njfNvp9S=7oAb2+(85}rwHY~8W91H5( zJ?8n$^l%zEjBN~llW!4bE=0Qnayhv)_y-040U@B;9@PC45w#QC%#8MM_nBT>K+ffW zt&Nx~MB5y=Z9<0xxKar~D|z>Tc0sa@01(1v`n>65X9oMs4go)pW$Tai4xDcp=sz1A z8kjw2>TnYQN66vuxE#KTz=|WX5LuY;`CN`bGF&uVWMSo|?`B|1J-+KFeVU(LkZ>xA($LtJd|Ic2u6WC zqoEYw1Y?4IC>Vz)6%5W^0%JT3^if-VEhfYX#t{5Mi3t*nYa)^hh5BWtpi1c$>rcAV~T!|QAA@Y zlA|98Tbo9dtw^Y?z9!@1d_SKl{CR{Y;|k;sLx6!lYOA+oI3EiZ8-*E;4MTt{6M|I& z*^DQyg_!_@f7DiQ$#6~ZfKMaY zOo*8QsIA^M!#P^emxA^2qY2PMNG4K{3^N0Su&v&b;XJL7$qe9uPa(-f0tLx1GXO-q z^_Pr?^Rz-HYXDCuCL{wi6L~Z-GeFpo8NkDNTF|G0j`-0O@d(LGI0}+sW`M9EGk}K+ zvxSUifJlTSlYmfzWHS+F2B5b3;*5t|14N8wfS5x_2HY)KGRzDB)>Rk-M*fV4TLVDQ zrSK&DXo?9>E8&?aNQRjKV2&s}kC|k+H9*8@28c}vn}Jo4Y%|OZ0OQ^O$#83ch|vs? z5dKU8W-?ha%nT4UXa?Zc01=}Z08$3fpGiQ!B*_5!l;ShgR__^rTLVCVqhNhJ&P)ie zA(1GoPGZaqKyCGw47Ub|8O;C_sn-DaCy;H1nE~R4%m6-a4FI!FwaxgTv;dB#2}lBw zCBw`Bu=7)R9;3O*$E^Wiy-|1)b~O3Y_{;?4QOJ^EW`MXMGk}j<1AsqZAQ{N^A)A41 z3P~~vW(J_P`r?d_TLS>5nMg)>4HFQtk|o2;07*mE06uOFkT976d}&N;0#;eFWSAKM zJfDK5%y5QV10;-Q07!?S(F8t$EE#47NE$Q)aBBc4>QT@UKLdC~d}abHLY53O1AtFf zcpfvG;no0OBK+Yk&!(831mffuo61@+6~yr9oM= z22BCnB4EO33V@`55CmsPG%jf~j4suoBwbKjea$AoEdwTuCIOTUWDp41NGSxca4FlZ zA=5yBTL?@TO#>vGlw~0&UI6%%WoyVp5a5;q6GjsO$z~$8n^2zN<8m-_foQDvsN$9b zFi=2w(xdS66p9B{DPmYj*)%Rld@I?GXe2$8krxr*)&xMbF&0lE6_1pL1k4;xyoM|c z0^GvD1+fJ~>w)Y8VLej%mdnA+3Zk*z*2Aq1To8;g6c22`q~gib-dql5Vi1k>77w>X za5;>p28bC6@l51&0T*$%6n{rF)>}N>I>AMhG3iltPYtlxNyU>Vnz>;0P@Wp7k@QSv zQvXI(hAbLF+@itdGMyUWsywN9q)32^PAa>2Qli!S%_UTK<juoqL1 z4o5L_8^kdSu}cOcmKpA0k?p`9R#7_KiqRmVS%_UR&;bh)gz*a+SQwCWVDGOe9d5yB z5Zf%mE*R*_P}R}_p8{tE&_z)?+^lF2MEXrxh5nX@V|=E;bujHXlD_2 zxnRUQ!yFxw4upjY(g8oMyqKXz(r_?}R7BX-f)V%316xEW9lRS>Q99hLXb}A@!Y&q! z_-7v2_#^2+{!CFi+^lF21uep^70ftjSbhg>2Xg6((&1)BgJ@_GcCBE>LxVK}Ne4Ix zMd@&}qCr%&2)kA=9d1@Mh>{jz z*9vBwG+<_sbRb$+lnys58bnKrv1DoOW7i7C+%%L< z3^JRF(&1)BgXn27cCBE>PXis0bnxgX*>*UFn%f|XT8v#Qm~qqqok%*s^D0V*n-vYB zsm0i}f*DT@+&_{IKuS?M+^lF2RV~J@70kG5>Ape?{Ewn^xV54|bhQ|}RxsnMrLnOX ztSpMs;bujHC~GlxtzgDkOXE9O>!lzaj+r=73I}u;5!SRK zK=hL~GIfZ6t@{JT)|jmkm8oX5HR58Y4w$a0g`?GuNiK;8B4Gho_r>5p^kxm|DHt5K z>q$=A+YNJYaK=tNM&vXIAfaOb>>>{(Fcrrh!dunQ(OQQ|wg?{J05ZVZVnPP#At4+M z&2115jh$PJcxXE15Erf5IwCOmLa@13)D4GgD*dbi*Yr^T4qOuAdlt67_``W$G4zN;9jl58V;5e+4!pRvFkA7Qmvh zmva|@1yc5DL?g*sDs+>My&Y!kd5kD!qJ{yEJyF6y9((ZKDF#DFGxj`2v@sZaSVuuU zQ^3QK#zZ4?`$)$g7pB7l1FC^Zs~r<$Ljw~NACO74M>%+i5~cu~Xk@M&8hjph;`0z^ zOnOuu6JH22q-gL_jfmplGx6DU=AoYH#fkt2A9K`&Cp#ysAQF`cRxvrGgOA%m@~8wb zRybPim~dOL3I_xwjRU+^ZU8^*llqsOXRs>wJl?Xg4 zcZ)R=t$s}WIfSbS&~?&U0ePJYcmpM7I@Xi2CEz;R$`XfFW}Gd|!{g<{Bv*L#ByH{O z94)yJt6Ydx?8#CdGx8QF18R2|2XvLOp@E8%TwCXX5Zg^n1B5Vvec+!;!@MN*_Or+AQ%%D2a z3YVnhQHfRT_$kPzfK!NaCG%6DuTnloOF`}8kKHs<`Bkite3<70nyU!T?2x38-G_q<>ZydP3R_9{RoIcF5~*16X!T=~mqGg~u!WQAN6M@qs+5X_ zdh(}Iw>r@Z#})AyF{pgFtHKM2+t}8VLWPm4uy$94<0^T~m{j1S5aj~^puGN5nbUd? zCCKimPO;T-qXG{xqttY4&lJzZ^-xo`V%w!Ou`#l15tvRI%L3JTfsw|r;>&0=hF#4 zg}t}}hGnX;Nv9nnMiee=X!t>ZOB#N3T$id`Jb)lep8n(9Q}_ zVKlJVqn2MPR?hjSl4sNGVVIrld zlaD*aOElJ3I&4uVpAj7k!!aZsrKppS<70`&dP|3M$MDdGYTMB)$b58+mm~`oxUdEX z?r~ua4v(~lO8tPWx}xncsUJS|)b2lt$7GYh2dpEsoe9_# zkZp&X6jWmOUxZ`E@gf3McJBe{+HF3L<0TsZpXLQ~f)}jnL?C7&zfcrfRT+ErCU|Ll z9y4kel6oMkh2#UgynJpTQkOb6s7&uajW3hA0Smg3PX_xFaAhWClLUFFe_OX0QM+|j zmGjX_TqPSdWS@+!D(6!eZXqwIA-xahizBSMnJV zy0B^ z#N^U>0V;2cwGS6ivV@Jnfif}#5LK(B9>sa9P|w~DLckgC1sI*6<$}yVAs*N}U?9LG zlA*N`#cShjRL3C{K8~y<8td%^a2aJjBbt^@Jw_ZY7eslrHYP&=5wuhYP+8l5fdH7_ zs@HK?Qbe4Q0r$O7BY}TqY5CN{uUG&85?jJ&M9b2dhswd$Iru0$ z1BD^|#AQk}Zu~9ywL#?#xQM@%?J+S#8Y)pv(5a+6-9wqWtp`N{+ zgY!tv2v96L8Vdp@?i&^*5dz{Wrud9VS2`;(qFi}(oNVSJzLjbvDhaE?N>UKuj!f{W z>??K*Y1Ly=H4j}tt&Pb`03uwK)T6j<73#@B;D`eO;$=xL1*>6gNf*4ULfI2AqF!mO zM8P#)h&nFJ;G=V=N>-wPTZNSf5MVFN;Q#AkR6Zl-l?SW{K_CH}4~0+=(XLeWs9dZH z^c8kl0Zm7UK0@es${DAr4|V! z2(j*fdPWs%BwGEL0G%&gcfob5z~_?v0is)#^s67zAr$yBC}4RBW=t$Ro=^(~4!l8; zd~}IVJ+E4CQ!%DoDN+zsUwjK3i1j-d=O0KS+U~?O8`l?eJbq}7%{B0#-d=n4k-Xdi@S4_k2q8% zV^N}W6~>Z+0hdw}AeNPcE39}l`Ux1(s0a*zwUUBCUSTi5@u);2NhlTiK`@{SJK`(| zj>s1<<5Q(YwGuEzl!FBUVpU0E)!$YWe~x`XUAMXk5NAq(0?|m4NrkDT!2-^C3K(5| zObZ1jP>0kS3KoE`Ca(|zM35?}S3jgfB#3GYgK>u~1dO;-Pz?iO8Fbnf-HlCN9|Y8+ zt=LhdvlAnR6l?`>uL%_32vVZ4z9_&JqY0>ITkEeK6OaP~gWVZ?|1DP{Ke;AA2U)2Y zK#k0mgBSpVJl4^g&#@ef**FNOlqgn3c<2;mk3hPSx+)0Jfmf19*eB3JfP!o61L}Gk z9b!7ER-)3Mj2r>}eRR~5tytmcv|~hd!qcfl_6V#CwLGE#QJPB1QTC!LltU2Uv&T-b z!X63}Frqqnz~2%8AgX~Cd;pc$tiOpErC2}|4GS8nFG|E6U=>igO%*mGRst@rG)lmT z<)j4wGk6mPDq_GGkN|)?y(*wGn<|t;01yBG;E!4f81bBZ;0obNWdb}ECK{j;oArhO zBQ_HX0e6h>y+Y(9q5$!j)OkWBH&vKP8Vz6rLq;?w9R?87sme!!H^ED7405ET{h|Qz zm`dtV_Mj@%Lnsi!4I>X6y~OQ>1dP~DbW8|PHYj@KqCCEWGobRD^+p0CQWF)yf>g3p z3i%691h`YGL?g-kDr`kSL4b7!jOb1}C{W2wtbx!e96(%%UWP__F{YiBl?q8Jw`wW z%P(PL#WGO=A~==Qs~^rG4p2G~t`0aF9Y&|B(T-dK$bb`IMQ__tSRELhM5VJ7BgPZC z1Vt&NE&-99R8vtIP)0});J9W1BQBIyKSn@@E&=4&rB)`beu(W<(vPwURiPh*f&c~z z&?R641?s6(>}&+PT9DO1X#-TcsfYt6fTy(+1>RT@VA=r4fNp3rktbaRi0xFe5(VEX ztRxK=aa(FeTqvD#ROS<_9I!9Q(4njWsWeuAs7|VGRQ^+iZV&-twlxpjCo|T{0;?ir z4_b$WFpUcl0Pggo5DNlEhfryaL_sxH1Yk)h1G=A)^!6$NqB@nVMA?R_u#$8|z?$b@ z;Z41R7pojdlY<=tL;$$)P@Xiv9Y7UO$xju!K?F#o2(ZN6)h1v>hQdN^v}A#Cz=Q=< z_OlKx;S-Rnqh6jRV8(WW3=G;e!lNl9no)qeoR?^19zRJzfL#n2v7mGiM?5G=7OZ`0 zLoZNjqOfbk9YYmRsZRzt02q_*8nHQKMyF9>4jCNJ0H_kEkU<&};Le;1sI;dFGZ84jUc4n>M1az1M?GMQ)eagMt_ENqBqrsL5WPwD zb5zb#g>ujrfW*tVVRpl<9LC}5&;-m#P{=NV?Kzst%C|KOsH|rlde-d?7;>DzWhzP` z0|Io~O17eSauv3cx&!P)K_^UA&1PC4Fo8K@7lEZoRwncl;?9r~jU=H|=m)T1$*JX( zu%wBQ5eW)Uy26AqeB}@|HV`5nlq6JrkpLg8dar^+fXDZN2&8&cA?~~=(MS?Wg`Ef- z@Nmn5@L$i13Ync31%WTzvq|7Ss5Uqd;!cYajm(vUAmBj|@ZoiXxP+;Y*_lzWKq3r) zt++A+CJf}6S`rp;Cq3c4#tK5I&=2|p5sVQfbtDXg zj5tsP1#l{m$ZDXMn3Hn`LPUm=5Q^254hoEzP6P!-DWp)q9qNSlgw)4W#JV8B#Ro#_ zJ6P+lA0wzED9E5Ll)tk;h=@+ATcEO^44@#EK>?RW6ry9FszwpsM*&v`6R^}NtqfH9 zv)*=MMtDLIfSWb}D<*kmKujmqN>ut&g_Q^t@UdQ#5fMsDc5Ao@Z@M`JB<*SiWC zk)QwqAaFqtkWk<6BBWBD^@ac=iW4RcfD8x%NCxRzfIHVIr1G6A%tUwr>=uF1sZLr5 zFu^yRVjw>XhKj488w^R5AV7&zROp5vz$G9s+IlSRHfkXw_7lhmK1X0cKuH`4sa$8h zF~Er1gctxl5f~s%72Ls2A(iP=VJ89uxFTI4qhpo z0V>U@LN|l~o)iNPW34fXav}9DUaXApW-qi)1c@u9XaJF)B)^M&0w~4L}Xm7h@`;=QBcC?U8C<$xcs0@eCb3}APLj5tqNBZ)8owp_{>U;=bHD={NAp$HHI zV5>&P0PcXNkVIbtv?K1aFac%sBn%)Xld2q*-c+F+!T>5mh8V#5I);2FJTD6O1>k*%)U|+0 zaAK9D!vG^b6YZTqNgl{k5i&?)XT)PFnTY~y6=otZfH%*-X2cnu;)Lf_VR`@@{gAr> z+%366DzT|THvoa*9QL@e7EaC*aJd<7TfpeDT(B(!*+~QerPr#7{`DxQh!KkkApm3` zARxd050)G$xdEb)v;?a#lhh4h%p+n%Z_?mf#PIMYd}A4c0J1LuZxNy|Dexv5nd=52 zz?DJ383zFoBa*ZBU0PrzQm!w8l~MoXEurqJ9{`0w^+iw!QhkvKcZic{WNs+}1wve+ z5N_I4OGgI-Dxrz>lkyra#WSiR5CSQK95pgm4*~(L23+_;FkC`hM7{48FC?gVfQdSS zJ5tIPim2=+_93*UqWEv@0}ywlD1~&=;LdW2sN5zahakX1;a`zXr8M#SLGB3nJd%}V z`oXw_>J+HlrV9Na77&eyuz(AHM2yHz9@x#p@K6H0u+rToA}Y6uRg?}1jJQlB1DFdE zD2F^(0M}GyJ5h;E6?P(A0uL8I!*^o*n@gbbnOO6{HwnR)gGhh_k;jK3L|{@uKxH*m zCyS`--5m&+F&JRt)@d=oBn$_|m}rk61~E4o1GqDtA}Xn= z!c0;OU?&M9dXr8&Dw|n{g~5qsfB`Xx{zw==^d%JoR8CWcau5R&DF*Pt0V9qR+8-7R ziU9^N!NI?t>4d?N>bVAmfWZL-fkJSAC`=_oQQWu+LlGzt<5BRh7-w{l6TT*hu(9G5 zMDjVkjeA4=^~OlABnx(@hsfTqYC(;s7oP3OK-> z=M+)NO%;Zc;s6^yF`_wX)nf*8qR=0D19B0%2r-#TIH(`YAr8Pw19FED2w1eEcaoCA zPV6AUmp~vO05ITyz{IK3S&9*%311q8fB>RD1t8!~bBd@8Co>@6s3Z|1u9H?hCh0>M z8W1*CJi{(RbS4!DRE|@HdI$(8i41{&4S*Ptp71SpNJy}E#{hxKb7H|nYbgr8u@8Vk zARvH>C`BMZ&#h!BiaS?fDZ(R&aKy3*&{wM0Ejsn6{AL~MNhcc!NfkT-qBN=MQF%@k z>LDPYOfm!lE=>mC%b;3II0k5|0DwTvB#Wp_Css{bJ245ykqB_70AN6l5^*OvMO30w zg_)#LB92uQF`_(awPOZyB9jbn!z4wCh|*NTK>Z*NFfc-1fsEIY3DRNu2C)eseWQc{ zD$`kS41gs^H4Kpm00SmK1TqG2XE{YwqLUE@_}HugBg&Hw15}0+YaXZ_Vw9xi8`6{k zn0m@?4mFb2aTUrz44|72(MbfXw_`+n!i#Z{9{|CiG6t9coz_YeU}LQW-y4c5On?Xq z7=Re2PL+C|=9KyY+5D9Mz%`Bqwp7jR;1>o2Rz-zMM!hmETtqfw^ zc}}8{`2tD+fsb1`#f%tG8k~y}3rdou4)ur#vDU;ycmOF?rFD;JBt4M{4p5B9gC`Yn za2GS8LizC3B|st*fEsFiApY0$oML8FClmq3hyZm8D1gxkWxj~1#HR{7Nl}0+MHe%o zKxt9H4CKUl6m(a*JU|d5ij%4xmG@Mk9r6Y!N<=8Yc>^&cCKTR+3VoIsB(;>+1u+<$ ze~J*qjF?V%4=P+2kPsxcS&Tc?Ni;H_Fa!|9xXl7o{2$e$IB~2y;DM1KY^)d|h|xW@ zN=TrD<|>gee%QFNn2HK9Bl;8U5kN8nokc)z1t*_Q6jRAgtafzsgb}w1wv+J4A#{XX z(woV}xMQ3|V|@poi%YAC8Ihi}+A&EULIZ;uYse^(-bN}$q$YLfsZ6Kpp|`T)@W1ulV19E~8R@|^V_e+rhd4*-Q`(%G*_BZz_Bl$Qb2SYH5$vC9CXW1DmUpc0%| z^|)Z@Yi&%r0ac7RO)3PaL?fH$oJf|djJ z${Z26F+*ep{sSwO7`!k*WCH#Jf8%k$=fHnr@B?ZaPW)Xg{hJ6pM+B0)ye1hkMfK>(76ahmU+f7&a)p2^T2l%KM-4P4_Zox+D9d%3; zC_ZH?$}9+^QLQyeLLNy%>8+Q9gz$ylgut~DN)skfLR<`~z!@q?2rgD8><#P%0%_uB zU^BAq#C(!eWV=a=p=5TG{VJ2H)~@y*3qsIq$O)-|kWvK{RuctMQb|Yw5RgBDB#4A8 ziBxHsePqAZN+Po#=o*uPgV$@z*ZDfS2Ka#@aG?mb&y}f+G!)BtO*jm=5LJQVr0<4D z*Ns#KW5-~RdFXENTDwYdplDaJr>E}~4Rl?~!B7Uy0%@-@3|g?U3$en%Q2Jg4bh=9I zDCZs6*Y=oJeeaK1J5vZufa)Ax#;d>t4@e6U>CTGc_X zI5a8H$Mn5|rHs#^)3??op*brfzJaH}-9I2!I8v*+XF8`OBcY{Ot~CMZ8HXwbdRleQ zbRGlo(j;rkOaOYuB8$17g4U+<8nUCjGM(kV3ax}dCIt_vKz^&%na*>_UhFFCS?;gU z8l%)RbAJVOrt==?P%z2ba-W6DVU&7i?z3Rev>rq@d5O7PYXS>4t`bJ9z{RV!Hk}ud z9YvN|TkgBiJ>^uL6-a#5J=1v-8KW=jS!MzYkgy`wNd<%{aQ*Z>gFuzmlOU2`KF+l! z06pV;m_ki}>YnL52`UaC^(=GYpl95ws8CCwx@WqGNA|*8skLiO0D8vxFoo0As(YsM zVX~40SrCgv&^c~W&vG9oLx5t> z%zYTtna+pFY9wUVmisW-I4Jha+=s!Q>3o>%dTd$GQdoiYS!NBzp5c6#Wf@dko6d*H zPMgbmmisW7ObR_KRA;E}na+oyIt|h|%YB&aFN!_G`OZvdu&Jc=VX`6*sm`?~umGEF zjQ3P1|De|y_Dtu)WY3rNEcao!+6=KmwTSAT>3o>%xV)@q+13&0jPqd%WhSb7rt@Jk z&15~xeHiZAY_UQ;it3)}d>AT3kt3|u1Qy^J1#X;~`!G1pbUsXGQ<=_kABMXDTZ}%= z9NTn0O!i7=SJ-7=4`Ce1_vp=fh-GNV1;gaTuWQaRbfViNUVvoS1Cd%DR?2F)p@LK%t;XwY}-Q znCx}kvaaP`jEg%AEmkOnQr$J38L&_439c7jZ2`x>HHWfl_KF=?#H;e zgU#@OQ+>Lob7V4iCDU5&$he58r+RONiY$7A1LA?!lcCxyxz@Et09kA-o1jq3rMhc6 zS0;0nQmt!^0K3MmmI^grs=KE1W$3;OlGgHgjEha)E8LHvx@$UTCUes=t>w;)izs!a zv4*B#=FQ+((|I#lshO;6k~hPq@fF@LpjvA>ZzfwJWL=ZI88(-%P_3rAYdUX+s@6zj zP4Z^ggg*K_bA!`)GuiSa)0*VXuvvYDYd}X-zPrLtZP6h(|I#^;*rEt$&CP93NFb{e4csNG~NuJb5!VB9++`)S$^X4 z%)6%XW)j&890-HUjR3XAgl5F&nRiX&%_OpTK-RU)2(WAExRduC#OIlJP2sliKgyYiv5`}_HdaYsCblyxB`^mZ{c{5zTU!qXTsk&=AZzih` zk##L|=}>E&H$$Ii1~aHNoi~$(owBY;-VB%Vmnf8os@9s$o5?QBk#$Xq&2TAyiNakv zs=KE1X0nJ^)-}nS;d1^G^m*n6r}Jj03{~#UYK;KK8kh8!D3qRnZLP3O%}>MG4^p@DgI-QQHsMuDCg;P%o`G51?Ivx&mMVST-z#7)1V68GEt~rgXGro4z`+ zCtK^J+RJ{0+T$jxLIt*hkW8Q`dzFq%I9X&Pvr+9#kWP&MYwcT`BrA?AzhlOK$epzr zYfK0#-+47KW;{*IB47cnKG3qUqN%3Kw!5mQs?cL4{`($}8^`YrKYsJo#SADjDl@{v zFn>3{T|lSG(ouonrxO#AszJ zw0aTYuSn5{G?u;M6Fa#x-yX1K6vR)w`4KRP2aF2SisM)avy zC~_H1!n%g7gwu>Ti56m@(Q9Uj)8z%l#L0@F-hHgdcu1WxV-!=Y$Us7Mms}yp3TAAt z(ZFGyDKB+T~F19b)|VtlNzZZm6a9gb zYZKWqa6=6sDjtqTkdICFtg5GM&<=wgt#<4K zDG*lYk6q_Igb(p7m1L9LQ}qzX#)fIuvKpVS$16gDtSb@;Be=PqzFh?!kvTuvDru5F zkFpjrNEME6eaYzD)g`0wwq&X8PV=q#dSl-L;w_s~7lYSubr%c-v{Rj?%2UXEv^HKJ z&`+O%WM{HKU5$iQRgHvuYAE)i#??*z_Ud+dOe6JA?Re97DW{FsgU!`}@p!^)$D4K? zr^Z7$^lDt0I@UhLe_&}F|Vqq!jUj2oZD$# zDhhAXWO1Pr$}S*YQwU(c*51dctnp$ zdANi(AJyyPZG>}Guoh1zuY%W2&d8M~$X4)4a)pcst;LHJdbs#oS7TkDYRWFWNt4;` z356VXKRv$3+PR{v^UM^>=(%5UrnPv4NXnd90#-n1p!=z*E#jBopQt|;p~HOpy6J=bzb z40Zan44HmK4z~c4Fxv^6-;8Xhe-Jr7CUsm@PMK`X)LQKWIiH+9W}PS1Vq@0V4e0h% ziR>G*98dK`&x^cjAwvyCe@7Z`B-^b2okJAD(uHh=ope)=u@En$=po{7xm<3q{c^eR zCQZG}ZKauZVxxsPsrXpK?XdljNAb$q&dqFcESzZ}yk+Ft&;nc}o)CNF_)^;Rv)yk` z-N`}Z_?X<_s>&&ojhR{Ho{E#x$E@?DLvCYMgKbyBOf_AJ4bq(O|GiUVclCH}o>+ez zO{{}_Pyt9jpfgl%(E8O@&`DA?!Ti}#C1T)6lxhKt8ycwtmzdkW%?a&q9&kekJcWS2RJsc zUfj`JLC;{#iyJvq`EGnAy_bgmTLm*H!G=y@HcfyL zW-(h{hOSfVciYZOf$)g0EKQ^*q2m;8L+5K(9Vz~7d2$i=Zbfyk8#ueCaOMZV^;;4Yjg{}Ii8*V$hTjJ5*zk!1((S2> zIcs>DcMpj1?D@K#{WQm&H9Sqc4o_uZ_N>}zhquo^;$qX!sl!tlHhi*ucYA7N&YFG8 zcg)Q&=w(R;-JUv`vxcYj*V$7UHhc=bY0f)qcv^NHp31=R**$-^r(Wi);pxQG;i(K8 zzT%*To_+o?pjXG^>}|XhYty`D?zFkrh&!2!T@rE-++O5YLiS5Az0cgc*qq&zi%n_j z>CatU6SOL+QB3JRRm>5mzs`$Ds&Hfg(z84KJw3bdCQVggD~)xKN+Ujj?T%w7Y*3VS zo>@Q{J@5Ra?a&VxotMeJbctup}MSb>Umr6Unl|a%9cfy?)m`=70aO z#Hz5y4^0{rWmC;uprX2Ts&?|W$B ztl!i!k7r9`%{^>Mv#L|~Vv{OLxa8=#+7*_r7_3!x^WT;3)3rJVmNZEU7uk~OKlN1O z!kaYpvkhI8{!(d#Ee)3A!&^U-{!qHias|3Qbv0+gl7`OdN4E6o_j{}_rA54H;WCmKgPX#>+mZZm?Exj7W_0+PZ zSIw9-nKhRVQfX3Hj)ORzE6O^rT4*tE^Upg!7nY>QI(@#C=~q~eJl!l+pet!glM*(2 zEMeKOY|lnpxnU+8R5~n6CogyxbljZa1zqSWU2_R}1tONQ#?;WXq1O6lfvK z1?Z;hb&i5$%Z^OtqHvuXNQES+-K5D*qNRg;O|sbIIPBTaq;A^G7j3QY(bt}hx*4^tQ3q{*zjbdakrgXy?{a8MLF&+-qtGJ4+mnas&dHcme> zCw+;!7`~JyVP>VJzg)rtFzwMpwU70ja)*UTTdy6Nu_X+mEE{{IJ@vBO~w#=>WHEr4Ds5~zbnc* zufS?-rHr1g*SVp8`k0)4WM!XzzZfG4!EFE!+^tqZ>mZfT;e0Zp2F6n2oh!;Z&(8d1^t|&kAxuA?(~oTI)9)eN zNSIl0=`WSg3Grwo5x$MiGs~W?C29r*M9VSHpo;i!d0K|~$N6&sIwn0+H8i3L=B49H z*bYANDtqWk-~FVf4#JjH+dG9`UgJ8W4^v@F;SE_C1C$O@X;RpZE1d^LS?6`y4X^F_ z&6{&!ORBBY=UbV6h3$xWnGn=UXdR@}KOR9o_DI)EcWDPZj&19)u3S$TTmjoXh4~$i zIu)*7$1wp{dgm3cPP$k_<`^_WPgf+Fh7Q4%Mr()BzFx-HZ4KuGVUb3>}o zrSK+AwuhGvQfUOb76WcFwOmowc?D5BRU19;{9NdgT6?DDAyKDap*vz)W=gaY9>=st zqsd`B)_ZEz`&k!I1;HwW%~`1aZGmv^Go3yi@|;ixSGJ1Su19u3e^5+On)p!c~<5osM+Rl#8Go!^{3*ts96?@*T*?5zhIw z2EIu;4qiu?oWKEx0$*=vdGvnJAuWn{<`hh%gdu7lsYofF z$2ZD#K7HoHiuoa7$sU`WF=)fiqxY%>0-6hJTF9+>KSLX!G0<_y8pIeWpI6&KJ0?u3 ze77TjSB6DH!_OsGPh1TA3@GWQ0-ERRNq%O5PVXRN#)K0T$2;?O24#rJ85~43!wJ0? z1c^!5gA!>}712Hi6De^AY9Facf@o;Dsa6=N%(}0$4>NvzhV~*Qu2W!WECjVs5$!8$ zVy1RI{i{c(L(3PVQGP{t(9U6sriVUunj=N$56i*w(2}VsnphQ4D4J(;M>G{_imR`~ z3~Y!LKBly zO3-Zz(QP5w{DRRF;zbb6NCgq?a5BZERPaW{WRQrQTy4(Z4@#s_RYdz7Or)yd7SW}T zRH=gKaU27}a7(kUE2u)(kI&C-K^cS)evULV7L&JmK}_o-)xhbn@`V^Ho>#76*u(s6 zbv*mfY>3XEo)68?iis7PR~1pwOz4mX_#W%aThlOuH{)kUzsOAfeo!KriD>2=Or(?| zPAEic{byH~bzM~#W^03|Fgf!s8f!!@<{I(6YM?GkBW7;Thq?J^SPf!~6`$MsVQz-+ z1i&8lp{HUTUhh=3#rW1FKYJ|(l}9*Xjd_*SuJId{ug!5X0YvN&MhW?TP$Z42BHHI* zBBd_D2{mk>tKf0C%B=e|eozE>TvRhO=vokt_Ij>}*&{J|3l+q) zK2kBygV!L+XaRW35{BN-*&u83^-;;4c~!{#g5g!7+Y6|s(Cw8VR3f2;wdQ?CJCipm zs)K~&>AJ4|eo$uMZJ&dQl+wltm33I?<`Kjrm09=cN#fCK>o6#Jnp)s{)k0kuUs)3~ zwejf!yMpesAm-vUi;!|aLDIBw+3?`%;$wqi3Rhbj{w+~G3tQvdZK6&*dlFisg;Q%Z zyGe8tN<=r`e>7Y3mL#CthM1hi!8iz`&2E3>@Zde%pC}dB? zLl`J0ZWwl+^tTzMrB~t#wOOR}@J1zl^9wKHtG4Iw2Sw7jDzbeJCQ|)d3%wKS`V86Q zR3r#A#6;E%42SL?KPJN1yRVb*Hg8(EFpZe$v0%Eq?>u<@0iDRmJ_ zpQ%XVff%AoP|1gLm09<7_F=}4&(pk1aV-c>N2+PWOx=J3MShT)OUcTxHgM8c2Nf(m-f|oXmCN`vFR%mbx&Fn7Lga=IEoLHHb0dXhwyD z@(*+LIKYSnD2|ZbGums5@Zo<8_2kc~oa5Iv;Mk0!!(QH1#T3tjR~+;_98$K%DIJs{ zQc^T&5ArlGs)%ZTKPZxhRZ;D8Fp*N%;Dq|X)|Ym5S=SXAV_I;q3ki2~oyj+}S0a6Y)P*#ZH z4b^zYM2~K}XS8^=J^U!fLZDE^Z`*O*whbEA7}vzu;{!Iosb4iX>xIWcwUUq?9sFs7o|tw;52bGV4A)T@(RQ$ehjFZD}I3BD@_b zrx7!??*rwDC&SAZq*;KvH~|x8hN*^%QE}*MTup2wB6}*@$J=Jd4b82JDW^#Oz>g!F zu);d?fEQ+A;F_Gp!BZqJtX)EK_@GF#6_L$3m`JJ1a6;LlA-j!VyUMKl3a~Ka$LDO` zhr1Spvm@m+V&?X}pR-Sf*RUYt1;}mxIL?L$#n;CFx;GM$JrVT-CiUF?ghxZKeM6$xmQ68e6L#Qy^&VT%)a|RQ!yLjJQ`jUrC9(T3WA1?<7~)r5ZM!c zHf~sg#%OMn$R>=cJLep3>zq+TKg6U04{T4CQz!O zVpRAK7^O!wUY7_TOtn1q9EQeIWdHk1>5tsZu}&>+yew@B*M#sv$=;P+YirAF9nODPdWy)}1r0!!<@zn?yAsL{#&= zDX_i{>ukg^Ig5jQ%`6X>Q25#nji}}vKAIuNp|^=3lJ${_B&cq^5LcIVUCk?WZG-1s zpN(pAbLDEUa~z;VY9XozuHMjx31aT&YD4u&&>BP;D?hh;LrJP3M>SrE2Lf@9eAM}T z&g2wghN&J?F_AelBkIX-9J8GGvCG6Df-v*P~+H$N$w6}S|5`OW52m$FghMyz98cT;8q)k zHoWg2I!n6BkUbF-nR`_naYJ*fV#b)roH-$mY{Clb%B*yarLm3y|CX zVa{gq6^zSjXxz6(d&wDr#Z7u4%n~9Gc&XYHs+rkBR6C@gJd%IA#$||fjUn*Ce33a5 zja)+Ut=-Tns(lV7QtB$4Q11xkg?Nao%(_nl4Ub>%I1lxX!}|eBq?hW6G-9TI(V}>$2rrg9MQtl zZe&FCh$hHyL8-_4)rROc4&o}a8CMvE?oEKyhR^0{rdzodD*bVtaD)szJr&VK=erYM0XhWFh^%M=*HFK=k85Z6U>?MMNN50+7w4Km53beip2WzbvuJMt8JV! zG0Y_tj&>ufi1s;{NGVO6P}>NW3W#=slD5tU0iwdo$+tx&Nrx@@~4@U=Gvl}O`WQ8-)~I<@_RqEtf-XTx_s$k|hOj9&d#xq#_- z)5s1ABy`Fw(rv#CF*%FF$fhq%3Hg3dWZ-O{gRN;w87KavVUwvkca>T9m7M})tTmnS z`N*!M;r7k1z|3^O*? z1qP9 z7rmtmP>jlku6%tE*%Orob7pb6#%OL;Oz}oSo#WgUYU`YC{bh*BSsX?-Il6K-6GLfx zKyu*hQJv$4wNU|j)@Le`AlovY+PJl=3^Pu%7w3;(=Qs~_j>G!_PSgUCJ>u*%<*@G~ z)xvr38bl$8OhdWtALeYxV4lc9WKVe`TzMj!S)Ig?QnA)~R$>`q zawdn-9eA52L<#3}H@JF=^f{PFDQ%ok?`WH2>yfz1to!tI@#sI0h&j@?<~s5H0I9&+ zjhMNOTOX4PgU5#V#Vdf55a=Yt260B*ojx>iUXq9p509~r8op3a;&aoo$qQbtRz(&5 zCS=Ip4lk^Co}E~Rn4HN$gp&YVLg8=bTa&+i4kl9lbW0y6)I8ccw>LGeGV4AKFg||W zNd8U<`P93si7a*D%ALasTQ z-Xy{Uhr42Jy;G_vLrl)(Fv0_eGs}A5a5uWj;Y^gaQzh$90>V%8z1w(+tIWDjPa8#m zbjD|UD5ODOC*g3{0ues=-rGDKvGkdW=^l!?2`52pKsbT)(QL~Smaqti{cjsSJ6&c7 zpW<-RE;UC|B7TI!nUPEmcg5OFQmQCJOe*pq!pXuep>Q~J>dE0g2NNl!j}vPkn?wq%%Gn;mk32EeMCZ7AnFUF{?ea5Iax2(^pfty`nSjRjou?&$*c+4#gv*LZt$kl_A=vh{7_BohHse5oj zjicStv~dwvnRQx;P@d;x1~P$8fES7!>J%3w`6+ZR$erX>=UH2;%zXPHawQyr&INb9iq7Hv zpfDOtkIrEZCQ@e7eIKbv616LP=jfNkk)KSJq5Cuwu@@lk{>yl-p#+3fs-imdypp3wcH^XGyk z1->qkKL;)J3)703+o|=DFH9u56g~q|2@+_839Dm`Y)h7)kM#G~SF`uO{^jB2_082i zegdTrDy+5_c>VeH-Tec4A*#xv``dA+SaVeuRE*U%veC`Q^*|tEcb$`_sFpH-EXj zo8A2K%07NS`*2n|`uVEwr8bYcsb6}2dpCRfqhj@P5itwwVqclL1i3uU%muAf7KaX%k68sT6*s(t4OE!Dv?O<522 z&yROkm;blu&ffiMBmMg8J2P2c!^=_2+dyrk?007`ubw|(=C`lko!uE0v4pn|54W$* zUU8H7qcX@LUL0!=ehSk3F-ox#8P|MBFHrw~^U%$M@y#M9hfAOg|1AYm#Vt&x%i}zk#-#mRXyeh){ zaPjANd$E34{Q2oS?~Xp%|9$0u-{9{)$T0tAxNprOe7wuQaXfpqZ@l5}hsJA$`~LQ| z50*`C?!qtA$*ukG+kA2bnZ9}-7en_Ev+3m{4%0g@B4<~a^yw4hn%RGRIQ#FSSK#iS z|Ac82+L?WTW?Nmhf|1Hcdm-7{b5r>+lw}Jzdv<&CaDDU3RkaijY54r9XOmfvg3BKP zzaqkKeW>4z{?yBXzfrmY6jQG_*y!)$9&HZjuShx@|DjF;f8+FyuyYPZWs)wT&F@qzQ-d3-PddKxA8!v&!eYa+m-H`$EJDw*#3 zDb+i&}#x7W|Ez#NyaU%&VI_VpiM|KaN9 z7w|T`)>l_I55Jpz^3hj+`1;fT`uyv!zyIdjFTVO7jBXz7?G64q`(N-Ve>eN?;qvCE zOSpDVpL}&Y`}pfWJbeeB`t<6)c-Zhte>cPX&u?!ZUSoe4`uy~(Z_xh5kJtAzbMar6 zk9~RlWAs0M{Mk2OeEIeF?|t{l@4x)wV|<<;`1b1g)!o(2Gy9av_{}FD zFF!3Eesg^@`vTi)dGp=%&o`GZ@&4iJ=ez5Nzt_fBzr4IO_Ze?(Cn-x_bpwMes=E2( z-OF!o&F!s!fD3(j_w2>fC-496=~EEW(`{&WA&=MUgCw7+lv|IT~A!GCJE z?B{=cXx@?aZmNHI2?zegAHV(b=@ak%mmlvR?%;6r1OH}WyI^%}f1O>yE3blmgFWzu2ctM*F6{-r$@3TZi85bw3)%HTg_d8{1y@GT47@6iUxe+y8Fs{P;H; z&px|^9QJp%_hYfoaNgdQDI8dLtogiIbi_&SuCEN$T)A{9ErODOV6k4e;QQO%)pL^` ziw*Q66j%R2hWi@DeD=5gpAvksmop%{G~sz47KUru@Ju~Ru@7zKx2pixxF)c+7)cd^K%&jH+evH*NF9#x8h6+t#WyLfg*n3SyfjNQAb| z61>~CCDK2n4bNE7HoG+s-(6T1YiL_qL@Knc>~Y_t2l(6+Wz@z7Q( z@j~0y9wQOkR0sGOU0HMd(xy_Q;#Wu^e2yJW2 zeGYA<{xY;}?a>Rd&2A7w+s@MALR)8bLT%gT!Yb24TY`g4f`iS%DsRGfm-b+Q(6+LG zYiv_nK%J1tj1mZKE7x41zpY&eg|?lgvxc_L%F)_3qAwI+r$=jNPUd`?Gjtq&6N{(i7o7w zx(DnMTiC5E-JzYwF0qB(#%gfG=Mr1k?d(c7d~Rpyuc588!mGBeOZJ7XJUJ_TZmxS& zw~#$_-Yu2KyOm-M^ei$%JdwHEDAu~I+DEsud)gp#XP0uZO?VC0sKUj#K9>CrccJFG zHT|JY@P|uRu^G7SvVY)m%!>9ye;ctGTsDfG<9g9DR>OC9vc9;UGB2ADafRC& z%aRG7n+t|;8zg(m0#A^McD}%K9As{D#XVenD^>~PZjv#|C2IKGPWIXbU@Cfg!gsf__n0U;4>*}J zZYRFz0_RDY$8v5};_bN0h4AD8Strp}(I$S*V!5))n9yJOd7jW#o_`eDO3GYp6MuKH z+^PL8JGI{xE+wNZaMxrWtCF?ej*DY}%meHOXjg&$UeBh54(wd;P>AEHU-(pjq#@^}~PjC}E+CZyOmd#S_ZG*=V%jZ^B z#TmvZzl;~!61{9TmWdudm+%2TCc4M*Qgn|LaFGv5vw{uygfd^aqWWDuBQD?*%DN$o zLe_V?vH(mww=ItU(gufI+mt)E$=0Z0-@IZOc8Sfv1rhmn$zHKr z%GrJaKT)`3w^sYut<^r@CyJh73W8nuiL$5FUUZ#3UZ)uY>Gi_9XtV6d@VU91#g{mC z>*v&OS|YL=agR3fk(NkEj%$t`*%HlyETwcPw5fe8@k3E6Unlz;@_57s(I$J(63?U- z`R4EjqI~nE@XK<(6yFwZiTFNX-K4+r*v)pnbM>E>aBU;5mN@QLzOn5L)*lUT`pFtQ@G=@=I|$VjE(quOAxevZfEJVt^O7}iM1>jop2&t zLh&Ok@k{!Hq6G(-oPG{HMp;m05_xjDTnQ(_vQ+oWjqHtx;Hj>bTiLte+6uqmw6FHD zx)A>lBFmn)1l{J%Y9EQer6BDHK=R1P5@HbzHr3fR>fRKnJoO zh%t&@wwKKG&Q^%Pi(O&|72ZXgU=24I z;&ZL$&cWA3Q0^|WNC^?j~2HM2W0sF~5vsxe+DgEK3qHW@b ztq_C~93aS}{h>HR`YX={Y4x($N?a5>xAa2!)48qiu->Sb)jH{KExyHSRi0$m>Sd+(IB;Xd=R%wKa0sc&`3=&keCq@o z@H=I`Yb0UBxnaAMHOG~Wer_e_!4-a9TEAN!b@JAbq(cDD&Ows3x; z4(w;vwN3Xtq#4Qjg0l6y$({mVRB*prsqS}c-2>o@ivD(*8--LC-2-+Sx4?;5_kdle zdjNbFay#l7#~HyNd{Mz4?%8GC5JnRH?eq=}p?Zm#uOW(# ztFbS@SvebF8qxEvJk-C%3${=lLt|g--A-~G@B`cu3qr(AIUD!vvPQU;6s#e{D7wNu zyXdsTgBju)AucNG)@fW6Kd-F1!q%u`AdoI&>=bJq9BuhrCs;$YNqk2fb>+?msXgKg zSh`Of13#!Mys^1Jgeb_exlrCfo7fg;P2!^Xfmh*J{3@%&MbRd{4?G(2eKtr@k35Ou zBC##B2~WbJg*R|3B(?=AR{bH26!C&ARoTyRvX}ETZsTQ7L7VI;$n25x^k$C3Ra}qc z?j64sDf>CD)x_7smLhu!+EiDIrTBV4y~Ki03Lvo{w23VsD?{#z@N0nLcVc@JpC4`F z>*0D(cmun+*d;UagDQHu>v_OBH+e&j>ak7##C#n+U{0nzO{1*#{#r*?qiZ#SVRhF&V zDtuAV3*w@}R~9UYbAvA`dd9(4KbPoBWB7z*xYWOu>7{BOrr|X6|tLOmXs~{hu zIV*|XY;b*~-`yyO;f`Lgw(TUw2)AA05u4=h9ci@6L%XH=B{&KRCn6nPY#%X8{hZdT z!IM(o0`)k8(@x_mC@)uTLjI)ar7J%@-{LumCn7USc?jagdEnu6q8F5xMND4c*dsiI zlw(PLVf#6Q4}B4x3(0Wg&_;ub}o5#w997I8gr!zbK?XJyKM ziHN>%9j+Y2j*t=~+=OCo;T%-R3jT0JlrtD2g5s~?T0`>OV3sN~e2ZwSIC83<5z~si zixhCh#u7n~z#BMWi(SG)lD!P4EwTMA?n5IdqGCYe5xAa_`_-*o#70?gktp*(>VC8% zq^*k|ffmKuO7|Y@@M<48hRQq;#1mVDG7lJ%%p<8mK=!kafqh2g!x2_wN%Fps z0i-xZeSpjjaSM?d_hq6h9ED`QJ9~_TQTC9dWM!@*Gs=KuT$r?c7x4r6F7otcTwE2& znxm9f)*LYa{cd?qYb!I(`|-O71&IwJx+Yu#HWe<$cAk7!?^kjAAwCE^71=*f{wo+l zwUxyAvAlA|+2QOQ*B7pZU7&};>RLfr)$2{xC%^0*A3f@jDdTIh;f`GWe?ba z4kB;t5JHYNvrFppaQcvadY9y@pp-{-ic7R;`!IdsNmOR&+z@^d`4E&A+XCOq`l8%a z=8Nq^`ooqd`okGVWXA8;>gSSmGiN^H06#q={h9L^KbO>;A@nMH{0?c{`rYzypoWJ~ z9k05=@ls{cdkvIPsZMb`k9!5uW5tg^G)MdhWH;$NaQ!ChhJi(YJH3-b+Jo@;4k37v z59vcP2A)tPYl(U*(F<~61#76mk9!40}R9?%z+RbsP6!47YkQ~=8IUB$_ByQ0mzf=0d zoqAkf91+E)ar%&0GmiVh&mH29vK|PBMH~P^5}U)7gYdJZXGd%Rxe_p4I~-L+z_wR?`rKFPMl&#c)W%9MFTx|TZme^`VX4K(|tzr`pof-kgag8{n zO`ki1)1~Z}xIxpk?8>gv070>I!YBxRUQ83rN}|zs{;$BM+es$#n6%IC9DuI3|nCpllfz zuBd)j;@(yb5%(yxNsTsc2a(hk^ zIQYc=aFi5T;I7G9YEC)&lUi=H?V?|THhK0PoDC%6MOhGQk@diHD?|qf^~pTc&&C*1 zKaDo23!Go*GbPX_`EY2H+#a+^EF5i;KaMuZiADred{&E!#xot-WN$=Uq8CuCtR(^= zvX&^f7oEa?7M;R>*3T`YF9j09p((BrA0}z6)u$ZzQn6Rt|z8v>AtH6q9 zU9_PZDvp70Nz?&c>gbo?yYlQdv`NkwhL!v8Ya98CW&Vzd=5zjaSV-R;ByiWLmQ%k@?FW<2CU?)i#B;)AKIiY0d3+V zp-tlaXv0Nflm(B~5M9B&5?sOklX;+aL~w-*0l^hGRzIhH3Cu|R5=-|M8?*pmoX1Z6 z5@=7?64x4{1DK4CA+=s z0B2I3PlGn~k?eVW(Z53Kk?ezT359oYj2GU;k1q-D;)Y&0$LKHW3fF_O9`MFxJ&-9W zyo+eD@P>tuBi2B%!gX+Mg*)-AIgBNIos6QamIh^NWKvkRUu zBhL;*8w@014dn)^1LO)tTgCON_|H&*`22`)i;oE}LUn-a3LT>p-axiqyzjBf<`_S< z?M-!n Date: Wed, 1 Nov 2023 15:21:55 +0000 Subject: [PATCH 048/499] AP_GPS: Remove GPS_TC_BLEND --- libraries/AP_GPS/AP_GPS.cpp | 7 +------ libraries/AP_GPS/AP_GPS.h | 2 -- 2 files changed, 1 insertion(+), 8 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index a085c021f283cc..0a5f3a7b6e1f7c 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -343,7 +343,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { // @Units: s // @Range: 5.0 30.0 // @User: Advanced - AP_GROUPINFO("_BLEND_TC", 21, AP_GPS, _blend_tc, 10.0f), + // Had key 21, no longer used #endif // @Param: _DRV_OPTIONS @@ -485,11 +485,6 @@ void AP_GPS::init(const AP_SerialManager& serial_manager) } _last_instance_swap_ms = 0; -#if defined(GPS_BLENDED_INSTANCE) - // Initialise class variables used to do GPS blending - _omega_lpf = 1.0f / constrain_float(_blend_tc, 5.0f, 30.0f); -#endif - // prep the state instance fields for (uint8_t i = 0; i < GPS_MAX_INSTANCES; i++) { state[i].instance = i; diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index a097e25138ee29..4b184dcde0a827 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -605,7 +605,6 @@ class AP_GPS AP_Int16 _delay_ms[GPS_MAX_RECEIVERS]; AP_Int8 _com_port[GPS_MAX_RECEIVERS]; AP_Int8 _blend_mask; - AP_Float _blend_tc; AP_Int16 _driver_options; AP_Int8 _primary; #if HAL_ENABLE_DRONECAN_DRIVERS @@ -739,7 +738,6 @@ class AP_GPS Vector3f _blended_antenna_offset; // blended antenna offset float _blended_lag_sec; // blended receiver lag in seconds float _blend_weights[GPS_MAX_RECEIVERS]; // blend weight for each GPS. The blend weights must sum to 1.0 across all instances. - float _omega_lpf; // cutoff frequency in rad/sec of LPF applied to position offsets bool _output_is_blended; // true when a blended GPS solution being output uint8_t _blend_health_counter; // 0 = perfectly health, 100 = very unhealthy From c06a75971076c667daad8121839bfa4c973a2ac2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 19:08:12 +1100 Subject: [PATCH 049/499] AP_HAL_SITL: create and use ADSB sim when mxs simulator is in play --- libraries/AP_HAL_SITL/SITL_State_common.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index 395c66b1be0791..320fcf9615f78c 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -216,6 +216,10 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const AP_HAL::panic("Only one sagetech_mxs at a time"); } sagetech_mxs = new SITL::ADSB_Sagetech_MXS(); + if (adsb == nullptr) { + adsb = new SITL::ADSB(); + } + sitl_model->set_adsb(adsb); return sagetech_mxs; #endif #if !defined(HAL_BUILD_AP_PERIPH) From 4ec80076a1dffe3f8e9ce5729cf59fb261e77d0f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 19:08:00 +1100 Subject: [PATCH 050/499] SITL: correct bit for enabling MXS simulation --- libraries/SITL/SITL.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 7af63f16c465e8..9d70ad013aab3e 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -452,7 +452,7 @@ const AP_Param::GroupInfo SIM::var_info3[] = { // @DisplayName: Simulated ADSB Type mask // @Description: specifies which simulated ADSB types are active // @User: Advanced - // @Bitmask: 0:MAVLink,1:SageTechMXS + // @Bitmask: 0:MAVLink,3:SageTechMXS AP_GROUPINFO("ADSB_TYPES", 52, SIM, adsb_types, 1), #ifdef SFML_JOYSTICK From 9d9b95af15faaf0c065f95ef9ee291287e67cb62 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 1 Nov 2023 10:23:07 +1100 Subject: [PATCH 051/499] GCS_MAVLink: correct mavlink result when airspeed not available only in progress if we have started a task running --- libraries/GCS_MAVLink/GCS_Common.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index d5c407ed2fa873..1d383a1003164f 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4352,10 +4352,11 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration_baro(const mavlink return MAV_RESULT_TEMPORARILY_REJECTED; } airspeed->calibrate(false); + return MAV_RESULT_IN_PROGRESS; } #endif - return MAV_RESULT_IN_PROGRESS; + return MAV_RESULT_ACCEPTED; } MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) From dc824506ae2a36be59adb28d9b9070571065820e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 1 Nov 2023 10:28:50 +1100 Subject: [PATCH 052/499] autotest: add test for correct response to pressure calibration when no airspeed --- Tools/autotest/blimp.py | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/Tools/autotest/blimp.py b/Tools/autotest/blimp.py index 05a8d5fd980567..661c4a516286cc 100644 --- a/Tools/autotest/blimp.py +++ b/Tools/autotest/blimp.py @@ -237,6 +237,15 @@ def FlyLoiter(self): self.disarm_vehicle() + def PREFLIGHT_Pressure(self): + '''test triggering pressure calibration with mavlink command''' + # as airspeed is not instantiated on Blimp we expect to + # instantly get back an accepted. + self.run_cmd( + mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION, + p3=1, # p3, baro + ) + def tests(self): '''return list of all tests''' # ret = super(AutoTestBlimp, self).tests() @@ -244,6 +253,7 @@ def tests(self): ret.extend([ self.FlyManual, self.FlyLoiter, + self.PREFLIGHT_Pressure, ]) return ret From 9087bb6b89b227cdf84d12476831331c8a10a1d7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 19:09:11 +1100 Subject: [PATCH 053/499] AP_HAL: track simulated ADSB vehicles relative to simulation origin removes dependence on ArduPilot AHRS library Also removes vehicles based off vehicle simulated position rather than distance-from-origin, so you always have company --- libraries/AP_HAL/SIMState.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL/SIMState.cpp b/libraries/AP_HAL/SIMState.cpp index 776e56ef7402d8..9a270445abf71c 100644 --- a/libraries/AP_HAL/SIMState.cpp +++ b/libraries/AP_HAL/SIMState.cpp @@ -99,6 +99,7 @@ void SIMState::fdm_input_local(void) // ride_along.receive(input); // update the model + sitl_model->update_home(); sitl_model->update_model(input); // get FDM output from the model From c953b4e5129b035c25bf0523a4c97721029bfb2a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 19:09:11 +1100 Subject: [PATCH 054/499] AP_HAL_SITL: track simulated ADSB vehicles relative to simulation origin removes dependence on ArduPilot AHRS library Also removes vehicles based off vehicle simulated position rather than distance-from-origin, so you always have company --- libraries/AP_HAL_SITL/SITL_Periph_State.cpp | 1 + libraries/AP_HAL_SITL/SITL_State.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index 4d2cb796a01162..f72214aa46d697 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -294,6 +294,7 @@ SimMCast::SimMCast(const char *frame_str) : void SimMCast::update(const struct sitl_input &input) { multicast_read(); + update_home(); update_external_payload(input); auto *_sitl = AP::sitl(); diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 8c3af4c856bd64..361b837cf1dbef 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -346,6 +346,7 @@ void SITL_State::_fdm_input_local(void) multicast_servo_update(input); // update the model + sitl_model->update_home(); sitl_model->update_model(input); // get FDM output from the model From fbe690d44b686bcaa0ff90b9a0758645a4559142 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 19:09:11 +1100 Subject: [PATCH 055/499] SITL: track simulated ADSB vehicles relative to simulation origin removes dependence on ArduPilot AHRS library Also removes vehicles based off vehicle simulated position rather than distance-from-origin, so you always have company --- libraries/SITL/SIM_ADSB.cpp | 50 +++++++++++++----------- libraries/SITL/SIM_ADSB.h | 9 +++-- libraries/SITL/SIM_ADSB_Sagetech_MXS.cpp | 5 +-- libraries/SITL/SIM_Aircraft.cpp | 6 ++- libraries/SITL/SIM_Aircraft.h | 4 ++ 5 files changed, 44 insertions(+), 30 deletions(-) diff --git a/libraries/SITL/SIM_ADSB.cpp b/libraries/SITL/SIM_ADSB.cpp index b0f48d88e46824..784d032902642a 100644 --- a/libraries/SITL/SIM_ADSB.cpp +++ b/libraries/SITL/SIM_ADSB.cpp @@ -35,19 +35,26 @@ namespace SITL { /* update a simulated vehicle */ -void ADSB_Vehicle::update(float delta_t) +void ADSB_Vehicle::update(const class Aircraft &aircraft, float delta_t) { - if (!initialised) { - const SIM *_sitl = AP::sitl(); - if (_sitl == nullptr) { - return; - } + const SIM *_sitl = AP::sitl(); + if (_sitl == nullptr) { + return; + } + + const Location &origin { aircraft.get_origin() }; + if (!initialised) { + // spawn another aircraft initialised = true; ICAO_address = (uint32_t)(rand() % 10000); snprintf(callsign, sizeof(callsign), "SIM%u", ICAO_address); - position.x = Aircraft::rand_normal(0, _sitl->adsb_radius_m); - position.y = Aircraft::rand_normal(0, _sitl->adsb_radius_m); + Location aircraft_location = aircraft.get_location(); + const Vector2f aircraft_offset_ne = aircraft_location.get_distance_NE(origin); + position.x = aircraft_offset_ne[1]; + position.y = aircraft_offset_ne[0]; + position.x += Aircraft::rand_normal(0, _sitl->adsb_radius_m); + position.y += Aircraft::rand_normal(0, _sitl->adsb_radius_m); position.z = -fabsf(_sitl->adsb_altitude_m); double vel_min = 5, vel_max = 20; @@ -81,11 +88,16 @@ void ADSB_Vehicle::update(float delta_t) // it has crashed! reset initialised = false; } + + Location ret = origin; + ret.offset(position.x, position.y); + + location = ret; } -bool ADSB_Vehicle::location(Location &loc) const +const Location &ADSB_Vehicle::get_location() const { - return AP::ahrs().get_location_from_home_offset(loc, position); + return location; } /* @@ -115,18 +127,15 @@ void ADSB::update_simulated_vehicles(const class Aircraft &aircraft) float delta_t = (now_us - last_update_us) * 1.0e-6f; last_update_us = now_us; - const Location &home = aircraft.get_home(); + // prune any aircraft which get too far away from our simulated vehicle: + const Location &aircraft_loc = aircraft.get_location(); for (uint8_t i=0; i _sitl->adsb_radius_m) { + if (aircraft_loc.get_distance(vehicle.get_location()) > _sitl->adsb_radius_m) { vehicle.initialised = false; } } @@ -216,8 +225,6 @@ void ADSB::send_report(const class Aircraft &aircraft) /* send a ADSB_VEHICLE messages */ - const Location &home = aircraft.get_home(); - uint32_t now_us = AP_HAL::micros(); if (now_us - last_report_us >= reporting_period_ms*1000UL) { for (uint8_t i=0; iopos.alt.get() * 1.0e2; set_start_location(loc, sitl->opos.hdg.get()); } +} + +void Aircraft::update_model(const struct sitl_input &input) +{ local_ground_level = 0.0f; update(input); } diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index dd0836fefcbcb3..1c867d56c11286 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -83,6 +83,8 @@ class Aircraft { void update_model(const struct sitl_input &input); + void update_home(); + /* fill a sitl_fdm structure from the simulator state */ void fill_fdm(struct sitl_fdm &fdm); @@ -121,6 +123,8 @@ class Aircraft { config_ = config; } + // return simulation origin: + const Location &get_origin() const { return origin; } const Location &get_location() const { return location; } From 685bdd3d3d190a2fbd62cdacddb6ab3aeb4c4343 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 13:30:01 +1100 Subject: [PATCH 056/499] AP_Camera: handle camera messages as COMMAND_INT as well as COMMAND_LONG --- libraries/AP_Camera/AP_Camera.cpp | 14 +++++++------- libraries/AP_Camera/AP_Camera.h | 10 +++++----- libraries/AP_Camera/AP_Camera_Backend.cpp | 4 ++-- libraries/AP_Camera/AP_Camera_Backend.h | 4 ++-- libraries/AP_Camera/AP_Camera_MAVLink.cpp | 14 +++++++------- libraries/AP_Camera/AP_Camera_MAVLink.h | 4 ++-- libraries/AP_Camera/AP_Camera_Servo.cpp | 2 +- libraries/AP_Camera/AP_Camera_Servo.h | 2 +- 8 files changed, 27 insertions(+), 27 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 7be0cb8e83d58a..19864d0023c55e 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -279,14 +279,14 @@ void AP_Camera::handle_message(mavlink_channel_t chan, const mavlink_message_t & } // handle command_long mavlink messages -MAV_RESULT AP_Camera::handle_command_long(const mavlink_command_long_t &packet) +MAV_RESULT AP_Camera::handle_command(const mavlink_command_int_t &packet) { switch (packet.command) { case MAV_CMD_DO_DIGICAM_CONFIGURE: - configure(packet.param1, packet.param2, packet.param3, packet.param4, packet.param5, packet.param6, packet.param7); + configure(packet.param1, packet.param2, packet.param3, packet.param4, packet.x, packet.y, packet.z); return MAV_RESULT_ACCEPTED; case MAV_CMD_DO_DIGICAM_CONTROL: - control(packet.param1, packet.param2, packet.param3, packet.param4, packet.param5, packet.param6); + control(packet.param1, packet.param2, packet.param3, packet.param4, packet.x, packet.y); return MAV_RESULT_ACCEPTED; case MAV_CMD_DO_SET_CAM_TRIGG_DIST: set_trigger_distance(packet.param1); @@ -438,7 +438,7 @@ void AP_Camera::cam_mode_toggle(uint8_t instance) } // configure camera -void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time) +void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) { WITH_SEMAPHORE(_rsem); @@ -448,7 +448,7 @@ void AP_Camera::configure(float shooting_mode, float shutter_speed, float apertu primary->configure(shooting_mode, shutter_speed, aperture, ISO, exposure_type, cmd_id, engine_cutoff_time); } -void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time) +void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) { WITH_SEMAPHORE(_rsem); @@ -462,7 +462,7 @@ void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_s } // handle camera control -void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id) +void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) { WITH_SEMAPHORE(_rsem); @@ -472,7 +472,7 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo primary->control(session, zoom_pos, zoom_step, focus_lock, shooting_cmd, cmd_id); } -void AP_Camera::control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id) +void AP_Camera::control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) { WITH_SEMAPHORE(_rsem); diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 80221ac6434ba7..929e5d512305b5 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -84,7 +84,7 @@ class AP_Camera { void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg); // handle MAVLink command from GCS to control the camera - MAV_RESULT handle_command_long(const mavlink_command_long_t &packet); + MAV_RESULT handle_command(const mavlink_command_int_t &packet); // send camera feedback message to GCS void send_feedback(mavlink_channel_t chan); @@ -96,12 +96,12 @@ class AP_Camera { void send_camera_settings(mavlink_channel_t chan); // configure camera - void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time); - void configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time); + void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time); + void configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time); // handle camera control - void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id); - void control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id); + void control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id); + void control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id); // set camera trigger distance in a mission void set_trigger_distance(float distance_m); diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index 668053768169a9..738efc75998955 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -161,10 +161,10 @@ void AP_Camera_Backend::stop_capture() } // handle camera control -void AP_Camera_Backend::control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id) +void AP_Camera_Backend::control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) { // take picture - if (is_equal(shooting_cmd, 1.0f)) { + if (shooting_cmd == 1) { take_picture(); } } diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index 5f8f8b1d78fb9c..5ae296c57bd432 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -89,10 +89,10 @@ class AP_Camera_Backend virtual void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) {} // configure camera - virtual void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time) {} + virtual void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) {} // handle camera control - virtual void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id); + virtual void control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id); // set camera trigger distance in meters void set_trigger_distance(float distance_m) { _params.trigg_dist.set(distance_m); } diff --git a/libraries/AP_Camera/AP_Camera_MAVLink.cpp b/libraries/AP_Camera/AP_Camera_MAVLink.cpp index 85b24b2d88314e..3568709f80de41 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLink.cpp +++ b/libraries/AP_Camera/AP_Camera_MAVLink.cpp @@ -19,7 +19,7 @@ bool AP_Camera_MAVLink::trigger_pic() } // configure camera -void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time) +void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) { // convert to mavlink message and send to all components mavlink_command_long_t mav_cmd_long = {}; @@ -30,8 +30,8 @@ void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, floa mav_cmd_long.param2 = shutter_speed; mav_cmd_long.param3 = aperture; mav_cmd_long.param4 = ISO; - mav_cmd_long.param5 = exposure_type; - mav_cmd_long.param6 = cmd_id; + mav_cmd_long.param5 = float(exposure_type); + mav_cmd_long.param6 = float(cmd_id); mav_cmd_long.param7 = engine_cutoff_time; // send to all components @@ -39,10 +39,10 @@ void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, floa } // handle camera control message -void AP_Camera_MAVLink::control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id) +void AP_Camera_MAVLink::control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) { // take picture and ignore other arguments - if (is_equal(shooting_cmd, 1.0f)) { + if (shooting_cmd == 1) { take_picture(); return; } @@ -54,8 +54,8 @@ void AP_Camera_MAVLink::control(float session, float zoom_pos, float zoom_step, mav_cmd_long.param2 = zoom_pos; mav_cmd_long.param3 = zoom_step; mav_cmd_long.param4 = focus_lock; - mav_cmd_long.param5 = shooting_cmd; - mav_cmd_long.param6 = cmd_id; + mav_cmd_long.param5 = float(shooting_cmd); + mav_cmd_long.param6 = float(cmd_id); // send to all components GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&mav_cmd_long, sizeof(mav_cmd_long)); diff --git a/libraries/AP_Camera/AP_Camera_MAVLink.h b/libraries/AP_Camera/AP_Camera_MAVLink.h index 0be92f09c0729c..01840b6389cd80 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLink.h +++ b/libraries/AP_Camera/AP_Camera_MAVLink.h @@ -36,10 +36,10 @@ class AP_Camera_MAVLink : public AP_Camera_Backend bool trigger_pic() override; // configure camera - void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time) override; + void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) override; // handle camera control message - void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id) override; + void control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) override; }; #endif // AP_CAMERA_MAVLINK_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_Servo.cpp b/libraries/AP_Camera/AP_Camera_Servo.cpp index b297576d0347f2..30dd9c385ae3ac 100644 --- a/libraries/AP_Camera/AP_Camera_Servo.cpp +++ b/libraries/AP_Camera/AP_Camera_Servo.cpp @@ -44,7 +44,7 @@ bool AP_Camera_Servo::trigger_pic() } // configure camera -void AP_Camera_Servo::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time) +void AP_Camera_Servo::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) { // designed to control Blackmagic Micro Cinema Camera (BMMCC) cameras // if the message contains non zero values then use them for the below functions diff --git a/libraries/AP_Camera/AP_Camera_Servo.h b/libraries/AP_Camera/AP_Camera_Servo.h index bd2a585b8e0d29..e9edb40387add1 100644 --- a/libraries/AP_Camera/AP_Camera_Servo.h +++ b/libraries/AP_Camera/AP_Camera_Servo.h @@ -39,7 +39,7 @@ class AP_Camera_Servo : public AP_Camera_Backend bool trigger_pic() override; // configure camera - void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time) override; + void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) override; private: From 187ae072256520d34f62ce34dce60f5ea37eb5cf Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 13:30:01 +1100 Subject: [PATCH 057/499] GCS_MAVLink: handle camera messages as COMMAND_INT as well as COMMAND_LONG --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 37 ++++++++++++++-------------- 2 files changed, 20 insertions(+), 19 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index a505f760b9c49e..7ba2c0c2c8b460 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -654,7 +654,7 @@ class GCS_MAVLINK virtual bool mav_frame_for_command_long(MAV_FRAME &fame, MAV_CMD packet_command) const; MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg); MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg); - MAV_RESULT handle_command_camera(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_camera(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc); MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 1d383a1003164f..46e6b3378ec892 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3449,14 +3449,14 @@ void GCS_MAVLINK::handle_system_time_message(const mavlink_message_t &msg) #endif #if AP_CAMERA_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_int_t &packet) { AP_Camera *camera = AP::camera(); if (camera == nullptr) { return MAV_RESULT_UNSUPPORTED; } - return camera->handle_command_long(packet); + return camera->handle_command(packet); } #endif @@ -4725,22 +4725,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t switch (packet.command) { -#if AP_CAMERA_ENABLED - case MAV_CMD_DO_DIGICAM_CONFIGURE: - case MAV_CMD_DO_DIGICAM_CONTROL: - case MAV_CMD_DO_SET_CAM_TRIGG_DIST: - case MAV_CMD_SET_CAMERA_ZOOM: - case MAV_CMD_SET_CAMERA_FOCUS: - case MAV_CMD_IMAGE_START_CAPTURE: - case MAV_CMD_IMAGE_STOP_CAPTURE: - case MAV_CMD_CAMERA_TRACK_POINT: - case MAV_CMD_CAMERA_TRACK_RECTANGLE: - case MAV_CMD_CAMERA_STOP_TRACKING: - case MAV_CMD_VIDEO_START_CAPTURE: - case MAV_CMD_VIDEO_STOP_CAPTURE: - result = handle_command_camera(packet); - break; -#endif #if AP_GRIPPER_ENABLED case MAV_CMD_DO_GRIPPER: result = handle_command_do_gripper(packet); @@ -5037,6 +5021,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_storage_format(const mavlink_command_int_ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch (packet.command) { + #if HAL_INS_ACCELCAL_ENABLED case MAV_CMD_ACCELCAL_VEHICLE_POS: return handle_command_accelcal_vehicle_pos(packet); @@ -5073,6 +5058,22 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p case MAV_CMD_DO_SET_MODE: return handle_command_do_set_mode(packet); +#if AP_CAMERA_ENABLED + case MAV_CMD_DO_DIGICAM_CONFIGURE: + case MAV_CMD_DO_DIGICAM_CONTROL: + case MAV_CMD_DO_SET_CAM_TRIGG_DIST: + case MAV_CMD_SET_CAMERA_ZOOM: + case MAV_CMD_SET_CAMERA_FOCUS: + case MAV_CMD_IMAGE_START_CAPTURE: + case MAV_CMD_IMAGE_STOP_CAPTURE: + case MAV_CMD_CAMERA_TRACK_POINT: + case MAV_CMD_CAMERA_TRACK_RECTANGLE: + case MAV_CMD_CAMERA_STOP_TRACKING: + case MAV_CMD_VIDEO_START_CAPTURE: + case MAV_CMD_VIDEO_STOP_CAPTURE: + return handle_command_camera(packet); +#endif + case MAV_CMD_DO_SET_ROI_NONE: { const Location zero_loc = Location(); return handle_command_do_set_roi(zero_loc); From 0e2261832e5ee1a18ca731cd33a85c9d87529769 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 31 Oct 2023 13:29:17 +1100 Subject: [PATCH 058/499] autotest: more test for emitted digicam command-long messages --- Tools/autotest/rover.py | 50 ++++++++++++++++++++++- libraries/AP_Camera/AP_Camera.cpp | 8 ++-- libraries/AP_Camera/AP_Camera.h | 8 ++-- libraries/AP_Camera/AP_Camera_Backend.cpp | 2 +- libraries/AP_Camera/AP_Camera_Backend.h | 4 +- libraries/AP_Camera/AP_Camera_MAVLink.cpp | 4 +- libraries/AP_Camera/AP_Camera_MAVLink.h | 4 +- libraries/AP_Camera/AP_Camera_Servo.cpp | 2 +- libraries/AP_Camera/AP_Camera_Servo.h | 2 +- 9 files changed, 65 insertions(+), 19 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 2da688ab124107..b61950f1248fb2 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -5620,9 +5620,9 @@ def SendToComponents(self): 0, 0) - self.context_collect('COMMAND_LONG') - self.progress("Sending control message") + self.context_push() + self.context_collect('COMMAND_LONG') self.mav.mav.digicam_control_send( 1, # target_system 1, # target_component @@ -5641,6 +5641,52 @@ def SendToComponents(self): 'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL, 'param6': 17, }, timeout=2, check_context=True) + self.context_pop() + + # test sending via commands: + for run_cmd in self.run_cmd, self.run_cmd_int: + self.progress("Sending control command") + self.context_push() + self.context_collect('COMMAND_LONG') + run_cmd(mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL, + p1=1, # start or keep it up + p2=1, # zoom_pos + p3=0, # zoom_step + p4=0, # focus_lock + p5=0, # 1 shot or start filming + p6=37, # command id (de-dupe field) + ) + + self.assert_received_message_field_values('COMMAND_LONG', { + 'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONTROL, + 'param6': 37, + }, timeout=2, check_context=True) + + self.context_pop() + + # test sending via commands: + for run_cmd in self.run_cmd, self.run_cmd_int: + self.progress("Sending configure command") + self.context_push() + self.context_collect('COMMAND_LONG') + run_cmd(mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONFIGURE, + p1=1, + p2=1, + p3=0, + p4=0, + p5=12, + p6=37 + ) + + self.assert_received_message_field_values('COMMAND_LONG', { + 'command': mavutil.mavlink.MAV_CMD_DO_DIGICAM_CONFIGURE, + 'param5': 12, + 'param6': 37, + }, timeout=2, check_context=True) + + self.context_pop() + + self.mav.mav.srcSystem = old_srcSystem def SkidSteer(self): '''Check skid-steering''' diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 19864d0023c55e..d8f4d67ba9928a 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -438,7 +438,7 @@ void AP_Camera::cam_mode_toggle(uint8_t instance) } // configure camera -void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) +void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) { WITH_SEMAPHORE(_rsem); @@ -448,7 +448,7 @@ void AP_Camera::configure(float shooting_mode, float shutter_speed, float apertu primary->configure(shooting_mode, shutter_speed, aperture, ISO, exposure_type, cmd_id, engine_cutoff_time); } -void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) +void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) { WITH_SEMAPHORE(_rsem); @@ -462,7 +462,7 @@ void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_s } // handle camera control -void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) +void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id) { WITH_SEMAPHORE(_rsem); @@ -472,7 +472,7 @@ void AP_Camera::control(float session, float zoom_pos, float zoom_step, float fo primary->control(session, zoom_pos, zoom_step, focus_lock, shooting_cmd, cmd_id); } -void AP_Camera::control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) +void AP_Camera::control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id) { WITH_SEMAPHORE(_rsem); diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 929e5d512305b5..245bdd60bb1303 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -96,12 +96,12 @@ class AP_Camera { void send_camera_settings(mavlink_channel_t chan); // configure camera - void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time); - void configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time); + void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time); + void configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time); // handle camera control - void control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id); - void control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id); + void control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id); + void control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id); // set camera trigger distance in a mission void set_trigger_distance(float distance_m); diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index 738efc75998955..c936f2127dea59 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -161,7 +161,7 @@ void AP_Camera_Backend::stop_capture() } // handle camera control -void AP_Camera_Backend::control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) +void AP_Camera_Backend::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id) { // take picture if (shooting_cmd == 1) { diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index 5ae296c57bd432..aabe710299473b 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -89,10 +89,10 @@ class AP_Camera_Backend virtual void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) {} // configure camera - virtual void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) {} + virtual void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) {} // handle camera control - virtual void control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id); + virtual void control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id); // set camera trigger distance in meters void set_trigger_distance(float distance_m) { _params.trigg_dist.set(distance_m); } diff --git a/libraries/AP_Camera/AP_Camera_MAVLink.cpp b/libraries/AP_Camera/AP_Camera_MAVLink.cpp index 3568709f80de41..b5bebb91a0944c 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLink.cpp +++ b/libraries/AP_Camera/AP_Camera_MAVLink.cpp @@ -19,7 +19,7 @@ bool AP_Camera_MAVLink::trigger_pic() } // configure camera -void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) +void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) { // convert to mavlink message and send to all components mavlink_command_long_t mav_cmd_long = {}; @@ -39,7 +39,7 @@ void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, floa } // handle camera control message -void AP_Camera_MAVLink::control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) +void AP_Camera_MAVLink::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id) { // take picture and ignore other arguments if (shooting_cmd == 1) { diff --git a/libraries/AP_Camera/AP_Camera_MAVLink.h b/libraries/AP_Camera/AP_Camera_MAVLink.h index 01840b6389cd80..396b31f7ac1f37 100644 --- a/libraries/AP_Camera/AP_Camera_MAVLink.h +++ b/libraries/AP_Camera/AP_Camera_MAVLink.h @@ -36,10 +36,10 @@ class AP_Camera_MAVLink : public AP_Camera_Backend bool trigger_pic() override; // configure camera - void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) override; + void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) override; // handle camera control message - void control(float session, float zoom_pos, float zoom_step, float focus_lock, uint32_t shooting_cmd, uint32_t cmd_id) override; + void control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id) override; }; #endif // AP_CAMERA_MAVLINK_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_Servo.cpp b/libraries/AP_Camera/AP_Camera_Servo.cpp index 30dd9c385ae3ac..80c3d7d7ba41f9 100644 --- a/libraries/AP_Camera/AP_Camera_Servo.cpp +++ b/libraries/AP_Camera/AP_Camera_Servo.cpp @@ -44,7 +44,7 @@ bool AP_Camera_Servo::trigger_pic() } // configure camera -void AP_Camera_Servo::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) +void AP_Camera_Servo::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) { // designed to control Blackmagic Micro Cinema Camera (BMMCC) cameras // if the message contains non zero values then use them for the below functions diff --git a/libraries/AP_Camera/AP_Camera_Servo.h b/libraries/AP_Camera/AP_Camera_Servo.h index e9edb40387add1..7a9afa25d3cb37 100644 --- a/libraries/AP_Camera/AP_Camera_Servo.h +++ b/libraries/AP_Camera/AP_Camera_Servo.h @@ -39,7 +39,7 @@ class AP_Camera_Servo : public AP_Camera_Backend bool trigger_pic() override; // configure camera - void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, uint32_t exposure_type, uint32_t cmd_id, float engine_cutoff_time) override; + void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time) override; private: From 11e541f123ac0e39a33454baa0ce3f91fb8b7392 Mon Sep 17 00:00:00 2001 From: Asif Khan Date: Wed, 20 Sep 2023 11:56:20 +0530 Subject: [PATCH 059/499] AP_Terrain: add get_grid_spacing accessor --- libraries/AP_Terrain/AP_Terrain.h | 5 +++++ libraries/AP_Terrain/TerrainGCS.cpp | 1 - 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index 2321ba1350607c..ff55ce0dbbcb05 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -182,6 +182,11 @@ class AP_Terrain { */ void get_statistics(uint16_t &pending, uint16_t &loaded) const; + /* + get grid spacing in meters + */ + uint16_t get_grid_spacing() const { return MAX(grid_spacing, 0); }; + /* returns true if initialisation failed because out-of-memory */ diff --git a/libraries/AP_Terrain/TerrainGCS.cpp b/libraries/AP_Terrain/TerrainGCS.cpp index 8ad7ae352e2ce2..30a2067c29b5db 100644 --- a/libraries/AP_Terrain/TerrainGCS.cpp +++ b/libraries/AP_Terrain/TerrainGCS.cpp @@ -196,7 +196,6 @@ void AP_Terrain::get_statistics(uint16_t &pending, uint16_t &loaded) const } } - /* handle terrain messages from GCS */ From eb5ead462bee77e2bd209c6d1927f814c85cccb8 Mon Sep 17 00:00:00 2001 From: Asif Khan Date: Thu, 21 Sep 2023 11:36:58 +0900 Subject: [PATCH 060/499] AP_Mount: add get_poi Co-authored-by: Randy Mackay --- libraries/AP_Mount/AP_Mount.cpp | 12 +++ libraries/AP_Mount/AP_Mount.h | 5 + libraries/AP_Mount/AP_Mount_Backend.cpp | 134 ++++++++++++++++++++++++ libraries/AP_Mount/AP_Mount_Backend.h | 21 ++++ libraries/AP_Mount/AP_Mount_config.h | 5 + 5 files changed, 177 insertions(+) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index c7f1701fbfe9e2..ebcf2a0f8cbddd 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -609,6 +609,18 @@ void AP_Mount::send_gimbal_manager_status(mavlink_channel_t chan) } #endif // HAL_GCS_ENABLED +#if AP_MOUNT_POI_TO_LATLONALT_ENABLED +// get poi information. Returns true on success and fills in gimbal attitude, location and poi location +bool AP_Mount::get_poi(uint8_t instance, Quaternion &quat, Location &loc, Location &poi_loc) const +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return false; + } + return backend->get_poi(instance, quat, loc, poi_loc); +} +#endif + // get mount's current attitude in euler angles in degrees. yaw angle is in body-frame // returns true on success bool AP_Mount::get_attitude_euler(uint8_t instance, float& roll_deg, float& pitch_deg, float& yaw_bf_deg) diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 7e8dc661d60289..1dec3ab9d50f9d 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -195,6 +195,11 @@ class AP_Mount // send a GIMBAL_MANAGER_STATUS message to GCS void send_gimbal_manager_status(mavlink_channel_t chan); +#if AP_MOUNT_POI_TO_LATLONALT_ENABLED + // get poi information. Returns true on success and fills in gimbal attitude, location and poi location + bool get_poi(uint8_t instance, Quaternion &quat, Location &loc, Location &poi_loc) const; +#endif + // get mount's current attitude in euler angles in degrees. yaw angle is in body-frame // returns true on success bool get_attitude_euler(uint8_t instance, float& roll_deg, float& pitch_deg, float& yaw_bf_deg); diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index c50ab5a5d5e7b5..ee4c76d6255f54 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -3,16 +3,29 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; #define AP_MOUNT_UPDATE_DT 0.02 // update rate in seconds. update() should be called at this rate +#define AP_MOUNT_POI_REQUEST_TIMEOUT_MS 30000 // POI calculations continue to be updated for this many seconds after last request +#define AP_MOUNT_POI_RESULT_TIMEOUT_MS 3000 // POI calculations valid for 3 seconds +#define AP_MOUNT_POI_DIST_M_MAX 10000 // POI calculations limit of 10,000m (10km) // Default init function for every mount void AP_Mount_Backend::init() { // setting default target sysid from parameters _target_sysid = _params.sysid_default.get(); + +#if AP_MOUNT_POI_TO_LATLONALT_ENABLED + // create a calculation thread for poi. + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Mount_Backend::calculate_poi, void), + "mount_calc_poi", + 8192, AP_HAL::Scheduler::PRIORITY_IO, -1)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Mount: failed to start POI thread"); + } +#endif } // set device id of this instance, for MNTx_DEVID parameter @@ -414,6 +427,127 @@ void AP_Mount_Backend::write_log(uint64_t timestamp_us) AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt)); } +#if AP_MOUNT_POI_TO_LATLONALT_ENABLED +// get poi information. Returns true on success and fills in gimbal attitude, location and poi location +bool AP_Mount_Backend::get_poi(uint8_t instance, Quaternion &quat, Location &loc, Location &poi_loc) +{ + WITH_SEMAPHORE(poi_calculation.sem); + + // record time of request + const uint32_t now_ms = AP_HAL::millis(); + poi_calculation.poi_request_ms = now_ms; + + // check if poi calculated recently + if (now_ms - poi_calculation.poi_update_ms > AP_MOUNT_POI_RESULT_TIMEOUT_MS) { + return false; + } + + // check attitude is valid + if (poi_calculation.att_quat.is_nan()) { + return false; + } + + quat = poi_calculation.att_quat; + loc = poi_calculation.loc; + poi_loc = poi_calculation.poi_loc; + return true; +} + +// calculate the Location that the gimbal is pointing at +void AP_Mount_Backend::calculate_poi() +{ + while (true) { + // run this loop at 10hz + hal.scheduler->delay(100); + + // calculate poi if requested within last 30 seconds + { + WITH_SEMAPHORE(poi_calculation.sem); + if ((poi_calculation.poi_request_ms == 0) || + (AP_HAL::millis() - poi_calculation.poi_request_ms > AP_MOUNT_POI_REQUEST_TIMEOUT_MS)) { + continue; + } + } + + // get the current location of vehicle + const AP_AHRS &ahrs = AP::ahrs(); + Location curr_loc; + if (!ahrs.get_location(curr_loc)) { + continue; + } + + // change vehicle alt to AMSL + curr_loc.change_alt_frame(Location::AltFrame::ABSOLUTE); + + // project forward from vehicle looking for terrain + // start testing at vehicle's location + Location test_loc = curr_loc; + Location prev_test_loc = curr_loc; + + // get terrain altitude (AMSL) at test_loc + auto terrain = AP_Terrain::get_singleton(); + float terrain_amsl_m; + if ((terrain == nullptr) || !terrain->height_amsl(test_loc, terrain_amsl_m, true)) { + continue; + } + + // retrieve gimbal attitude + Quaternion quat; + if (!get_attitude_quaternion(quat)) { + // gimbal attitude unavailable + continue; + } + + // iteratively move test_loc forward until its alt-above-sea-level is below terrain-alt-above-sea-level + const float dist_increment_m = MAX(terrain->get_grid_spacing(), 10); + const float mount_pitch_deg = degrees(quat.get_euler_pitch()); + const float mount_yaw_ef_deg = wrap_180(degrees(quat.get_euler_yaw()) + degrees(ahrs.get_yaw())); + float total_dist_m = 0; + bool get_terrain_alt_success = true; + float prev_terrain_amsl_m = terrain_amsl_m; + while (total_dist_m < AP_MOUNT_POI_DIST_M_MAX && (test_loc.alt * 0.01) > terrain_amsl_m) { + total_dist_m += dist_increment_m; + + // backup previous test location and terrain amsl + prev_test_loc = test_loc; + prev_terrain_amsl_m = terrain_amsl_m; + + // move test location forward + test_loc.offset_bearing_and_pitch(mount_yaw_ef_deg, mount_pitch_deg, dist_increment_m); + + // get terrain's alt-above-sea-level (at test_loc) + // fail if terrain alt cannot be retrieved + if (!terrain->height_amsl(test_loc, terrain_amsl_m, true) || std::isnan(terrain_amsl_m)) { + get_terrain_alt_success = false; + continue; + } + } + + // if a fail occurred above when getting terrain alt then restart calculations from the beginning + if (!get_terrain_alt_success) { + continue; + } + + if (total_dist_m >= AP_MOUNT_POI_DIST_M_MAX) { + // unable to find terrain within dist_max + continue; + } + + // test location has dropped below terrain + // interpolate along line between prev_test_loc and test_loc + float dist_interp_m = linear_interpolate(0, dist_increment_m, 0, prev_test_loc.alt * 0.01 - prev_terrain_amsl_m, test_loc.alt * 0.01 - terrain_amsl_m); + { + WITH_SEMAPHORE(poi_calculation.sem); + poi_calculation.poi_loc = prev_test_loc; + poi_calculation.poi_loc.offset_bearing_and_pitch(mount_yaw_ef_deg, mount_pitch_deg, dist_interp_m); + poi_calculation.att_quat = {quat[0], quat[1], quat[2], quat[3]}; + poi_calculation.loc = curr_loc; + poi_calculation.poi_update_ms = AP_HAL::millis(); + } + } +} +#endif + // get pilot input (in the range -1 to +1) received through RC void AP_Mount_Backend::get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const { diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 7e5563f44e210b..fbd2ca0a801044 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -182,6 +182,11 @@ class AP_Mount_Backend // send camera settings message to GCS virtual void send_camera_settings(mavlink_channel_t chan) const {} +#if AP_MOUNT_POI_TO_LATLONALT_ENABLED + // get poi information. Returns true on success and fills in gimbal attitude, location and poi location + bool get_poi(uint8_t instance, Quaternion &quat, Location &loc, Location &poi_loc); +#endif + // // rangefinder // @@ -221,6 +226,11 @@ class AP_Mount_Backend // returns true if mavlink heartbeat should be suppressed for this gimbal (only used by Solo gimbal) virtual bool suppress_heartbeat() const { return false; } +#if AP_MOUNT_POI_TO_LATLONALT_ENABLED + // calculate the Location that the gimbal is pointing at + void calculate_poi(); +#endif + // get pilot input (in the range -1 to +1) received through RC void get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const; @@ -269,6 +279,17 @@ class AP_Mount_Backend MountTarget rate_rads; // rate target in rad/s } mnt_target; +#if AP_MOUNT_POI_TO_LATLONALT_ENABLED + struct { + HAL_Semaphore sem; // semaphore protecting this structure + uint32_t poi_request_ms; // system time POI was last requested + uint32_t poi_update_ms; // system time POI was calculated + Location loc; // gimbal location used for poi calculation + Location poi_loc; // location of the POI + Quaternion att_quat; // attitude quaternion of the gimbal + } poi_calculation; +#endif + Location _roi_target; // roi target location bool _roi_target_set; // true if the roi target has been set diff --git a/libraries/AP_Mount/AP_Mount_config.h b/libraries/AP_Mount/AP_Mount_config.h index 3195a5ce387d47..9159653dcc79e7 100644 --- a/libraries/AP_Mount/AP_Mount_config.h +++ b/libraries/AP_Mount/AP_Mount_config.h @@ -1,6 +1,7 @@ #pragma once #include +#include #ifndef HAL_MOUNT_ENABLED #define HAL_MOUNT_ENABLED 1 @@ -48,3 +49,7 @@ #ifndef HAL_MOUNT_VIEWPRO_ENABLED #define HAL_MOUNT_VIEWPRO_ENABLED AP_MOUNT_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024 #endif + +#ifndef AP_MOUNT_POI_TO_LATLONALT_ENABLED +#define AP_MOUNT_POI_TO_LATLONALT_ENABLED HAL_MOUNT_ENABLED && AP_TERRAIN_AVAILABLE && BOARD_FLASH_SIZE > 1024 +#endif From 2235a8e0636fded40fdf465756d507635e71ba79 Mon Sep 17 00:00:00 2001 From: Asif Khan Date: Thu, 21 Sep 2023 11:37:23 +0900 Subject: [PATCH 061/499] AP_Camera: add send_camera_fov_status support --- libraries/AP_Camera/AP_Camera.cpp | 15 +++++++++ libraries/AP_Camera/AP_Camera.h | 5 +++ libraries/AP_Camera/AP_Camera_Backend.cpp | 39 +++++++++++++++++++++++ libraries/AP_Camera/AP_Camera_Backend.h | 5 +++ libraries/AP_Camera/AP_Camera_config.h | 4 +++ 5 files changed, 68 insertions(+) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index d8f4d67ba9928a..b3583a8468df60 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -526,6 +526,21 @@ void AP_Camera::send_camera_settings(mavlink_channel_t chan) } } +#if AP_CAMERA_SEND_FOV_STATUS_ENABLED +// send camera field of view status +void AP_Camera::send_camera_fov_status(mavlink_channel_t chan) +{ + WITH_SEMAPHORE(_rsem); + + // call each instance + for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) { + if (_backends[instance] != nullptr) { + _backends[instance]->send_camera_fov_status(chan); + } + } +} +#endif + /* update; triggers by distance moved and camera trigger */ diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 245bdd60bb1303..f0f384a1991857 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -95,6 +95,11 @@ class AP_Camera { // send camera settings message to GCS void send_camera_settings(mavlink_channel_t chan); +#if AP_CAMERA_SEND_FOV_STATUS_ENABLED + // send camera field of view status + void send_camera_fov_status(mavlink_channel_t chan); +#endif + // configure camera void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time); void configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time); diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index c936f2127dea59..94613beef107c3 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -247,6 +247,45 @@ void AP_Camera_Backend::send_camera_settings(mavlink_channel_t chan) const NaN); // focusLevel float, percentage from 0 to 100, NaN if unknown } +#if AP_CAMERA_SEND_FOV_STATUS_ENABLED +// send camera field of view status +void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const +{ + // getting corresponding mount instance for camera + const AP_Mount* mount = AP::mount(); + if (mount == nullptr) { + return; + } + Quaternion quat; + Location loc; + Location poi_loc; + if (!mount->get_poi(get_mount_instance(), quat, loc, poi_loc)) { + return; + } + // send camera fov status message only if the last calculated values aren't stale + const float NaN = nanf("0x4152"); + const float quat_array[4] = { + quat.q1, + quat.q2, + quat.q3, + quat.q4 + }; + mavlink_msg_camera_fov_status_send( + chan, + AP_HAL::millis(), + loc.lat, + loc.lng, + loc.alt, + poi_loc.lat, + poi_loc.lng, + poi_loc.alt, + quat_array, + NaN, // currently setting hfov as NaN + NaN // currently setting vfov as NaN + ); +} +#endif + // setup a callback for a feedback pin. When on PX4 with the right FMU // mode we can use the microsecond timer. void AP_Camera_Backend::setup_feedback_callback() diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index aabe710299473b..ad2fa95544b48b 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -106,6 +106,11 @@ class AP_Camera_Backend // send camera settings message to GCS virtual void send_camera_settings(mavlink_channel_t chan) const; +#if AP_CAMERA_SEND_FOV_STATUS_ENABLED + // send camera field of view status + void send_camera_fov_status(mavlink_channel_t chan) const; +#endif + #if AP_CAMERA_SCRIPTING_ENABLED // accessor to allow scripting backend to retrieve state // returns true on success and cam_state is filled in diff --git a/libraries/AP_Camera/AP_Camera_config.h b/libraries/AP_Camera/AP_Camera_config.h index 565c344f31e808..b153c479639486 100644 --- a/libraries/AP_Camera/AP_Camera_config.h +++ b/libraries/AP_Camera/AP_Camera_config.h @@ -9,6 +9,10 @@ #define AP_CAMERA_ENABLED 1 #endif +#ifndef AP_CAMERA_SEND_FOV_STATUS_ENABLED +#define AP_CAMERA_SEND_FOV_STATUS_ENABLED AP_MOUNT_POI_TO_LATLONALT_ENABLED +#endif + #ifndef AP_CAMERA_BACKEND_DEFAULT_ENABLED #define AP_CAMERA_BACKEND_DEFAULT_ENABLED AP_CAMERA_ENABLED #endif From 8a791d60824be7bc81693990b6bcff3656d0f2ba Mon Sep 17 00:00:00 2001 From: Asif Khan Date: Thu, 21 Sep 2023 11:38:00 +0900 Subject: [PATCH 062/499] GCS_MAVLink: add SEND_FOV_STATUS support --- libraries/GCS_MAVLink/GCS_Common.cpp | 13 +++++++++++++ libraries/GCS_MAVLink/ap_message.h | 1 + 2 files changed, 14 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 46e6b3378ec892..0cff164fd2944f 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -998,6 +998,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK}, { MAVLINK_MSG_ID_CAMERA_INFORMATION, MSG_CAMERA_INFORMATION}, { MAVLINK_MSG_ID_CAMERA_SETTINGS, MSG_CAMERA_SETTINGS}, + { MAVLINK_MSG_ID_CAMERA_FOV_STATUS, MSG_CAMERA_FOV_STATUS}, #endif #if HAL_MOUNT_ENABLED { MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS}, @@ -5775,6 +5776,18 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) camera->send_camera_settings(chan); } break; +#if AP_CAMERA_SEND_FOV_STATUS_ENABLED + case MSG_CAMERA_FOV_STATUS: + { + AP_Camera *camera = AP::camera(); + if (camera == nullptr) { + break; + } + CHECK_PAYLOAD_SIZE(CAMERA_FOV_STATUS); + camera->send_camera_fov_status(chan); + } + break; +#endif #endif case MSG_SYSTEM_TIME: diff --git a/libraries/GCS_MAVLink/ap_message.h b/libraries/GCS_MAVLink/ap_message.h index 6b4fbb0e295878..3a707bc4628d82 100644 --- a/libraries/GCS_MAVLink/ap_message.h +++ b/libraries/GCS_MAVLink/ap_message.h @@ -51,6 +51,7 @@ enum ap_message : uint8_t { MSG_CAMERA_FEEDBACK, MSG_CAMERA_INFORMATION, MSG_CAMERA_SETTINGS, + MSG_CAMERA_FOV_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_MANAGER_INFORMATION, MSG_GIMBAL_MANAGER_STATUS, From 6528394797ade6d907a0e4d9436cd82af577e816 Mon Sep 17 00:00:00 2001 From: Asif Khan Date: Thu, 21 Sep 2023 11:38:18 +0900 Subject: [PATCH 063/499] Tools: custom build server support for SEND_FOV_STATUS --- Tools/scripts/build_options.py | 1 + Tools/scripts/extract_features.py | 1 + 2 files changed, 2 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 1e92c7baa8a185..7ec8811fef8951 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -123,6 +123,7 @@ def __init__(self, Feature('Camera', 'Camera_Relay', 'AP_CAMERA_RELAY_ENABLED', 'Enable Camera Trigger via Relay support', 0, 'Camera,RELAY'), Feature('Camera', 'Camera_Servo', 'AP_CAMERA_SERVO_ENABLED', 'Enable Camera Trigger via Servo support', 0, 'Camera'), Feature('Camera', 'Camera_Solo', 'AP_CAMERA_SOLOGIMBAL_ENABLED', 'Enable Solo Gimbal support', 0, 'Camera'), + Feature('Camera', 'Camera_FOV_Status', 'AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'Enable Camera FOV Status send to GCS', 0, 'Camera,MOUNT'), # noqa: E501 Feature('Camera', 'RUNCAM', 'HAL_RUNCAM_ENABLED', 'Enable RunCam Control', 0, None), diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 5e0285fa9bdd8d..e847065e833bad 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -122,6 +122,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_CAMERA_ENABLED', 'AP_Camera::var_info',), ('AP_CAMERA_{type}_ENABLED', 'AP_Camera_(?P.*)::trigger_pic',), + ('AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'AP_Camera::send_camera_fov_status'), ('HAL_RUNCAM_ENABLED', 'AP_RunCam::AP_RunCam',), ('HAL_PROXIMITY_ENABLED', 'AP_Proximity::AP_Proximity',), From fb26bbfc4cadabd69ba9925216f93ddf8c72ede2 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Tue, 17 Oct 2023 16:33:02 +1100 Subject: [PATCH 064/499] AP_DroneCAN: add support for detecting downed link --- libraries/AP_DroneCAN/AP_Canard_iface.cpp | 29 +++++++++++++++++++---- 1 file changed, 25 insertions(+), 4 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index 540120564d8075..5fa96606f5be43 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.cpp +++ b/libraries/AP_DroneCAN/AP_Canard_iface.cpp @@ -214,6 +214,20 @@ void CanardInterface::processTx(bool raw_commands_only = false) { if (txq == nullptr) { return; } + // volatile as the value can change at any time during can interrupt + // we need to ensure that this is not optimized + volatile const auto *stats = ifaces[iface]->get_statistics(); + uint64_t last_transmit_us = stats->last_transmit_us; + bool iface_down = true; + if (stats == nullptr || (AP_HAL::micros64() - last_transmit_us) < 200000UL) { + /* + We were not able to queue the frame for + sending. Only mark the send as failing if the + interface is active. We consider an interface as + active if it has had successful transmits for some time. + */ + iface_down = false; + } // scan through list of pending transfers while (true) { auto txf = &txq->frame; @@ -240,15 +254,22 @@ void CanardInterface::processTx(bool raw_commands_only = false) { if (!write) { // if there is no space then we need to start from the // top of the queue, so wait for the next loop - break; - } - if ((txf->iface_mask & (1U<deadline_usec)) { + if (!iface_down) { + break; + } else { + txf->iface_mask &= ~(1U<iface_mask & (1U<deadline_usec)) { // try sending to interfaces, clearing the mask if we succeed if (ifaces[iface]->send(txmsg, txf->deadline_usec, 0) > 0) { txf->iface_mask &= ~(1U<iface_mask &= ~(1U< Date: Wed, 1 Nov 2023 16:04:23 +1100 Subject: [PATCH 065/499] AP_Periph: solve a potential case where last_transmit_us can change inside irqs --- Tools/AP_Periph/can.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index deadcd03f36f71..01adff69a5f60c 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -1136,8 +1136,9 @@ void AP_Periph_FW::processTx(void) active if it has had a successful transmit in the last 2 seconds */ - const auto *stats = _ins.iface->get_statistics(); - if (stats == nullptr || now_us - stats->last_transmit_us < 2000000UL) { + volatile const auto *stats = _ins.iface->get_statistics(); + uint64_t last_transmit_us = stats->last_transmit_us; + if (stats == nullptr || AP_HAL::micros64() - last_transmit_us < 2000000UL) { sent = false; } } else { From 7d4d2f98bf98512e645288982961bd5aad61194a Mon Sep 17 00:00:00 2001 From: jfbblue0922 Date: Thu, 2 Nov 2023 10:31:09 +0900 Subject: [PATCH 066/499] AP_HAL_ChibiOS: corrected analog input pin number --- libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md index 87f58272ae8af7..a5f52fdd550d87 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/README.md @@ -113,8 +113,8 @@ The JFB-110 has 9 analog inputs - ADC Pin5 -> ADC 5V Sense - ADC Pin11 -> ADC 3.3V Sense - ADC Pin10 -> RSSI voltage monitoring - - ADC Pin12 -> ADC SPARE 1 - - ADC Pin13 -> ADC SPARE 2 + - ADC Pin13 -> ADC SPARE 1 + - ADC Pin12 -> ADC SPARE 2 ## I2C Buses From 73589a276e2c74f34abe34297ab5a8d35d0d0504 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 2 Nov 2023 12:34:31 +0900 Subject: [PATCH 067/499] AP_Camera: camera_fov_status includes field-of-view --- libraries/AP_Camera/AP_Camera_Backend.cpp | 4 ++-- libraries/AP_Camera/AP_Camera_Backend.h | 4 ++++ libraries/AP_Camera/AP_Camera_Params.cpp | 16 ++++++++++++++++ libraries/AP_Camera/AP_Camera_Params.h | 2 ++ 4 files changed, 24 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index 94613beef107c3..abda67057dfae8 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -280,8 +280,8 @@ void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const poi_loc.lng, poi_loc.alt, quat_array, - NaN, // currently setting hfov as NaN - NaN // currently setting vfov as NaN + horizontal_fov() > 0 ? horizontal_fov() : NaN, + vertical_fov() > 0 ? vertical_fov() : NaN ); } #endif diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index ad2fa95544b48b..bae4fb8ea291eb 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -85,6 +85,10 @@ class AP_Camera_Backend // set camera lens as a value from 0 to 5 virtual bool set_lens(uint8_t lens) { return false; } + // get camera image horizontal or vertical field of view in degrees. returns 0 if unknown + float horizontal_fov() const { return MAX(0, _params.hfov); } + float vertical_fov() const { return MAX(0, _params.vfov); } + // handle MAVLink messages from the camera virtual void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) {} diff --git a/libraries/AP_Camera/AP_Camera_Params.cpp b/libraries/AP_Camera/AP_Camera_Params.cpp index ee3f7796590ab7..7b32ca60cf1bb8 100644 --- a/libraries/AP_Camera/AP_Camera_Params.cpp +++ b/libraries/AP_Camera/AP_Camera_Params.cpp @@ -87,6 +87,22 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = { // @User: Standard AP_GROUPINFO("_MNT_INST", 11, AP_Camera_Params, mount_instance, 0), + // @Param: _HFOV + // @DisplayName: Camera horizontal field of view + // @Description: Camera horizontal field of view. 0 if unknown + // @Units: deg + // @Range: 0 360 + // @User: Standard + AP_GROUPINFO("_HFOV", 12, AP_Camera_Params, hfov, 0), + + // @Param: _VFOV + // @DisplayName: Camera vertical field of view + // @Description: Camera vertical field of view. 0 if unknown + // @Units: deg + // @Range: 0 180 + // @User: Standard + AP_GROUPINFO("_VFOV", 13, AP_Camera_Params, vfov, 0), + AP_GROUPEND }; diff --git a/libraries/AP_Camera/AP_Camera_Params.h b/libraries/AP_Camera/AP_Camera_Params.h index ca54550fe1ddbe..cba713a16319ea 100644 --- a/libraries/AP_Camera/AP_Camera_Params.h +++ b/libraries/AP_Camera/AP_Camera_Params.h @@ -23,6 +23,8 @@ class AP_Camera_Params { AP_Float interval_min; // minimum time (in seconds) between shots required by camera AP_Int8 options; // whether to start recording when armed and stop when disarmed AP_Int8 mount_instance; // mount instance to which camera is associated with + AP_Float hfov; // horizontal field of view in degrees + AP_Float vfov; // vertical field of view in degrees // pin number for accurate camera feedback messages AP_Int8 feedback_pin; From b79e96ab57663122151deb61cc46adfa1b276c97 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 24 Oct 2023 19:30:05 +1100 Subject: [PATCH 068/499] Filter: protect against extremely low notch filter frequencies an incorrectly configured ESC telemetry source can lead to a notch running at very low frequencies. A simple example is a lua script like this: function update() esc_telem:update_rpm(12, 0, 0) return update, 10 end return update() where motor 12 is unused. with that script in place we get a 1.0078 Hz filter which leads to massive phase lag and a crashed aircraft this is a safety protection. We should also try to find out why the INS_HNTCH_FREQ lower limit is not working --- libraries/Filter/NotchFilter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/Filter/NotchFilter.cpp b/libraries/Filter/NotchFilter.cpp index ea2a77d80faabb..14ce778efa4cf2 100644 --- a/libraries/Filter/NotchFilter.cpp +++ b/libraries/Filter/NotchFilter.cpp @@ -71,7 +71,7 @@ void NotchFilter::init_with_A_and_Q(float sample_freq_hz, float center_freq_h _center_freq_hz * NOTCH_MAX_SLEW_UPPER); } - if ((new_center_freq > 0.0) && (new_center_freq < 0.5 * sample_freq_hz) && (Q > 0.0)) { + if ((new_center_freq > 2.0) && (new_center_freq < 0.5 * sample_freq_hz) && (Q > 0.0)) { float omega = 2.0 * M_PI * new_center_freq / sample_freq_hz; float alpha = sinf(omega) / (2 * Q); b0 = 1.0 + alpha*sq(A); From 1bf7c9ee776797e160e75295da430b33977db9df Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 25 Oct 2023 17:48:48 +1100 Subject: [PATCH 069/499] AP_ESC_Telem: added stale() method for ESC telem prevents use of stale data when close to zero time --- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp | 16 ++++++++-------- libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp | 13 ++++++++++++- libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h | 3 +++ 3 files changed, 23 insertions(+), 9 deletions(-) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 9945d16ce45784..0ebc163c2d27ed 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -107,7 +107,7 @@ uint32_t AP_ESC_Telem::get_active_esc_mask() const { // have never seen telem from this ESC continue; } - if (now - _telem_data[i].last_update_ms >= ESC_TELEM_DATA_TIMEOUT_MS + if (_telem_data[i].stale(now) && !rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) { continue; } @@ -211,7 +211,7 @@ bool AP_ESC_Telem::get_raw_rpm(uint8_t esc_index, float& rpm) const bool AP_ESC_Telem::get_temperature(uint8_t esc_index, int16_t& temp) const { if (esc_index >= ESC_TELEM_MAX_ESCS - || AP_HAL::millis() - _telem_data[esc_index].last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS + || _telem_data[esc_index].stale() || !(_telem_data[esc_index].types & (AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE | AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL))) { return false; } @@ -223,7 +223,7 @@ bool AP_ESC_Telem::get_temperature(uint8_t esc_index, int16_t& temp) const bool AP_ESC_Telem::get_motor_temperature(uint8_t esc_index, int16_t& temp) const { if (esc_index >= ESC_TELEM_MAX_ESCS - || AP_HAL::millis() - _telem_data[esc_index].last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS + || _telem_data[esc_index].stale() || !(_telem_data[esc_index].types & (AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE | AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL))) { return false; } @@ -251,7 +251,7 @@ bool AP_ESC_Telem::get_highest_motor_temperature(int16_t& temp) const bool AP_ESC_Telem::get_current(uint8_t esc_index, float& amps) const { if (esc_index >= ESC_TELEM_MAX_ESCS - || AP_HAL::millis() - _telem_data[esc_index].last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS + || _telem_data[esc_index].stale() || !(_telem_data[esc_index].types & AP_ESC_Telem_Backend::TelemetryType::CURRENT)) { return false; } @@ -263,7 +263,7 @@ bool AP_ESC_Telem::get_current(uint8_t esc_index, float& amps) const bool AP_ESC_Telem::get_voltage(uint8_t esc_index, float& volts) const { if (esc_index >= ESC_TELEM_MAX_ESCS - || AP_HAL::millis() - _telem_data[esc_index].last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS + || _telem_data[esc_index].stale() || !(_telem_data[esc_index].types & AP_ESC_Telem_Backend::TelemetryType::VOLTAGE)) { return false; } @@ -275,7 +275,7 @@ bool AP_ESC_Telem::get_voltage(uint8_t esc_index, float& volts) const bool AP_ESC_Telem::get_consumption_mah(uint8_t esc_index, float& consumption_mah) const { if (esc_index >= ESC_TELEM_MAX_ESCS - || AP_HAL::millis() - _telem_data[esc_index].last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS + || _telem_data[esc_index].stale() || !(_telem_data[esc_index].types & AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION)) { return false; } @@ -287,7 +287,7 @@ bool AP_ESC_Telem::get_consumption_mah(uint8_t esc_index, float& consumption_mah bool AP_ESC_Telem::get_usage_seconds(uint8_t esc_index, uint32_t& usage_s) const { if (esc_index >= ESC_TELEM_MAX_ESCS - || AP_HAL::millis() - _telem_data[esc_index].last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS + || _telem_data[esc_index].stale() || !(_telem_data[esc_index].types & AP_ESC_Telem_Backend::TelemetryType::USAGE)) { return false; } @@ -324,7 +324,7 @@ void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan) for (uint8_t j=0; j<4; j++) { const uint8_t esc_id = (i * 4 + j) + esc_offset; if (esc_id < ESC_TELEM_MAX_ESCS && - (now - _telem_data[esc_id].last_update_ms <= ESC_TELEM_DATA_TIMEOUT_MS || + (!_telem_data[esc_id].stale(now) || rpm_data_within_timeout(_rpm_data[esc_id], now_us, ESC_RPM_DATA_TIMEOUT_US))) { all_stale = false; break; diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp index b104c835628210..0048571452f230 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp @@ -40,4 +40,15 @@ void AP_ESC_Telem_Backend::update_telem_data(const uint8_t esc_index, const Tele _frontend->update_telem_data(esc_index, new_data, data_present_mask); } -#endif \ No newline at end of file +/* + return true if the data is stale + */ +bool AP_ESC_Telem_Backend::TelemetryData::stale(uint32_t now_ms) const volatile +{ + if (now_ms == 0) { + now_ms = AP_HAL::millis(); + } + return last_update_ms == 0 || now_ms - last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS; +} + +#endif diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h index e40c09b64a3c9e..b6d6725a55fa15 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.h @@ -19,6 +19,9 @@ class AP_ESC_Telem_Backend { uint32_t last_update_ms; // last update time in milliseconds, determines whether active uint16_t types; // telemetry types present uint16_t count; // number of times updated + + // return true if the data is stale + bool stale(uint32_t now_ms=0) const volatile; }; struct RpmData { From 6273fee8928f16d796bd6975a7c81ef27836f6e7 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 8 Aug 2023 20:58:51 -0600 Subject: [PATCH 070/499] AP_GPS: Rename GSOF packing functions * Added docs for why they exist Signed-off-by: Ryan Friedman --- libraries/SITL/SIM_GPS.cpp | 18 ++++++++---------- libraries/SITL/SIM_GPS.h | 6 ++++-- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 67cc25b31db3c4..1b73e48899bcea 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -1086,9 +1086,9 @@ void GPS_GSOF::update_write(const GPS_Data *d) } pos { GSOF_POS_TYPE, GSOF_POS_LEN, - pack_double_into_gsof_packet(d->latitude * DEG_TO_RAD_DOUBLE), - pack_double_into_gsof_packet(d->longitude * DEG_TO_RAD_DOUBLE), - pack_double_into_gsof_packet(static_cast(d->altitude)) + gsof_pack_double(d->latitude * DEG_TO_RAD_DOUBLE), + gsof_pack_double(d->longitude * DEG_TO_RAD_DOUBLE), + gsof_pack_double(static_cast(d->altitude)) }; static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN); @@ -1127,11 +1127,11 @@ void GPS_GSOF::update_write(const GPS_Data *d) GSOF_VEL_TYPE, GSOF_VEL_LEN, vel_flags, - pack_float_into_gsof_packet(d->speed_2d()), - pack_float_into_gsof_packet(d->heading()), + gsof_pack_float(d->speed_2d()), + gsof_pack_float(d->heading()), // Trimble API has ambiguous direction here. // Intentionally narrow from double. - pack_float_into_gsof_packet(static_cast(d->speedD)) + gsof_pack_float(static_cast(d->speedD)) }; static_assert(sizeof(gsof_vel) - (sizeof(gsof_vel::OUTPUT_RECORD_TYPE) + sizeof(gsof_vel::RECORD_LEN)) == GSOF_VEL_LEN); @@ -1219,7 +1219,6 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) TRANSMISSION_NUMBER, PAGE_INDEX, MAX_PAGE_INDEX, - }; ++TRANSMISSION_NUMBER; @@ -1245,7 +1244,6 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) }; - // Sum bytes (status + type + length + data bytes) and modulo 256 the summation // Because it's a uint8, use natural overflow uint8_t csum = STATUS + PACKET_TYPE + length; @@ -1273,7 +1271,7 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) } } -uint64_t GPS_GSOF::pack_double_into_gsof_packet(const double& src) +uint64_t GPS_GSOF::gsof_pack_double(const double& src) { uint64_t dst; static_assert(sizeof(src) == sizeof(dst)); @@ -1282,7 +1280,7 @@ uint64_t GPS_GSOF::pack_double_into_gsof_packet(const double& src) return dst; } -uint32_t GPS_GSOF::pack_float_into_gsof_packet(const float& src) +uint32_t GPS_GSOF::gsof_pack_float(const float& src) { uint32_t dst; static_assert(sizeof(src) == sizeof(dst)); diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index 746a5832a777a0..a4648c6123d9c3 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -113,8 +113,10 @@ class GPS_GSOF : public GPS_Backend { private: void send_gsof(const uint8_t *buf, const uint16_t size); - uint64_t pack_double_into_gsof_packet(const double& src) WARN_IF_UNUSED; - uint32_t pack_float_into_gsof_packet(const float& src) WARN_IF_UNUSED; + // These packing utilities for GSOF perform a type-safe floating point byteswap. + // They return integer types because returning floating points would involve an extra copy. + uint64_t gsof_pack_double(const double& src) WARN_IF_UNUSED; + uint32_t gsof_pack_float(const float& src) WARN_IF_UNUSED; }; class GPS_NMEA : public GPS_Backend { From 369f369f1dd4fd023b5483c202705cef004e9082 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 3 Nov 2023 19:48:23 +1100 Subject: [PATCH 071/499] AP_Mount: fixed SIYI parser bug this caused lots of lost packets --- libraries/AP_Mount/AP_Mount_Siyi.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index 714a9cadd694e8..1e4c54c8bf6949 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -302,6 +302,7 @@ void AP_Mount_Siyi::read_incoming_packets() if (reset_parser) { _parsed_msg.state = ParseState::WAITING_FOR_HEADER_LOW; _msg_buff_len = 0; + reset_parser = false; } } } From 55040175e686afd5126f5b44e02d4f018d8977e8 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 1 Nov 2023 14:56:54 +0000 Subject: [PATCH 072/499] Plane: Cruise: only lock in heading once moving forwards --- ArduPlane/mode_cruise.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/ArduPlane/mode_cruise.cpp b/ArduPlane/mode_cruise.cpp index 57d3bcb4bee2da..2d8c4c428c2424 100644 --- a/ArduPlane/mode_cruise.cpp +++ b/ArduPlane/mode_cruise.cpp @@ -58,11 +58,17 @@ void ModeCruise::navigate() return; } #endif + + // check if we are moving in the direction of the front of the vehicle + const int32_t ground_course_cd = plane.gps.ground_course_cd(); + const bool moving_forwards = fabsf(wrap_PI(radians(ground_course_cd * 0.01) - plane.ahrs.yaw)) < M_PI_2; + if (!locked_heading && plane.channel_roll->get_control_in() == 0 && plane.rudder_input() == 0 && plane.gps.status() >= AP_GPS::GPS_OK_FIX_2D && plane.gps.ground_speed() >= 3 && + moving_forwards && lock_timer_ms == 0) { // user wants to lock the heading - start the timer lock_timer_ms = millis(); @@ -73,7 +79,7 @@ void ModeCruise::navigate() // from user locked_heading = true; lock_timer_ms = 0; - locked_heading_cd = plane.gps.ground_course_cd(); + locked_heading_cd = ground_course_cd; plane.prev_WP_loc = plane.current_loc; } if (locked_heading) { From 66b8fd95adeb2b5eb05e4fa32a35795b51d5a650 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Thu, 2 Nov 2023 16:20:33 +0000 Subject: [PATCH 073/499] AP_Scripting: add binding for GCS last seen time --- libraries/AP_Scripting/docs/docs.lua | 4 ++++ libraries/AP_Scripting/generator/description/bindings.desc | 2 ++ 2 files changed, 6 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index b88227fdbbfaf9..e1560bbd8e4e60 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -2312,6 +2312,10 @@ function gcs:get_high_latency_status() end ---@param text string function gcs:send_text(severity, text) end +-- Return the system time when a gcs with id of SYSID_MYGCS was last seen +---@return uint32_t_ud -- system time in milliseconds +function gcs:last_seen() end + -- desc ---@class relay relay = {} diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 69a2d1f27f347e..038db48be8b995 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -248,6 +248,8 @@ singleton GCS method set_message_interval MAV_RESULT'enum uint8_t 0 MAVLINK_COMM singleton GCS method send_named_float void string float'skip_check singleton GCS method frame_type MAV_TYPE'enum singleton GCS method get_hud_throttle int16_t +singleton GCS method sysid_myggcs_last_seen_time_ms uint32_t +singleton GCS method sysid_myggcs_last_seen_time_ms rename last_seen singleton GCS method get_high_latency_status boolean singleton GCS method get_high_latency_status depends HAL_HIGH_LATENCY2_ENABLED == 1 From 96f5a1cb2b4b1a25f3e07c12f4cd0f191f418fc4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 1 Nov 2023 15:16:22 +1100 Subject: [PATCH 074/499] AP_Scripting: added bindings for telemetry data for ESCs allows more complete ESC protocol implementation in scripting --- libraries/AP_Scripting/docs/docs.lua | 35 ++++++++++++++++++- .../generator/description/bindings.desc | 10 ++++++ 2 files changed, 44 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index e1560bbd8e4e60..1fcf77384a4956 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -1733,12 +1733,45 @@ function param:add_table(table_key, prefix, num_params) end ---@return boolean function param:add_param(table_key, param_num, name, default_value) end +-- desc +---@class ESCTelemetryData_ud +local ESCTelemetryData_ud = {} + +---@return ESCTelemetryData_ud +function ESCTelemetryData() end + +-- set motor temperature +---@param value integer +function ESCTelemetryData_ud:motor_temp_cdeg(value) end + +-- set consumption +---@param value number +function ESCTelemetryData_ud:consumption_mah(value) end + +-- set current +---@param value number +function ESCTelemetryData_ud:current(value) end + +-- set voltage +---@param value number +function ESCTelemetryData_ud:voltage(value) end + +-- set temperature +---@param value integer +function ESCTelemetryData_ud:temperature_cdeg(value) end + -- desc ---@class esc_telem esc_telem = {} +-- update telemetry data for an ESC instance +---@param instance integer -- 0 is first motor +---@param telemdata ESCTelemetryData_ud +---@param data_mask integer -- bit mask of what fields are filled in +function esc_telem:update_telem_data(instance, telemdata, data_mask) end + -- desc ----@param instance integer +---@param param1 integer ---@return uint32_t_ud|nil function esc_telem:get_usage_seconds(instance) end diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 038db48be8b995..b830b16b9d1207 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -382,6 +382,15 @@ singleton AP_OpticalFlow method healthy boolean singleton AP_OpticalFlow method quality uint8_t include AP_ESC_Telem/AP_ESC_Telem.h + +userdata AP_ESC_Telem_Backend::TelemetryData depends (HAL_WITH_ESC_TELEM == 1) +userdata AP_ESC_Telem_Backend::TelemetryData rename ESCTelemetryData +userdata AP_ESC_Telem_Backend::TelemetryData field temperature_cdeg int16_t'skip_check write +userdata AP_ESC_Telem_Backend::TelemetryData field voltage float'skip_check write +userdata AP_ESC_Telem_Backend::TelemetryData field current float'skip_check write +userdata AP_ESC_Telem_Backend::TelemetryData field consumption_mah float'skip_check write +userdata AP_ESC_Telem_Backend::TelemetryData field motor_temp_cdeg int16_t'skip_check write + singleton AP_ESC_Telem depends HAL_WITH_ESC_TELEM == 1 singleton AP_ESC_Telem rename esc_telem singleton AP_ESC_Telem method get_rpm boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null @@ -392,6 +401,7 @@ singleton AP_ESC_Telem method get_voltage boolean uint8_t 0 NUM_SERVO_CHANNELS f singleton AP_ESC_Telem method get_consumption_mah boolean uint8_t 0 NUM_SERVO_CHANNELS float'Null singleton AP_ESC_Telem method get_usage_seconds boolean uint8_t 0 NUM_SERVO_CHANNELS uint32_t'Null singleton AP_ESC_Telem method update_rpm void uint8_t 0 NUM_SERVO_CHANNELS uint16_t'skip_check float'skip_check +singleton AP_ESC_Telem method update_telem_data void uint8_t 0 NUM_SERVO_CHANNELS AP_ESC_Telem_Backend::TelemetryData uint16_t'skip_check singleton AP_ESC_Telem method set_rpm_scale void uint8_t 0 NUM_SERVO_CHANNELS float'skip_check include AP_Param/AP_Param.h From c1831bae320c00338307c7c5f15e1b6b6b50abcc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 1 Nov 2023 15:07:45 +1100 Subject: [PATCH 075/499] AP_Scripting: added HobbyWing DataLink lua driver --- .../drivers/Hobbywing_DataLink.lua | 228 ++++++++++++++++++ .../drivers/Hobbywing_DataLink.md | 57 +++++ 2 files changed, 285 insertions(+) create mode 100644 libraries/AP_Scripting/drivers/Hobbywing_DataLink.lua create mode 100644 libraries/AP_Scripting/drivers/Hobbywing_DataLink.md diff --git a/libraries/AP_Scripting/drivers/Hobbywing_DataLink.lua b/libraries/AP_Scripting/drivers/Hobbywing_DataLink.lua new file mode 100644 index 00000000000000..d1be31dfad657a --- /dev/null +++ b/libraries/AP_Scripting/drivers/Hobbywing_DataLink.lua @@ -0,0 +1,228 @@ +--[[ + driver for HobbyWing DataLink ESC telemetry +--]] + +local PARAM_TABLE_KEY = 44 +local PARAM_TABLE_PREFIX = "ESC_HW_" + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +-- bind a parameter to a variable given +local function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +-- add a parameter and bind it to a variable +local function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +-- setup script specific parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 8), 'could not add param table') + +--[[ + // @Param: ESC_HW_ENABLE + // @DisplayName: Hobbywing ESC Enable + // @Description: Enable Hobbywing ESC telemetry + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +ESC_HW_ENABLE = bind_add_param("ENABLE", 1, 0) + +--[[ + // @Param: ESC_HW_POLES + // @DisplayName: Hobbywing ESC motor poles + // @Description: Number of motor poles for eRPM scaling + // @Range: 1 50 + // @User: Standard +--]] +ESC_HW_POLES = bind_add_param("POLES", 2, 14) + +--[[ + // @Param: ESC_HW_OFS + // @DisplayName: Hobbywing ESC motor offset + // @Description: Motor number offset of first ESC + // @Range: 0 31 + // @User: Standard +--]] +ESC_HW_OFS = bind_add_param("OFS", 3, 0) + +if ESC_HW_ENABLE:get() ~= 1 then + gcs:send_text(MAV_SEVERITY.INFO, "ESC_HW: disabled") + return +end + +local uart = serial:find_serial(0) -- first scripting serial +if not uart then + gcs:send_text(MAV_SEVERITY.ERROR, "ESC_HW: unable to find serial port") + return +end +uart:begin(115200) + +local function read_bytes(n) + local ret = "" + for _ = 1, n do + ret = ret .. string.char(uart:read()) + end + return ret +end + +--[[ + discard pending bytes +--]] +local function discard_pending() + local n = uart:available():toint() + for _ = 1, n do + uart:read() + end +end + +--[[ + xmodem CRC implementation thanks to https://github.com/cloudwu/skynet + under MIT license +--]] +local XMODEMCRC16Lookup = { + 0x0000,0x1021,0x2042,0x3063,0x4084,0x50a5,0x60c6,0x70e7, + 0x8108,0x9129,0xa14a,0xb16b,0xc18c,0xd1ad,0xe1ce,0xf1ef, + 0x1231,0x0210,0x3273,0x2252,0x52b5,0x4294,0x72f7,0x62d6, + 0x9339,0x8318,0xb37b,0xa35a,0xd3bd,0xc39c,0xf3ff,0xe3de, + 0x2462,0x3443,0x0420,0x1401,0x64e6,0x74c7,0x44a4,0x5485, + 0xa56a,0xb54b,0x8528,0x9509,0xe5ee,0xf5cf,0xc5ac,0xd58d, + 0x3653,0x2672,0x1611,0x0630,0x76d7,0x66f6,0x5695,0x46b4, + 0xb75b,0xa77a,0x9719,0x8738,0xf7df,0xe7fe,0xd79d,0xc7bc, + 0x48c4,0x58e5,0x6886,0x78a7,0x0840,0x1861,0x2802,0x3823, + 0xc9cc,0xd9ed,0xe98e,0xf9af,0x8948,0x9969,0xa90a,0xb92b, + 0x5af5,0x4ad4,0x7ab7,0x6a96,0x1a71,0x0a50,0x3a33,0x2a12, + 0xdbfd,0xcbdc,0xfbbf,0xeb9e,0x9b79,0x8b58,0xbb3b,0xab1a, + 0x6ca6,0x7c87,0x4ce4,0x5cc5,0x2c22,0x3c03,0x0c60,0x1c41, + 0xedae,0xfd8f,0xcdec,0xddcd,0xad2a,0xbd0b,0x8d68,0x9d49, + 0x7e97,0x6eb6,0x5ed5,0x4ef4,0x3e13,0x2e32,0x1e51,0x0e70, + 0xff9f,0xefbe,0xdfdd,0xcffc,0xbf1b,0xaf3a,0x9f59,0x8f78, + 0x9188,0x81a9,0xb1ca,0xa1eb,0xd10c,0xc12d,0xf14e,0xe16f, + 0x1080,0x00a1,0x30c2,0x20e3,0x5004,0x4025,0x7046,0x6067, + 0x83b9,0x9398,0xa3fb,0xb3da,0xc33d,0xd31c,0xe37f,0xf35e, + 0x02b1,0x1290,0x22f3,0x32d2,0x4235,0x5214,0x6277,0x7256, + 0xb5ea,0xa5cb,0x95a8,0x8589,0xf56e,0xe54f,0xd52c,0xc50d, + 0x34e2,0x24c3,0x14a0,0x0481,0x7466,0x6447,0x5424,0x4405, + 0xa7db,0xb7fa,0x8799,0x97b8,0xe75f,0xf77e,0xc71d,0xd73c, + 0x26d3,0x36f2,0x0691,0x16b0,0x6657,0x7676,0x4615,0x5634, + 0xd94c,0xc96d,0xf90e,0xe92f,0x99c8,0x89e9,0xb98a,0xa9ab, + 0x5844,0x4865,0x7806,0x6827,0x18c0,0x08e1,0x3882,0x28a3, + 0xcb7d,0xdb5c,0xeb3f,0xfb1e,0x8bf9,0x9bd8,0xabbb,0xbb9a, + 0x4a75,0x5a54,0x6a37,0x7a16,0x0af1,0x1ad0,0x2ab3,0x3a92, + 0xfd2e,0xed0f,0xdd6c,0xcd4d,0xbdaa,0xad8b,0x9de8,0x8dc9, + 0x7c26,0x6c07,0x5c64,0x4c45,0x3ca2,0x2c83,0x1ce0,0x0cc1, + 0xef1f,0xff3e,0xcf5d,0xdf7c,0xaf9b,0xbfba,0x8fd9,0x9ff8, + 0x6e17,0x7e36,0x4e55,0x5e74,0x2e93,0x3eb2,0x0ed1,0x1ef0 +} + +local function crc_xmodem(bytes) + local crc = 0 + for i=1,#bytes do + local b = string.byte(bytes,i,i) + crc = ((crc<<8) & 0xffff) ~ XMODEMCRC16Lookup[(((crc>>8)~b) & 0xff) + 1] + end + return crc +end + +local temp_table = { + { 241, 0}, { 240, 1}, { 239, 2}, { 238, 3}, { 237, 4}, { 236, 5}, { 235, 6}, { 234, 7}, { 233, 8}, { 232, 9}, + { 231, 10}, { 230, 11}, { 229, 12}, { 228, 13}, { 227, 14}, { 226, 15}, { 224, 16}, { 223, 17}, { 222, 18}, { 220, 19}, + { 219, 20}, { 217, 21}, { 216, 22}, { 214, 23}, { 213, 24}, { 211, 25}, { 209, 26}, { 208, 27}, { 206, 28}, { 204, 29}, + { 202, 30}, { 201, 31}, { 199, 32}, { 197, 33}, { 195, 34}, { 193, 35}, { 191, 36}, { 189, 37}, { 187, 38}, { 185, 39}, + { 183, 40}, { 181, 41}, { 179, 42}, { 177, 43}, { 174, 44}, { 172, 45}, { 170, 46}, { 168, 47}, { 166, 48}, { 164, 49}, + { 161, 50}, { 159, 51}, { 157, 52}, { 154, 53}, { 152, 54}, { 150, 55}, { 148, 56}, { 146, 57}, { 143, 58}, { 141, 59}, + { 139, 60}, { 136, 61}, { 134, 62}, { 132, 63}, { 130, 64}, { 128, 65}, { 125, 66}, { 123, 67}, { 121, 68}, { 119, 69}, + { 117, 70}, { 115, 71}, { 113, 72}, { 111, 73}, { 109, 74}, { 106, 75}, { 105, 76}, { 103, 77}, { 101, 78}, { 99, 79}, + { 97, 80}, { 95, 81}, { 93, 82}, { 91, 83}, { 90, 84}, { 88, 85}, { 85, 86}, { 84, 87}, { 82, 88}, { 81, 89}, + { 79, 90}, { 77, 91}, { 76, 92}, { 74, 93}, { 73, 94}, { 72, 95}, { 69, 96}, { 68, 97}, { 66, 98}, { 65, 99}, + { 64, 100}, { 62, 101}, { 62, 102}, { 61, 103}, { 59, 104}, { 58, 105}, { 56, 106}, { 54, 107}, { 54, 108}, { 53, 109}, + { 51, 110}, { 51, 111}, { 50, 112}, { 48, 113}, { 48, 114}, { 46, 115}, { 46, 116}, { 44, 117}, { 43, 118}, { 43, 119}, + { 41, 120}, { 41, 121}, { 39, 122}, { 39, 123}, { 39, 124}, { 37, 125}, { 37, 126}, { 35, 127}, { 35, 128}, { 33, 129}, +} + +local function temperature_decode(temp_raw) + if temp_raw == 0 then + return 0 + end + for i = 1, #temp_table do + if temp_table[i][1] <= temp_raw then + return temp_table[i][2] + end + end + return 130 +end + +local function decode_current(curr) + return curr / 64.0 +end + +local telem_data = ESCTelemetryData() + +--[[ + check for input and parse data +--]] +local function check_input() + local n_bytes = uart:available():toint() + if n_bytes < 160 then + return + end + --gcs:send_text(0,string.format("n_bytes=%u", n_bytes)) + if n_bytes > 160 then + discard_pending() + return + end + + local s = read_bytes(n_bytes) + local head, frame_len, ver, cmd, _ = string.unpack(">BBBBH", string.sub(s,1,6)) + if head ~= 0x9B or frame_len ~= 158 or ver ~= 1 or cmd ~= 2 then + gcs:send_text(MAV_SEVERITY.INFO, string.format("bad frame %x %x %x %x", head, frame_len, ver, cmd)) + return + end + local crc1 = string.unpack("BHHHHHhhBBH", e) + local RPM = math.floor(eRPM*10.0/ESC_HW_POLES:get()) + if volt > 0 or curr > 0 or RPM > 0 or pnum > 1 then + -- we have valid ESC data + local ofs = ESC_HW_OFS:get() + curr = decode_current(curr) + pcurr = decode_current(pcurr) + volt = volt * 0.1 + in_thr = in_thr / 32768.0 + out_thr = out_thr / 32768.0 + mos_temp = temperature_decode(mos_temp) + cap_temp = temperature_decode(cap_temp) + telem_data:voltage(volt) + telem_data:current(curr) + telem_data:temperature_cdeg(math.floor(mos_temp*100)) + esc_telem:update_rpm(ofs+i, math.floor(eRPM*10.0/ESC_HW_POLES:get()), 0) + -- 0x0D is temperature + voltage + current + esc_telem:update_telem_data(ofs+i, telem_data, 0x0D) + logger.write('HWES','I,PNum,RPM,Curr,Volt,InT,OutT,PCurr,MosT,CapT,Status', + 'BHHfffffBBH', '#-qAv--AOO-', '--00000000-', + ofs+i, pnum, RPM, curr, volt, in_thr, out_thr, pcurr, mos_temp, cap_temp, status) + end + end +end + +--[[ + main update function +--]] +local function update() + check_input() + return update, 10 +end + +gcs:send_text(MAV_SEVERITY.ALERT, "ESC_HW: loaded") + +return update, 100 diff --git a/libraries/AP_Scripting/drivers/Hobbywing_DataLink.md b/libraries/AP_Scripting/drivers/Hobbywing_DataLink.md new file mode 100644 index 00000000000000..117de4d13f0e8b --- /dev/null +++ b/libraries/AP_Scripting/drivers/Hobbywing_DataLink.md @@ -0,0 +1,57 @@ +# HobbyWing ESC DataLink Driver + +https://www.hobbywing.com/en/products?id=59 + +This driver implements support the HobbyWing DataLink for HobbyWing +ESCs connected via a UART to an ArduPilot serial port. It supports up +to 8 ESCs. + +# Parameters + +The script used the following parameters: + +## ESC_HW_ENABLE + +this must be set to 1 to enable the driver + +## ESC_HW_POLES + +this should be set to the number of motor poles for eRPM to RPM +scaling. Please confirm the correct RPM using a tachometer + +## ESC_HW_OFS + +this parameter sets an offset for the first ESC number. It is useful +on vehicles where the first ESC is not the first SERVOn output, for +example on quadplanes. Set to zero for no offset. + +# Hardware Setup + +Connect the TX1 pin on the DataLink V2 to a RX pin on an ArduPilot +serial port and the GND pin on the DataLink V2 to the GND pin on the +ArduPilot UART. + +Connect your ESCs into the 8 ESC connectors marked D1 to D8. + +Power the DataLink V2 with a battery as indicated in the DataLink V2 manual. + +# Operation + +This driver should be loaded by placing the lua script in the +APM/SCRIPTS directory on the microSD card, which can be done either +directly or via MAVFTP. The following key parameters should be set: + + - SCR_ENABLE should be set to 1 + - ESC_HW_ENABLE should be set to 1 + - SERIALn_PROTOCOL should be set to 28 for the connected serial port + +then the flight controller should rebooted and parameters should be +refreshed. + +Once loaded the ESC_HW_ parameters will appear and should be +configured as per the above documentation. + +Note that the DataLink does not provide any data unless the motor is +running, so you cannot see any valid data at all until you arm the +motors and they start spinning. + From 4ffdb65288b4ba9dd790a2fb45a934bc2c24bf15 Mon Sep 17 00:00:00 2001 From: olliw42 Date: Sat, 4 Nov 2023 10:03:14 +0100 Subject: [PATCH 076/499] AP_Mount: gimbal_manager_set_pitchyaw is not a command --- libraries/AP_Mount/AP_Mount.cpp | 6 +++--- libraries/AP_Mount/AP_Mount.h | 2 +- libraries/AP_Mount/AP_Mount_Alexmos.cpp | 2 +- libraries/AP_Mount/AP_Mount_Backend.cpp | 2 +- libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp | 2 +- 5 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index ebcf2a0f8cbddd..8ff5a5362ba2d0 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -380,7 +380,7 @@ MAV_RESULT AP_Mount::handle_command_do_gimbal_manager_configure(const mavlink_co return backend->handle_command_do_gimbal_manager_configure(packet, msg); } -void AP_Mount::handle_gimbal_manager_set_attitude(const mavlink_message_t &msg){ +void AP_Mount::handle_gimbal_manager_set_attitude(const mavlink_message_t &msg) { mavlink_gimbal_manager_set_attitude_t packet; mavlink_msg_gimbal_manager_set_attitude_decode(&msg,&packet); @@ -445,7 +445,7 @@ void AP_Mount::handle_gimbal_manager_set_attitude(const mavlink_message_t &msg){ } } -void AP_Mount::handle_command_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg) +void AP_Mount::handle_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg) { mavlink_gimbal_manager_set_pitchyaw_t packet; mavlink_msg_gimbal_manager_set_pitchyaw_decode(&msg,&packet); @@ -906,7 +906,7 @@ void AP_Mount::handle_message(mavlink_channel_t chan, const mavlink_message_t &m handle_gimbal_manager_set_attitude(msg); break; case MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW: - handle_command_gimbal_manager_set_pitchyaw(msg); + handle_gimbal_manager_set_pitchyaw(msg); break; case MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION: handle_gimbal_device_information(msg); diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 1dec3ab9d50f9d..fe3003eca536a0 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -296,7 +296,7 @@ class AP_Mount MAV_RESULT handle_command_do_gimbal_manager_pitchyaw(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_gimbal_manager_configure(const mavlink_command_int_t &packet, const mavlink_message_t &msg); void handle_gimbal_manager_set_attitude(const mavlink_message_t &msg); - void handle_command_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg); + void handle_gimbal_manager_set_pitchyaw(const mavlink_message_t &msg); void handle_global_position_int(const mavlink_message_t &msg); void handle_gimbal_device_information(const mavlink_message_t &msg); void handle_gimbal_device_attitude_status(const mavlink_message_t &msg); diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.cpp b/libraries/AP_Mount/AP_Mount_Alexmos.cpp index f7f39f6119be40..a08eccf34fd8ae 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.cpp +++ b/libraries/AP_Mount/AP_Mount_Alexmos.cpp @@ -259,7 +259,7 @@ void AP_Mount_Alexmos::read_incoming() numc = _port->available(); - if (numc < 0 ){ + if (numc < 0 ) { return; } diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index ee4c76d6255f54..d3cc0cb490ddc9 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -106,7 +106,7 @@ void AP_Mount_Backend::clear_roi_target() _roi_target_set = false; // reset the mode if in GPS tracking mode - if (_mode == MAV_MOUNT_MODE_GPS_POINT) { + if (get_mode() == MAV_MOUNT_MODE_GPS_POINT) { MAV_MOUNT_MODE default_mode = (MAV_MOUNT_MODE)_params.default_mode.get(); set_mode(default_mode); } diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 0fdcdd53c70fbf..518b698ef69e76 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -219,7 +219,7 @@ void AP_Mount_SToRM32_serial::read_incoming() { numc = _port->available(); - if (numc < 0 ){ + if (numc < 0 ) { return; } From 78ae42c45f3cbe4a2b304860465b7d14c04dbed9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 6 Nov 2023 10:27:09 +1100 Subject: [PATCH 077/499] Tools: added Web Tools landing page --- Tools/autotest/web-firmware/index.html | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/web-firmware/index.html b/Tools/autotest/web-firmware/index.html index cd23bd958170c6..6de8c89fa2b4e2 100644 --- a/Tools/autotest/web-firmware/index.html +++ b/Tools/autotest/web-firmware/index.html @@ -98,8 +98,8 @@

Firmwares

alt="Companion">Companion - Companion Computer example code and Images

AP_PeriphAP_Periph - DroneCAN Peripheral Firmware

-FilterToolFilterTool - Filter Analysis Tool

+WebToolsWeb Tools - Web Analysis Tools

Types of firmware available

From 336c16cae0648072628ce6baec28f8b95c32573c Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Fri, 3 Nov 2023 01:43:07 -0600 Subject: [PATCH 078/499] modules: Upgrade patch version in Micro-XRCE-DDS-Client Signed-off-by: Ryan Friedman --- modules/Micro-XRCE-DDS-Client | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/Micro-XRCE-DDS-Client b/modules/Micro-XRCE-DDS-Client index a2937bc5af606b..97175304425c5b 160000 --- a/modules/Micro-XRCE-DDS-Client +++ b/modules/Micro-XRCE-DDS-Client @@ -1 +1 @@ -Subproject commit a2937bc5af606b2434e9a841adbf5c003fc1ec38 +Subproject commit 97175304425c5bee87c6fddd99de1ef8d0c394dc From 3411b85b7155132348fd32e7e42c273021d1b480 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Nov 2023 12:06:20 +1100 Subject: [PATCH 079/499] AP_TempCalibration: add and use AP_TEMPCALIBRATION_ENABLED --- libraries/AP_TempCalibration/AP_TempCalibration.cpp | 6 ++++++ libraries/AP_TempCalibration/AP_TempCalibration.h | 6 ++++++ libraries/AP_TempCalibration/AP_TempCalibration_config.h | 7 +++++++ 3 files changed, 19 insertions(+) create mode 100644 libraries/AP_TempCalibration/AP_TempCalibration_config.h diff --git a/libraries/AP_TempCalibration/AP_TempCalibration.cpp b/libraries/AP_TempCalibration/AP_TempCalibration.cpp index 529c9a90b6c99e..574dc9258d0846 100644 --- a/libraries/AP_TempCalibration/AP_TempCalibration.cpp +++ b/libraries/AP_TempCalibration/AP_TempCalibration.cpp @@ -16,6 +16,10 @@ temperature calibration library */ +#include "AP_TempCalibration_config.h" + +#if AP_TEMPCALIBRATION_ENABLED + #include "AP_TempCalibration.h" #include #include @@ -231,3 +235,5 @@ void AP_TempCalibration::update(void) break; } } + +#endif // AP_TEMPCALIBRATION_ENABLED diff --git a/libraries/AP_TempCalibration/AP_TempCalibration.h b/libraries/AP_TempCalibration/AP_TempCalibration.h index 5572258586504a..0b8eecc68fc44f 100644 --- a/libraries/AP_TempCalibration/AP_TempCalibration.h +++ b/libraries/AP_TempCalibration/AP_TempCalibration.h @@ -18,6 +18,10 @@ and opportunistically calibrates sensors when the vehicle is still */ +#include "AP_TempCalibration_config.h" + +#if AP_TEMPCALIBRATION_ENABLED + #include #include #include @@ -79,3 +83,5 @@ class AP_TempCalibration float calculate_p_range(float baro_factor) const; }; + +#endif // AP_TEMPCALIBRATION_ENABLED diff --git a/libraries/AP_TempCalibration/AP_TempCalibration_config.h b/libraries/AP_TempCalibration/AP_TempCalibration_config.h new file mode 100644 index 00000000000000..9a936924c41b5f --- /dev/null +++ b/libraries/AP_TempCalibration/AP_TempCalibration_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef AP_TEMPCALIBRATION_ENABLED +#define AP_TEMPCALIBRATION_ENABLED 1 +#endif From 75f1459fa680ec8c9dd13d801d046546d0ac0b79 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Nov 2023 12:06:20 +1100 Subject: [PATCH 080/499] ArduCopter: add and use AP_TEMPCALIBRATION_ENABLED --- ArduCopter/Copter.cpp | 2 ++ ArduCopter/Parameters.cpp | 9 ++++++--- ArduCopter/Parameters.h | 2 ++ 3 files changed, 10 insertions(+), 3 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 8bbbc186c19e14..7ddd0be1a87607 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -220,7 +220,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if AP_RPM_ENABLED SCHED_TASK_CLASS(AP_RPM, &copter.rpm_sensor, update, 40, 200, 129), #endif +#if AP_TEMPCALIBRATION_ENABLED SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100, 135), +#endif #if HAL_ADSB_ENABLED SCHED_TASK(avoidance_adsb_update, 10, 100, 138), #endif diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 334c4b02934414..0f5b6ba6bbf029 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -838,9 +838,11 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // 18 was used by AP_VisualOdom +#if AP_TEMPCALIBRATION_ENABLED // @Group: TCAL // @Path: ../libraries/AP_TempCalibration/AP_TempCalibration.cpp AP_SUBGROUPINFO(temp_calibration, "TCAL", 19, ParametersG2, AP_TempCalibration), +#endif #if TOY_MODE_ENABLED == ENABLED // @Group: TMODE @@ -1236,7 +1238,10 @@ const AP_Param::GroupInfo ParametersG2::var_info2[] = { constructor for g2 object */ ParametersG2::ParametersG2(void) - : temp_calibration() // this doesn't actually need constructing, but removing it here is problematic syntax-wise + : command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f) +#if AP_TEMPCALIBRATION_ENABLED + , temp_calibration() +#endif #if AP_BEACON_ENABLED , beacon() #endif @@ -1282,8 +1287,6 @@ ParametersG2::ParametersG2(void) ,command_model_acro_y(ACRO_Y_RATE_DEFAULT, ACRO_Y_EXPO_DEFAULT, 0.0f) #endif - ,command_model_pilot(PILOT_Y_RATE_DEFAULT, PILOT_Y_EXPO_DEFAULT, 0.0f) - #if WEATHERVANE_ENABLED == ENABLED ,weathervane() #endif diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 18a32dd25fc184..e1f207400f0825 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -522,8 +522,10 @@ class ParametersG2 { // ground effect compensation enable/disable AP_Int8 gndeffect_comp_enabled; +#if AP_TEMPCALIBRATION_ENABLED // temperature calibration handling AP_TempCalibration temp_calibration; +#endif #if AP_BEACON_ENABLED // beacon (non-GPS positioning) library From 1f7e87ddf57aa01bf3b963cc36049c7f1f666174 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Nov 2023 12:55:47 +1100 Subject: [PATCH 081/499] Tools: build_options.py: move baro-related thigns to new Baro section --- Tools/scripts/build_options.py | 34 +++++++++++++++++----------------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 7ec8811fef8951..b9a888c7f3caa2 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -259,22 +259,23 @@ def __init__(self, Feature('Proximity', 'PROXIMITY_TERRARANGERTOWER', 'AP_PROXIMITY_TERARANGERTOWER_ENABLED', 'Enable TerraRangerTower Proximity Sensors', 0, "PROXIMITY"), # noqa Feature('Proximity', 'PROXIMITY_TERRARANGERTOWEREVO', 'AP_PROXIMITY_TERARANGERTOWEREVO_ENABLED', 'Enable TerraRangerTower Evo Proximity Sensors', 0, "PROXIMITY"), # noqa - Feature('Sensors', 'BMP085', 'AP_BARO_BMP085_ENABLED', 'Enable BMP085 Barometric Sensor', 1, None), - Feature('Sensors', 'BMP280', 'AP_BARO_BMP280_ENABLED', 'Enable BMP280 Barometric Sensor', 1, None), - Feature('Sensors', 'BMP388', 'AP_BARO_BMP388_ENABLED', 'Enable BMP388 Barometric Sensor', 1, None), - Feature('Sensors', 'DPS280', 'AP_BARO_DPS280_ENABLED', 'Enable DPS280/DPS310 Barometric Sensor', 1, None), - Feature('Sensors', 'DUMMY', 'AP_BARO_DUMMY_ENABLED', 'Enable DUMMY Barometric Sensor', 0, None), - Feature('Sensors', 'EXTERNALAHRS', 'AP_BARO_EXTERNALAHRS_ENABLED', 'Enable EXTERNALAHRS Barometric Sensor', 0, 'AHRS_EXT'), - Feature('Sensors', 'FBM320', 'AP_BARO_FBM320_ENABLED', 'Enable FBM320 Barometric Sensor', 1, None), - Feature('Sensors', 'ICM20789', 'AP_BARO_ICM20789_ENABLED', 'Enable ICM20789 Barometric Sensor', 1, None), - Feature('Sensors', 'KELLERLD', 'AP_BARO_KELLERLD_ENABLED', 'Enable KELLERLD Barometric Sensor', 1, None), - Feature('Sensors', 'LPS2XH', 'AP_BARO_LPS2XH_ENABLED', 'Enable LPS2XH Barometric Sensor', 1, None), - Feature('Sensors', 'MS56XX', 'AP_BARO_MS56XX_ENABLED', 'Enable MS56XX Barometric Sensor', 1, None), - Feature('Sensors', 'MSP_BARO', 'AP_BARO_MSP_ENABLED', 'Enable MSP Barometric Sensor', 0, 'MSP'), - Feature('Sensors', 'SPL06', 'AP_BARO_SPL06_ENABLED', 'Enable SPL06 Barometric Sensor', 1, None), - Feature('Sensors', 'DRONECAN_BARO', 'AP_BARO_DRONECAN_ENABLED', 'Enable DroneCAN Barometric Sensor', 0, None), - Feature('Sensors', 'ICP101XX', 'AP_BARO_ICP101XX_ENABLED', 'Enable ICP101XX Barometric Sensor', 0, None), - Feature('Sensors', 'ICP201XX', 'AP_BARO_ICP201XX_ENABLED', 'Enable ICP201XX Barometric Sensor', 0, None), + Feature('Baro', 'BMP085', 'AP_BARO_BMP085_ENABLED', 'Enable BMP085 Barometric Sensor', 1, None), + Feature('Baro', 'BMP280', 'AP_BARO_BMP280_ENABLED', 'Enable BMP280 Barometric Sensor', 1, None), + Feature('Baro', 'BMP388', 'AP_BARO_BMP388_ENABLED', 'Enable BMP388 Barometric Sensor', 1, None), + Feature('Baro', 'DPS280', 'AP_BARO_DPS280_ENABLED', 'Enable DPS280/DPS310 Barometric Sensor', 1, None), + Feature('Baro', 'DUMMY', 'AP_BARO_DUMMY_ENABLED', 'Enable DUMMY Barometric Sensor', 0, None), + Feature('Baro', 'EXTERNALAHRS', 'AP_BARO_EXTERNALAHRS_ENABLED', 'Enable EXTERNALAHRS Barometric Sensor', 0, 'AHRS_EXT'), + Feature('Baro', 'FBM320', 'AP_BARO_FBM320_ENABLED', 'Enable FBM320 Barometric Sensor', 1, None), + Feature('Baro', 'ICM20789', 'AP_BARO_ICM20789_ENABLED', 'Enable ICM20789 Barometric Sensor', 1, None), + Feature('Baro', 'KELLERLD', 'AP_BARO_KELLERLD_ENABLED', 'Enable KELLERLD Barometric Sensor', 1, None), + Feature('Baro', 'LPS2XH', 'AP_BARO_LPS2XH_ENABLED', 'Enable LPS2XH Barometric Sensor', 1, None), + Feature('Baro', 'MS56XX', 'AP_BARO_MS56XX_ENABLED', 'Enable MS56XX Barometric Sensor', 1, None), + Feature('Baro', 'MSP_BARO', 'AP_BARO_MSP_ENABLED', 'Enable MSP Barometric Sensor', 0, 'MSP'), + Feature('Baro', 'SPL06', 'AP_BARO_SPL06_ENABLED', 'Enable SPL06 Barometric Sensor', 1, None), + Feature('Baro', 'DRONECAN_BARO', 'AP_BARO_DRONECAN_ENABLED', 'Enable DroneCAN Barometric Sensor', 0, None), + Feature('Baro', 'ICP101XX', 'AP_BARO_ICP101XX_ENABLED', 'Enable ICP101XX Barometric Sensor', 0, None), + Feature('Baro', 'ICP201XX', 'AP_BARO_ICP201XX_ENABLED', 'Enable ICP201XX Barometric Sensor', 0, None), + Feature('Baro', 'BARO_WIND_COMP', 'HAL_BARO_WIND_COMP_ENABLED', 'Enable Baro Wind Compensation', 0, None), Feature('Sensors', 'RPM', 'AP_RPM_ENABLED', 'Enable RPM sensors', 0, None), Feature('Sensors', 'RPM_EFI', 'AP_RPM_EFI_ENABLED', 'Enable RPM EFI sensors', 0, 'RPM,EFI'), @@ -295,7 +296,6 @@ def __init__(self, Feature('Other', 'GyroFFT', 'HAL_GYROFFT_ENABLED', 'Enable In-Flight Gyro FFT calculations', 0, None), Feature('Other', 'DISPLAY', 'HAL_DISPLAY_ENABLED', 'Enable I2C Displays', 0, None), Feature('Other', 'NMEA_OUTPUT', 'HAL_NMEA_OUTPUT_ENABLED', 'Enable NMEA Output', 0, None), - Feature('Other', 'BARO_WIND_COMP', 'HAL_BARO_WIND_COMP_ENABLED', 'Enable Baro Wind Compensation', 0, None), Feature('Other', 'SDCARD_FORMATTING', 'AP_FILESYSTEM_FORMAT_ENABLED', 'Enable formatting of microSD cards', 0, None), Feature('Other', 'BOOTLOADER_FLASHING', 'AP_BOOTLOADER_FLASHING_ENABLED', 'Enable Bootloader flashing', 0, "FILESYSTEM_ROMFS"), # noqa Feature('Other', 'SCRIPTING', 'AP_SCRIPTING_ENABLED', 'Enable LUA Scripting', 0, None), From 5586daec49f79056d743317b82b73c042beab6b0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Nov 2023 12:58:01 +1100 Subject: [PATCH 082/499] Tools: add AP_TEMPCALIBRATION_ENABLED to build_options --- Tools/scripts/build_options.py | 1 + Tools/scripts/extract_features.py | 1 + 2 files changed, 2 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index b9a888c7f3caa2..385c0c44d72da4 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -276,6 +276,7 @@ def __init__(self, Feature('Baro', 'ICP101XX', 'AP_BARO_ICP101XX_ENABLED', 'Enable ICP101XX Barometric Sensor', 0, None), Feature('Baro', 'ICP201XX', 'AP_BARO_ICP201XX_ENABLED', 'Enable ICP201XX Barometric Sensor', 0, None), Feature('Baro', 'BARO_WIND_COMP', 'HAL_BARO_WIND_COMP_ENABLED', 'Enable Baro Wind Compensation', 0, None), + Feature('Baro', 'BARO_TEMPCAL', 'AP_TEMPCALIBRATION_ENABLED', 'Enable Baro Temperature Calibration', 0, None), Feature('Sensors', 'RPM', 'AP_RPM_ENABLED', 'Enable RPM sensors', 0, None), Feature('Sensors', 'RPM_EFI', 'AP_RPM_EFI_ENABLED', 'Enable RPM EFI sensors', 0, 'RPM,EFI'), diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index e847065e833bad..d0b943dfe27752 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -191,6 +191,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('HAL_DISPLAY_ENABLED', r'Display::init\b',), ('HAL_NMEA_OUTPUT_ENABLED', r'AP_NMEA_Output::update\b',), ('HAL_BARO_WIND_COMP_ENABLED', r'AP_Baro::wind_pressure_correction\b',), + ('AP_TEMPCALIBRATION_ENABLED', r'AP_TempCalibration::apply_calibration',), ('HAL_PICCOLO_CAN_ENABLE', r'AP_PiccoloCAN::update',), ('EK3_FEATURE_EXTERNAL_NAV', r'NavEKF3::writeExtNavVelData'), From 3bface980df5744e144d6395017fc13c7db3fde4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 2 Nov 2023 21:12:13 +0900 Subject: [PATCH 083/499] AP_Scripting: mount-poi supports locking mount to Location --- libraries/AP_Scripting/applets/mount-poi.lua | 40 ++++++++++---------- libraries/AP_Scripting/applets/mount-poi.md | 4 +- 2 files changed, 23 insertions(+), 21 deletions(-) diff --git a/libraries/AP_Scripting/applets/mount-poi.lua b/libraries/AP_Scripting/applets/mount-poi.lua index ebe6483f41af55..a75bf9d7476f1b 100644 --- a/libraries/AP_Scripting/applets/mount-poi.lua +++ b/libraries/AP_Scripting/applets/mount-poi.lua @@ -1,7 +1,7 @@ -- mount-poi.lua: finds the point-of-interest that the gimbal mount is pointing at using the vehicle's current Location, mount attitude and terrain database -- -- How To Use --- 1. set RCx_OPTION to 300 to enable triggering the POI calculation from an auxiliary switch +-- 1. Set RCx_OPTION to 300 or 301 to enable triggering the POI calculation from an auxiliary switch. If 301 is used the gimbal will also lock onto the location -- 2. optionally set POI_DIST_MAX to the maximum distance (in meters) that the POI point could be from the vehicle -- 3. fly the vehicle and point the camera gimbal at a point on the ground -- 4. raise the RC auxiliary switch and check the GCS's messages tab for the latitude, longitude and alt (above sea-level) @@ -42,7 +42,8 @@ local POI_DIST_MAX = Parameter("POI_DIST_MAX") TERRAIN_SPACING = Parameter("TERRAIN_SPACING") -- local variables and definitions -local last_rc_switch_pos = 0 -- last known rc switch position. Used to detect change in RC switch position +local last_poi_switch_pos = 0 -- last known rc poi switch position. Used to detect change in RC switch position +local last_roi_switch_pos = 0 -- last known rc roi switch position. Used to detect change in RC switch position local success_count = 0 -- count of the number of POI calculations (sent to GCS in CAMERA_FEEDBACK message) -- mavlink message definition @@ -157,29 +158,25 @@ function interpolate(low_output, high_output, var_value, var_low, var_high) end --- the main update function that performs a simplified version of RTL +-- the main update function called at 10hz function update() - -- find RC channel used to trigger POI - rc_switch_ch = rc:find_channel_for_option(300) --scripting ch 1 - if (rc_switch_ch == nil) then - gcs:send_text(MAV_SEVERITY.ERROR, 'MountPOI: RCx_OPTION = 300 not set') -- MAV_SEVERITY_ERROR - return update, 10000 -- check again in 10 seconds - end - - -- check if user has raised RC switch - local rc_switch_pos = rc_switch_ch:get_aux_switch_pos() - if rc_switch_pos == last_rc_switch_pos then - return update, UPDATE_INTERVAL_MS - end + -- check if user has raised POI switch + local poi_switch_pos = rc:get_aux_cached(300) -- scripting ch 1 (drop icon on map where mount is pointing) + local poi_switch_pulled_high = (poi_switch_pos ~= nil) and (poi_switch_pos ~= last_poi_switch_pos) and (poi_switch_pos == 2) + last_poi_switch_pos = poi_switch_pos - -- switch has changed position - last_rc_switch_pos = rc_switch_pos - if rc_switch_pos ~= 2 then + -- check if user has raised ROI switch + local roi_switch_pos = rc:get_aux_cached(301) -- scripting ch 2 (drop icon and lock mount on location) + local roi_switch_pulled_high = (roi_switch_pos ~= nil) and (roi_switch_pos ~= last_roi_switch_pos) and (roi_switch_pos == 2) + last_roi_switch_pos = roi_switch_pos + + -- return if neither switch was pulled high + if not poi_switch_pulled_high and not roi_switch_pulled_high then return update, UPDATE_INTERVAL_MS end - -- POI has been requested + -- POI or ROI has been requested -- retrieve vehicle location local vehicle_loc = ahrs:get_location() @@ -256,6 +253,11 @@ function update() poi_loc:offset_bearing_and_pitch(mount_yaw_ef_deg, mount_pitch_deg, dist_interp_m) gcs:send_text(MAV_SEVERITY.INFO, string.format("POI %.7f, %.7f, %.2f (asml)", poi_loc:lat()/10000000.0, poi_loc:lng()/10000000.0, poi_loc:alt() * 0.01)) + -- if ROI requested then also lock gimbal to location + if roi_switch_pulled_high then + mount:set_roi_target(0, poi_loc) + end + -- send feedback to GCS so it can display icon on map success_count = success_count + 1 send_camera_feedback(poi_loc:lat(), poi_loc:lng(), poi_loc:alt(), poi_loc:alt(), 0, 0, 0, 0, 0, success_count) diff --git a/libraries/AP_Scripting/applets/mount-poi.md b/libraries/AP_Scripting/applets/mount-poi.md index 38eef69184ab08..b88ed337a26e31 100644 --- a/libraries/AP_Scripting/applets/mount-poi.md +++ b/libraries/AP_Scripting/applets/mount-poi.md @@ -8,10 +8,10 @@ POI_DIST_MAX : POI's max distance (in meters) from the vehicle # How To Use -1. Set RCx_OPTION to 300 (scripting1) to allow triggering the POI calculation from an auxiliary switch +1. Set RCx_OPTION to 300 or 301 to enable triggering the POI calculation from an auxiliary switch. If 301 is used the gimbal will also lock onto the location 2. Optionally set POI_DIST_MAX to the maximum distance (in meters) that the POI point could be from the vehicle 3. Fly the vehicle and point the camera gimbal at a point on the ground -4. Raise the RC auxiliary switch and check the GCS's messages tab for the latitude, longitude and alt (above sea-level) +4. Raise one of the RC auxiliary switches and check the GCS's messages tab for the latitude, longitude and alt (above sea-level) # How It Works From ff3925a0fd096cb85f974dc87b24ff53752193fa Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 3 Nov 2023 12:56:18 +0900 Subject: [PATCH 084/499] AP_Scripting: mount-poi displays startup message Also remove out-of-date-comments --- libraries/AP_Scripting/applets/mount-poi.lua | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Scripting/applets/mount-poi.lua b/libraries/AP_Scripting/applets/mount-poi.lua index a75bf9d7476f1b..aa42620bc01447 100644 --- a/libraries/AP_Scripting/applets/mount-poi.lua +++ b/libraries/AP_Scripting/applets/mount-poi.lua @@ -157,6 +157,7 @@ function interpolate(low_output, high_output, var_value, var_low, var_high) return (low_output + p * (high_output - low_output)) end +gcs:send_text(MAV_SEVERITY.INFO, "Mount-poi script started") -- the main update function called at 10hz function update() @@ -181,7 +182,7 @@ function update() -- retrieve vehicle location local vehicle_loc = ahrs:get_location() if vehicle_loc == nil then - gcs:send_text(MAV_SEVERITY.ERROR, "POI: vehicle pos unavailable") -- MAV_SEVERITY_ERROR + gcs:send_text(MAV_SEVERITY.ERROR, "POI: vehicle pos unavailable") return update, UPDATE_INTERVAL_MS end @@ -191,7 +192,7 @@ function update() -- retrieve gimbal attitude local _, pitch_deg, yaw_bf_deg = mount:get_attitude_euler(0) if pitch_deg == nil or yaw_bf_deg == nil then - gcs:send_text(MAV_SEVERITY.ERROR, "POI: gimbal attitude unavailable") -- MAV_SEVERITY_ERROR + gcs:send_text(MAV_SEVERITY.ERROR, "POI: gimbal attitude unavailable") return update, UPDATE_INTERVAL_MS end @@ -206,7 +207,7 @@ function update() -- fail if terrain alt cannot be retrieved if terrain_amsl_m == nil then - gcs:send_text(MAV_SEVERITY.ERROR, "POI: failed to get terrain alt") -- MAV_SEVERITY_ERROR + gcs:send_text(MAV_SEVERITY.ERROR, "POI: failed to get terrain alt") return update, UPDATE_INTERVAL_MS end @@ -235,7 +236,7 @@ function update() -- fail if terrain alt cannot be retrieved if terrain_amsl_m == nil then - gcs:send_text(MAV_SEVERITY.ERROR, "POI: failed to get terrain alt") -- MAV_SEVERITY_ERROR + gcs:send_text(MAV_SEVERITY.ERROR, "POI: failed to get terrain alt") return update, UPDATE_INTERVAL_MS end end From ae2ab08b1fac760bf929d5f3aaed4ccefaf26535 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Thu, 2 Nov 2023 17:10:30 +0000 Subject: [PATCH 085/499] AP_Scripting: add bindings for fence --- libraries/AP_Scripting/docs/docs.lua | 16 ++++++++ .../AP_Scripting/examples/FenceBreach.lua | 39 +++++++++++++++++++ .../generator/description/bindings.desc | 7 ++++ 3 files changed, 62 insertions(+) create mode 100644 libraries/AP_Scripting/examples/FenceBreach.lua diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 1fcf77384a4956..aa240b686de038 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -3032,3 +3032,19 @@ function mavlink:send_chan(chan, msgid, message) end -- Block a given MAV_CMD from being procceced by ArduPilot ---@param comand_id integer function mavlink:block_command(comand_id) end + +-- Geofence library +---@class fence +fence = {} + +-- Returns the time at which the current breach started +---@return uint32_t_ud system_time milliseconds +function fence:get_breach_time() end + +-- Returns the type bitmask of any breached fences +---@return integer fence_type bitmask +---| 1 # Maximim altitude +---| 2 # Circle +---| 4 # Polygon +---| 8 # Minimum altitude +function fence:get_breaches() end diff --git a/libraries/AP_Scripting/examples/FenceBreach.lua b/libraries/AP_Scripting/examples/FenceBreach.lua new file mode 100644 index 00000000000000..7367f75f506bf9 --- /dev/null +++ b/libraries/AP_Scripting/examples/FenceBreach.lua @@ -0,0 +1,39 @@ +-- Example of checking and reporting on geo-fence breach + +local breach_lookup = { + [1] = "Maximim altitude", + [2] = "Circle", + [4] = "Polygon", + [8] = "Minimum altitude" +} + +-- Lookup brach type bitmask and return the names of any breached fences +local function get_breach_names(breaches) + local msg = "" + for bitmaks, name in pairs(breach_lookup) do + if (breaches & bitmaks) ~= 0 then + -- And + delimiter between types if more than one + if (string.len(msg) > 0) then + msg = msg .. " + " + end + msg = msg .. name + end + end + + return msg +end + +function update() + + local breaches = fence:get_breaches() + if breaches ~= 0 then + -- Time passed since fence breach + local breach_time = millis() - fence:get_breach_time() + + gcs:send_text(0, string.format("Breached: %s fence, outside for %0.2f seconds", get_breach_names(breaches), breach_time:tofloat() * 0.001)) + end + + return update, 1000 +end + +return update() diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index b830b16b9d1207..2011ba9835361c 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -805,3 +805,10 @@ singleton mavlink manual register_rx_msgid lua_mavlink_register_rx_msgid 1 singleton mavlink manual send_chan lua_mavlink_send_chan 3 singleton mavlink manual receive_chan lua_mavlink_receive_chan 0 singleton mavlink manual block_command lua_mavlink_block_command 1 + +include AC_Fence/AC_Fence.h depends AP_FENCE_ENABLED +include AC_Fence/AC_Fence_config.h +singleton AC_Fence depends AP_FENCE_ENABLED +singleton AC_Fence rename fence +singleton AC_Fence method get_breaches uint8_t +singleton AC_Fence method get_breach_time uint32_t From e47a5c1ea98878d994af1092c3757798e8ae204b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 2 Nov 2023 09:53:13 +1100 Subject: [PATCH 086/499] AP_GPS: make AP_GPS_FixType enum class Don't want "NONE" in the global namespace --- libraries/AP_GPS/AP_GPS_FixType.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS_FixType.h b/libraries/AP_GPS/AP_GPS_FixType.h index e3254551d3bd25..93b51fed0dbddf 100644 --- a/libraries/AP_GPS/AP_GPS_FixType.h +++ b/libraries/AP_GPS/AP_GPS_FixType.h @@ -7,7 +7,7 @@ // this is not enum-class as many places in the code want to check for // "a fix at least this good" using "<". -enum AP_GPS_FixType { +enum class AP_GPS_FixType { NO_GPS = 0, ///< No GPS connected/detected NONE = 1, ///< Receiving valid GPS messages but no lock FIX_2D = 2, ///< Receiving valid messages and 2D lock From b3ff88c51916a23beac8437b96049e941b71ebd9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 8 Oct 2023 17:31:11 +1100 Subject: [PATCH 087/499] AP_ADSB: avoid using GPS and RTC libraries in backend instead, add fields to canonical AP_ADSB location "_my_loc" to hold all of the information backends might want. This will allow consistent presentation of data regardless of backend type, and for the sources of the information to change more easily. --- libraries/AP_ADSB/AP_ADSB.cpp | 84 +++++++++++++++++++--- libraries/AP_ADSB/AP_ADSB.h | 55 +++++++++++++- libraries/AP_ADSB/AP_ADSB_Sagetech.cpp | 23 +++--- libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp | 28 ++++---- libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp | 7 +- 5 files changed, 153 insertions(+), 44 deletions(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 9c3e9dcee58bb7..840d841cbfce50 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -20,16 +20,23 @@ https://en.wikipedia.org/wiki/Automatic_dependent_surveillance_%E2%80%93_broadcast */ -#include "AP_ADSB.h" +#include "AP_ADSB_config.h" #if HAL_ADSB_ENABLED + +#include "AP_ADSB.h" + #include "AP_ADSB_uAvionix_MAVLink.h" #include "AP_ADSB_uAvionix_UCP.h" #include "AP_ADSB_Sagetech.h" #include "AP_ADSB_Sagetech_MXS.h" -#include + +#include +#include +#include #include #include +#include #define VEHICLE_TIMEOUT_MS 5000 // if no updates in this time, drop it from the list @@ -47,6 +54,10 @@ #endif #endif +#ifndef AP_ADSB_TYPE_DEFAULT +#define AP_ADSB_TYPE_DEFAULT 0 +#endif + extern const AP_HAL::HAL& hal; AP_ADSB *AP_ADSB::_singleton; @@ -59,7 +70,7 @@ const AP_Param::GroupInfo AP_ADSB::var_info[] = { // @Values: 0:Disabled,1:uAvionix-MAVLink,2:Sagetech,3:uAvionix-UCP,4:Sagetech MX Series // @User: Standard // @RebootRequired: True - AP_GROUPINFO_FLAGS("TYPE", 0, AP_ADSB, _type[0], 0, AP_PARAM_FLAG_ENABLE), + AP_GROUPINFO_FLAGS("TYPE", 0, AP_ADSB, _type[0], AP_ADSB_TYPE_DEFAULT, AP_PARAM_FLAG_ENABLE), // index 1 is reserved - was BEHAVIOR @@ -319,20 +330,49 @@ bool AP_ADSB::is_valid_callsign(uint16_t octal) return true; } +#if AP_GPS_ENABLED && AP_AHRS_ENABLED && AP_BARO_ENABLED /* * periodic update to handle vehicle timeouts and trigger collision detection */ void AP_ADSB::update(void) +{ + Loc loc{}; + if (!AP::ahrs().get_location(loc)) { + loc.zero(); + } + + const AP_GPS &gps = AP::gps(); + + loc.fix_type = (AP_GPS_FixType)gps.status(); + loc.epoch_us = gps.time_epoch_usec(); +#if AP_RTC_ENABLED + loc.have_epoch_from_rtc_us = AP::rtc().get_utc_usec(loc.epoch_from_rtc_us); +#endif + + loc.satellites = gps.num_sats(); + + loc.horizontal_pos_accuracy_is_valid = gps.horizontal_accuracy(loc.horizontal_pos_accuracy); + loc.vertical_pos_accuracy_is_valid = gps.vertical_accuracy(loc.vertical_pos_accuracy); + loc.horizontal_vel_accuracy_is_valid = gps.speed_accuracy(loc.horizontal_vel_accuracy); + + + loc.vel_ned = gps.velocity(); + + loc.vertRateD_is_valid = AP::ahrs().get_vert_pos_rate_D(loc.vertRateD); + + update(loc); +} +#endif // AP_GPS_ENABLED && AP_AHRS_ENABLED + +void AP_ADSB::update(const AP_ADSB::Loc &loc) { if (!check_startup()) { return; } - const uint32_t now = AP_HAL::millis(); + _my_loc = loc; - if (!AP::ahrs().get_location(_my_loc)) { - _my_loc.zero(); - } + const uint32_t now = AP_HAL::millis(); // check current list for vehicles that time out uint16_t index = 0; @@ -697,7 +737,7 @@ uint32_t AP_ADSB::genICAO(const Location &loc) const { // gps_time is used as a pseudo-random number instead of seconds since UTC midnight // TODO: use UTC time instead of GPS time - const AP_GPS &gps = AP::gps(); + const AP_ADSB::Loc &gps { _my_loc }; const uint64_t gps_time = gps.time_epoch_usec(); uint32_t timeSum = 0; @@ -882,6 +922,34 @@ uint32_t AP_ADSB::convert_base_to_decimal(const uint8_t baseIn, uint32_t inputNu return outputNumber; } +// methods for embedded class Location +bool AP_ADSB::Loc::speed_accuracy(float &sacc) const +{ + if (!horizontal_vel_accuracy_is_valid) { + return false; + } + sacc = horizontal_vel_accuracy; + return true; +} + +bool AP_ADSB::Loc::horizontal_accuracy(float &hacc) const +{ + if (!horizontal_pos_accuracy_is_valid) { + return false; + } + hacc = horizontal_pos_accuracy; + return true; +} + +bool AP_ADSB::Loc::vertical_accuracy(float &vacc) const +{ + if (!vertical_pos_accuracy_is_valid) { + return false; + } + vacc = vertical_pos_accuracy; + return true; +} + AP_ADSB *AP::ADSB() { return AP_ADSB::get_singleton(); diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index 91ecee728c109b..c2578fca139cd0 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -28,6 +28,7 @@ #include #include #include +#include #define ADSB_MAX_INSTANCES 1 // Maximum number of ADSB sensor instances available on this platform @@ -85,6 +86,58 @@ class AP_ADSB { // periodic task that maintains vehicle_list void update(void); + // a structure holding *this vehicle's* position-related information: + enum class AltType { + Barometric = 0, // we use a specific model for this? + WGS84 = 1, + }; + struct Loc : Location { + AltType loc_alt_type; // more information on altitude in base class + + AP_GPS_FixType fix_type; + uint64_t epoch_us; // microseconds since 1970-01-01 + uint64_t epoch_from_rtc_us; // microseconds since 1970-01-01 + bool have_epoch_from_rtc_us; + uint8_t satellites; + + float horizontal_pos_accuracy; + bool horizontal_pos_accuracy_is_valid; + + float vertical_pos_accuracy; + bool vertical_pos_accuracy_is_valid; + + float horizontal_vel_accuracy; + bool horizontal_vel_accuracy_is_valid; + + Vector3f vel_ned; + + float vertRateD; // m/s down + bool vertRateD_is_valid; + + // methods to make us look much like the AP::gps() singleton: + AP_GPS_FixType status() const { return fix_type; } + const Vector3f &velocity() const { + return vel_ned; + } + uint64_t time_epoch_usec() const { return epoch_us; } + + bool speed_accuracy(float &sacc) const; + bool horizontal_accuracy(float &hacc) const; + bool vertical_accuracy(float &vacc) const; + + uint8_t num_sats() const { return satellites; } + + // methods to make us look like the AP::ahrs() singleton: + const Vector2f &groundspeed_vector() const { return vel_ned.xy(); } + bool get_vert_pos_rate_D(float &velocity) const { + velocity = vertRateD; + return vertRateD_is_valid; + } + } _my_loc; + + // periodic task that maintains vehicle_list + void update(const Loc &loc); + // send ADSB_VEHICLE mavlink message, usually as a StreamRate void send_adsb_vehicle(mavlink_channel_t chan); @@ -205,8 +258,6 @@ class AP_ADSB { AP_Int8 _type[ADSB_MAX_INSTANCES]; - Location _my_loc; - bool _init_failed; // ADSB-IN state. Maintains list of external vehicles diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp b/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp index a5ebfea68c2dc0..2ece79f1c004fc 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech.cpp @@ -20,11 +20,6 @@ #if HAL_ADSB_SAGETECH_ENABLED #include #include -#include -#include -#include -#include -#include #include #include #include @@ -485,8 +480,10 @@ void AP_ADSB_Sagetech::send_msg_GPS() pkt.payload_length = 52; pkt.id = 0; - const int32_t longitude = _frontend._my_loc.lng; - const int32_t latitude = _frontend._my_loc.lat; + const auto &loc = _frontend._my_loc; + + const int32_t longitude = loc.lng; + const int32_t latitude = loc.lat; // longitude and latitude // NOTE: these MUST be done in double or else we get roundoff in the maths @@ -499,7 +496,7 @@ void AP_ADSB_Sagetech::send_msg_GPS() snprintf((char*)&pkt.payload[11], 11, "%02u%02u.%05u", (unsigned)lat_deg, (unsigned)lat_minutes, unsigned((lat_minutes - (int)lat_minutes) * 1.0E5)); // ground speed - const Vector2f speed = AP::ahrs().groundspeed_vector(); + const Vector2f speed = loc.groundspeed_vector(); float speed_knots = speed.length() * M_PER_SEC_TO_KNOTS; snprintf((char*)&pkt.payload[21], 7, "%03u.%02u", (unsigned)speed_knots, unsigned((speed_knots - (int)speed_knots) * 1.0E2)); @@ -511,13 +508,12 @@ void AP_ADSB_Sagetech::send_msg_GPS() uint8_t hemisphere = 0; hemisphere |= (latitude >= 0) ? 0x01 : 0; // isNorth hemisphere |= (longitude >= 0) ? 0x02 : 0; // isEast - hemisphere |= (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) ? 0x80 : 0; // isInvalid + hemisphere |= (loc.status() < AP_GPS_FixType::FIX_2D) ? 0x80 : 0; // isInvalid pkt.payload[35] = hemisphere; -#if AP_RTC_ENABLED // time - uint64_t time_usec; - if (AP::rtc().get_utc_usec(time_usec)) { + uint64_t time_usec = loc.epoch_from_rtc_us; + if (loc.have_epoch_from_rtc_us) { // not completely accurate, our time includes leap seconds and time_t should be without const time_t time_sec = time_usec / 1000000; struct tm* tm = gmtime(&time_sec); @@ -527,9 +523,6 @@ void AP_ADSB_Sagetech::send_msg_GPS() } else { memset(&pkt.payload[36],' ', 10); } -#else - memset(&pkt.payload[36],' ', 10); -#endif send_msg(pkt); } diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp index fdd8431e3e9e51..c7fc9990b30446 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp @@ -25,10 +25,7 @@ #if HAL_ADSB_SAGETECH_MXS_ENABLED #include -#include #include -#include -#include #include #include #include @@ -336,8 +333,9 @@ void AP_ADSB_Sagetech_MXS::auto_config_operating() mxs_state.op.identOn = false; + const auto &my_loc = _frontend._my_loc; float vertRateD; - if (AP::ahrs().get_vert_pos_rate_D(vertRateD)) { + if (my_loc.get_vert_pos_rate_D(vertRateD)) { // convert from down to up, and scale appropriately: mxs_state.op.climbRate = -1 * vertRateD * SAGETECH_SCALE_M_PER_SEC_TO_FT_PER_MIN; mxs_state.op.climbValid = true; @@ -346,7 +344,7 @@ void AP_ADSB_Sagetech_MXS::auto_config_operating() mxs_state.op.climbRate = -CLIMB_RATE_LIMIT; } - const Vector2f speed = AP::ahrs().groundspeed_vector(); + const Vector2f speed = my_loc.groundspeed_vector(); if (!speed.is_nan() && !speed.is_zero()) { mxs_state.op.headingValid = true; mxs_state.op.airspdValid = true; @@ -587,6 +585,8 @@ void AP_ADSB_Sagetech_MXS::send_operating_msg() mxs_state.op.squawk = AP_ADSB::convert_base_to_decimal(8, last.operating_squawk); mxs_state.op.emergcType = (sg_emergc_t) _frontend.out_state.ctrl.emergencyState; + const auto &my_loc = _frontend._my_loc; + int32_t height; if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, height)) { mxs_state.op.altitude = height * SAGETECH_SCALE_CM_TO_FEET; // Height above sealevel in feet @@ -595,7 +595,7 @@ void AP_ADSB_Sagetech_MXS::send_operating_msg() } float vertRateD; - if (AP::ahrs().get_vert_pos_rate_D(vertRateD)) { + if (my_loc.get_vert_pos_rate_D(vertRateD)) { mxs_state.op.climbRate = -1 * vertRateD * SAGETECH_SCALE_M_PER_SEC_TO_FT_PER_MIN; mxs_state.op.climbValid = true; } else { @@ -603,7 +603,7 @@ void AP_ADSB_Sagetech_MXS::send_operating_msg() mxs_state.op.climbRate = -CLIMB_RATE_LIMIT; } - const Vector2f speed = AP::ahrs().groundspeed_vector(); + const Vector2f speed = my_loc.groundspeed_vector(); if (!speed.is_nan() && !speed.is_zero()) { mxs_state.op.headingValid = true; mxs_state.op.airspdValid = true; @@ -632,7 +632,7 @@ void AP_ADSB_Sagetech_MXS::send_operating_msg() void AP_ADSB_Sagetech_MXS::send_gps_msg() { sg_gps_t gps {}; - const AP_GPS &ap_gps = AP::gps(); + const AP_ADSB::Loc &ap_gps { _frontend._my_loc }; float hAcc, vAcc, velAcc; gps.hpl = SAGETECH_HPL_UNKNOWN; // HPL over 37,040m means unknown @@ -668,7 +668,7 @@ void AP_ADSB_Sagetech_MXS::send_gps_msg() const double lat_minutes = (lat_deg - int(lat_deg)) * 60; snprintf((char*)&gps.latitude, 11, "%02u%02u.%05u", (unsigned)lat_deg, (unsigned)lat_minutes, unsigned((lat_minutes - (int)lat_minutes) * 1.0E5)); - const Vector2f speed = AP::ahrs().groundspeed_vector(); + const Vector2f speed = _frontend._my_loc.groundspeed_vector(); const float speed_knots = speed.length() * M_PER_SEC_TO_KNOTS; snprintf((char*)&gps.grdSpeed, 7, "%03u.%02u", (unsigned)speed_knots, unsigned((speed_knots - (int)speed_knots) * 1.0E2)); @@ -679,11 +679,10 @@ void AP_ADSB_Sagetech_MXS::send_gps_msg() gps.latNorth = (latitude >= 0 ? true: false); gps.lngEast = (longitude >= 0 ? true: false); - gps.gpsValid = (AP::gps().status() < AP_GPS::GPS_OK_FIX_2D) ? false : true; // If the status is not OK, gpsValid is false. + gps.gpsValid = ap_gps.status() >= AP_GPS_FixType::FIX_2D; -#if AP_RTC_ENABLED - uint64_t time_usec; - if (AP::rtc().get_utc_usec(time_usec)) { + uint64_t time_usec = ap_gps.epoch_from_rtc_us; + if (ap_gps.have_epoch_from_rtc_us) { const time_t time_sec = time_usec * 1E-6; struct tm* tm = gmtime(&time_sec); @@ -691,9 +690,6 @@ void AP_ADSB_Sagetech_MXS::send_gps_msg() } else { strncpy(gps.timeOfFix, " . ", 11); } -#else - strncpy(gps.timeOfFix, " . ", 11); -#endif int32_t height; if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, height)) { diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp b/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp index e16a6a6a6bfb4a..ad7bb48ca8c12a 100644 --- a/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp +++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp @@ -341,8 +341,9 @@ void AP_ADSB_uAvionix_UCP::send_GPS_Data() GDL90_GPS_DATA_V2 msg {}; msg.messageId = GDL90_ID_GPS_DATA; msg.version = 2; - - const AP_GPS &gps = AP::gps(); + + const AP_ADSB::Loc &gps { _frontend._my_loc }; + const GPS_FIX fix = (GPS_FIX)gps.status(); const bool fix_is_good = (fix >= GPS_FIX_3D); const Vector3f velocity = fix_is_good ? gps.velocity() : Vector3f(); @@ -379,7 +380,7 @@ void AP_ADSB_uAvionix_UCP::send_GPS_Data() nav_state.HrdMagNorth = 0; // 1 means "north" is magnetic north msg.navState = nav_state; - msg.satsUsed = AP::gps().num_sats(); + msg.satsUsed = gps.num_sats(); gdl90Transmit((GDL90_TX_MESSAGE&)msg, sizeof(msg)); } From 6368ec4bd5969b8c2168a7580079a3c9b1220e03 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 2 Nov 2023 11:01:36 +1100 Subject: [PATCH 088/499] AP_ADSB: adjust MAVLink backend to use Loc _my_loc --- libraries/AP_ADSB/AP_ADSB.cpp | 7 +++++++ libraries/AP_ADSB/AP_ADSB.h | 5 +++++ libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp | 16 +++++++--------- 3 files changed, 19 insertions(+), 9 deletions(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 840d841cbfce50..2acbd81b62189f 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -360,6 +360,13 @@ void AP_ADSB::update(void) loc.vertRateD_is_valid = AP::ahrs().get_vert_pos_rate_D(loc.vertRateD); + const auto &baro = AP::baro(); + loc.baro_is_healthy = baro.healthy(); + + // Altitude difference between sea level pressure and current + // pressure (in metres) + loc.baro_alt_press_diff_sea_level = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure()); + update(loc); } #endif // AP_GPS_ENABLED && AP_AHRS_ENABLED diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index c2578fca139cd0..0ebf1b1ce413cc 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -133,6 +133,11 @@ class AP_ADSB { velocity = vertRateD; return vertRateD_is_valid; } + + // data from a pressure sensor: + bool baro_is_healthy; + float baro_alt_press_diff_sea_level; + } _my_loc; // periodic task that maintains vehicle_list diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp index 571f265905f7e4..bb510a738aa1d2 100644 --- a/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp +++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_MAVLink.cpp @@ -19,9 +19,6 @@ #include // for sprintf #include #include -#include -#include -#include #define ADSB_CHAN_TIMEOUT_MS 15000 @@ -63,7 +60,9 @@ void AP_ADSB_uAvionix_MAVLink::update() void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) const { - const AP_GPS &gps = AP::gps(); + const auto &_my_loc = _frontend._my_loc; + const auto &gps = _my_loc; // avoid churn + const Vector3f &gps_velocity = gps.velocity(); const int32_t latitude = _frontend._my_loc.lat; @@ -72,7 +71,7 @@ void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) co const int16_t velVert = -1.0f * gps_velocity.z * 1E2; // convert m/s to cm/s const int16_t nsVog = gps_velocity.x * 1E2; // convert m/s to cm/s const int16_t ewVog = gps_velocity.y * 1E2; // convert m/s to cm/s - const uint8_t fixType = gps.status(); // this lines up perfectly with our enum + const AP_GPS_FixType fixType = gps.status(); // this lines up perfectly with our enum const uint8_t emStatus = 0; // TODO: implement this ENUM. no emergency = 0 const uint8_t numSats = gps.num_sats(); const uint16_t squawk = _frontend.out_state.cfg.squawk_octal; @@ -107,11 +106,10 @@ void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) co const uint64_t gps_time = gps.time_epoch_usec(); const uint32_t utcTime = gps_time / 1000000ULL; - const AP_Baro &baro = AP::baro(); int32_t altPres = INT_MAX; - if (baro.healthy()) { + if (_my_loc.baro_is_healthy) { // Altitude difference between sea level pressure and current pressure. Result in millimeters - altPres = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure()) * 1E3; // convert m to mm; + altPres = _my_loc.baro_alt_press_diff_sea_level * 1E3; // convert m to mm; } @@ -122,7 +120,7 @@ void AP_ADSB_uAvionix_MAVLink::send_dynamic_out(const mavlink_channel_t chan) co latitude, longitude, altGNSS, - fixType, + uint8_t(fixType), numSats, altPres, accHoriz, From f7dd6dec9672fbf933f75d570ca72caf73966091 Mon Sep 17 00:00:00 2001 From: yjuav Date: Wed, 1 Nov 2023 15:01:00 +0800 Subject: [PATCH 089/499] hwdef: add YJUAV_A6SE_H743 board support --- Tools/bootloaders/YJUAV_A6SE_H743_bl.bin | Bin 0 -> 17764 bytes Tools/bootloaders/YJUAV_A6SE_H743_bl.hex | 1113 +++++++++++++++++ .../hwdef/YJUAV_A6SE_H743/README.md | 267 ++++ .../YJUAV_A6SE_H743-pinout.jpg | Bin 0 -> 182419 bytes .../hwdef/YJUAV_A6SE_H743/defaults.parm | 5 + .../hwdef/YJUAV_A6SE_H743/hwdef-bl.dat | 51 + .../hwdef/YJUAV_A6SE_H743/hwdef.dat | 241 ++++ 7 files changed, 1677 insertions(+) create mode 100644 Tools/bootloaders/YJUAV_A6SE_H743_bl.bin create mode 100644 Tools/bootloaders/YJUAV_A6SE_H743_bl.hex create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/README.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/YJUAV_A6SE_H743-pinout.jpg create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat diff --git a/Tools/bootloaders/YJUAV_A6SE_H743_bl.bin b/Tools/bootloaders/YJUAV_A6SE_H743_bl.bin new file mode 100644 index 0000000000000000000000000000000000000000..4c4ab96f0449ce0d12300e73308a76c220e7cce8 GIT binary patch literal 17764 zcmdsfdwf*Ywg2AdoO$E{OfpgO0_G7k5R@SSiDG3k6HY<~O(5DL>g`FQmouO;zFKU( zmjR+ivDYBfMq+P~_&{xepy@SWItXZ=wliRC2zte$4k21kNMKGL%=vxynF*rpy}$nM z=lA>Pm(ORj*V&J?*IsMwz1LoQ4a7)nA9KWf@*hak7yM)G7_JEmiTP@zJCHUbbs_yD zV_e*(?|;ze;{FW2-u;h_+x-u=`zHSX$@dF$|CXk={x6Qd`S0NWpV0aLLm%!0QHUCk z-uuh>mBB%C(^dF41^-^P*etov5b_748_vzW=Z|LyHA|tv>L){kYo25^2hJ#{XMOpmJpPuN9u6aQeQtTY z>y+{&ac&&UXet!9qYqVP#p6+`>_1OFibn}4?I6nWQBJvS#2|7?^N1jZJ16;m>d6Vy zlAn6Y&NR)-3<)BcP78>QQ*IndZzsz4RigalJW&>m6^cZeI!u(iRm^Dm7g2-QA0;75 zOnc108ynp|VB?p2mY12kOdVxsGI`EUcm6^ZTtqRA@q2Dlh0)RumrmW}N?uNDr^?H5 z;=H7)dgurDSSzX0f-gpU<`SoDZFkCafm3P#)BvbKns9y5+LF!&`G=jHjVQkwD|R+W zMQiyYQ=~yI(#u{S1E%{Lq|z?Nvrd7So1DZJ1Z?(Y2l&GDo{vru#cbfr48xD!WdE*x zlk*YB3Mo**+OhU(M~$zhDqqZz=^Uaw6BJ6ec+^O}yacj$pV=Jr`C4UufHd%DNy#=( zP-zN6X39IGoK1`UUR&fN_M_@4+adLo<)~`0A5twDEI+D#j|x-hc1#5!(XmfNj#5 z$T+6)oZ%tBL!1ZIn&R=&gj63E*;=(#s9l6`W*d^GQC*KoIk%iZznRW%+4H*3=Fse< zId$hxWujQe+N-Q<+d8RzPi01cmlC)V`ti(p;(S%tkC&kzP55H^L0YZtFZsx}Tu5pyv%Wl;6cOdJ4NOkYkMPZWD=9j2oYg-# z%D37VOe;FoLw77woysv2F@s|BkCCPW9#5C25OXY*m@|;>Luy5O3yIYqP3DWzi21=} zzsCT7in{S{)@K~of0eT_nGW3?Cxvchcs*(5?1r8D2FN6HC||^SD*1()g|$>SvN;Mp z4-nvT2kk zO{15!rzvTCT9G+K3ba^iyb8D~D&LKgD_;mFYMzTQn$Dg#iKMVK3_f2*l&eNq*@F1A zkw;WF_L1wb_v~rspK*)ys^z>+^bzWED=XIv^9HdeIeh!X>%=L6X};T}ouFvp(5<@@G_4!@&TdA* z$oXQ({kh>i1H`PIyMA}J!kg9&E#5t;%G__@pOUwD7M}C$e&cL#-NM*)yEA=nETUVS zA13(y$S`zg8=0w{o3oqWM(5L3UZq7}U=L(_btCqUZ|*w++k24GSv}HkK!IQ9%fg{a zyQf`|(ew6zjZ1xXy26vj#hyjk<%J=SNS`7~{RrKr+1FJPW#dTo>7D#<1|Q`fT3jen z$a2Go5u9B(bk}a$YUtl+D2cL}ed|0c`(zjP#$g71w2NH+h8O^^_It9AO`Dz3liEs4 zCWbFpcs}zLYk93|yVkJ9Eea09%ffu@(W5~z8Z8A+>xT`^XQJ<_SwW^fL@6BRqQrT- zUDzpL^vS@!ZfMUgHYTr+`N}S#1#1btKD($LueWhjJ-3x{6VRVk(n2q{E4r;clQNFC7EkQUpaw_gk@oS?Tn%y^U* zHak*ZX1m3^D7z-icB@oS@vC7i_S9HDcA`f|tb6pc78+KxYh1%F+r_w)SZ|Fg)Bbfs z`8ri=#)7)UF4?8U?is^5>!QjXBL;A7=7=a>3!Z;4{NkrZ@rKXXild+H6aV$I`Qk&L zF`Z$$wfzxF0u_W@(Wh3kGtMYZ5J>?y%EvxZYl2A4EyKk1-I2zT75OyW=E;oQtQL@& z;vA8ekE*sk3&fs^hdri<$wzG)RkFS7l=>ts_#{eZjfSg-MgmlsIznuN(f6Rk7L1pL z6zC8{jP<>;S<}VBP}y|js6nAh>d5VRXCndZ@Wg5A;6!SlFkm7-QcW%`wnwwI|5P=R z#93dhXfD_ZBo$ILcWANaw4g%CfxT`I>;qq_=z2Y8tn3;@>i#MwUu99}*G&{_z z)&tgJp%7&)Lt7bbzHCNOh*-$2IX+s-JIv*Qjw$kF-`j&}!WHRLn_l#!MQ)W-MSAT9 zk5!y>Bx{(ixuKm?>FRS)dJR8d=0A_D_oRv3ky#G50|^BwRhKsH@(7U@Ph;rmwJ2Ln zujK{=ZZNVum+^&-l@EUQl;Mmi6e0#+wGyn~Ru`zCg<}!kS3MLgj*8*0a~uy2L(=PtrSoR*F)9zOhsTMyqzONOHs@Sc`h zIxNF<;ez(f!^HiphmYj8(>e5-p=d5Ev9;t{x-8;YlovTMoSQjJ^T>>mNT7l%=fy1^ zE{xgbjYI<#SPR~1*Jp_)u}S=~T3}nY|06Zf{OoIhT}7R2%~p!D>$TWP4JD*ZJTPG9 z4E;f}!&4Y?i0|)xifFOjtj_g(-sJMB<;~@v>^-;FeC5Mxfpk2g#qu;#_~(fEMA0g~ ze*?eK^QW*D%Rt%hBgBUFvys|HqfDNhFLy0cfXQ@x{gig(F3G*#hIReU=nRqNe;vI- zW~WHE+H5Emu!p6l+D~WP;UuoAHGl}gz4>5m$#MaE4pefxK=t#d_5T~w9_uZskX4~eO5Ke_< zn(fFIwb%+xkf?}q(se2TEJyY+9T{J93?IYc>PRg&U%weWGgP`@x!de?4-$bcnB}%A z8sB)jhMbFh8Fh8pHoox%Cwt`#FO~TA>s~q61628_Fx3y#962^tiBf>xy zc8=;Ha&PKlvXv+|45vWP$h|3xg@IDSN`5_TsxtWw_f2+kd!R3&9?(*b`^a+^VlKZ7 zYYzCx$7c=vL#~d3C1gf+C|#sQ84-uC#WNBAGV9x;1U<08VL@B$37A>nmN^cYzx%Db z`2J;l<3GPPdS^P`%yd>RRU z{0U#5;*8k{yDf%2`x231ey>lEuF^3xyj|xTfVbfSUVe|#HQ`vXxI2$-)?&NP(`T*` zPsnqCd#8@OFUorD0Q^bRf;B)24%Kn3jnZ2ZSI5^M=!1`;&yZp1GIxag48>bKG_pb7 z(78dT#T%p*`JTF*0I`SrgyL2d|V&~x~Xbs>FEQk|DCgT_67uwt8 z9e%o?O{&drtGi^a!@mXnPRea{C;e&dHnF85A*VvobYhOaliUPb|1Z4{qj#X|ioRGi z!!=oK5yNVJGi0C2_z#UpyF|RBoml`j%%)7^MX9q)?>`Uy2XJFznDK~sI7kFJVn#O0Mz2BN(cJ566)mdXXgsR-fq$L zhDl9}tv}CUhjHG|xXI4c(vCxZCXKvK*jmu!7ql57+iA7f&mnDNuWbtU*gAG*XtAG! zO1r)}Cu@g$H8~r+@jdnV(p))XtuP}iLLcI0WJGcvq|VI8Ho2{^N$AT6SRgI_0z*7j!gM%SyIbh>Q{XV+pbjmd6}Lh1DH<6bq!#&1+_tYIaIbAQd7 zrCpW|Y8ONST9l2m!1;Z&a3yqsdGHulUW~Jz)4xxZ2Q=FhhJgY*)ofxy6KX=u@C5OS z#M_FDk!E$hjX3Qy`JQPrjXjL}j+vv81AS9U_!E4UXQj!pVdbHf2|IQ!?2P$LHaB%& z(3o6ZHj^*Xn2ZP+SR&X&s+`r9x6_vybghOS7irG{mEYs)q62BX(ov&2rHA)0J&w00 z_$l;1Y;sL8gX$OKqp}gRxy7F+=e5&js!Z2t3;!}zth(&^)`Xqaq9%4W19tgQd4)ey zCNs~5^B$)QtnPt`Fc9QUV-L2@DaB}Z_vho|Ksra&=L@a!vIm*9cU*4u-zG0=7wl5D z7L((N)r7I)Y&U&9>8C91Vlt%4@7|zJw}aR%*b#~9TA;;V9wE-deYAwh;ckXXfm4${A#H;6U(+0cepsFjVqQL+H{YT#ztPnF_*%IkDGunHBA{mA`^{4MYE{zdDZ(EJ@zgQUDk zmFj(jjJGi*+uZIqe67vfXcOoFrPBqmz`+NwTGXbRbeCHdZq;IQFM&C?WWTe)>O=z3udDPs0l@C?76TtSpG!4wC2*w{YH@V(bJ#i_;a zN?KdJ(XCh|ys{3qBIk6U;c)&F%)_QYx|lx;kL5} z8fZ~-PXq48Xlwf?d8@k7^19mS+EYOa8^d0?VI?oOt;|I~%bKgg?sJ@Hi)Y=?+TFMM z8dh@7ww1(r2=ua1*1=cA#$mUL=aC=on{v~qE7wL}2M^h36Lo5sBp=7V@sOI}Ak{g@ zJDmZh%~MLAjS2&s_=c4fc%5s7B1kQ{}HJEfm5WJSSPZi+tOnMZOliUv#U3`b-FB zV&2XASkeBqaIVoNa_AKs{RLW`8hzzLtFybtTWt^LC0qSrbQ@ZAjs7H>bwS2OusxZ^ z!Y`-KpzpKW+Aq0K`;`W)h@bx~?Lzriy`=a_*!;_J7Stf!h*X-?TT*mg*tno~@1&V? zdnOeX`8N@R~i)$Dew#jvSKn9`6_(Jj0J>-gH-Ig0G2DwAht8 zWvRL*Pdt&O=ZO}?X%lnB98jNnVNW`=hHq!9D;iC#hoz&5ylnLA>*CMY2Q5ijvx;Uw z?~Fx;Fzv}}w{)c};EG0j68+{R``f?KKj*|HMSYPpeQl0Ylc44Oq@TVwdISnJrj-ekz%W~LV|A?w$R~_!FNnHKaeeRa;=mrQAdx& zJrIwr*jHJ|?#!-^4`pBeqd0*kg^R?LDj7GY8-|%~oYdHx1N*KS-sv~t#L{BNwBac0 zH$0V?1^APW%gxxAT0C1r@bTdEWOZhrr6XVNksZnLK9C#_Xt96OsJ=&9-0@hxK6Yt` zX$i#+Yg}xqbO!E_sIqO0!)jq`ius!M;7%?Mly~w~OXXVmmfRN4Xb(8X{5vN$ zNu1MMXBIbY2vls8+n8meX3gUKUbTFd2miWfrBr#{SqXCq!Udlm=pQTi-`f7531 zsI$ysxTfIUOs5?_yW?8dDKl)wI@nK~@3`DjH_4{OZVj>egv_Q^Lp zOLLbIeXefz$k~vARq{##YJDMg6H4%h2fvKrT$z(aVbq&BH5*zrDx>FbGId=k5eTxFHim)GEbdR z8cMY@Pv!(M^)e}kDxZx~<&UF6-U}YS=Yf1dyiy#Drd}x=qwwjlQ+4W_0h~!{N0tvg zW>zbyrek&dfQ4?5fC=Y!jz3GJQl*q#w=4Tw&f4^LwJ1eI! zGz(a{V>6(Ct(t@Raw`*U{#EDya^O4A$2;L;dmV49J}>z5C&hVvUguC-odq`lrwED9u9b*`lN`8T@sWhpP`!VPyk1T#-vTYXdeq_n*#8vh z+2Q%*SO$Ed7I#W6{1PFe)4=>2AE|E!%>x$GtQ&e%3+#YtqdjWA`xTkb!&`YzRyppX zDczvsHz;Lm@okkfqowOL-1MlDJ<2=?-F^I=LY&qKom%ZDMLl7vjEt=EZ|@gUHi%V= zCLG~xuvbQjBhl9!S*lw?3hqpWq0C%I`I%^De@e;>u~aM#Re@*y@s4P+Z8)nOqZ51X z%M$ZiKxcoY`y@h)hx(erdS&n9O!pGn34NcD9_D8VVLHQ9nT<6asNiQBdJL7M{~+24 zm1v7H5-Rn=F9mz}bF9xm$F@BN(G2^IzD$&ZD%}~6wVwCp6URGyZy^@(?LIQs8Q`7V zTtTJR(pMvUxw-%5p*^{{PgvpCq{S#t7gR2PAZo^akL_%Hr50NZdor=hkr4CGCG7TT z9Gz*>?e?^pe1tfet$xXgggtML?7=Bn)XA*+giSB>Xfe}1$ISllNc5Zb`~uK#>M+ch zj8lp#IhXP|Imz{HsiJn;4B!3;ZQ<+_s}<=3WlW{ZKYVw~pj*t^V2kM~RXqVZ;; zR2al`l)gVUYwM)`{whNNcLRwytkrs z9&}-KS9Ce_OP@1x35lEOKbr&g_yxPhkP71B{P-G0Pm>^4>%!iyLyW4RgU%wHFwH~Ks2%0=dm4B!~- zwCH2--Mz9$adW-s&BiixGc2s+5OOW{hGxV#9);>HSPj){%w6L+ClziB;l?Pr1%2HR zcqDKNV86mDnp9}+NP~WUq2Z0Dgo7^)?+>nxo?*xkblJur$4P~y9R_hBT5Zs#Ezx2> z(wGOvRM=2=Sk0OOk?jcDX-Mv3)C_v*8o{2p2Wh(&yG9fGu|F*0F%vCzllDc_=3u%+mE&WUPTM@&TqRm0 z8t@7{O@1){!-#;GlHrJ9V68W=GXDnLDyHT6N<-PuFO@G29Yb8hR8USelk`HrkX|AS z1NoHQ9!ezVv|}m>OjZo0kq9(#_9o8~mA4J)5gc0VRGe|k=CH%_Q7D$^?+Yc^;ajj$ z_J>QwJ<%*XS(c7@;q7&qg(ZAjI?PL)YYW@+ph?|v3X23cwxY4H4Qs*z&VBK#gwAl~ zCf||0uqJU{Te`~g$zHrJ6Bb2vV((CtglgPm`9#=P`D+RU!+ZH_@>k}sDIX%``72YG zaOF<<$X@SI@II$x@-Yl9U_gx3Eo84(wbketSo}yOx18ZIbx;R(S8($%^8n~^MON$w zTI`Ir-2)3&ucceH*gG2YOwn?-QjESPk8qShEaodvaY((Dv$+^;EG~tI{gw->>WCUH z$dv*W3R?$mZaI6m9MCwt*c})QO6D$B9_Sdyl3PXWh=R!+|E~3W_1Kv4@A251WW3G& zh_@l*@iu~yisI?@53qO}Y1!A~Z5W>MSRI|(E=D6epX@$IrK1WrW6%7fcHdi5d-HMf zDLl8yQ_5lx?D5#0Bl%S4|o2&1K`>1h)-iN zY2%5}XTr-%kHvnP&_l?Ns>JR%O|S>BcqlRlD;+Wnz-M0IB@XD~ynmO4evfr2MQsWx zH1x9EtpwfZkpeg^S(cV8OQXdN*-v{A;dC?7Ehmmt!|QQa%`av4+GCWxq|iFv-)bCt zFB7_P_dfXU@#Ykd&CybPht+168UJo|nf0>EHM}sP%&3=Hx`vp%iP^mq`)jkvV8Q)5 z;6MjF7op0RLvn`=T*mGn~CsPM-7rgBAw{xU1(Ot*%9DU{xT$iFbgl zdKFTOc`ZOqCZxW=s|a35e1QvZYf2f$kk}b-gk+DZ<{w^T!rt>kbNBnuusqmQjK1UY zEpki6h-sQ$dfb%PZRl_0kI8@N+~lu(e1*JsR5?dRFLgZLnJxFq&7KKIGIJ00k%EMk zY=>Q_#Wrb;u=HVPuE&edh;U~0V@}uaGdDs9sP~XMHygV~r~689+h&t&a&GyRk2mJfYhNEdH{?Ej*v+uKgY$^3 ziE$oP(RTnYAP zbAlhtu46aCY$Z5p3i{72rI)?vF7ZqbGp^FP*cECRrcd_HE(bQ7pe~Rwvr~I3$g=|DL2rvFw%}xpK zeXTz@>10o{ydBYEH><*v;8SpWe~P)K{EY!&(%GKu^0e}1saE<;l-Yimca0$4?SIuj z)qUwuaQWSJd>CU^$7AxF_#fP5-S6RkLoUbOl$z3Cp=&*l9Tc|a>+sz8DURyfcoATe4(G?e zqc=y0d!9LUYh(C+J0yr_^Gx61c6C-Yk&jy?r@kjB$8plU`G`CeB!HcT%;1LH z4#qPZ)-9PqX67?{Xog2=hQ&i>B+5pQUoA3DYq3X19T()|OvXYUU=B2nl&b)<0`N4i>A0*0FCCdW) znSH=^Exx}jBf@stA!2J^?xoc=N#|Pk#IM_J@%k< z&~Gi@fT#|>t{~)H#n;7Sja>=;1%LosucH)mzI?)|*Z^e^AoN?uYSM9pV(e z=q>HSNQA|W9Fh+rPUMi}P2%(F_`G%S!_@Pu6R&28*b?R`dSumgxU>CUGl<#kkKnry zzLB<7e^~`@!!27pZS~wywz9gDp4u;gpY3Vmu_P>pi0#5;`YX`5!ae&DACeMb@gppb z)7H)+MA(_6KKWi>YUWG*hO}k5TNV|Dwut)&+>`Q-m59tbVZW2v?D6XUkhWFstK9S4 zC2jTSff%F2_&?TIj7gWL=Lj3^w^5h4LOdV)WVCJ7Kb7BBeoJ{yAAce2X>oMGJ7S<9`1YhW9 z5%X_1i_eJT@jv9U*Tk1rRd+7dCAJ+BV^KD`kC{o#bWQHgexvCpIQu4x?%8?A3uYtVMA+K+hUst{W^7=HI;Pd1N z-hSFQuG-WtENIQ07`94>5FK<#I^@qS-w1Crms|~u7ZfsJl7N;gk91Ps@>TdkEGq66 z_-)SehTJ;N(aU6|mr<1IU#LghhVgRUf7_AgWAD_D>{%{N6d$gq4Ma&BW)}Dh(x>%@ z`-Bp9H#*!$$`AJ$=V`IuYDI`L6$a)~n|Qd->5{7vTU&K>Rkk-=&uC(PWuNSoHpv^M z-^+)jG{3jb=jZD;`MvdNc<(|RyqjF>bDz=fSx|XYZL+0eZ)(DAvdQKc(&`xJvr_AS(fJ*@%NWwP)-j{>}fL~9-PXOMP zgm(honS>7m-jRe)0Dd+Jj{$yK^HES$(euNhY4)+D^uVQ?J6 zt)N|>R%LU}|m|cIPipL^vLO&SpY>xTn$(MsE8x4!)lB(4X_#&$s zHsTkA37<7;za%GIdK6CmFDLjWRvnY=LnrD|gp~ADZ`xw!;~Zl#q`3W#+06J2)t+e? zav64&49Vu`{r*PPL4X6a6Mn>S(;t8SHf};ET!>y{JMTo_Ei&#r4O!uVzgn&V6^*!e z-zQ&tvM$AUe6{nR8$m}r_Svwd-H5xorOV(Ojk11-mDhbyjJDZ$gDXbLNJg`o!Hw}~ zRt8(_>5#r<&e7FgSb;|ye(gx{ZL5cF7x&f^$F{l^4ZV12p^g=G?4(Qb1u@`kO{G-9 zv+F-9r@4>qZ8fbqjak*1x)auSJQhy+^&uy;HR{sfpl=CTSO5v|*a%5~&Nc8UXmi-_ z(&`oB8UI}xcM*J4ZNzWf8sQIW#4i~DL8gtQXN_CY-0mTbxQ9N%ZDJkiS=qD3hB6z< zY$&rO%di^An$zx@HK%K8uo?*aJ}{U{#$o6l;AY_0b6{^qo2@9@iZVS%*;bUbpsWRD zdXBOdls$p6Cs3y6D0>2B&!X&Els#)eB9w$+vUw)vkzE%bOOcyF$> z(3iU=bI83;!0$1F#knidawXGo3LP(n*4LQEx>@gBf2LB(jYg*rRXj^QfKm1d#+W$B!{3rO2;YV1iuUq(c z$pNBp2noV#Jta-eW{1s98n_f%G0|ZDFfBxFg!$&ECBXr&SzS63;;46%;zZisWQUKemKSc1LVWQCVMgRv%~53Wq93ZaSUH}vNKnUwc+>7 z6V&suijniNX=CSO10!1O)3HRGuKk1{Hnb{7MEqXS!9J3~;g=(cw>8Eu#9dy^l{dqZ zBsRkdel30-QQhXD;p{xTHMq{;cPl6EV7cN{#l3>Z&+4GCn zj(^Q9nLU3VOD?9_D+q77nNZtu!rQ)0$kU+ZzxaFR5@LQB=`EyRAax?WfV3IuUy$BK zVqM!2pZZgzV@Pi!MUc9XUPk&c(x*tQ9TuJb*8nm0oj8Do0%DZmzni z?AzZhyQ+54cPr=5Eg`Ns#U*p+T{XY->N1bFe31w=`roIy;O!J*UW^zZHt$)`50==R zu0o5@5^!NI?AHLL$Jy)-DFS=wLXTZdeCI9|jKQ USB (OTG1) + - SERIAL1 -> USART2 (Telem1) + - SERIAL2 -> USART6 (Telem2) + - SERIAL3 -> USART3 (GPS1), NODMA + - SERIAL4 -> USART1 (GPS2), NODMA + - SERIAL5 -> UART8 (USER) TX only, normally used for SBUS_OUT with protocol change + - SERIAL6 -> UART7 (USER/Debug), NODMA + - SERIAL7 -> USB2 (OTG2) + +## RC Input + +The RCIN pin is mapped to a timer input instead of the UART, and can be used for all ArduPilot supported receiver protocols, except CRSF/ELRS and SRXL2 which require a true UART connection. However, FPort, when connected in this manner, can provide RC without telemetry. + +To allow CRSF and embedded telemetry available in Fport, CRSF, and SRXL2 receivers, a full UART must be used. For example, UART1 can have its protocol changed from the default GPS protocol for GPS2 to RX input protocol: + +With this option, SERIAL4_PROTOCOL must be set to “23”, and: + +PPM is not supported. + +SBUS/DSM/SRXL connects to the RX1 pin. + +FPort requires connection to TX1 and RX1. See FPort Receivers. + +CRSF also requires a TX1 connection, in addition to RX1, and automatically provides telemetry. + +SRXL2 requires a connection to TX1 and automatically provides telemetry. Set SERIAL4_OPTIONS to “4”. + +Any UART can be used for RC system connections in ArduPilot also, and is compatible with all protocols except PPM. See Radio Control Systems for details. + +## PWM Output + +The A6SE_H743 supports up to 11 PWM outputs,support all PWM protocols as well as DShot. All 11 PWM outputs have GND on the bottom row, 5V on the middle row and signal on the top row. + +The 11 PWM outputs are in 3 groups: + + - PWM 1, 2, 3 and 4 in group1 + - PWM 5, 6, 7 and 8 in group2 + - PWM 9, 10, 11 in group3 + +Channels 1-8 support bi-directional Dshot. +Channels within the same group need to use the same output rate. If any channel in a group uses DShot, then all channels in that group need to use DShot. + +## GPIOs + +All 11 PWM channels can be used for GPIO functions (relays, buttons, RPM etc). + +The pin numbers for these PWM channels in ArduPilot are shown below: + +| PWM Channels | Pin | PWM Channels | Pin | +| ------------ | ---- | ------------ | ---- | +| PWM1 | 50 | PWM8 | 57 | +| PWM2 | 51 | PWM9 | 58 | +| PWM3 | 52 | PWM10 | 59 | +| PWM4 | 53 | PWM11 | 60 | +| PWM5 | 54 | | | +| PWM6 | 55 | | | +| PWM7 | 56 | | | + +## Analog inputs + +The A6SE_H743 flight controller has 5 analog inputs + + - ADC Pin4 -> Battery Current + - ADC Pin2 -> Battery Voltage + - ADC Pin8 -> ADC 3V3 Sense + - ADC Pin10 -> ADC 6V6 Sense + - ADC Pin11 -> RSSI voltage monitoring + + ## Battery Monitor Configuration + +The board has voltage and current sensor inputs on the POWER_ADC connector. + +The correct battery setting parameters are: + +Enable Battery monitor. + +BATT_MONITOR =4 + +Then reboot. + +BATT_VOLT_PIN 2 + +BATT_CURR_PIN 4 + +BATT_VOLT_MULT 21.0 (may need adjustment if supplied monitor is not used) + +BATT_AMP_PERVLT 34.0 (may need adjustment if supplied monitor is not used) + +## Build the FC + +./waf configure --board=YJUAV_A6SE_H743 +./waf copter + +The compiled firmware is located in folder **"build/YJUAV_A6SE_H743/bin/arducopter.apj"**. + + +## Loading Firmware + +The A6SE_H743 flight controller comes pre-installed with an ArduPilot compatible bootloader, allowing the loading of *.apj firmware files with any ArduPilot compatible ground station. + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/YJUAV_A6SE_H743-pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/YJUAV_A6SE_H743-pinout.jpg new file mode 100644 index 0000000000000000000000000000000000000000..095c7ed56d1c27d988648852b49050894039b82a GIT binary patch literal 182419 zcmeFZ2iV)x**E^AP*w{qlnsS66bd+rBoEmNNx)0CBwMz%ZKiBXwk+8imTlQULkp#4 zZzu_~Y{F_7fdmLG1qxvX0t5(j00|?|QV282|2#G!38j7M`+u+Nd%x>L8IPZ%qg&_P z=RWuN-S_dj=hyvd?E556;A0cMHDT<0@Mmn@sX4_#L(2hlnRU>6H#<35)7dzGI^pOM*I*A z{-RTm;It4r%^#ll`88?gHsI5Ar>ah468Pt@1Ha9f^!dDcz24MbV5;fVAOyp(aWa1Y z6wqTzyWetUZ%V7Z&xpu+Itis+aWu=-%+|zlx^mgb_ANB{Pz!C75^CQzj@U#HxgCo;mcq1aCo?oJoHLIH1|1u3E zFrC2A;S*Xgc{AB`PHHhrSeZNG9t9P2^maG}=p*Vc8N<+Db8t$g8)d*#f>)h4CLc9 zUufxQZa~+od@0Q(;0{5MW|oZCYo$5~SZA}a;L-vWbNWFjpBxfIavWTeMBI=?#H&gM zCYJnlOK!UDvKZx-D?~LcN^DxFX4!V9?Z{}?WTH_5OrJ=^3P4;6#bg`^M0uRI^<*LzPqJA)iSrCy zCu$|HR!a7V1kG}~hiB7Fkfr0eKx&n4azG}SM6E8fd|%Xx;Y>Uh$g{LUCTm`m*L$_$ zl*vX3Pia-Xit~Ypog4J}HET!^_T>k4lGWWT$A|KaQ7wvsRhDo>kr2ixHLIp9T248I zbjtq!YWhQhzJx)Fq7l+cO{-IBl~7f;bGjwVEt_iEHrjU`+t-C;AZS2LqVeRoh$SLX zj1SsjTqO2HcpM7ZCiORy-?orGNKu?*KKdguTGjI3i; zHyO0+RZ)Wray5+(2^w`PS!g9Pl~jg{;hB^G$t;JELex*%OuH*KsdhUbk`;+cHCu8e z0qm~;^%AzLIlLOG%3`xg%P9nQEv+#mXlA-t%8T?whjBxRj$09`X`iSXLBdoyELZBq z`bE*HC9!@C4OyDa`b0VgH~1)GmBpN%Ewgbttg%5DDUB8-Wf-jvp7#_Bj}RiM5CNY; zSwe`1?Vg5o`Usl})Lo~E8a1Puk?EqTm#`LwGlDMEi5?Yc@KrfzV~QvEha;pq;M0Ha zzYx@m%S3<<*}CcLwNZOWFwhX1u-Sm3gjNwaJ1uo#HC+^wxRXS?B_@!!Q%Wu-cjR=b z-eFbE33!4CdHD)ZH5oDn!Ob36X()*eppjtr3o1soQ&i{6oou-pYRV`=hI4Y9isy0x zIiysiY{iTw>N3xnIg2Fy{z%mjQ;JBCGCJCN8CGNZqMc13p?oJFiE1%VK*2!TLiIoX zZ#d=kkM$b^L`_M8TZCIWO!c!3Rm6*eSm;_(w9X27qQbETr`g2-=2?Beuf?Ga3v((E zAIwmcf_7T%A;AJJ=3A)A85L8=;D%}0u43jWn{GHzloYzIpzE$mWnnm3?Pz_^vHB@F z$M`derU_=>2MfcACK|L+Q5q8Dny?nEaeXQ01|zV;BvD!A;&dg8;u;wvCAd#T#Ha(C z9Y5u`0@CVxvSidNoR7C01rBv_67{zTCmVKrLxN#38$*~zgmn6RxJngmP0jc%Ipu2) zP_VPPvLCbPcu|mPhsu?5MJ>}CSXim76?mHuI^l+)IVqKNL;2EZ>(xzPGdJMqJXv-t z{kDLU$wrLNnk9dzQczu$aof1m_I)i$9ggr{iM5pu=@Cav+5RewiV+eKOwnfrk|rsT z2;WRGwM4h4YO3i8!ERBJx$#3!5^szA{`8#7)8{j}kX~#BJK<)BvipiqjjVam9bGrPHU?vw2xIM2hXrOSCiZ!Be*&^}{B4(#71WJ@~ zp0@LbQsyzjEpuqNf>tmf4ieSxb;WY9P9+5^%2vBVg6<9pc3DI5QC6a&8dW7xi}9FP3@04TCi9^x+VC|Tu@7;PK^(@)wSm`WNUS&{NMtlV zL%D^n5A~5!BM?eil&vZf9qYIR3j`RWeK2rKlme^Rg<9V4S42TXVM(*YRfPe{EC-bQ zNRJE&{s(HMK!=^CA!d8^j#Dp&SgKBCJyVTDg;*pj@cGD)Ade=XXx5dWIIBirU>YGj zR~uKJz!d2%h|Y~`O3utfpEpDkoaPL=14#~qeZ?w=_t15RtlJcnRVWnkFuI%106p34xRe1$25!Y)?L;D!RFv^Xd`Pg7 zOlT>w$_EI`%Lq;za90J6B3%^2h>{SbPLUwVK&~ZrOo`}_O~DGa7=tL)fDC9^3Q7tY zC6l$W!q+#W8to$xBp{HM@k9j|_d6GJ^GduhuXMaiHxa#D>`rEaybbNIOgx35h|&Okubr zA&G%6ZsibJ@Pq=y;ts}j(l|z=Hrh(ZYnUPrN7zLw0bb4ulEHhvrf5UJ_=-&*Ww%|d zsHtGz`ix+qU}6>t#iCUkkEY zVpxteS(?;qf}s=`!;py@Ocw%h0~g|GE7FcDtiPo<PIvC1VwArpphf1=NipPayjU5p*44p2fO1eUteaT9(fnG9P zv>mWlx{lcBiM+;IWip!*X^-r2aL+c}zML|s7S8)Nw!vg6JS1obT!#<@GT^sud_9uNSO)^Q5s`wfjTiH$j2Db zuaPG0_RER|EE^gyB*_*2rRk8A5s_|;sE1e<5=oJRSzgzSP_%lR+JrECq^4shJB4IjUXXcxD?5_a@#n^SL`$rmDRN z)=g7EJUTF)R7(VsBe2qdwhRxq%AA~$MLD2n;!HiCv>I8tW*|g7;(Ab~;0t;JF-V7O z7fZ6($a4UpL&xdJ)mAb~o3I`C%Tbo};%+LKr&%jhas4Qe@ZCo3a^0MFU zMadv<#Gw+#6cEaXGny@+A=6XYvQY)bU(EA;U@Az z>}DOgTtRDC-GUoAIPMo*Tm}o@WXzD(j~JCKRktG=m2kV79c>`tK@xXA_rChJ?givX zo%IZ@XanhL$XqZQNE@6kC&T5U-B0vuQM z&nCLT;Rq8QyB|kfn&y3u-0RsrQbGu$kW8lPxR4G6Z4eKwj}-n*sKNTMNN-3`rb|*D z5knn=4VnqGnkqucI0JO9qUnH*?ANl2-E^1E>w_UdA=5^^eA!o2VSlC{RwUNVBeEFA z;{AHnBylXKeW__%gJ`*C zxA8&?*ip`w#as#xSz^%hY^mCf2{>DA3*c3B%fOHjS*;t9f?iMg1Eq>k2CmG=v=2w9 zMo1D&Yv|QPW9yxmC}OisNK!xjZUW8=&4V|}pHXcc6j@KOz zlH4J|vdm;mfWLGsF@hLHmn{q7V1Vc*6)_FlK)K_oQl{Rh6e3N(o==w)+X?jHj-!NK zxKplrWP+f~pbb!(z(@`S4oUD%nsZdtQwEt>g3k<{ZmEL`S+Rt)y#=FqLjyv+Z)YAL(>iFU>n$EFf3> z9O_YJE-2ZoQ@5LPBLVO*zv8D%7Dn>@U^(4K1H%!b9Fl~@culZMAqIGy4y%R(JP{Xs zuv}3aLD-k-P-cS*4_H#_7%pAtk|h|4;c+P&X>kZI7+9yLwTkm6kILCqzoL%XUe_! z2xifeZ5SpUvLYpfJgFBAgHNljW=kSHkeivluT*Y^1dE^oK^=+eUKfqh8Lcig19{nw zsG2W~3vFajZgBL7hahl3>7EM|lrHfyOXH}PFj5|ka}B9jYZ}#vz*N1w1@&ST1m`=U zM#?pk0MH49V<{uUMT|zQ7%9b=95(_a^|I5ZQZ}%mv5ch{E>7n&6l}OyMZ-NZPnbav z$wE;`jR z8n7i8+fnFPIwDCxjR{~)9HpOhAtg}Bg1tiFZpq3EK@AI1c`im18Xg=e2VM%}avAul zA-53eW-2IbAvq{kuL%vWLncx#(f4RmhSFrDV8=xt)dEV|pXb$#)p1i2M#;5!gf|M9 zM~slAl&(V2m`~R$>2x##Bt>(8C(`YhwT!P{f<(mtVJ_DJFs)u4RJ3|gw^@_0BoGmA z3Lb)>bvWgX0mUx@Sx<~~Ny4onte;?tWi3ar&4NkQyhs5LafPa?*@dcIwA-~@gB1r% z0J9RrKpPT_*%n2u>kFV)ZzXMo zY8r8eO@wLSZPHnRQJdAYT5#F~WeCEc6N^x})Nq8wFpNgWy=H_8!eZDZEdYPFI-(m8 zagIuo8K#ZLm?kekN>WYIcF?Yc>LICVU_uy=0{hSEST{vQ^+t&t5=7F#`)!#%0q8!X z0Rgk9`ue~cXvlz8q zu;Hqt($9l1y95jr0XcF%QR7R#0$H`;Rwq?1wmoO$IRIbdt8kTet5tJ@V8B6LOvQ0g zZ#IFqtP!R?0I)zb8sl|<@WqvQu-52g6sBa7hB%xuo092TKi7!cZ6|IL1YH2`74(IO z1LZ_112**=OPuFAe2>Z&0I$DtBK{O1*RLbAv zGkr3{=YnDr0d`qRg(F_84^;yJA0B4t0xObbwl8qRfH3($o)+13ufpi5M!D+xha(iq zaF-vH$jU&eW-?qg?b;q`MFu2}ql0WZ+v+s|U=tJMR#9+Zzffw)D)3z4vIuOHVBram zPJlq)C|9zh@HSnnAr4=(fyCBD*x^!S$;n0au->F8$o7N)O2Q6gXf-H=lMshXExbJ`j^L)JU68L(w=jvU)y{j)-Lg%}_ex zr810J5?#mOVJ#j3L2fyU0X(?r(^1EAUD@t7eR<%=A#p`8+Kw_@ z6uwtTiA1cB64JU}gi@a51j`^4w?d|3Dk5DFS(PCjHkd47Igy34Wn2!!MJou~c>n|e z4`o9rG$hziTfo1AQ72S{X_|urOo>(iWM6Z|wpn6uBJX5tb*9Jah8k#?@x0On5TFrp zpk|$P@=X;>aHyItlQf5g*DHR$^<7l;~M@&O&mdGL^)FL49W(Bzz zz)}IT;{j~LpPz>AYCKMUaM2(?E#2*?7wxsd~ z?f@I#V)|Lcz)CXR<$+}e!A1-~3@NkR6bN6sB!sz887X5F3L@18okIE%UPas@*JsGS z<`SBY6^1;FSI5US7+)-_te_CcXa+Do36`%CZ_xzNhthhyUjrMDGC3?oIe8cYZi(&p zL7^nT8ELS{5C=iglrxG(!;sDar#(=#BQ_F_*cmp6BqUdWB@~Rd;lMq;>1zYT$xe~E zYB$@{8d)tO`PyQ@21&apMZstmm#lyua)u+!<(Z7)xgnBFxyb^T67pQdrSd|k5@m6r zBM5xD2m-Vg?o}8ulGG!EO3^ejIV4`KcVV1Wbr4U+mrwfDWVB-_(#hEYopey;y`3G8|WyP_JTiVnv`=1t6?M6nL6^ z27pDqgewLDKwim_I~M{-L;wW>oI}bgu+2mZYKCz!>#M4nt`Qz6M$>PhjG79=@W8c@ zJ`v@Tm=}dJNtY%Uv#t2|`$z?>>dC>V`} zC<7$is7j~hXF77*2ANMFV|LZ66ht^_c)6ff*LdJujUp)%=gWEv7YR8O0$GzxvBA*A zHsQ~fNWFz|dcrs85e$M?F+UGS5+LHuRLKY=6=1C>A&?voHwu}OolXqc_Hcxb-X3Hr zhA&YS1!@31K~97sk%1=hF(>7SB~9!%MX#hXW*P3}8DF1*OmRS%^=lwy?v zM!?2LNv<*#Ksrzp?Cv%rqFkROm`J8uwxgmfI%zMRa>WqHe07Ps7DO$y?PSViHIQ_g zc&m{Pcl>P-7nB83v|?CfI6{GK%K_U#OF)g4(EcDjh!LrvhuUJ99aQ=`z1wSA66_P&+*eo$4ad}xKJ?if0n>iO-_QaEfe-Mk8V*tSb=n{vh%kW=41^C@)dmezRYng>1z>LQ zX3AnB>6T{j0w%nn;Z-h!_GSTxxY2Nm1kAVtNi)6c5pGg70x*GjIm03 zEf@y!FtW=^#Vm%*Oq^mfNDuQU+XFs2>$S^zCPE}Ya9bFUFlv5810Dw+Xvz@l^cXgu zDM%m@F4JV97xY@X1yXCHA}A~?6e=Ct$K{=zt9Go07?bg0$rlTHu7o-)rFA1Bl&H9o zwjkFKt}kN&({>U$R?pVtb`pxJojTMN#EcdmZap}LqiB&gBY_xDdEICz=rB}UE+-H?5CEyukxSf{c%y6KB0{l!Hq8}5 z4UJGM`fOhJ5g7n8(?B!h4hL2ykK6rb5EeL)o1_BSWMfeC{J>R=)A5v%PhkC#V1sN* zl>-<%TL5k5g2_g$*=EBY$HjvzY1DOHLgFkL^ydPZ zpc3=-vw|pMeL|0CtgPIx@Ys-tQlo+v3!)HhWrDtPIRczMK|*~2NN7vIEw@rSG@g*G z(+uEDkioYtHRj|U?xZMHy zm<;c4R}~~h$uzK>d_^Vl@lpYeH8Wg}r0y)YRTg^16a!S=YMad%3Y@PK>u+Hei z5o%f*&o=}k*iE|y2*f%Vlua8L408Ehk*NtKjwXPW))GFD?BKd;)~M&JnF^Uq#oYu` z3Nlo`NpLhkdzzyheInN4qY)dc05s2#!_97az=u1GS_cUhp+fX2B@S{%VjynFa1rPu zD63~-zb3H-ThfE|nh9LdMyyeYCUtl?!gQf%8vqjxgesk~C^I7CxMrHg{aU%1V?p_% zCz?JOWLIrI&}CBhffaS@j%pxKnFl@nl{?8tq>V~o6qRQ&{Hu}#XB zWxMPT!~VWY7)c6LB{XRwk??|g8#n{3AeY43QC0blWLNMgDdhL89s{wTbaSbt=hTYDHhmO{2 zz`y|jwE|EyA(EsE*P~c6;$_e%q?(O318_;GnhO98Jm{yxY|!pE`jMt$EmicmC%Q!WEh$TlM|#6WOW2C75PDs~*rGD=QJctxX?b?CGdPEc_U z0f>nJ^5s-85`x5X-BnBZLOxp{Y%hu=oyus0P}Q(wW}l*1r5Up2n4p7NJdzHDA_ho7 zflwEY&~eD(s7y22ZUEd;j1~o^ing?N>F2rJK9&8rc zNuvzJ;FzxwO@MT`BB6R*h+=9@ghz$am#r98&-oPM=c2}ehs1J0Z3U|=QXSO@?K z2qAO>06d8XV zT2fGLjGJlGr_y-b(Ar&`1NdFTOu(kv0J{a0#|%t}G=gAnL`!vss-@gGxKmE!Vm%aw z`3RNCsyxp7hho$45xnC@fClZ-K>6!~{=lXKss!p~8dk?b9W|p!kp?g|{&WWi@+^A} z3i3*rI7lR;VWWu(vA6?=`(<(jJ6on;S(pi1saCJhYauX}E7ZK29ReOeHdjk?CPVyv*v)#wY5PR zuGlz$43Zi!B9u!S5m0)o0!$Q(bw`UrC)_lMOyc!KL`9e)pOw6Zo|D4}I&PTgFr@XR zejo&}6F1(0oTiDISfG>*B#BI=@AWB(sOWiL7!-%_pQqtyngvxLu{=P5<8r!C4i?b5 zmBo!xwpXA*bqDR|27FGTAe8L{^X0I?=SzW3$FkG9M`EdtDZu@>nBe1qkvo^rBiU*< zRYZZ3NalG0fXQqZWDW}c3WTU=K$e7dvo#pV^>n2N%C%dF-t5$H)fdt8*+^cCnmGex zz(Ea5_j6~dQ%0kH2$UBF!;Dn-B}(-~p@sQHsp13HLE9KC+W?z=^{3$~gRpADT}sWW zbTN~w5ChMT1rnK@5CewOB1&l7GF=%|U$o)YAcpewoQXEuXoZRu>Upoi<7(XqaW&JeedF zDV1YN6rYR>jt9yh1(%P26wD|MSEuVXQIEGUG!E=uj&0d+G7u(;)ei6$K#4~n31gvZ zKiO&9el%XG*<@O41p8T&vf5&}#{2YSOvsPY?n54arD6LzNqJ|Gu&R(vw~36XP)XoH zAVY$tA5{4WM1y3cMkofrRNz$xTc93170Q#Xrr#%VR=FWrbWX3iX0Y4|w8bjnHyWy5 z5`t}A_27U6cS31G8+ouek0*Rmx7DOgf4b>c+GN2_%c!0-lEpMqfFTVE(@~j1qD;rO zJ;;DUJ-l7CfUffoB7zC3w#))b_8h)FGW3KR=G2e`Txmv;)Ql0fssoa)$N-?0-6RiE z1&UmX4!B%M#n3^jYx$bBfIrx5`5S@&7Ib4hG@SA#b@&_K{cqeD5?rse{*9XZ$}X;9 z06+NDu18*SYwB5R$Grd4o1l2f% zzmesUOr0z$8GGPs;!-U@kZ`e#5Fkr6BxrOje{}!~iz-q@YW71l7)4u+s*@uEJjZxc zGU23p8QX%YVV+L}n+|}&ZMYo@62*R=rr}IKM|e(!CaZ%{cq>sHtjj4rMcQmWDOVJY zr{yM4z?sYd@s&C)$*+mNuH2#(xj}fojwAc2xJS9^1Yzn;0L7chM!(l#I=Ketv=gGm26NdpMM%oc@u5(`3-Q+z@|YVY(oU` znV#-hLgqPv5bT|jJ zuq!tdvZ545MNo7%*=!{Tu1u=&YPc3D;qfk!W`p@mP!vJ2BbaMDV)9TgREn@pwBAn@ zcpmDe0;v#iH*%ZQSPXf%QQhm;^P5;_z(L@Mmje~m2!OW*5&-B>$LWXMAwf_pA}eID zB!oPRu+wlo3$tww1k`Nb;ezqJW`Th)34h<{r0Q~0YY*~0+$!o(kie`}?54p5gLVLg z^N=tKZxIf%lI=W@a~G6(fVc%ZBj**r&k}1cMz!ko4yj62 zkd4qKyWeMYkgy37s5c7DRDYcI0W=j9YeK;w?LckF$2E#JC}007iCW(VL6|;c!)d50bCAmfHp=g^^89s#Yu0K0l&3oEy}zl-hJ?L+ggQP6v&y<{HZSv5gK+{+H)A z!SUN^hTH;&XuT;_MU_F_%%qu7bRwIa7|UfR3dpN>p8V?Fm#w&U;fjTqu9$oCYiC@s z;>rcDpK!)&bMBq;pRo4JNKmW z4n;GY{qp^d)_?ST!mM=0Wr;}41PxQGT6J0k4Tr;^!VUKaLdhh8L=wS3JQfc}Q9KyI z@c4St8$J3@WQkTAIENMGbF$ihKz5@?|A}nQ(ZE@F+1TjSoerQKu7ZSMxEz>LR^`By zAf|+-l*3qc3W`=?1oM}%aKyiU*k3{8pWc&D9IdNVamQ?a&4bF*hq5tE+c59Zz`}kN zg{$Zk7z5|tgCR9E1q;FcDPcrbv2rLFP-JkH`JbNMFre|39^I~PSgHSD&j0l6SCKaV zf3bD+im#yYRj+dXrM!;FeChrM66=?5qovtMbA7%W(pnpw#_w-*W1N5E>KvS+*|c^2 zjsNs0dfNqCcbZ%o-*YqDGLVw-_1maz!;rx%Mi*GY@eUga$M|0RdYj^(9{tz!dv&Gt z@4irAL~7XUUlVDYs@sztC0YYo;lKW-gAvV5ANtqCD|KKwlsuSH&AzxkfBah$CV;!(-xoK&?uT{vjcvcx=0E%P z!JAFke(YP@PuOhx3G4nab{+U4w9Urt+&{0^KWnSt?z7T8{Gl_e}8Oj zi_OM6eP@fUw%T&r&9)u;7U;Xhge|w)eup3Ivg`9(@3_;>!uetGg6E`P|LBfqukr4j z^vsD@|8jn$i0t!Pt+#)Do2dWC4=hckpFWpA@2ZD>b?qN_>z}l&017jHfj-Oxe-dZ+ z-4EY=`}Je_;=Su$82c_5=eM@sZ2Pf;$JTuI#f@)1e8YinIPeVzzTv<(9QePV1E+MS zu6kznS&wf1(}$kt2NykX!{dv&n+f8IImv6bU;I$`JmFSBf9I5Ke|9(W+6%9}cf*U5 z=j{00q*E^R@3F;%KYqg0FFoVP$L5@|@^4#Swckk}eel_`JJ+5uHu$FbzrmC5edqKW zo^0-M(;E-`+|P+^4(u#4+<65{^4%oxm`2w?Dp7^r6q$2 zOWBL-=fAPlYgcwozy17$N8Hdp$NbAB`|NY+G0W$lu}|1f@0;K5(;Gf`=zzBtnt`{v zgPSftWcEu(PkVjYUltsH#>$1xU-wO2uAO#L?czy@vSQW4KiuJg8~?a;(bPYuU%hD8 z>%Ef>IN`lT#~pCu`%5_Nl$Yl}{mJdbo#ahVoSZy=$*smEJ1?C*`ybyv{OmU#k3W+_ z&${E0zu$Z9Nx!(4IOLt{)JM`c+&1sGr=C0Q?PWjt(TR@zyWc!|?3~#Gc1~n`~cgWF4e!9SYckLeQ z#+JTv!aapU4*t-6&E6T+IsMt<7U0{#?y;FGS`iXKi%PjF1LF`ZKTIYW}0o-TLCY$`k9xelp|2dvBb$mwL}7uN*yf*2mb}kA0wx{Uh}D>Q9%o z*Nr{=glf)BZ+YR(wfQeEzH}{pbl}+1A=4i_dd9u04_i0(UVGV`HO0?CH@5H^ zdfnKc7p*z`BWmf6o2?t`(HE~9yMNXv3;%Y(_4{wR_MM9lS~qs$y0H&>e}=gHp7$*N z6?V;G&+YwEcjrguK6M~Mrmi|byGt``tB$y9_Zx1T6Opcb-3G_un(_Fd)mgT8Z7xqLCD-_JOH zzlSdrw|n`X&SNK`jisBPa?THv-(_~Z^YQjYM}7PBbz{q)zGl|nURit7XZyZ+@`V48 z13Ue7?wX4hoHzfVRSTd*$RA&v`<;Vl%sT(_ zm$Kq{=bfD0E&a;_FPWx>lFMcg>fGzk`nmt<*}vq94gWjg;Nhp8{>bq!%z5^tYCQHS zdR=?kG0UD^xKP&b{3Z93_dW~V`r5Wzt=;0LrN{jEFAvY0t8mlyJL~9k*F1Sy@e=dN z!%lnlnA$b(Kq{4*b(|LM+mpW`h&VX^dX_=8=}yYSA_&KP_9 z`Se-WrVezE*}OG(Cpfv;N_$mf=JEHS_XxXRck=-cF;}O34~I^}{U;R{z1W%Yj&s+R zcl?mOY!3YMo0m`F7RS|dlF`s-H&u4OntyNUT&}RK?|+M~y7UwM({AU2_u8La{Q8-D z?sC+9l5x+|Z$Ed+aSM;^{QZne9w;t7`_!k!d!|KF^s}d)Qv5N>@vhrW5* zv6HU2;>^2p5o^K9k1l-TXVdq%&-nIzceoGu=iXU;zr;7sGM>+W^6XW29Qn}G*Z=gh z+vp43+m5*I@88>@d*$&5cOo(Kh?J#xx4-Pny{2{kKIv;C z>H&}L_UiJ}2g&LSsfTW#bki#b6@!HzJ%dqazB^d3*M7gdZlB9)fBEaxe|mlX8IvCX z=W^yX_uXmAEyxhAZuUuY_C*7yt{9ts*!^4YE!_0> zBd6~6!{7}|!`%mtzy5b~_nEYI+RaBKA3gf&(8(|McWEu&j6X4O>s3G8`RPAC^xz$T zKlJwGj$0)j*;xV-v4!^Gf;U?SPF=a=tVjCf5!XEV;l+PmcnPTaJ^D9;nOD`$ezJ5| zV#xu#|Li+n_~f~*r(by&uP(WD&!tPYx%HOs-xs`PZ0y^mx353el9 z3m@CbmpSmQX{}RlA3U^V!ReD4q11OTFh00zuZN}=reAyVb=T+ic<@Ij8}e!tMR8Nc>~3 z$Deswo$~D+A8njCp?n+|eQnEQmd<@{=Uca5edqb-N3Q>H=kA(McHg0X_1VYC$IQL_ z^3qah>-!G!-}2C%&&+vz(T_8iKN(m#Z&CZi>#um{7k68C?(x?i(|=mbHP@VS(xRU& zz3aeZj0LxUbe?+U?z7+O-1O8wNACadzT3Z7K;Bzj-Q`TTeb&yCe^7kn>fdX7N4Ap} z#lzn6Et|pDKXI2XIUr)ZcJDotR=pHH>=*n_PZkfjb-#JO{fu3&p6al>L>>?PX~OFp zBxS;iPd|I){VkV1^l^3b?Qb3Ib=uw7(+lSE(px8FR?mKBA$s{Sr_LA8`*~^RK&OZo zUYJ+E`mkxuiPiGH+kc2NGmm}zu6ZY4a^MM=wb$BTEuDYT?2DH$2VEIXW>0zfS8s*p zh!ZE?wfxawtp8^7p;LpWAMy0%#vMBydO_rGf1Ucu0`dNfKFVF>A;RPVNXo|=}C9|p1S+i^KUB7mvX(ge>3T|KWo1V-FWWY%YT01tBy}5Y%rz z_1Fm?&3kj!9r-=|ch7j@tv?uB?Xv63QzxySd(tlt-EHCN^WOa63FnBx-M_zlzboIm zy;ppB`g`Z?fAv{J<-ntEyrMY2arzIUo1ZhWH}h-0Wbd74o%Q~j%TM0^*7uHnGkc15 z{qmExSp31I!j30B#!W7CA9?9#&iN}dFPHXvV5_A|yvL6@?AntoW7m6kcy)U6)op_p zUv>1n+=mO$YpiV>PpD75wb$I_OTYN(%;c-L9d_6SXD{EJByO92>YN9D{jqbciXZdt zAC>9T>|ey+{bb{5eh)tln3>BC-udv{>PIH5eCnoqk@vU!%i`Pm?!Qg{>Dj-ZfAfydpL`!-V4IPj9(>RPVd?Hw%YS?8)9D)?dtwU;xz1R4 znSa}3z8rn_Eq>}LD@%NA?vci8$6p6T|MdFsH!ryPIn%B@!YpnPT)+xoi2 zKc4&Wq5EC+eD~-*pILhP6Z-}#w>%*k?WwOU`stb%FF0c_te~7b?U%^BofprZ*}7rY zZCe(9`u?ZqetXvHL)VSTGj?0E-@38G4&8jSL)MKoj$OKDpLJu>E%ycgx9Ep0X1#Iq zs%6g}`S25O_GTY4ZJ$rOM^Bse{(`mF$YayqT5$^SoIiW`)776&J0yJR6FdKI-Pmj9 zr>oz7a_{m!hrj)u?Uuj!ojY!QadqQ|OMc)A6X(RFCw_8^d(Y2z+N-|e!o+VT&z=`^ zkp0^`#|~fe(YbREzA1a)f)hThTyrCHe_->g4qN&2#N&T>vbQGlLinic%-Ezm|Ni#l zlLuyH@j)}UdgNfK`PqYqJVfNudp|g7r#D^?Ev_6Nw&r@*eD`eM(%4R`j$AkP(xQ)M zefY}S$0ttSlKO19cyN8Y?3y>;e{zeTtsA@P<`*`rtQ&juzR8=i87RZA|Kv97#-2TL zS>>vAW3@Gl*Bmb0C$3q(Zfs@mwo_KmvezVDIz-y8{_%p}u6^={%BN4iliz9G*fMj? z3Gdh5pR>j`zQ65eYp(lHeE*C!<@?8;+;kNG=YHF5-PqNO=GTg|esb`2FKc5f&seqW z?KjqqEqUvci%%GP>*h{{`U&xEe(ym0NFZ@l)GHy{0D zIN44-NKXFQi^rX_!-|iWU;XC;9>3xi{FN83UUR_y$NoU_Jvi8AUUkRTn==mDv;FFv z?7Js@G+#Sv?MKBwrsI+1mZ$ojntIM7CvNq`EgwH*m~$Whjd1Oa`-wSxNpHs9v-G2< zytnwqSMOMUc$dE+(b z%z1I*k<;oSSUfgzvcf|`&9lR`Tv6Q@<^WNKQY4%QGzh&WByZClr zb?eF%tCm*^?pk_f{f}2&>0E!qY;bPkh2QLa<|YgN?XBOQX}`F~oBz1>yz70$ zc~3ue+r>|$UU}i=#mCHht3PGF`1}ucZyd4naXNo=@$CnmdM@C5Yrgivvi(lkg?anC z=k^x(A9(5H1AjRKTYSWt2d}^HBJ2;hKjalp`DpGGpZ+-WPN)C;FIQdlrztyr`it7> z`%LB!J-pF8rT5g5$%jo^b~kS0AHn_tX}v9-ZUH9y#vjHOiXv zryaR^)=P_)EbR{@vJ<2fuJ>XI2_)t;z7VoABlT;4c$4iMh7>)!OBkJbvk#sf(_A{*dh! zeEgRcvp`7m(>3=#e&)6-{_(&qvpzm_?V5$bEspyaBmRav|L<~Vuf0w`@sTyl-+tv% z=B|k!>^lGO&i60AYT8Suth{#1f6OM1|HGucUMQS##MFg9s#cD4uTXE=bG|@CUVHDP zo$gnT`E`H6zc#qLk9}*`m3!Pi@A&Iqe|`T0?pHq!gyYY-weyATUVH2Nz3lC`9QeXb z*J-!M9$Ng|t1GU*eYa1~=@XIFXMgvHi;j9qSc$dfogn=zdHXxh&f4mR^XI=g^{>xQ z+vTzYt5GUBZPft}-u}q)oA%AfS8RLXl`D+tOOKfGE>qgYXwPr|Wq15XuM4N1o4xh* zhf)*v??3kRqLwTwst?o6?+pGKO)%bU> zQO>}nfgQ9L!96BsU#VQ(j<1RWYQ2;WKcJ2}WIvwA&EjJEhoSsW%6R^+11Xw5%e_`F z7+7{FN}xRsIH3Bult@&Pb!0l>k}#b)9aA7DFRR!1m{qF3>fl?XVa}r1Kblg^Oi!-( zOTY&}Dlr;X^Kap!v46@RM9}XJtbyN~p#Z)F1pd*w`GE_c0Hc-J;@xxqVI_>{WX!)HjQepl3KKa&tvr8J>&F?R1KgRn8PZX6ICdt1f>OvgWr7l7`2+rWZ3i zXYG9afsL-9m8L*H4&aN|<7SD3Q$Xk-io_TyTFDG9G6bJ9`W5Z0o&pPNKVIS%KRQ(8 zHexV5p5Izy{Om#;0AdR!K?t@F?wgd>Vi_{^Q;EN5G@Q!$sTs2N-W6V957vh=Zo!qZ zc1Z5?=*NVGYW6ry?(3@qCncyn+)XBpyKXF=!qY`xMGp77iaG*Mho0iM3Mk%)nLq`f zC-*qT^)V6UtO4?vc<~oym}TdI?%9qN;DP?&FG?z4>{cFibhP4DY3?ryTSe}9JVti5 z&UsqRqn?iV-aFj?LxgF*dR=L_N`JMK%$w}j?i#1Kl=sNB;dz+W?Y>wKW`fxklrgV^ zsa{`~j0L~r6+v@7xIxFu%AXwF%;kv#ZIjzIT`BD_H98{8vDh|!(O2}kr__c!1NP|f z7{mJk7Fd!S4E$X2L03=CX8y_~C*on?g24HisbJyu{=l7td)l#DtAwDy9hsDL*KgT+gx3EK5$p* zR*O}*NGu<@D(U>-qBBghW2VGtTrJp-nL5hGMH%;lm{zJhD;Fze3fAYKzTn;MVuCNK zO#X3HX$@z?XQ*Gs$R|EAMb0xf#BgIM`J-(x(aa9VA^%ZatB=DsxoBx9Tvuq4)Y+xJ zw%<_93(=-=tt}MVE%J_o2pZ*&QC;?-KDvRN5m%`~W^jO1Hi|TO_nM!bvYz`Fv0I;E zlT$5cRyqN%_KzU2assB;>S3A7opEa z7HbIg`Ftd&fWJGwPm*yi^wmEaqwHsZmbV6N@ps{_gh^yiXrQ zHRuCub-F~Z23@|dOc`3%MzD=>QFv*^hrkq;@(+;mhs&s8!)1F9Sjr{JVM7sS`03aE zZyA&+8QVx6en2rE*7`eZ^QaDiSI_6EufoZ0d%nhOH8a3Mf)`Vnao!>@Wvq|=+BZ1# z|DwEyc*XhfZ3WthU9n&uZ?Lj&mZyd}a3SrOH<(H^20|rCS}QT|BoklYIrMue~uL2`g(Ov~sF73QgNak?o7+f%GV8QV4ydYF%E3toqpghZ) zSKhD8FFBN}_T_M&w((D^iVsgpsT>hsF$n}`(#GMd)byaU$oJg{V7XzcyKZF`Ct1PM zR~Q1{x0C)$!!2KK&Z)0riO%(a-{qo0WpFjeyqX@R#9JNi7)J)WNv7{r9&+8919yxG z23&HZgQ)hzlezpNJDGHh!}Aa2t+VUQCKm`yT}!$a7LaGJo>CVg<6<_32Qz$|n-;-d zIxM#p?#m8%%j};ZatSYsH-66nT^wZN&ju9GPm%z?5$^~C>$$-Wfwl9LGn7VV)}HpP zjYmzh($$rFeYhIP2lobk)N?ZZ;{5mKZ-a`aSG%s5mk2$Lw@=vzD}sw6dZ_>5EcBwh zpO`5oxQJ@$U|ZexAvnN&YMyxDL?o-1vA6^&N#mcYDR^()_S%QJ(;DanA*~2Gb&0>> za-y_)iWynNT0i8T&t141J~KJTy)0cenH0Z>dW|aaABVYrBGBqF^Km)b;y&xK)Vm17 ztjm!*;Q`PMn`yW6sUuqKe`tpfS8jFF>B8o+u3WxG$C&>5PFjDo<=ij_aM$`Aro=YI zj1|aa7yn-MaIVaba&-tKI|drW{#L2kfXw#m9ERqk83kg3#wU6V{+VbTD2};z_RwUC+f7m z1MAccOh6TcX2su!%D_5D=?ZcJ08Z2k1fkaJGP@S6soD59+SyX%Mh!i^x(8?EtI2vw zpVVX<(!!H1Yc%(2SSDq;KM}vqY0~Vzr<-{nk$dfgx^3*0lzhxv5lU~5R$5`bWIKyh z4`nGSomGc^e_M&iv96U_HP}`r-()6Eq~mRrIV51jo5dhS%CkYrAvLfYTy3Y*_0ga} z{V$5V3bfqsb+COqlRl0IN5fn1xIjwI=PTtU<+0>le#dAm19|{>GCbNebSzvDr+Gpk zRqTl3DS^#b-6e-2O5hDdPCRAXHT4h9onGiTt@#`A8kPJsL9i`6uYtK6V9V5(3(11> zST79t{KNQJKBl^iP81>45*mc!5H$;ITLN^-M+tU@^uhE=6!dD+E4p`$PwDyTS=a*w z%DKu`T$`Nug9@l-;s-_XYQ#oE?UYcL$zU4~241r*I%Gy&N2oX1FiFsQFLE=w zip)hY3oKBn$%WG(1CJZNr@nSV_X~t8NN%0 zzF07TsGO2YDxLWy`3zNtpWx7n%4=fy8jsi7%q_#|z;a>kV@cE8?r)3&M>hWj!M`Z` zAftd-lqiO4Ph(g$5<)xScd4)=PL~foDcP*z@ z!B5*xc2FiQt-<8G;?jPEpQoC__xIm$;=@04e>=p%$Dh;&ks^`nJi?(LkF;xPYTs zEf_A+c#Q2@xKmsJtl)yk_Dg@tDTgq}WcIJ|#pVw|KxGyxS--Cb{z$lYMzq&mSw9g6 z%B$ROKR(+94^w-@2Hs}QnG}AdY2_fE89lN88d0wY@d>+V;_F{-JiGV;&Lgua2cbjx zs{oaXwKeBiDH%c|#r=gb+7@;6k%h&??#U@qLur`dg40V4znqr_CKB=PcM3?lfCc<# z{c3vqlzxas0sE$lP|MNGR@rtLaH~TdmJ3B#_xGoC|$m;8CcGF!T@oEVb+uHJnf-45^&%&19(vIm!*UtbJk^;QcAg)zuy;S1*uP> zyL6`;I-r+px&KAs(zbp}ihkM%BO2U=iGGo(n5Ike#{Rtf&|qZVnhOQE8MO$hx10`{ zZo^Yf8nSl8-cU6+z|PofuPbs&w+jmkR%?qYO*8Pm7z~#p;i#isZ}>AG~V- zNp#N>%8faiV3~=Sg{3!nkh0#SNxRpF5#*=j%)jS30((%W7r@QRcCq)Dp1lVht(Bbh zRq+R<96)Bz{i>2rZGk-F^H-9GzqfJ)6>u?K?|F#P?lbQ5#F|~FwK7-yN^L@~IaZDp z>>V66{9Per$C@+-CIu}GvWBGkEb^n;6o~g(lThGAf~_8duA*55MyHtS2=^vy|H@38 ztMU0Ir@Yz$T-UtlAtN~^RDOmG1_J05Gtb5DwG(k1u0u<@=lg0`E-u!w1O~;N_A0Dz zD~qloGg5`T2koz)JpakRC<1`71=OTKAAjEG+8svwu+an;1aW!l#e!@XWZvP59JO%? zGKp28_1#<4EW<5{*RT!HZYYJ8Ca9tEM3b>XV~+XVFNrzvko#+y+BUmzFQ#Z{%f3oy zVPQLu$EanFPG5&gKIeUVHy%{Sv}1ml+x(P)n^Y5Cp7{HbGuq^(J_-sUM!;1Ky~{=M z1*fkAIxjh!1zOldVyr8mQ}v73H)dLgNHa^n+Zt_ftaabdTMC#LOBA7@Z>W@cI)@?< ztrO+h4}13FPm`IC6OETKDcO?Wl;e7fQ~Mu?s|{qig;Ng`KaT+QJL26S$CPx5Ht!-K z5J)KVt0XIuXQaEajXRwgfi6*#Mb6T~8BW3({t<^!>ViLHuaSLtcR6h6 zDv~1FT&4Sk**Zwl+Ou-E6w9z@w_HNQpY3d`6-emYwMemr69+SCnU;?XwTy zTK0oo;`+^~Br&krhiZ4%%)}IfjVyt#qedIn1IW>A`?)Pa#^c5y!#@pKR zsZrdZaQ}Zy+~}eZHrH>u;to>kv4?TvXGCo;@6di9Ozrn&rA^iE8Q*ygBu)Cr(~1$G z1TRSCi7v~pHMy3s0vh>tH8pZNAHwg5MRlRV@-*ibbx`>DWSjag`ekHTjGl^t28?$x z^S*RO|Dm(fh8QgzkI~C=OMN&P0@>+*e(`6vGh~M1h_b2zBI1mzu$V1qWPK~Y%gWB4 zzLK@X^z@l@Sw@G8=45*SsKlK^;AyzT>V_LVeqYN2ejziqZ~vkY*pw+CgC^f3am9K> z2{J|a*GR=A#d^eU%+muZwsEZzJSK)@@55+9n4@z4{C<%!OpKLsP}ocvnPgqP1VYBt z56*g22#}hExwt`jIS6U+opFrnb>TZ7Pii%HKK^<9OeXyw2eALOKvYf^9Rqr`cAxlo zp(wM%$u_!YS?qF2(}x7nT)cl#cumVY`{9V&3jhvOoZ0`E4qCtXhI#A#S3!=i^9CM) z&7!%2HLizS#`cNXx|SnXs(o_+{rd*M`MsX;T@Xm+mm4ok;J1rE$oTrGZ4s9Qr49`%Vxw6sQQNKyj(W5dOW&W^g^-fA zLXy?)A&Y@OUp+d=*=8{;js#2L3e}^`Y4s0xMP_D}c8U9Wb1;6Np;Gc^MrO>y+~>U< zPGC#>G^e_DH03aU=jhNVsILLH7ytaGVcR{_0&)`h1wW|eyb3Ccs>M1wb3oGDH< zQS0%Y6kh$KAD%b64M?jh?!&@ZC{8948xrrp;Ozp0qD@T3v74`c=i%HUnc2}Q*=cSA za{Ai(c3FMJ5H{k!Vjy^GU6zBB@AO=7S2bf9x{T4z5-kV=931fHA>6l>^B~#7?EFVd zGu*a(4Z7CN0b^wz^%~Vgu0aA070~iZsG<~GDo;|fu<(Ga-n<*|6$5m#O$cG4sZfEz zDBv~O5mN)y`?Y?qvnx}pjgfHaGRc{2kyYtZ2G&Rr0e<9a$VEpz05)A}Tk+_fy_s7* z?M?OMB8@<{i(O?M<5EXZ(B@jHMO(J`C>JLIe+K1tM_-G4{1ZNV4qGzu47`t6?s^cC z&=HM+A!p|Uej5)IT%P+~%tar#vAdE=PKbWbfYRw`u)Cjjm`S{4! zg7)wP%9ulAQeJ180Yy2QiI<;(jWnK51XtB~T&1eM|B5>eW-mVRVv1g<#-3Lz*@snL-wpw7$MRjN;o-8VaUOx4k^TJ(z&SSy)iJo) z`bTE1lbA#d;GTO+C-RATL(mp@>-N>h$bqx1>rooH`k4KWb?I`iX=FFfxO zG}$OB+gTH0jnm%LWAyqs)}4@{Qx~k<%sIK~dR*0yH*K52D|eqggk{=kfYz@}L@;^a z?EjRiK4tXyi*mk)@(&u7B?lFI^g*8&zVdar(U<++rKZJ(-Q-=!CeWdd zm_{qgk(s4xOp)Z^$B6dO=U9}h{*oZ0<@T*Tznw&_JC6MQ%0H}AOxn@TE+ahk<@LxL z#KA%(>;pf;pwyL3%J&RsR7`70!L`6EHz2%KyUX14nB=}|-H0*wTH=$YLG|HdT9=9N zgs-<~xHuxK&A)P{z)j6mQPZ;GZE?$Z{nTcs@Rqzyqv@CN0>vDee%45q@d>12CWl|f z>oWHa%qjAo)x73VRUWXpiGn^K`f&9?{r5^w-jIfYDYw?L*_bc$f|tJi0{%2>KNAyP zXt^v!mM10;l}2yQzw(F!bXzhsi~L1Vyr47W19MS*a&KJ)!iS|9d8d}`3F|dM37Tmw z6ar6w`udMiG?j#7-#5#x&`%^e_o=?;DY}YF%R+08rL*LBJD`2AM3IguJiNV1%Xe_@9VLF3v(z%lMnQ}CML7iG;rG5$>+SA?!J^<8_`H;Czeo)dCa8?kJ#sa^f-`9Oj(nL%iWYQi z9PY|6s(~ej#Ptd-h{nEamT9Ch+^3I)V03jDtJW;2fRbj6>ZcSobX+;6T2^ex3|tSj zQ!By}mkp3>)lGD4+t56HnvI9^yaj=2kL!lO}td9j5MRWihhml%|<=#+;G~8RN2iy=J4m!3>o( zfvCSIB#1#wr3qF~|EsI;M~>hp-uqV{dWYlA$EO|GHy(K9gezUOe6_kleGS8XL_XV1 zY3sbZ`}r4z_|p?({)Z@jv*&7{SK#`t_+1M|fj08)_!#%z=!x{=iE^&Eyz2k3_7^28 z?=K4SH&ui|+i_RB_=y|!!xHMhl8EQfzq1ltWEqZBU0jNLB(`Vi+E{+WbLQ%MpS zn(VkqmB#2b$L^d+vVy-O_=x8kH;7ta>w=;9u|~vR=QyU0z-Cyh<0u_mCOg_)bVFO@ znj?vpl8ANy*fp!9|eeSrsYRPq3Va9O9 zzT3U>nuSDRXYPtUVOQ%8uwGcl^gh;&5--gWG1z>hHB)jP=TelA$RXI1OtoL*z!RXw6rJ+QHy7A1mKfYrOA-cYX! zr-P_*B~N#YXuM?;Cl>1*F?f(d1B8_=-=u8x$-p1Hd?|DOMo`y){M%)6qaH!<)L z)ps;JE_&w_+P z(s;u$H^O3W|2v9NELJ_ZH!Zz`_^7Fl=_NYrH_cb^`yUMF449mDQmLuy#g6($HR7`HUFK=^qLAifX@b8Fccrh>=J$62WC@tzdG^+^n z=@&r@^sv))W}KXP6`dr>Qj_>xZBgQ<#+h&^VBh&h8A1}?&FzTeoCW;xy!|s@jpXWW z$>dJ?Vf_bo3pW`4MU3a@gGm=nQ>Y-3FWMBzEPMVz^78Xbm;Pj6!`%)rQFtH;M{6v} zo}!P4>#%29;#4fJqRyEAxthN$mn)xn9R~uZe!o3Ip~62>17RM|4_L+`A6C*W$rje^ z&LzfTb0kLN3?{*?4ltj?;FcXp%I8Yf8VczaTC5=8P)SZ!`luCwbV+f$2e{_Gz24UOVc)P--Sut%QAnLlX<*L(|jn`z2TJr(>DLTAv^5wSVs~_!tV19Mrz0#qH z);QkdN&!{!D32r*yVQae84D7EItp3rj2D2d3 zcf_`4&m$v!w8hd;2{z@yS`_bjXgU?G9E*&_^nRvD?h<4)4Vk}xWxmUn9Lmg5nOrOu>3mT z9=F0p^JI^hyzu1~sld$3nYZw$B-0Vh^&Jv;t!bh2>4W>&;%b273F@pfd76^no7GgcnFy+IZ*DU?0f9fWfTv%>yvfUXtDE!Au?;|WFDaFnr4OiD8+a>@8fqZWw^afl z2cSl%7aJjISoEII+CCS^)8*OTysW}D$}Nl?#;NT^7= z-e1IBG#ilDXf-XW`VT0gfMDOIcHF&Z-G|J z!qg0p3CULG9lfd!Z(r8%&7f1!m1rPrkvG=^!{Ez8P_Tc>gTMf43NH z>bO7FAcvTFW?X!J)EO3w*yYG?CY$gmJhA*5AMcKVYt61OlKt_ZP4 zK;Lh74_UaTC?J`eqUd-$;-ssIotpph-U&%G5o z>>Z}`SxtJ!s(7c5@|Tq>-c5?i%ARO-k8U}QXAd7XEf^2=67Gw=h9Sk$wyHps$E%We zA3gn%-L;!VO(8-|mNWL7MyZt{_ORT#@|jsBaeMuMhD%MznufO~MHNXpU+ZCWL!@sE zCIXt45|$MQnmpuhuX=<7VdZEsK!+fQ-Cl4MNZ{S|Br7!eCkCFhjMd69SH>Fc$0v6+ zz9FVn3cMmL`D^rR_tb#80xyVvVFYA|G}Fq+hi~9K1S6ku@cx*$&kJtvv>+=wmUty4 zkV@`yG<(X*u*S)ha7fDBp1Jq-`pF&t+Se~Zuo>VftG+p@zgF*Z`kMC3s(k8Cho1xL z<4Ag=zIr1+T@iP3xz;SN0_jn|7d$CEao31v$G7aex!=1+L2-L8F$z{9uA}a^TOQ-T zUUPVjW#sTSd~kNFA*$H9B##CZtV-U)$;>FDCSeZq>}5=-s- zjX=NxS?p}uoqENB4#!;kb6q?Zj3W9M<)0V@&4Fjzit75tUx%!wb837xLY!I9PN413 zebuXD9qhjL586Z|n29%RkMoVvmnd%e-i`Bm)dzp2CLf32l|GJH}sv_R+v_@vKV zp9#;V|6l-^;4zORrW3;|@Ze_3s5g9+BL2uP{xf>x9lfm#dQz3CM&)OgTHfmy%fj)$ zjC{B%fmZk~tQNnD+79`Z!xJ*oJb)Z0`#0)SO}{L(Kkt+D54!*OPh-$Om&X;3fJAxY z>|HJ|*m?1L6g(7{>}iB~%*PZZPBnJQOsVol84~x=v;_b36c^(9$G{Te3fZTw_G4{%7dl^Xyu(-XX9NVc;c)DC0%7r{-y zK$rNVlu(VKQAL04Fs`@e^67?8btjC1uf9I`|3!h-95J6SUIsjUfWHYKkFI*l=iEh3 za)eInwX3+dk_v2CGumC=?3Ytx;%qk_i*fI7>Aqd&@S{AzLOs9z=X&`+tESI7%m^h0}iV|4_i34n=8hSo-+nyg#*IJnck04wM{s4GtMd* zOh^Yr8+0XRX_oozal)wvYok-r_Ymb{Y&bI2!mi+(X;W9DPE|8eb^9MqtV`wGrr`$U zr4krC(9-E}Gh-DNmG1@}zuKvs^vN73G%R$8EHyJhwc|9b=a$YY2}&NYD6u zeG(H-)^sR+N#kq#kd`yf4j3m8`l&;$gz$rw?6z1}9n1Q(JqWw|QYqN<(yF_-Z<@O= z9S{-8j*Jh$jB*&+3C6y`BTfIJNWS|&#k&7u9)xmse;l!ohqsQ`IV~Qc%$p4KmpP8vpq2&;>i4HtIBA4<08==eYZ)ii5T2?f5M*4s=2*2Ts7g|Z(KKvT*g`tp;E;DzI(pRCn3wHF4 z=SpbWsDb0f2mC)3%ZqkXMs%#p3^t0Hy~-1%7jq%YvZE5ZX1Svl%G^qQ+HI1_vQ3cA~zFnfMm6nAx8qB zyH*Cry zqL0aAx*|+vy9}t5_@y!gQt_;;_(gMZL4^S*XAh&g(`1jaRWgXr(%@&mKkiZf=r+^* zjUgsTeRK7&ZiKqwiP2VF@s$k)tE1x<7Be=L@R`4bGy=^cZ!Swwx!H(V;;YmPrz7+U z7FCCbZU}9*>R_VazT4;`N@9w1m4A$1BDdy*eFE@h`PNknjd`lsR({NArG|?{D!p@mu2Sz2 zn;RshsW9-~p=s7*CdjgJWd@so6qoQ*O4W+3(CO%aRc+_U6gwelWL4y1u780mMf4Ax-Qq+^^zUp42gGpUvE9WK`M3IZi3`JVfZH6*+-PEAIN$V0Ud7-d(iPqm%w zx3aPkd6dRCjBP2lW8%{x_H#Nxd+=g=|8&F{YP*++Ga8kAwpo|7fg;Sh>Ty7ZI)Gga zxunTkIflVkY>^%M9R^Tf}vsfK18z5J+L?1UjPbNSsUX&@zQ@`c*n3P9G4mcIA<%g zaH?R8)%cTzVOHz-hHNO@eg3jIO|sz=MAyNCFf%_*75+*u!jp$FHOA=+=~R1zxgXts z(F;nyw%oTq>)Gu%Qd_;y6IS`ucKt+LE{!tC4NXca84(Llb~UIrqKPc(?|>RV^*puQ z^CZczj2akfmp?30heykZxD66QM~(<5r}w~gMmabE*i9OXE|6bv#Y1EBSg%N4->S?| zRvXEnyF3H?X7^IpCPr_oY3)UJeh)5MvB+B4e&L#t5B(H!Vjc;RcA*n< zX)xr(+_^pYvrF4hYG0|gqr0br0SkN>as(qx3Bnr=18uzGHS$8dh<1yMCgriBAKUtY z)BCRw<$vfIn&&c76z;p_X)N8(_6Dd>y$m=Bx=i$b^W@CGn|U6 zA=*nqGyNeldg|ixFN(_k(Sua0JsO$yvWgK1@RKp?PIpYk-TB9LTU)AnDK5cSXihA5Tx5h0)M#)8CGUV3IU^_HD} zfy^OOpWh9*RfT&bbvXz>w%b=RwF$WG@0+*39Tvv7cRcaO824i?<Am zkhz+pDQOQ9^`Y#YE{30(>#>qkMcsTJ@06&~PTlNaa*>mT)7QJJSpG!`aM_FEJM(L^ zx4kon9fca;UvZHSj~O4O5+4^Q>xsV#=SVpjj<)LiVG${`4|^iOo&$Wy^knrLbW~;F z9ZBX5o_I4VPRG_B7{qpqipN?!#alU_MYAVrL0sGjp;-MM=`MKMa8_BFoNwP^=X5Q- zKdh)yM2&Y(Xsg1dIn?cV)rYN;l0l51%639b;U{kf{{op>Ip++JpIOJKccoT{#S1g& zO}8Dd|GG)ZZK;leLG3b#C}Hko;tr6ZOU*TIaHcdFN7@337`P@hBd6x6_36R;$>-vZ zD!?6Pv-JkYG5aW6Txa_9W(UhEixc}*?&fq{_N@N(ANV2fby8-6g%16?Ycn73 zLTy|DqK~8PIEa3j-ncRW>kRvkyHw}A0of762W(@w+bCs{!<)IxcE}Eo5}ulZyxMiN ztSA?a%B-TPacV!L18FFe(i8_^M%Et>-Sx}S(Xf92l*BFmZO9RrXUu_eM~ zKP?45mN$g896n4hd%yi%YVYnr4^wml?Lp3TNi%L2-U>7w`)rqHrZ*(M-@eRn5dTV6 z-K7RJi>rj|THtpMswyLGm&RSU z`a#%**r;{$f8}AoJ130Lt~4UfTb80HJGi2 zn}-x6Kt5+0>`CV3Uz;hkB30S5Era$LV6ToxY9j|LCCd`w%pC$5Zxyu0g7KuM-!}yR z*99}t*WAy+!_#|>M;$E}#!V{i4%v-|G2UeyO)q)zot67x>AMbOQ49?n`oI@)<%0+x zS`Qt9Soy~-JA@6B`B0QDFDVZ;+xq+Gj?fmi zY_(jJ=^bCIcgU>-bE~V1Tg&Zbmd|*ZAvq%8uw3Xy*7S*J#DFHrV+33zZP4rxftAVh zF4BUJjoCRGNQFXW`agtZ|4Qsr(Volw`l;j5GvLFlkS-c~T|?cK&S%xx zbt8pd7dZ~a`KAZh8pWjs<@WNbDmkqBNZ+z0HI7@47l4lGne5AU=lPPI%;uGhH_W!n z!yD_`meJeH{Ufjfsi1i(s3eX{)qYv!oZ+;4gCTbALkBSb53>AoJGQLy38j^9f&^Qu$Tp7{107t(~@v&*} zjNLG{hz47bvoyLD`HU15(Cd3$0}A^gMSI{xJaa9YqW86=GnhX`U&+L#6o5Lr+zB97 zTP5_{d2~$=-!NOPH1XxY*~#FnB70lqB0k82z`K*fjS-h)oqnbV3(8VrWU0fGlLT~ihJ)2fbR=J8QT$QxKhPcTnkTP6M?uGmT1Mqk8NjnNdmB0w`kt-A* zF-JK4$#F@hC zV)6NpEr)jPp8bu_{P_qNXG(3Qa5GbIGRLvV>5|XgJidM|+02i>PlLHZ$i3QS+T&%u zfy8xaZF9J~W_?g7>xa9VR;Z;Xgv?DQ^)Ct@vtf1b+@gm2h7WBC58qAXh=Dm^qbPfo zsD1E5@|Swy>V>wFvLD=l$?7ldo}|5>L?@}JqP8=R;Epq3^r*UmrqC$^#Q{iTQ85~5 z%6pgT=vxg`h%3~g=jf9!F>8dV@3Ec<=~MxuVVznns~_3tQM{KQmta58 zs#&IZRaAUuI2VSE@D}1*g6A*y=K3u_Szp3CE2R0tlD_roPxsH*=*^ub$VT&cmd%?} z>rx211CvtH{oe4Z5ueXsGb?sN4ub%E_nS?L4vKu+`8;sB#3UEFG*5Qs^r{F_l zB)_Aj{psfix^wufEDt1`D?(0C$;ShstZZC^gMHo^i18JdauI;VWzPFzwKb^c3y!mOql*hKtWYg?hN zd&eH=7hRi|{4f?P%u}M{pgG}qgWg4p(7I9dVKSXdS>`27VTTm%_hs{AKUsyVOrFOC z_$1lY!gz2HvK*FP*zidKGXg{7^msJMQ=!DOKCvd%ZOd?Dz^G^7^9|Q1&|Gv?z<2SO z__m-lkm?z&?JbXySry+(BkD7C#{y6o3hZb=Yl(ZX~d?Qily5ruLByQJoFxiuNA z48;spyQd_d2#Rpt|B$x+KO`0p`9z$Zk^x1ft}f|Bu0UsnZn0-#_q>`Fn!{^!@-wbm z)EBQtl{HLyQNYvY)W4VpsQ#j>OO=%_1Onu#cMc08d9w(_A& zg*1jIwzAc`5A}%0KVuZ_O`|h{n$lOLjgG&Iz}LPO6;DTqA%6R#Pc?(GDXGS9t|Am5 z><-=qR*4RVLgCJIgoX){B;6lf(x5*hU}>QKv&Nt{a55~&f`=LV*K%n&W9x>~ zD3hF822+1a|BuE{*(qK*^;pbfKl7ghH$zxfFLyAR6VY4${k8sY{NkSAFG`0R?4g_j zZIWy(-@CBhhuqj@PHt{d2U`tdVAxo8z&=;=K0{7fLXMYK3K|wY&wDw-fGAGkE`&=n zr1XE#`VnB^7T2`67&U$uuCp7XzLG6$jxY$i(V64*l0L4Wlbbbg`zbG9AmobVNr-k) zH71l()#}H$oe$Sj{vE>aM7>LHHO{>ZToD;K+}&kQu-wJ*ymUEb$lvDxi*9*x^2~NP z`ZlOexQ%*B1EVuyA~Os@HH_6I5rWCF8VZZD6*OxvqNSxqj;`Y_!}lKzcf|^~11>#> zeaI!One=FED9wuZYA#hr=3_ZuL?GJ zJrY>Pw`%4qa*nLn%Uo2MP+F#FF8hpdzUre;Yi|_EolPknJH)l5hBUU?7pEC4?<(Pa z8H6S>dU1IKYl+kvFgIFIgVrMFwP7ev`2%;@)$yvy zzX_M(-AK;F6!Ixs%`l=5-C1BkQnVOuDZF^|iNO+Jk*YP%{L;|8|LK1M>_NT6ey@Fy zYi+a>+mU9}R*Ti>ubF(%F>z$d(Dr4(#Ct4hUYNsD_>(iud@0M)3~b3fi)V(NrT%lI zYTvB9A6roDpu42eWxKtj^;N@I8kBGVF|4o_5U^gYzcbG~;ArPgE}b(gJG8&qPUEIR zP|i|S$U9@)Y!Ju8m(!lB;sWFC^dAaOwkwY&-adv487zGJvB1zeM;NB#OFt!RyBvYn zxG^uI19hlg^ss-bN7b?0SK{SCw>=mJlV1GUs6+~ScwG0!8eSlsp&JOzMVhbGc zZNYHGH97Ge2vqR}s=Ymqed?w!qAPwTFvN!~Waiqn^Wwq)EQvf^N{tQxEgdv@mae-I zs_{_KP{O8yz7{E=S7 zL%wQ>Tz+-@Mc<=8(&pog z?%ZknSjDcE3T6?|27KB{!-!vkssDJqqrN(8V zQ|HCjE9w?f)ujqc@QilaV2ZMa0Hr(vJV)fm9x}Ss@LWxRmRaq6BHK3MLH|7eht{uw z*~fQvR6_=GGIy$MY5otAzJxU$*+jrGyM?BN1a5$jDt1YJy1c%itniB{}7 zbO`?TVtSFou;fqYhk%_8h6UHF=CC_zAH9!dxYpuW`@Os|u`+a-A95D6>;n6qyC2~H~j9tauN@ee^3!yo-;7 z72`}6i3j^U*vPetY%=%t-HUt1yLCQrCb9g|tIkL^Z*|VaVlmARcmRvCj|vYbxS3lf zuimOTDcBl&k2`_2#kG(08GiUzZUbi3V$8#{o?Z=sU+s33`d(`5f!uls$(8gVF_*&yo(z=8J5x&(~88+}e6BCK<%WH`J? zS@Pqg-PL0kmQ_D*zSI@(;YaEjN5KRe5Q2~(UdmMns>xoK#I(8&NKL83K%fG4)vY?p zk5Sn*qkS#3`xpJ$W?$TjS&7Md3#47T?|>=N$sCGyl(c0TKdETE)fR8yl?I?r6=VR{ z;mD`AhW%4SmtfE`oS==FFKo9-m4yljI{VTezoc-699t1u@T?W%*_3}DFif{_mNIrqy1ufXXtln*2~5O?njwC0RK@xot(Rj zj4VDGM`0U4&?;GMuI5Zi zBw1aO5>3Or$H7nrh8nro>zPwH19eGOz?lzAh93(5crCQ- zfL);cWxX)7bnOJs4#5Uw;8!jP`;)cJ^$Tb&{Eyc){<{YF7w?lg*Td>!n$7ZG`L^kM z|BSbE7Bnh!oG(@WJvIf#LH~3v3O1a9O0u@(On)9K>6-wt)Y|rs)W3b7GrbjW*ISZ` zd%U!CUi84i_Bd)(Tu)_3qt*sFq^y!3Cm=SUwbq?B-z>7n6|(Z|cibJQCiBV|;`eyH z#a+6ohfm(~T>8wSG!V9W;ooE8U`l1zczk8>Skt0(^b2()HT&@(aOMirzxAtk{Z!Yo z<89{}XY&VKetplos;9mXOZ1o9&$fr3?s#+W+P@3wT>2q`uvtYmKbSbBEv93D*@Yiw zpSnpP@$Xzw{_m3_9Zl!`{o+O`s@io~gi|-V+1Q5Fk%b0!tThL;YZUH?j1yq2E%NpR zt*ntxnpJ(~G%|Y}jJhULqYpLSq0$QZ%oyOj3-*s3dAimbERqIU;CZ)`F2wc3%&<>W zn?6V=>#P;_*N&o5zX1ILNl_lqYsm8RKfG8TiS3|TpeM%8K->Hmo90<6n6*NG5z6wW zxuUof{P9uuEM-XcA;xKl$BE5Pe;u*Gg|;X@}6el>A}9W#b`?^!*sNPI zA?A6KhjJ6l-l#wHu;_a2@Eb#wf z@2!L4`nGjZNJt1Igb*MEPjDxA@C0{n++7-L+zFQ8?oQBdXr!TW2=4BU1$PJ#Typz& zU!8h8yY^1)I`;0Zch)~pbFN-%%{j)DA@lo6)t)wo#q(2F=3m*^>aC=W<(9p`&NLS_ z=}tlC@#t{m%k^{y}a2BUPWS1KPN>w#wS5wc=v}tKa7heVZy; z?cX2SgNN(*1)L2K1KGsg>bQLEjL=j2#rjhi2>bk41l~|4U7u$%wsLJ&SQr=)mU%GB zk3rM!BLYR^s)pzMVw!B29eKzmFmUn|e%=u%4Oc`;^=O6~k0jp45?GHJqx)0}`P5Hb z>)j3;Klt{KzaP4=+n139t(BCj2Hp$aU+g6*rZj(~m0N!uC&&HVS zsUpxS(qWFH~4^4AA`XcjlhEOqK$jfY6J1lN>{W_~Ie?%r6@ zpE*!3oP$i4(q#!Y*7n`B@xEJJi3pQa$`|Ej5qSUY$p)#5T*|WNsRlQ+N76K%UwgTklQv@P zrsCzuupsRI0PwI>QF4BMR3=$^CKdH+c{I7qhDt3v%a}lOJeSK&mN&O!1z)GGli5ZI zSmNW*_sW{d0^fWcn5(V@7<+H^UzB)+%oUo62-GT-NI%Ce~V%CY+)zUs7p;gwi%p+OIVEcgoKIY(BIv9QOne?mkWve~RzrGsRhO&?hblo40V9AF4r+cO~4o za?Hk8W)xFJ0ZE1#tFbRF8)KE#Mn&mL0lKeext~EnM5@0*4Uzo@L-df_QhOq_kVTtE zw=xGb2yM4oSd8iJ6SD$LmP6$s6+7oAm4jOh+ZF1zuQjXFB?$2r-Uhv3um$N7Jd*uJ zB>$&JbJZ(qAHV8KT|?Rk=!xa7PnKTQ3%9hl0bHoF%z{py*Igy)&#!%*74n?cBY>r3@Bsv@pS#&pdaV?H@9gi~t&ArF%sN$B$r;WMMLBbH_3)Rt9yi!0)!XaEYCM0} z!r0l*D@k?S)L^6`qlSpUy9Z)9Yii4octzU%+sl+<$io2zu6=nPl7BPxmBVz zelLM7^*u}TF<`iL0AmkJ0e%25o~8ikWTcw0L4%QTIrqc;gSWopIEh|W8L1?{^rS$m zUn%GI6U~&qw3>%%+BrHN&rP=oqD@}+igmU|OZN5(0|3f$m&fXwo7@5>Tf9#{{?@LB0Qj_P&>WGAkOn9X=ehN);D>w6kwO};I~X5?c7eUN6x*Mq>w}yvMi(aDU3V zD+Yi`Wnj|KS{>6mdsO95VP)+(E6Y!}r!rY0)Hu}TRJ8iL`zF~`+oF(3W*O^`5y^qlC&?Zq%%XPHNVdKtJY|J3BnXo;F6 z|JL-=Y~l97M1Qa>b=yfQ$R0Z!$s;&YU6?lAj6G6yy`^G9ga+$Q_XzCclgESrVw`)p z-fvV54b0LNKG(2HjHACzjf`{e>h>lhF+{hWuDK*u&y9p4-cm3nUilpLKikMD`l>Z3 zD#M`)<{VbDq9lA19-^p2PTdpCC1t$TcIEJJ?~g-xICYu?AT~#gC^4MLsF%-5AJffm zW~k**nLOL^a2w|z$fej&hjcVYo1fj(?(hH?+tO&9z-kk6_aw+;4p!v94~O5B^VxKZ zjXp(K{gIyCd0_uoBbM*ZnmYb2E*P3`;iUaokA>9vDuGMO9AlUshbFupA737gJ**4R z78z*RzxB32=(ic+cVIFO^Wd`gX~r90T?UBInfmu>GKc1#0TUz=^<=Ks5slBY?HNgi zLD29==3~L(($z+>^6jrbJ}8`_ZgWs;Ld{?L)1!3~&dPCsT3HN04+yysSF4(~!2%PcuNxKOT~J@okK)>Iqv$%*Sx=x|1x*V5u-);m>HS z{;agW%cERSXXrLpb?YwF#4XojvwHY#DQ+!n*u@SWV*9EWUQE#h+Ev!1>0`H6@8QPh z9ab?+9f{0F4?^$SB7NI6&oDOWRGle0aB zoM2K_F%;=Bgfhehw}lyR5wbY0e8X5%rb*+=)})Fvm8PoMpy!N}E1<9{lv%KnN;747 zr}84Wn+=)6^33p&&X~Z;$SXv_c%RKE!g$0udE2+jg;CIGYSN>mghwbLJyh6PN=Eu) zz4w_PO{(l#ac<;l^6MX$?;iSR7pPhiVIzXIb0;C3NTw;cY{(D%*RR0~49`h_v_xu+ zZ+D4unRZcUlmatF@dc19ho5A{KwB_1N5X4OIgDrVa` z-zWQVr1(3x4ox|o`>!uAWy>QIQ&8TN1&Mp4LE}FE*YRbR(L_v{JBbbjZ}?DFzZvrJ`tAw z11-G77BLHqHye_eR6oJ795jIEAF}+t`%1oC|KzN`ZRoMZM}K{9EZ=UMDWLr1vK!p& zSp}TU+t`EU&pjl@$V&?=$#Bo7M^ZSxeQkYk4CTR{`-0#PPj39aSG{L*?#8T9!xbK= zUcNgwT0Gc84YP82D9@Ixold1onB5@oDc$|mi7%i2d$|w1PY(`ZrMtMvkno~?2w=Le zF~N!8p<%UDEOq9azL!N8-T1lwCBjbHTK?#5pNLl;nS-2?G z2{jaOkv~$Y>L+R}hM%pzeD(ayq+)V6daI1nlR2s!P1!iEUWi$rt6JBxZ$pr4R+v6IAA6jRR)d(7n!Q<<*qbdDG z2_3FQz9R3HDHBCvXme0r2++z{+hFx`hrT}lVO5{rwX7p1#R7L#?Cxa?5k%TUO94t1Ns>b`k6ZMp)kaBNyeBxw} zv|5eCdsbErJ1ixn_NA(rGENF~$X3}j5A}16+r`>_ z6@RzZ$xsjAl1hO{OKouyAX*=ekwUM6@Bi%$GVga z@-M&P*>pq1-o3eB)qeL+Sxf$)jsH^B-)_Pfvk}>#`;ptRJL9vMzcE&S<7q-#t`Dgj zv2$HsffweZ^_KPzR}OVJKAy;MTAH8nXKVtWaxX99O|>&G&p^g2ZIeD)&|j`QG)T}Z zs9KP*IK~i-qdcVKHjv&4yWd(OxnKr5&)d)4jD(sRTB8*&W^PIds(UlP{am8R0exRe zGsW$27zGX!e5>5y^!rz&c(59iB<+mJnL zk~E;uC|=Cr(2WsMjCz}Bx^oa$k4@5;*C$aYi;+`RI1ZTDy=` zcejJ81vU3Of)8kZa9`_lgKOb>Upr|OYx}fjtNZAk*7VpM%KN{g&N9CpzEKg*Ctr}2 z_#<5wG845#$k^VXFMEXO$0H{sJgWgR4JA#uRKE&kHd|<6=Z@vxf(_+2hB-qN6w_Lx zpDcM(I_ZvkjfA?>| z6b_S)O({#}GrYI+Ca3Om@+aCvc}P{`CvJ7ay*`12ZN{*4KebckuZ7c;o>8hnBL%lZ zDSSGiR2o@cdbV21Y5A3G{gU!K{k0A8Z34iQ$8dj?-eC&l>+5ZAKZ(w8_o$u^nY1N; z*;|)6Bd&gI6Zb^=xRbp!Q?N?o?OL+47TpYn5$7wlxf5D$wzy;(RHz|kWakP^TC`Q8 z4iaCmVfDv~0Y$)}`ia!E8J=n%H!y8jmwq)_h#vQCl=r>J8ZQ!aFwXJu-Q>+L6hnP; z7v{{aLiVzOCO6GY*D~`tUHOP>Tp!MzPV=YM0fEZ%AqNXIW&)qo7~GXwxEA8eyUpN|ab5Bx%rykH&bdxIr^s!=99cE@uH;zaWsBIi*TMm#KS_4Mg~ z(7L~zx@;}^Gw>$V^4otElf;A8GulDEu{oY`1FBZYn! z<}e_FA2NKfs6(HjjcZjap>+IX9@h}@mPo)gP=z)bqn0tCXzfK&n}YXiA>qFz#ls-5 zTuQe-K!V(u%+5G5oh`mx^mM}^gE$-X!;5FuX=fr$VO=jR<7@jQH>d_n!jOrErgLrH zyr`reolDDZiqi-DmtW8`K@9ZX8zxe;(RE+(}Xz@lRE74bCCP%mX!=S-gB-Z*@ z`D~SVb!z#{N-$zEsPb#9b=r}RcrRkyp~@;9lN4_#;1|l%Zx0OSg}J;~@5mQgd8quk zc!u<=kt+6cd8l_3XNflukhg0zf!-L0i#shV-XI=qU%)3+iSZ*~$0Pwhx70HOnb&8> zB<0m1nJAL58>+&JS2i)?>@`4jz<2d6z?UBNouqqWp>9#Cq+<#dKbX-;ytnLeYQN?J zVAjN437S^E7b_h3#5w6~I>!1#N+p>Lh3F4yHUFb?{|9O4|4(%8U)mb}lbillUs0fb z);HWaF(b3>e8vRl|um2OeQtEeW zv|QtUeWqVKoOLYvZImaeGiQ2jmTV{&2-{mhnzEB%hJ%}eX`OD~=v&su4?do9Rr;Rm zp`JJ;32J{3*HK8VwVInD`{@#OHqxF6Q7-H^TGU8N>S;PniR)N^AA8g=|-Av1@wE)C=eDS&z)Qs}8= z;TKig*zp;ayW^<;$v>jV#F3qE#FgAB`((7oe31TVOKq<)VpDU{+o(~fWnMjtvJcq^^c$~-PEnhvU18zK$5m#~u=5t%xHb#N(?;08$a?1P^!n90~a83 zsz&Y3;*fUN8Evhgv@1e7ur(T;R&A#WDUynntJ+Pd>x)G0 zz;EljQ4~G<((CSQ%Tt7bEAgA0o=6s#MT)O(@}%%jhT$Q@N^1E4^e0SmG3(s#jMI^^ z^_6eW7asflcWs3b z`YVd%KUsSJD*lsa8|lGDK|wkpIlUK=O|pDmb+>at_Y~y;-(1=-fmM4~`;d&5k^0NgVT{WG1HXIHUl5I4rq}iKxUddw_?hS(JlZDrpW?WInEH>QS18Wz=_naQ!22>2I*A*g-yu zKe>?nUZFnWyJ@I@0MkTo7b?0YLUKlRwsf7zqg+Z({z4H&a+O{t&$g80kpBrP_22nM z>{MN--Q3;0%53AS0`M;WZU_WXo&Tc1R>!VAH6e9YeUbJ35I}3#%E!E$kA*i1<`N9( zD8kItz`!eUZ{h8K^_MyO*g?l^Ub{Nld{DHdy{08Hu+&eU9y`~b z6sjL{wY2b3b{mr(FK~HR1O+qMkA)4$TWUTI&!PPuA#(G%HPcsV4;Bl|gK0RoUbDG3N`m z2*D8EA=c8_9`PQwX}bz=o%0G3E|VgWm7s@Lq|YDOm%~qijW+5r2N>=av+9jwH?wK7 z`opwIyNLshWr~u=VnGv}3SwVe*}Sx$>u%HKCQ4681UrioR^@-gBL7Pk|M?f{Z3gn} zkGx32IU4%dp2 znRR-0_60!bV{BqDTrg)ugL;!9JV+LY{eDbzcAAeFt|0!5WQ3&a<2OlCZ})>Vir61v zA1D3Fgl~lJD?bQNXWt=_BQV zdAOiqZpydefYNeI2Ra7ZEcI~Y>oYEjn_PKgE7Q#Ol<2PhIGO?H7YfbJPy*Ol3_2jo zvBd&%J>-c3&oBfe_%w2;U%pL~mzZm043BNBOXeGorlmH3a5_&@82vOk@@9&)RNxWY z35ofG9^EU5(23II%791;-}ZvOck*IIBy=GutiE?~b9^7>xZ?096!e%H=UXx^g7B2V zCsfxC)VAUJ)(eQ8&T5xIOO^r0dlj%Ab+jJI3i)>C{4p$8CL(;vhbAeveFBd6kmb>|T*xtq9 z^fO13!o*aBaHROk|F4w#pR`f5QLQ!vzm$HGRJzm|TAuE`Nqs9(V#HN)2zP1)t>gnJ zSX~jWrp?hT7HiXQpUGs9U=<%lh)DFl@it*Z^XezEFf0FolI+GlSl^nS*%H0hklCHL z8eUttr&V zI5<%?VzI?LBQ7`G$E&p-F$w*eBQ+rG{=Fozqqd4=Z%@E^1C*~zDw@&F{WSWy)Aw)K zs(&H`efU3>KOO$q3Fyj_qYWII{bl@R)!juiFgxUQ(m6z~r@9M*5;cI_qI8(wKEx(F zP(LIsHdA{W9hWI;I@c|q{RG4CkK#tdWghSz5M(*@b<5|f zMPWzAALpU3wU#Vfm@4D)+=*nCg$+qMkGlI?uG-(Ro&J`|_dj*K|HcBlOLt8mVM7Qg za)GBzUZ2|zxFFuAe%%B6C;&P%6cmmJ%<|tDtu2BVJ8GVRgV;_~i-GCy`(P`me`iPi zQK0{x%3QKB*++5wQf<>V3c8#w6)fZLwD<|Vuslxdt)uc0jUj<((z|5=<$}1lHVDu5 z$24XVN9m+e1S7HSL$^f@I8RpNN4@OgUFQ zHNthPIzvu|8`OQ(ynTaHmM7l%0L*SdN=Or;elk2?j1$dwBW-twV<;1=0_iH^udYdF zgoae<)u{JQj>bKj#S?D3|d!G30CHUmWI4}=x%5euKVbZj!tu&nkS%@-OZq`;@F z8Dvu=UFLR5j8s(*Ez32mhime6UAd;kMt>q6sdu=-2V#Q~N>(9UnxErgFC)8uk?aU16%QD_l&H9QyrCDb56#B^%*Ac9$XByL=Wqm8h z1ZGa)m0dZGP#Z!LbLd_^yx(f%jb_fv%5|z0w&21bHjH+|E#S%MFzFt^cj917Ts?zz zeqFy+-|QdMHKQG>jJq;bJ?>jWN65lFrmU-7`uH=>4NcF}^_T(*ry4EeNB4nOyD}c6Vb05~DsIZ{*K}V|8bLgv^%?GZS2l zv(-EXA(9;dv+_b=;E}~FxPKP40PaYg!Ux1~jHcwKE-;aMw9=KT?NQ-x-gjHHB(Ru`wovWyTe>XR&ek zlV6x0E$S3)GFI^PrFN@KC$Xzk+8P$?JU9w6rl8ra=_5?t!n3Z4EK|X6T12qbHc~$y zs!VXY#ofXvOX&E1q@Opwutx%kjJ4sW^;wIBRnAPkuV-u-NiFN3X*h*zMtZ2*(%ZNI zpf#4@anKb|s<`?kA9R5t6$E?~@UIRi)J(y^aB3tk)2Tv2P>uF3&>U!~mBm*yZ;NM@ z{BjH~CHu5SwPK<$$1IX83rPe2rAwP(4J(q8mt+fr2_k~`=~2abzyU*4*4%uuk)$g1 zn`NEVms9V?Tx2~}ovkO2c$)X?g+C9yG0-e>bqdQ0&k78Qw$k}x|CZm2A-4O1L$bJ! z6B|U(oXW1pf4-uG>ozy2i61&mAfF{8y`Eq`0%JRMu{Gr^}-cFSVkD72!4@2Pvc z_6~#iGB9x<%t;QvzjuWe$WErm>(Wxchb3M~yN@f=`}0+Oj))$^WB7dj*)4T8QMMO7 z{Hx2Nxw_eg9a*#3Y(@cElX6YIIBhSwE|wZjTU^|x_W+}v_NUpdn^R=#%|b+13;o@zW@ zH>K1p!RXr1-zE$G82WZqBi4qN_Aqd_iN=+Qw4+fR@H8VKtVS($_*v?)|2EQ!&D@KB zS)l@#Z6oiH(|nUfm=wKKb=)rv0LF7(ok$Fc*;tHDFq@Q~Z4Jt8qzBKFc8JS}W38H^ z>*($r(AuU?aa|u2sw+sks#rJT>ZJ0$>XcwHE^q_uvEmbq#}8Y7X;WR+WI*gX&Rbp; zv7Im&vl)9}Gw9;JowCgwgZ>N>AUW(wNDYsw(!|yX;Ur}_@^IfZW0;CtZD0@|-GggM z$jz(ova=+*HqdiOmEEd>RWsQ$D2nwbw&+jhBgsKk)M+fW^|k{PpzCypnGEh31QPs9 zt9C?^J3FWQeFZ(%(V84#f`^{4+Au~?jF8iJRPMclcqPQU5exbe(;0gL9!j0m=|usmb4?&~0cl}kT9W!5 z-5FgzQDuR?DMY@AplH?=6Tc)fkW|N|+>qINZ1->@{N=TBb&|<#z@=zkqg7%%VeAo9 zA+lCp`F5K>DZ89Vb=iBWrhBUXBbO~oUhmw-Q@ax7O|U{v$v}-m#(Ds2g2|Jwl2qQv z(?gCy0gG(j{qpg=bjXYj%6y_)@3tEP41UwA`06h!kZ!y5OfixgP(U!B^^5Mey+8{> zWO@_gUmb@3f%{P9_#tZg@Rn5Iyw1ly1PhnfvxEpU5YC2zkmIUGq%CsnWSsdd?)pNM znWJ^O4qVD&ON8Q#<7qV4B@T^MpHQi-#yGoWZuY;d*(ufZ+P+3D3+bE4S1Ss2pQEi~&wX>8q&XiK z*N&B^%S3|@oG}4JT(8qP`Q{rX#%r0OwKyuJ)#-IAj8z=Se2rjVpThNUPSEmu7&6j0 z;qojkv{?1UI=9SUGD0z*yl=`OKoIBzGZSTKI&FiQKCL=x1$P=P->gj1dDRWR8(1jx zSXZSNfJ(1j7IX^;Ju^hJsdlh7Fqfv68lS>y*yUGO6zQ=piY!=}lWgM`6>0FX4O4%r z0km|L(#VpiHg@gL83OoR(8sX#$6bE&T101NGu&Eo%Br+VB6{hoSj2+Sx95I=(Ig)G zre;JMutIzCv&LF`I2=^=u_{S+KmxAy>PS`Wo?GR3kN{S2ZwJY)MyI*|d2RWKcGX6& zhYPA-MjT_U%%yggsKQHnhjy<=fMr5ieOg0tL=|3b*-sT9UruWth)o$PASk<>;UQ8i zQs$2bNnwiOodBuu;C-Dv*B-IyIEA;=ymySK?m#~gkn99N_;+}zr>xu7;PqBw8PSZv z6-&)ZU;|Tc1H!(cn4dh(5y@iCByKXf6y@ptb_dZ@c$_*cE_tPF=A&NY#z|*l$bijI zCTW?F*3ijIJ+x`*J2$5{gZ&#)6Nb4?f_b_J5XNfK)=``>CtoL43(wNEE$$ngusKrk zZ7=Q?D|%8da}k`<|f0e1H|OlzhSISZm>WY$<;^);IeL5Rzg?@chz4eJ~7Hr`*MAxNp( znNq&@g3n`?U7j9XHD5CRBOuTFR zRpK@ov7U_;W8wjR=c^B&>j@%E_Pt}dC>1iGdxFW8rRs=@E?Ied(A0~mYYhcqk1EDi z)D+?A^KhV>wD?}9mj1d~DWjIzJUD>tI<{0-$MqAZwXgg9Syo;VrLa~aOX1igsXd|g z!eJ3T%ggywJS^#|-Ot|l<>aQ?JG!-c_JVp|K78q4s#jwbik?FxZL-9j(?a6qHFB8B zp0szNV+(chpgE`07f-8{;X0>T=cmWjEL!0c=0Yj{BJqN|UL`=A|SZ?dG;Kn*!mO(4pb&(7{+L55R-Q=y6mEsmXTnNxqYp zqaq)0!RC>XQ9dp;T`z8GeM?zZ0Wmu+H)z^Avg-Jp;LS3WV8d0Z>X4h_zQb*o+B~wt zV9M%W_dF1xv2vXihUTpYU5y9Sc0)>rl~_i!9sH7*t8LHO8&+|N&R zOCmM|k_l0J=gKblUxn|%xqW2fRtqUq>Se$zCH zqi(t3F(HB1+_-GA@sCW_nsXm^!x!VVXYHn-J2#QqS9NR4Z$k7cKDvt@3?-9O_0!OW z_wvC8N6)6t>s+NMj4Mia`4Fb`YO!KrpIQ63(gB~VN4Mou+VXgsODZjG*x8;-vKp_d zO!-c{PM4z?FVp9XsOr{$x==IX&m}D}sQe_#wCV|@WgB#;^1%R(dTvblC3>_fN-n?` z&X0?2J-##uaFdqf_|9B_xrdWo*xVct%I#iu3iuMGP~G^|W4tE+%8dnzK~ zoNdrGOx()WM5vVg6tSghlSYC#8|3Zsu<{HRB5I{7eNI+udHSMXAX-R!#WYT%*R+KV z)BgFpm%abeu=|hR^z7$K{bOusCMcbDaEY!X&$W@KuLcwz2y>O+X?o@g?T;NcKa^5k z<9&PkxSIpX@+tBS1wd%a=H)dT<2Cfi`uz+O7aBg-3VvED_57z()jzbJ~JK6!r zCWSVxc3Cb{!`@L$~r%h&JZ8I?N`T81$Vkt4&TNV60lArTXvyaMLWi}ry08t_evL9_-&6O)?W?;-XR<-DyjcHV$9jB-k<*R)upLNA~Q7Xo7*Y&t&8Y|_dpq`jY33tT8DtzgBEFN*H15uWl zqJjlfb1hk$w;Hr#@10IvFuYIr1X(au(E>a9>apVor0CFl2xJNn_t0s7|ChB4=X{<` z8tiH{Y@850Q_JzXdl*wCp{9>1rJLLPb(>>^udY9I;qg^MGK-plq=5BZeE7u&(#CFu zm(Eillic%Mc2nIqE-%&Uc%7m#oHE=UzoUZuQ2+@Zj~1K;I22MfGL6= zQLcL!Hl*rzl(r?k`*fPu4Xsa&xf8e~K2WCd4*I`bg#zgQtX^sG@s$-!^i^N=!`&!N9tUHG>7C8V}O6w~@? z5hyw!EN7^}OMDFrhyI~fXcT9^ip-Tqd^$D`J5a&735ZT!=N@(ht1gTQwuU!EEb`Sa zMii!d@!Gnnf3menRoGursi7IJC#U6LhMo_pda(*5aiG->0^CO19DP3 zu<*9h!ADJGrJNs@RE*6B_zDeG;CPq{RCk($u<9_A?2d6B zg2yC}6C!O%Y2V_i=!Hw##e52tp2){jD~oSC_J3*kFDvhVA#*Vm0s&N9YCj_f-*(hvv&s%)62CN|tR?&($vmVkUFc&9ve_bu#L};^EH&D@7QP^s`m@*miXtFC%lqicONqL+#R; zTtxA?x;4mJ-gWFaHueCAJ)Eg3NG^!QDZ{_5-3#c6{x!Q#@LcDHu0gWVMNT(7gqe@n z5P0Cx>B(pakKzw9Gv_>Ob(iSvTV73X1fZ$eeYNCkZTnFXZ!7nuKd)XjhE z3Dh+JRkE}ifizc)7Ds*+LkyS-EJHx0Osy)!E{>~&^j_$${q>7p?ChuL7&?*mSbCqs z{XbhJKeobsN;b~GRgzh+wfB|BxC@WyYceYd9XOSqZ4I0onT-*du`ZPJZ|_0=eXf7x zR%9dNlWw@rFYg;IUeMO3Wjpg!7xtQH%Dnmclw=i5HD1LA9vu-8Z5f)NWtKo;`t~p2 zg6FvNCZmER_tHmI%X8x6g7aYGbzL^A(fNlKHp7%-I*+Oy7bqFoipp-6z z(lN1qNr}?$n{F9YBAjg*=u5>n_7*N!yCu+OumEoJUCQ2)nG$rGM-RRsvu!8BRj?Ph z%3f}~6R90ew4tD`7hh;i0one!rmVrzdoZCkw_z6OG0$sv+<;984KIv}l^)QLPoy|l zsMQSyJQ~%bB&3ejqBQK}b&5-=?{>^a!G8BQE&s3k7ki}WrmI=`0DC3s1K6eKi4HjS zooB<*7ojNVoJ+IowOI)YoVOsof4IdmIQM0SNob}eU=|JuEVEZNDzVsW8AJj_ zn9lOQsvZ}Cckuw3N#7hi**q}A1&9#UnA#<&u-lQEe!9lkwNuzmaMsTq%NkyaFZSYh z5rTxJMAoK-=M>KieS_A14zbo`V1az8OU3MZE%n-O}0gq~+ z-S*icNMDY^Fo#4fs*%aA;m-1@Dh_!V``U-(J&nSjxXTtlz<+Ep3U{-UNA}mk2j=D7 zU^DbC&(C)u)K$xZI2w={BjhpK0Y%NCb>hx;kuI2cZju`%J=Fo#3#pX81b|2~dGZ@! zKh>s{x{Je!a~rR>d`AwtZbOo)r)a-W{BEQQ%aSDH?5?%9d(7UI?A$SO@r9fB5AIwx zuLyGQNEO_gQteH-(lH0AeZ=hBFA$eU-)JS1SPpBiN0wEZySO%tIWr2L zn(NdAD|8r_sK4dLPsx&%ADyiViT-dEVh*cOk(StCkShZH^MyBeEiwANm>^1aIPzYJj->&HD(>))ZUFZIYe&QY zyJxdr;mK7K)AU!5kKe^q0>>=PGJE@_`K8fb(y*K1D;4x?^kOeh9=*2{ys5rRTk2J4 zTp%DlRi3B1^unGR z;lB{uda8JkRp4eznOysLZ|#2CtcQprsh-jXsFkS)t=7XF@t#XMFjB3U1p~gw2bWNpmx;4>zkDjVe-#wI$7*UpB>HpBK)95r9LF-=PQ|t$Lw^A{ z^XdSg?P2EU>}Lcxz1q?GeE59BA{^|d<&wc1{0{og8;x~8+z~hyzgV(ARx`WB;?OcO z)Ta=&HE))rwSExkE54n^%iR)CG;2Ygr{M&;E-o3Gs@f4Bc=KD4JgubMk59PboG@&xqXNmI{O^;aYXUhl9r&5lAiE` zvgtN88V6AFd+Za{QK1ej81Q_hd>`CO$#7T#f!oaM&$dk2O?Ch++(BNffxO{l`^sXrD#IbwqT>nDUQXOz;y}Af<8s#6#XB1^C z-z9V1BXzypqyrVlH|C;_YuV3h~V#9AS~STq6OF5 zFx!eR_+Cx9WF~PZR=EOQ;I@le3#Ve57OJZDvTynpgak+9d(gzwf`$bEP8n;2&z}E6 zasGvZAm}+=ARg8qq04MOY-ulG-wxkMSMo+dJn@=Sb8CX0pP#g1FO0`d9SIb;&XcY6 z@}vWX1;^G;vhd|aUT_X1lruFxMcmAi%9rWUa*Z^_4=JG^|G5bU9IQ0 z@}8>2%VRr9!zVvSmuf82rQRk{Ju6h`P@}m+ohI$?k)Zg{w6MhT*fypsXjx0f7&uU-H0iUjQZ#DGv~Rd@;gJoxw*3ai72!YR$q`DN7F&wvwj@o8sL%I}XyVcr7i zabE{i=h!c$6$>;Oxcr!nGpv{U<%OffS~U7!UrH76ijJS7-AKAO=DnxP@HkSon^u>v z>AAHS8S^36jVl1A>AF_B8RSSzn@8Mlcot5V;6{8kw>iQE49dlycTo@`k0FyJilU|N zXTY)xFUqTn5VZQzeVoZE_CEGSSA|+C?vPWSB*ysl1mGT)wm2UkwX%G2DWTLm>W|Ph#@taZMWh{ z`M5+aKEY|`ATUO{kh~d@5!XA@VbHqpgXP1<8Csgz~&u9LRXG||3l zfMsY)CBw+d+H{!S8asD-*mPn5tC4uW``a%k5~wG<{njSD*fX^1dRmSbHES`~+9sKHxjLEhdQefJfJUxv=-44gcAT3r;6ysGGXyskoXdhS%CUsATl5x0&b{ zBo!bzasb>mcL?$ircc;=KVBl$=p`l48g-8LCl(p{abhPE&8%oTutF`AXjnXTTNCC8 z@uTOw=Y4r)KxeW-k+Fd-JBxcjx_bEKdz9l=vv{MH7WWMKakjAdPalv>VwII6qHEFj z6R}nr$4%mHx^}(-dt_>Ple`8SyW%|F7c+bMbr9g$ON%Pduy6WO%XqeBrUxz6xSn+L zSxfe2s+rXHh;yNYHJPVFnpvCW8y)JqtZH*QA{`d$T&jj)gfNkWzT~d<@W*riNId@q zWnn4Xce2C{rFyTsKR=jvo9AjaQJQuA_(Fr5p4nEuQp+|G5f_$f!Y#p@7=pO!8;ldv z>Whfg;0v;zEdFfZTrdge5*hi>GQDDl7oPvDOn+XjQWBo@sdC1GkeQVADckE~F71}6 zSmW~Ty^5J#L>WCe!MQ#|no0|di3EV%9A=Zmh z?}o+lMhn_KpJ;IG;fMmg+z!U8vv$(_a_4&TR0Qstn#wMXO;JeJ!2YqO>3D?CCZT!= zJ-hxs6sPQr1{NssAXhb{eM>xDg;ab|!251@*mSdqdYK7Qbb|d#Z*41_u3?w1WDpoM z`UgQgT(@jVw3k#q{`rAi=Gar?JjcoZXNpPi2);}VQ;4WYbQ4y>T%pBx8z;RU$>gVtln$& ze(ufR2@2$jaqn8ChX#a#Mbc5jly0>SI@i!RKCF=KZM2k(;uI*b>g=^zbCKKd%_5>8 z_Z-aMUoMjz=DA^2Sns@kvm|I$IE2ec3(j3v?Vu@C6Ha9{pQ+wznz1!Fhn;6-e%f?V zvs*ptA{&;0cg|=ZIhv)-Nx#O*93|#G(PrVL&MaOE*l@`th zJz3pJMm$V>yI0v#1>d>=y8xMeFUu674OgrO9Ai;w>1b27culLz=@7XysbKbo(XU>~<-|IgXi|$^v zYE}KJs;hqW`+iO%CS*$pceYr+$H~$g;0CgB`jh?Jb0*9XEZwr1C7sMS+CNt*^tU-J z>x93Cnh@`enRoMuxZtDV1S^i|*}CBEU3g=AM~1r!`_YD3yq5CCgw<||>+pSM z)3Z>lYF_%G0KI1`>M30tlI!Z}yz?!lk8#6!t5(z$)Sv?Fm(y?83BDFIq0&Q8fiD=} zom$o7M7$bC2=uN07#QW-C~6GgR*{@8i-Gx(Mhj$$KC0@v;ES zqfnYr91^SiGBriz$-EV8G?8&`2=$vEo%eD_N|{n^4sXZx7GPSyF|=##Nwl+|eGl+> z1KjR+xJ7q=Y<{jC@Bb!H?ybi@79YAu@0eNe&G@bxtBXph%4^LAJzwf11UzksCUezc z&U?FrS%6HRg!s2!ZbkZ1v)tr*YFXNp4{EO(df{9<{*Gn-r#|AIU!OQSx(8T>!dK3^ z6vUNqHI}hXBnE4`;mlpJ8s+u7w=&2m7-1z&y~yDX$Ic@qLY{RrQy*Vv9kw2?QvYSm-=QOkswl#*ydVlk(8Br>EwNuDsl;DlxI z#jrZB+op9u9E&4HWNXG)n*0Z5d3oXeC%9{{p)aZT8_}kw%)=XmWqY>^r$e~Ay*k>wL<(x}K9E7J4!ak9heAgd0cO_zE<8$bx6q(Y>moPQ8QF~=Vpf${AX+>%E znloOCp4Hqe&vNZsn2q^%J(tE62kDeDwf-3~0LJzw-BWa}!%QL28-b z-&voBznp^oB6aK_KewyMjkZRb(N=$Khx`BVb;wW67C+85siDL9^Jyz)iFNuA-lY&I zyZ73JEL{`SD{*Fg>YK=pjs3(h$6A4UyR2`pDyZIx?yI$-jyKdS$I%Ev$-Vch2=cpF>v7RHT&_Q}1y(!8o} z(<(jGvaf!p|G+%aWkx~Lw)j)*^#IL3r7_4x)dQx z?UB9@M1%s2I#alsS%!aSO87^=^B+6Dik4m2vQ9;Fm@DD>+NDqQ>+RFy|) zo!ncs%w`(s0v|UZ5khaJ|3Z{=W5Drb`^=om%}rC(&vB0oby=VyrA=|ll{IxBfGTh! zMPb=|i{W+4DbH_kOANZ*AYZv}YI^24vb&nH`e+R)5@*_D$V_h%>KI1r1^wjPQ-=Ns z9sYCfVJcgO5BILd7m~MWH_wIpl*a5x-Z`IVn-WReI22858y3j1(4)Ls#=i(0vS-Mp z`{~`-I_a{K6SW=J)&{OXnS)^C%+L1E*3XOjsj! z++VmhhR{0X>NIyR&{0B^mtyA+!6{&Q4G?!(00rTh1>cR!E!V52rs7Po`b&%;N79+0 z75cp<{9%i?F9{*=->zwSBVe2S;6T8Q9JJC3;+qS-6>iapl`V*P}f%W;8x@ z`hcQc>lA=|Istl;qJ);r7S&+fHb1BVc5K-UbMMe)+N9oAvf*EE(eDuqdh3O_B7}m^Zl&%+rbLo8Ce5zacWc)-mmYt zPdUi!e^FigBS!j<9Q|?B@`X9{7HXHSN`PNNYNigrHIkH@WQ{VGSn^i4 zvNvK}C>RN-hs|=D-6mA=;snB+HyTIawA^S~7I*a1y|I~ul;;lHiX9p8XDUdW6TVL1 z3AVM(j+$hOI&VoyPVBJBEvnTrj61(@zmu$%m#qLbI<5Op{5d24!1G^Z=a7%|HBeW#C33O=It08yhD;|XxR^H!Lg^yb}U%!J;8 zk*l=Gp!)u&^X~%o^(m$6E1|oXWR1lvnDGzsdAXBltDH`m7-#{0*Zwhr)x4$C`O!fz zOO;kQdeZ+2lFZ#6D{hJa?Jm9Pl?_erZL~g#%&an$z-Po|!;^gXY8g9u_Ph5}xEI43 z`+4g6ojCkXea~t$xV;N=4yjs-(n>x4 zPN|;ZGVT)g)|}EHgK?2`j>gX@*BIHC>0Gg0A)Mdjeeo}pyN$Pb`z`_z#vCOcB%fRi z{AAu(0y?Idr5$`Tk6B%O3Z;wOMwxAsS3K!FckWCQXw11c9t?A=L~#a5veVgV>n2mr z%Jn`Tz0#fkw4oA8ZA?$>^5;yF|26Xn+-}QNJi!|?glXlDbPzuB>OFh4YwqzTbP>Q& zN;&pkfLe~7-}6n-4xl1uw0Mm}noE>%ku2wFPi0e|h~FkDXF2pH{9&u%DaPN6btm&{ z`-oliF7nIX4OUZV*V3rK9CY~XjKtQNx5iG%%tr2fLN5ZkEUKL9+sP_(j?R*B#rr(< zz|#?{wlB`XvRrl(XD~2y?M2$%U(-VR(=9Fplz2TM{8#<&<@9gw}qF;Ap?SdRvLSGC+(Rd8J zPemx!_*f-xPcq}e1W&tFd}&G^3ogy z&I3QG3pw9ZkFyUXfw%*n)ZRCahMe8_5S}~_9rWYmG2Z0cjtoTf|Ginj8{dJp=r12q z9!@LZqBfzD2+$KzGP*CUM5;1$`TW0!(sm|*%MK~HGxdrhBgFz77v#fUHk zsB?8RP(&7;w+y;1;j#!7tv?nHNL=tt9TB<7h&f$I&FQ#R?w6AjdDDhNKy>o6fe*H% zg@RB*qc?1;bEEyV%i}t7yx9=SqbKT1TvF68nm+l`JUM02E-@N;?jCRQt!b?Is)hz9 z`YK~&L`eI;V;|3Aj?uA7)>sX(=eba2!(Ms4OWa%?xBt+TCo?C6zr8Z19-WF?$Nr4X z!puaEva#w`3G8ep7SjOl(fV&2vKooe*Qvvn$6I7ZTHme1BPocar%=#j+x0YXIj|j> za{h+JcrDjb6uG* zYG~5K{N@it9mwxw&yVsG=eUMw_Z>62loLIry1`a}g`A=|_kNKv>ruJ*;L010JKfg+ z3z*EnsyaI8YMWI6v4Bmja!Q)BTJaO6cgnty;V=R6t+xh=MN4W> z<L3JI&m6D%veZ~x^nfm5qOSM@MzUO;NXnR<8$@cC1X z+qfu;C^l1AUT1ikUjRS6h;2Tew)Vc8mZrtDR*Z0n_?pI@A(cE^^-oCLz~c>t8QZk2Dxdl{P+(QSYwjdP;Jq-EjG= zQ=FI)!sm7T-bmq?pEhrMHdf}J_1%}cRw4&zS{o|6rY@_lJ(JtUe8wNg$#3LjJheUB zFU|azH!Y0XbTZde*o4)G0lLg`}&x0DMUyF3bo(eYnb4G22d!Cholf9ena+~p3>cy*7HfDBBX8(R|d z7QF@`Q2E7CxgDO1g(k}e`C@dr(6R@dMCGjcws6ssubrgdZwf!Shu=fqB>>G=3yl6c zDEvC2k;Fj5X3#u@w=HM*2EW5LnN1Iu2}I^Ik1E=7&3wESwYh!{r5WO>)}EcjwyWA~ zk(wZvZA@)sh*xIAX88K+$iwfOJ|gIhpm)GHD<>aVU}AmMZylsNTZ$&6qy%{Ob{&y8 zpYuJBcscSewt0|SL>*^U1oHzXA)@&DAs>-Vz2W=1bbaR*+XYD%t&R|BXNBE@al(vQ zXYZ->I;p05eg*39KjLJ^&71=1&X3|Tf}KN=HE~bB-2G`ZLA{?MrZ5=0!04-0v6-g# zK>of{`nD0G%;#Y#JGhT4Y#SWtSiP;8%}A42f!p=zE{T;h?MCtGCEWV0y7=S){SIMd zlIpyY;TRuCu*`(4Q>a{}QCf@KS_IGInmFvddtO7ks<6f&Z;`UNS52PKpuZSMoBI5< zKKoxgF!*lZvgNqy-NO5J3kA)RX$^0)x+vA!#jiCUidn{`ORmx3n1NwA5DwFAik~BJ z%6bq<&8fR3%>-SyglzRmO%K$frhO)_3#WKZw`tBPT?_QIjXut5GZKLj*j}UJRGN(1 z$DBgfN~KAWC3fa9GRxijcE3Y(pQf!n!(Ic(k-LlieEuq<(=D=i(r<7LNC;v|<*Gas zP}FA4sOw^~rUkk#mdEMG>#sHC1Y;#^ey%c2A9t2j6}ClRX7cwv5cb0TH{$@%khp^; z^q+Nf&G}5G_8!`V+mR1&4LW3N0uzz9oVYOZb5c1{Qo_8c$4bphHW%v^c~K<{Slmz| zVB6NjmEhnBWo*beSzYPBCrs*fDVx$iv1tk&1idJ_+L4vvA%X_Q(d7@xfr9*A%?mWy zYjr)THd)haoEf}o=#c#hM}s^}Q$Xb)cVO)+SxW7WeY|O*)!M6K8^I_V3b7 zord0BN6=D8va_OK_uP$D829iRYQQ|Fs+RqvJ^dj157;q(E64?3{^Z-len8ZFb!IV@Q9s%jPSkHxsdNq zot#gcgg!Jy0^?C>!i9;8dlX{Bb`r*sNy|CZahR-Lpa~-Q&pSdd+?yMO=f_Ut?lxab zThwC=oS(nXO9mT(?PgK7`3!W*dMOvnue|8zM|L78RHy zwO^F%JvM7(2Xq~}ig1-*n;bBxGa8y?i67v}-DS}5lo3vRGmJ|;bn-<~XZBsU0z($o z)7)*zoZk*?kZh!dhqT#V7T$>!JUK}DN8jdd?e*QiaZ5T@ZhWKt2tF4&lzEErb7Cb# zc=H!4gVTno=7;yU*CIw=>+HTqM}RGO7}vh&`wcF|{}=Uo#DA>_CWVzMtsuUbF#F>! zTu0)7Ze?Jg%sV1$iqIf2K0|R$Jx*?(xH}(^dmEoeiZ?%J%*4;MXQBW`;tQlbfy1)r zleSTG<8RG0wt3W-s1}U$z}WhxICCl3y`CI$OeiB7W~7Hr7k-&*)E;KrR79kZmopqE z5DubO_(?}eUNfz*kMQ-8dcB3W9#pkqAo;u2bUzSer-a%5Vv zzKZF}y!Nq8<>^%{oR1y4d%HtGLaE-*?9$7|Y5CsanNrS(f~+l?bR5RU=!DR?w}U7z zlyFAFToV;`Gbup)BXB-UY_&7QO#pEU-5-pCd(?WmvbQ?LtXinKBn*P3K0xsrwU>4W zH1n;AYV<^4bpe$Eeb)ILSh3NH#|ypxPgUt375fi7YCq-OhPL|A`w821;Ef(CH~LvU zSwB^IeMd0$xpyhNXueJBM))Pv%^wb4vu^n}xMsVB^x_wdWyN)=o2b#n6$B`AttqT( zV8w!o)|FkB+36AmH@BXMh2&^|G(nA#d^6OFCgcjUg+c$8UXasLoOv;l0ESHgQ zpPF+V9{KX<%h=rGhkVC8?c0JAxNRDmu=O(J(1%<}%4WZZDC*O=X)C7o^@XOzq@WqW zJuBAodUnd|4B?EOhRQ7YdM;5mccw$$0rVnn!=_%cRy?Ti`Ikx@JmdD~^vn zfk+40Db2|J}bS5wpqD}10%4%=Y;_|G2!1~F=uh?|Y<4KG!i4A$(X_5H-o zC_0NgmiMkT`U3o1y$x0iV}RA3qfO{v%wBN1fUM5oCQsmqbgSweii2hs_SNJJP4$4G zZTD+*ImHa$z6}V=jtdj7BI0x@DlO)#zOc=_kt66(vl2LY{{rFG0LHS?BeP1Aiif=BUDFHfM_MRJU{bbOEpaGi^p5@CJ9p2MN}@d_-4+gHK3vYj)H6 zUge}I7wHySJqu|;`6xb0Ko(-DN2GP!(8a53$C7x46o_|-G0`^ybQEAW+X znCBhVhsxL!=eTM%XCUQp0J8yF2pjGxsu>t1FT-Um=>=!aEn37je+PzL!j&NoP*<>b zuDrCA)ot;@mBq#)w{ja@;Wm@`oZgU+y(z{aJ1RPnJ%pb<;9DkA$O9$okN+Gq=hu1B z3z$x4dBr>eOk{KD*LM1>?-6n_1JksEfpVtV>3{!)!IW>6#g3!R1R^4{(}Y5*3>PSpZ}gqvh6;6Q3T7$mRT@he>U^3x=zK3H9PTCQ9-H(YuTk&oo}V6L<6&&u3ncvpnQlrl*?DqcUOTP}9o@8(@+gWNnyIC>ocNq@A)Z z_UmH&S}s20e}mt@sJS<-5767ZVus$PELL|dZw(GfNDIUa8t|XV-@a_P77Ja!2|4u< zr63T+ghN)Ba}a9lNduQJ@8Ic4M0|oyHcN3_vPQC3rpUat4*`>f(<{#;Pp3|OY_xW} z9GKGx%{j!A*+^k(=vPp|fBoF9{;qmD?a;Q!wkQ3K-yp0D=7mT*6j9>|5X zF2dHlZUuS4Kkt-VC#vo$mxV(`x{sISs5X31w!4f8Uhv)cP|^u5hXj0X>@><_Taeo3 z)-~fFXp5ZQ+cRZixuVsDf_x&J(RHYsH;H)8Xt|a(0;xkrP}Xk>Uwe_UpSu}6W(n|J z7f!sPeGGLEpH6+ctlB1#X$_pY*yo)$NfT7mPV^wq2=o=AoM$B%rI}-;Zk9q~Le%X- zAu>opQVBW%!xMUL&bGTQ``=0rl2>Hvr#xljvJ z50yhbkrlgH_cZh8vKr2TaWVWYIXlHtjcS}-4PEw$AJo8vXsZ>a3njYvyQ-Bo4xbkk zbPh-aCl|)b)As3YyyScI`M>lU=wAB*x(s;xrxYN~k-#cc12g^+VWRJT!}U&WKo2s?-VD9_|$hP*gp};NyI+!Sat%xxQS7C!8d=(~)W<`Vw za+)GjnBJ|sfVwCh$XjO3`8o|QxUqq~$C`G7MldqP-+_z_GdPRdfbs$p<;@dkWnoc1 zph8;4h%Zd>JGUxzsktVOazW3YRe5iV1~%%wKV=}JvC~=^tVY$rcI2j(X?)k>^dn{@ z&0E*pXMy#ULg;R7?qo9IS|F5xj0rtMsuqPj%gU^XIP_PM68~?SND;y9k#)#YV^pW ztHU*FFX%I-bF$l%{s?NUF7K_Yl`$C?p9wBbd(f-l(tEfocd0<#ppw!lit#d5EjVQG$#dQM!MR0n)!nB%gtPe zN~%)Lk$@gXMTNX|dSqT{+Hgm+i?&^}y?UPOWr3B=(PG#6AgiBoYLu)yXK7-FUkRDO zU?|eZ5Jh9c^7OoSG27^Z=Yv(Bc3a`kq7y|d{AKTs4hgC+9|_Dl>tZcXDjBE1wL$`c zso5;!Y%|Ec?jp50EJiY1Qj#yCziSSJ2aPi|0Fbi>e*(lgwxYo$6o>HB#;u~8@Q1Um zv@A>0J>F*C^H7vk(M{2pkvpAPo;d()XGjm*J@uqDV}-4=1ZNC zPZY=~O7+=4e>!~7hM?7rH4aVdjBr)tx-~T=hlPuT;@g|A(2xdbA(!7uDGGA)t__9P*&-zL$F--MV7{sWTjXb^rh9+wy7HG%S zbdBD{#oB@xm|88t9uY5$Q3 zPyh9>_DSK!>-u6IT@3==;;7^cJ+$=d5~$1;z2aK(ZjwM>;J?b>X-WOnvt6by51@AZ zx8@^p-%H+aT3~C^p~bz9gJkAA{~AE{8QwJ+a$oqf9{X^9rdei=FXM!NL&wprU~uq0 zBFgt@XL{KnQe?6suJeIkd4L2)4V^m)k^ZGXF7oOU#w`Mh8b66HJ6A==a(h&bs|)Ac z26SWo21kaZNamVawn*)Ww8;o_68{EQiIj`zSEaeYZ>76-IA~~jIG5RM_xwK2ltjSC z@-UTXKal25q)A?gTgo~=0X-snI(YYo^VUk|pj|0b8bhlX_| z4lCx&oBY&h<^KFTP#^>8G%=&v-CPllrt>Ms*^Jl{=>6c<>@vQ zYcX3~_AWGD@b|K6t?T(E=HsF9ww+a9;=(xH-{4~G*KeA6Ibyb^ zT#cgGrT8I)^Si_Z)rimg=Onci_XC>};Nr2y^{m&^p63!hl?@MUTl8WtV%+$M(@IAS zt9DR!pQH9tuwjA#=7*yJ6l-yU8H~<&f=NYppEn0JcfA35v%F-IC3k&=9w=TG(UL#% z*xUunJNh&Q@{6zXNhbgrPJ-oIk#BY>21*x$dbMQ5Ufs&DCKk?v*J!ltWYQxCTj5zN zb1okNg15}!#!N!p>B9-`ywIF?7_qzfJB`=Cd3netY6_|!$+s^_L?`cs^)UvUt{h%p z5?>|lD9ZI*b(gZcwiLQEpLT2{e_HmTEAj5|g)j#FDuNhnzj6bb-xQEj%dbjfk#WIAX zAIg7Nv24*z&t^3m`JhE7ks&=$T5Ut`v%y^6T;MKWKYHbxDRs~)X_fVZU)!KVg|QW> z$YFDl_t3bB{cK^BtHDUCOxyObyuP8>0Q>DZi}1CS%$%Dh8?s9KFL^-)PpY&swoy;p zNli45N0VtzUH7~0VS6i!tLI#03`v{p%tiWXdef-SEl_EoojA8!v5|_(=6R7D^Q#)9 zOPnCA?fPRMnI+0K3@>~o8b`l)rkFa0!;2J|5=1LZbZGHjMTgS1MePh;|`H{ zJ3W{^o%iI6S=t?ec+3x7f1HkJM91AUqNx9SoKmTmp2hfNvh5$;6OSvZ((9Mm2ETO! zaq7Y>cq_}f>zk>}h#~k@sT^88X0AD}Z+e*+GoSbRAa746(|_qjnAwi&WkPjBm^!pJG`xNee9kfOhIoQa{}@?}Kc=eb^h`^6!R*#gt5 zO9HnEEskLD$*Y2qXEeLyL6h!n?kjG#Qz-|VQG@w)@z0;L*h}r~NtrrWMhcPP5s*(Y z?Z!J_y*-Z~m*rZg7Yym;ymfx|%`rTvDY`;EDW}4~#wLE&%QTYsY5|GC+&@~`@<bb0jyAgnG7FB40 zDY;wEw$;6%@zrFU)<>;k6h60eX>lF`NNwcCHapnQ$ra=pTGUqv&V{cN8C7*wuBk>U z@-Y)obW)cP=09O@Jd^pGlqiq{Gk23LUer~Hja-G9Gxw)oyb8tSSdwvB* zeh)lAV|_}jwyF4iR&Sl~3@d2kvZU2LjpEqI(kS2{52RQ=yfA4GyggM&(%G1E!tb5U zjhD~-nXVzH?uR4*Py0(cm;vd^7lSZ4>fp%meRG8DA4w!IOoWVws<^ z4kaYMJEpOsU8`;};HiBqmg24M=VW|{8)tv1ZY8$P9Sw)NIV^%#xNoqT#auI8sLEYQ ztgI|@4$-qguz90iea>)rH~ z$+**SA=5ivZPhqmq52i6HfCA+VREdRE9QbGdO?e>q9XOAE_DI{H1fa28(`?)hUWYR z$Jj0m{FfbKf1jqooTMqk_jPjY98>Oi`Nn=}aDvOW=KYhRWvr?QUy->5Eyf6EO?{ya z3Hh8hS{ek5LYXqj=N|<4fJGs5!Ild>ue&eNDjl_AaW`bG&7!0-v*nXkV=MousjQ)-5gRmp}B;C_}^Q z&;nvskKCARbD{50tZ3aWIlv{!+xfVbJqK~aR9Q{>YVyOfWO*(g${6EpjBz8{oHzjN zw=`+X&yoZ>ob~w%T;qf5W?6^~rd%%%$!EuM&249BN>?Y633lq=Qk%A}3YIYW;5PK# zxWwR07b|K&Kh?{cC%!c=(zuv<+a*WY#1z*`s)=og7$&Kz%WcNb`O<)}pw}tQj8f!)vaA_iA8)v>r=3 z#nZ%(pqb^|+1yUQmNL*>&|vt-sbyTO*A-q3J&PQui!_#d+VVb)FK%~PoR=0LCmwqU1a)F$$n1KFr@P%;H>O%D8;L< zzvL(%zaMkmuZKKY=wH6>}WoD zP2L^Uf`s-`=7HV<_1#7?UkKu8KnFtep0H-0R`+Il9z$Z(Zy1 zl2T#%#al-iWO)YabZO2%r^=;u zzZG(@k2!pi=<)7y)6%$Mbc#ONrerA7NQKxwI>hy}eCbz#>=p+E#=mvdr1Ro0rfovQ z4a=#v?EPR$*Z^B5TIcV5KJjWGS6(uZBCF?fVb+%%+bR>kIn7ifw2;xlCyijBoDD_2rVO)QF3Jt|IYZ=opE_7Swrr%S< z$)n-`^`22$GsDk6lU5IOnb@|=EM2Cp`jRk6BZDu}zxw^}JSWzN?lHgkl?=eE-vK?a z>E&;5w!XagVi)a~;r&^p_2)Q}PwJmO&i>1e@c+Alfz$p4*WmEPkrqG-JU1K^uv>TlY(Fzsm!{tJzL}r%(Tp5+VP` zUi3_5rnace?rrXVGTjE5xC-NCss=a2LcfA(i>U;409C+~cMfVgW`mf@L6s;dL!A;o z;;im4c#*K}Qw7wMUQj)#U1_I^ehB`m;7Vv-E?yDRm}Pl;yn3 z=`f`XcaYRFwWQEumNDrZmnC0#T;LUq@0oO^v+Fkpd*I*Tw6!>Xf4YAb6zWg>XW2OLL9kkNjxM7Y1lZiRgedz!z& z@%`nh|8c1JCGo%PNQTe6=iBm_kA0+kTGQir;s3{1EAErF2|#|U1g%sLbR7a<`U8)p*4ny&GG4rQi)DGNygDg;WeXpVTl`#dHc!Kp zF*i@0qLERAhL^AId!C9QD}DYxsP|>{8Y}Usy!FX8RN;K(| z&o`I@Kgu}Y$T_d`k8X}|y($>KO~1z+cP+THvx9DP1lxm}~ zTfxrtLbWj+%u!3XV6ZK-1To~gmftjapTz8JVIJmora;)k<`P5kjR4Z+HVg@jjR?Im z7POneT{LM*p$&G;=%1&X?NMDukH^;I03TJF#{p2?m(e-)nU_USh`u2%R< zrzc%_qC@*2-s<61W6L(0uFdlHV@>G(5K6hAoN0W2G z2XzuU`3?gZ_Ja!tCVyF~SC+bq&r_5Ls(T%okb8`7k|CFi906u^Z00@c0-MW9zix0C zTlgyYEiO9&ZH>q$rl8*`4Ge$gv*zg7T)6L^{vd%cLVtDN^r_xvrTdNWf8pD{ZN4SC z5HGI;{YGituQi-@^tIjkjI{X+(v5NH@d?Zl8$V>98*M%}iZ2jA`?4`R8t@G^dkp4P z>Pnsdp*4{9l)4mUOw%j~a6+n#cip6>&2}I|sByq+)S20pk15w3n6XN2R2E=V{8I80 zzyY)(MByI2zD?M{EQvn*j`6I=J#~&m8mtmNx$p@uQrmHk6(GB>$sbdx@}pqe_f+fc z#7u9zLC;__UUq;)m>OZPX1`x&G{y%q{YKovrY)j8mjX{^mGks|yG}d-xn^FEt-dTs z`B`X79a`YXOj>E5yE;x+itm6U%7+5s_g4Z~nnvgN;pv7FBhWs*Y4>NLd5gm!OZ%_g zNol=U+)W?N)|gi@8(RvLpM?57m2orpzN%FD|K1q>i5C2<@Ao?vrCu8Dm#!V+xn2a= zG4r}FU)D=1LFe(lPUgL@W80r4L4|jbZna2KNL$1I@mWjec0^sLpf7~KFA&LN8^_ys zNld@?c#V?WiLZWX;<8!ki5mXD&D#j8Gbx8)quc!D!>0Z+)GC!p?@xIpxy#wWV{?Xz zdR7ANR{`!=tk_(vs?jsbL)Cp^{)GdQz1-_o{Am2JvO(Z?7@viCrEk4oUGaV_n`+MI z(P~a*kE&tN8l-O+YcZjW>(5(%;kwuOLlx)MJ{72jDT*c{HbJ6sFzrP&ECJZ7yt&n^ zel{(lPC;XSJqH$oTODfNPb-}U9Usz3kR~_8og-TORxms+a8iJ0XiBYivlr8YN&eX* zkcEs$%RSqP*I;EDDO%qXq3)z-333rWY;zA}sxI{E>E`wSN;Jlyq3~Ez%Naq|6!cp1 z;T}qFJ&z-!2K3_g*R ztwbDqn72|;+DJ!b+FP{5uw)l~ADvOey(I1#JC0WKHh=5qufRHU!`G`10mKn;J!~jz ztALOZ7%iDIX0QIGXm`)K((-H9-ul4Z@(SzG9%h@U5LPzS}3{o zlCn{n+?M<8jH6%Hd;6U-kv8EuF5;grm85%Y8bJy79Qw@1o0XnDBT9<9Hg8$%A$AvJ z;w((k#1)x*JP#aK?h`;+&m_k&qlic9KYx6(@Iu&If2fAvzJD0FK$_~iHAmu=PD^dR zpbcssUhXN=)K3mHL!`9EL`bJBGWtaOs$R8MM{J{Kg%rX6yUirU8PQ7); zCi~0}`dTy)&9~2MP#9O&(lkfH?S4N}fEM5>$?L=`8UTy$igHBZj1C%`RX(E-Rqu>H z!*u}3*DbIt$fsXScl$P91aGG$Loc;;XEXYIm@8(NxIdQw4TTizrtGQ`&`Zqbpw`_# zY1D#vyu2)_Km|`bz4}^NvFOeYOU-~C9_ufxdQeIFLolDrS3ZZOXLz(KZ*jvk#w2kE zzr^SF!t`$mdxhbIJASuE5$z#e*=kP`+Tqeb*8uI8#+5!x48Tk-_gGjg&S}Y)*8z#; zDk|No-0?7&VVV_D?;CT(c4J^z`i$ZZdQBslwLMiXc`n~z`nwm+1lPmiHo|USLdtor zx*HErA1>)bI7@dyK@lJuw%qOJ+`&3kyfG$xu=tDQkpJH`EGe#>2}mp2}Ijs+%G+?u|stT zkM_SYE4Wt5fwU&4JNcw~yr*MYXRxBX(rL*4N3}dDm$%eZ7M1=Y|flnsr27$cYV}+bM*=9QtZc! z*c06qd$IL@qI38s)HA|=6c{Y+jV>Aroj6deQ(RF#bBBtHs??VSRk*VTyf;=aDxI3g zNS^|b9fjmG35q&pE5xOwdf)-iP*TL}WlPd1A1MPoZNXmcg%x&jFL9JXw_$H9l7+tY zDx27gm{5_y$=r#K){k$l=`x~dPe*Pn6UH@mj?dOzfc0~+!@|Tx7++1ihxJDP6)*C% z2v?sL@0}D&mQCtSqQ@DGSQF=`;drBj9*;0-Bk~)2{9B#Kta6fFdS)cf9qpDBaul|l(WpjAW;KwXfR><7L945o!2Vfs zn(Oo79gkf_gfIL}^`2jy3Z_(~+i7%`7(Pt+X8?X@th|l$0%>g!@-+8GgqU}xSJeMO z7p4OA8Yx$*>89@oML1jGy#?Hb^^7s$9m1&v%*zYRB9A2AU#EEUi3O$#6^}5MYv^OP zgV~d${#fnr^-sLlh1SL}Iz1%X5u#{Mf6FCJt93YgFXT0|kd8Z}5NxHtsLkBt8(On@ z=3;^0zp;-+hrX(c8}X)6b!_Yu>%i1hrzSi++;UzJ01&8V$z9K#qm~+)t+JdA<+C2n zbq!0ErB{pPB0yy0j4*=}>G;DA{{Nc$Z)qjMv81ipIR&}EqstB7fjKnlv|748Te(>e zyb%mlgyi83$|Djz(@l%ukCQ1~Hm~Q#rDUH^$fPjY6o?1j{7VZ*05z!;EzqOrwRPuD z9#17K0^D2OcMU>nJ6U#99!jK{x|O(n$#a8?{ZP0!g_DCH@<+Iy(aI-Y(r{C}>Ycx| zw4`Q?!%q0|h$3AIWkT#nNyO6&9t$k%P3sx;-*TAZX8y?@4f>dWf|U9HSd;m$ZJtPR zG)c8Q8k6?v%PrB3`c&rXiGdA=vicZnjhzFOE<`PXWZ&!*3`#3Ui9!5|bR>c@{gkOT zICP3U-&HdIEBe_#rD+wd>}Ve=R81`qkTF!{FuwH`x;H~WKNXnnD~sHF9#qyVUqZk? zUo_pU<~9FmACN;77ZjNAB{D>2V){mUtP^j^CY_?MSn~>qF`BW&;ka2cMZ&7&yik|k z-LIr5+HGN4u#0}&T(5`Mpnn*wQK5fiUMw}yw|W#_+s_KwVFsm}sNcpc*v$9s8Ub)Ji9`mr88SK7T{q4TTGraW^)0})&$3pQ$ncN-rpmuU}X2lSfK!kWpSW4K3Bf+-;BAZzw+gsdE44DdML^q0{o*hCQz@@%;PrF`OG1BKL34Yu%y+Y?_o;xD96$!3bqfM**Dl`!rVX&*IVSQAIOa|a}Be*MY{N0 zCuawGauS1*%?>c)9PhpBQdMk}&zPiMtLbHNo+=(l0Hn(OzGuV<7XBcDG`@IiStC8M zf1j(TFuP@8{HCK%dXb9sfwoeTdbhjPtMZi3(!{c|E33yvLM|qqW{f+Z0Csd@DZ6O?j5l$-g@$FvZq$`febqtBlct5cR`0LnPN0* zXVQF_2OG(PvGL-9c>b|vdSma^4szfnuRKmrOJqxrA9wwgq6-D^QXjHAiWBhgA^*{>Xk9`(k_8b)74TulyGE{xk4D7Ny##^ zF5Co}z}zPD7k~%=kDX__OX9T5oHiI6ub*0rcK8JsmB*Qfj_bTqjdMv+w;^SK^z#qd z1HnF77zONBcA-r~b@7T<=~QL1L<~I8M`#?CoQrj`Bw4Ni^-+JwrweWyxJ$x%_OgFOSL1ls7A{;H!7WU}ybW=>HY}Aul+r7-)1~Xwn`KD|0>$84E88Ui%&@+3uJt1cj1;e+mv>xK(9p@NxVp^O>F zmVSk9o~mzlWQ$LXt0-oEoV6?`qbT|2ejD{mbu|~s=>+uhJbH(+!7|2P>L-YOt!~_p zv2yix3m(+2xCvV4y6Hu_ggCm#TeiXhRlNdV6C6OjsgeZ1X-!bg&v062rr4T*SF-@l zG(^DK)6QIc!WDgZi_7#;THTvD%R>|b;!z+p&W*q1Yj-`(+M7O`8Am+^`_`e_IcY_4 zEdKA0CHUPzGNJUL2x-Shd9f>4ch~6_w`L!jrRJaPA8JXDc&QiJ zU=}2QqtK+;!?--n_Y6I{i*)(?NJE~}Zn3`cM!vW`HztV(>6iwe{lc7Ty@7Nv6;b%< z0|^wWZk!Q)zvl>~4FY`qn4ef4RHsx#_Q?cwYQUBAy51SB*OO9(fyV)-^9V&&kXiLv zt!00Tc*27y)gCmh(yS4ND0rf&-Q8^vsw;kKEo$e8xelMjo<N{8<`*aEf1pV#KQ;qzeY@4V+uj�_!?T7n^NRisKT7ycr9az`#CX?$ zk+KHW<(X9tItX&g-Y2E|dtHSahNWeZGmdh3aPi+xa!1UqIW2JjKzelh7TxOU7x6b` zdqBPson*Z*PDjpub&tRB+(JxkReMy6>QzQ2<$aboGsO8kH|i`!HRFxcbkSMvEXzWf zMJ;_m&2~5JrpM@2w!L7~K=6ZJpB!s^TG!d~ z7*|Ptz=CZq+GD;ez`_{p*S9NZG;ALir5MCo88;05eBqJ#&Au&o(4lLatH8uNdE0*0 z=z;1Rq`8$9kLBpMF8Y(KhqH6#V=5m{jXhs}yyv{SGsui2fWB%?< zQcCr0{Y~|03%mhCSJ&DGP6ZqEjYd*aO5DN5FRKh=X;-L&c>Dk~E(fVTFB{)j8P79X z?2@!@Ih_)1HWmo_M-&gwG$Fy9IarPE;R*j>o}7`p)y_RJjyL>uJpTPzQj0NlS{5U% zrHZo2uc7_tQD7SFzgN#cx87|X_B&uhm#|_`H*%wgK4+Jv9Gu${5H#G5jftHpubP&h zn4ju=Fl=_tq@1Fn$$QE6nLVZE4+(YKEvhHEJLSDNJ{fJttKZZ4#c#N)gRd2TzQg}k z>4MBR)AkFn@J(q-T&x~KPP($@oKN@;O07r$dtxRJF$&|p?b4yqE!p+0opTLp@^4>* z?6*{f0yoM-T2B1VgMvyz>KEPi23&;emE+E|%hoNVkRnrb;m9%bI=H%fM|q1e8!Nn$ ziY9v-`L(2?GzCO04i^Rcx;gB(&fc{yo|JUjSeKp2kcoUP; zV48H&=`Ero&O2p9_w6_{)!tsP9?=P;#w5uNQSPDHf(g_NM-}Xjov87ujbUdrf9SPK z37(k108DG#(-qT!0;#<3+pQw(!$HDybi%I0g#|Xh?4WE*^^Q9wp%2;gpBCd@I|yd) zWQE9*@_)S|vOGm-Gp+q@)hyEFMKTb+!u0C^O?tV_(kn|+=z=Qref)Rnk~kX3^;%dD z=8<9e3T17{kL+bW$clfM%msR_3^gS=sG#3(C?gm-29?>=az44%pIHbHv5ojo{I#v7vydsO1Qh)#7mAWE53^dYMOZ9Fiw$7{o7apRR zJ@@o5hv_|bGvzGO?2u`3DE)MKjJ<@Bx@$xCz#4&sp(=NjnU}?Yso}~oTgCJtv3sf% z4)}?HX7ipAdSTe{Ydu1fF8OFY(Nf)llje!qLY|av(O^poypzo~m!A;Qy^ygLKRCMs z1-9jtxWW~;T(QJoqn$T&Wxm5Z=8P8*NA(S_<~H^zZRgIW5Ua-14kYS698ex}!|tig zMEgqG?^yme46>mq9^RO{p`206QUMR;P$rr$B<(1%+4%^JX(3uB(IxUeu6W5pSK>$ z$31-?WS}qL>swr6(HIpOZ`sN5XU}e~L6GAqujk*H*W=^8z-$!MBQMSj-t}H`u+s0Y zn@ILeulF;IQ6MT-lm~|t_On&Yix;Numh0#0`}5?zwwM6%`a;=<7dwO85p1)Ftq`Yw#-gk-yLJ*tqmyw1kQ-8$@j`@TCV23UN%&5Uw>g_CXUgp zGg8T0_jr+a&yaCRuypY73X@zwp9nDN@7h!zX0MlZX8kXGv?R z<=$~TypH5G^@%$&jf-q=H>D}ICBmfC&-Xqn?(nXyd-8!{#WL3Jcg> zJoUU0SE!lK7A#h?!0u|ifdn;g%hm49q+Nt(!=|}$Lmcvf8uQa0Z(kf_TB$$`CDq?) z1P_m(yME>i*bhc5gQA!L*Mh>*;U=q=seKOo_ar-in70Azp8gQX{+8fdpl(Oq>#eYL z{1cyYmrCO#`(pWe zuWW|H9PhuYE}{paPlnT(=w23Uj~FXfuxu2r6H=Uf!2lKj&2kV1YItPdvwC5Nxd!GI z|3fvkS7@nji@isiMQQ#q*lfwy4;;{mM?=4IK~J+rUwe?;d*z?O?pM-Vu}$xP%+&y) zRCJSOGLx?=hP0>Wzs-r7(SJqz86N1M*aCL(I8h8R7ls8FAcoCBPm*g%I;Hh8)@;6g^@lg&5Q(UIARqB z`=4fZlHfoHaX5JWIfMA7AKEhZt~X*rD4JF@x08>TENWXn#B(Oo$_xd!>pVxudGHL9 zlBu%_oQ0oC`nmg{Jug8*am+pI46Q~=BN4~)Q5XYjT^A@I)@uex(?st51w=EvB)Vge z3o=feQEyL{_@TJY1GRIaGEGf&Lp(R28Ws8l#cf=N_V~uv#328OX8dnuaMZCV`cGEd zl}G$b-pR3OCT6=rADN4G46*CZ{7zBwJAHnOuAbiC8VTf@0$rI$o*&4*R{#8GJ^Zh_ zgw)=Qo3C5$=X%6d?H5;n&Pr2wgzmKKzU}I=%nxj8xs-J|?1)-n>B%dj2~i;1hr8ip zhc#3hI0S*c)Gs2e+G|=)RoMIA1XAW3hctWh(>td9KqyK3b-KunX4qCxEJG=@;=MwNjQOY_z3Y|cEuOfW z_&;vd;B3CT7Smq&K>_3yE3kLSzwktR)i}2H8%FC&g%rH8gF@sFw+QmB9kF%wN_xj8 z#t+lJzulDVUbr04Tms27tZIwwjYvH=WC1Ik+wBn#&?3wI>c}@)9c&O{Dn&(As~I@3 zYgY=kr`W|Rqk+);??zK^MEO&%>Xpw+ASI`=ug#N?Zf*s9pXUbVn`3jUM|+y3Xo)4) zEQ1w`xhZLW6sUl1!jj1qQ~4g7=Q5Xk?dth&HBr@WI-M;RbLu|y^@?E~!VlD+a8=<` zo&HgT4fWUSq(YZZ?Vdd6=5%VF+aPCld`$avkn3xmoqhB(rH52IPi7caMiGu^n`0|N zuWIU@IooPxE&hfzYp@#cv@blT@`#*UsJx|9 z{0PSO-`?JhV++rEk>?o&TO0FehJYrLdHA&kw2aiFC@tO^z! z^jsj4Qe$LI^R5L(Z4+_<1pNgi!OxY#e+YNud)Gcc(xL5FR_|36(^_~$wS^@!E!=#P z&4WwFV$KpV5PfXEg$uk0`uTT4VG0^k_35b269GCL!1=3r)}7}rF&VkVD&;!QVuu-d z8E9U<_m_DCr?(M$CnA{t`2(d4pU=-beSxlC-P}R?O`Ad4j z$XCSJn^VE3Pt#+;Bihw3LkG}2weAlO9&%)>a-8|nyrdl%p{Fem+){8ONuKbRjWC0O z0lE!_#Z#^@f?^du^FDQj;oj<78MYp?TQmSTuL_&is{Aw^5}c}A zPd>L&FNEA~=42h(F6uMF6I>Rj`h0IocGY^XpSX983Uo_}JjVfH9R=natCtk0NjmS7 z(66;*jHGb_T)1U+>hc(UQocWD8=X&L7+7&po?E6Zm!EEaGVkiH+n)dS^-Erk#eoI0 z!LPZlOC`hp37;ezTecw%1Y}hp9iK>dkRCyIT$7yAl07#;6QCZehMj#_<+%RMF_stg z#ibRN6UY@dbJX5GB4UCqnNOkW+Tk>}DcwK7G;&=tk7zZ=s+*dsaPld?4U8cyKstOk z$A)2j7ipekoruhs+a^c_$u;(DI+-4!>$~bFuF&P8AC$+WAXSJ$;GBsFH-|s@NFbui z1?6%PKcU8)YU#r92YNoM9&F+W!)2Ct2N+C|~M(E@Iy zuWn?~^IVK(yG(H_?p$DV`yJjnE3EKcaVRwLYslYfN^xNy;o7p@j?yXMC=d&BESa6I za2?Q=s^m(m@Xr^bwA7R0esbyePF@44A|4#|do!yqjr}nCBUOgy@{Ig0G^&1-QOg{$ z2OqzFGk|7ZYCyXgw$!_W(}ii2L)F&KWBPX8gxiNg0Diup4IzqMO)Wi64PrBQht)@9 z<81V?djZoL+W`pIQR-n!+pjDRG(G4Fvmt$$b$u%&jrS8m=N*8H_{uxVwJ8s*)WVCR z#JooJud&uqR6?m1KfbVSZdS1U(tnccQFfOw;;#-$_8=8}tz`8tDYTIR?22ZMT4 zo5_+YTvfw?*oyT2q?G&*_{X)raAbU$@|c!F5$x3s-p7)q`nm(NdUInQLn*S6kX;`s zE`5_4LIY~GS=+M%ArEZFWJS&r#vJ?B4CR6mZHZU=@#%$C3uvWp&?Ub+neGJ#ICO_s z>urro`+AXZ>y}{vc&ABuNKQ*jxJFI4>A`%t`0fg^=F})aIo40Mp54Y zYa$-&R7ItE&&>B;N|+iE3r$yad*&vrBHefH zdb|7OXt#GQCX1lQXwfdTq)sz_$?C-ia?SOY??h=mmS{e<{RL2O`Lq~Jg!BtW;73}+ z3ExfOm`ljbJ;rq2BEY*t!o^U=hjRjsMU(UqTs7AG>UOYhK*f779bV&o70!qdjPnK-O|w$J5MZybJ!erwrS0e!NNF_*n$ z8NqXd9NhIM{d9WXFb73T#z_1L?>cZxZZ%5+7@^V@Y{)}8!4|Lr#>G6PH#bp!?9YX^ zA?)yXTNbB`@?Ms8Uv!Mgee!sldv~PT8o!mzI52Tvr8BHgk{I>SB&LSe4z*|tAl>*T z#TJz$ovXgqP#fQ3ZtaQoj_0-Pw<-YvdKM#7H72=@qpGH$WFE{(+N|odqf>E)4>QM^ z_~xUhgB3nhvuv_I53TQG6w7*#RvMRklxFr~@08q>v^Blorp;v#K)Q4(pN;V?Z6k&p zM`IiniYA{f7#LvF9r7*&mGqSzISIgzD`M6M@PGcDu>WV<9~|vZ2Y3HM^4+hc?S*D9 zFY4U{L}Y_}#gscyU_hpcf8z0Rf|V=ISm96(@Iz9p~)+Fo>>X!{JJx@>v|D08r}fu$I5tf?9PQ{wa*>T4K?I|^|SG)&aM z*S+K<1pSmnd8ECqYaW^>9$qwko0C01A2z$zE!pIyTyY>3fUkNM$aB0zAR337 zV|6fu%juO`q7&b3=saQz252j_?$uMt5*ln4EI%}T$Z2GycymC@rP+NNNb5%@{petK&>MSnuB=(v{ zjl0zCru4h^daIh!B z4~lOypf>t53(D$d{>7H3wNEQmO2qiEwl9Wp3pLm_S1*MF=SRQV*&YiK6~%POPhiT+ zlr#s$R>T3L0~GsfbFPYJF{J#~0?bMIj-kk0CHL5jPU zV^$6xY}-{Kjz=vIPZoiFF8jdrFna&r{Wpoc#EAVvgSr3Nmnu zrg9F6Y7ki>G3#0VElcTxoT)e#>fkOJ);bWP9uVbocx_y*ry}#F^pLCk(O-B}J-zaZ z|M<5%J)jVe>ZS)2s7g^dS9L97dYNhXL05ubSbUvPWlgm}oH!&qJRQ6%BUg~cNBpZS ztIZ&_r0-)-uP2r7+Rf6wOSz;kD*akx{%e=nB`U*1tEBm&d7tLmpy}<=Nej7oZIwBu zmHOlfIqIxVF)2`y^tj~6pfBnLpE1QXi+Eu~6={$YKo3iK8`)6v!=b)3@a~B$5{ch6 z!~<1nb`84e48X4zPIR6Sl$0lLunSORA}lA-XVZ_&{KpLbwY>E4@kC^r2C*hv@_n&#|MvbNORasxp}W%~JkyDwf)PGU7nfDH=6KSe83QYOks?Px0?=K0tOyha zw>D{$%M$tx7|7Kt4^(WRB6M=dqDu^L!27Svog{kkjEOPzs~1fQoAuQT!{YH3u4^W2 zY(*G=crdaOfLTbMaHv;S(dm;zif9Y|T+X*}7s_XlbW|Qb;#fnPwF{Uwa%4|k$!znachltJLLYpG?J=R%0w2tG2l`mhLQ19*4 zTqAfEHd}rTmRGBbXXjOaT`{EG>cc8Tw~o1g){dPBiYj0|=WFy}@{L2A4d&J|ufAMe zrys-;W^jPWM3)BDqsfrOWQ~BT6I#@3PlU)n9m?s0IkKsf}UUO?&Ot?sHUhrYQH9 zn37@N()Ld|dGoRtaY6ZW67wmGJMr4%8SbXCx|N_1);bWW6m?G8Op55#(d2BJGM9Cd zJ3EZ>bCxRlA^R^VN0Z#Bs^SuBT%?)Nw-xn$SbJWJMw#cB)Esa6<#tTFW$P0$#PX1i zN$EQ6k1qM1dS%d%R8nfPfAT{XO?%uI1Pxp!BxBKCj8qh&skyWPZQpBHECHM=)!u5` zUk)lq`f(Q{x#xKiA|S`nCRT^;Gs+!yIaB?tEu<}|>!6^vH&FJosV{-($!McKTfIZO@7Y(#B~|9-+~YT+0-}*<$y;hai=MuEX3FFu zVKqSC=cUd^A7>byKh&3+UT6_Y+9bmfvgSC#7hKY~gj6Nw@uXctgYsCoIf^_=b5HB3 za8YAxVvc5bUNwJO;d)kCNpO;R+Ji|F=v>xxBg6PF2!C634Wweh&mZ9K(Z1^*zrYCy z=*@1{afN)N3-d2EViOqk@V%%uVOq=o5%0h9+tp57BJ}cKmz4i-^%tHLU*unS0gv3Q zu6w5GJqXnFs_{KUSg-wOS}7de&8jE38dbaZLnxLM4Z$f&Z2rURz6NaYS9x~ajhiZp zCEX&yx;OSg)_&OIma@y%I^SXn?F+wikJDWClDyrkAaZll>Z?06BZY>iT7(cXG$%qN z5gGdX9Pm1e??Z1_8rfip;W1bE8X}|^8B;i5)>rSVT(FaOIt>K7wo>Yc{luzkUDpi` zb`x1=00yMgf2$e!+_`7sWBJ;C#=KG`$$;dk<7x|qz+t8h`Wi`3j%a}M*~JEYsQ)%^ zS_A^B6kUA?Ml3_4l0n%E*_;R>g#hDO)rH&9CaoTsYEwqxY6fXx4YJjWx+>roXjqyi z4ic^HTS&rr__eX9n4=p{(7%1hmHo;W>|QKdfNy>VS(s>5$H5{rooX$ZYPLH(_WAC>U!R<333MEr3Hy#aqZedB)icH$e6^t9W+-Q=X^EuZEhMHA!anR z;RzKLgk)FlIPP%xa6LV^?!KW6NnOKYyUfBOabM|6s@ny=zASQC@X3%UxYAvmQ(mEgGvC9 zK0so4tobq#^tY!L{#DFGn!9YH`^zJYb#6|30$SCBE@mg6)l)Rf8qG`BI_8j}ZZt!@xwhB4&`; zPSBuIm5BuyZ_R-@l*vQGdPda0yo&U`e2}dV{A@U`c8+S+QXOCK#CIC3$yFks7f}4I zT)Jry<%qf+&`vxz2U&`&T*}MXdJ<=RR z=Rkt_%n5y?tPB!hG!n!`7E&T1)*22O?7|arHXoR`yf7n!}32j_^GJx zYsF44>4})@VvO{cpb-@O9W9$cmNoLMe#bXx1uk2XUC&VR9UaBw=(un>iU%D4I z+bWn*Vg0PmlGR*Ar7bh2sz)R)Jg;HaX-^33InQ;sR=>Pw)C?<>pc9r;xt1mA75>}^ zl=6tByq}TX94x6k>17M4Vi=*dF3V;YHOt*h@Ii}ir>FF{0`RTRV2k8|7H5vWM+tfk zd=u=?w3qs%L9t=Y_E;AAOl)pzyXgDNkYb73&cpY7Rm(<2MLC9P+HISzjt!HQ2R0)* zdqmoG%X)|Nw_mrOQ{c<+F|@?8+;p$l*Rzt0HeagP?CZ`BZ13={JZlm5yLK}ZO=!ai zew$ony?|=10JSrFYfyTlY9mbwBcEK4RXa4EH5PX1d8e)xC8Y>O)%Vy_4CU=osFOgZ zreN<0A?dYpmE9UOEcMX4o?ug@CJpkUN)H@SL>3KFoX3lm&S~knl3Ntl8X*_RT80F& z)2=k`Rk^6gwoYwg4Ew&A=Y}cbfe6|504n25JECeN%Ew+#|A{bDto{sjX+8*$lQG8U zHirFf>BoVF<)Y53`Z6#J=M72FXak^v5{SZcdYyawE8C1ZROJ^2Xc{2;y3J?^)fOp^h%*@uIiW@&z*D?)1pMJQ3EHTeBtWJs-`BOO+uIw(S9sC2sAm2Rp2 zjo!5iIhzuJ{<8-Yjm|S8zNgl~TpACpmFuiw1Q=H!GmJF$rR@-~XRZsY65o8V6(N() zVXPtsaMQ9hI+N{D%LO~#sE=)v)jP=+Ey+Qox@py;h899b5&$2s=l4l)TU7vXyP4Xe z)z} zygKI5yj7pOx}S&jjas}Mb@=0xQsjtTeD)@k)1n6v(4LTcMv(`tShJTJ*4Y1)$IGDh z2ViZ0i`OddWuuVSBA5zP9+*thafiP;jc4p`ZyqnSpli-CvW@)y@jtoJzc<7O5Z}MX zB?9uA=Ty8>nUmZ+kYic<+%_r}DcxJoZpl+|Se*2E7%4E9blmF}e) zuHt;G!r7$8@^n)>NbWxAOOAs04D_R-7`2T1S}ZB7pdwrfh`DufFD})J;W6GhgLf&v zYO_!a33%KiH@AV5S@K;eVyzV4$vE^gY{rb*0aI$g3qxdIKiuT}9jqK@(gaR_n9P~@ zbxCbk+CWUfsbbSFzCB~+*@!JwA0}GT!u^Igmg51m`IF;l-mZw*37{snUJ*;m?449Q z$!5^$t-po$6?Z30h|k@w(r>?I3fylm zRS5I%AHMB94ENyer^}FKId=@mcsJu}tG3sc8rRU6GE=9ovkoFrKYn+O9^>Yg^gVZ9 z^@R0k`_K<&cBT$MF5lSbTu*k4qy(tc4?2OzU$h^u`~ehR=I?&IoLUkI{gws5K$s@xIYpnb@bD}m1Z^rW->q2;EMP+`?`5gqfGKlFV`R%jN zQXMr~rq&7zo}~dd4CChxvRyl;b4-c_01iCI&%A$o<$Sy;_Do&S;>3!d*LuUJ?SH|q zQyg6_FDEw>)z~!lMx<*`N1kXdue&)6Mgf!>%jc00=Xd;vHbNbs5`kOs4NVTQ>#-%J z;gL%_OJ@~&(t^b0)cu8Zx3q5>@FtE&?lEw=wxL+sSfdp4yzjtpdUwK8sMA*PPPUf% zK$ph)Z#8*ZrYpKizXLAIh7n8w;zHFKoAmW8Rzqqetm&*|q6B0SpsSs6e|gMJ*?Uec zD=*6a_HNq|Wqfv)m2U}-;V<ff{BtTfQ=z@vkBbzUoHT{YwaYgOvjQTVj#TkU z@JXb?`;|uJR%dLBp>CeO`X^p$=0A)-NuPMiulKN#SkJ!t`=#L@tyDJk?a?DU*YX!_ z?b-BMZ8w=g%uXY`F0&2oIs}FbufGN$oAr`1+GZtmY#iDjNdd#N$XO}keHa!v?R&bY zj$s?RKkcRCLcAuhQ>EAH(zQ$cXi24kWaS{m9W4=n|blXt^i~eGrjHjUev(3 zGuAdWQxL}CmtlA-IBL$}mnJc-yY))-%|GVxcO~;ub@^Gz8Jdz;uDR^2J*CqBF>S@h zWCA$OL%_18`}L7`p~{|l>W_hBQ$e24q9XukRgfpCzrtQZftdLQH>XizROz+I4Q@{T z^Gda8$^?r0?IJL##;B?nf0TP1^rmpnxK!`1$Z-&jUXde$JC`X;3325q73HJ!=e6hT zV$JS^Y{%yr=Z+`mc_4_5Fr?H%|NIBNfq{3#%iSfF68RIW4e6i^GFD#q$w2!QGo|4$ z5Nl`#htmL4YM9UWznjy)wb_?y1U(8#miF@vs%06KFikYq@nC??V)y?%+d?- zb3p(kg_%4}u(qJ65wfd3QEP8U(u7OsYb*GiIm_p5zTSNJVDCSV=?=mEyi(WDX2;4K z4`6Du%Ti)hZ)D{Hqf}UUW4eObUWgI@eRz4eQuLYDs+2A{|$q zoE2}*i2aV#LhSiTSOF$;7WYV#cDMGC+Bj|1VFh(^a$23vk_Qkfw=@~%_F~7sOd0(} z(-D&54BPTBZ+;KZlOsMLp|2W8TwTNn&@3&EujUJc=)N0z?dF!;+nAczIB1rGX_jmf zd^0MI#0)_HwC~>~Zpmq=HPtf;i`3Y(>HH3$$rX|taz)x>`dec0C+bx(^MzD2vI1W9 zH>Ne9ChiDuTsu^EKjLleH2z%Wc#v$gfyB_S!5>O?16qRd$y)xL_fG)pX0bQS`ZRP0nr_}Rt{l3XtMgd^8p^4rLo_eb=0VKsYju=PR2K*{{ zi7sM2ZhKH^ti=zTFxBslU{P{rL;uF1TF{UoF+O6WdRw9%SZspE)RxZCghfoCD~2@( z`Q~NlAxm4b7TG;WU*GJu5YylZ5y1_?0?#rK|5FFZ?11T+8!Y09>nYhy&%4y>ldCOT z3_;x}Plz1NOd%}*HoKSHI>?+O8U&@T*sv5ocpe|{c-0_xVu4QLf`SU7M~Y*`$yuyj zfT@|i8w#j{0LnJM#mLp1Xo6u=4SPKF#C6E*y8&vN6U;WH5P3+65kn#3>+_^omTvrg zmayohDPHLpy$iKWVvCmk?P8^^d|RNZ)sinM@so+ELDhz;VtI(?_@AQZ&)6I-*#z1{ zU#@TJ(;Pz!1%&KI#N!fe84DkZ?K{}mY%r*ZN4;aEWVo49Xxri|$Z2zqjabXs;w;W- zwynrg{R^*?|1dUxAmI>iB*9so9BqI^0(jXWfsH7R*SWUU8OPvX)QLM~zJp~3Rr+)3HzI9*8&IF#DHFp$ zj#g!v6!)r9zBYqO5IBN+D?QU;v7Cu&F!|!kftPOLlfp^+c4YMXFC2fOdgK680LOuB-RI3CE$_sLh7Ut4e9lLqGRIp3SKvIsWce$wS(a09^$)WB57=HB_Owfmv= z%M-N_zayV7vX9zz&V}#n@K<&4`4X&(mEZP$lx96c_l$o0!*(V+J5Es4f&ASv&KSO2 zdQF3Ont`^Wl)QHc#pT!Ay&D}!Q4N$TuJ1=<&_M*iMPy3GHGAIr`d-e! z^eKttjtfv5nU>+`=rc|05U8W|T+Ghpy4!=CdVXPT6*l>_<#6r$SMtXua{;$YfDKmO znGgHpNBIbTFIf+|UN^Yka`9-nSFi)nF*oqebRAKZ1O>XzOC)B>hpZ-98^SPN=D@b0 z_4s9|9Q%%?{F1c1Dxs6}b_`|x+S~!LpG`y2O@{fso?J@WXX8?L^0?#YW%h`R4YvkI z%uoajSItxLHZVv{uX`)thkr0V)bE(F{^-BaV z9=LbI$j*8lX}vFx5pLoC&6?4Q@Vu3_7XmNV@sLsE>1xyLS#o zkyk3`A4Ak}9`TUi|0Va4NJ+7)H)cZ};%oLSG?*;S7*`*ZI=T(@$UuyFx><=SW&%eh z>3(hL%BR00_evG~y>6;hWB$Us{AaJcafNU2^0&oTbVu#%++v(iLpSzQ_(BzT^5N84 zwdl^I@H}8YOkaJByv(2CyHdf_p4Ge`5_N~`s(Fk2VlJ}HsNp^r=1nJ5v!h8NcAtm{f5=jkauDGs14bNgA6?v-4>(*!KuRod={nx{|R`=KXg8}98Im*0MWBYlasQoS92Qf^s# zeFyJi%OZsN`i)F6Zr!|p@BgQ_`50n)1g9>=v9fbPGf6&aHD+9AsthSJ`tB8!tt0w9 z*3miezL|^0%IS>OtxlJ>rC3Jg$;zWA>akWwRYc+aC3k(d_H$eiyyzuaaGVQ4qhIWt zsE$4C_Ofl7)}OEKGEO89Q|Mj?H_b-VE7z$th9Q+GhuRC~r-v0bauWAgib7{U{=4Cv zuG`!FVqVeEka41m;_Him3OF>jC6Zm+Vg3G)~H6` zIPr)Xt$istm;OcRr+5tbIE{;{1rR}&8CrqMD92I!lpT}E0N8aX{(kri9Dfgk{j2xGC zGbZ=O_Z#&kon^jzqe1NAap%Q`VD8Y})@~KHzTZ=$cqa3! zBKv*<()qOavr+tG0@-r9YsY9I$)aV@R_&%3J!QBIY2G+!a8svq|IeV)QXX(gcI{2D zNnnKXbG|h)^rs8%x;hf~F@2rs`%c5Sn8C<$Cc#d-d)c z#Onq+Y@=@is2&}=V-(a)SQ zLGUJbxd}YIu8Lb=%Or9j#;!p_=E)<^yS!PGS0z2k*&pV1T1rNtw!(_X==Z^idUcOX zxi0Q|4)0&}7}OilDsi!1l4-E$#utuDXvL-ANwqc*JK5>)&hKKr2U)&{sA<)abG4Rh z8>_!;o6dDVlWyf`giE@#09BIVY^{%*`hKT~7;t8`@P~aTW&9Tg!LAO>EMzExctHBG z?;+@&9h3BsM%I0=FlrTQaE1mwDzrrZFT6`(QX`)&@y>^!+c)%$b&J^-;HE4QL5sO! z*pp`oO{l#@p;Oom?{&T}b*vlY?iw|LXXW+&QthHj#Zj`>2KC#jtg==kQj=AVe>m8` zl^+8w*Br`Sd*&ueCaOTh(cmwxT+$!+pz8d<+<9YFb+ZfQr(^o2;cM7{JACIql(mV{ zM>U??&-{f)p7IekZyDX_2U&AHSrMH>Oj%~n;L_2Aq)0std7*&6@U}8sh5TyvB{xmR zTS-la_Ba!QDwD(>NyY7TNBea=|I(x1U+IunLt>|O0RA!8%4np|Xw_1}Th+CeEvDHP zjLH>_8D%bYPpS1H;U-Q2R=&!vQLhtCrjqsOO1Ki&ZuzFWS7l-0A*EDBq34bNoFH=wyu z71tg9e6tloqTCM0HrR@=(q%KY+@i|jEI9Nh_8hQV5h>@!6A3JQSvY(7$e;gi&))NA z(mSJSCHjfsd<#qu<$o425oy`#rxx=Ggr+w4g;Djb_u`qn_~+r`>f{$zPh&i^AzJdO z>k@uUBnlb$O#QBIzcNcWYjbe)K*7|#AJ{zab}0MoHSvrzsem@;-O+!T1}6 zXZMbbyVq1>8gh#eTzUnn?V(O^)(s9J-^H9EUW>Pf!)s(Nq~y;SzVq@+uQ>R}N28z= z-<{j$z}bUIwunNagy#ZjNbMGeUvm`GkCB1?Z=-AJQ3hgq4&-28&E&{|erwWyAMit` z0*~aYAtiU{w3k0G*6)fQ5@@44TBh&_*Gw@VBN59&XSSg>b$XigT+$1-Y)v^lsD=kC-AnV@ob~+q;n5FIMZ|D=KO# zZAxN1%c4ergmn_RvNQpO(^y1sYy> zIZr1_CLh!myB?7F&&U9-`E4sv&H(>OJ-3?l*c!~|I1|b^&#=@PJ9f4iweqAyh~vi7 zB45@01JU@2Ygdmdo;cS964Yq4aJY-bqyYsEDh4Tr-vl=<nJ3% zQP$f#8k8PU!W?qe%(NbIQYUsK(XQhu5b`VkheHBY`P<)zv@&?~0a;ah*K;4lgb!e< zPm-*0!%;~Ta_3(994>ra7R@&9LsEVPR%@&WjruqO^oht)eh~lWX6~8GonyAsjD}|@Vg0Z@#g}>MmK_@b+MHMJSFYXld5{1b z2p7TTkHhSfR}Uo|lb0EZ9E`bUd%ZR7UO@g$f($0)DSL{Hg75fZvri1muiPsV$2UHO zJGZ$N4~;|)C-06Sf=`HO9}MXGD+V*%ug!`2*S=XAaD4})o!Ln}!{^Bws@&|F#?8RD zXjtNl<2)11w2zOC4-L{_KeKJHr?bvJo1T&2llc~2IIeHy${BT^+NWuOEBUNS z8Xpyt90#f`1q%0*Ldm*fyWjB5Wy9VE^BKJva-teI`PX^l{j&^qRb9ZpO~cmhkXTWD z!g_BgWz4kiT59%dNp|l4gSWSiYO`P3g#)yug+g1jc(LHF!HX5AxJz-jV8x4+;;uo8 zOK=D-1&RbM?$F{8pt#GIXYcoX@6)~3-s?T*tabh&e`F;$x$l|z&CE4(U6zb|d^~s+ zxNq$e=YZfyir0sp{`A;NYDVXI!%dKxwE{sNpM2@cuIoAcnzmXvA;PZa)sL8f3k8Pr9yNo z7K`U3V%n(gG5A7zGZxQ3!O#C=-UA@`KK=Hz0??rsWTIbO!DA+j4bf@VuJ`M8lW>?` z@=BUHtj3x}U?tToDU@?yRh~<1MSLLhNVbMCJsJQD9jEE1%71?^!qz2HbWMy@+Wg+$ zbEf#O%-;+>*)=Vi9ku1$=Zh?5g~fPFqeZ9r=S#M8aPAOC(MF=3jkWyo645O@))CV; zOAemvWS)`7IYWWH@=t)686ka_?~rXe34Nq;XUc4Q$ybV}*V)^)NWD#*8^S5>$Dk5- zWg8t{1DD*Jkh3VSP>02Z7&$HX!I2TgQ?9E!A;osf<9DUfCqWT;{DUZ`Lt(mCn&v7( zWzia)&KX-M&h7u6rWi$uo5I|^Vx!7-dyozT!6J_dFa;baj86l8@PDrw<5)XlFTke>l{= zv|R*CD-8F_g{`F4@$9OmNtYDqg;`y`AXdxW`Q^?8NlaPP9kUoM~l3y?l-yeWTY zD~ibVreVuuz0ET%WEl$} zT`i6wN$-$Jhpx9TXw0jc2oWuU+{(r& ztq+AQh4sAl&*BD3KK$C)zwN|*GMDd#HBy=-Fbg^~!b^qMMgq=V-H#EO9Tf`(g&#xZ z5IQj-5Y9|Cxs2T#?%PD}iW($FV@;h@$avd8i+V;xmxS9QHaw&D_-!Y0&E}Gq9cSwg z+eLvd^Y%$21|}9lBIK=kjB^bn;?=9#NW6WSrB%TyN0|IEW;ZD&I&H3#mA5%6DibbD z@yPjJpiGSvUl=;Ynz2K}Q?NEsvLdt-|Gx}U^<^UFV#pHRpKZLX)g zcZUn>ZnM6}2pI{Vgez7{FDzJU)07z4`IQMY#YyNc*~lo+>wh%@dYJ2PuK~M0vSRzZ z7Pg#^hl*|c`6dJ=&5bTLTQ{VYCM~!f7$lLagVmz7`s`m-SJoFNJKUNb#ju9c7(G5r z={r))Fr&%J?k<4o0kJHYWBDPA88dqR)GBq_JMJ$>%{@GEKie*YrxvXNhJ2ePQ5Z zUL=C%tE<%P(j|Bn@p6(Y|9gUFOA2L4MMQZeI51zYIg@dpP16c9N4ImoJ*D}(P|}bpc90MaUTxwZ}<31G>~BR$eDxIH2mj<2~P|DMs7 zs6#9~6S7$MI?UEXojk{77dvIbAx&_Bj15;&yt?$|4p<{OWR~IgRQ~c1>9rT%Krz$@ zxZdZYkJpali6-;!>4s4tLJ&gZxdyD)^A7;~-JV?cQD$8a?mX`&(>nsBf=v4AMS_LH z#Q7&I4*;57O*X9h{4k&R^`k_YFC_`4v?I@n761JWc|pPcVO*dbfv!d%yC?3TlvrLB z*PzSnA&=gg6df~vwtMQmAY89%(}yIe!!xz8AKDoo0M0#{=xkLbeEoDTI=^(~n&NBz zmbp6^okiD%z?xQe$vZ{2FO5`vUE^r+yDem2lXk6xNMUWTENlizS9WxZlt6f4L8mnh z+tRe@`ATz6^JxS0J1-s_F|xcMC`=PRV|tu6KIB5eh_DwYlQ0K=l&E7w*L%&12d@%0 z&Y^Ny8B!#?QoLIG@DD{u08;rd|0=A_ALuV+`;EHE-bi=WSEp_|J7G3%D`KnNS+<^j z!P^e;D2b^&W-3&RlipUZT=rQAW+LYL$R0G4)NEFnwsSNHz3fI+!;0+1XpNI<3+N_A zk@tj0wZ)-ruqJOH+Qxa{azB@s=X?rhcqKB6V`EG*;%7U~J^ch($E<%K~yenbpDpWr7m#SPsi z5Z4-^$a9kJm?u6&fN5f0D6$Y~Y_iQ37y6*M80*$N2tIRs|FW7ry6Hr6VewtAnFp#3 zb9%D8eo$GOex?E$JR-<5gi;Qd?(f9*D7|}z-g(`&h{f;bm0#0krPS<>RSv?Y?qtCA zKE1C_3ZpTkJYJ1+#2HXQUURtUZ&9QWeS7v>N63S+9CmVXpfBum9i!%XwpNhnw6oB_ z&P?F6F|eDuTk*>+CLv>UM8VV&G=j`6)J~N?=gsY=$nG!W_FC=Ky)vvy@2W~EmQwLcYk$cVV*Z*lMn`U0LL{PRrwQ=gCuOCxV5icHBStTRV@22dJAv#epR*Jhtb3&`VOw%x;S4Rcn@r_9`w!$S&k9q+^V0wtD zI_3B#lm)X&Z3QaZmI^vObxcyxyi|louQxLI&>TLA{r7a}XuM4Vto{~@uC})OwNQ=F z1$~&!;<#d&pizEt+;e*l)r><34P*Ti!SlD1bsvxfv^ZBh37vl(Eo;c5g_BtRkND*b zp%5Quygt6Nh^RV6Sx3|jO71xeGkRriMcz|kod${DB#g=#?jB|Eu?l5J8&TY|g_2V| z#YpI{>w{2Dxqg~$z%KHd=aUE5_lB#^G+rC&3DdOyh+B#*3#*b7^zNr)!wTMh?h+Og zJSlmlMs#?2dH8tePd9%P4Vj$UH_dgY-OMrBZk;pEolU1;7SJm$i}`XO?!d}~QTNHY zg@ls%7v9S2b+O%-MI1gvBkX9A8|C`T*9Q9({`F_LeYyxYo_sMj+vPU4iY+W7k383` zu0x@qsO5N;47}QlnM>K3Xf^tjaD|jxqfknlw!bS%VDp)rERmBK8E#Uu_&yq!V}w}7 z$G9q0?n-3VZnDQ@ayzLqHAcrphVS6bc1FZ+@!vL%0F=GpYfV`8mDwFGzYtrKUXZ>@ zGUmKcrKP4%#|9qK@=^6>WmzQ$_tE@oin0ul zc-z?B3)K)=WjV#~*%1_arS`9N_r%E=IPMwp)K!mKK}SBI5f{=&cXEsgU+;?FzZ@wW z)&5!!*N<4JXkfY>i{1)3wJF87r9Jk7n>d9jW}{jcZ^Ltqe#REC3IVwPTxosm{{VoA z-XldouX<2qcNP%R%16H`$KEuE6s5OhUeqqLC(dR@D96Fb<=C98(BSWqTSq=vgGHjL zd1{)q-wjX)$0V$gGqj>W0aQ$mZ>@Bn-=r5H2YiV&3Lw(TOVi~oz%>1An_kJ%bm6sB z>##x>dTu}U7m4beo>YyLt@>M?v7}oCDa^hbR}TP0ih*BTfR~O--?CBmeUsbF&TDMd zwx!m$4(i()f^MmSTrn@_Zd3cQE5`?u zMUHPD0B3_09Wvj%Vs6mmO;Xzu6L&>iqavfMHf|#$?iR|4s*QWn>74cvGY-t~2AeUc z>rieuy$Q0%`%fI%CzbW*>Y!|9eC^C)i>c5@J)$e)hWp|aE~?hSNN%p0z6E{rY6J7! zc4fLFAAcHu!tT|rZ)7k2{3%y8cPah&+h-d^*R_y0s}Qm#QuyF+;SVI_iwBFj@Ek&~ z^B)mr(K~CwW6Do>Io;G5oPTjtM}}6S&oA0r+O^Ej=$^2IKrE$AHWtaRrs9VoZB$rG zWa)@17{4r?l-)ipXIgF0&+ypg7bwWK$^2=}Moepm=$#9qa-5xl01RuKubM-zH-v5K zp761T_tZ8GpFpYf_`O_71*o|R{cRlLDma%{4az=Eu8N@3ln)_ zmv6%Ri|AY+ANhT^pzCWhDv*NIRzR@UP5a->K$OS4jq&xsT zKTQFg*!1k@W5MKwd5E@~#e{^pJ(fo$VJb2W)TJdEo`$JvssOzypihsq*SFT!My_~^ zoU-sZwRxWDN58WTBj0zspQ#0k_ zJuPh-4ur7fYkz-b{?QTg#dD3is(}p0n~emYDs{7)v;nTp_N4^*Xma$f-fXJ*fT=>I zq_@=O_zFf`2?nG!(1MT{=5b=~ZpoQtBa8Hdw-MRIt9{|>Tev`TG+!5u*UUqd$vZ7Wy>+fxP+013_ zkPHSk(ABSb#RTgd@qJP8c#sGjE39z7!ea;vm^Q{wfmsqy^DmU!RjRmdWO}E0 z46W7g$$eU`n5NUz&8~JR-bcnvVRwRQS;a(s05TxR-Q!t56D$_G2(YlUdr5w-Wxnhw?Az^z9dife$T07fGh zgO@Y6NRcjR=ZKDij=kxlUet!)Kwv?^0f|M#`(U&0=dz{iI6z$!x94Q)7uz9o8$XG;ey`EF9J>UxGN_ zZK^jNg}dPLADXfJ#P~FuvS-_G|BOCUY0TZ1ZIU<|hOb}DpdoF3n%Gnnz5=gwty6>c z^C>?iVI;HM@#MIFP9hqMo)GRR*}m&t+pSsV_Ux$=1d)C^>^^QYUvpGb-fU?j!yH(_ z$SY{z3&&ViWc$_NQ_bm!EhL)I9ot}xRHIk*`M%tdAezPVlK}AKt+Rbsx7rjbu_u;> z-(0WvUgzd*QEn@8s%~X-(Pa z-vK>+W>Y)Uwg(C2*_ry9p&(J}Z{ra>WTsU%tPS05es}w1@ZCu4=mQ``0x)L$ci;IB zI`@G87GnqO_(Mv!_EF#+Z6fJ^m4Om7z9>cYQnAT5Z3L{HrZo0`q~l5%viTmbG-R9f z$XtXG?v4;{zj1OG=e5MA%{F+YAhmlmO91dC;N?(}uytBXUU?{!M1;4KuSJ>u@?hzv z8u=b<;$=mB=`2}a+!fX0fLNYNM7O!pr^xKam!p?ztWLN{0TLJL?7DS)I9U*`M7X)5 zy=kr9{9s{gTpQe~sYoQL)EDyDh~f3Pre|^qGf0P9&P{l^BUE$^>({eLz#}fPt#U4? z1(EU(dS|y1tAW7*Grd9wbAs;%s&6MTXOb@Ke;YO1k`VkFHstS>MFkpN;b`}*1KCk6 z04PRRd7Ha^H)3unzm=QBcveOmq#gj0Mroq~%>MJ)ihiSaY8LAdF_J9IP!fAwoE0a>=N*2Z|px!y<*nN)}hi$4`&(POEW!oM*yJ{{0eCt zRW3hSz5p;HEI#yDE@8*R=1yyUx3AB{lD&13=bXw|9eJ6-#6}P;?Cn9FA5N0DkR<|z2*Z*k&FTeK5i z;=Ed{L^?yux?s*mYASw7sL((oTZn!@{Z{}ZYxsvA`vaDUQC?pb9{14Pf$vpOGcBwH zYiw8*iHXIlA6k8Ae6!4sG)xAi#evmhZ+X|%qj2HXzZ9AT$LT zqbWLJER~Tqc_nR&qs7To;rc`B^Xm;|W^iggqaW!Of8Pd*(Z^pY3{>SgGhDN7=22h? z)!h9GxAt$5?PcSr?9(Ci3I&=UK4c5onOMfAayw%sCa3|yiMNh;_kh|r)ca)%xO|ZsSKU0=J&@`T+Rbo`eb) zq1l5+66!GVy~KB+(EP0SX3jQF;WL3GslXDY!J72U3!!WE`uC}WZW>g=i``PJjDfcl4Mv!|_7M4*piijhOZWz%4o%@I&-$>PF1Y|0)%=>8|90ZSODb`Dr#C0P=m9 zNcvs&wb6CY`VXWjJ_5ZOop-@lkM0c1>EUdsubwO4H=i(+SzfQxpU9S*5*ZGxOpLT< z5|UR>CM`>+70CK+)SZ3w`7pQ_fJ*cgJe@XG`@CoykH2}c&fI*1lVyUBGs1+mkeNQ8`gdN@U#u>u{L|O+nl`ir`iOLI;_k4<<~^Fc&m;NEtOw-z9}AdN zKIN3Xpif!{txoic&g}0C>sB=AZW8|zL(RSQucUF(D z=u(&ytAZaE&m5+t_OgdVK_59%?u53A*w=eIrBGzLjo&-fTW@_kZ#fW@h8{ks&4rGx zdoi|_M(3zsy7dyj5R2nh6t5VjjMNaNNEAGLbw76no%7$m-?(a`K`CjsIV-vrExdP- z4v6_9K4{%RP6YR5?qmI(Sze=w{qy1dufJMI0(Z3s!1iAh78&pH?{ROQ9kV?EShEok zncu7c7!QDod*5cZYpUB3AJlIEz>vtBsr24}o9y-N^vzJ&`0Ss;{B@@x(m6)u?GWuj ztqdX^52vxcl=%098GZ0%j+2Bf&;tP5=MDGaV-Li%Jq?JjSX2!LSmu@yr177O~mcgFr@9D&?z z`^Cl+mmg|lWt)@*L?u(imW05BmhOq|`-zubt-6i=TpOqsvhmt^M2i8}X^UO!s3zR_1u zl~*CPm1&f5XQbD9+_j^QkI%934Q#KnOCLA6ni5`1gS~CZY%JxoW0UC2q2+ zE=Dh2MF>cpgN@%c#hi5SKjtM9OvswP9v-Ai11BW(zsd{r3}Lu!2%e)9zXs&oj~CFs zS{JmbidPFC{gAaw6SUIC^R@+Yvd~+iZ@G3es)ePCgc_BUpmE|#1K** zIIlsyhavl@&R#*~Gt8g&_lyEW zsZhufw9fYC`TcnyaaRT(9h-V+P*zpL0lB{+BP-lAu2cf#BB6Wx+FKZ3r%}WtO+I6* zmj+yk?N1khbWt?;-rn~Sx8y6sKKxhDj6D|G(svy=QQhv+iSol+uD3QOqBD_WdBXAb zk%Z)r@uDp=9sqY#$hAVk)4%5x$RII@gsduujj$g8haHCDov9|hK*k$igmSvsp(8;&s_tO=X_H3$Jcn&z&^e29 zVok+!m*VUMc4T3N^x?lB(P##@H?BsfQdb$5sC{=Or!&aocl-e`%?1qkkC+Mm=)Q83 zzvaEveYICVnu*U1xahRyD&sp^!My`CyAB>Z@FL7R6+K%Hpt5UF^n$ zACujL&a;il)82u`BOLjAIo39^TWX-6+m|7-X*8iPR^b8AegERp{|%N9^3x<}b~gPj z*>7#bSW+t2>Pchj(7v2dNcg%`)HQW<*Ljk4>(@dX`_YGw|0G?X0yqh6-DpxSjVv-U#pyXK{-$!k0oRgt10DdRYAvrRXPhX4kJL=?T^XuFWjz^)q}P*!qp{zkFSKWXoy8 z+>D?%DU4?T>ZkVdI;o}*jUWl0)j^`>w&iiPEJ|lf*Gay%ui*MNT{^?8Q;)432`(q@ z#7cBz%AedF+hwK+dCn>-Bwn#?9C`wb-s9I+TKs}$?9|ZNagN2Z$Jrws);EDhu!!(z zo6O#}4bt{lpHeJhKDyB3Oo>Efdm;3V$U7dx5)zz+Xzj}rEQEUR<-B@l`BH`w|o0QG<*e8Wo(CO^$ zd&pH2F{Ui z>=eX({L|HjSv4Y3gP%3Ft!4YHI2q|YTeOpzI-DZJ`3-8pO)CHBB}o4Ny@Xc;Im^ZS zY1YM3ZdrZPHO_cZ;Hq(Ze=XfcX9%T%Ck_1%oc?ZuA=hy zY@uClPxUR|hycsx{lM+ye9jUrwrS;Hcex1T%H^corg-jzbQbClu-F*4O4f^QLJn4A z$DwdFqFo1!Up!x2z@bC>A);$2;ovsY`|9JHP;PzQU zCgoPxHFrA~^vE2q*3Z(ngkt=~0c{?@>c3+1f4v~zeE`__-%&gOPQp<;y8J(gAdAh7 zi92U-BNnn0J^Ner`B$~bmzjS#cM8b^vw)Sw24&PfSY(u!pS3E!+ADaq7V{jrA9t=WGf9Gyl_3C&4M^v%P^9Sdyl^Zs~D- zuZzgeqxoTduY092Ofn6d<7aEnBxwxT99_SaKTE{pB{!!gd<~M%K<^r>a21D@^tRsN zN(DlDb@jQbC4ZDgmP8UQ;ssXrH-4`pp-(lU<8E`lHEB{&_sNaI{_JCy@cr=7I4a(< z?Y0@hiKQ8vJXBaa7S>>^8{RQFyYw2=M2DQQSz$kn$pyAre`jJY!0RfZ-cYm9qUh@6 z^ndC*%->$%TuB*|m$&PzJIr_fxhk&i%abIV1rU%I-s^r!ELIZ}?nru=!c8MQZv-v` zw;%V325)lI;CLdRB=SJu(-@scOYrydmrT>eRPGh8?lxoYaj$Jp#v4%&9gH#z74N<>`#1N=|CN}sWEc2h zE7;dtS^E|U>W#6N>i3mxh-DQ1^wu;Pm)cc?x{fZJxXZ3BX$W8HqJWKDf&1F*t ziH>bqf^t3aW@?_}PU?4SECfI$;w|O#V1&$klCD4}u}8uXQ*316GDW_p!OqekEYc=8 zA)!^Tq7_!FJ90;lZ5A8;R+d)1#$EEVl#FBDBqg)KsriY8n=WIduE0F%PN zzIn?WGR0ZTdNRER{hhGMypy){{gfIA_C)(?oa@NY;ogr6m-g#5tTDA7EH@;hG)s~H zA>Dm7DJ{YkRd}wgqoQ8eg*O3(#)h(}o*>`xLw!mq2)jJhz;DG?jlyn=90`RSRDJY{ zW^CRlE7jo^co#2%cSN!_kouL2OU{wR4|kn_z+OXXEMzs>zId1MEU;ytdIJ$O{N)EE zCUkbWxVY=BW50Agf78Bbei`c|PuoD0`k*9y?WWDl#dyZ(Zgt+{0f6d{c-3XtAjT-_ z;)W$(04lQBvEgLNGpp2K%3zuvZ9$KN4Vgy^-(k$c1$@d&KTVD9m6_~=v2{6|1F7;% zf$hHI`VC!QsdZoI4lfFXJpkSt!InH^h(*w(c6Trg{O558w0d}>P^%3NbgW_PjO}0r{l+rE4Hxr>UPTjRQ~sf+G-Pu8AaT$>={H`DJ&nqcI8-Y30DRA! z+V3;swp%Od(AF}hhf{!F25vlm5HeLbr2@3Jnl)bY5&IPPBBLZ%(xUNaY{Vz`#UYyI zA)n8%WJt544p~aeo)@9^IU&E}Mf!XX^;9M$ld$o{qimVJnVi?NZWY}#;ewh~v(*e0 z%~%E>`AWj^UShU_4qv{h7%)sM}nkXsA(EdOGiWl)EjMv&e=&<9vW< z_>A##r(+;QjgGQk0{1wSVltb9uX25KE6Ve607}aJs8M=5*#qF0|1bq4@hcAcU8d+& zfdBPGz@JA4GT!|62OoK`$ki-()moRJG}HsDsL8#za6sZwL?!t+shl?y(C6{vpgG-+ z4;Ar|hjHOq#AGF0Ay^w2K0njwW!VKp6hjUwed`YH8fwVZ(zPLP#r0;bwP%5YI%)ME zDBo1@ENA8_Hn}HAFH=bgE`Bv4o#V9Ni--@6_&<6GaR$qSV!S6bK` zr+){RXYT6Ijd0`QJbPWN>B5C$1B*7x4RIK2KG1~wNG5=eRoAJM|IT-S#&RH%*c+B? z&w<}iSsxv}5zT$EImPofJ2-Qy;oKYDab%_RELG98uRh9`_&nLx3p>Tq%Mb3Zt-{%; zB6(XVM~qeJA%Bg{I$7Ra`PN_ys)sR3_Siv`%bo<=4sU{fYTx;HN3-&~su`RDS#(P= zD7%!84? zm9jU#rplu0Vgm2@6Sqp&2my&!p%^KA_BvHbvwEzcf*8D6l)HVy;EUZ55LSt4Gd79I z5W@?6tzm7x zMDw!fU^Y=aGbU#ieMu{kNOHaB`MdS5*H=9@7G}x!0+vJ1q;yYesU{Q-Cs=1d`VGhQ zNfP{BC{8d6r5bRlTSQc*_BKtu-1T{KeV5E_+;~5kU>B@$VgZ-)6|vRF<6OhxVF)7;Jdmu+;Mu7<<9Y8N`B;I_rV zN(rtL1EV+t+1;J0BX}HQmN5Jkb%B}du&3$w3sdg*hUcCRayL3Qy&VnOz~48jaEkp4)|e&uWDjPC}zsW6fJTLD_`*s@Y*m~s#L0iAVLmH<4<^HO3mIEvZB)dk!lklQRqwxn<=jHNuc z#q#*eFd%rnpkFfU??fh#G+e5V4ST9!4R++7u;p?)9m(FB+QmjTpSeBewXfzBN^h%d zdHBAr$nu$E^3ZRrNq(uowcF_`Eeb5o8IDcz{kQZfC^+z87n-RbH&m7xW#bE2vc*hP zDRUy|%fAmot2N@j*z05q7fc6gI!$Qwo}E9da!a~x;pB8sk5r(_!oZpN4@@jno=qd~ zf|@?|1|v1cMY=9l-MbGD*aG>!`wp($h`WU86p7$*|BxBJIWm!R-Z26l-|Ng7vV|!4 zFcwAP^!=wV*5#g|vbhSJbt?ktz!tAQ=uZ!Vq<{J%Nk3TJ5XB9nZ!l?5zUD2j;xEkd z$}`UN9b+&Kqop=+%C6_I{6RQFo_8NQwv5Zf+Pnak4`l#(%^x!|+)$iG54gdaJ(ZAIl3{!hn4yac&uQ)9- z)<(7U@#)kZRmy8KojgCz!5@^Bv9_l<5O`a!p-^~i3v{{c>GdHeHAe5v*~@aCiW_$( z?o+gj0^{N`GdyOeLF` zGs`mRRgm|^j3)Kqi|Xh+BlqmqIkx$Z+$k@!R*R$*XX%Kvm!oP`NQfhYMV8eJYgVJf zSi5HDv<7#$X(CNj?THqWsdemb@We$1P0eQtp?vDEc)J*df-eQ03U5lAJ`+h?hI#6= zRD5fVZzFp(;_|BMSdZ%D!z|aH$&wD}+TG_!MtN@WSBXKJd$W~iut2F1hMz_C(>58NC~$qHA#-tB>R{J-gil0KKPg9Yqu|EK^QAVc$HsSN^G%`2ypPv+P*ubVZ-@qWMV} zwP$kB2ZBL8#IQHH5wXMvnd0V(S1vVKoaUVas>V&&e*e-Y`&|zlFWT)*+H&8p`#49lT`9#| z=Piid=C_Yv&ll1#)Xpex)7j)$Ox!c2<0SH~I?YSx!kd3rQS;eQ{jD&Zj3%?{SUhi@zo1GTlc4R0*k*iyw zMSsI(r9W5W`P$RRU6Z~7@R5>fR$e#LukmwChX^Z| zBVF@OKUybs+o&ec8XH$D)#B1?WD!NBI3m&aZ#``Co9#7@`K2U27yaShFZsmwyfxR# zx^4GKe}COk-dr-O{+Onm@tX&iNx?Svd@Xf0#@}Q4OL8&K1;V08-#)NTYC)6Hxy)8v6ud$&0lPsmzCV3SV zHcd{Md;|GYJYVVwL4(LDLgEjqt72bMk2%5U_H$|(LVqbOgjesrBdn9*D;swr>-nX9 zOz!AgC>tg0+Qc-Wc?pEP4#L?+CIf>3+e!_1Cls_r=50n&&Ei z$LpDudeb(Q^CV6LvUFW@?=0YJ=8Z%m*z+-CcBPoigsAp0y;Z4LGMpxWdoN zL;v6>nE@4dUPt-$SzvBId>Zg5aPV zh7S;ocTZX6h#th>k7_%~gkoCj+ znU@lP-;v`5Dr$+1hxhscr=WU-;w(XXS7zF0lCn3%&?w2QwZx&+Et)#!1Xz(Vo zjH{tcL#L(@uFjwi|KbSGFnz)rnF9@KOwte3?=j20vAwf~NcIk=pKS0sli#V<-PKAGhq9l-K zEzt=vI{yGgx4z}R`wJ9JLoxrRb)Rz8T;cbF6mm1M^OXSb*#D14FVh|0{fOwTm>?2Q zcC7kiQ3i7&`FBqylne$Z~mNpkRW0a`CI= zq|viIh1~Rkv`2|rq?CCsY53Y-8U+|q@1MV(Rk&gmWyQ=sG-IawbH%F%F$|j^A>pHUE?GA zFu?DU7-YRKT&5N!MRTYhCpqPAj+L=S1LO!Yqp|<{jw$wk@AfbQFly1dg%mY3+@Pc% z2YGrjauYllznvTuglcrVDwyU5?!KGUOH)_nsEtpYgCnuc&VZLbc#rV)QmCO*soLrL zeiUs9rnu;jNk^#2S>i<|f1@(5KCh03Yu{gyu zY=DJ@^<$n_*HBM-zqr4+co_E9pO%j1K1gIL(#M;icDLE<3Q-`JE{h}|%Kh9aAGyW< z4U?g@Leq-{kbu|yEzdl$!}^*=uSG~9c#qWi+;1t*){=Admq}6S?+y8v1G9O#d`ePT z8X8n7jEPMnV&IPdL}(Iy=F^~QCoq|Dy`Y@6I!aN^dq#p4zeN_kU0P7aJ3OPCL!G2N z^~J1Ifl`&JwrF+hX{Jw65XIxpAso8Sk)msJbkA80;1YzaT@_l9tF~6N?e$_5 z|LLkRygm&Yh=E1BYdz&`T1CpLGkg*j^)2D(p%S{<^ByK$CfX4BDJ2(hH?2KaSHbEU zX4-SQ1YGo^0UV0|cvXQY5^$9rna2AD-D<1|Jg5$;e0qE5o;qVCwS`%(x*;#GobJby zCl%~{7$5Krn+5#%B9dPGJPaty=$IrOdofJ<`xV<5F)OPko7Aq%4nLf%LClnr>`m_{ zBfGPpb0xcHAd53dVq|&=y=o>`3N0@OQgN7eSw1_kZkK@x%fbfOW0bnQqfGx5gr|UKDhf!XfXUA(@ z{Fjk?yCm#b!{-Q`Umn@T?b`DsWy$>W*eNl+=M2xtXS)TVygI#52CL8TxN>vzNm$KU zf3zp5&!fuCS7Wz5aIUq@t5^St5=O3m_gfoU^v z427SK96=TTVjl{$$fB4LZ?Xz)I^*u&&*QkFOPvpb>bMjv z;g;V!k22PJ*)GLo{Qr|(`H=4V7aIECa@!f{z4?Da&l7$29O*xIiqLb_8|AEDGqYX? zNgs7-$(?6^<3wmK=tgF%g6Kkbd$(L6xc%l-C5aR8Ln9Jeu?`!ky7^Wb%6%U|3>szxO0|R(d617-Gf>b^ShAYp74xXj5-0G3 z!c7TL9smN(Ccuso>Y}0z>YO*fJYtv!h7<`Cx(2`MItKTcdRfCx)-hl8Fds&Ym! zm-MGwrvQ1Kkw`nppkT_U6`^CNIgDiU;&)jMb9me0%7@*m;Wne$@g`j+H{P9^zO=O1 z4zGZfE5TCaIUoy08E&sp7ODTUhqt}(bs?*Bd}>pLG*UI$`HCy@=c7P0(f=Lz7#UR6 zhhf!co3%T>lx)?%>)QPB9sp9OWndz~wp{EI@?)`?do}Q9Eb>tiSgtQYdpqGyCOyjb8LP=QUuNUL^aJgRaJTf9 zeyTtg-4}(7#u4XV-<~;=`e$ojYbLRbS=qKsm#f}q+Q4lhci`CA>qkUm71pz(KFniTWWWlC&<=% zp2_tb;Q!EwpC0$IOgZuGJIb+6Z1u^mR68HX6Cp!t*y@SqXGdm*xO#yS@s{otmc*0D zOi|opl1rnXD3rH<_ZU*_>6Bdq18BX{kjUr{uJ1GIBvE^Zl3P(>IM%t7wl%zHlF3@a z?-;&x%dCp_|LWD_?*fU&tS26NreQZg3#n|c;|09@R0VLb2|bU8%DxY^OpjHoa5&$+ zEy@&)Pl)p>Wu9d>o1&(#8OR7LOmji1-S@hnCCwXX4UWK)d+ZkSU8zG^>66z<8YG+$ zJz55Cw#P^v1qM13&hXOG&z*9rYam|m&u`BVs;>*Dbo+Zoo~zmJen6tZL<|w>>kiHt zmJ|v6BLJBi|lc_Yy^Cy6VADWoQ+#tzb*{S@;XY6qet z+acoqO9xjrvcQ3Gj=_9(5x&-CTW4qbNF1QPQZ0e6^l^+a1UPdp%!NWogim2Kcis1# z{e*;Ppn^ch(vSiSRDGF+OG5bo_|u}MBSu;%v_L)=I_+x)?#GIy&&@K&Je%EfH{T{` zJcn91rUdNFo*BR#N{-DY)PR&&8C%HPi7NLmVOGSo2RGl2gEJQQ<{hNyO%Zig_ptbo z%hItD&;+PhQZ3MRuvR(vfeZTaH+G$uZM->V8O~B093ZU z!da{QKQcv%*n!YndQULL+~96|e0 zXuZEsLG{9DrU6?u=UefaH9jRnMwC7DJNerIE2>{tYsS|}5nRFsKzQQrdKM@=4N1)L zxGz9pB`8z*bP$eD#f9=O9a>7dhI~1}L(DAG8YX$UhWM=Y}^?Gr^)&n!j~Q zCruQrfS8`9R+LzErs)g2l1;`(T~CG&`lk@uc7Mq;Jgs(q4!=kI6ZuBP~^uTwjNe!KoT`RZ0k9(a8|hAMhi2@>95GxDFjYke(|g}BZPnY zy%VfB+Ng4dauspNzO*wpHuf?$Zl5ZbDsMiaJ>IUDmnV>(%VfCOyi-k<3NM&d=yfmq ze_Cz&V+24O@XBy}s&TF{w<2VBrxFO;7}Fbe?~#^^URB0%puaHi+ew&iK~3@ra3k17 zy}amUYYcDFVthwc(5avnO1Eiia<|uvw!X#eRTmK1z*{S?cbsBMU(mkbozb>C+ykzi zJ1{HGW20n^j2d4?k7!+=h?NRPZ z;*BT{e05~zkgIs;0p-_c#$0;AsTcjNVe(>gedcnGSEj}6%%PSf*9^M9xw@UW)Av`r*d8@{CX=6Fr_RFo~>JqDG~7- zFqGF!kY~Z!oN@7YNbwZmOkxmIWmJq>5mNr;k%ao)vG6X@9SN2lt@MVz|0Neh|7DGX zIy_TraNC?~__@gjS8TJAq=L_XS20!Z)gs&Ym>ASWR13@Zn#aW=Wl5Q1OiFJ!QzV8q)& z_V7CVN;B1K-b_H9g(t0!2-u7ZTVWl{Yt6+WiGCputXqSwI-Wmva#-1seF_d=;eUVG zEg!M@%e43FcmLm7RsNlc)2}U}KC?>V;`1q+nj015Q6vD3SWXx#q~_5Lv&+T02%%J& z8EHL#(K~!ZgK!8V*23Jldmd(s9vboOz19uQdH%Q|a+KtMqG&fK{biVj{~8NJ3t5*5 z?rW=g7=EF>V}yJECkn{01`Ub8O8i}%4_PGr7eFp@srTi;ipwRSY*uLG*vy~tYsP{_ zPa>Uy3^{$>+JW% z8Mv6irvU(7O+d}+Dl^Py@U_dD+*ntLao9#4l%m=+tBDw@SG-~qO|KzTL^x~skWpQQ z{RJ}4rVM9Ia*@#RTlg(V`^)cTV6s0CJw&qoW=)b_n&0x>g0xVyQHbn2D14$D0J%}M zMac%mT6rF~7CXG(M)>M+Q>UNNNXl|MQZP>ff1>zijtdgDH>~s;dHVx|OeIMc26a3=!TDgx_{bD@x`q#>h)Ff0QcWYuYa<`qcA&OD31o3%Zec z%(%nuq9q5Fk>`lFsPQY_K6t{0i7U5opS`MGIoyo#-INCCuy_Nc? zp==Er&m-f?24Plt_TdzmCD3>V{`WJOe?x}o(Z8?z@{7z0hS?)YAmu6NNMX6-wkcah zlDYUyR#xZ~mGq&Dx@K^jRQGT%J=BJhBQ|Gdf=*o>4IuAZ!-UkuW$g1c`&Dv*PSn51 zsJ3P*DZOx>-}rgTVZR971d|YdhRx$DRs2AB&K*Fr-fp&fa#qtu?#&iUqgA1u@yg71 z3eur_DoZb1>&KD+qi>388-=GS9Nx?eqOEmzR}@un>nb}y7RtJQ1Yy?#$KB!M1f~Q= zjoe}?GsAwZIDVd$@k=+XtmRsOP+J3wxTTS)KFfMxsnVw@P_&lC>kA|8RHBbkrVdx_ zPmA$Hg6M~EiW*t$Q`}zZt)L*IP7xV+;XhFx<4yiVncx3)Iw-%nxyyZLfs5qMh`hHf zPcf*v&0tH1_3*yGjt}iW&i8m*Zsg23FgrfX3ejJn4*RAd-P0w(@IvOzlbg`k8t2_2 z5r^-yeHfGc4DHw{DP2euIv%lSPN{RFt_E*8s}r|!`MEied=@_$(e-)FG8QoJ1tP&B z$aT>C9M>f4lSlaSeWNOO^c`3K{hfX%h5(oa!$I?W3u{HSs~j%nISY%8Q$)z;=$Q+T zySDO{7>Ld`=G948{!25+VKgsz$7!T5Oe1{lvhh*=U%BIcf2Jc3k8v-gj5Qa^rYBvZ ztwj5qh`H2>>+CFMc0H-_o-+<8+B%FV(xHW3GZJnAObqHHK38={N{)oan~m-VyMB;4 zyuMdQXMVGvIBe;K4&JI7i}g$v8I-0UMy%*}^Z_$`=D1suB|Nwxe=1@*q-NfRO^A z$V)+(s}PtUVwCaBhiqgLL~tNHqrj)Wl%$KocR#>h|w=%=??~WlGU05xA2Sj1zJ!xuMp`Me$gbO`2 zs`Iy~6og$5!5idVwLFc2!KYptp3o*Y1uApwoFG%ADvk;1&?_CoKWe`}NH04a^?YtP z>LNm6Nvx85FIA^WygEU)2p?&oXcuB`GA~ElwegW2tYY!QU%#LML|gpPD2TH4KA7dx zpMlx^E9NC4gUN&Gtr9ezNbfwZP_rnRu~XVVu)>mJaLAE^Z7{3fwJMJEFd)0a4Y60x zn*LCZt5Qvwf$95zeu3TYFS9Wo_X*$F^_*C(X~N7L=OE5ED@$FC33eO*wyB&&ap+*D z)YS2A*Rarzp0IYK)RU<$eE?AVBJizK@W&j7EdkWoe??aN=Qu<`<`@4$Q>L`0hUB`a zV{^oj7;n#gWmC+Bv8aqxC6V8n$3PyHoZqhNNpdiWjpytR(r@IDYK%LqN@OSIBH{oT zk@6uZ`>lW6iNUknzj&j1P8}K8U~oEFS6p?@en4&?3PB3^0?OH_N9MS$sC*cg|~|LuQI3KbEkg+IR2}V|2=s^ez#wc_P?c* ze|X(%`?ZDNN!n=d_Lmcvt)x#s-UM2F`KL5qCYET5=BehO%Fkjd%G8xvjamV6hL1j? z(*BYr(J(d{FFh9S$SgZ&Xw#T41{|o@aRwI3Pn_R+3sVS}mtHI3iF}GkSxn{>J(b_S zjXPnZ3$WnukC5ond)VG-EJ! z6+Z9l1H3UH6SgEQrf8BO-(=oPw@^;IePPQr+jy};rF!eUjgXfqrw*o30p!z?kY1ttd_%k+BKF1 ze**+6fkj!X^Fz*VpC|BM*}Cv-kie(3VCY%lP-MvBJUC97L6w^VmEfB3xMwjt{VuO| zdV2*u%a+}HPVgtnE(GKghT`#Oe}}jGDZiGn#Gd<`_U@u%8Ay9H$o8$Hc#ftO9+O@> zwW_uRqh@)xbRlzyP;|J$MDYf~#yl7yLc&_O{vhO+V(pjTuHo>t?QP1t%l9tjcgse< zu=gImTV6h6yLkl(zuLI3=(Tnhe}JlgJ0+NN{||d=hBMYK@IEmOX?c<2%4YK%2Aq$< zUQweeGojBpPKR3=gzHY>y9svSAJhu17s+VIeVUN;)!tXhQX~z@J$qf}(7Pl@3FWLS zi78&TxLHiHTAgd9U3PkzbBN=aEZ-!2Ab+(Rtb2*MIvkpg9%R(u?fFS?V=1FkBu^`G z%X>N?PkWYC+c6bl+Ciom6W?6b&)I9YUKlUJpdckyWa@!2r&t|?_o5yJ$ zxLc%;&~(aFe_iVnbsJmPz2D6>-X1b`kE}oUd1y$=*LM3W$M-bn48tv{);<={1Z1U{-5*~(7%1H?HffiX==;?|1y9l8vj+?sJ4XwrUctu0;a*Pf1N zd#GEZ6$$}vLGq;4aDytNj==y8E-a(dAIJNKFxyvN*@$o*qep*CLjJ4)&HwpH=wn-? z6ddOAYR}4urYG6x%ucZ7wCI<<$jV5tJTpm%l+5m_bx+3i?)0s7NmGmq*Ut^vYX69& zbYU1O9kL#_l+EwP!2-@rdEuT;<0p}yxKEvZ`6jGCX4jPlp{a3tG!^A$m}Qw|m?n!@ z?Ig#}H`p}di6`WBzmi+}BX;wFt>xT{WG0B?18dDf7>qq)(2tNY#*5OT&=w>R1KxSm0^@L3Do-xv0Kyx2} zs?j7>tqwQJhsUX&?9kSEQF8*HRT-{aqG)IQ7VAXAWhAPf_^oG4$Y9n*XFyJeVj-2n zjJY;hpZ<9h7ZcK*m2OK^9E4hYcej$UQNxeMFOP2Ux0Z(L+IZiE)LlY`k^%>nS?L|t z%m;noi+xabKE2ME$wBj>Gn2)K-7mnm=hA}TkqD`W!N}H7m7M+4t@dQ}Kx*O%7raN6 zjWGN^Dq$o8(mvCyc)IkY>N%gg+wri|1DrLCKFxh=;{NAkyiS4PF_SW%Sc2b2Hva=e z*xwb)=sfps-Yy9df3l4mqoB~8WYsly)?6MoU~+1jIxOMWYZL2#C4r=02t$k%sm!0$ z$V!G)m8x1r>aFByVKFD-5hoyr56ub6wA;7)$Rf&K$6~vQ->PN&l;ldNF*Knb)QFV+ zy6P)7E}IDhIwzF&S2t+MW{9(Dl@QzdUa6U*@aq3|xltZEFBT(kqkFZFB3Vebi^;Lb zfEa0B=m@+tZb|8GK@sP$6+cew5DLL=$E%mCU*1t(ZwbV17f7Qk!ccqi2m zlpbW?cPnN7Bw8irv%swO*+5ttkbu4K#FPLaV?x5ni4;YA$&8u&3o3GTwS2URF5kH% z)TXkI{Ohz6QYYDzi{EkdCSCUnZ)Ez6NN+Q}s`)t|Rw2%=F|g+TS%g{8u8=CRe1XQX zga(&*$wC3h#04+58OWDgZB|hv(pFp1t!`R70sd-5EChpQgB3uLp3_HRvxq%gdWU+a zYG1N9$$j87t|02IKbjh$Zp9nlj(glk(6D>JQGPLMqW*WCtNyN&?y)V!b2L`g#H~%& z-l;4F4jb|rbmYBZp|e7Ck8Z@*XymTaDcyE}o+32JV%OJ9)noZ^)Z84A@)6&`jCh%0 z(FvPApFjHt$D}00j(XY%F%skPoeoSiC+|M|P>s>x=GJ|flWR&(#VV0pXA>1%R@g7m zYm!Xb>*4dq=hv@BtQ*W1QhL}qhQnW`&OI>%4xYw{2L^X1&wF%p$O6j)JY>2bohvft zO#$!7;`>vH^K>M}zmv{%^Mt$)aJhfdZ$)E~WS<9J6-};L-nqsJ;LeI1C!r`8bNnV) zX#vz*HKj7=YuVr2*D^_hS;jj$awF1|Vr0o}g7m~GLWx|6fm?B{WV z9BM)=bakyvurEbyae~C|A;oi$we$Qh$YJ5RL#{B)Y3`m<75_x3pZO=A{9nck$(Fyk zmAe}uU%zul88;MYF}-=E_0l=a5_Qgiw=8*f42PjkGk3}pOOqvObkxB$h)Q?%83i@M zLC~)2=xUx|76^2s>+TQoHL&LC88KiN@w;#cS=% z_G-8fhCHSee7mi7G^&g*abqU9yu|J!E13Bd@E@bNOeB1dhORkT&G6NPY>0LF)l^9P zzAALKypf|d;JDGfR?0@uZs_K$R{MoXs(`pt0$74WRv1}6yCvf&+ij~=9`Aypt72{7YTmIhV&VToLcy+N^ zr*UqoCTQwpn}YjB`=q)QV?hGPy5?s1J1fYP)LUUKe*W_XEOHjc>E?nX4k~0<~CP z6sm#V7%j03hWKf$N4meBW3t&xa7XlGxwWdIlk4fR2mTNzL>!H))fiKB2_iQ)e}mkB z(UV8{E<@ogtGU|=+C3or|8s(i1g*iV*{==|CZkd1ND*LS3k zG^e4W9>k~j#e5t{ABm+FkIWVBeSY`v*2}JVzQ3qTU@7W~;s`;w^bpY97sY0rWs0nR zT(v(H9upj4QK=N1$Bm=U9MzXj#xgD@pW?=SpFOSTU^-b^^~67GVOjx-`{bM7l;3W! zhKamqTJrk=${Z2A+E2mGFS=5rRCS9V{5XCsBO^H|OU}ZgJMW@nPh(vA5D7iGI7P!Z zaoOxS&(G^Xunz^!&h2&?s)Qa#syWh6I}KV`&S-Ii)%%IE!Da+d<5V7D^@p@@^tS)D z8RPGoX8x{|?r-$&4}GejJqT#q>;aOg#XcBMUB2Nlcs2FpLMseNQ}H&(yuLQ*OO2pB zLaDvqPQvZo6a3a!`NDp0qB=Tk`RW3$HyiX)(3X>yu*G#;)3wz{)e>2TRq<9h&Ju{sxrC}j?I%=Fsq5vjsP-Tb~<5th}ibu|+XgZ?d^W}iB>@94`#g6_BrQGV0}K^ZqH$Rpz2x52{nS+$y&R~x<&5y44OylQH-b^BFoVqLn} z1=FVAwsGjY4+g^zlokE^by5kcYbS$RGbs?XIh(R&J4qws6=mSw{1`T=-T}s$E+I3Q zJS@q$NALcmVdww(dg<@VX8$2ha;Tod%b3NP`jj`i=3a+;mC7AIOCi*!(rhg>U@2FG zXKFE57gTxzY)J!gQ^`z^*X7Pg6__0wbo3M8(H;|-#AQ6!QzHTGk-5BxA}5GHzhB5N zT-C^Ub!J`*pwe+-Iy?XJLCH+Ypp$lp`htCP-Xq#$XNUTLG$1h~J`oyI^o392_qq0g zd{b?4XkmE{+bDi0WSY5=nWC(|R>atyu@)37m1t_2J=kXSF@SR;Lp?oM64Qmb(aK%M zbg{C(FS2j&efC^OUjv|Qdq!BOA(TzRmety)zWiL7aXGc^98516H_e;&>S3JRg2ZG^I@Uvq6 zQY3u1<-&Sb2MYl>!*sJJQXM71s#&Q1Oql*Q`+@nU2kmY*ACZ>(M`lN;0`{(4Wyh7Zl0(BC>FBnlgQO-C#^Ee^;X_w&Z*%$u4-3aQ6-4vGR+;jKvO8kPG zw;Z?7>|#A?+VglqOsHiGxmLcf3-)^d4Ih(t44c*t`so5yP9%Pt?V;<=`9Nez8AHtt zL)`|t%6*9$-fM^^B1U;Bg4DdHnf@F03NQTy1;+cv=6+Cyd9#ND{YP~!f=i-S%ss8l_7EJc%Os^=e zBBD6ZY;rDw6XEx39@te*VF=;?Kup$E$E?7nJSCjjxd%Y@gv5TUhv~H}-^odViB^;@$6)nSfK|U>J`7amtZ{4^-=ne#@M0WtxS#WvhcD{D0*lkFKPaML*{XKF zR8zYkPOTo|A6D_Y_ifdVuyuT-TInLUo!QU`Z6WyUkh+GypyNjpvM=I+4u=)CQL9M( z7mFbGmyu@UB_5eMo*Kixgr$ky^$UeBzsvnv7H*|A_n6$sA ze)X3Ccrx^LB54c4A1HSPG~qpl?O0-!`V*zU(Jyqc!AMeK*sf1NS9K-l9ouH`8#;e> z!Xzc%p-{MHF3@ZDU{lm4amZoTgM?9x>!Z=F{bWA@X-6>Ij|UTrOo}3x@MLQIb+SG? zwVxOE$RlD!%RQ@a~>L2Cy{2LK;Wg|!@jf9tT*n8dwOFZd;O%z!# zB3k&Vo~%bTs;*)8LvHh{I8Fmi$pqDVtm9SpJmVRdB9BDgxMhN$NHXpq*Z7RS7>p9C zlK4ctk+R$?fjLp&c9|s0hz2CX&;%(hO^Uklm#g(pN7Tm#yk>1PnsFqu>&r7b*%?H| z_0idfRBa^=Irw7?al+^ae6_oI-CCp(&tquAqI5Kn#Z)XPa@xluZ|M^X$VWxjER+5A zIq1xan!D{j{&8CosT(bYYH$>z;GelOm>n?i(kkV*2@OXHw9|3K}nZeX|GE-)lV< z*wkASD`s*@J6?aSQWoe4r$^*WL)$-U97EmuSu-)iA0c}2@Dp2V0(ufOo67kai(0jx zfZZ7~3X}1&EfVAe`LKebu)1HvTRoC#S-nVDHxiW5hPYBL9qwm&R-SEG&oSxBEVG0F zcu(!~o^C&~er#Ph&47`!m>G&0GjPuA7no_^kRvXzYu-l+EKp&=n&J0UI*P;}>Q@$If z*r}yBp^A>d3?$$Rf|@@&fA!a5M^p6Ew1=U#L5_us4h2s8i| z3V`J;Ge8tfi9WYlixm56y^VhT_2XHrS)96}j)k#|AAb$zTW7hr9q;98>*m!U>BgMX zP)@Rmm}4gvOf8o7FZngji%PFuQlHeFuNP`$#N^jqxa&sAMAZ6o2^Hoq`PYxvc`lA? zj&dZwG-NAsdFWeD#bQ0pHrS&bU!VY!Mt8)i8ITK>76G<;k?}_fB`7lp(s$U9S}LQ(Ds;rFWUu%N&cm#ZB$X)(d7D6@9?E5|Dok8y9F z!L!01U^2~XOAKr}GQL%V>CN*NJXZUZPD75vgm~5G`4K)#iuH{X$DgT0Sd||y;jecM zzo);tG1V*tdE3^^7M~Txm~hMV=`wAaWbRcS?V57uU7aoj$BmYfrN9YDfs%3x8#CX{ zk5|xHq!-Cu&0oGFDXr_SnNhR1#*c^&%U;@@>Ny%9(c>8LxJ|(+zQCDdUujebVpfaj z=?M-&sxUul2|gp>PX~~~CaSCMu&GZrPlyG)mV6#Eu=?T0Kk_x$zxau=Qsrn9WoG%v z@g^EChE+$spWan|)hRO{0EN+_A$7Y}zD}W`kH1+?>dolODexB52TVIC zuK^|oKyt?j?2qwMNs*Au0|Z+Fm|;y-M9{10YtY$;luzb^EhL&dMfewUwH~ADvN?V{ z{IPrC?b*uQwvY@pmqEUh=n1Gx0}VdBq)vgbl0fk|m=B4=b8KL>!3T1GvUgj!_S9|( z51rLB)ZLpUGb?Tle(Tl(+_eQK0yIJwn!_QYEYwZirPC@oLV+<~pACkX|7P)&U$|h! zKZ6D+;>c@sD(-&^?bcy+jEob&qy&I8%ecFZsm6P^++L3{DcmWFyA?e~qJEM5Lk~jh z;PN^zp*RkRXWqWh^>bzNk^}N#OzTf_l8l4Y1?{o|=wmpa&j7X~+I`?lbxiie>Tp8D zka(B=ENpJwsCr^o7%kkgW=x-`bf{Lp?$wYsD`&{@8-dc2@1x<1GG7FE{p53ANL%JW zOJ>#FM8Lx#=ykd0A)%90(9)s2xGqP-uG*G|@`Qq%Wvq=JyZpppt8VweNyt?sxcZ$- zEKc3=c1qgI5OovOKDyRZz2G?KF^X*U=N0nYNOxih7d}z>NGR^-tT3Z$ZTj}SBkqMj z(jLf$NaG9rEryk!>h!;VYMvSfk7FxK42`wqu*wWmX5DOaZ+xlZ}Nl-aAxsDKpgdl8(Duqrt$tFt{mBs~)UELG3H~^DWyZ)zQx!NG7;Z>gc z2iTFin~K7!&C_+fl%kbvKwU8hFC|x%kO;Ce#zWmy4HBB9uv!{bvg8EJ*M8IlHPIFwRM8_GGHo~5}sXpk? zTljvtr5zHd=9N#tH0mmGJCJz1J%b&%nCRL-=S(YFxnaE3X#X zn%yIHgKI!c$wgC<#Jp0G9H(_&VkqL2@MDac&O;5>9E`5>tB6@jbDzojuC2g2-lgsl zzS*h;5Wv+wwX|Z#`<;GRT#cCJT2)+&CgTdtR4M0tEb*A*$nGGQM1`YDFziwBxPJ5D zkMw7!3QNmPOd3;wWpfEpPYHf&(i=meCi7B0M;+W?#-+Z%%T32`#jd_RtNS8elK#A; zL~X5`Ax?LEBZkz^?z$E}-8|o>+0Dwk_uC%Tzj>A1hI-BD!jtN9w}5S*Lt9>TNwDB; z$`U^Zhb^9^;c?r?-lNv*L^oTAa^5PNSADzj?rxUHQIjKh`HIc|y(>&uXUtit?nCJ) zE#o>}`V)DD&L)p?11L6M(P-3w4#zyJfkwZ=5L6f^Il7$vV0CEau*!I=iv{bAKU2)S zkd*5j>y6?5ZD%Oyv(0V?EfSYCWWRyZFT|kTPVvxxF znPH)+OGBtX{U|+0d!7-Ga0y#Ef4=0dl22uu16(WT0wfQAVZ8p8w|R1?ZGzuXNdQ_% z$>+$gWCF+RZf7kNd30;9eu|aqku`H=Hv}%HY1yQ~Cl| ze|I==QKz$S&S|ry-mG2QyWCKrx?qYi>#cjho3rZL&QPcJ+OW_Pn+sh4qD1pBX4@Qh z_j?nj;I^&Zq~c-RsuypH7XLRlh}U^|+AOToTG?VRm6mAYZU(7yW?55O;#O5V?=dQH z+u}MAuU(9D%gJ@Er7JP;(VYxqpjOxL(Y(;>2I-W}yu@v#sr2a(>p1zeNBMQJbq4L0 z17@bCB~v5|5laTDbCo4z9JB|WZZ3sXKa#4{hx-?TWqW&DxQB^w&HhbTAxl;ILSwQe zW&yQ{!|~iv(XgpX(%E9IM^wEt95+(&8YN$Op_2@nz=gpe(_)Frm3F(VnZ7EumF_QQ zAl-882J2H0gmKM`m2(w$Ghi$WSM;FbwMdurJW=VPVuZCIB@6@prN7=S5U1L7o(gQ| zMWo>vlEN;{w|@m&7CU<>t02{>q&rpu39YBQ|B!Mn9i8r(;klP37kzNgV5WsjO@KYl^C09Q+U`F`9wa&o}+Me0$4SuC@l(kLGIJu5#ttiY@ z6~0&sEmS+3I5?+}j7qvTpu=DKCKrfzmg>@SNZL?iSK#C=HuV86QtFYfrdi*?RBygN zGHgn@ba(-JpJ{F9cmdjR@`LTOG(q>0&rGDpO9?70Mcrd4&pY0d~8b3f+sE)PWG8<&sfHanMvt^dC^fPAM)p zM^Sh25Rv%gXLBz_;)>RmJSoDD>JZ|ltcCML>l=>*hm1&eA z7`;_9iyzd}sQsvFDWx8yh!45OV zIr9Rljfs6pNqtVUQLbz-Y|#-90>{@jQlfN2oQo|rl>4C;Idn-k19Hv0baKvt`kDuE zi?*QpS5UbU4ojA)U_G`+bW1A5RrZG|rrDS75n**i>vL>1#V)LgSN5&2yxHQQF-~^l za#)#`#q&pYl^VOmY-#y3xECANR>b3)neZ9Ld5M7z#t(};RzVK4TGVXsuldr=@{%ec z7B~JwafhEK&RKV?znwp{x^Y%jM6O8YJWue}LMaHWrIOrInM{N=ohQ_-%uL^6jU=+b zL$;n#jXCox3I%OlCew%vYnYrJ94)YNSuE95U*39`frT7{VVoRE%;HcUrp<3!uT?k* z8y?X0-=$J*L|-|6Cx)6rHbr(fW#gY9q&R$&sB2r7>ooG1(JlulrTWLyUwv4_7(RCbt#mm@|TCZukr*D(i8v&WT zx&L;*>4B5zSguP#WX3m-urK*~IkcSfG==9dhrzum*HKm5s@;v-6V2z02W686c{By3 zR8vWGHqv_yLZ>jHbA)U8aNopf?aJBQ=2s=WSj$G$9Gs3OTpm7LCgPZ|#(3d}Yt%1| z@3=*^N+xv@aq8{~?JA;In?H9(N;+lHFoKemm8xb>DSSH{c$0W*%a<9MONC5W5`ZuAw48BOH9v|g_w%yEW&mNh+V*LT)m5ue!e| z+&(kgg{6Md>33|wqXPp6rnaX|CsQg5ieIeBN;}0`3~3MQU5KSXfS+Z32{t^RF0Zo1 zOsN*R1?U%%jlU>gXv^d06ym;UJtxi#*t#r6by2A97jasY)0sF}x2zwvSAVX;M?P-z zAvR2jO}xtc`CIpI?4?1L$CB*4#;RckGj9z1rag)3U1rYZlN6%JySl@x+IeQs67tiY zA(9LXB@m_7q`c7nCG`k4E8d_UkcD6N_aw<~N`xeag8$fGiBD8LkDWw)$Fn(U!8k=Z zuTXSwojcmc9tV5nTC<*l{Q!c`JjS!T-_$;M0u^_AO&^Zw5aLOytI|;>;&hbYpWs?e zDxLX3Q_3b=RW|FX%assR^pk9{-MZNaO0eD;1TJR`kIUqm;YF&}vN*GgHJuo-L`IpO z@#{b!wtd%`oaC0uH>?y0BsKbt{({Qc>Ahs`hP7O)N-d)+3USM(36UHR`xn~%k;=PD zNCg%@y#^C&2tT=#-px`Xiu4&;Dq@fukmPKlYLa6)Hhw%sOrTgw4lA39cHCmE!|rf6 zZ%LI*3yx}5CWG*vNt`vJ`PInu7j=xKIBu#&v=6|olqz=>lV6vgNoClACfKt}o}3GM zIGsrqQ$3TZ8J^jXo)o6?An-h(@Ke0%xXw2eUwiZ9q?>ck1)}FDU>^TKBJ;ei9G`#d zit1gJTe6z=($MsNpS%v=0`VxY$k8DJQju0V7w_Ew5XLau(rhF%nGW+F+AhjQuLdt7 znwo2AUonXi<*~!{JbY;EtPr}8(xACX`Pa2+Zz5klthTE2iP|p>WQxfuuJa@~g;dqx zF5@L_E7XNLIa8JdBGHsVVy}SKvT)Hy!#7P9bH%ky0lg3ctu_i>ZN>wkS@PN}*;0pF z)4VGpaJe?@E9e}wWhrn8N+gxYTGX3YnE8Ghx}_d&MDr;1bXwUlCpE0MClQ*gZZxPo zzr<7rfZheVy2+6bb4m{i^;Z-&DDZRW0X|M$Ffs?;!^ww z7XB+S`QQ2x%{{9^%_@;H8SP>_g5jOzKKYhQ$G(;ii()xYY!db4uXi?!bG70y*?zHvdkQuU(I78?hXjh>xa zCn>$m%8VX>t6U-+Ua+@WhYx^&Lc$eyfx8R3T%#OEG!Kb)7WNV&T8w@jDQ0PRPjRQM z2NQ)>dMmb`jxIJjTZFC7n~GfbaywmYJ^MK-R<(md?HeltR9^HkOXhBZ5&>MHp&?tW z4XRD1okF_S&o7eB_ued7=nwCQBjgsM#0*|4ol#FAw-y>`KdYDj#v$DoHt9r4=)}WNWsYoF*A>`K6xRe~)%CFz(AM)K#6lUd%c)|Qk?{u+I zc*!6Q^w1*BWA~d6|4`}$b$3&}|NDfv7^JvkV=3tsi`jni56q@kcwI_~Qq#*gu zXtytH{1wwF9^!Mh2RIYDLXNhFSGdoV9k*Pwm*UL~MZbon=d>8tq?*EGw#Il|g*olv z@oVl_&iv@0dC7A$1Owa)vf)>--_oVz#;#2cOsjkvaX zS1&kAiAye=kAJ;N)_`c$v*?ZSiMr;k&T$7R-Z2%b$_YkC+FdyxcTwg^aI3quUxN>* zlW0dYg?kVBEo}`RLe+WGZrIkii4!!MPM_ve^uJZIsR8HKgS@YCmFv4>|POjh&Q zitLJimnf5C#o93i)9+DSV|0}uvSXI^Y?7hH^pLu%Wn+LQw)w;+dUUs zJx!Ky+rSql?-*G0#}8(OPN)>sy8#OEFv#&CGz>c`2Pt`TljyK9h`EBz-#<@F++(*^82^8g)@pTE3>n{ z0TZv31EPoS2!dt<$@lZ7W+;dMv|>JUOn^JxSG821e^; z8544Q)LDz7D6UwqATTFDYIvpgX4;q85+&V6;ECx(r<+2-_9dsC#1Qej+2{d)0bnJ~ zaEoGm16;>(U$@q^W~tULxf^oOv{6&mGf!rGMnv@br> zlX6y!EzJ_wmty}P94PkN*iJg@Q z0E+wIc-vCsb^Ge`iZ71@VXil0FSSJ&&Ph?X_?3R5cu4P|`?YqWh-~gGf0Ma2`W`=H zgr2e}e7i$aLXCfegYy5{_|s#Bx-DZ}`gD-?$yTjpvrZbK(=52O%I(=hoK;574WbK1 zYK!WurhpRCvMq+bN4_~9hKx7-_}>eYw@jO~hQ-#LY)M<&ro3}!PG$*msG&_dwSxdv5?=j}-*#pX2JX$v z%gMB|l6JR$8yuT!dT1Xn&l#Iz2|HK0LOw zhZjoj-R*(2UQh5Xel5GP(>(#H6g?ODWv&Y}(+68j$tUj=F@ z)2FkAGsAXi1bgw&e<8?M{6_=vtE&p0eBqTt;YcjMvTkL_=lQeC0pegM^~FIwIG-u~ zl6!Z?Jf^r%m}_Mt++5gLdp=h1x=0G%)u^%)+Z@E6&WEQKZX5otqH)?w(|7^6D;i$7 zX3QR|1(xK$Y~z|nTeuETJb7bEuRHJtLYf>R(v&ma|LwEi8?5Bs9=>Py_Wz^4{@4G0 zQ0Tz);A8r2+{lRL9$K?g6l`R_gm;rLU+t(5u*$J5&Ig`4Q-w{9zlK8*1ec>*DuomR z3SWm2s1T7ss9{U|E3XtpxMswY?hJ{(8?iG-=V{pSo1l}_jLvFs&N@ccq0A)O z;EUprbw)7)S>7Ll!$E5C?IGxm#qR3ysSpk)#4x{wG@iaHD_etIYua>B8EkiYeFA72 zs|GVA0s?WPNxO#}pj(|0RLj50eH41jw=bC2FkZRD+HHCZ)!OJ~GQ>oi80LN*(~4ks zQ%GUwt3_eFhr+eaA-XK{$4{GQ#l@%i$4&(fw#?CSee3Hzkz4Po*{o0JOA@3)Y|5nd!dzOZ6STbe>?&d+8 z2Nsr#$sHH+xI2SEES|-BI7jKn57OI|jBRYT)+qWTH%`WhIxy%9u@2M-XJ`XB#nnWA z>G%WBdO@Bz#UdAb`N6qojiKc>{;d0F9Js+>9g`N~UKDGUWT?0e_PhVc0n$Zk42F>A zwO59`FVO$+MMSUIg{qq|bx=2xdFRk*LtZ~xkIE8z^pSB)%8t~SLn*EYU&K)uI3nCe ziyG0-pohV*^ZpA?tL;Neo-;kOK$wdD)^lhJ50Ki%@iXwAvQzXxy2P_fDqU`Dw#10lD&(5O+W;RyKrBOFE2}Kb+Y9~^*TG8=<;q8aeQBL((io(YcYiq~x6G9z;IShmlD z2KTH|qtrRb=9wa($$fA_{hWo!(bwG3Sb}y%Y0r=XgY6+GRbqk7l@}IBFNeZX=WBs` z)QdlkGFXT_th3^?ozC72l8lIyCcuddb;dH7Osc-+^AVuCzkN=CG4?tQ#N|}P>duF~ zo|74vj;WXe7G8?{7+pEnsLM!=0B625%w!yjP0E|fIJQnyLEJ^_Xz1~`0BvHckzg%T z2JRY<{0_4rb*@Ki>8NAwNi%JpobRs$;nby1*}`&+rF37;D)jb~ZJH!QGus7Hg*_Da$e*NI>lw1zYc&oGox?Z_$r>t~q%poRM{&*BHZRV`nO-F~f4 zKzd~>pYfkRm`bm_7N#mJ&Tf+L-LP9&$`6rXC5pV_pf~fW9>qfWVM1+HWeT{bFVuGmC#%HOnzO@p4&^5cO3L24snODdj;rrWjTce;OMV(iz!gZq1-2S z0~9T_J>RcSwl(C=?YrjP7~F#< z1PJbK!QEXGAlTqCz@Wi(a3_#=wszmG=Q*|ep4!@T&hK~LI{jBy%}n3j*K}X^-Ishn zPD^A`H*a=qtGhCehpEX-I}DHB@Ie!GeOA#0O=hS>|s?1lH>@rq$%`R@l~933n|F95~h|-B+3G)PiMk9Gz&4 zZga@J--8rhi@-^5B<~pZhC7pH6|FrP1?Q>6YSdJ8tzEFK_l>1Zvh4-}I`6q%=@n7+ z`IgeHV{nWLwO6S}av{$*&v{98us)sKTY<+QYTxlX8n=?{h?K83Erz(g_#g%{)7Da6 zW_sY6e%U#_q9?``ahV(jQO(rzTd7B+{G3UKlB79Oi%yU-xwe01{p|)8P^qbSSS8g1 z|GSh1dF2=@rkpPBj~`*qQ?$2ZD|CUxX%k`RNWKyVIh=ZqAJ2enu60*ABS+qXKz9C2 z`f=k*O$sz$*GN7v|Gs|5^K+cOCiP80_p;xXyW&)kXIDWnp5kT2aBD>6?u(-ZKK`-H z5a6TSW57I~20xx|WzrR8fkZVTo7b;l(Bc$tR{$iZC=YSlBoWODPy2MWr>!*JP%1eE z8Z)i00vIw)vo{uAeV(F`NpbIhMqT&WC1unpx9QI$V|iqE7+YGcCBc3N37;ZFuKtQ3 ze(w5v_BCqOWUyK1A-q^_yv+%-<0&nwd<#6%j4rd|l3859}l4p(_=`}kJM{;;g zN0T(zMmS_N+ASH(#XG_p+?8ZLIDV$?-r;A@FAAgp*xy1P z3}!mTW*UF)a(cjRtZF(JAf4M3S(Ogl{H~sI{)Lftp+ix<4)BJm`+>**;#?o|i+o zXyW#-QXMk-X%Om94HvpbRRfZvtq2YHvY_pX7lg;ck4~0AAyiASC&tJ|=!XS{*vE=e zR`RJ??#}%a;9Luw>pB&jU3iX#t$Mc+HLr>D1VtG)nlK<+HXP7P4F4KPUXh|wQb@>c z8~2r=J)A)F)iu((r}4Ffo<^m>utHhcfXB|)R#86pc=@a({gHtwII*0CtHEnBtQ8T@ zbo5kpvbUz#Uk>nF$KPA*GHZjfeznv)9!gF1XWlr#^P1jA@FLra7aNjf>Q;tH$ zKs$XOr$17v%?=w@6vaCq2=GME)eoA|L*%%B2)MuGzy37APBdtYW)fSDa4I4ann&5H zS`|N-^(D8Oa?L)low_Irdb!j>D=PD+ga>q{t0_x1zDawBe7Iw=e%&*sap{0Jw^cRU z*kPdR=I=6rIkzw|$$G!hq3u+Apnv`ONKvjuaHwo3lO`d7fLQij@XnMg=6JrWqRz|{ zDyA)RHsvf}%*YL$!mo=^-h#PVASSGwuocSk`7A!FTKb`*ui6BAwRH| zCBKy9Uy-8H51Q@Cy8-+6DqX>5vUBA7kB=Z95?R;-mEOaqm`S^vp9_je5EDln}74KFT820pwYcWeL&H^GWl{W+_A@#yzLIRL7RLL}Z{zwNUrh0RhXFsji1G zP8>nRtfihFvBH+<1=&z-M1)lWYGPk50q;|Pt&uZyIc+c*Yd7dB$vDS;SG+#{ zb?~vvHbsCUPr!{%$WtaDF|EJCy!WO^++ypXUuBmikDQ>Fx!$ob@OOBFW@(ukpGI}ja=-#XwyGos@U8GcW5%-JdbWO%&xl>dV@E4QA? zNM$Xr8Jxm9k{N|wrFJd0+vE6C>Forszg?_4^tkZgtFI((nVMh~z@w4YjpC5#Rp9Zn z(hCj(;gSz*=vV@aQ(%2Ld8fnU6TFbvmnk^L8o!rOEuqd>&# z=9P_i2~dBX!Csf*Xxidg9|1Lr(3>Yfdlpx6Sc+`}n&56J)gpTW$J7NQilUUwIdSMX z&(oVX-TsN%en*F%8<0i&am*cc7gfD&7tO=pa-5vs&1(3nni$En1{FL8{XB z`Gzt=l^JCQ&t`_zG&7NL4kUnlmeK_@Df!uRjlgXxO)Dd%p99zBDfr~}rI@LJ5=H`G zARN=jJlGNsxfL9(0!>VTXEQPdx+7Ky(#$X5f3wI2KT*Sun}g04$WY!|tC?O?qcBna z9YA-b%sN(m%~oIdVsL6-#aAl(VT$i7sKl1`?F^H+9RLNwQVhO*@77)e%Lt7Ncfl@m zbZ5cEI=Ze19=y6Xu3Y?i{Sj^gy)qQ8aj>}#Ww!C5V0>A0i2Cpe5NZ~lucbq$r7t_H zO`j`c+<)^Gp~36Fgb3T|p&-{iW}o|ht`bmL^u>y=wVy-1O=}r*81^I^(UACVo@;kE^4l(vHK)9 z)~Tdw#itbRuytrSUf@gPc0Je?T}NSTX}Wa(agD}LF~4E%nCeaR3Jp}kjhN&6-`oZv zJl1BH%Sl1c;CMA`8E~rv4`&7Adjyw%EbGP5)uyOitp_bnp82~c2Vz0MKm`Gd4& zTxxnsj3QlgTOf5%j-V9G)33PStLmp%RzOSD$`3s2T-fT{$5mD`D1D+g-W-#Y-<|FX z4Nqk4ijxN&3B^rtRhV%5aG7V{#5!Mwn21Y3t#Vr?eEYTby2|vc-}wU@hgI}|bvVel zuzVH~_x4uFXG9F+=s{FBe|-Z%k!@~*=bRR|q!ul`wIhtS2{5_9y`E5u>--@hvf@$e z(XlX0%v4eRJ$_h~q!wUIpOB!=T)iSe9D&Ecgyr@38Kn9?t2(^!G5M!ogBR!5HN)i1 z(C8#9sF&<7_+}V7zjZ^)A+KZk!tmGld86S}K@M$kmrX0)xBton_wWDlzns&be}z@9 z4B0z;?g_TRHWe>eBB{5A5|9gf!bj0B4V%HAWrZtRjV*tDp>|0mh7EAVV!eN#ahS(+ zx_BRs&8WS{kf5Qx_!AtgbsnZk4$tNKVgX%pqhJ?ykFo+N^p7inQ-ub%5KUxvAzkuE zIcf8_SLNfgAZ-09-(z7ryZs^oti}*~M&S1gtu&^_Vt!e|64HB3jVfzN?Mwk3o%2LK z^$oKxvzS1tCM&xqLjhm9MUo6h0&3^{;YOK~ap(AV9}a06kMrlm z%*#y<9rUaD4u?&=_X+DA_bxwsz^!E2&L^7-@!Nz54eD)vbZ>Eij*$M)xkRKKH;cTj#`xueWU+z~(j2OOM& zqid$N{e0N2h1#ZTiH-kODcV(2?E)zF$;uqWdCcw1W?7d~g=d|>S(Bi|{A<9qScfxA z;>QmxyMI9>{(p1Nhr?T6|KLw#idvi?R z`9uAY-zFVe3FAqt?eV>9_35smrq-!fpJnXYXm&TLs9ad!s)rWl9dQY!2Bo-80ZD}= zjlQ*w1Y5ou!V<8&7^9>zF{LkX@P9Qe$B}LuZ?-R9cVJWsJ7f|VH)vHyS+-_Si`d6s zINcOH-8}#G+{kT=($eI^c43wOt7AFMbU=K-KBDg0h-v$9fuF-zQ0v7qkO8ayAPshE zNqo9{ZiZqrS}uBFbe0M8eX-l=8(dI6bxxRx4{!EbC5@GV3wJq09@6K?8T4?T$Oce1 z$RvAidvr#;=!wlm`tLZp3;8i<>~+u~=W4F&|A4gp)gFj_*2mZft^FDpBKU|fj)^LQ zs*8lAE4K7ZIbdqig9PniOY}uURobzB5fKo~Zrxd4$HzZ1kf5e+1Usm&$JDQ`OQJ#N zaCa{DbHW=K;0cQM8i**@*?;5ufk-?w%5T@rE!o41$sa%1x+34F(hkH1E;HU&|5imGv z(%;*5EFF_p76`z#v|j4)6oXTLSnN`gBXyenGv011Ri??^IoDPUH|!a$L5*|F{1)jR z{uAg9Rc9yfCmE^nJu76iG)6=Y@nqr#d+D4H=~;ZZW);HF&AUKz9pl|z5= z`yI3PtlFc=p0DIdN1UhlrT1E9;t7_(Urd0sc98r6VU{<^9;YH-AfdYJhZ@tjh4kPob!QO=jl>3HpKkOQJX>oqLgo5yFLQ+N}&}> z2ONH$RUg~XUR4y{t6LUkCev7w){16{UWM zxW&qnY)w+UK!6pD~pKjW7}uB7c}O1_28f?bH%Bi zjyQM>(U1D%P~Nt~r|=kEQuE6By8<}%g+_PXl6!R0v1nNdggLE3nXfFn+~)MQjHyly zZ1ZxQn`(76{9r7%>^h)PUe|3|cnRBh#dcV^Vyc7UKtpNCUeg(Em}xYtbYXnP0))Yu zRGaUk_43Tm;?_?PJ)nMAKv8F2hxd&nPi6fGd0AnEVk)DCj<&dx%#2FNxC$77I_6p* z!nlOSV(h9vu;4kylUHs>zt)*n;4sQg5+-MCTM|rzu;QR7%jI#h^`y_91J4KpLa{$@ z-3~}g|3KWe|JV%}Cex5Pub;ci_$JJu=HAAh-hJ|6L$N3A!(F7Os?j1iJ=K@N!wa?5 z!P>qvBKf;M|M@Qaz!GOfUDv+dR7VT4{o9jAYNhwkmH7NE&)>n%=@vzRw!Zvz5nr1J zOOoP7p~Ycs{FDue^ZfD*T*(G3e2>+l;i(L2$_zq=Z-gcOF<_8?3e8&4|FryybN{ir z2lJ=aQKD&5U4^c6Y2{1ttG|%!5Po1P9wRN*HjJk`OV|?6O|Oc)so%p+%&I$>M*bV) z`fn93l-A9ht0UjU)m#TF6j1)JfAlP0q`}EY79j!S(|-TzVk|jC2WZ~@v&T(&1iqew z;im$Qrd5mGZV~)$AAz%E`Pw_|XLL_}^$I}KQqJ{vE7NN;7c28}Xe~W+yX)^fnEcw_e$-XD*F9EE9i7f0mHRZQ zUtGUrun)E-+(abP(e0~B4&OXo;h}Pp4E8&OY?`)7?>_Tn&_q^g3Hh30Z;pPw(&6ba zX*>18pvf*mb&20G{tbfD^@2s=+h=C{viu0<)R%~43PKJTA#{&qV?0vs)!n;zEv5q@ zJ?P+0rk^QJ%*1^pJAvyzq_uTmN&&qzqCHKj<4QF3*I3*Lt`qia%(7E5gA!To=FH=i z{GA`-m%?i83`WY2GILEd%ov&olM%65)q3G(SaWBqVfs9O)X$&P`4;Wy=0=F3B5CNa z7`Rtav53b>d1;G0y)xDh>48JFw&EUn2lVQWf~Bi3nc=hMuvuG<^7?De&$lfSsj*6f zIgyLp1WSJX0r~4nTfPwmX=UMow8ZBYZzpiv-=7?vC#_TG%nT^uO7v-0LHxrGA}vC<>OSUk)1Pz{M^z}>p{#b{m_Q2Iy7R|4JVUJp`^8f~r9 zSJmka&~&hVyHO{dj_HtUX_q`u;R7f80p9iMx8mm93Mi%IP|<0O1xo|>ZRO*1vP`jd zlrwIu|J6f`?7YVao0NiJa&oHi<#~F(1Z=|o<07?p#P6%I>}L`d2f(8RP%S5)pma&( zb8I)ix2%=x7T>JYaIplgQnaEu4DVUQ+bHS}NZo8l#{fCSJDz1mD+Vz%GngMs6zGWr z`+_8JjxT6K#$-g?EH!4a;>DNxt z+s2s2O!F-(_2;Io4YpG@#_y*_>m68iZ_hbS;l%5JR?`=bG7xEEarVJ)A{QFE`IWx; zO%qo;Cx+mn9MVL|I^)c5&0RAO0Jq|)9Mj7#*`>z{>t^7mQOZ@93Db!=00uIWGbo-JopWQ=l;wsd8@YCo8IZp!--)K_Rq zsdgiQPLa|o+glOGfH^gDlj=(*e^71gQ(1Y@A(+(R-j%lCJV>j7U zI%Q?71l^#Mfp|pSM=JnnvTUCS>*d-NI7|QH^Zr?OUpp`ri2u-Z?aYXdh3Fi+MhXpfYm4qyKoH^~bKEkgLlWH3 z1pPi-p^Bn*hLJVQeU*DkEcU7`I3-}S;(s#J7nHr=m6O(cbn=+(5-TXcoEpLH4K zIvIyJ>NYbrmwDjas;%#E%rX6Xv_%>ecWejjU5SV6w87JfCLVG;G7b2&Z1s82L*p~m zs`3vqtW_0?XK>@_)4REI@=BWGKe=x=v}N?4a{y^elOj{mP(~a+wkl0^48$_G`&|K8 z$miQ=(wAsV)3^Bp3?%dil*LnO_+2bIgueP?Nu_&6D^gX|) zvObb76!^xHX;iFhS8t~xxzBRVeM0TvQM!w-{CuZX62`A&aL+<$QAC0EJ~7RQo{H8K zCR|idEZj_kd70!IyElUhFeLogW*L^LV>|C}7FYM%c@ebDPKq(dPT23P_a8|EK9-eSg~__} z4l3EMtk0u?vWFXZi1cAiOF!{BJMmlF+5~XfSg~1a9Gr^c<~*#m&Rxz3_NJxhHuU7> z1{ua=b3$a=+^*}zn_8VlPawP3qi5poSXtg;ti2%Y5e@-H6CQ9t>y?o12z`z1Q+KHOcey+W zv|Kfu6yWxkAv!5jpWC|H2s>Byj_*KOUvz2;&7jGmRHRT$=Fp3{5~u&FCxzAkW-)r@~$_) ztg1MFl%;_#(;%cdz_TlUB8MZ@9U6&!)jCFGzjDadrFNIcGB$_T-xalQpy;pA-XzHe zHz`AO*^HB`Qdl~=;iS_ZQ-!?OO`aoG?8w>kfKa|q5{O$x`KIgc|R= z9{(V5;h9ffq1~b>><=*y!Ed+7}6h);CIm2XBRjOAkWW-HX&=@{#foCvi-bPi~<=TDXXxoMN{hAr{?#`~K zNUGAya}h2~L(pz*Po_3^HG68=b<@-LZO-|h#l!yPJP3F|uCf4|Me=stHM>fC<(bPu zVLat|H_Fw>DHb{T!T}s~SQ6OByEq2dG1#8eg|)taj-(t1ulqPs8Pk=}QLgJbC(?Zx zGbRzWUSgP=Nqmin8O$3{%c)Pvx6G5)kH^E8zdTrKh4m>sDJs5RWwZZx5D#{__k@al zj#=yIlpbmEMzWzld+W7GSHMVsQ`JhTB`bIQ{G-1YtmD<0_QEv{>|2ujh-h5P+kSqR zvUdTQ5jX7{sn|}ilZxg-kwJl$qw0)c$zJ=?F4ZETYnRy(-McRlE~tNy1V&!!nrCql zFOopG5`=bLuwOD;Ce*9o^lHAr@j&D2Jv?%BoblBJDbqJs-m%iQ&ebMd3p)&4R2~u9 z5?>j$M${M;Up1u^F?&?^c6v92;+#Xetb3**94ov~q1d>~bs=AQz@b-r1B+XWN;8np z-@_{xdaK+$t{l9ob&?}BBv*4j>4 z);+YDRfFzpd}5UaLGnNngY?4Yxzp>t*B}qao`w5xh1ST+u7EywtM>c$r4J@nDZVd_ zqk?C|c@nE1$y>SV>m#z(PXKL)2D(Reb6Y%hCB+-WDsltN{wtXk)^c?qGsi@s&n-a< z9j|7PGENq0v}2k{@4$@f%&Jku3q$fOr)%$8b?V3u_ia9?4wG`c3J@PV!Gw&k zlOB`GHhXexEH7#DDH^~&+;Z_hp#zW5t?(-!_2q^u2p?yFIdawMI^c4pO%&wigKUaQ z_e6U<2d8KEc@!CkoTlDp4L?HM&2=8F#!qfPn%Y<2Hq=uPI?ut*;E ztYOKD&sta<6_4d|Wax!eIohfZY8%TF1yop@uG4J@p+}vg57RWjWY@e^)deeh8+zmF zb+^*|rfbge62mlMW4E~%zQ zW8Xl{(OiX6&Y`(}^$e|s-T8`u@Vz((Lz!lDtaX2T8MpOR1}HxPIN%bO81xr!^k2LG zWr6>)z<*ibA7KGM5<^vs*J>^3LYALG(^?TgkWv}Q$l##jV$s4+1wG1s-31Zn$g*Ju zXD*JM@?cGtatAV&y2vjxLbU{w9Z&G=J%4L|2VHh_vJz5RR+y(%UDa;(r7@$jwbA{q zaBJM~Pjm7NvUB~>mgp$qGf|Qezn5X3TV~-{N0qF)5%BOwZf~f4FcWht%*I1mh?bUN z!l=I4Y`b?->t|?&^$FVw0VA;;oWM_=p$x-pFX$g(qW{w|fp`$bd#O#O4EH?h!Iwc3xl=UR5CRunPG}v*Oos!pc zQ^6Tx+gf~VvU=&N^X1vK#mv7f-9pa=r+xbcYy6;Dice4#6#r52&?MAvgt8n28RwI z(A(f1a2GS+*Ghgrv&dQXnz% z$sL-hYGM9078!2PSi8eQH2!rF8m<`L*&?Mb;miTdO^kst&}=e=Z+&r+%z*oJe|;8# z&YX6uYprLKzjFRAu#)R0Cv4f^c;Uj|!NCh%#Rf+*=5vf)&O?j+m?|;>t^HKP_)3Z+ znxMOWs}~bo|D{oJAX{F_fGc@NwgA#d9)CaOnA^eJB`J%$k{^AEvAqc8L40~r*+njw zY=hFa1XV%vrb1iOCZYa$S#g$zsj&O{xRy{9IEk+7)7bs~8Z(T4yneL{<3`vb89LYA zH=_KpQKXF3+KAs^%(P2`q$odr>9PHcS z9$lHWdL~7c6eQIi+iFq);#As_t#cF>id7bi4y4hJWM(71@lT&VN2Tzjx2PHSh^I&o zoULwcytP+e(M9IE7ZBD)t2{T`Xb?Y=z~{m&VwRoc zjA(fG5bpdL0ntC^_mNeA1;6^q9Z?ESgVD%nNWBu4z6xu(sM2p*@JsE@vLE>9saG*H zqYM{ZAWKm8FlM!36_r&QJ#chZ6fzd$q&*J7=T(6%3%xI;dL_D7fzvb^}{=8Jy}$OEZ#IbkkIjWh(Ji*`MX^TH0P)V!(Cta3V^_-JVz)8M%O#L125jpuFUi?$WZ@awWD|_msj$G z`=-b-rM-GPJ9wqNd!^f_eqcaYuBHZd*yY8g9^?H*Rr^d=kZkMHitw!fVf%uPB0!m| z7Dj{Tk8K|lSKVrSiIK?tlDp5pHH4DYq`A_>Tx<0K6q3?z=+D0{ywm4fD&zOM^vE7B z(!snaMH(M7-EUUC&>CDfRc@RLZT2;v;$apQa;LKY)>z&dLNB3}@6*>bb#3x#*?mtM zH|(YGl~+rbgqYO#_t|2qHTIZs@qD>}JDxL8FnAa`2oagT~GtPs=g?avhTOOQg{X#Q9NimRx_QfxF4{d zdC5m1!0yQ{BtpCGg$L?X81```V?=vMS;3Xo?oO5@D&x*v5fhNW2chnx7OhIDUsf-r z2Pdf}6<9kdK`f}xu`-#gAUaEIvS{nn5O9e5wxGfeh4G?tb7c-4d__Yk@ro5|eM!*6 z5=Mb-ohxco@O3Ae9{XKKu~Tk#dHFg}TUMtbF)e*4z%+1;V9Q|``NPcWR27adtSK!c zx2v73z-+&TRfSDN!N*6wrU`4rjRfN{%U7M&GSSB<@ncO0;Pp`NTO)5g{`Ud69xvx> zZw8?A!dg1;=uLYVnaQES{H)y}d#=~{`E{gKgPxvsfEG`VYCDUVw@P_^I*S5*Fq27fr>~~ZyEGeoe?2)Au9(rV zyFUcdgW93Rb!M>+>@Ur0)Ij&k;Gb+iEobLI)Fh0Q+cE%IO%gslaV4+~39{^CG+pvc z)6>i^Mpw-SJ_(y$)5Rvr2w(1XeKe*gn?>G_>hD3Xjj~2s(7&h0&pT&wjgk-n1P8lD zNs`j2UA`n@=Kb3{qkn@VBBQ}Ei40+Q?^>+!nxk!+SGjb<` z7_ONN*~L$k6P-U1>Js)5uoKFc72dtTi339yk+C+jntdG5O*9)^BMl#dnPfeK#rd66 zrhDyDmj~n2R=-OL$@8;u{Xu#jqR%q2LfjKII`ju=xE`;$Vdj(+>T@@$vd9TI4C`ub z2Os{9WHu~HN7WQo!)1HAlzR_7xbl|pYSTy}e_>$R_Jb1f^{WSGxpXI`qWsKV6hG&+3Jl9Q=VAw9-%=iE5ek+Dou58Ap6 z&h8^wC>tV=Femflfn82pPUDl~{7UZ{Z#OeTp$dg|?;r3@M-izWjNoDTppm3UO!M0h z)1Kbj7HY-#H2X%Ue#F(pnJ=*?0UuWLA9K2)4i2yfE_H7o#@0qz`Dg*paZ@b3O55Xb zsMiufUsjDFKgg0)ys75e!`ECD>Uw9yFcwu{T_LRBu0#&`BJyvqW)?y8Qj7}F-?RUTsG+K>0rK=iLq7>=u4={ zeZwYz@}P9J48T-cYPZSmAo~RJlg)3;wgfJVG{^|<-YPE*9ngLyI^36%s8>@y(rivG ze#l(@X}2f~;I12@gUMq-;-%}Zg*5qP2CDb5W|pZOxK6HyDvUj5I%=AUBcS)<5aGNQi@lTpUL zEPISrJ=aI0!+0t?xC9iz*DJzO#EcM{#f^|iubt=-eGdm_%$ilP_HD=|Um#c%ubkJd!WYmPgtUVj&7s2lPPh)`~?eDZ8!T}v(3cU7XHs9v3>bJk;`hgm= ztd7T~VYzwQ`BC%4;2DnGbZ+8XNV;%&*7}+~m1U~>GJgo3kFWBL2q$P~Xbw+d(F4i} zb}H*qh2Te4cu=OJj|C=OoiMiMG21&P&d_B{b6Am?v*EW%iz{Ljk|i~jl)vF198Z{1 zn^qRm=<_~K?#xluM%AK_*_ce&ZY`bXX7O%iVQ%vtZi~(Gk)7uJa*OS2;&cEX-?-6* z*{5VHx9Uj=H(3I}Qu8xe*~RtoAl!o!`OLD3#WF8Qfg&1VxR@@B>PV{&RfC*kQ ziVe_E3LR|8RMktRZ3%K$G*Q|)unh#DojTVV3$?I*+I8k$)DkwqdVpt z>b^Qpcws2HU-nr^QKmbl7M7S0WlvAD!7qZL`+5mka=1mEMMry4jHUABpo_0GE8*9x z`x{GO3{%K~0pgQ%l10LP8B*fecQiOYOc-ka6sB<38QVJ>KlTQ-W7wM7W(RKNNDbsqn=1%LwN+}8sGai^EW%3u_XV#^C~~?Y;zU+p47)X3 z%F&`3kAR9vfIw5^tKjX(jtA}T;l&5f3UlhC9NP*dsd~1T1R1tC{1qg8QTgdYonZXD zz~6tB=)~qRBsu|3QZWiyLJME{t(31+&s!f=;G;CMTJ|5n{b!eFiZ$k(gf3Em)M;RX1y8O`i>V=4}jRW(gV<(U{7lBd%yvrz$v+dB-DvZU`BSwE{K zh)iQL_Pk%RuW}4{TfCsAkwMyF3LuJ1#&!e=nxZf#y*a_WBvR7MdT`t@ zo&3(o2IcH*BV_z2 z3`ki(s|$RU6Wdh0AzAhL3?Zh#!ur`<1|wcHhdW2bxjyHw*2dDks^X7!jd!UXyb8VN zxh1U%1;&u;`T*tb5IMQC3ou8zPZbYSjPCnxE@wnN^XX<^>}gQW)ltRWA||DyMxguf z=**#JJ%@9G!g}8ws;=5f%@;(iH|}{gAy=m+ejz8K&)O2fZX7>0|ATY`*LpDX)&GO! zR~?T07QB|eW+#6c{19&Y%49kzV8 z%gxgIM6W69w%_KJP3z(DdW4jD*$|`!D;nR6uluNJY5&9c;cZywOYk^dQUX*S4o1GK}g8a*;93%{ruZY z)9wn7-sk8>F7ni1&=-f|dRzn5VXqSFwoxn4dTglew}Ou##chHC73r!(Z_FsOZ~Q7q zuf&cXx?v!a7&-Gp0^jTd4M%Dc&c}FaF@F2Xp@T`L1TdstH zU;LsHsnoSWNL&|s#@Brvsca7iBPK*96AvFA^BY4cZ!(5YhhH2pKd5#6xY})3Jz-GW zH&DMl!t0A7aQd~0D9gqSMnaDDlk{5RnSL6}4Fg{-z9Vu1uJ(2G?i6Kmb{|1)4`I7o z`Vb4N9bnQpWF?o3*+%HR%(5q!NFs^<%?mWBZpo~P={|a=rCb88HXN;$UE_$Vw4TkR zyT*PAze6sTz)?$3u^<%#B8#D7wN2fSu-W$uS4SC06^O6J7OtbF(|cxH!DsP4aMYg1EW3g*hQUoZf$swoUfW zIw`TSPyHyVP|+9y*HhCZ?1=g%f+bKpn}=`Yd#L>Vw{IlAbw}TD#^3Bd8E<#S21C5p zdd|N0+#!MfTPNZ_&Gs50VUo)wP_s3$8}0q9?Xm2J6A?xoqnhK?M=H4bg9In&|AW+s z(xi1i4g1E4qWpUWAYqH8`nZ2NiRkuy{_HVdR&#<6E|gXYzhk-dV1=y>vw@v;!tRHc z@t4a*`WBJoodIE<1}`BWU&@h4qj}d&6d2tCK9me#X^#c1dcy?wQ!s%vbRxU zj5+O~9N~Naq>{|0?3(K`0^oz~F#(vuV$hg3H9F7?=KbMI;vAi zAM<^2m%$Gn6d#pm`(`_$;{oUR=);IAe9ru^b*~6Za7=O8Wb)8{=NR-levNx-a#>>j z*a~QwH}swBBn6XVc!)R3(T8!ddSO+p+%YF!TWofJ3L+D^1?8H^vV0*P7#vq+6p)b2 zQMM4L8{NR{m(h62+0d)j6`9!OIBvUFMXejYv9tYyH z06E@~rac$$D#gxh-aKTb)i;D%*?9gz;*ge9Dx*fHyb|(g5BwlPz20CJnHAy1F&s(1 zQW!C6Qk2lll_ax|e~WzPea2VOr4Pq1Rs(xIJR1mInws91XcEqEX>X5|U1<(Q zWy*xw6Opb@D-_p*RTF(Q?{v5=iF!%JpGho9@cD8+QZ0WMpbPq&sx8SMq)~~d$MQfh zw!Oqj^3+>8%*+cBxWZFhpbI-OLSOQqX#+eJ-i3DsG6ag+|DbJi$TOJF)^D83jao=R zN!smp(P_3_3PzN6rfmqsMPT0yiZy@7a)Ek3aQy!ZQsmXKjfn)YYm#kW39}E_<-|nW;jC z3}{S7I^98n#w%56_14Sb#R&?&;aay!mg(Tz1?uPITS9%+&0BU4C~AwGyxC4uNg0<< z)4|G#La%-fg6nhEmPQJRRdDP}{8J|M%<1*kzSL|ZD%6bWEW0M%ZpSg8NL}|wE2$Nr zGhX4G8qZ`qWJQ_vH~t0gJ}XVJfn3xqD;WoJ4{8=^ECt-%=O)7JhH+1f(O-tw&zvc0 zvM7)4xgX^~YfoiJJmHQEM=~38b8$0YIOj4{|@NR}(AUk(9^$5XUv7wMjP|8D(>hRD8`Ld8Dio5?aAU9q2Va@ZH0+cfOrd zw4>kFBA93D%H->(YDSng~VnbcZuXf4|Fkwg0~^?QNBch-0G_zfXRt63DOQkLK9hXeV-rL)GpvXyyY&{7UH|Mt%JBr)DzzpOP zRlZV*X{mM_9pj2WO2-&6R5u_G6)RNdrfx!*XcxgNxpJnZV+fcQ^z94j4!bVj?;w^* zPEy$2TSE87Pa_n0K97*%00sT8drdkH*4HU|>&DGyPpSg)vYvLyPSjh!>CQS`zo3-1 zjkMX`=uza=7gc9gSWW*w?VV>(lj#=6!{Q<$MM0#9xF|*eNklpVL6i~4Hy)!%G&g}iLGk4dW@!R{pXP$Xy ze)F6&=Xqw%|1Z3xBpr17ARLi{!^vOMZZ@^HdggiVS2gF*z}H<~l92$PPP zZocSa^@nYaw47TvN~g+9@_5kgzWeJhZf0)A4!aoQX1H_lSvXdtm)U9=b)?m5%q%`g zr|jw&$_xlj9c$99)_RK+SJubTJwoG)Y)E*u!N!CRx(zzNNA%wGV&?HjdZgAxZKR9P^tQW3?sw z0J#wJYWpAR00qAzHrF*ixgvLO^*Yi@;zIF|QU4l2 zW>wqHkvY-><(md|J&CJ-V|%RThv{|SK;>3wjoViFICw+LfT7AVw-OMqlR6y>B}t@q4arrT7t6}VRUOy(LUqu@8!cUcN*OxPV$u+h30si+cn{zvs?e?}nE%W0NBB28gbsFN8M~87D;@|8w%B4!QJ|1uA zkPi@Ebjr#cTsa}QDA=mv7N6E;DyAPA@wLgvfe5Vu|F<{9fI}A4NYP4Hg++lr>4h?m z4Xr~yc?pxLKJHFK)2V&Ii&gN+OXu^s-OphKgqk5gv9EmPVySVa#i1kOyu;rQjcnK}?u!2U!>yZ+B zJ_$b9<9c=&QRx&Oo~`RO#8ulAC6! z=Xyp1x6b=3@|%g)?NCRRke$40 zDGE8~f_OHtI1B%oAPVBb5rECA>YO2=2O?74%mM}gp9N&=@*L2$ZXDvNm5s2lVPbzmX_KsS~UDYSvSUhN#FRnTnX1bv$EDEl7FS6zWgik_;V&q zV$;DIM-;7>m*zh7Ms_b1C0^kHOOTY?ugl82SyNlv7IfpwwU!bbBJX3ufW;4D@2<#u zbM>VgP^LIyj$tPhcZE2xRU5`cInwykP)gzkD)Gg@7Jb38>X{nt2%;Kiu>rRzb@^ct zT4^SK%~4cRdrsYsK294f z19j#d8`Y~BIgjL;?7hdiCQA~t1Zp=)`Zj3Qt6JX@?^3)U;#=!{{2G~y7e7+A51$_1q*g|iH1{nwFgkS-F zRp_0j9S!x&>eSknP*qCP-qhafQ>Hh2KK|OHOflAiyLqy~PAh8@JpY$J2K4KDR|P+w zlXw|K7)m(G&Xw*ForoQ+>?;;?>MjD2YXj@gs)1$5F&@{R8I^c&#wn;UPA{qW$Ll7v znEZIr+O59;YN@THuYxANOr zE}<#17Tf#{HqasbEm_7+Zh~s6jZopon(jl2olD*d?^6T2cC-;&^`omRye=(mxwLDh zTb9j|!4gazlIB&UP~G9#oNW&5kGUIT;)%9D_u#@)`t8z=dbRDrkrL|IP^=S8kxf0x zbi^8+;&Mt^reyjKgaDaj`QX83Bh55(@#3+6&^SJ`c>N4J)$3-<^}>KQZDmMyuN8ADw!V&=f4(X=s|r% zOhJM;wfK}>;v`z#=Y^W@C$s&Fb?2AjS?rry$eug3p!Xurb&&bayU+W8AyDPs8Ngp0 zW7$2CM>YzFWh~|gip8p%=n}`aCx{3bFomqI>ez;PMTed_QIF*ggwI1Jnl(a#W37v} z2u$_5d>gNAZI(rccc=Vj*RV*R3lN7TU0-i5&vJ9_HT#W{YOmGw#e zDdYh4sv7ZLBbxDJXUyVI4B~y27gN88gJ>`leqEH0aJCNhO&L-12xq2MIzm117H51_ z?FYn6VdD~ocJxN|OV)HQ4Du9yR|(J{!EaI!hHqE`;v}UX3UFlN*vuEwykxKC-wQp!tAF4K>}g7*xa8f_IEQ*ZsCe7MXt_SI`wt1s zRuAKQk+t==BxY^)gd4RcUc(#F`rBJYW+X5ViBQu^*+2!^7ya#rU&YA;3axRwggjDa znfcEm7HV9oNpvsLWo)r#t$H*r8rJAH{W`&9CzA})n{IZFHtE7nt`e;UcA0KB{|Gzh c-&lNq_)g$Ef$s#q6ZlTxJAuE90AzpU-`@2A;s5{u literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/defaults.parm new file mode 100644 index 00000000000000..34857c95b504c5 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/defaults.parm @@ -0,0 +1,5 @@ +# setup the heater temperature to 45 degree +BRD_HEAT_TARG 45 + +CAN_P1_DRIVER 1 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef-bl.dat new file mode 100644 index 00000000000000..f92599db5bfc2e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef-bl.dat @@ -0,0 +1,51 @@ +# hw definition file for processing by chibios_hwdef.py +# for YJUAV_A6SE_H743 board + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1141 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + +# order of UARTs (and USB). Allow bootloading on USB and Debug +SERIAL_ORDER OTG1 UART7 + +# UART7 DEBUG +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA +define BOOTLOADER_DEBUG SD7 + +# USB +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +PE15 LED_RED OUTPUT OPENDRAIN HIGH # red +PD10 LED_BOOTLOADER OUTPUT OPENDRAIN HIGH # green +PG0 LED_ACTIVITY OUTPUT OPENDRAIN HIGH # blue +define HAL_LED_ON 0 + +# Add CS pins to ensure they are high in bootloader +PE4 IMU1_CS CS +PA0 IMU2_CS CS +PE10 FRAM_CS CS +PE9 BAROMETER_CS CS +PE3 COMPASS_CS CS +PC15 RESERVE_CS CS + +# Extra SPI CS +PE5 EXT_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat new file mode 100644 index 00000000000000..206b3a81bb380c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/YJUAV_A6SE_H743/hwdef.dat @@ -0,0 +1,241 @@ +# hw definition file for processing by chibios_hwdef.py for YJUAV_A6SE_H743 + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 1141 + +env OPTIMIZE -O2 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +FLASH_SIZE_KB 2048 + +# bootloader takes first sector +FLASH_RESERVE_START_KB 128 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART6 USART3 USART1 UART8 UART7 OTG2 + +# now we define the pins that USB is connected on +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# USART2 TELEM1 +PD6 USART2_RX USART2 +PD5 USART2_TX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# USART6 TELEM2 +PC7 USART6_RX USART6 +PC6 USART6_TX USART6 +PG13 USART6_CTS USART6 +PG8 USART6_RTS USART6 + +# USART3 GPS1 +PD9 USART3_RX USART3 NODMA +PD8 USART3_TX USART3 NODMA + +# USART1 GPS2 +PB7 USART1_RX USART1 NODMA +PA9 USART1_TX USART1 NODMA + +# SBUS, DSM port +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# UART7 DEBUG +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# these are the pins for SWD debugging with a STlinkv2 or black-magic probe +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# SPI1 -IMU1 +PB3 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI6 -IMU2 -IMU3 +PA5 SPI6_SCK SPI6 +PA6 SPI6_MISO SPI6 +PA7 SPI6_MOSI SPI6 + +# SPI5 +PF7 SPI5_SCK SPI5 +PF8 SPI5_MISO SPI5 +PF9 SPI5_MOSI SPI5 + +# SPI4 -Extra SPI +PE12 SPI4_SCK SPI4 +PE13 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# sensors cs +PE4 IMU1_CS CS +PA0 IMU2_CS CS +PE10 FRAM_CS CS +PE9 BAROMETER1_CS CS +PE3 BAROMETER2_CS CS +PC15 RESERVE_CS CS + +# Extra SPI CS +PE5 EXT_CS CS + +# I2C buses +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + +PH7 I2C3_SCL I2C3 +PH8 I2C3_SDA I2C3 + +PF14 I2C4_SCL I2C4 +PF15 I2C4_SDA I2C4 + +# order of I2C buses +I2C_ORDER I2C1 I2C2 I2C3 I2C4 + +NODMA I2C* +define STM32_I2C_USE_DMA FALSE +define HAL_I2C_INTERNAL_MASK 1 + +# PWM channels +PA15 TIM2_CH1 TIM2 PWM(1) GPIO(50) BIDIR +PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) +PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) BIDIR +PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) +PA8 TIM1_CH1 TIM1 PWM(5) GPIO(54) BIDIR +PE11 TIM1_CH2 TIM1 PWM(6) GPIO(55) +PA10 TIM1_CH3 TIM1 PWM(7) GPIO(56) BIDIR +PE14 TIM1_CH4 TIM1 PWM(8) GPIO(57) +PB5 TIM3_CH2 TIM3 PWM(9) GPIO(58) +PB0 TIM3_CH3 TIM3 PWM(10) GPIO(59) +PB1 TIM3_CH4 TIM3 PWM(11) GPIO(60) + +# PWM output for buzzer +PD14 TIM4_CH3 TIM4 GPIO(77) ALARM + +# RC input +PI7 TIM8_CH3 TIM8 RCININT PULLUP LOW + +# Analog in +PC4 BATT_CURRENT_SENS ADC1 SCALE(1) +PF11 BATT_VOLTAGE_SENS ADC1 SCALE(1) + +# Analog sys 5v +PF12 VDD_5V_SENS ADC1 SCALE(2) + +# ADC3.3/ADC6.6 +PC5 SPARE1_ADC1 ADC1 SCALE(1) +PC0 SPARE2_ADC1 ADC1 SCALE(2) + +PC1 RSSI_IN ADC1 SCALE(1) + +PC3 FMU_SERVORAIL_VCC_SENS ADC1 SCALE(3) + +# CAN bus +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 + +# GPIOs +PC13 HEATER_EN OUTPUT LOW GPIO(80) +define HAL_HEATER_GPIO_PIN 80 +define HAL_HAVE_IMU_HEATER 1 + +# define default battery setup +define HAL_BATT_VOLT_PIN 2 +define HAL_BATT_CURR_PIN 4 +define HAL_BATT_VOLT_SCALE 21 +define HAL_BATT_CURR_SCALE 34 +define HAL_BATT_MONITOR_DEFAULT 4 + +#analog rssi pin (also could be used as analog airspeed input) +# PC1 +define BOARD_RSSI_ANA_PIN 11 + +# enable pins +PC14 VDD_3V3_SENSORS_EN OUTPUT LOW + +# red LED marked as B/E +PE15 LED_R1 OUTPUT OPENDRAIN HIGH GPIO(0) +PD10 LED_G1 OUTPUT OPENDRAIN LOW GPIO(1) +PG0 LED_B1 OUTPUT OPENDRAIN HIGH GPIO(2) + +define HAL_GPIO_A_LED_PIN 0 +define HAL_GPIO_B_LED_PIN 1 +define HAL_GPIO_C_LED_PIN 2 + +define HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +# use pixracer style 3-LED indicators +define HAL_HAVE_PIXRACER_LED + +# allow to have have a dedicated safety switch pin +define HAL_HAVE_SAFETY_SWITCH 1 +PB15 LED_SAFETY OUTPUT +PA4 SAFETY_IN INPUT PULLDOWN + +# SPI devices +SPIDEV imu1 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ +SPIDEV imu2 SPI6 DEVID1 IMU2_CS MODE3 2*MHZ 8*MHZ +SPIDEV ramtron SPI5 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ +SPIDEV dps310 SPI5 DEVID3 BAROMETER1_CS MODE3 5*MHZ 5*MHZ +SPIDEV ms5611 SPI5 DEVID3 BAROMETER2_CS MODE3 5*MHZ 5*MHZ + +# IMU1 +IMU Invensense SPI:imu1 ROTATION_NONE +IMU Invensensev3 SPI:imu1 ROTATION_NONE + +# IMU2 +IMU Invensense SPI:imu2 ROTATION_NONE +IMU Invensensev3 SPI:imu2 ROTATION_NONE + +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +# baro +BARO DPS310 SPI:dps310 +BARO MS56XX SPI:ms5611 +BARO ICP201XX I2C:0:0x64 + +# compass +define HAL_COMPASS_DISABLE_IST8310_INTERNAL_PROBE +define HAL_PROBE_EXTERNAL_I2C_COMPASSES + +COMPASS IST8310 I2C:ALL_EXTERNAL:0x0E true ROTATION_ROLL_180_YAW_90 +COMPASS IST8310 I2C:0:0x0E false ROTATION_YAW_180 + +# microSD support +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# enable FAT filesystem support (needs a microSD defined via SDMMC) +define HAL_OS_FATFS_IO 1 + +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +# enable RAMTROM parameter storage +define HAL_STORAGE_SIZE 32768 +define HAL_WITH_RAMTRON 1 + +DMA_PRIORITY SPI1* SPI6* TIM*UP* +DMA_NOSHARE SPI1* SPI6* TIM*UP* + From 9285188d85ca543ba68b5c188945f17036fa08d8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 1 Nov 2023 22:34:52 +1100 Subject: [PATCH 090/499] GCS_MAVLink: handle DO_ADSB_OUT_IDENT as both long and int --- libraries/GCS_MAVLink/GCS_Common.cpp | 19 ++++++++----------- 1 file changed, 8 insertions(+), 11 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 0cff164fd2944f..b8831667c95066 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4755,17 +4755,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t break; #endif -#if HAL_ADSB_ENABLED - case MAV_CMD_DO_ADSB_OUT_IDENT: - if ((AP::ADSB() != nullptr) && AP::ADSB()->ident_start()) { - result = MAV_RESULT_ACCEPTED; - } - else { - result = MAV_RESULT_FAILED; - } - break; -#endif - default: result = try_command_long_as_command_int(packet, msg); break; @@ -5045,6 +5034,14 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p case MAV_CMD_DEBUG_TRAP: return handle_command_debug_trap(packet); +#if HAL_ADSB_ENABLED + case MAV_CMD_DO_ADSB_OUT_IDENT: + if ((AP::ADSB() != nullptr) && AP::ADSB()->ident_start()) { + return MAV_RESULT_ACCEPTED; + } + return MAV_RESULT_FAILED; +#endif + case MAV_CMD_DO_AUX_FUNCTION: return handle_command_do_aux_function(packet); From 9445cb2672a640201bf15c6be9485a04bdfaeb62 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Fri, 3 Nov 2023 22:22:27 -0600 Subject: [PATCH 091/499] AP_GPS: Expose COM port and Output Rate in header * This removes magic numbers of hard coding the hardware port and output rate * This also fixes configuring the incorrect hardware port * Now, COM2 (TTL) is configured for GSOF output * The data rate remains the same as before Signed-off-by: Ryan Friedman --- libraries/AP_GPS/AP_GPS_GSOF.cpp | 13 ++++++++----- libraries/AP_GPS/AP_GPS_GSOF.h | 26 +++++++++++++++++++++++++- 2 files changed, 33 insertions(+), 6 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 248e38ef139201..af79dd2339bca7 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -17,6 +17,11 @@ // Trimble GPS driver for ArduPilot. // Code by Michael Oborne // +// Usage in SITL with hardware for debugging: +// sim_vehicle.py -v Plane -A "--serial3=uart:/dev/ttyUSB0" --console --map -DG +// param set GPS_TYPE 11 // GSOF +// param set SERIAL3_PROTOCOL 5 // GPS +// #define ALLOW_DOUBLE_MATH_FUNCTIONS @@ -70,8 +75,7 @@ AP_GPS_GSOF::read(void) if (gsofmsgreq_index < (sizeof(gsofmsgreq))) { if (now > gsofmsg_time) { - requestGSOF(gsofmsgreq[gsofmsgreq_index], 0); - requestGSOF(gsofmsgreq[gsofmsgreq_index], 3); + requestGSOF(gsofmsgreq[gsofmsgreq_index], HW_Port::COM2, Output_Rate::FREQ_10_HZ); gsofmsg_time = now + 110; gsofmsgreq_index++; } @@ -167,16 +171,15 @@ AP_GPS_GSOF::requestBaud(const uint8_t portindex) } void -AP_GPS_GSOF::requestGSOF(const uint8_t messagetype, const uint8_t portindex) +AP_GPS_GSOF::requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz) { uint8_t buffer[21] = {0x02,0x00,0x64,0x0f,0x00,0x00,0x00, // application file record 0x03,0x00,0x01,0x00, // file control information block - 0x07,0x06,0x0a,portindex,0x01,0x00,0x01,0x00, // output message record + 0x07,0x06,0x0a,static_cast(portIndex),static_cast(rateHz),0x00,messageType,0x00, // output message record 0x00,0x03 }; // checksum buffer[4] = packetcount++; - buffer[17] = messagetype; uint8_t checksum = 0; for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) { diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index 8c8d56748a049c..fe3b0cf8f6e64e 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -40,15 +40,39 @@ class AP_GPS_GSOF : public AP_GPS_Backend private: + // A subset of the port identifiers in the GSOF protocol that are used for serial. + // Ethernet, USB, etc are not supported by the GPS driver at this time so they are omitted. + // These values are not documented in the API. + enum class HW_Port { + COM1 = 3, // RS232 serial + COM2 = 1, // TTL serial + }; + + // A subset of the data frequencies in the GSOF protocol that are used for serial. + // These values are not documented in the API. + enum class Output_Rate { + FREQ_10_HZ = 1, + FREQ_50_HZ = 15, + FREQ_100_HZ = 16, + }; + bool parse(const uint8_t temp) WARN_IF_UNUSED; bool process_message() WARN_IF_UNUSED; void requestBaud(const uint8_t portindex); - void requestGSOF(const uint8_t messagetype, const uint8_t portindex); + + // Send a request to the GPS to enable a message type on the port at the specified rate. + // Note - these request functions currently ignore the ACK from the device. + // If the device is already sending serial traffic, there is no mechanism to prevent conflict. + // According to the manufacturer, the best approach is to switch to ethernet. + void requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz); + double SwapDouble(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; float SwapFloat(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; uint32_t SwapUint32(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; uint16_t SwapUint16(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; + bool validate_baud(const uint8_t baud) const WARN_IF_UNUSED; + struct Msg_Parser { From 1d08900cb07be4890d656ddc9edba3ddd6846498 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Nov 2023 22:33:00 +1100 Subject: [PATCH 092/499] GCS_MAVLink: handle MAV_CMD_DO_SPRAYER as both long and int --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 12 ++++++------ 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 7ba2c0c2c8b460..94c938f6c57021 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -658,7 +658,7 @@ class GCS_MAVLINK MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc); MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_sprayer(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_do_sprayer(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_set_mode(const mavlink_command_int_t &packet); MAV_RESULT handle_command_get_home_position(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_fence_enable(const mavlink_command_int_t &packet); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index b8831667c95066..ba7d573c540abf 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4584,7 +4584,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_long_t & #endif // AP_GRIPPER_ENABLED #if HAL_SPRAYER_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_do_sprayer(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_do_sprayer(const mavlink_command_int_t &packet) { AC_Sprayer *sprayer = AP::sprayer(); if (sprayer == nullptr) { @@ -4731,11 +4731,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t result = handle_command_do_gripper(packet); break; #endif -#if HAL_SPRAYER_ENABLED - case MAV_CMD_DO_SPRAYER: - result = handle_command_do_sprayer(packet); - break; -#endif #if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: { @@ -5056,6 +5051,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p case MAV_CMD_DO_SET_MODE: return handle_command_do_set_mode(packet); +#if HAL_SPRAYER_ENABLED + case MAV_CMD_DO_SPRAYER: + return handle_command_do_sprayer(packet); +#endif + #if AP_CAMERA_ENABLED case MAV_CMD_DO_DIGICAM_CONFIGURE: case MAV_CMD_DO_DIGICAM_CONTROL: From 387aa63b90a4730b594cc02aecfcae311f61bcb3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 3 Nov 2023 22:33:00 +1100 Subject: [PATCH 093/499] Tools: handle MAV_CMD_DO_SPRAYER as both long and int --- Tools/autotest/arducopter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 8703b161d142da..1cb332597dfa97 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -9851,7 +9851,7 @@ def Sprayer(self): self.start_subtest("Checking mavlink commands") self.progress("Starting Sprayer") - self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=1) + self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_SPRAYER, p1=1) self.progress("Testing speed-ramping") self.wait_servo_channel_value( From 57df5651761dcc217ed7b8634a2de77ba32473de Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 5 Nov 2023 08:00:07 -0600 Subject: [PATCH 094/499] RC_Channel: expand explanations in FWD THR docs --- libraries/RC_Channel/RC_Channel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index c8179e325995d7..fac080b717a4e6 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -228,12 +228,12 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Copter, Rover, Plane}: 165:Arm/Emergency Motor Stop // @Values{Copter, Rover, Plane, Blimp}: 166:Camera Record Video, 167:Camera Zoom, 168:Camera Manual Focus, 169:Camera Auto Focus // @Values{Plane}: 170:QSTABILIZE Mode - // @Values{Plane}: 176:Quadplane Fwd Throttle Override enable // @Values{Copter, Rover, Plane, Blimp}: 171:Calibrate Compasses // @Values{Copter, Rover, Plane, Blimp}: 172:Battery MPPT Enable // @Values{Plane}: 173:Plane AUTO Mode Landing Abort // @Values{Copter, Rover, Plane, Blimp}: 174:Camera Image Tracking // @Values{Copter, Rover, Plane, Blimp}: 175:Camera Lens + // @Values{Plane}: 176:Quadplane Fwd Throttle Override enable // @Values{Rover}: 201:Roll // @Values{Rover}: 202:Pitch // @Values{Rover}: 207:MainSail From 73f58d3624f5bcc855435681cf7542a70af28c8f Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 5 Nov 2023 08:00:07 -0600 Subject: [PATCH 095/499] ArduPlane: expand explanations in FWD THR docs --- ArduPlane/quadplane.cpp | 4 ++-- ArduPlane/tiltrotor.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 839d76b92dc5d8..0a5c724fc82b65 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -167,7 +167,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = { // @Param: VFWD_GAIN // @DisplayName: Forward velocity hold gain - // @Description: The use of this parameter is no longer recommended and has been superseded by a method that works in all VTOL modes with the exception of autotune which is controlled by the Q_FWD_THR_USE parameter. This Q_VFD_GAIN parameter controls use of the forward motor in VTOL modes that use the velocity controller. Set to 0 to disable this function. A value of 0.05 is a good place to start if you want to use the forward motor for position control. No forward motor will be used in QSTABILIZE or QHOVER modes. Use QLOITER for position hold with the forward motor. + // @Description: The use of this parameter is no longer recommended and has been superseded by a method that works in all VTOL modes with the exception of QAUTOTUNE which is controlled by the Q_FWD_THR_USE parameter. This Q_VFD_GAIN parameter controls use of the forward motor in VTOL modes that use the velocity controller. Set to 0 to disable this function. A value of 0.05 is a good place to start if you want to use the forward motor for position control. No forward motor will be used in QSTABILIZE or QHOVER modes. Use with QLOITER for position hold with the forward motor. // @Range: 0 0.5 // @Increment: 0.01 // @User: Standard @@ -507,7 +507,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Param: FWD_THR_GAIN // @DisplayName: Q mode fwd throttle gain - // @Description: This parameter sets the gain from forward accel/tilt to forward throttle in Q modes. The Q modes this feature operates in is controlled by the Q_FWD_THR_USE parameter. Vehicles using separate forward thrust motors, eg quadplanes, should set this parameter to (all up weight) / (maximum combined thrust of forward motors) with a value of 2 being typical. Vehicles that tilt lifting rotors to provide forward thrust should set this parameter to (all up weight) / (weight lifted by tilting rotors) which for most aircraft can be approximated as (total number of lifting rotors) / (number of lifting rotors that tilt). When using this method of forward throttle control, the forward tilt angle limit is controlled by the Q_FWD_PIT_LIM parameter. + // @Description: This parameter sets the gain from forward accel/tilt to forward throttle in certain Q modes. The Q modes this feature operates in is controlled by the Q_FWD_THR_USE parameter. Vehicles using separate forward thrust motors, eg quadplanes, should set this parameter to (all up weight) / (maximum combined thrust of forward motors) with a value of 2 being typical. Vehicles that tilt lifting rotors to provide forward thrust should set this parameter to (all up weight) / (weight lifted by tilting rotors) which for most aircraft can be approximated as (total number of lifting rotors) / (number of lifting rotors that tilt). When using this method of forward throttle control, the forward tilt angle limit is controlled by the Q_FWD_PIT_LIM parameter. // @Range: 0.0 5.0 // @Increment: 0.1 // @User: Standard diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index e8babe5e86d93b..0be2a078452826 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -260,8 +260,8 @@ void Tiltrotor::continuous_update(void) we are in a VTOL mode. We need to work out how much tilt is needed. There are 5 strategies we will use: - 1) With use of a forward throttle controlled by Q_FWD_THR_GAIN in all - VTOL modes except Q_AUTOTUNE, we set the angle based on a calculated + 1) With use of a forward throttle controlled by Q_FWD_THR_GAIN in + VTOL modes except Q_AUTOTUNE determined by Q_FWD_THR_USE. We set the angle based on a calculated forward throttle. 2) With manual forward throttle control we set the angle based on the From a318ef333d77cb3e9c2432be31ce9dc6a798625f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 Nov 2023 15:51:26 +1100 Subject: [PATCH 096/499] Plane: release notes for 4.4.3-beta1 --- ArduPlane/ReleaseNotes.txt | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index c6aca9db6e61cc..2dc429c325ad95 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -1,3 +1,20 @@ +Release 4.4.3-beta1 4th November 2023 +------------------------------------- + +Changes from 4.4.2: + + - fixed setup of ICM45486 IMU on CubeOrangePlus-BG edition + - disable AFSR on IxM42xxx IMUs to prevent gyro bias for "stuck" gyros + - fixed AK09916 compass being non-responsive + - implement GPS_DRV_OPTION for using ellipsoid height in more GPS drivers + - fixed SIYI AP_Mount parsing bug + - configuration fixes for BETAFTP-F405 boards + - fixed origin versus home relative bug in quadplane landing and guided takeoff + - correct mavlink response for no airspeed sensor on preflight calibration + - protect against notch filtering with uninitialised RPM source in ESC telemetry + - allow lua scripts to populate full ESC telemetry data + - added YJUAV_A6SE_H743 support + Release 4.4.2 23th October 2023 ------------------------------- From a288e585ed61e7daff73d479b0c4c76cdc64e14b Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Mon, 6 Nov 2023 13:28:21 -0300 Subject: [PATCH 097/499] Sub: Version to 4.5.0-dev --- ArduSub/version.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduSub/version.h b/ArduSub/version.h index 5671b5c762863c..b163a7bf69b207 100644 --- a/ArduSub/version.h +++ b/ArduSub/version.h @@ -6,13 +6,13 @@ #include "ap_version.h" -#define THISFIRMWARE "ArduSub V4.2.0-dev" +#define THISFIRMWARE "ArduSub V4.5.0-dev" // the following line is parsed by the autotest scripts -#define FIRMWARE_VERSION 4,2,0,FIRMWARE_VERSION_TYPE_DEV +#define FIRMWARE_VERSION 4,5,0,FIRMWARE_VERSION_TYPE_DEV #define FW_MAJOR 4 -#define FW_MINOR 2 +#define FW_MINOR 5 #define FW_PATCH 0 #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV From 289db1e84bd159a15beb3543fd5d4087153b8119 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 7 Nov 2023 12:19:34 +0900 Subject: [PATCH 098/499] Rover: 4.4.0-beta9 release notes --- Rover/release-notes.txt | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/Rover/release-notes.txt b/Rover/release-notes.txt index e6957078113187..95fa148ce58834 100644 --- a/Rover/release-notes.txt +++ b/Rover/release-notes.txt @@ -1,5 +1,20 @@ Rover Release Notes: ------------------------------------------------------------------ +Rover 4.4.0-beta9 07-Nov-2023 +Changes from 4.4.2 +1) Autopilot related enhancements and fixes + - BETAFTP-F405 board configuration fixes + - CubeOrangePlus-BG edition ICM45486 IMU setup fixed + - YJUAV_A6SE_H743 support +2) Minor enhancements + - GPS_DRV_OPTION allows using ellipsoid height in more GPS drivers + - Lua script support for fully populating ESC telemetry data +3) Bug fixes + - AK09916 compass being non-responsive fixed + - IxM42xxx IMUs "stuck" gyros fixed + - Notch filtering protection when using uninitialised RPM source in ESC telemetry + - SIYI gimbal driver parsing bug fixed (was causing lost packets) +------------------------------------------------------------------ Rover 4.4.0-beta8 13-Oct-2023 Changes from 4.4.0-beta7 1) Autopilot related enhancements and fixes From bbfc949b45277120842996077187b7eb709505e1 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 7 Nov 2023 12:20:17 +0900 Subject: [PATCH 099/499] Copter: 4.4.3-beta1 release notes --- ArduCopter/ReleaseNotes.txt | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index 4e0319b51cddef..941e75014cac48 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,5 +1,21 @@ ArduPilot Copter Release Notes: ------------------------------------------------------------------ +Copter 4.4.3-beta1 07-Nov-2023 +Changes from 4.4.2 +1) Autopilot related enhancements and fixes + - BETAFTP-F405 board configuration fixes + - CubeOrangePlus-BG edition ICM45486 IMU setup fixed + - YJUAV_A6SE_H743 support +2) Minor enhancements + - GPS_DRV_OPTION allows using ellipsoid height in more GPS drivers + - Lua script support for fully populating ESC telemetry data +3) Bug fixes + - AK09916 compass being non-responsive fixed + - IxM42xxx IMUs "stuck" gyros fixed + - MAVLink response fixed when no airspeed sensor during preflight calibration + - Notch filtering protection when using uninitialised RPM source in ESC telemetry + - SIYI gimbal driver parsing bug fixed (was causing lost packets) +------------------------------------------------------------------ Copter 4.4.2 22-Oct-2023 / Copter 4.4.2-beta1 13-Oct-2023 Changes from 4.4.1 1) Autopilot related enhancements and fixes From 2d9346e85a77cc39c2b93c319678149ef9015372 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 7 Nov 2023 17:12:11 +1100 Subject: [PATCH 100/499] AP_GPS: correct uBlox M10 configuration on minimised boards --- libraries/AP_GPS/AP_GPS_UBLOX.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 343587c68e55e5..323a0f0f1cbbb6 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -930,7 +930,6 @@ uint8_t AP_GPS_UBLOX::config_key_size(ConfigKey key) const */ int8_t AP_GPS_UBLOX::find_active_config_index(ConfigKey key) const { -#if GPS_MOVING_BASELINE if (active_config.list == nullptr) { return -1; } @@ -939,7 +938,7 @@ int8_t AP_GPS_UBLOX::find_active_config_index(ConfigKey key) const return (int8_t)i; } } -#endif + return -1; } From d2a3fed4a17d2fd99f9566cac78c6ee33c04e6c4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 10:05:23 +1100 Subject: [PATCH 101/499] hwdef: AP_BATTERY_ESC_ENABLED needs HAL_WITH_ESC_TELEM --- libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc index d083fd585ee347..4461774aa45606 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc @@ -61,7 +61,7 @@ define AP_BEACON_ENABLED 0 # restricted battery backends: define AP_BATTERY_BACKEND_DEFAULT_ENABLED 0 define AP_BATTERY_ANALOG_ENABLED 1 -define AP_BATTERY_ESC_ENABLED 1 +define AP_BATTERY_ESC_ENABLED HAL_WITH_ESC_TELEM define AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED HAL_ENABLE_DRONECAN_DRIVERS define AP_BATTERY_SUM_ENABLED 1 define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 1 From b69879fe8757ff6242a212abd5a1825f8d1d630c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 7 Nov 2023 12:13:49 +1100 Subject: [PATCH 102/499] autotest: add test for battery reset --- Tools/autotest/rover.py | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index b61950f1248fb2..ab13d592fc7679 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6614,6 +6614,20 @@ def MAV_CMD_DO_FENCE_ENABLE(self): self.run_cmd_int(mavutil.mavlink.MAV_CMD_DO_FENCE_ENABLE, p1=0) self.assert_fence_disabled() + def MAV_CMD_BATTERY_RESET(self): + '''manipulate battery levels with MAV_CMD_BATTERY_RESET''' + for (run_cmd, value) in (self.run_cmd, 56), (self.run_cmd_int, 97): + run_cmd( + mavutil.mavlink.MAV_CMD_BATTERY_RESET, + p1=65535, # battery mask + p2=value, + ) + self.assert_received_message_field_values('BATTERY_STATUS', { + "battery_remaining": value, + }, { + "poll": True, + }) + def tests(self): '''return list of all tests''' ret = super(AutoTestRover, self).tests() @@ -6697,6 +6711,7 @@ def tests(self): self.MAV_CMD_DO_SET_REVERSE, self.MAV_CMD_GET_HOME_POSITION, self.MAV_CMD_DO_FENCE_ENABLE, + self.MAV_CMD_BATTERY_RESET, ]) return ret From 09ab14c69f2f2a1182dc87573b189821f487077e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 7 Nov 2023 12:14:07 +1100 Subject: [PATCH 103/499] GCS_MAVLink: handle battery reset as both long and int --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 14 +++++++------- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 94c938f6c57021..695cf157efaf92 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -640,7 +640,7 @@ class GCS_MAVLINK virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_battery_reset(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_battery_reset(const mavlink_command_int_t &packet); void handle_command_long(const mavlink_message_t &msg); MAV_RESULT handle_command_accelcal_vehicle_pos(const mavlink_command_int_t &packet); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index ba7d573c540abf..35bfe5159a551c 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4476,7 +4476,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_comm } #if AP_BATTERY_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_int_t &packet) { const uint16_t battery_mask = packet.param1; const float percentage = packet.param2; @@ -4744,12 +4744,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t result = handle_command_do_set_mission_current(packet); break; -#if AP_BATTERY_ENABLED - case MAV_CMD_BATTERY_RESET: - result = handle_command_battery_reset(packet); - break; -#endif - default: result = try_command_long_as_command_int(packet, msg); break; @@ -5016,6 +5010,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p case MAV_CMD_AIRFRAME_CONFIGURATION: return handle_command_airframe_configuration(packet); #endif + +#if AP_BATTERY_ENABLED + case MAV_CMD_BATTERY_RESET: + return handle_command_battery_reset(packet); +#endif + #if HAL_CANMANAGER_ENABLED case MAV_CMD_CAN_FORWARD: return handle_can_forward(packet, msg); From abf32906d244e5760a0551d91c9cc223357d78bb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 7 Nov 2023 12:01:01 +1100 Subject: [PATCH 104/499] GCS_MAVLink: support gripper commands as both long and int --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 13 ++++++------- 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 695cf157efaf92..7dbd32ef4be56e 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -657,7 +657,7 @@ class GCS_MAVLINK MAV_RESULT handle_command_camera(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc); - MAV_RESULT handle_command_do_gripper(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_do_gripper(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_sprayer(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_set_mode(const mavlink_command_int_t &packet); MAV_RESULT handle_command_get_home_position(const mavlink_command_int_t &packet); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 35bfe5159a551c..fb5615cf3541a7 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4552,7 +4552,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_set_ekf_source_set(const mavlink_command_ } #if AP_GRIPPER_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_int_t &packet) { AP_Gripper *gripper = AP::gripper(); if (gripper == nullptr) { @@ -4726,12 +4726,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t switch (packet.command) { -#if AP_GRIPPER_ENABLED - case MAV_CMD_DO_GRIPPER: - result = handle_command_do_gripper(packet); - break; -#endif - #if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: { result = handle_command_request_autopilot_capabilities(packet); @@ -5048,6 +5042,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p case MAV_CMD_DO_FLIGHTTERMINATION: return handle_flight_termination(packet); +#if AP_GRIPPER_ENABLED + case MAV_CMD_DO_GRIPPER: + return handle_command_do_gripper(packet); +#endif + case MAV_CMD_DO_SET_MODE: return handle_command_do_set_mode(packet); From 8d03d7e15d333c3e56b490c4a6741f1e496c144e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 7 Nov 2023 11:41:29 +1100 Subject: [PATCH 105/499] autotest: test gripper as both long and int ... and make use of context_collect for statustext --- Tools/autotest/vehicle_test_suite.py | 82 ++++++++++------------------ 1 file changed, 30 insertions(+), 52 deletions(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 41289802504939..543bb6d5d04963 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -10297,62 +10297,40 @@ def GripperType(self, gripper_type): self.set_rc(9, 2000) self.wait_text("Gripper load grabb", check_context=True) self.progress("Test gripper with Mavlink cmd") + + self.context_collect('STATUSTEXT') self.progress("Releasing load") - self.wait_text("Gripper load releas", - the_function=lambda: self.mav.mav.command_long_send(1, - 1, - mavutil.mavlink.MAV_CMD_DO_GRIPPER, - 0, - 1, - mavutil.mavlink.GRIPPER_ACTION_RELEASE, - 0, - 0, - 0, - 0, - 0, - )) + self.run_cmd( + mavutil.mavlink.MAV_CMD_DO_GRIPPER, + p1=1, + p2=mavutil.mavlink.GRIPPER_ACTION_RELEASE + ) + self.wait_text("Gripper load releas", check_context=True) self.progress("Grabbing load") - self.wait_text("Gripper load grabb", - the_function=lambda: self.mav.mav.command_long_send(1, - 1, - mavutil.mavlink.MAV_CMD_DO_GRIPPER, - 0, - 1, - mavutil.mavlink.GRIPPER_ACTION_GRAB, - 0, - 0, - 0, - 0, - 0, - )) + self.run_cmd( + mavutil.mavlink.MAV_CMD_DO_GRIPPER, + p1=1, + p2=mavutil.mavlink.GRIPPER_ACTION_GRAB + ) + self.wait_text("Gripper load grabb", check_context=True) + + self.context_clear_collection('STATUSTEXT') self.progress("Releasing load") - self.wait_text("Gripper load releas", - the_function=lambda: self.mav.mav.command_long_send(1, - 1, - mavutil.mavlink.MAV_CMD_DO_GRIPPER, - 0, - 1, - mavutil.mavlink.GRIPPER_ACTION_RELEASE, - 0, - 0, - 0, - 0, - 0, - )) + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_DO_GRIPPER, + p1=1, + p2=mavutil.mavlink.GRIPPER_ACTION_RELEASE + ) + self.wait_text("Gripper load releas", check_context=True) + self.progress("Grabbing load") - self.wait_text("Gripper load grabb", - the_function=lambda: self.mav.mav.command_long_send(1, - 1, - mavutil.mavlink.MAV_CMD_DO_GRIPPER, - 0, - 1, - mavutil.mavlink.GRIPPER_ACTION_GRAB, - 0, - 0, - 0, - 0, - 0, - )) + self.run_cmd_int( + mavutil.mavlink.MAV_CMD_DO_GRIPPER, + p1=1, + p2=mavutil.mavlink.GRIPPER_ACTION_GRAB + ) + self.wait_text("Gripper load grabb", check_context=True) + self.context_pop() self.reboot_sitl() From 5e61e4cdc5d965007fd11389e90172e55a279802 Mon Sep 17 00:00:00 2001 From: Jonathan Loong Date: Wed, 25 Oct 2023 23:22:24 -0700 Subject: [PATCH 106/499] AP_BattMonitor: Addition of AD7091R5 ADC I2C Read Driver This is an ADC extender based on I2C which is used to read the current and voltage. Enable AD7091R5 in config.h which was reserved previously --- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 6 + libraries/AP_BattMonitor/AP_BattMonitor.h | 3 +- .../AP_BattMonitor_AD7091R5.cpp | 236 ++++++++++++++++++ .../AP_BattMonitor/AP_BattMonitor_AD7091R5.h | 75 ++++++ .../AP_BattMonitor/AP_BattMonitor_Params.cpp | 2 +- .../AP_BattMonitor/AP_BattMonitor_config.h | 3 + 6 files changed, 323 insertions(+), 2 deletions(-) create mode 100644 libraries/AP_BattMonitor/AP_BattMonitor_AD7091R5.cpp create mode 100644 libraries/AP_BattMonitor/AP_BattMonitor_AD7091R5.h diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 5f1ecf8f7382d5..f1d7710bc6551d 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -20,6 +20,7 @@ #include "AP_BattMonitor_Torqeedo.h" #include "AP_BattMonitor_FuelLevel_Analog.h" #include "AP_BattMonitor_Synthetic_Current.h" +#include "AP_BattMonitor_AD7091R5.h" #include @@ -554,6 +555,11 @@ AP_BattMonitor::init() drivers[instance] = new AP_BattMonitor_EFI(*this, state[instance], _params[instance]); break; #endif // AP_BATTERY_EFI_ENABLED +#if AP_BATTERY_AD7091R5_ENABLED + case Type::AD7091R5: + drivers[instance] = new AP_BattMonitor_AD7091R5(*this, state[instance], _params[instance]); + break; +#endif// AP_BATTERY_AD7091R5_ENABLED case Type::NONE: default: break; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index 78311d25412396..dbeed2e470ff18 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -65,6 +65,7 @@ class AP_BattMonitor friend class AP_BattMonitor_INA2XX; friend class AP_BattMonitor_INA239; friend class AP_BattMonitor_LTC2946; + friend class AP_BattMonitor_AD7091R5; friend class AP_BattMonitor_Torqeedo; friend class AP_BattMonitor_FuelLevel_Analog; @@ -107,7 +108,7 @@ class AP_BattMonitor Analog_Volt_Synthetic_Current = 25, INA239_SPI = 26, EFI = 27, - // AD7091R5_I2C_Analog = 28, reserve ID for future use + AD7091R5 = 28, }; FUNCTOR_TYPEDEF(battery_failsafe_handler_fn_t, void, const char *, const int8_t); diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_AD7091R5.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_AD7091R5.cpp new file mode 100644 index 00000000000000..70e37eab43c420 --- /dev/null +++ b/libraries/AP_BattMonitor/AP_BattMonitor_AD7091R5.cpp @@ -0,0 +1,236 @@ +#include "AP_BattMonitor_AD7091R5.h" + +/** + * @brief You can use it to Read Current and voltage of 1-3 batteries from a ADC extender IC over I2C. + * AD7091R5 is a ADC extender and we are using it to read current and voltage of multiple batteries. + * Examples of Pin combination: + * 1)Pin 50 = Voltage 51,52,53 = Current. For 3 battery combination Voltage will be same accross. + * 2)Pin 50,51 = Voltage and Current Battery 1 - Pin 52,53 = Voltage and Current Battery 2 + * Only the First instance of Battery Monitor will be reading the values from IC over I2C. + * Make sure you understand the method of calculation used in this driver before using it. + * e.g. using pin 1 on IC to read voltage of 2 batteries and pin 2 and 3 to read current from individual battery. + * Pin number represents 50 = pin 1, 51 = pin 2 and so on 52, 53 + * BATT2_Monitor = 24 , BATT3_Monitor = 24 + * BATT2_VOLT_PIN = 50 , BATT3_VOLT_PIN = 50 + * BATT2_CURR_PIN = 51 , BATT3_CURR_PIN = 52 + * + * + */ + +#if AP_BATTERY_AD7091R5_ENABLED + +#include +#include +#include + +//macro defines +#define AD7091R5_I2C_ADDR 0x2F // A0 and A1 tied to GND +#define AD7091R5_I2C_BUS 0 +#define AD7091R5_RESET 0x02 +#define AD7091R5_RESULT_ADDR 0x00 +#define AD7091R5_CHAN_ADDR 0x01 +#define AD7091R5_CONF_ADDR 0x02 +#define AD7091R5_CH_ID(x) ((x >> 5) & 0x03) +#define AD7091R5_RES_MASK 0x0F +#define AD7091R5_REF 3.3f +#define AD7091R5_RESOLUTION (float)4096 +#define AD7091R5_PERIOD_USEC 100000 +#define AD7091R5_BASE_PIN 50 + + +extern const AP_HAL::HAL& hal; +const AP_Param::GroupInfo AP_BattMonitor_AD7091R5::var_info[] = { + + // @Param: VOLT_PIN + // @DisplayName: Battery Voltage sensing pin on the AD7091R5 Ic + // @Description: Sets the analog input pin that should be used for voltage monitoring on AD7091R5. + // @Values: -1:Disabled + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO("VOLT_PIN", 56, AP_BattMonitor_AD7091R5, _volt_pin, 0), + + // @Param: CURR_PIN + // @DisplayName: Battery Current sensing pin + // @Description: Sets the analog input pin that should be used for Current monitoring on AD7091R5. + // @Values: -1:Disabled + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO("CURR_PIN", 57, AP_BattMonitor_AD7091R5, _curr_pin, 0), + + // @Param: VOLT_MULT + // @DisplayName: Voltage Multiplier + // @Description: Used to convert the voltage of the voltage sensing pin (@PREFIX@VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). + // @User: Advanced + AP_GROUPINFO("VOLT_MULT", 58, AP_BattMonitor_AD7091R5, _volt_multiplier, 0), + + // @Param: AMP_PERVLT + // @DisplayName: Amps per volt + // @Description: Number of amps that a 1V reading on the current sensor corresponds to. + // @Units: A/V + // @User: Standard + AP_GROUPINFO("AMP_PERVLT", 59, AP_BattMonitor_AD7091R5, _curr_amp_per_volt, 0), + + // @Param: AMP_OFFSET + // @DisplayName: AMP offset + // @Description: Voltage offset at zero current on current sensor + // @Units: V + // @User: Standard + AP_GROUPINFO("AMP_OFFSET", 60, AP_BattMonitor_AD7091R5, _curr_amp_offset, 0), + + // @Param: VLT_OFFSET + // @DisplayName: Volage offset + // @Description: Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied + // @Units: V + // @User: Advanced + AP_GROUPINFO("VLT_OFFSET", 61, AP_BattMonitor_AD7091R5, _volt_offset, 0), + + // Param indexes must be 56 to 61 to avoid conflict with other battery monitor param tables loaded by pointer + + AP_GROUPEND +}; + + +//Variable initialised to read from first instance. +AP_BattMonitor_AD7091R5::AnalogData AP_BattMonitor_AD7091R5::_analog_data[AD7091R5_NO_OF_CHANNELS]; +bool AP_BattMonitor_AD7091R5::_first = true; +bool AP_BattMonitor_AD7091R5::_health = false; + +/** + * @brief Construct a new ap battmonitor ad7091r5::ap battmonitor ad7091r5 object + * + * @param mon + * @param mon_state + * @param params + */ +AP_BattMonitor_AD7091R5::AP_BattMonitor_AD7091R5(AP_BattMonitor &mon, + AP_BattMonitor::BattMonitor_State &mon_state, + AP_BattMonitor_Params ¶ms) : + AP_BattMonitor_Backend(mon, mon_state, params) +{ + AP_Param::setup_object_defaults(this, var_info); + _state.var_info = var_info; +} + +/** + * @brief probe and initialize the sensor and register call back + * + */ +void AP_BattMonitor_AD7091R5::init() +{ + // voltage and current pins from params and check if there are in range + if (_volt_pin.get() >= AD7091R5_BASE_PIN && _volt_pin.get() <= AD7091R5_BASE_PIN + AD7091R5_NO_OF_CHANNELS && + _curr_pin.get() >= AD7091R5_BASE_PIN && _curr_pin.get() <= AD7091R5_BASE_PIN + AD7091R5_NO_OF_CHANNELS) { + volt_buff_pt = _volt_pin.get() - AD7091R5_BASE_PIN; + curr_buff_pt = _curr_pin.get() - AD7091R5_BASE_PIN; + } + else{ + return; //pin values are out of range + } + + // only the first instance read the i2c device + if (_first) { + _first = false; + // probe i2c device + _dev = hal.i2c_mgr->get_device(AD7091R5_I2C_BUS, AD7091R5_I2C_ADDR); + + if (_dev) { + WITH_SEMAPHORE(_dev->get_semaphore()); + _dev->set_retries(10); // lots of retries during probe + //Reset and config device + if (_initialize()) { + _dev->set_retries(2); // drop to 2 retries for runtime + _dev->register_periodic_callback(AD7091R5_PERIOD_USEC, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_AD7091R5::_read_adc, void)); + } + } + } +} + +/** + * @brief read - read the voltage and curren + * + */ +void AP_BattMonitor_AD7091R5::read() +{ + + WITH_SEMAPHORE(sem); + //copy global health status to all instances + _state.healthy = _health; + + //return if system not healthy + if (!_state.healthy) { + return; + } + + //voltage conversion + _state.voltage = (_data_to_volt(_analog_data[volt_buff_pt].data) - _volt_offset) * _volt_multiplier; + + //current amps conversion + _state.current_amps = (_data_to_volt(_analog_data[curr_buff_pt].data) - _curr_amp_offset) * _curr_amp_per_volt; + + // calculate time since last current read + uint32_t tnow = AP_HAL::micros(); + uint32_t dt_us = tnow - _state.last_time_micros; + + // update total current drawn since startup + update_consumed(_state, dt_us); + + // record time + _state.last_time_micros = tnow; +} + +/** + * @brief read all four channels and store the results + * + */ +void AP_BattMonitor_AD7091R5::_read_adc() +{ + uint8_t data[AD7091R5_NO_OF_CHANNELS*2]; + //reset and reconfigure IC if health status is not good. + if (!_state.healthy) { + _initialize(); + } + //read value + bool ret = _dev->transfer(nullptr, 0, data, sizeof(data)); + WITH_SEMAPHORE(sem); + if (ret) { + for (int i=0; itransfer(data, sizeof(data), nullptr, 0)){ + //command mode, use external 3.3 reference, all channels enabled, set address pointer register to read the adc results + uint8_t data_2[6] = {AD7091R5_CONF_ADDR, AD7091R5_CONF_CMD, AD7091R5_CONF_PDOWN0, AD7091R5_CHAN_ADDR, AD7091R5_CHAN_ALL, AD7091R5_RESULT_ADDR}; + return _dev->transfer(data_2, sizeof(data_2), nullptr, 0); + } + return false; +} + +/** + * @brief convert binary reading to volts + * + * @param data + * @return float + */ +float AP_BattMonitor_AD7091R5::_data_to_volt(uint32_t data) +{ + return (AD7091R5_REF/AD7091R5_RESOLUTION)*data; +} + +#endif // AP_BATTERY_AD7091R5_ENABLED diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_AD7091R5.h b/libraries/AP_BattMonitor/AP_BattMonitor_AD7091R5.h new file mode 100644 index 00000000000000..e99c7e662094e8 --- /dev/null +++ b/libraries/AP_BattMonitor/AP_BattMonitor_AD7091R5.h @@ -0,0 +1,75 @@ +#pragma once + +#include "AP_BattMonitor_Backend.h" + +#ifndef AP_BATTERY_AD7091R5_ENABLED +#define AP_BATTERY_AD7091R5_ENABLED (BOARD_FLASH_SIZE > 1024) +#endif + +#if AP_BATTERY_AD7091R5_ENABLED + +#include +#include + +#define AD7091R5_NO_OF_CHANNELS 4 +#define AD7091R5_CONF_CMD 0x04 +#define AD7091R5_CHAN_ALL 0x0F +#define AD7091R5_CONF_PDOWN0 0x00 +#define AD7091R5_CONF_PDOWN2 0x02 +#define AD7091R5_CONF_PDOWN3 0x03 +#define AD7091R5_CONF_PDOWN_MASK 0x03 + +class AP_BattMonitor_AD7091R5 : public AP_BattMonitor_Backend +{ +public: + // Constructor + AP_BattMonitor_AD7091R5(AP_BattMonitor &mon, + AP_BattMonitor::BattMonitor_State &mon_state, + AP_BattMonitor_Params ¶ms); + + // Read the battery voltage and current. Should be called at 10hz + void read() override; + void init(void) override; + + // returns true if battery monitor provides consumed energy info + bool has_consumed_energy() const override + { + return has_current(); + } + + // returns true if battery monitor provides current info + bool has_current() const override + { + return true; + } + + static const struct AP_Param::GroupInfo var_info[]; + +private: + void _read_adc(); + bool _initialize(); + float _data_to_volt(uint32_t data); + + static struct AnalogData { + uint32_t data; + } _analog_data[AD7091R5_NO_OF_CHANNELS]; + static bool _first; + static bool _health; + + HAL_Semaphore sem; // semaphore for access to shared frontend data + AP_HAL::OwnPtr _dev; + uint8_t volt_buff_pt; + uint8_t curr_buff_pt; + +protected: + + // Parameters + AP_Float _volt_multiplier; // voltage on volt pin multiplied by this to calculate battery voltage + AP_Float _curr_amp_per_volt; // voltage on current pin multiplied by this to calculate current in amps + AP_Float _curr_amp_offset; // offset voltage that is subtracted from current pin before conversion to amps + AP_Float _volt_offset; // offset voltage that is subtracted from voltage pin before conversion + AP_Int8 _volt_pin; // board pin used to measure battery voltage + AP_Int8 _curr_pin; // board pin used to measure battery current +}; + +#endif // AP_BATTERY_AD7091R5_ENABLED diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index f1d6522a6df0bb..12ca57ceed7c27 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -17,7 +17,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @Param: MONITOR // @DisplayName: Battery monitoring // @Description: Controls enabling monitoring of the battery's voltage and current - // @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Generic,8:DroneCAN-BatteryInfo,9:ESC,10:Sum Of Selected Monitors,11:FuelFlow,12:FuelLevelPWM,13:SMBUS-SUI3,14:SMBUS-SUI6,15:NeoDesign,16:SMBus-Maxell,17:Generator-Elec,18:Generator-Fuel,19:Rotoye,20:MPPT,21:INA2XX,22:LTC2946,23:Torqeedo,24:FuelLevelAnalog,25:Synthetic Current and Analog Voltage,26:INA239_SPI,27:EFI + // @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Generic,8:DroneCAN-BatteryInfo,9:ESC,10:Sum Of Selected Monitors,11:FuelFlow,12:FuelLevelPWM,13:SMBUS-SUI3,14:SMBUS-SUI6,15:NeoDesign,16:SMBus-Maxell,17:Generator-Elec,18:Generator-Fuel,19:Rotoye,20:MPPT,21:INA2XX,22:LTC2946,23:Torqeedo,24:FuelLevelAnalog,25:Synthetic Current and Analog Voltage,26:INA239_SPI,27:EFI,28:AD7091R5 // @User: Standard // @RebootRequired: True AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, int8_t(AP_BattMonitor::Type::NONE), AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_config.h b/libraries/AP_BattMonitor/AP_BattMonitor_config.h index 7b14fea17fb3bc..4fab7ff189ee93 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_config.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_config.h @@ -86,6 +86,9 @@ #define AP_BATTERY_TORQEEDO_ENABLED HAL_TORQEEDO_ENABLED #endif +#ifndef AP_BATTERY_AD7091R5_ENABLED +#define AP_BATTERY_AD7091R5_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024) +#endif // SMBus-subclass backends: #ifndef AP_BATTERY_SMBUS_GENERIC_ENABLED From 598e2b07623ed289921c3594c6397f22b09d5c6d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 7 Nov 2023 13:51:20 +1100 Subject: [PATCH 107/499] AP_Compass: remove more exposed params for periph these parameters are not useful on peripherals which use raw mag field --- libraries/AP_Compass/AP_Compass.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 47a4b66cb07033..5a0ef79dbe45d8 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -66,6 +66,7 @@ extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo Compass::var_info[] = { // index 0 was used for the old orientation matrix +#ifndef HAL_BUILD_AP_PERIPH // @Param: OFS_X // @DisplayName: Compass offsets in milligauss on the X axis // @Description: Offset to be added to the compass x-axis values to compensate for metal in the frame @@ -101,6 +102,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Increment: 0.01 // @User: Standard AP_GROUPINFO("DEC", 2, Compass, _declination, 0), +#endif // HAL_BUILD_AP_PERIPH #if COMPASS_LEARN_ENABLED // @Param: LEARN @@ -111,6 +113,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { AP_GROUPINFO("LEARN", 3, Compass, _learn, COMPASS_LEARN_DEFAULT), #endif +#ifndef HAL_BUILD_AP_PERIPH // @Param: USE // @DisplayName: Use compass for yaw // @Description: Enable or disable the use of the compass (instead of the GPS) for determining heading @@ -124,6 +127,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Values: 0:Disabled,1:Enabled // @User: Advanced AP_GROUPINFO("AUTODEC",5, Compass, _auto_declination, 1), +#endif #if COMPASS_MOT_ENABLED // @Param: MOTCT @@ -162,6 +166,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { AP_GROUPINFO("MOT", 7, Compass, _state._priv_instance[0].motor_compensation, 0), #endif +#ifndef HAL_BUILD_AP_PERIPH // @Param: ORIENT // @DisplayName: Compass orientation // @Description: The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used. The label for each option is specified in the order of rotations for that orientation. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the COMPASS_CUS_ROLL/PIT/YAW angles for Compass orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_1_ROLL/PIT/YAW or CUST_2_ROLL/PIT/YAW angles. @@ -175,6 +180,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Values: 0:Internal,1:External,2:ForcedExternal // @User: Advanced AP_GROUPINFO("EXTERNAL", 9, Compass, _state._priv_instance[0].external, 0), +#endif #if COMPASS_MAX_INSTANCES > 1 // @Param: OFS2_X @@ -584,6 +590,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { #endif #endif // HAL_BUILD_AP_PERIPH +#ifndef HAL_BUILD_AP_PERIPH // @Param: OPTIONS // @DisplayName: Compass options // @Description: This sets options to change the behaviour of the compass @@ -591,6 +598,7 @@ const AP_Param::GroupInfo Compass::var_info[] = { // @Bitmask: 1: Allow missing DroneCAN compasses to be automaticaly replaced (calibration still required) // @User: Advanced AP_GROUPINFO("OPTIONS", 43, Compass, _options, 0), +#endif #if COMPASS_MAX_UNREG_DEV > 0 // @Param: DEV_ID4 From 7b6ad15f9092e5099067c2e529baca41dce46720 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 7 Nov 2023 13:51:41 +1100 Subject: [PATCH 108/499] hwdef: make f103-QiotekPeriph a single compass dual compass periph is not supported --- libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat | 4 ---- 1 file changed, 4 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat index bbfec631fad60c..443e803e9f23c9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/f103-QiotekPeriph/hwdef.dat @@ -1,9 +1,5 @@ include ../f103-periph/hwdef.inc - -undef HAL_COMPASS_MAX_SENSORS 1 -define HAL_COMPASS_MAX_SENSORS 2 - define HAL_AIRSPEED_BUS_DEFAULT 0 # 15 ASP5033 sensor by default From 1f47856fbbe56389b75089d9e8df84fe6ef8330d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 14:37:10 +1100 Subject: [PATCH 109/499] AP_EFI: remove unused definitions --- libraries/AP_EFI/AP_EFI_State.h | 3 --- 1 file changed, 3 deletions(-) diff --git a/libraries/AP_EFI/AP_EFI_State.h b/libraries/AP_EFI/AP_EFI_State.h index 97acbecd6b2209..c73416f5a377c6 100644 --- a/libraries/AP_EFI/AP_EFI_State.h +++ b/libraries/AP_EFI/AP_EFI_State.h @@ -15,9 +15,6 @@ #pragma once -#define EFI_MAX_INSTANCES 2 -#define EFI_MAX_BACKENDS 2 - #include #include From ba76d4e2f90f99eb4c95790884581e2521ed7c7e Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Tue, 31 Oct 2023 10:04:12 -0500 Subject: [PATCH 110/499] hwdef:save flash on FlywooF405S-AIO --- libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef.dat index de334979da0cd3..3b2beee7d66c43 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF405S-AIO/hwdef.dat @@ -151,6 +151,6 @@ define HAL_FRAME_TYPE_DEFAULT 12 define DEFAULT_NTF_LED_TYPES 257 # save some flash space -include ../include/no_bootloader_DFU.inc +include ../include/minimize_fpv_osd.inc AUTOBUILD_TARGETS Copter From 477534b44610865ad42c0f17a4cd3f3b7e7de964 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Tue, 12 Sep 2023 12:22:44 +1000 Subject: [PATCH 111/499] AP_Camera: Add handler for CAMERA_CAPTURE_STATUS request --- libraries/AP_Camera/AP_Camera.cpp | 13 +++++++++++++ libraries/AP_Camera/AP_Camera.h | 3 +++ libraries/AP_Camera/AP_Camera_Backend.cpp | 20 ++++++++++++++++++++ libraries/AP_Camera/AP_Camera_Backend.h | 3 +++ 4 files changed, 39 insertions(+) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index b3583a8468df60..a44243c8caccaa 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -541,6 +541,19 @@ void AP_Camera::send_camera_fov_status(mavlink_channel_t chan) } #endif +// send camera capture status message to GCS +void AP_Camera::send_camera_capture_status(mavlink_channel_t chan) +{ + WITH_SEMAPHORE(_rsem); + + // call each instance + for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) { + if (_backends[instance] != nullptr) { + _backends[instance]->send_camera_capture_status(chan); + } + } +} + /* update; triggers by distance moved and camera trigger */ diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index f0f384a1991857..356901ab262816 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -100,6 +100,9 @@ class AP_Camera { void send_camera_fov_status(mavlink_channel_t chan); #endif + // send camera capture status message to GCS + void send_camera_capture_status(mavlink_channel_t chan); + // configure camera void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time); void configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time); diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index abda67057dfae8..f6cf2c2d2b6089 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -286,6 +286,26 @@ void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const } #endif +// send camera capture status message to GCS +void AP_Camera_Backend::send_camera_capture_status(mavlink_channel_t chan) const +{ + const float NaN = nanf("0x4152"); + + // Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress) + const uint8_t image_status = (time_interval_settings.num_remaining > 0) ? 2 : 0; + + // send CAMERA_CAPTURE_STATUS message + mavlink_msg_camera_capture_status_send( + chan, + AP_HAL::millis(), + image_status, + 0, // current status of video capturing (0: idle, 1: capture in progress) + static_cast(time_interval_settings.time_interval_ms) / 1000.0, // image capture interval (s) + 0, // elapsed time since recording started (ms) + NaN, // available storage capacity (ms) + image_index); // total number of images captured +} + // setup a callback for a feedback pin. When on PX4 with the right FMU // mode we can use the microsecond timer. void AP_Camera_Backend::setup_feedback_callback() diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index bae4fb8ea291eb..067fa15a080eaa 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -115,6 +115,9 @@ class AP_Camera_Backend void send_camera_fov_status(mavlink_channel_t chan) const; #endif + // send camera capture status message to GCS + virtual void send_camera_capture_status(mavlink_channel_t chan) const; + #if AP_CAMERA_SCRIPTING_ENABLED // accessor to allow scripting backend to retrieve state // returns true on success and cam_state is filled in From ac313b6d7a445f207651f96e5f1ea758dc55cdbf Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Tue, 12 Sep 2023 12:23:17 +1000 Subject: [PATCH 112/499] AP_Mount: Add handler for CAMERA_CAPTURE_STATUS request --- libraries/AP_Mount/AP_Mount.cpp | 10 ++++++++++ libraries/AP_Mount/AP_Mount.h | 3 +++ libraries/AP_Mount/AP_Mount_Backend.h | 3 +++ 3 files changed, 16 insertions(+) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 8ff5a5362ba2d0..9c79d79205d50f 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -850,6 +850,16 @@ void AP_Mount::send_camera_settings(uint8_t instance, mavlink_channel_t chan) co backend->send_camera_settings(chan); } +// send camera capture status message to GCS +void AP_Mount::send_camera_capture_status(uint8_t instance, mavlink_channel_t chan) const +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return; + } + backend->send_camera_capture_status(chan); +} + // get rangefinder distance. Returns true on success bool AP_Mount::get_rangefinder_distance(uint8_t instance, float& distance_m) const { diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index fe3003eca536a0..3763a4f8221189 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -256,6 +256,9 @@ class AP_Mount // send camera settings message to GCS void send_camera_settings(uint8_t instance, mavlink_channel_t chan) const; + // send camera capture status message to GCS + void send_camera_capture_status(uint8_t instance, mavlink_channel_t chan) const; + // // rangefinder // diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index fbd2ca0a801044..0503d02ae648ab 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -182,6 +182,9 @@ class AP_Mount_Backend // send camera settings message to GCS virtual void send_camera_settings(mavlink_channel_t chan) const {} + // send camera capture status message to GCS + virtual void send_camera_capture_status(mavlink_channel_t chan) const {} + #if AP_MOUNT_POI_TO_LATLONALT_ENABLED // get poi information. Returns true on success and fills in gimbal attitude, location and poi location bool get_poi(uint8_t instance, Quaternion &quat, Location &loc, Location &poi_loc); From 2f9b9e245262cd709c87e01336543a9046589958 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Tue, 12 Sep 2023 12:23:53 +1000 Subject: [PATCH 113/499] AP_Camera: Add Camera_Mount handler for CAMERA_CAPTURE_STATUS request --- libraries/AP_Camera/AP_Camera_Mount.cpp | 9 +++++++++ libraries/AP_Camera/AP_Camera_Mount.h | 3 +++ 2 files changed, 12 insertions(+) diff --git a/libraries/AP_Camera/AP_Camera_Mount.cpp b/libraries/AP_Camera/AP_Camera_Mount.cpp index e81327fb58201f..775ac53146af8a 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.cpp +++ b/libraries/AP_Camera/AP_Camera_Mount.cpp @@ -88,4 +88,13 @@ void AP_Camera_Mount::send_camera_settings(mavlink_channel_t chan) const } } +// send camera capture status message to GCS +void AP_Camera_Mount::send_camera_capture_status(mavlink_channel_t chan) const +{ + AP_Mount* mount = AP::mount(); + if (mount != nullptr) { + return mount->send_camera_capture_status(get_mount_instance(), chan); + } +} + #endif // AP_CAMERA_MOUNT_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_Mount.h b/libraries/AP_Camera/AP_Camera_Mount.h index fa53057295b8c2..c453b96cdd6119 100644 --- a/libraries/AP_Camera/AP_Camera_Mount.h +++ b/libraries/AP_Camera/AP_Camera_Mount.h @@ -59,6 +59,9 @@ class AP_Camera_Mount : public AP_Camera_Backend // send camera settings message to GCS void send_camera_settings(mavlink_channel_t chan) const override; + + // send camera capture status message to GCS + void send_camera_capture_status(mavlink_channel_t chan) const override; }; #endif // AP_CAMERA_MOUNT_ENABLED From 3ba63d33d5c3665cff13382d4af154e7300828ff Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Tue, 12 Sep 2023 12:24:21 +1000 Subject: [PATCH 114/499] GCS_MAVLink: Add handler for CAMERA_CAPTURE_STATUS request --- libraries/GCS_MAVLink/GCS_Common.cpp | 11 +++++++++++ libraries/GCS_MAVLink/ap_message.h | 1 + 2 files changed, 12 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index fb5615cf3541a7..371f16a8641a74 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -999,6 +999,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_CAMERA_INFORMATION, MSG_CAMERA_INFORMATION}, { MAVLINK_MSG_ID_CAMERA_SETTINGS, MSG_CAMERA_SETTINGS}, { MAVLINK_MSG_ID_CAMERA_FOV_STATUS, MSG_CAMERA_FOV_STATUS}, + { MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, MSG_CAMERA_CAPTURE_STATUS}, #endif #if HAL_MOUNT_ENABLED { MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS}, @@ -5784,6 +5785,16 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) } break; #endif + case MSG_CAMERA_CAPTURE_STATUS: + { + AP_Camera *camera = AP::camera(); + if (camera == nullptr) { + break; + } + CHECK_PAYLOAD_SIZE(CAMERA_CAPTURE_STATUS); + camera->send_camera_capture_status(chan); + } + break; #endif case MSG_SYSTEM_TIME: diff --git a/libraries/GCS_MAVLink/ap_message.h b/libraries/GCS_MAVLink/ap_message.h index 3a707bc4628d82..973c48d51bad10 100644 --- a/libraries/GCS_MAVLink/ap_message.h +++ b/libraries/GCS_MAVLink/ap_message.h @@ -52,6 +52,7 @@ enum ap_message : uint8_t { MSG_CAMERA_INFORMATION, MSG_CAMERA_SETTINGS, MSG_CAMERA_FOV_STATUS, + MSG_CAMERA_CAPTURE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_MANAGER_INFORMATION, MSG_GIMBAL_MANAGER_STATUS, From 622ddcf47a8fe08a061677679d590a588f4f2096 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Tue, 31 Oct 2023 17:59:34 -0300 Subject: [PATCH 115/499] Sub: scale get_pilot_desired_climb_rate() deadzone and output with pilot gain --- ArduSub/Attitude.cpp | 4 ++-- ArduSub/Parameters.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduSub/Attitude.cpp b/ArduSub/Attitude.cpp index 424f853939a22e..408d9bfa6b1cad 100644 --- a/ArduSub/Attitude.cpp +++ b/ArduSub/Attitude.cpp @@ -96,8 +96,8 @@ float Sub::get_pilot_desired_climb_rate(float throttle_control) float desired_rate = 0.0f; float mid_stick = channel_throttle->get_control_mid(); - float deadband_top = mid_stick + g.throttle_deadzone; - float deadband_bottom = mid_stick - g.throttle_deadzone; + float deadband_top = mid_stick + g.throttle_deadzone * gain; + float deadband_bottom = mid_stick - g.throttle_deadzone * gain; // ensure a reasonable throttle value throttle_control = constrain_float(throttle_control,0.0f,1000.0f); diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index e7162c5ebcf1b7..73ce3dbcb02f54 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -271,7 +271,7 @@ const AP_Param::Info Sub::var_info[] = { // @Param: JS_THR_GAIN // @DisplayName: Throttle gain scalar - // @Description: Scalar for gain on the throttle channel + // @Description: Scalar for gain on the throttle channel. Gets scaled with the current JS gain // @User: Standard // @Range: 0.5 4.0 GSCALAR(throttle_gain, "JS_THR_GAIN", 1.0f), From 409ee80e00954dce00062fc1656fa8df85443426 Mon Sep 17 00:00:00 2001 From: prathapjaga <145013835+prathapjaga@users.noreply.github.com> Date: Thu, 9 Nov 2023 16:53:36 +0530 Subject: [PATCH 116/499] Update GIT_Success.txt --- Tools/GIT_Test/GIT_Success.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Tools/GIT_Test/GIT_Success.txt b/Tools/GIT_Test/GIT_Success.txt index 54dfab7eb55bac..9f00eea02a121e 100644 --- a/Tools/GIT_Test/GIT_Success.txt +++ b/Tools/GIT_Test/GIT_Success.txt @@ -176,4 +176,5 @@ Greg Poulos Torre Orazio seba czapnik Ramy Gad -Matthew R. Cunningham \ No newline at end of file +Matthew R. Cunningham +prathap devendran (Tamil) india, 11-23 From 08d88ce7c605ef5ce1297d12c5ce24a9f817e024 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 7 Nov 2023 08:06:42 -0700 Subject: [PATCH 117/499] AP_GPS: Use GPS_COM_PORT param in GSOF driver * Instead of hard coding to COM2, allow users to set it * The enum is confusing, so this needs a wiki entry * Use the same port in requestBAUD * If the user configures an invalid param, send an error * Add values for the GSOF COM ports * Fix bug in RS232 being port 3 instead of port 0 * Use set_default for the typical user value when the GSOF driver is run Signed-off-by: Ryan Friedman --- libraries/AP_GPS/AP_GPS.cpp | 5 +++-- libraries/AP_GPS/AP_GPS_GSOF.cpp | 37 ++++++++++++++++++++++++++------ libraries/AP_GPS/AP_GPS_GSOF.h | 8 ++++--- 3 files changed, 38 insertions(+), 12 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 0a5f3a7b6e1f7c..34fd3f82f74b11 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -356,17 +356,18 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { #if AP_GPS_SBF_ENABLED // @Param: _COM_PORT // @DisplayName: GPS physical COM port - // @Description: The physical COM port on the connected device, currently only applies to SBF GPS + // @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS // @Range: 0 10 // @Increment: 1 // @User: Advanced + // @Values: 0:COM1(RS232) on GSOF, 1:COM2(TTL) on GSOF // @RebootRequired: True AP_GROUPINFO("_COM_PORT", 23, AP_GPS, _com_port[0], HAL_GPS_COM_PORT_DEFAULT), #if GPS_MAX_RECEIVERS > 1 // @Param: _COM_PORT2 // @DisplayName: GPS physical COM port - // @Description: The physical COM port on the connected device, currently only applies to SBF GPS + // @Description: The physical COM port on the connected device, currently only applies to SBF and GSOF GPS // @Range: 0 10 // @Increment: 1 // @User: Advanced diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index af79dd2339bca7..9de37cc4b71f48 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -29,6 +29,7 @@ #include "AP_GPS_GSOF.h" #include #include +#include #if AP_GPS_GSOF_ENABLED @@ -57,10 +58,15 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, msg.state = Msg_Parser::State::STARTTX; - // baud request for port 0 - requestBaud(0); - // baud request for port 3 - requestBaud(3); + constexpr uint8_t default_com_port = static_cast(HW_Port::COM2); + gps._com_port[state.instance].set_default(default_com_port); + const auto com_port = gps._com_port[state.instance].get(); + if (!validate_com_port(com_port)) { + // The user parameter for COM port is not a valid GSOF port + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d has invalid COM port setting of %d", state.instance, com_port); + return; + } + requestBaud(static_cast(com_port)); const uint32_t now = AP_HAL::millis(); gsofmsg_time = now + 110; @@ -74,8 +80,13 @@ AP_GPS_GSOF::read(void) const uint32_t now = AP_HAL::millis(); if (gsofmsgreq_index < (sizeof(gsofmsgreq))) { + const auto com_port = gps._com_port[state.instance].get(); + if (!validate_com_port(com_port)) { + // The user parameter for COM port is not a valid GSOF port + return false; + } if (now > gsofmsg_time) { - requestGSOF(gsofmsgreq[gsofmsgreq_index], HW_Port::COM2, Output_Rate::FREQ_10_HZ); + requestGSOF(gsofmsgreq[gsofmsgreq_index], static_cast(com_port), Output_Rate::FREQ_10_HZ); gsofmsg_time = now + 110; gsofmsgreq_index++; } @@ -150,11 +161,11 @@ AP_GPS_GSOF::parse(const uint8_t temp) } void -AP_GPS_GSOF::requestBaud(const uint8_t portindex) +AP_GPS_GSOF::requestBaud(const HW_Port portindex) { uint8_t buffer[19] = {0x02,0x00,0x64,0x0d,0x00,0x00,0x00, // application file record 0x03, 0x00, 0x01, 0x00, // file control information block - 0x02, 0x04, portindex, 0x07, 0x00,0x00, // serial port baud format + 0x02, 0x04, static_cast(portindex), 0x07, 0x00,0x00, // serial port baud format 0x00,0x03 }; // checksum @@ -347,4 +358,16 @@ AP_GPS_GSOF::process_message(void) return false; } + +bool +AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const { + switch(com_port) { + case static_cast(HW_Port::COM1): + case static_cast(HW_Port::COM2): + return true; + default: + return false; + } +} + #endif diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index fe3b0cf8f6e64e..a55d91c0a9198b 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -44,7 +44,7 @@ class AP_GPS_GSOF : public AP_GPS_Backend // Ethernet, USB, etc are not supported by the GPS driver at this time so they are omitted. // These values are not documented in the API. enum class HW_Port { - COM1 = 3, // RS232 serial + COM1 = 0, // RS232 serial COM2 = 1, // TTL serial }; @@ -58,12 +58,13 @@ class AP_GPS_GSOF : public AP_GPS_Backend bool parse(const uint8_t temp) WARN_IF_UNUSED; bool process_message() WARN_IF_UNUSED; - void requestBaud(const uint8_t portindex); - // Send a request to the GPS to enable a message type on the port at the specified rate. + // Send a request to the GPS to set the baud rate on the specified port. // Note - these request functions currently ignore the ACK from the device. // If the device is already sending serial traffic, there is no mechanism to prevent conflict. // According to the manufacturer, the best approach is to switch to ethernet. + void requestBaud(const HW_Port portIndex); + // Send a request to the GPS to enable a message type on the port at the specified rate. void requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz); double SwapDouble(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; @@ -72,6 +73,7 @@ class AP_GPS_GSOF : public AP_GPS_Backend uint16_t SwapUint16(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; bool validate_baud(const uint8_t baud) const WARN_IF_UNUSED; + bool validate_com_port(const uint8_t com_port) const WARN_IF_UNUSED; struct Msg_Parser { From 8b0bc101f27ce47854a73d748bd253a88ea47c82 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Mon, 6 Nov 2023 18:49:51 -0700 Subject: [PATCH 118/499] Tools: ros2: Add missing socat dependency Signed-off-by: Ryan Friedman --- Tools/ros2/ardupilot_dds_tests/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/ros2/ardupilot_dds_tests/package.xml b/Tools/ros2/ardupilot_dds_tests/package.xml index dacbbe61e1efe0..8e21f9ed4bd0ce 100644 --- a/Tools/ros2/ardupilot_dds_tests/package.xml +++ b/Tools/ros2/ardupilot_dds_tests/package.xml @@ -15,6 +15,7 @@ micro_ros_msgs python3-pytest rclpy + socat ament_copyright ament_flake8 From 4f00dfa69af236b1ea5cf06f5f60bbf06bd9cda0 Mon Sep 17 00:00:00 2001 From: xianglunkai <1322099375@qq.com> Date: Wed, 25 Oct 2023 12:04:50 +0800 Subject: [PATCH 119/499] correct the filling order of the struct, otherwise it may cause compilation errors --- libraries/AP_Logger/AP_Logger_Backend.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index 57f8792bdb2010..f938254a3a472a 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -574,14 +574,13 @@ bool AP_Logger_Backend::Write_VER() patch: fwver.patch, fw_type: fwver.fw_type, git_hash: fwver.fw_hash, - build_type: fwver.vehicle_type, }; strncpy(pkt.fw_string, fwver.fw_string, ARRAY_SIZE(pkt.fw_string)-1); #ifdef APJ_BOARD_ID pkt._APJ_BOARD_ID = APJ_BOARD_ID; #endif - + pkt.build_type = fwver.vehicle_type; return WriteCriticalBlock(&pkt, sizeof(pkt)); } From 125c8fa1fac81fc7d3bb78592eac786e4e53f978 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Tue, 10 Oct 2023 20:14:05 +0100 Subject: [PATCH 120/499] AP_DDS: support automatic reconnect to micro-ROS agent - Add ping test and attempt reconnect if connection dropped. - Retry ping test max_attempts before exiting. - Move `uxr_init_session` from transport init to session init for reconnect - Tidy handling of transport.comm - Fix codestyle Signed-off-by: Rhys Mainwaring AP_DDS: use PONG_IN_SESSION_STATUS in status check Signed-off-by: Rhys Mainwaring AP_DDS: add local variables to clarify arguments to uxr_ping_agent_session Signed-off-by: Rhys Mainwaring --- libraries/AP_DDS/AP_DDS_Client.cpp | 104 ++++++++++++++++++++++++++--- libraries/AP_DDS/AP_DDS_Client.h | 17 +++-- libraries/AP_DDS/AP_DDS_Serial.cpp | 2 +- libraries/AP_DDS/AP_DDS_UDP.cpp | 2 +- 4 files changed, 109 insertions(+), 16 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index eecac3fedf70f9..29560fcc792080 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -2,6 +2,8 @@ #if AP_DDS_ENABLED +#include + #include #include #include @@ -34,6 +36,7 @@ static constexpr uint16_t DELAY_LOCAL_POSE_TOPIC_MS = 33; static constexpr uint16_t DELAY_LOCAL_VELOCITY_TOPIC_MS = 33; static constexpr uint16_t DELAY_GEO_POSE_TOPIC_MS = 33; static constexpr uint16_t DELAY_CLOCK_TOPIC_MS = 10; +static constexpr uint16_t DELAY_PING_MS = 500; // Define the subscriber data members, which are static class scope. // If these are created on the stack in the subscriber, @@ -67,6 +70,18 @@ const AP_Param::GroupInfo AP_DDS_Client::var_info[] { AP_GROUPEND }; +AP_DDS_Client::~AP_DDS_Client() +{ + // close transport + if (is_using_serial) { + uxr_close_custom_transport(&serial.transport); + } else { +#if AP_DDS_UDP_ENABLED + uxr_close_custom_transport(&udp.transport); +#endif + } +} + void AP_DDS_Client::update_topic(builtin_interfaces_msg_Time& msg) { uint64_t utc_usec; @@ -569,22 +584,83 @@ void AP_DDS_Client::on_request(uxrSession* uxr_session, uxrObjectId object_id, u */ void AP_DDS_Client::main_loop(void) { - if (!init() || !create()) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "%s Creation Requests failed", msg_prefix); + if (!init_transport()) { return; } - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s Initialization passed", msg_prefix); - - populate_static_transforms(tx_static_transforms_topic); - write_static_transforms(); + //! @todo check for request to stop task while (true) { - hal.scheduler->delay(1); - update(); + if (comm == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DDS Client: transport invalid, exiting"); + return; + } + + // check ping + const uint64_t ping_timeout_ms{1000}; + const uint8_t ping_max_attempts{10}; + if (!uxr_ping_agent_attempts(comm, ping_timeout_ms, ping_max_attempts)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DDS Client: No ping response, exiting"); + return; + } + + // create session + if (!init_session() || !create()) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "DDS Client: Creation Requests failed"); + return; + } + connected = true; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "DDS Client: Initialization passed"); + + populate_static_transforms(tx_static_transforms_topic); + write_static_transforms(); + + uint64_t last_ping_ms{0}; + uint8_t num_pings_missed{0}; + bool had_ping_reply{false}; + while (connected) { + hal.scheduler->delay(1); + + // publish topics + update(); + + // check ping response + if (session.on_pong_flag == PONG_IN_SESSION_STATUS) { + had_ping_reply = true; + } + + const auto cur_time_ms = AP_HAL::millis64(); + if (cur_time_ms - last_ping_ms > DELAY_PING_MS) { + last_ping_ms = cur_time_ms; + + if (had_ping_reply) { + num_pings_missed = 0; + + } else { + ++num_pings_missed; + } + + const int ping_agent_timeout_ms{0}; + const uint8_t ping_agent_attempts{1}; + uxr_ping_agent_session(&session, ping_agent_timeout_ms, ping_agent_attempts); + + had_ping_reply = false; + } + + if (num_pings_missed > 2) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, + "DDS Client: No ping response, disconnecting"); + connected = false; + } + } + + // delete session if connected + if (connected) { + uxr_delete_session(&session); + } } } -bool AP_DDS_Client::init() +bool AP_DDS_Client::init_transport() { // serial init will fail if the SERIALn_PROTOCOL is not setup bool initTransportStatus = ddsSerialInit(); @@ -602,6 +678,14 @@ bool AP_DDS_Client::init() return false; } + return true; +} + +bool AP_DDS_Client::init_session() +{ + // init session + uxr_init_session(&session, comm, key); + // Register topic callbacks uxr_set_topic_callback(&session, AP_DDS_Client::on_topic_trampoline, this); @@ -931,7 +1015,7 @@ void AP_DDS_Client::update() write_clock_topic(); } - connected = uxr_run_session_time(&session, 1); + status_ok = uxr_run_session_time(&session, 1); } #if CONFIG_HAL_BOARD != HAL_BOARD_SITL diff --git a/libraries/AP_DDS/AP_DDS_Client.h b/libraries/AP_DDS/AP_DDS_Client.h index ac6a7c0d5626dd..acdf4c7ddcb162 100644 --- a/libraries/AP_DDS/AP_DDS_Client.h +++ b/libraries/AP_DDS/AP_DDS_Client.h @@ -73,7 +73,8 @@ class AP_DDS_Client HAL_Semaphore csem; // connection parametrics - bool connected = true; + bool status_ok{false}; + bool connected{false}; static void update_topic(builtin_interfaces_msg_Time& msg); bool update_topic(sensor_msgs_msg_NavSatFix& msg, const uint8_t instance) WARN_IF_UNUSED; @@ -143,17 +144,25 @@ class AP_DDS_Client SocketAPM *socket; } udp; #endif + // pointer to transport's communication structure + uxrCommunication *comm{nullptr}; // client key we present - static constexpr uint32_t uniqueClientKey = 0xAAAABBBB; + static constexpr uint32_t key = 0xAAAABBBB; public: + ~AP_DDS_Client(); + bool start(void); void main_loop(void); - //! @brief Initialize the client's transport, uxr session, and IO stream(s) + //! @brief Initialize the client's transport + //! @return True on successful initialization, false on failure + bool init_transport() WARN_IF_UNUSED; + + //! @brief Initialize the client's uxr session and IO stream(s) //! @return True on successful initialization, false on failure - bool init() WARN_IF_UNUSED; + bool init_session() WARN_IF_UNUSED; //! @brief Set up the client's participants, data read/writes, // publishers, subscribers diff --git a/libraries/AP_DDS/AP_DDS_Serial.cpp b/libraries/AP_DDS/AP_DDS_Serial.cpp index 8ce7cc3b0ec937..3906e165214a77 100644 --- a/libraries/AP_DDS/AP_DDS_Serial.cpp +++ b/libraries/AP_DDS/AP_DDS_Serial.cpp @@ -90,6 +90,6 @@ bool AP_DDS_Client::ddsSerialInit() if (!uxr_init_custom_transport(&serial.transport, (void*)this)) { return false; } - uxr_init_session(&session, &serial.transport.comm, uniqueClientKey); + comm = &serial.transport.comm; return true; } diff --git a/libraries/AP_DDS/AP_DDS_UDP.cpp b/libraries/AP_DDS/AP_DDS_UDP.cpp index 0569e0ecdabeb8..2610291231dba2 100644 --- a/libraries/AP_DDS/AP_DDS_UDP.cpp +++ b/libraries/AP_DDS/AP_DDS_UDP.cpp @@ -83,7 +83,7 @@ bool AP_DDS_Client::ddsUdpInit() if (!uxr_init_custom_transport(&udp.transport, (void*)this)) { return false; } - uxr_init_session(&session, &udp.transport.comm, uniqueClientKey); + comm = &udp.transport.comm; return true; } #endif // AP_DDS_UDP_ENABLED From 95dbb7a3f5b532afb0b1920b82d9bd0c071b35f3 Mon Sep 17 00:00:00 2001 From: Cedric0489 <1406012633@qq.com> Date: Tue, 7 Nov 2023 06:32:59 -0600 Subject: [PATCH 121/499] AP_HAL_ChibiOS: added PixPilot-C3 --- .../hwdef/PixPilot-C3/PixPilot-C3.png | Bin 0 -> 299845 bytes .../hwdef/PixPilot-C3/PixPilot-C3_Pinout.png | Bin 0 -> 85296 bytes .../hwdef/PixPilot-C3/README.md | 401 ++++++++++++++++++ .../hwdef/PixPilot-C3/hwdef-bl.dat | 71 ++++ .../hwdef/PixPilot-C3/hwdef.dat | 227 ++++++++++ 5 files changed, 699 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/PixPilot-C3.png create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/PixPilot-C3_Pinout.png create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/README.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/PixPilot-C3.png b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/PixPilot-C3.png new file mode 100644 index 0000000000000000000000000000000000000000..8958dd878e7a0ac75d10c9fb6713016f62aed372 GIT binary patch literal 299845 zcmeFYhdc#viIgBBl8^d;Be0G zrFZ&#K7YgS`*<`SIIsJ@U)OkE&+B>JV)S&>Nr@PVKp+sQ#=ScRAP_zV1j2npfCqf1 zR4&gS_>a)@p1BtY^ib{cFBVOT>TM8+NZUzORZs7Uhqs5<6A#bp8mg+-J)e0vIJw$` zK>oA2hJI$r$ZLvANPBVhYL@t|x+E98~MXSP2H8Z$d`jXh7fSLDhzJkBLAjAdqW7unGsLj1;tesG*1pnl4SA zrvpvDV=g5C#bSXnZ>n>FmD@m%jKd8Cz|d|`L4`7h5DxSs7R0>qmO2>HfeZ4DGfN;> zeguMKstELhu1kYKs;txl*w?kN3q(e{V5QccFPiURfuMb<1L>NhVl>UE!;F6W2-q_F za<^-ZiVYnvg#+OVM^1V+C-uE`Y^^~O5Qy<~#8ix-0zf%R96S!h=JR zeQycf{sxQ#qR<(F&swjpPGWoZVpaQexs+OfW=%j(mQF3j<_HTO5Df>Oz7CK+S7yz7 ztM^Twg_($$c!%5eZHLIO*NPaipB}K+p~t{a(Q|_-Z! zc&Q83X~b{nbA^WPVu4?inT`5_ltT{$-!Kvt(BX}1}S zpt93A4b|9;1(aDoDe6CoN|Ua`s2+xIdD7uMqR;E5Z+}UMbNd?swGF#$G^K6aG{+zT zU1l5(hs{0lBuLTqjc6KujxXPy6@g1toD(hYaqbH~qmhYysCX%**v{wXy9iMuQ#M`UD#=T@%+q=wD#o-wSt%T3XSZV zzB0tJU;BE?e$Py0@|g+tmVir!wyj0&>9&?HE{e%lI7rJ-)vL^*!XeQickSr_7TMPt z7(!+y=l&r3An9O`Ahw{AV9lg+r9)+CrPOTTZ0D@)&a<6sJ6p4GAJ1InT!GvpSvOgv z4`HihtA6W?);XV{O~o<0t$+=}qaR0P8w(@qM{b9OM|7L;N%#nxl!!QiWCDY$sI(oT zKf&&|ONLYP2qN<52g<%Dt%*HP3P&^wZ#47lMmheH@TXIBsPJI6tq@?Ew%)7t;o4|aILSypbmcW+Vq^YYOlW8_dwrqA^J+>-2)?t_GNVJlxNb1PH_t8QHmPu`@6+qbzM z3s^^A&?8wz1^ctX4Q$1)is1af{HV_2PL3soPR`KD(9BT$^E{N?S>HwcN!QPS{cC$V zxR0d);0$F^8Dn@CCn3orC(%FrPnI0MqF3X z6QZ^~kPi34h@Cx1hK1Z@$-Y@4>j(k^_44l#}@Rwcw6~YQ5&_y6I+r z^F0_x*WI>joUaY({Ded;4O$=jJ0V6x`kwUFrd{YQn;97II|t0~#~DP7zJIUE|J+nO zwKU~>pZmwd2Q7BAHmQ$|;m+w37A9eQbg9-Ao)sTHo>Z$fuPvMESWg5W1-Q-5F5YkY zv9on=t7yx;0%_h=b-%;;_Qdc@1ZgGHUhFE9wcGtg@3(=@M{xu713w0^C2S;iEczQO z=Jwx879I!YhFSKRTvV1fbWvy%df%n z0UufS?bS~=mWqRee(C*wJNSA2^T1MOSkn=~*1Z7!QQ0n^3c*6R0)@97@ZWC=b6Kod z)H|Cnp>WY(c0Rol@uqnNxi=N|PFJ2M|0;Q0l9#Kaq%fX2AAr<4&vdcWx9o6K9m-Rp z^WN2JvPOPCSX_^{M6`Pzav*KzxSKR96+SAchk9Q8yjNx6v1O0!+cA~@=zXZYB{u>e z3p;a$PIyh7ObJ=$2Xw%{ZZkEx^DHnobGIIy_#W@j`4R1E&07Y>`&XTJ&R%TdpOJ5d z)uU_dp>D8~N6<$@pUuhPWQ0+9=oHLY)X!1%e)S1XHO|=hTsAf)QpS$`$Aif~OKMA~ zhkk^bU;?(h%GZ}JmQk8RX6Mrg;?vhdT^|EV51zrxORHpiIeXdK2LlxLiq9(t=R)Ak z@Ybc?4z|pj=gMfkgOM}4-jZQmq~dxo`dk`%@+gM=5@P!2HGG{AU6mEi2#94 z0XhoV0D*i&K%mV>AdqYZ2t?jZZ;yWF zN#s`8mRpDv>swW;79?lk2r<6q3J=e9Vr+ zrIB>?$H2$!Dc!w)UnUv3y~O;_S6s$9KfA6z3VfT^@kIE4J^O_Lt@%G6HhTL19{tZ6 z|IbW+qvHQxAu%_P`}e(H-cGZphT@12j*s3Vd`Q+V7>T%zy!_eta;R)1%qro(oD$dL z{hg1qxiO^iC@3as7i%rNg`)d;kOAooO;^Ii6FOF4yhe`y$f0j}i_<&v5 zklR%yPA^0-U8U*f3xPhKa9-F3lsCJX zw+-SzU^C)(_i{BaCHH@;8JeeQQ(|LeFBlfW1QCus`{<+k9OM0(py*uCT1W|ScJY1W z+P~xd_)%M-MuIAdzI}cynZLXab-Q2T$AX}Q3S z$Ll1`A(4N%yb0om3W$si{5}`x+k}dH`hIeeP$8)6?7MubG|2zoQ{}Y+*&KMkcW}^} zPd|IR-J zUB+!YtwbzP(yMFeo`PY1nu1ZupOe5k=l8rn=-d{Q3%aI21-z!w1}gAsYp3&~TJ%`Y zaH#tCs2%Q?7YFQ-FC@!x1Sr*i4ZWa9!=InzeZ*6e%fGSYh}Yo;oZDb%H;5F&{pWRy z_7d&QbLpq^E%(_qd!S*Gk<}Tpq~fDqDI4O|{0hFI1hb1;bDat$l>=6~s@H*MNLNCq z5Z1slmlkkid9&ZuQiO4KLQBe#&cFK%rPzI)`P_G#-4~pJ{GAAFX1|O2x7kR_TDu3> zu%30Nb5h9G9Nltw@*vO^Te_j=7m`AAeaQIHk`|R5R*rtP5~B_-uv^jndCb4qD&+2~ zrK3>aP-^el42oetnRouS;7}4yyL=OqX~VQ?{mfdsq;dC~(~=g!+l@rv{fgdpHc6bP z|2b-snkwJG5?7eGT#s^49KEw}MZmdu%@~w{+iJH!2b*@$L&DZ40W;GW)hSBfFo`{pOhVN@+9Q@A^b>UD^LH~0TSG|(M2~_ zOCkVzoh|c1*?EZs2vg_v_aUv@i8n7_<|OpdRR$TWf2TSs?+#yczdGocUpiJ4 zz572aY7~5LW4y#TcC;ZH5 zet7~Ena!0oNaJaQq`tG+kntXpv-cPGYE!CW#O}BE-+X~)no-@x5t-{nmL@Kin6L<# zL>q$~6v}|$5Kn+pT_MHjT3@Yemh^+Jo9#=g%*Kl8YNu6-?omN|*PDJ{ABjR%sBMD~ zqd61DKydb>d;trTRxR<8T;Uh%g+l|+XRLDGHfkFd2SF?0!kS&d#+r;;i-TK zf!%~1Ky}0WAXV5U*h^qC{9T-2Dt|oB?D~1qX?$iv*NrjX<2Gt2mxyX;Z>*&g(=~-n z;EdzxD1(2VsveErbF$4uzZ(vttMP(9V~WQ*Vf9>Rbw8ef8uwhk(1wNq>3&x2kq2rA zNmFLvknQ{&L;BE!W(C^ttY4UGU=*oU%#O7H$TrZ0tN#n^Pxs!2aSF~6n^==xn6il( zFN^X+dm&LEzwKvURh%zZtBBeA-S$I+a1a(yVbF~u81E2gT(|Y^*s&z>;;&8{U5 z5xOLDm1$@EeYJ$P2}*ZEAz=sK5cRv_r|(xxcd!<*=X1|b*I%DApWq3J)`=fo%|e1oD}CBLyQZLznGc(F;XtMNAAX}jZ&&sXWR887h`GlN?$gjEMc zg|AbqVr~_luSa7YJUfFM%1!qtSRvz82&~Jd(Un+XIP!GT#h*)LO7b}obpqujcGs(@ zdxZcDwjW{y(!eJe?sOGFMtU>3zp04=hO2U!DzYmVJOOS!;uZ>M0nG`BxVwV}hvf#ydRTMi$)Ic5S z^zCfwBo}@u{%4i|(1s3dX^(~?!nhG(ssvTPe}!g%cpjV|JX7kMFPRD@M?fXnTKOYI z7S?|is%_JZehU~%144IAz7PPI@yUzgtLibHOI6rvy2GBfo?qn82a*}y3>;?(E|zf5LH_cd&M_s6ssdO_Q_DU#oP;)qui-6es; zYZ|r<&v|Ew&-!Myx37y%x!rgn!MTH>_;z2h0&WN_-zi%|t-L7uly!L9IEobTKr8}D zeHGrN?Md(FOgn@xPBW;sK2oTk4z0u<>r{0qpTaIC*dwP73kJqY2juXY+x*^N)C{j4 z>w?+v+^zT7*CQz$@cp&4spYU-hh!wP*drN+l!3(?+N;E`BJx!O<(W19IsJ(Y0z#z= zxZ*sGaU;)uhWT`Lc`DF`;Af>}s6;h?$OM*HYl0ylE(SRy?A z8Z&>al}`L6bWxrS+Fk`tL)x072iTFWB9I$#7d8mZy)W-GS2$ZIkPTMUvz-Wm7OD{B zZ@*jcfh|Ee?^mELVSKQX4U8_{?qXC^;TF}2dD;%{uBq*W0(;~c4~s_~ltHF^hsPIe zc1V&6B1VYgMi(eaZ>Uo85-L&UT9896Z0Iy4P%Bqr`ihb__CBw z)bD66IkTY_Ns*UxaPA@@wIxl$-XBH514*YWVW0li0<}%EAIob2HhH%4x6|tx;H=DE zNwttc>9%x->!V*QOn2J9`ixm3VQ+7FJ(cmkdGvN$8lkUbcN00gMiVh!0wjI zyhw_O-5FN*U*d@4=M#!_D*k$ORU=$+TtjtCW}wXtj7v}AiOZbM14pckr4PS8(4Z zqXsEd>h7$DXG1Et(7WvvDuu7zPJ@<>Z~}B#i$xUrYIy+kN5@*@D;z4tc>ZxX3aspUi$VA!a9tP+O^Rxj6bCZKI;N0R_ z|5i={R)*u{UAv5BaVZH#UOieGeTafW!xWpLGcE3|! zi+P$LaB^fBJ8*K@tCJfAl)qJ~CdkoTx7lHZyMh@TO?2ek{G2)o+M+ShU8+3Is zsroazrFD0xr86gi#Xy5YwXTXgra(yikF>&9uKpH7RFiY=#2y*QD5Icr%?rJ=%sw|+ zYJ#CqG5fvWLe49##&-iC|HazU)YEge4Pp>Dkl4xg<^$!g0K(vNCB&2_0o_V*+i)16 zKZ6LRO2+PO|9RopxG0-b3!lgSyww?l{Fg@^mh=n%gG5PXTrZNfZD;m%w!sdn1P8QE`?jCD z^37~><-MTUk|!u08O|Lke`}s_Mm^my9WXWbQi)fsKpXf;W7gN}1G-C_ErEMhiyvPj z3#e2G#7YnDCet5RHL>^yrP-4f=)d*41Eh=cH5E_c|1>G5-#!dyaO_3AcA>~>vrmod z7tzQj_DE~^{%N|j|KUXgbP9s13K4`Ycwa-L*Qk)>I!aA{1(Nt$yj)8*Qo>mGgf*eT zY&Azen~b9&AkFN!D|KPx!t8RJ&tdUba#oQ|np*IXr)TNOtz(cF5FW4K5i$?(mrP$! z#BJ`MvS9_=Mug1{t!c5erb}=Rjfr}OzV;a+W*2XD#gs#o2F+Jj^hu#(ow?jy*u8_^ ztb#$8O*P|kkla-PB`p-_)4@kGG>2r9Te82*6f2~fE-u6O7&2e&ch{_UG(VPwA!}3{m89;EkSPho{GC*qwQ@y zyO>qXp6q4$?5pSDOA7UNfyXTrJeb__z={cVKV*JU`ImTk;7PZ^LIOj10&4%Bj-pt>`Yz(qv+PR3%1gsl*8KoCPU_+LZDq`3%rY}C&u9~Qz#lp0x$8L+J80O;Rf2j zox4!Wk&7c$Se#6GFn^?HJZs0KS9D=pQ<_-_c?}U1T*CpiU5rMI&tMmjX%*Y6$4s4G zN3^s0c%Ep(Fe{Z}afN89X+wQ?-@2MVrzT%K5-Pk?3?;A#r9lJj9cuS$MT10I2$0@*MAElA>D6sr(f zI^HBB&5qj_o=+dbS-cyH4>?dJh~NC|qKj4DcdRJxK`x@sR;Ezo78dp?G{}_T=M1a; z3)C~&+@XL}xl8(oOal-avO97GqvN_x<0m9vR=cx1n13qZp^jvrazrL5MFjB$V|cEt z_jtI*qvz*wEKD=R0$^gOeD!dz+XW|V0=N9ak>IB&tEF4+94Tx*XCe*aG~@;lK&<)v ze{g7BE8s$*8Mz)y=5A)&@#{j4w7ug|LpfxLc|}p@{m%mdk}|Gfq7TAczB=Cytl1-@ z0*rj><8MT>1P}iBPc(QJqy_Yox=8ygzil?qpa+wbl+JaQgLnIOYd#(yaUmFBi08&j z#O;7UBcg^{TZQJQn;ng@M~*3E$-@EO!55}PZxXSU?)%hjW1J-t0 z|G=0DBvwA26|Kt2IKfWD4KN%O$6IqY0i_1m?cwi@xxHx|tE{?NK;QyZ5dwkV(TsnU z#0FBM?FV8j@%wH7W0<$V4p7Qdt>~<-Tu~JQEz+o*ln^zY#zRc8%)dtk6ZpryU&r5H z)OsXA0oeJ|e9%8TQ#*yi8DQf%6N8+17{Dmuol+982aF=@#2I8GA6$8mk299XLyvhLkP5waYu*OJH=#@rlpg{C3MM&W#I9IQkQK@yIG6BL z|B-%Zy%h-as6OivvC?#a)OnfAB`-DwATxj!zoP`M@`Cnztt;ab1HD?g$YE~}(j$~K z;W-NeB9!l}@%l(tFrSOF09w*9j+VDqQspLB%d;0dWcc9P<-> z?Gb;?0W?jqeN76I9z~(J()O_Q*HcD0I-r32gjxSH>e1}YzJ;4&KP*%)taO1;+0`If zD_>)RD!rtz`qgHB>Y{^PLJLTPo9B5yuCT<#-h8r18d6tu_M{Vu#P$W3VBNr)p>SXG z0knuNPsNi&c|0I#;{PO#2#boDcRa9bWlQ?4zqNu&InCa%XIQZ5P_pLyxHiaDATEXw zW(v6hz5()MMDRSs4JL1T~Q6%=8qE9&trgX!%>`9ha6dbIFs}h z#yIsqx%?Dp66@iyS4gU62=sD2Bj|ua+w4C;TlC5r&NFtj`zB|?_r1&FA1I4mQAoTp z<`azrn;}riT7@sGD2|11yawajttF#Y^v;u-ANS9Y3{_#k1}nQS{%xQNj5T`prySQS z8l%k6fu9t3oFc2Dw3kzERPyBuP|7I}v^D{!{x*+&^>W4*SqH7RpAJtDu=lt0a>b4` zJjIi{0~p|G3+9TY&&rqH!3aiDtj+nKi$ARobC1~qbeax9r#Dq~+OW&R1C?8#4JdF1 z_VA#q!vyljO6F>5x((z@z{bh)o(Wgyq`f#?H-?HM5IMaJ4uJ7o4#a)afFvpm?y~!f zDdQ~?x5E?!lk0^#lx_w^dzlZR$TUW8Pi^CQx(_;QLhGmW0R6rth~>)c$3;}5hCS7o zarXJ14k)w8y8L8P{ZF4@a0b@@DG|oYti69dUTSt3?9i}R18g%(akOOKI2i}IDMc0! z=eBxuKmjZ*gPbOY=772XNZ|jhV8+NWdmRrgCmWol0KHY6fDU87z?8jc2p`RI!kH{9 zQMwV%=&2SpS9@ohK;+jw6OGm{N1<8MgayXyAOFb5mpI2b8^m~Zbc_3(x0zPbBdk1P z=(mMI2NlFesOne=TSrLXnOD-W?9FXJ$;d#mq!(pZm21P^0}+bLXeGz3F{-yXME_SF zyUTm%Vc`Dwf=F~FAA2pzhAX7ZNbiOT-v>kYz~>4*BNYd%SV`Uo4c?8gx<^ug%Kj(H zNC!gR{Eae3KetFUe@}IoP^5@yxUV*)99T<#o)W49O7ccHeik@2Huj|||M17Zqs2>I ze>X0AnyTg}8D2+hvVaW?h8+0kC!HQ;Et8S`*UYPM5dx*XXy}zm?uS3B@qz^qtA=ok zzu__3tZ^VKHJT*F5xVjmk;KAk0%2et;L~tXl5!yWm}{a3AY69P(3Mj3RfF$^(&voy zr&eQF%a>dty3l-G{@LXw*;@JR0meoZ1snjsTDSW0*U7OFN#O$};p=gRkCOSY+Ohrp z2c0hmWY^>Yx?rS!i~qyDq@wV-Wg(z!UxuJSU+sfS3Fk#U85#+4d`Y3h)|3eFp)VBO z8_-NACD#=aShql*gW(sD2BQnmf>3nh)EM;tz$aqxlWJz2WAwZm>HOhj{$dsGk2AYv0OlQy4$+IqpWdfDh zuF-`Og1zl~=yFOq?VRkoSt&G9YEj#As>cL;d1|2a7%ToOpL#$OiXN75Ku!kE&h&0OE+r;%I(c1 zv4is`KVht3{S@6Pw|!*(n1II9VK$6O2Kyv5&0eh37Qz*aYVf+2aor?i=9@1}8|c4_ zov|*N%c=YJxBo_g!2733MBAqwsF_I`&~qXixJdU~Wx{EVF6pK8{(mztV}msNBZ0na z5UCN_H;UvLB5!tMjot-v>`cYF;x7Uk z_)i>JEn5G3Dpf62>N~lbFJ(lcJ#xCZ%UWVNh2#$+1G_H*#ph3Kchr5c1auZ4W?pIo zpbbbb;Po-tlO^mNKxp}BOP^$KE(nNwBd>VFw ze{`4Yc<20rCUSIU_fkE9#Uvm9#nG4d`PjOYw?=+xLdR4Hj)2L)-MJHI*m}<(snSsG zb_eGq;Uo4)J^Z}1#j4mGZIaq7)}tgGr_C%v+q>C-$aHD@;IeDL5xx81S!oyljR8Lc zLMN~7_Y)KQc+=4?)5h(mL@o{xL#dN>Zd;l28Ok7Q7iC}=Vo}j}C#ThBQ0#UR@WA)O z0DbWtZL!Ge->k`88drjt44M4A_ry8n-ihtxXFj(p0L0q8H;G(-{7Ho*zIsq^ z^aI>{AA2vi2O8AU?dF=KR2w4fxtWEr20Oo*i5`?FG#?r;cO%UB=zN5)u{pNh-`_fv zcr?iATkznrgorCPHWUAW7=tb#xf1PXZs|orA9D}bBQ;>mwy7zx?KEau zslGr?Wn4{=LXyFIJcy77_{*BmO!ml9if-Gxb2D6cCywj&dw>kqVa&S*e2>6}NIKb! z;Sr}JXbBL#cw)2I2)AZCjfRicZZ=pZwKn?>f~k96$uP~3we$AXelZdR)b3d6zr|~u z&PfM(_d&Y1HI@|+u^*f@kbr_(D`4UF>-d`6JfT)`Lh-P4{BJF{e2`Vz*s+)4T!}&- zSFGG0`!-x9sjj`b39vbqzg*>dwGufXG4>nP$0j>5MvxB&GDcYT3}e=uNDR0mr?7_j z17n}Ej%3EYj`7Z^cSg+ta;>L$IoBWfd=D>U$3Z^-W9Q8WjM~!JIjMECtdCl|S1(+Y zlco1NQ#+LHLL?%@4MJYV%H7%4F1$E6-VvxQ(Sb-W*Xd7$xBx*@GBv1n*6ut(=)r9% z<#<`KV#(D1tFuKPi$=D!AB6+RNQI~uU%$At>2)2uVZIYQ6xW9 zD=WUa%&mf2JrDlP+|AK>eLt&LyC}rVH(NMh*vqY2oAj&q9mmZlqu-oRRKwoD+b=91 zJh^shQ}MHW)ZdsbwdAGnNMhsK=D;KDqjmd*!=huS$5CK~6^B=w6E;K&A0t3A?90(@ zv*Z0d;PgF@b^9;fj9Puye5VTwu(JT3Vs(}C@845l>Y%58%3{e2isEv5){4xpFw}~! zo#)z_6A2K#0DGsDPLGYi&@O*N6T%+DLIm@=s+qm6kn8wVZSaq>+BlH{HXgq{=aScv z^wpBU2A~{?icuyHf{$}FbJXl-0dzFL?W&XeTOCqG$yO%~r$trK(H9O`ngKh%c*cIc z;sa#p4^+c@c2f#NGTg#Q@Ri+2r*O*=V(4We7f=6O zpeo>DEbEIK9kWB+a!%qvd&%jWGilJ)`*9~}{7ZvZ(leIfKQ|`~a24nNPIyPv3^Gs5 zTbUEB!X+hn$>2=D{Scpcx1!!PW5Or(7KCr@$S=#g#J;jbF98B_lBeC&rD?bc%N4(4-! zs}(P0fPe^&zYK`Jpa_ObQf1(y*!9;IjMl$ITB~BI&IXP?!9`*j;l?s+KuWeSOfYdd z;e5AX(c2Am`|T% z{=FwP>dz2G84TQQdM~+__TAC4+2XzaUI!7p4nXb_ns0Kfj9YT|-h68jX#_BktSX!O zkGp?fR7n2kZYQl!9QugF#oU)v9ekx-8g6;TeS^%U7njUgxIwBREVO6vb&VS;!1^BG~O$d7Q0&tmI}}Na9R1eVt=QjiQ*kR>T*eCZ!Y8kfz3-6#AI9=Ib4oV z+{re-|K@jvb82)>qwdJ36w0!Blzgo=b|ZKW5(51dllz=C7wuM=kKJ_iM2~#@<_s2T zhM%9tgnjW%W0=D*wejT^MU>~=O5nm7&H5T0{4x3>9ZIn`zTAmVOyDGj@3PaQuw2KnE`xX)M?o1qwah}0Dn6zu0-JCk2qhf!JO@-v7 z39AV^k5HaX`fYEO7qe%K`s-Hl#E;o8XpJDae(B=#{WR~1=GOz?0n=lkiyaX@QplR> z0K2)4eu~}_=u;$?mtKDwH1=yv9Wk9z&^)Hf|H7DJ(#YnCp2$1k4wRHF%C}+1&9q=x zuOr@ge%oy$SdOGw0&xe{1d%)1lL#Z5pX5|i&^tR|E&(UJO#43;11kq7V9>yXZO0@Ccm$aCsGDOG}oNZEs{P$h&OER32z%XO}3 z=hO~HuJC;P{lw5&HxVDSy-kym)!~%^?yi@DJ|OV|m<**mp}#5hJ^!Gys&EE>_$zOq zczQ6<(5(0+{XUJ}P8t*0=6DJ12wh;<|GaK>lLW5mt!$>Tlh5$U%iDF%Y6R&rEw%Rq zCJobr?LvuT?9owQs3GzGT&0@SDHR1^f!4O70mtH-q+M5Y<(H=a)7}`#lLIsf0r2<7 zY4!(D{3k3qa4=6F4(9taU_yr#tkhTQP$oG%aIE{-ToOM=Hxxl$Bac>LvuZL%bm5)rKQ4 z2s9KQA0Rzmvqusx=ltY%>pb^`&9@^IBdc>{opMOF-S_0>AP2yB6X1NdMuT(X$7;@~ zyldsTS+j~#_uWjV$Zp`Fk>FjNb^?Dkgr;ief)ch6a>p=zEnH*STcJ`h-Rl0fz_6zu z(6?s&Ew8FYj|- z^3zwyRR1g%D1NN~DqhmskG*5}_!`R1k-!F+_NOBsmY$#A84Tr}J)XZjHoZy)N8E2$ zW2XW~TKbn7&OsdoJC3ooa}$lKF>f)Y(A;oqyhRO?+wm3mn4Ej~K$wlWQlSBZchB#i zF;}#;0art=<^ihj?i93x+XZmj4rtx%fZV&gUm`lK0SErU@5izpIz`sbb%EM*&zP02GXA?I|R$Z<0CJ>>;#t=Xc5Y~5sJzP!! zj}?0B#Cy#d|E92g5sjk$JlKon!5-(V*hyaHC+JD&smeBYcoUfBO`RN<5%+D#->fJ| zQk=RmZ=b})^0y}&<6- zK_;#&ruk4N;kINve0-|!(neN`D^2My;z@;|fC-Ns{VY;!UnGS#K`?lVxaWijBs4X| z^%q-_%a`Qfwuu*amw%&y#NIeBZRz9E_^Vtyja3k*96VnbYbErRYKd(C6q;zI!6xTl zR<`~M6TMC(ac+Caa>JYL+>WU19;(ld>+-#0qcph0f|CIzf%)+IPhATH!H**@N1zhj zR2{jD;S}8u8B05pW7W$XWypm|;8RA7HYzWCZ=OcD3Y8;9)nDeRo z6|PPp$F2>o!bg)dtFu|TupumAV$gI5IaXKt;EuKS`b^N1g|{ViiWzwr|D`}5o4o0O zvg+qVB0IYP1Gs>b{A*ky&?>AE3wV|4XTn&q?*itc+GEF{S~^Uo5C^3)1^^Y*nJMoL zx(uzPe$$;>D)M>%JZ&hkj5$Z&)-WBi(eN__kTspURy*ATcUGxTwik`t0%8)%e7}@b zw+8X=`j*)Fi>^xq&Q89{Wdq7R`wS)`xWz6!h)SI&A0*G>FJ9e1etF+p6rlifgi1k> z)N4d9vo8|a-N);+z~5t@aa zj!!IE*=#qEdFe>qss%13|E0Sm@6#>hdmqoD->pAsBxajAxDn*51rA+n zceg3%{M6V#cKc*$O>v;E?zg|t3_~$cgjqhhsAM*pwsH<9>>_Ws_xmoVaQcDVNzch) zr6GZp(C})E0ZgtZ5t)zuaVTK^8qCwyvD6fdEbht$De7#WT=ywFTo4Ofe_!&lK&zgxy8_R1TP0ZRF3 z0^9YHHc%8u7nG+(GK2bg3+4jl?%_2-i?Ik#)$cLSLFOp>iZPO&5A&CvPl2oU?-`{R z-<*0|yYVq8@bmv+Tp{Pn3V7iT&UO*f>+bycsZH>oTfpUAnGSM)eS)8Ymh$QroI`+R zuQgBLVZ3P(n@5H$kIj!+Z1tKKi9`{(JGPkqu?R%iLQrl~)$cVkkHSJNJDd{mhcWwA zqSVEy3;)?mWLt>lyZ{Kzg~wEhg8=nqKmy|$!eD~t#@FleZ=}1%`mr}EzQ@zNMf z%Vr-i>%DWmz#Bqo!**rL=iiClNwa?~*!YtJX4<+TKGKH>8}QQ6d$`K3Ym@qVK)&(i zN_!S>v#91gcU~U^b7WS=62duS`o;7L@#>Vt zk`~IgxQfOQLq6v>pL|+x=&Dvs?3vXk0;sn2-KeSdB*b6i7@};h^ zQ)ThzMi4yE-5DV^9X7v9=~Vd+m0TWUsMFtEUUd9_vaD3yx)#NJlU$!E+qHXsg_p$b zPkZSRxN{n+p#I%0*V>P{B7x0$2S<^-J#*2N-Kkj1J6#V;%|oY5{&4Jb7P1)e*rZb3z_ULdK;!-E-4q-(}8lCWm)UCTuDZZT^Y z`Wh_So1~MfneJi-2k{g(!uo#GU}SyN;DO_!C3h-7fsA2_Q-3=Up{|GIH}zPb`%2Cf zQBHScsMsWoiMY}b3bt;N#ZO{0Uah!YnlK*Bn?Ns#mefUANFMSo zH0KPmhwwtPr#A}n(J9k2%9}>9%S3$Z?}vn{vJD9T4=dbUetksWKagubW8`eNJHK^k z!x&+u^|qSfty4Kv0e3}=##F~28$lm9{PwZlPfXTSc0n^3Z=s#;m*?VYea9z=Y|WdK zhPH*M@o0NEoRB#!4&HnClsb$cnDK-a2*TcQcv09KRt}y#f%FUdb2v;HKhh<<3ygj_ zZSyEBzG+8f`FyjBu>JZ)n34j+iB$XppPw;Mi)dOoNn2V_DcAprO&`RIKrOYO4(7)W zu)8wl+xOibZtrdB46o7mg>o6RI)Xzv1MrxU4yYC7fsVPU)b0tWFJ*3ndMK z)2?{>hl_On1fqvsQl9Dcu}tPTiv;I}fs0lcieR%dl5mSMsPWfv9JF1mvG#L8)$ms)G9>==qT5Q0&G>pZ(k9_ieKD&SU7&M<6S#M72UfF! z=wTRzsB0I#r|AzLGfX z$p^(4gRadRkK)nUiQRQNfnT)>e0#WO$_4X}sMp$;dVHIJ6R)!{2kQS&=+ITdiQ7Ju z2^>!gm?fA8n&>o{M#y)nEs3eL;H7NSkB;&*Sx&PZ-jkIJ_>9{Pl|fspWf^LRtS@CI|+E7U-Dl zw1SV;!}C(&8c@S19S|zoeg;F|3~FBFG`IZL=Kis0Xx7{>*;~`$)hOa>oW*NR^qwx7 z^Scz0rD=5dX3tGr%y*@R6V#t;iH)-HAyTL&K;Q=>eD^i?bW#X*lr*6>Z3 z>K41reSRP|K60a{(}0gNHENsN)+2$~nY76dkmks?^_0=dadGIVBI z>xbXW#*TAw-K^;w8j;hyP|axWZ8)hswLjSfAsQRO3#*Dgm!=6=}`P6!AWQ*T znI(DTyd+3nBGf$c*+ijQ3#bb^uTeSaRB~aH^TtUMZ zt`#51uoD_tYMyq%_|$5_WJ?%JmzaHgF6RL(LJ*Bc_ay!jTQK3HhobXzu})>`$-WKo z#8Kr5*DOXvRmXbaa!wrlctOYNQ97y|aeg1W1iTL1T+Ozh=^@CivM&?JsVUx(_&Svf zvBnOKkj^?61%lS(2n$->N(-Wtg&+U72I%-_54(OYLEP_o0io(*loKC`q zJVVL;h(43S`a)93Gr=_@wz>LK;3I=NvnkJK@SgU_$@H$gjwy^dh+FvB_O1Sil+e!9@7`j4)^jmlf|EjJO`Cq<%5$b@&;$z^VxmrjEE^B4YKs`E&&X z$09EYGnRMfh#L)4K(O^B9=-SF^bDR2Bj+;FmX0xNflaf*hlpcx%@u+1tS4_Jf8@Q~ zviC#J>ntAfmxRmsC4bG#d?$X+{NFH>N|d?3)-{p7)}1B~_{9xg-8dHnxm0>_RkC&C zg~0Os@<5LMmr9k2!cmm|mMxQGOe&FYqnW)Nq8J#PMs*wpFn(FU(cyVH&ol%4o@33c z?qsh?3kd}+&IL^!zl0KmKfk`yqaax%oq>9|zO18T45x|LT;5<*qH|DqCDbn(>-=Iv z7lAQcrXdmAm_}>KDs|m|iqL(q{&}N453f@t2ieJnT7KKJfxmcn`$=^JOtgvJ*E5U9 z_ua`|Tj1LJs3mQ9Y%rcbTg~YAbkP%2jDXi8Mo8?(RJMBqZxDih!wz7ZkQ%i!cu-cA3wgv8g; zLLu%1T4X*_LWC^W69k2C0ofU0&hauLdSUT5d~QZ9cVhwY!=@Z|Kh;LtkKA^1`yH z44Ej@MbV_5W{ZIrIpDXi?aFQgCB%|NY9r%`!Ter{=yOA?ao(wzA{l2l>pJpD%mf3p zidwxYfBNT`6?P8!xg5YVr~r~i)WKBRN!!eX;8^~>!ij3m7Q#h?Pl901w&oaost8PS zbT0Sqot(UabRjG>4iUVZf@SdkQT5*ORKNfK z_;Ji+kH|VCBV=S9BO_(cWF(_bLz2DcAu`Hnh|115Ax_H5JaUTc8JP#^kZ}$U=inUY z_oUbNbNjuYe;ogMKCkO~jQit$zhBq6(HE$QI#T58U_OuO|AF&TXR_u2P~M=e8B?Rw zzeLfRM!w9bcsD3|__{T?MPe&%FYlTg|7gS<4zJr{nCdU==t|$*jETAqE={Z~G7~7% zF_2rIOa6-22`aw-M+h#9wiN5*)OJUl8%n-2p_xc{zg~H`qJj3X5TO?u`EDD{Lt?@k zU^)S4Ab+R&#EszxxokRYsIlGOxNNouzRP=f&t;08Jj#%}r~OfZ^ThU|(%e zQ86RK{#Gz-JonG_eD0WhQd#AT2ZGa|KTuNM0PmIazwgzTg`r756j`KbTll?hY~Gj) z0iQ&RenN_^iI(fIoFThyJ8@@ZPhwcnWgrGk`b+Es090sHKC2C+`_D`H12va2+Bb&t-Z$|pgLB(Rw%XLYC<%K4YwKK_G))N zaYToF&hKq}g_+KwFUA!`nxcEUyNQ%)m+fam}K8xpoyyK3K0aM%TpT%8{j_Jqp z^?pydcp2}Dv&^Lc)fLc~Z)gvlWyrRWQKMY>(ap*ur2d5__=hPimQyQ1E`37dhC7Q) zaRv+3VMdrVhqk8N$1I{vC9+DkR}wSw(_8cFxH@nFF-OLV}-fyD?V>$;r&vEQed_VC7p;eH(*tgns zesZ?pQLe${eK#p~Ey?xtj+j-T>+<3M`o~KmEeY<|$RMP2c`8^8&xWb+fJ8HrYy{UQ zX|xs36X`7(yv^2nYf2cW)USM?JG=De8yiT#_J2R@&K2OpuG#;lyeW-S46+t`h?HS_ z7))xrrzLq#y|z6fX0C+YR+MEqCtm_yteGpK4n$LyyNt;qYg5m?A`<7}V-F<~ez(zT zKX#OaE3YxOGLkRiPcL+laWuNpd!+N|Ck*Uo({}UeHq6&j{8&C#c1{5`z&vVzGHRdp zi*oBZ| z+nY5cZH=52>WLkss=$`vLO?ZE7&S2q2ecg|f$B5u?9ZICY5ONJ+jqDegNgTf{-?3F z+kd(qtJk2<-d*cifSXxCW&c19`&t*ge$;iE?XW$n@@v?P8K8j!l$hT9tvVBsI(*wq zz+-;rYa2N-8Z$KOLOz1chPex-v|6XXvT>vb_>wl zIgHLd_G)m9ivRKVB!vB&Bgq_;)OFmnHz4Z#ToE-F9_3-ry(Yx}9S^sNkd$_iSR9CP zw{CwRAaT6uyyC|17gJuV^IieCv09I?4__|yi}l^|KHyKFR@8w*=(|!yYjs1f-|Ia&{k zx>B`Y8hV}%Ud0_gv4Z{O8-GJ9#xIcuPNU5Q&6qehAB|?Cy=!cURde1&~a z`|(7bo{DJ#vzzrq#cFZ(90J`<#-Ldimwj60}>}NlUG6wy>5zAA|bO*?bWjZ2TQMe_Si%1)9sHV0I!B#5ROrB)7>^ zupb8oBN~3(O8Byp*aJYKzmCRG2X!7Ew1IFmt;TBwz8XsLUY+&}fpiLD z2?s_mb%&`t=yNE@=GE+=rTe;&?xx*d73lBUT4^QHN}KKC<{b zFp{nbOK^Qg=rm7tN7i@S)Stqj;L-uQvVU12F5+JlOZa2<;739Al+9#0+3zYM?x=q^ zfpPpIa;P26siU)h7TVuUTT;{f-OL=y!n@XB>tC!nBcv`N^Dkws&lP$$%~SP+3|M*x z08kJCGCGQ-KNrUvIZ5E^?J*Ic3ihDN#zwhl@F_ulfG)(hMPQmCj5Vv5!(8BRE1L0PS`X1_0n{XBXnztwsA*-h1NP;?-}{(WyRGmUVj%VzX9DUWxOpkY6 z$bVl%o|Qzi}d@&zD*$w_ZF_U5od;#rL+D(|+1Fci&-^J&lgps@3U-9~MNj?1 zepT=aMYk{P11l+szk$Bc>6!X43}-Pt&K<~6TH2|4P9!&93mNglE9c$i`?Fr(Vrd|A ztXo=ED#_xI>}wA-(_f4T5B6`?wR?`99x0cSsE{L60)Z56C2T6ULiL5=;cgf@497nA zz8gz3Unt*4CTAnLZTQ8(3P@8uD8y{Mf%<0Be^q|UKWy^PY0Q*}+HC|)bJ@4HbqPz_ zj~MUakIKihiuHdfN?@69Na;1PF?D#}K!Y0gEgh*T9A6g4e2ekA-%Y)PCc~p829ddV zffntzaZsa%x9K$j{%#=6Pqt+b2X|2Opgaw-e%HvSQ656lsc`9;)E9GIyeJ_&I{+eh zj`+JkChJsdSBWu+96h@sQ+fFy_=#pg5~pum;^0IX;&#K>PQMIDApE$9L;govpxpxt zbc{)UD;W^96P};EVhqjL&UYY(W|ziUO2+-oxzP25mUeRPh*s9 z>q(4*`6pBA1P?>*dTO$ZO+!m<5*vHA{_JA6Fe#|1Ig?9=?7~S)aU-euh2WSyxt}FB>>} z{*JBLY?6q@p#JN(BI*XKLt)l1SK^B)XkU_f;?Q>h(-3-X+jMn2>HoH$xy`#cI`N5H z_c^@O$v#u-v2Gv{3l<9Qq>v#Cxqdhb+WM0f&3WiUd&u3uHIa1~O^un1umV^)QXrt9 zI}CZC3(PC%Q6b5~{JUYsC!`y7ubU8GD{siKo;*hPhyP8Uiu2&V z3vEJZ4})grAO>H;hO_Nta5Hyb2Qw)-e`!q5c9c5oY87|S&0T4^zR|uoX;*aT8%?qHQd zChbfn3Kz5t8P+%qL32`dEe7D?0GJ>;MZSbtLbI_YmevLT4adw4*KRx-m4s)EJB|Df z0ZnID1#NH0c&Qz|!d%aP+x6nX3k}qZzHFe&ndE29(>#&WwhJ*}`X#-AWb2?BB#E1* zoA*!vNR55h&sOlagQug(YVYo{-?~gx3XL5!{ci?NdV7ltYY;at8>ejnz#y?d#XR0D zmKy$GGe~iTs_6eHyUpL)FZPN8W%SOj>U0MqXo;rqEY3KpYnCN2NC?K{$3jZmraCc3 zUG6}lhtOKlq*<=7e=k`fM+@SGg?5nr$nB=#9p9mulD^}3W!V2OUXAW#_4rGClm!5) zI5oBV0V1SkpykxGP05f;!wea+qZz%VJnlB~k*S$}d{v4ib zQNjAP2oyRXobS&T3j~0zY+(=LMl&z0_OV<)ut##H=6E6c7QI?bx`X&1D28ue9v?Y8 z-C4&zY_kH5xIBqPfI1PYfydEy2Bj5)3lPP(dAyv2OXF2AK`Y8(wKKVmX^s?ZdMvUS z+xVly+$C}s$)WY~+R|q?ae$a75dEK&qu9Gx1IOnf{H_WFXommtvK<0!_kli-#U8++ zV)YT#1QwGExZ?oMQlgn4w_i73t*_J`;e+KBoMuLllhX`#vkPro|~GZzt*5+CKT1Y-(c9jXgP!N%Y7}C;H%*2=d8B|cpyw(ShFW~_Mf7* z3Wstl4TgFr@0>~&`|;7ya!TjK+6HFRJp<}}3K-CdC6o$kXsu`eNs5~8P4}B(oM*zs zqWy_&v}7Mx8Feu^7LGI{yMdcelk!)bsgl0ut1lnkOI*B>Tu6EFD$X0|_EZ~AO(e9p zHB#5+@^lW`Xw1I=oEt_;^naM+RUvB334<*e= zN*6TcHt}l7Uz(pBK$C1~menR}L`#q?TgN8lZ zj1R4-^G1_F`whWMBDN;4{?O$akEb^Wc&g(W06C%^kRB}kmKd1RvhTGk4T-i5qpt1~ zzi=KfIeA6gk~ozk-qbaZnn^05tfDBfT3kjb1Dw&m8*4K+$p|yDg4^Xbnqco>AFG!N zjt*6;7I&(jr(Qv`$>yI8rklWtA=HpT%Fy-XgruVyWll-^AGggb>UqjMLGD|jOA+(- zC>D58Mw-a-c)&PsE#y|{oJVJz#jH;lH4^N5!B1uBVhn=IhyZ5_l@(0))}jmL!e^ld zlG}-q`PoCopA~C+7vKIKSamgA*-n4Zd%_vvEcI@H7Fqb#R@D5ZZmNDk5XwoiSs|(g zM)+EoT;o$Qp>gN4FvIj4pj;kW8E7hAl_%&B+So$jnsZ0WjuhH-?j{Lb}-T?>Jujd-6{E{oOkXN-23rU#;v6 zCcx||U{%Bc0Yy6_6`QSW*?O%NsbNgF?lJAo7{a5#N(EZr25w(TfKfDuesMV08`fQk zwt1Z{o|Z#)(qw=SV@u5kufKM>?JG{`7V^ZEv1P1VvjNL7Cz6~!{r5KYIYq8m<;tT4D(xRibPY5NdRG=x+_ zn44*Q>o|`|rOyw#dR;-v@@1fTzdMG-GU}bq1)$KtXD9sET;h9fKL#($PeQN!*jisT zC0ki*b4BP@nlS?B`r)64H&S0nRH=Vn{MLx4{zQvb847Lg>0z#~;G#jz{G{>6MHnf_`-GsCJ@91)xd@YgN|lT`I=`R zW_BdeP>W)VVy3`tVC~oZ({tP;xCcC+UHeYloK%|W0YM4<>4#A%rRLI_v7+=gT9hiJ zmX`?v_`X*b*f#|)dY57R`sC}YO<2lJ28 ziBBAr;_+knkm7|oy%G)&qu=ebK-rx2b*~dJCh{#&8N7nErx&8)r3V= zUJ5AR&sg%|Eu9#rlm8F*D%-0D(?y~H>V#7cCq3hgKF@P^{UkhN4 z7x)Hr9!q|@VIfMT{ndTzc>aDZSNj7*%=tij zeM~AkO++AS1PJI1sH0g@U+TXYal%`qZ?;%eu{S%r73}rF_5z)gU?YNa-Qr0F9Uxpe z>9w(adh&zl#|@1K8QD@TLpV0U>zVp2QvIgz!;_T;)Ho4K7Ik~0XS2p1L_Wqrhc}HE z?vEY#i;8{`_C4YE`*tey!d5>jJ$ZzgtmNyL|Mms~*d@6-RW7Ow4t_T|9%NLEZa%;` zn0*+(L;7 zeCIXCJS{+SL-}xNy}9e6<8F+dpCvdG7f?KEMm|@y0PmyxkS1{?;o>|;G(-8Bqo$U; zG5@a#yM6dgkzv8YG=mv(=fs{!z2Bo3OZnrOQ*O2=3ib741TMW^^__Y^5N*cQq+XmI zXo+kTMs>t^d3<44%J{<6AkY9Nso-4}x~LV&u|0ksGuuhR^zwAkh3Sb7as6LMJs6ZP z`8;|d?2xn_$lmm6yrP~{3x3UyIsV)hLd)^I@GQ`7+OK%B74fl+No&lUT;xj;e$oFX zkp|)8o3bty+&yWPlea`!fi@M$)PsfiFSgYY4o@wps37U{E->J>*{RC zslP9dQgpV+KNvw^L?M0&+w9}1a==jsr04ei0$DMF4Dce2`stH{PZ3{utJk(J#(KtZ z$3%d#Xd#je7P4qiIY7nOM%_X~8mO&SiB2nvDK{9N01L$(Waw#$xr&ui8kPR+8o)F) zakg!d6Ii2{JPraAuj+35p>@EWU)HZ|T>en7X^r9WKE3Zo1I!9t8g&~yUe>EF>eap; zy9qaQ@?OY{r7EF4?rwmzUpsnJ<40!=l5Br!r_5%MA;AvZ6~gxkuUe(3yee(YbVUMSjFMh@CH z0!o4VD!>@mU055NjLME>65dkbdydvf~mlg?u!ZR;*4i0mnTW$IF zh?pM@cR#kBr$jh@p7lyvA`oebj2oBaD&c&v0&36#kCGIkGe>W8lwol}8QmW&5LL2q z;`D%r)u`lAJJa?!^ca;I=8rnj`{|r%f;O-GrW@in6SmgtVG-9QWh6P8eQK!Svc_IB zK6=pW?*;Ne(tNK5+UCnRrx`b#fh6sR_CVw@k~Q$E3+Z!if48R`{@)3!t%3CSU3X8O zu({a^Mo=zKO1bk2VUb{0Js@9)UclR9NUVqJ4zapx?S3P7v^xsNwhP~{vnC(|xyVWKJwq{FxKD24j5{oX4xX5ohTVO=7y~H{SV$t|)bCg# z#eG20oimDCrgPjEqDS)HvmPM~(cJ$cZLtz*%OP4N;y!U`41sxas%YMnEV)A;9j#8I64)|Oqh$&1$*L;f`0wG^B zb==NB)s0N=kxX8(|8U;$GH9@ksS6uC9jCiED8ZTIefrj zwCrO>g?qx>tIn@XIE!V@wi$%?o?GFsDp?v0oSk|0^LnLsb>Ga4`Zy)w zu&+h4sJ@9umu8#GQ7%i}y`M`lV%s1$=ll;oal*3U5JvwqF z1GMEfyHRibZ3X3&r)@=fa*+<4*n9aa9YCsBr1Q z$y`(8UfeivvrvPqQZf7_{vum1Zo0}KsmK&!$dbn#XZUZrQVRFjSlFI#qBue`?r$vN9?6v5pDL9ug!Ecq6kl zFg2u1C}9{kW~;C6=RMoZ*}W|25(9*kd1@~DU(Ij0_SE%?;b&q&s>P(-ZC&P99O1mP z2sRENBQ&sy$z@E}d1r@6<0An(W(6+V5=*l~9|=owd^~}w3yx-pOq(dgydT{)!DOQ` zi!v|`9BwH4OQre+3-?=pd6o>9`vzz3{~pFNjlJdukP_jj*=K1@eL%woIcObO^r8g6 zYW$-ZK0o+iDzPk}OYw^;-VsLsWTcsPwQG`%`(Wggz#km2OD*<^UTB-W#FABV`p8^V zmZJpL6gEL!ClC{9=R|`80rvImOl8hM_f=v%klFdpA8`xe3jduq&b>ztLqls`fT-}t z-urRJpGEd33LWO7{u(P8B<~G8)qF}2B_~2(5ZIG-72CK&X_RX2cjhMNGHuXA#`33( zCW&>?qivpBfkn(&Y@#jYlF2rh9`whO{0D&|rD~_mnQrWdUsC-;S7lpeJBp1}S0(|7 zn@j%khrgH9JE!(IyMVRo!mxUx}2m_)#0dW^b;_|9L^VmD8{y3tR`$?W2ll0)HoG=cky-2 zC}*ise)Dg!`X1KucaTc2&vE?C_%J#gN13WvEG4ME8akPH{H7wl_ng>-U#iVrX8A_s zrri?+l==h7!sB&7A26*(A@U{9Q`1MV10hLb2Uk|AI~EjS0H%pP7iLK>!bG-v5NCL! zEaKAlkjaE`TZcp7V9UtfGvPZuQQilw;gEX|sJejBH#P za@d_enfSQn_JhA^#t9aV7hlE-HnMjx0?i%s86S{{0lZXCIx6ZNQT&J2#o3>-L4CJW zItm%$R)nrzF``9^+1rN=^4AdG5~AHekuRW8z3C(FW31?N_cLWj^NuL~g)5(T%2u3p z-_VY5170?qsh^I@7Ho~w?Vh7T)Q9$8#JSe45FoDe_F}Eyh1zQAiHB9JxXu!;OHZTh zX=j;oMl7bZ)}ccPJOqZpuc8OHW>H>Ax4L;z=`jOb22{_h2X!C^?zmrLdT?31FD5HF z_B${7c_!6@<)OV(^KK>~yptoY)rZSWiP)i%`?zc*P!}0-TGiCDNgvq3@)4 z67I_buSrUPU+vKBLa$wtp7246X1d51;h`qE=J(FoywHySINgbdkDY=k`Uzqz0jg9Y zhnc*a16zh=DWDy+`E;`BVke9aPR_hUeEYPPx)G+=dr zjTh1JG4449lgJVrrn==HM!+=@btP2lIbUoIz|Rjx5AV)2q)pJQyCn&QyL* zg-W1Yl8YcXqqRHFXhO~=m{HB;mdF7xL~PGNLmzjb+HloKXAtadJHT1UxcA0Wt{SE{ z6yB$bHOQUMmuhwBw8-6LO?*<-aV6KlaArFe0ZKoU&?k7EQW);mxa%#(uy!z_O47u9 zC*ZP51Mo&@Un)P0G56_kxEr|jicoHJSfjU(NxBArMf%AfSguRi$L`7FLr_}KhLK;^ zbDG6OpkBgLZ^Al8Lsmiej#|7raXVR@8Zmzw-S02pV%H*d?YL7XMSc74%Mec9 z*aPYBUzWx%8UYt#RMoSSRyn?!?Ke}foY?O!LFe)49a}B}Daey&pk+3h6=6G3 z(D(UT5qjqq+9ri4o?w}%CpTCns8$D{bl4pJKcxn)G>c7VBlfr|gM>7}ESJ$_By>G{H zZJYDeDoK&unvmf-TY#)ra<51$KNvD zZ}=z4f=X+1z(p+z7E@o$Kb*pUB?vWXSljQvtC>B_8L!-_Zc+UY=Cg4pnN8Q3wNKqhqft8KN)(j>5?Dciyys@K2wQRjCh4TM4D z#Ua%leRcV%!Oz1Boq+Y%oM`{&*=_(F`q6G%6Pe|hd^^L!wu;+iM60k>L(L_BKr(ov zyD_v%Fc!j%fRJ=ol<)G-Jb{)|f0j|K=<_T-G(2Msy`ghbd$hy%H|yfX!tmbX#3=t? zDNg6sKgoZ^WuA)~WSYk0jY##1r*iZ#>#D~qj<@exT@`A0v3;njxl%K9?+qn+=ip5I zvl2GGzMMtbK}{ySKM>xE(PQGMdw#@=dQq;)c--j5iQYCvg;;C95!XKwO zE-Wnt4?lhP> zLl}jwu*@qcIO3L2%1K38RL%y)iyOl={lN>`W9(uKrZ-0B6pDj<&LmvY6;1QjNuBt$ zB)#w+3n7*Po(IPu`J~;xrqNM(JhC^+a96}kGfjX6yWAy-pF$6zSEJY)%=U36a$$3S zBc*rVbYV2jQa_zXzaSFN1g~jk^QVO@I>Bn6j$d$|U$TdtqdM(Rhq2(zF?H~ca(+YG%Is{wvhNU6F`R#pJl~_?p)2$}Q!thY zLV|X8ZXI|A+D8?xExrwe_>Y}Fs-4dTMBOh|3kjcHw-`{8%cs54*~7&Mh8RVi%4b&& z{F!`t{fnv+6L8xGNi-rEjRmJ)5|MCO_`N{|9f@zy%5}>b9k%(Rf{JA6WPC;xUdu~o}xf&*kI^qRMj)$7YMlfk5oj>rQU1bGuQm-qkIOp zUSMwf?z4lF(YjU&bc?Ek0u-9Hfy#3fUbKw-HX2V&M4wYo>o|qEk8xZWWgs#{OGL3v zmtVpS1-ZCF>{181%cr@^V~+R7?f>?No*QbCDP!u*c68Sy)Z_5d5oD6{ErBy~fXYuHS^ZNA)c zA+?nUPEF+8+@3{qb`P9Mc=!~}^+(ech~B;ZiZk3hvH3A5?UAc8GMei=8N+rqlz#+X_JBr5W)Q-|j7RtXEP_v~P2 zzM(cXuv2H_AoQ+(K3Am3*ah*|0MPj-xsvVh*_pA-q8Ke&E0gg#C%%CoZY2^`9=HL< zC40JR5$Lm80HQO*YK>*kY@A!GNto^7YC!f;tThNOw!qX#9f?T)&qw1g60q3;e5S+` zK2?5wdGW|O?H+F&6%ays6dwSFjcvO}hK;2W)8B7oIl2Qf*s@dNe>^?j#^A6Isgqd8 z-muDp-^~L}$=lOaQ8V|#XYA)mSHow*+gF3n+Pwx`40$H->wRG)K=cL}@gdS6g4fS7 zbi0>EH9S`y)_GmnbhFe2=u`TPI1TpG!9I+xOxiE_hX-h>^pPSYP9?OPAUQwd=YbIb zO0yC&d3tz(4a!f$L^)6@zA&SI)+Wr+QLAWj$ax@NV2v_mVuHwoy?5rSRr;N2*T1 z&EkmJRkf*U$j;8d$e%@rj@H5XtA7$FuO39i=%xatd3>uIbF#OQ(0s!yXt$r4WoIlO zr;*IzS+4^(ZrKw;`QW$BY1~suO9%zyTs9FaDuai4v9&I)WlGvQ$GGt7(4u6-$5h+9 z{fW%&con#&xHrX}u4@+vhR5F#wry`-F$q28ev# zZ$EnwyL4UTySUH9#)-S7%L^B{p58sa$Eu9oG~=q97(MN95 zOKV^$VJlHi{l7Bd^m#d-*#$fTDU+Rm!;AFKp;4yX3b$I9%Pam? z0Hv^X(x3}vsdlCm#R3<50Q4Pu5a9K57Be>zzzd8DI@;}FuVS(RIl*wJcD+#H%<=d) z@DE+|1w3-q3K>M5>t_$Z(dCU`y}XNwqPWkiEhvR~p`AGEKa~5$tF_)M)_{`@4+cKu zQu1OfV22C%6!oP8E3youX;a)<2w}?)Tm;>iCZJ~bHeJ6i87xCOQynnnKJ0GmNYn_` z#7CgZyg%vS;$HsB@rYI7?+CSe-~6-?7!MQvx%-u6xqX7&pS%+jFza(kP)a&)Dm>)D zA`IdhkwD&Cgwy5B{;f6B=@fx|i}}ViMc~Bv36e*4R)SpXcU$^Dtr25&e}v5#GTkbC zx`AtKB5u zh-KvN$gl!IfV-_q&kboL$8}5{bq*&CZ(CyG`i(SCQW=Nl0j>sPI+4>1k^kazKVvNR zRv6W_ykvX6L}PVrNpFnliV-KmG0eHq8@If*S0#~v$)`U|aHP5E2C0Y3GG3ytuLNwJ zrpLNT?Q&OSIKP=BO0dNr&e3{540@`!*1SuHd4*CKoI7GpBm4%J%O@|+PXJ_qgt=4y zZtMtB==qck*a`0a9teXwLH;yDt_gYqL5Kr;&u8p=3wmz_5q_GC822t6_vW1hc#ewk zz6*xPmOmP&{PS*~2z6pAoc+E_ZTL0^F%;sh2d;)0ecRSn^=&^3^f{M-N_i$@YtEtd zp{AmjJo=Pp;AOOZ_+0iw%jDJbfOm}pr;%SiZDb7e3Bf8U*TOzYToNgHC>_NI`|%qG zhMdXFlivctl9$rK043+7U;Iv*PK}3Ji1bE2127OnwRDx^x(GHjD~pO5S#o^VLC%$INn!)eHzEv$#MN(AZ&ycgy+y8j`Z zmMo69aAKrZq_<`Ae?L5fUm$4ABCi2p&@^?a@ZzU(Un^;oG0Zfh{QvK9>CPEof*U4hWMY60S`)3mT_R<`w;#-&H-Q9S|#LXj`TOh>*)_)K+89u z0#3Dw2uh23%Z3|Aj~r2!d_LR_tH#9RV6gb^b}OI$owDr^CU|g#&&SHU10~Uk4Yge3 zRgmI!X>#N?-_O{$GGRI?0g9O=o~vc3xso&xaOpWbika*lo4D(dT@PIJmH$E~B+u%@ zp}$MkRO^txYW3oz>q6j}Hdbvq=(`@@!#fzOWIMV``B~e|JSok$nxuf*^r=};beo@4 z!~gFI6iUe4r)ga{GN0_mQb1a?qx*!(yWmewy7@(McQ@_H+zizGQ$ z?tRzbSU@1>;XoG4xB#KyOuOh;s+x@J@AD@mqTip7%45Y7`>7^5f5bov#`;lBb>MWd zw5>TtvKuTJI|lDj1IS`Eqb8Ue9+#ID(`p1qnOcU&OT}2J+h4y?m1EY=X(DvMk>%!{ zXBX28Pkc9x`kA_^(Y7BXjaC!@v zz}ZSA7;zyUtR%_>f!`xMyANps!403Y;-0Ie5aSc5z;-|W`M+&1es!U(H+^k~^Y!-v z-@x^cmW9^ADtFlH4+`*YeNlUN!c~IM1;7hxJ*c^18QpR&p#mM0>FNUyUl0CD;=Vco z7sdx+4!yK@!_dPcxHUi0s6~Mz?q5JXxHWpyYZ7I8q&eJTeQ((QIgA_2bJ+^> z&NM$X&Wo%rufkpJ?#Asz1ST{mIgovB?&`cJ zwq%l>!I6R_c1$gbTSM_~UofT>?ZFuh3FX5xqFTly{}6`lF={9ukQwbVoo{T`qvzvi zgNq3PJ@~nA-@YCH0Dq64k|OJX=Uhc-6Wfl z%8?RPR>tk$Pr=SD9dPwro}-K8ZvfOGMMj_y@T|U^K@=;#gr_TqUYj8_nAumJ_K*we z!36LUxTG_~oD~e0U$uG@J*YgnpT|e2GIVz}4Jaq^*K@SOMlGyAz3t`472QrM!s!~V zauVj~X7$_yx*_14*O#bnbgn1X)(yI%xP7lMQ*?866!KoqPNg{dVKQoj+um%fdUuDl zB0*TfrZVB?i4w^-`&&eGzHi zldkuu(N7#VrfpsT>=<6*eC3po$B7Y$ZEVx(ZVxYN{3>H?Q_W`NjhMycSGPnm!9*(r zn_dfB9Y7JHG8~=?rSYv-o$?!~VI8m0du;1aN{Vmc<#)g4OHmcTpMZfSL zJ9(;?kKbK=J}MPZWIm;3Q%R@KyDV4TY$F{gi-|^6@l5w}U~h`lJ`WZQ!o0rYYbR(L zr1JNZ_+=Z$ti4ACg{|@&(?$nN6M_;tO|yW4MqFV1<_ElpdoOW_J2r&VjN*1lXosqg zd5Bq7tD+)G2G-rA?4wtLmfIi=GA&R>GH2O$eO(*2 z+@j5JP-Msg0!SoY$rGHgs^0;JuW1ANz3+sCw|-Nr3*aItu=Q59&Q=lf&hLi7RmayW zfcr7S89Om@d*X2+TyTDPKzsNqyr736bnQ1KAdVFGu;Q7PZ_g(Zqp%OUp!QXAph*6! z&;257fxf@wZX~z&zCpQhYcY`}@j45}J>_pKah?^o{Uury`a~{PxzrN0-T8$0EMV4d zyBa;t;)sAez`AYbrR!}mtZKKjdN57;88~{izvjF+b+0r#t~%?_htKN55!<($^YcvQ z#^J)%aX%fBg~7l<=v7+LZt~KU8aQK*`}MP9-HCM(&PG=88sST_1BhJS##6qR8nNNQ zlL+r{?HQ-{XdJ?t;JqT~@@X9fra^w;1 zCsZsNDtx5|4U828>9wL`{g*6EQ%*tN;UV4hRy@K!zY~c;ron%11$^!A7~b*)>a8Mm zH%qx+(_XJ%aBA@hy*NBzU`ydz$Fl3GYM$(HfH(y9s(0Z?Hs9}P%J+9&cX!Z~-%3Mz zG_KZI-*e*?uHZ%w>LSlWEZ{nIJ=-QlWxYx@TEZ0~kiGHgqNLaZKlD|qJEts@&k$Eomx#}-JRnKkEeUyp{9{AGpBLkS#+aK;f7w8gV%Q+1ASZaxg*&`)xkmde$%^t+SHuIPs^{1F^;(<4comANw+Y+ zuH^fq5WBpEp;hkZsx+13UWxtGI^)umM(=Hu^LHs3jc?4_O zJoj8;$4fnD3ZouU9g>8#LJ*$U)DJeCek0Rtmkj6wt{E!X6U z7N{y(r@wgh-FWkTM9jzTj_ucBaSIYZ#ODgi8Czpw;ll8^qIx2uhh)+)td*B z(jqgT6M<_W3KI`XOxOW8h5;>;FVDMiG|~0w@VM9D!kI+#=MeNC3wmoHVJQI#tDeh< zf}`7bJ=^rfwUrfh3MRe7!j@u4c}xgNq{$bxRK|}J+{^NSyYLWl64&)h8TNmMGYR>5vG2G1$E+<=@Q4-lv=HR;eL)Lj%Y z>DB=~3LEqE{zZCy!w;HxZJ-JmC0Ta_&#c^wZxjB_af1Z*&He6z`LXyjgU(Rg+Sf9)^i z7GC@l#504%*1-rMJfzhRzkF~qE*g2jdx#7>JlCCi%~iDjTSVfcoqY}ZO9*za7ZCI* z5q03GakIE3uL72o#>j(IotE!vu##9W)ELSj#sTDJjzwkdPk(2~1von_r4KrQO?Rl{ zH1NwsMMD1#cJ6b#-<}7I!~W+%OazDQ#hOoVY+c?90904akvq*5h7ZMq%fq?wo+uBr zrAx~vU6)09iOexK(M%H6XJL8gQyrJVjt4Lseb(YuWtM-}=d8WRmvinj2GGHC>%piv zfKqYRw?gOP)EJ=lO9vsv?P;EMN9rJ3u&*t89yI~CCYFQ$S?v~4O59%>#-;y=&Mk3% zt=V_JW7F&hl{1_jxSa#H@K%D9LZ*MF|&;LS) zVLI>se`I}kIGo+~w$XbJqxUWt2}T6bJJAw}-g}EgZ-aGN9_vW16bt6R>YwdfnO!JYJ{77^$Ws)>HY07>nsUD=|UhkmZCLzs>i9+PC4s4*?5FEK6x$#mkrrQXgMG0#k;Pbp!=55Skp%Na0Z+n20 z$fb^Mg%|95bWPuj@l)>FG4_s1LDaG0^L zNDuz1+r2(Yez|xdg;ckCGb&X)S~wZnhmnZsw)kdxNoVJgCk61N&L=cPJr`zsHtxBZ ze(OWNNLkP36y2v9)2+C>TH{`zYX8ZADE<97oZBu`bHaZ;s*7Ks%|5c7uopaBt_@mZ zg}0)fOT1a-Vs4ZtF0pS}XpcV0$xUrEefikaBI))EmFc^=og`AMUjbSW_-!t0_kX7{ z#H`5zx_V2~V4z@f%Xdk2F4u@xqP`EpWO?4dV~J#eZQT}yCj073dwZE8#lL7*{ou?_ zd_O{j2Fdi?{RA@NYqA^h7#zXTllYKQX$7g!#x^5)NZsVlkk}Fl2*X5xS%YClOK5@a z7pK=A-~*!-Y7w%JjrufY@QNU&b7QMtZv%>^%c)eRP^+gxI@8lrvdct(E=;Oh0*lKc#wnY)^82f;&9C1%dZvazcR9=xB=#m=X7%@&U0sR;xvj29WV;r7AZa%v9 zm&ST#40~w$U*8(`Nq{LF0Vc_mwjEMT+3>actrVi+Oxv!5VSMy->)HKZYs%(!BKoW+ z&Cy~pgP+#&-9*k=Ubt&9X8YlkYsk3cXtTf9YsYRP1Da$8&>@_-ccw{xauuin zH6r?y4G~3@Ap>`)Ij#_vTfbks=yY5DY8CHQ?k5wjIMdI&gQ{&}aszxR;C()BW<|lu z5dS&*a+9=*yJ_SqC}DCH@(_q=*G2GUQiZ7wUNCKwF^jpgxzo1OEIJqv(J-6yiAAVP zyzqSgMabbk8cg;Ge+r`NG@<7tCDx z{Su;vmn|}}arI0+1+~|3tSl@*>SA{eUpsey{P0%m!E5IXc-#;y<`uSrjLu(;zd8tx zIUB4;&3kr_5WKRg@|J-_nZ3eWQSEueIQ*L$33F_d5KSll%mDC~5e@U>P4}rt?zRjW zcHyf^3KeV?K&AKH#mAh4`c5a&I3J!AbIcqyL3eZGW1#RBevs?su@OQSUO7^eYE+MW z3gq^s;tdC;HXj5)09Od1RJlwexK3pE&T3I;ZkKrvor6C)s&`k-ZJ{Tte|epmUz>m- z&`pX_s!{Y0PUzLczY~|Zv_9~6FW#`YcrB+jKUS*Ek;!yZIh#Q6P0RIwA9#Xy4MfuA z;WB-budw{p$R8g8@lSQEOx=}>@@|hc4g`^&@g5dq#@vyEl}9!9l^8_z%R99PrR`&z ztNxyhBNHur_|IRXwfrZ)KH92xR5wWO*yIW3G0kPhUr;43f@kjCl}W3Zl4TCtT_9YL zS|pRs1lsFFT4>JM4mhlAv(VTwNjDX|JJ76|kAOCR`pNI#oX7+wx54$v%hE$p0^nkN zcO`{lcPVj1_h$met#0GLrhOU=3*V~_ycFc>Ofws@t*BTkr9*Pn<>UrMgR4f%Z!Npy zX(N+Vb2(H*@Mj3#dha@HdTgGL9CvES5qQ3Uf6K3Ao3ur4@42iAYqC`5P*3JxK+8ZL z6KN~Sd0LFQQ1LAW&i4JQ4R)GvZri2mrtj-hDk;A@r_oo4?SL_6;IzLPW@p&7mg+GQ zKIGV~bnSj|XpR{y5;5O=$CtNyvXd%ma)dZJXfwSz3Qz+6jlheZ(v4w!SMk$_^9dBn z&M{K4Ea4XbsQDeCL7x5*M3b)q-J|=M<%zF!u-)(g)z)mI%{-Qz-l*aI ziiADuV(1uM-VQZLV{;~h?##L9_BGtU${mKQgBrj6hCj8Cz^0~A)!G9huS^j#YG03* z;@tqUajR_v5WaP-ftZ49qi^Ej5Cg3bR8!iGRu|!eDcZn`TOIEYWU6`y}$89 z{Z>Zz=dit2f_V=r4+v16a0j7@O)z$ZeRrN%y~-l6@?kr9_g?Lek%rEkV!g%kH;vw3JWv!J9whxO>7{*ng$53TrTxFh|s<{It@MSxIPul-v zHNg!`1m}ei0fPY?t==@UH)3hyCU8gI=&-&2E!#>q?{}v`^e*~sLVPM^qVxywS*|LO3GqcnBXolt(60c71hn6rpy>g1 z35}FebyioK+d-H^ZJotB1b{5?f5LdzF^+90N3&SUen>Vczcld|dBuTMDr6~Jgg*a^ z_Tk&8#Sm(qzd((Dtngz<4X~!iFK?NiL{;}`p4Qmx#+7KI^C|O4lI-1X|I+DLuX*1g zJ52^Q5_u*mjrb2;Fdh$!t&DOenbG>q2iILM%ddF>nV&u`<^b&Kt>I{dE9`HPnB_NT zOZX=0#Mf{oK!6E!AZgY2x^rF#30|Qlq=oqFpOpBZBqkmCwme$rbbXMhw0|)BKBKud z?)|hDeow*sycES13BX7R;$iBC6@Y5}=8H@2iL*Pef5rpj_i)ZooIRl5LboCvX-1U; z2l2=(cK8bg)*F%Kqo$w87e~%hz^?2{CZFXQ-MYq{b+cRm%x1j4B-vV%9!KjIlwUnH z?4(&yy#(@PpsdGL!K%|OL4Y1By4GjO@}0pi6#9hQXhK}FHa-+gPOqc{aufkoh~lQ? zMk`a)ibqyjh4x0h?O?Qg+#whaMqt#&#N>;Fs=j~r!tQ;Y%g!{Rmh9J!I1QL*SZ4A~HT)GuuleLWh?Gy@ z%pB+FJ3gQguejt+J46LS1`!Lhw@_!qm#_Tl9BzU4W2jHdF(xc2MD>amTaNtp_YodT z>GQLig2&02*96YH%3IvfMuB@O4|UPVwK-1rtI>Ekv+ zc(~ipBnVkZKAP#wC#}7`)-`iCl-5cSeJa)P%yD0X{A%s}a46(BWII!^_y6ooHkJaF zvidqIhemIk=MH1f_a~)dcYNSc)92#I!E}76Fy}i@)-F_yoQKWY8%Xb2-Yz}Dcf@Vd zc89HG87aJ!h+JcZ#3(Lv<~k=I%+h`XQ#fTNz^^fV{i3{{dfXeTJPzW>@`AAvQ+{cZ z3=w}@Yw%VCZwAcay&n_p9fHk~Ba876e<5)I6B+aD%vWk&vd`>Hs)bfW;&p&8MiUX$ zuMlbF6EvRNGlD7<8X8y7NrNB?RS==W@c*fYblj4WM?Bs^gC@GY!{p1?Lkxe7@+p&FyrziB z)KXSunYU0xYlTXSygeS}_8W)49?rjb9NT%zuD~41%USVhwq__v&hp zsV?-Lc}SOet8fAJ^mXVl3YVk%%^h@j!t!>YmNdQG0V59s^}WovB+`cNs2gJ|?9(oh zaUh@fdO*|T&93z{CXfwxK?kIELDnqQDRwYia2{eMOBYkFHk;vHJz9JeCF$0%zN|$# zl*g{6OMXNajsEu@SPS6?{USI4x%;&QjH7e)Qcp2*-Rhrfokn!eeT^$fpQE#NM>($~ z(L8i}8T^C}Pt@i3L7Q_y_+8gfiZjy&hT++}?+I8s+O%&MU%B#rr5UCU;*93*2wSm6 z?3wP{RYERBkoxCR-M-S(-0G%6_;MxWCh`hg_i%k<@LXajt{b})uUR71GU0NB>jA_~ zne|F&_*_Vu1&XM0+p!qnpjUon4aTdSS%N>$o0Pk7Pse zsuH`rUmekInz2E>u;i|BL*6zfgcO66qIeQTJ4h9>H@I$C@B$&-eyQVfXjelft zzj#ki?Sj1%6P>k8!*LGBm|=hIRgSTTso0bI)*(e0m>R4}@Td*?j!r7jb@67c7Tqmyne^?9Vz8W?UurcK zd3y8VvEj>$Y~5N6GU2zkiEHc)9)@r|I{W?;5DKf&0{e6ufT11)Ryrky+)PY{Dw+oa zSgXp5w>LA}>9}rqdmT1h=MayN&9TT(LO%P)Z;N^Hf4}Jt`M1xKzcaNVHfla*Mj3G% z4Uu$yPVYZ*JpIs}qlSeCsh7G8yE{!@XMV4u;9FiQ9RIKaO?4hKnEvR79lCu^q;ppj z+hX)467Flx22~fRB&AeRW}*EVzs@YS+1(%(!kidtFez ztBx1Z&2i+EVp54}tqUpt>%l`So%opr&?qA%a`B+OT3Cp3_%Cp{9YblTq;!L63`MHS zR5<1C8!g6s(+9P}M(eQgs!OHTUJB8EXi|ZX6<=?ak@td|pnW6o9emjVpk*;NRN$+) zJT+m!wl`1j9{0qPbi|i`?vZ1^B|Ri&XWf0Ay)$$9(gNGJ=K8K$od^&Nz#Zu4NOSNw znx@a%CCpQGhMwb!h43NEYE=^FdrQ5mMkTZ?*1GjKN>v2KN}hJ-|Fs|ASVGhTu znXH_k_0#6TE93u(0#WUGys2AId_$!K7qZN81YvV_WNJ_OlTvZP3<}($#JTGa*oy0o z&&%zGwgpz-d*(gEUQg2dY{1o2d_f1ifzf$9q`GzM6T#OcA&2d8dL}5WJ`5IYZ_kBx z+sgw2rw4KyMD&0|3{_dua61L_SO_2wy@diFsjmlsIr4QZ^VfJF2~E>j0!(M-Ec!7P zQgMKI-GTaLBWE=s$N4hp!%&KAp#Cv@!;SBV@RQz>K)?SVpXe0kWLGw%-C-V7>~|Q` zxY~DWfiSZFh?(=oIuYd9r9GrCZHiute~60J`~3Z8lwv`h!GtVu!m>s8h_+)EVg9%M z2roT-{N;CWUIM&}95D(*<`2`{6G}dIsTyiTJ3%ZPXX#_m_jJ6cZ15O^X2LwtT$2h?1h2CMrbB3 zo3qz~wc<9Zo~%9MdpG)2Kv*_>v-{yM;jmgwk2Tz|3le}$kpQ672TYl*SWVoDCX$!Y zl^fCX>*PMmaIu4%zM1>#Df!y#F5WF}Dqf)RsFct?3yL8kzwo^=#c|I%pnMOpRuM_m zKW4UDsQ|+G1MQPuhOIGW8zIx-C_N|rf4+SfE$KaqF%nG0R)7|nAur1)%C!Tr&Y@Lr z`_6J!LR4DBJ)?{S!EnrCh&+vd7>9s{2cX<5eGBFYiJekI8ToSf58`v6dmC zHXCOTe?N~)y3s+(rSTC}kpN_Z(U-D!zzZEwS!;Va=ZXjdHnBecdq{dqRGt*s%IrEC zej5rvF3kSA|Di(%ruS3SIiO&@WBTYF-^4rYHupWK!&z|6c6gTFsQzAxV|XT1Hnm5> zZet$xj*eX!&d3!Whegovd3jW9eo5~7ss(KS0YQoXmrg4Iy|D2~0_RJL{XyQIdRBaS z@(+LmXzD^(l0`!TEc7q0gC%=Gc_{~9pI9lLNWq*1g?poJP(b7*;y8OMqD^?`a#x0Y zbt9FN8Plx?$^oD)1=VgyW^-JUf`P|SUjAtbD>dTBKYJF#T3n`wET^4t;{>oz8LoN))(?Sb zMuTk$)#Yvy)G(_ZpvE}{_}cvZnGCrR_RjmxuTQYZEFz8>V5N{S^m1s6{7H0n2A>Mh zkMEZ*ileroi}a4W*GY+FM>ZltAe(3$w$U+v19IGsk$;vMQBOml{GG99`pbRMRXoHG2L%5@yQ57>Ig&t~SkFCT}p5*L~(tib=po>}pq5u^pR_lZ)((Kfh# zi149_dfCoA%6;YWslP+aPbY@9)8C@lL`m*n&q37zg$i#t9~IlB{QIJNM{7+~ z3Rmt02?~)UaaH>@iw+~rh8f5ql3R1%)}Qux36|%pz>x!M8vxLv-v>YWCSr*NEJ7Cn zFf{)OBise&^EK%}Oi1B4xP(x6!8W3IMfxBlfl+Ofog?r9$kklL_ zg19yJn6M|MTrv5)G5Jx9m^hXjj~kRn-;?n`*!A8*tl}Hm_B`k4MZTH3PS(Ls=iI+B zOT{}A_`5lp7{4VMH^!<2wc}iY&&3XikjV%(gd4(TrO2n;vik`fWm{It0*ijq!pYERO3;bjxf~<(WjTT-7>ei?l}DXyxtrn6HCZRH;&-wZ*ui;%S9eRg ze5C|^89gwSuiUu$`$CNY*S5!CLExhppk~vI76Hgjge3wG7Q!7Ef7b$-;B(-v$sOhn z62=oZoFcU#ckm>k@V#%Sm3&gD(#mL$KYI?5Q9z?SK@3oK;@NBcJTI z(RCS3um(5J5_U0Eixc^>SFse^ZT|p=?~?!uTT2bu>(+7K?;yRAg9wxe?pjF+Rk@i5 z`!&DAwc9!{SHOY8fC@);Vt#gjsS}@|RaRn}u zS?OKLx>Oz~B7P&7wkSKRK2AAtz30*)kDxX;(4|%aev;UPosaW+kt!0Y(eKCe)Way| zNK0l`e`mXQnoU>9PHMa0wKAPkDj!_4dfYEw+Zjoxuba2f8+U_6ch50#1TTfDjb6N1 zu?6u`-My6mel1_Q+;y@ZHpJz0u2R+LGB5OEK`3!wfg{hojLobek+35Jmz$Dt6(9sL z&^Io6Lx2MTImF3OXM7epIAyXB`UTQOv!OT*BlC5jS%6i|C z@^j;iuFs3(J1e{4J%tb`GmgIihY&kr%k|;4*iyUtmYuPp0=*xOM$ZSC}uf z-6*HHn;j^zMT%PDJ*ZuriOKwgkz0)lz(3HOcbDiYjLiP!6?Y2LcMS*(2Sn_@qkzm_ zUn2hUDFx%88MTej&x-^VI-(=?hw;7Sybmwq`_fl!@}@rNlSi=SNZ<_*_X4>L24Rd5 zOgFD{?efmTVL1KyodYGLA%Ya-)ub(mkrOw7aY_%g6^g#2y=DR35M3?G?E6@W65)4_ z74*>~9Hsf^OL^6=Xm8I%_ZGhnUl($Rvvg1!4t-00v|%GiH?iJ!=imX72>cUB@!b4) z+zJtq=&rW2b{ePv$;9xHj8)z|C0%!28Nm56U{W(oiE51(K#rI#F z97{ZqH6XD-Eb2rpk*O(rpp2wVrz9|&b!GlQW8Y}^Hv zqkOb=`U_|p&{cnv=uqT`ZE5kdmej*6@f)r{3?=&S6{nm7LB#jFXYBc1QGUhP){#=k z^sLd!m=G1QcK4hY%pGgF?%JQsLL;95bsRcvtv8&5x1;dF(Rf>tNAifk)Nbpb*hEOq_1;4gKwI*@hx9<~jR33#7@HQ-o09Ht)_JTT2j-11@qw1B*e3ti zGCPc0={SO=H(Cp{&mE@o>0Pqpxj=o6kB6e_XAv5%3?_t(VV{p5^jXilLL8qhhw|Z! z5pijL4PD)-_OUWm3H#kWiu;)DL;7>J0$w`C+Hk<4b$iR}I-*v+Pch@1)lM4gdKrQA zhMZEWm2L8-ggCBu-Lb^9sFoLO7xu|Y@th3w^j+%)oW6;+iLeR#`~i0@qSxOg44H_( zjrHlYWT)oV^Zv$@+pNzJ!tjJ&)JbvBf&8h#AXZi!7wO6dxFi3?U3*k8Irq11O3e#2 z$p#bTOkPv^gvR6k%`8a$3^h_x@hp7@bGfchlKo?_l#(x`KGND0g{=;{uO_nkC|B2W zXB{tz%>Hx9>hp=~yYUbea%{^ahB*rai4r28VU5yGR#70;qQCic(n+fiH${X}Dzr zcGk=|8s!bWVYDzuGW_Vj+D;H}CiT_EM2)e2NZ+b6$6Q7e64)~K6F4PY2U1+~B~!jK z(P)9cN|Y3uHc|jq=sV6CGHVkPH4Njy(!oo>8Nqt;whRf!H6mPy;^R40K%OGJor2}? z-=uGot^?n)?#~5^XnL55(4GVLy+H@0pcPG>DL-fOQb5ECG{J@Bil_-EnE=7Xg{Fcr z?6h5h_w_&kH0LYFkToOa~*>R7@})z#fZID<>n2$D>9464CFJ$uA5>$|I$`qVB2c$ z%c4q&PV!{!D?z@$V-xajnEBRv=s#X&;(ep;vQz~M4!PhpKSyd8JVy6*_wtnA=E!GG zM@BOkGqWS^XN}j_tB6Ke2nGr>ZC-Na^lbSTV$-R)LyoYazh>Ltput!d0Or3*8o(>T z*ifP%oOYGzp5WmER};nhqtLT>iiPcu{`D+4uA_cu%MuuHjEWw`eRCWW;?^#D&PGe_ zno{f?+xX-VtO`&&Y=H7{bzfF&h#KsvRX(~ew4Aavmpj4ANjBdGKLbE->n+ZXA`%)& zH(&&*i3WrAH8&D`CuQY1IX0Vv+dOBRi)eV%w6&<{qQ-?bhJ67sv8Bj-!}RJ-<25-l z8SE+RGCw_))uR$4t_C=QOVgi@@K_N_bU?c;gE5E&LkQyr`wCnC_|(n0DQn*&AzS3LRT`#wU!jE7MUW4rK8NzacS_M- zEeJG0RnB^}E{JxEbY6^|xg|IMyAh^!NiFP2?n^oHNM9LQ?H98)k)VCtV1kG8&7>HE zFySv>gLE;)I}49O#6427@s{5`x|CHLHa4-b$b9)c@ms=wg+wK}jGs}|F&vyrI;|yB zO-4~_Iv0@3Bc_TqJG!O% zZCf9iWjC4%a;mxh(p5sZ1J$XfxqA`(bbwbqvV&i4UW?Ojd{lg=i8lRPCMiA{}Jzb#4x-0-5oPw zTzm{ylGyO{Gf;~23X;^2w6aG^A>eAu1W0A6r;Of1cnx@GAX2<`43mr(^X3(H!Ze}{ z`VT5qY^VQ>r4bK50%R8})iXBh6$Mc;RM{vFJIdOTAX_YqBYO1(X5-0{(q=&>h{rnr z0v<-ODsUcq$fc=1*=UiaI?@9riNhSNgS&=NoT4z7Vm&F(*|`}Wk<4`6pv!;wqP>3% zlarrids65-U&p-bkY0UM^vK$C?D9u9^i5NHnq$10W8C!4I|D|>pf(cy z1_#d~3zC-9PK8*e8%a6Y2F+szU=HgST z;TDlPWZM*E)x_1jqL7#@aX0mZ?kh=OXc&ag^M(V_g1L&Ris6v`prx9m_^+@_luCZ&WlB2har0-BEPbNjyz{Ao!sn5*Ej z7U+=2a1E7(=lce&4<$>mA z|MqeFmZC|2193CJs_5nZLlTn2zHw4nX83$p<$3;)XjL}@SyBe&s|mkQwy0|?N-KH7 z;opEE+##wyuPN$F;anT~)HuA>+`#B_*P}M#WHk$(6)83-TnG5fbXA_^ahb>6?8vmC z6p$n6)2n#r;6D1n&rQe)_x3xM#Kw_&XrP|B?5C#>81OM2+IiRHWdH@1eLs1>Pt zf-u&?*LlC!@5e;#b#p(tYDqs)+Gv4U;}$O3%{R>B=+AA%15ab{1`;`BhmCo=_laiuN49el1|Eyqt=BpCR~{^{{o304El28_al4t||JsZOhgm%mMfU_8 zYwLbME*X%GVh-!sCfv&)bn+$IBeD3}=Pp3?z+G5(L`<}Ji?zG=&OXB}r>9ZQlLZ5# zmW3?lnde7vmq^NRgG1FawqAcdOFy0vt)qaMUVde25-)}Y zgx%N=d2Djr)qEB!hi(Us#D*lzZyp?;YRV@>iaUbs#udbNQ3?JOo^PRGfrtEz7zA2- zH2UGl{hs|Vr6?B32FC{guSehcgD^!v@hPK=d4n%T=x0?>&Gc`$u@pZwB++tHHvUjp z*aB*46gb^{VUyMYrW)kR2R;)<3J(w4H6a{7)d#MS;pQ3c+usW)Pmz~Gh^LyW38?qR?>(x=v6?n zSj?=z+TVaJr4xBU$1qnB+fo|K8a>lAd8xAA6q2UCo0bRR4V9&(C^E@L=UYU@qxo|e z_laNq!dxzhJr|REK#?ogo9BoZ{y5uVyuY4Y`LlrZ9y}+HVtV^|4LORNNpX(9C)Ox{ zko%qUTzeN+uIoBh04A-)M3M|kvUFZ$q&T~BOOi!OTvroB`=(%t;E+^15}e$;99?{U zIl+8snsj*G6sIGE;%8F_NQGq6(0p-Hm!X6V;T5ToTr>L#2SQD<1?30s`_6+gT08B7 zvl(?mW~q*+IV-uu0GkHI4)hXOki9zH(Ivku27LR>;y=E9+bw`k*$~6+t1Jg6P7;!z z=e^Os#w~Cdq+H1l!$n2MWjW;Ec^o1 zBj=vWM+(!jiI3b9*3XKnj}NsjdwcXya|=xZJ1vL2Vz5v_PMx7jVLsi^Wf#qtKTNLf zkwl2!y2$HvT~W4i1l#H(SUc9@bcoHgI8{V!p)6~-Gbuf-a3?-mN#GY7ekU-Ig9K@) zuz)L8BmC9y<&Nb%XM753v6bFeyB9U>t-VO+`#?ELmc>`_^`$ZH0x-t|c!$d3tCzU_ zfyjj{uzN4r8;Ii-IV6Nm`?u6eT=38QNI19IX;>{dJxpYZ7`lIiG0x}s^XpHqtjUMO z<@KS*y_*bXeF@?IkEF_@{erPvS@JGp+-dxAEf*1G%r{&G8p*;X{Gt>H9zS{DZ)QJ?%6VHwjlQ6)%#}uZ&XVwa}Tqp3u-80|H!X& zIj3Y18bQVRyuWM7Dt+~TbSdLPyXToOP9xkU$Qh*-JzhUD*|dHm}|9>Z2528^JomlyO}C^d|IDu(G>QPg*45V?4RG2t|R-7Qqk~ zKk2nqR$!XeAr*R%bUBW1!si9p6HMC|n#q*YBd>)6ToWbtrpq2lJHbJ6t2R7OzYt`v zxjqXtj)}B}u>YPQj@W?2oo92}Su-m7V4w9CPNNBwvve*lp3Z#jkOuOi_Mz7zy4RME zYjzJ@=Fgs`VEPs``>O++o|n1Z^qv3Ov~>w1j~U?wd!Af~C_N_|@l$>3H0OlgVzm}m zoTj%gvv^u7xCVon8-uoat;*w{Ap)KI7nz}$=a>i1nlGn(La#6G?1mZppA)Mi#v z5dhaMdMY*a3n^I*j^qyhIIr#?gcxEPwrh2Q7m~_%?JgrA;_+CQ$=Zsw)Ac6>vfTq^B7*y=EI+Ws zalA2e@LFllEACi@B=F%?slEFbGP?eVtuTBFwLnEfn%?5Fdd&%TaS^qi`DUHbCGuP?*`8!7`JuDBw0CalTKUS*Ij&bAhw>z?pV1NY4zf= zu-5cPw?W=s=YoRc)Q&?4tK6UbeQqyzXuq$kP*P@wVHa03o)D#>SU-ys_$L-K&TXqx zGx6hxp-}D0-nv(bmicikgw;CwiF|MU<~hG@O~iM>SU^4$<|pR33t?*Rz+^ivaGwtC zQ1z&X3Niz6h*(xLJ2AJe^rCN?A5luIUmvF2wp6DJq%zV5?%2zQPZJ?OnOuN@zWxT@ zHh;vrk47a)ra{}m`M3{N&*(@@Ubm_v?h!udg$}61OdrrL3?>BGQyg-92(RE8Msbwv zt`f$O#L!iX&rcBTJ}94mzPcs=OBT_!gV$VJcGCykllVI_xYUY&AK+en^xfI{^!J=e zPESwzJIXIack$(?Mz}uM(DtAo$y?bzOB5dWGp6@i%U@+eNJe<6Kf@~PRvcS)gMVG_ zEgW8+J8bm|jTad|xCCZM(tJ9Qspx<%J&dBb7RFw}dDx!lx+LU&;G+3HLQoyls%t9! zFtS@_3n<&%efG!U^~-*=`aFGLo`3b3|;{ z7ruUr!RAeJ$f$8~UDjpAf#gfyD3gZBhX5Tx#vmPRGweVNee*L$BoAWVB(Bph!JDn6 z41oDh&L^@0axGd{6+i9X9QqI{g%WnMj<`C5@rsI>D#LoW$_mcAUYI0`9ig0J{`#gv zg0*H@bMJaUF3K!AIuDL_PV4dD0PT^OmrLRj|DO!?Cl1M{_mIn?!y8v_p5kp0vnQ>?+9DAiEN z>@TnySi1{0|)~jw#+|g z(KuvG_O&N0+3@`Iz&(>acQ*ARI$MO|>ZxztG=E&W49OLPz9{ou|2d89p>Mi3m{*%`nSqqXp z?~jN0>WbXav{9e4a*DUfkK;eL=XbC>iF2ZeQ?yl4*mlOJ9cTRYd?GBCoc?L6&KKb# zAUeovHc#9+ThhjmA;_{sqXiINhiZqpc)))1O`9(QX>`}bY6hU>%Ft(#pLe%W?cc4; zk_Us(#7z$PaQ85g5{E>lS2fWq?$1C+?bL~~uKU(QOZxG2pFXQ6LNxmAmc(H-9WPg( zA;?0}qEx$RRuAa|4b7OFPtcKlb%copsP`+<16h}{)MyA+$?gkffK_4%SFH;H_p5KL zSr`i%7o-?Zzm%>!YrW&h{0#W4xZNKv7>Ee zW}Vb)VGn#nTdv1tHf)i0L&Mps{WdYG{#1kuL6dK)9O}$o0>rgx z?Vt@szsNK!i?S+lhD}daM{7LR?V)LWkD7hxqs>-Z1 zhJ_S|MaL0$iUD)D#TM98X_d$)j>G&zRhuJye=&Tc?(?&!Lh=Tf>;LFCR#h-2K5S7I zf5z~wFxfLtK9C0&-jMmSsko-gDCi#dqQ{u8Oul0%>tC2+cKPRhYO*nC=85;08 zJ#iDVnbCwyfWknPO{LA9-(}6{02Iba_>WU#3*vC5!8D+Fo09&VtF3>YfA$mVY)e6n zVDA;MoA8D~=WKP_YSC!m$i5}~`YU^h@tl$SXv+XeU`bM?6zhH1^g2=@w~}Y<#~o*K z(k=5lZ)6_ED9nbZ2i4V9`kPKhh4UVB5J-e2X&Cg2$Drko=z3Ua%>D7C-MFH}L)S zh(@I@hr|VgF_e!iHF5(!aTJU+iNo4TI9mw+k+W@`RfJY=*2Zw&NpEgx_G|}S?iuaZ z3KfC>-h^M5^H`V*V-Y1uy)Ow{LZjakdDpDe&<+0(HSqKBxSd$WhQU(H1*NF?x#hVM zTE%lg&^$&Z4r!;fw96i`tD+A$rrG>E>Q#&bskvt#UD_q_w;ZG>Gn%rA7v`f%9&x^^ zmF-e+{)tbSIwa-mI8gk-0baOwUb}Cd-B2Y=X6$K zBkP@cC5y44$Gpm$L~>wG-8#GFL*2^+EeII!l_AALQ~>F?qApq~qcL7Ii*7RC%K9>g zOWLih0ewRR1^IrFe(D%C=gnLteGojs=YB+f@X8{gx%z$&#<~MgNSo96bH(O66z{0? zo!R1s)#^fCyVO4LT{NGFd_w!vlfuJRj-=)^RHi=CcO~dGDBfuBH)Fo`{Wl*e`mVnb z#Mu{MOJ#I>mU;Sxw1nhxwm$ZG-|ilk)Vv|tsY#8-2HbgB;X?On66| zWWG51=?~|05wi2TJMWSM;Viu=DgKmId?G&mbM?D_RWTPAb~dVs*UHa#tRy08zsDEx zJt&LK`X6)eShQf^EdI-odRU+{>T^AQ?}n57=%UhnVIGg1`#orJ`h=CGXG4mY)N0s* zt514awc&J4)fP$lrVrhOw}N$hYpdj!3_>5Ty%;)Vo)_D#Hmz_ZZjuc5)FzL#b<^i) z;l1e-(Y+!QH35Q8#M<8Fm(ms*t0kI~a%u~EBm)Q-c5ULed~K;nuzG%=i*)yv`5I$0 z$Zzs`fWNBz_Cu39bEHY$fFC~zi2mbl)fV5hN_~&XUl&>9d#bLm+q$8Jq&LOx_8$`O zm%nmnc&YXu|OtVZ}vZLS@E?_Pq9=?2#|w0gKmd zvr|v^PoTZ~p|Jx(UD3A>9&8wTWVL`#o(z2QX*^AjYOd7|!T35;~7=s%tdDdbZgN}_3EHZ=Zo$v?Z(_^6}bafZ=Uwsjvq z7@r7J*`yM}v`UfD<&Zjr>o?(33iO6v4>VxQzbm1TUYRIbChmsnBEBldJIvBL*=&oP zkpHZehteHBJlk%s+-q;)4Z|^aeu~*Nr2HClqe2w?alJ4l={JA~(Vmj`1eC_QL%w2_%+$Q(vgVj*|J0SY*a{ZHW5OFDaYidxEl#u?R2tTthbc1WiHlEw9 zh{U9Ekl`D48YF7o-HBSnsvPMRE&4C35Vkgz;69*5Gmr)a8Z1l59rTdU;XB2w=mfhh z6M|V@2X@*niAUFb_x(u%jI-Q3r;n6v#Prs!X6~i92=I=}#eI?#Scv98EQgMQ-hiZl zrzNvZvFL3qJgjBxJ&gAI4opwaCKZ2Z0(`JO?VkdCrwIPAwT(X6bA0zYlIN}d1W&|P zl*S_=n&Q#9o`^x{qOd~gV2cOFX6hqV2E&ypJMT>i5<==~aiIHx@V5_G-FnBtI{!`6 zROKaAgj{#29(ja`Z+MVSCSba0r%?9z_(`W0`HIP~HP_XP1iyTOtB#mi#{}KMP#xMb z*EQ>ilS&M9ui{^_gk{j}te;}jJ?|6I#t@qS zH9jU22DcudUx`N95>i%+TX;p&10Vl;f3IbUw2;B;y#inj^TtM|EEJPp|GxL5bWAzMPo^sL4{L8K$t{M?zi%KT*a872&h;DFhG&!A(>niiBw@s= z^6)D1b5m?cebz^O8pB6rZ-ozK%TzNW(=+aTP}GTiusP<=|JOq+*GKD=B>A@HQO&vA z=j7jMd)Whhw#pc$*6k5ySXZjK)N-nfcP?`zb{cK7d^7CwQ$A%>t-IxkVpub~8t6*g zeF&V2{$I6M2JmWHkH|ZPlgzOdSUH(p;=b%24-a^dG;!%U$}woJ^cVQl&A#eX_xVq(4&oU^Z5w8wAjc7GRC zntAY3l=OT5r*pEs%>i=-&wGvr_#+GCjmvRK`fmzAIT|U^?}OO3f`g|izQeikS*i_V zSp^e-sjzYz(~Wg@a2%~mA?+kBt-UjpPiKOwR>0kQklQ|C%mvE{iZ6bDO9ZKeAcKgl zPBQ!4ghiX|OEBZLVnJD`bt>fIRi+&a$Ox#SIH|a4omDv;Kql3qK|3m<28{> zQapPxfb?1~XsX4rfxe{itakoxz&lp`p5pJ9u~R6LAH|=Up;gt01Au5)Km_0eCPQX+NPSVcQ!fn!%%yhsy_7}&z4^rXKlMbB9EppG#UJ2-W0W# z{FnLF{{1>_N|QMYirJ~hI`pR)zFlzF+cXe$YJ)1HI~hMg}vI%IP<)xoyC{dV++)2-BoKk8r;K&>4Ubrqm#4wS=| z{kCu_)lYRps{MznY(dM|mJVyOVp4Wu1MOLeLh0po+HAg?7OvLkD5=BAC}-BKCjkBJ}_bVSJ0H0einAsIKRIMU}72 z)sKqs2~$BzXOrz^)n6+98%^cmx@;|Td-CnbR^Rw0bIPFNpAIR)?>>r^)OD~gXt4g} z`H(Kr(#C63;?)JXTD{+qsEMoCU^tf&=Mu{j3Cpgg$mnr_^dtne;^mO5g`b*qp~xe&HF`<>sT&Q<|3iS> zDj4vSBRkX;<*i7q6L^{XD)JNFlT0zG=+Bw1|H8-Ao&(g3&oy-4(EYZp(2JnI5nzy< zN44)-4&+Ztr~Wnh1xXR<=draxZhZT7Ujo#F)qlLu$@mHcM@9Q5x1Pfl0eB)UuEfQ5 zrw^J`sR>>LpMb~Ax+Ztx_91>GIB*B4!j;mkjg0UR+Y8dsaQ@wnesMn@6WpwA9*MsV z5KjdE%^C9CzUC^1GdAm)`x>7Tg2){Vz$DjMr!+~De1(pr7{B^r;pxIOBJtr+gRjz= znNY1gO3z#fh+ep4bbkVe`Ya&9U#z=E$d@WUdyxCpC~y%22J>0A7JD9i#B^VE�Am zmh0g<6%r1PS<(Il)jJQdQ`Mj|^W4@pl)G3%x==aHda6D-Ck<0QxCZc{g^{0GSEJPp zE#hXSm&s>*@v}!WUtBdOCf>b{cX=Y$Uhv=YMZ3@$BbfR_R9pdMPa8$2BvTcrBxTRC z0u+J=S$CgTTOD^N43BkKZNIa#|3urh{wSUx+}dmun9@GnQ0}HS@{XSS0s3phE^q4P zn0d;w%vx{7d z65l(2GS8(7*#I{PMl+o$p!4lEH|WEz9>{h}c5#Fye$zelKr;Xd^aUWkeuzASYH4`o zNz+4|<}?6=@Mh8wH~UZT#eYRF3nDf7W&nvry_7*c7~ouWK~+@co@;4-b;{vSq7s(aDn z(-jl*SO6T)OH==aQM(B`0;-T*<*e)3cFe3?9#k+MVgym+_^Cw&&rC z7J-65WRzQxBWY*O+Gr4_>xjnc&W?UmhNJvK!l zyvGY{&;Ng<&0P!uVt}P}6{@PKNjXw8<+JXWwDIixYQZct+>u$0%zp%riu1E@%> z8^jIrTE@L!u_pWm@NH+-ciMob-2Z&rwl7zL7HDF!VjaMm00vwG;Ul3Z@A%QYKMBmNx((ZIoxN@jlkcG9x*JyP>VNm~ zBF{$T;;wC3;H*|+eO1){t>YqbCV>Uuhd(CYqvsAz@+ksb(Cx=>VQ(7g!4Fp$yBh^P1$!#;w!mTK_0OZp3xNCh4u)d@7ci zT{R_ob{E6dU*U58Lxyw;W3=uPXZ)D?)S#G!}Q`etLO+H!h4-~A{a}m>zZqW{T`c2Z=xzcf8KO5RF3Qq9mU6rVdk=4FQAwD6*yxpxy z6BfcidVX=6Raca9(9v-QQ&hYVI=iDPMtKX@3?uI+wX+H9E#X@;f$I?Qu{5!{0F|^1PkAJYT1N>QohF|%z1=Qxux zcMwL`s-N9eG5~rYKlngM?2l8G?u~j(|Lb2NO?7CgJ0>CNon|jZ9x_n>KzJLMD2YA} z@SSrZWRHfEzIeEKkK)WbkX&{-HnIJX2@P7!^w3}JlqNaNM{ZzMjy9ko$n9MPU3*${*yxALE~dHdWCl`)WtkgAtSC@BUp4s`dfamj=f<5s;mGD;g)^av zr@GJa5{A@Yy}IEG2|5887zjprK9(efD%2LA*`U9B%aYL^WOGp z=fq=<;z%)BV{q=c5}DzZ!$$8_XRXDaw$h)OMF(pQ~5#qcpvC{q$VT*%H~m6tkC|B z>41h=Z|z^Rh9E=S9Hq9Rrz;E7nn{=Bqrx{lFU&`vI(=&d@o=nz$Od_>9iY87gE0|q z@AfN#h=VUFdm!-Xep2t$TeDpZ)!s-};oC^+$R46|F-2)IOj46afLihF)RyZF;4e+7d7Ry3ba$63zET(`xU9CiJQeQ-~B*ske zyyp3Q6}9+oc=Dbw*48oS%NU#V_ru*4<$)0Q7T-|;Ac0s`{>uq8Z0`` z2-1zB7z^HS0>~qhj-4K&X)066KP!Ik@b?veoT}0i>gGLpYTxR7-RSLf{8*w!9R;bP zWhZ4%Uute-lg3>lyNy+QGoi&t@e1*N)wnnhtr+^wE2ecgvopRt*azlMd7z>?>c@Tv zeJyQ`mK;bPw%0vG4n$Sr|#dcAS?-Q%AvyAD$z3kW-?Q4s!g*%W_2w9NhM?&U)(;HosfO}tDQ z&AFj}ZI%%)l?AJ=2~fX{?eUF|dRTgkgvHLMAn&>ZD(`4}c$&4_5OD{4ydgU9;8me0 zCX0QYs)v?kxvvzXaT`Ye1z@3nw4?tVA0XMEHNZ$XK`J3N*BTN+2b6}U#J32x2_I%Q zX*^Pg!1t-k;}W8q<~@ySM;_tMe^pTbxhS7t&1M3$z-HBawNHgTNoPCdy{hxNT|?X7 zZp%2VDtBKmed?yr0}pYPn8>GpqyOuep4h=0WKp6>gWUwQLl z(LnTc<&HEWBY<>+E|&@&j=YjCeJXT^@=@g-Rhz6?5t}d-tUgLzI9``yU^&Nu-f;b2fg;%^ov7UfsFxq z&DyaN(j0qzr03AwwLShBmbC(KKgoLLhYo*f;i2nXt^Hjm*CeH?XT(BnzujUaaf3sF{RCQq0Ou`o_|rc!8m(e z-e==OjDY(aAFxAcbYJ0ZfU*6v(_eg8N!6)8U>@v~)l!m_uAGipTLz_yvRXup=T=S* zbZ5=aT^0TowFZ^DkbepplXi9i8jo&Rn^O`)>I*rt6WqzM5!4M|Z@u`TuXl2tmZb!4 z_Hj|}ae!4R-3;r9MP#X5>J3oZf8KdAOEd&U>~~%1G_M|Rktl-`!E_DNDLYok+-z)` zbRAtkDHiIyp^V4@l^m~hqFkA+((532tIi196p7X8Us%QFFWw2pb zltZpcrjFSQN_Xa7!+dEg1VoK5w|9>##3(>yJ7wqft_pq#It>>bwh7}sP(sflXA&E| zfEl%A5AhcoNVR2?k<4}nG8BmIKdld7?`B|D^f~T`mti|SR#aj$9-tIwi7fz4jkuB^7HeWy+cnK^jvfw?1(TyvYSQlq zMMb9DB!=2J_jgP^vJK?$vZGBZox1a9UCcV4xGQBnUrQc_l!UKaCHq-cT|SZj8bEN` zd_K?XbD2`t#w_!TeYFAf+Bl>X5=D8+<}aytZhZTf!-K`SGLm)L9`YsSukDR)C^YPR zjQJe^eCs2L%YFkfOEZv`vQ%EL>uy|#|J^eg`whgK#A zkko=Vnd(`QatB;!9ki7pdE%q#1wrSHg?M8H>HocV6_p>*H4<-_Br3H^ygl2Kn8*@z zR(d$gOVjJ3mq_|3uyZcmC_q5ffYiYgX_YvEV-e(-Mmd^!?9<%~w#uF%C`;J0e3rT< z?pgpeR)W&VEhBr5oYF1J#?Xa!rN^r`ktzCrw$3?5D*ii@S#3jbVc^WmK7vOh-@C?c z&WbFt9}ZACAZ|W5dcxD~VlW*|q69f*Xo~-(Lo5PB!l>0F4IY6dkrd`8@PQ1P`ExOd zcO(ykC-vtRzPhns?-c|b%GhJa<>1}d|9Q>P;PU1>T88Df!Q6e2&wD<^7tO!Q;2_~PXZ=3LE0J=k{s5j9+wMXH)cp5WGMdgh9@sR zgL&g{=w8s4<%Y3Y5aOWAguQYlFWPd3Euxxol0HD~ViG)NJ97C?o=r|Bf8|ng$&>!5 zm+I$Eo+bag*nN4+SFdhULSkinGmn9Ow6>F*VIhG9CUzkOewJIh1y>Z#xS&GfV)aWbHBAE)BBr6rZ_)7dhs((*G7V3rK8O;@-3ZX|_PQ3BtPi_=c zQyh05=eC&RUeRdWz`(M+=*}$i)xYzx{2(6$W!8mTn^8|Us~dkqO{1mRU%w>l2f;Csc-w*KYe8QCZmdU?MzSz*^ z%0&@!0I4ya$K?)U05d?Q-kUn4w{A#hP)+a-YUR5NY2@&F6_L7eE9K-BtN+b+-#S0~ zmBLbI@S9E-D$j;C?;LeamMhl*9=O#gDOyoaWkdn>mpg+x$bM3RptAH2HYbeRDL~U~ z6I?c!d?7WU^zo#X?)!@TdsBeh6#A#*4Q-Q8L5u}gn|J&4GRVRsZ)pKncCW zHuK|KzlO_m(jT##OQ7~7`LH+SlO(0AU!X_Q#*i`!Ukcv=9TDy)OecI(?9;OvU~Uv8w7L#FH>eh>7YrkJS)aG zBPU|r?tWO7Hwhm%I^XkK!IY8$W29s>y=$MJWg5k@gZ6=`2E75|cc6WnXCa3%S&6i>k1v&|7waCFja&FYlWp%1J%jBU2x+K=*^*;F;1m~L0_&-!+<($RpD zpq=ho6;zTnH!{jsR%qE7aM>;VsgLXhqG4l;%lTrQ6p0^M2z2;KKEd43al$IFJ+AIQ zAVUH{x;*}V{kFlteyi4LI=OXfoyQB~s6${7W35E&iOUbM3o4~rREUrv&!|gW8f+U+ zOiVc^Cdt1lruOFg`q^aAm3oN`kza8W+ZJ}rNK%1iCo}rP5j^2cp!M24DKGvSY|f3! zb$S2kU+I{nkJvj}d5d+otY%Zr;6gSeKXP2ZNBVK(GmzFN6}y{UN3k_4hi%~ECjr_H zMiGO=d1Ppul*`?1O)!R3Gdmktga58oXcIwx?mtcMftYN%$Kk9&vy69YDEVI4lA6k5 zTj}4GJ&orq4*|!xPZ1***bWs3U8zpV0Ao|8Qzc<%7sc+~t8w@1!JAgyCRRNpERRhM zzFhp!2}CEqbI7}p*V8C*6{p`PhJB1)I3}oe@a-4;x%8*$cDc2CK~K?c*vYZtd9S`Z zxGo0Zjjert{3e^Wl;m8~(4xT)w3t&0XxO{x&DQtE5X_GAPVTNiXii+rn#39ZPr1Oy zhC!FlF~4D~SNNS=>1ZSAUL?pbx$xd0C3zVbWDi)Ao@VS4%Sb+hKQk1A0RwN2C61+R zj^-Hkhd@C~-II)dpUT{%I(i7`C71zft1h%=#4C$Xow9lQC0^W@gF>9+SCY)MLDWmw z0(pjr$gIBpwLhVG3--jgLXN1bGr!qwHud2+*unCo(B&iMz8Ix;n_-By-1vabNDy*y_og}^vF{3iGOkVvzNk&&MkL)egobNz=cZX#oER3K^VY(tFlUTG4;QjjB{RumNh;NK$>$`MFR4hElH-Z=$x3Sbdz>aM#lJ%yO0+#SI z;{RWQ_On3;O;eF5y#yzP^0~OG;W5zDMcgV$uJEC0`gNj=qnYEg%4xT&=>o`wHxl0p z;zB`b^-sS?BFo}r<2FfF9Y2!i-R;xd9P!e|>jH$5KV0w4UL)o7z<*+0%w5(y$E;Q_ zi)32;DZ4*Cws*0zGcr?(^KU_YZpcaa?RFB}z6oLBUA(`5VI`e9j{ao(sCdBNc8dBw zWQrmaq~X4LVmiY@*zeptg$b_^t8}hvDl!5WV%*(s*}sWn;lC)*Kp*9k{x@V@F_&MJ zZ_6F>q5A?FDxI8D9sl0zwK#{RBe=---wY^9!X}skf+y*3M_p)Ck6&jSgm;3~YZ(-o zKTD-LJpwcbS>nS|Zl(~65O4VX#J;aG3w>F|%Fchww8fsAgG9%P9 zdepfcW8ym0$^Z7kgA{ATjKBV>{7)I+SMv=j)eu=RH!oBiFPbz#z-^#ieD;7FVl`*~ zf7sPP-}@)AR|H;dErRw09prafb+Qk*^m`haxTDt?Aakv8SK}yR8JuQt-Of@#sd^8I zikpbF0~+dAWBGt5kxv{Q-c{#svAHN%WOF2+Go_S0d~A6TY7?;ix*__)_0d*x)t_L> zc2Dq};mSw#zW&PSKFP-Lv3<1*i)jH?QV}_x@6S1>2!}d`w;F_A3Y=+@+X4ouaFU)6 z4Ohutils(dyO1xFT)6#jcE@?BT+hnj6*GMdtQ2mG+kW zPsET-XLa?DlzP}dpM8atr{T&6e&|KOPm9ixLO%F#LGUYbrQQqZJKQ|COk(`^arXGQrrJv}XjD zPi06Lk!b=6obS^WKmI^^0Cp5{bV+x)&I>RBjNJQ0UGC+&GvVbw7Z-g5ySxudJaNk5 zs3|c`^2vGu`qveR4Sh$Xk{`S7^b*zCQAT;DXYp%^l%M$()p$V?PvnZiyC+)}L~1lS zTH8=8E(_fK$|J2?n2BONW^I^1R`=hKVFfMDn#-q#1G{p3ivxCHg!AZ37@oA(cDuWo zaV6-z<2CB{&k``LuyIc$*NFd9unULY`n6bf)uFyZG>&Ci= z*8Ugc$`Zdki^<7;z!k1h?uNC0 z3eO(Iu8^H-2&-UTBQdawbCUGR>s*bkgS*zqBbYH*i-{=YsA?D1B^j49!u(%8E^m?jZE;)z ztR*m(PiGtq$S?AP1ql1V92iNG$zi1w8b}AQBB0k45A-bl%Lupy_0Si)sj?0AFLcyr zoq6|o{16nd?;-}Zu)_`P7WFZZh7zk>RMnZ)$!v z!mtXeS&~OiARYw}L6c*jFlr~e7^M&gy_g# zh(52r6aomwv5XZ}WAW$>(i$$mz^Y27KCL!$jJ?m7U=vdws4yklzE_v-vlF1hEpZ^^ z$N}g^Z^aUT(42U&1ABVD2za_^(DaZB{OG(*-UI3aby0^g2zMh#kx>hhSF_3f6utO& zSWAKY`DgNsV{zS{ zC8h_Fguig0S1ckqynzah%p_`32;7mvHWL)78c-U}Wu}cT*V_BDoQv62rr^v6`i8yX zjf9Palxth_ilb4Js~Q*XS$(iC0TM=8yDMqM5P^>09OFu&ryS*au)6)ocBfh2T=|E~ zkxC?8{VV|0r;*NNanW$OS?u)+%pL+CeCKmFbMf<3ALoZp)j$TL6?z4o zZfDVFY5ex|PIhyzxwuj2#M?>tcAI03%%et<4xe_L%7}>g?Bz(yjzA1cw8DLox%>4C zi8h9eq+o-pyL9?oJ^*6CTN_ybSd#%gdu`Oqn;DEemsDSdn9 zC%YIHK@!S@r#-JkyvA|xK>gDnqGW$)z_X9y3i$i9o1pMapUyf)pXu9x&!S#aD_CPH zAP>#COUF%n$CazZirn63pXi79m1zl9biRAh=v+-Z=m~h7Ao0?5gvLQv$SDm#Ppljg z|2*=o&9rq&sFqLBYBf&aN6f8CkEv#4&6FHuG@J87GVyWXFaT0h-bf?&Qe~Ia^(dtv zr~gV6^-^7v^k}!a)LwjC&4{CfiHaJ`ye-3J=-(2l` zc1@ZtiZ1NZ!9BF)_{%eR-g8Po%%zq-H2N3`sMq`HyM`}1Xaz1dZv~VzO?`7O+lmZhXJlfw=dgOK*jG6dlIjtGf@x13_#4`jlJ!>om8ewI61zZ-3;14jhV> zxy@-jS(JSgtf7?LPB!~aeZM<;GLlP(Y;lDB)2d#dW(o9C?ROcgI(TpL0lCKkGeeG+&aY9t{*IixPRM0+_V zb6teQOyMiwNe?V~V%y^NJWwoD0T+aIZ5o)I{TIIktoWq$7H1FHTg6|pXcdut{3TU6 zKq<>KX#chQcA`JN@aseIgV!_*+fmX^LI0+-cIZf;Rd(fJ;sM+5v|kJn4FKxB5Q28!x1?Lz_pWgB5na9b zS`biK^1Fi9nYIoW7V29aY7xhF!11|-gmSRSg?{JRG~=13$PVwS@cgwKNqfKV>ly(L z2u7xMFFGqvNYKCT*2yW0PQL+8G7L3Q2Y4+5N$U1f+1mfxOn-e20ak}(_}OU)_1Sj( zx?2gy;Tp|u?J@NSz0&rqO?Lis_H%*6Rn)zm#; z$K(Q}?t-&xkIFkw3BC(PA{!Z|z+L89%n@Q+B3oZT-j7w3He+_YwDXXHGA$ecc2B_Y zb^_)&#Bga0m+@Qd^CGM4GP~r-{hpQ%i2fWQ{?lcpqmk*vv8ZWYxYW?9m>ULgt8m`v zX86G(OsQ^45<=PsD)vLwhkHKzT>j&*6DSKmIemQLKp8Kc*fjly?wqIhWKgFyv(7si za5F^%cKH7aTk+^8!WY{ZyStw@d3L>~R6KjVvqD*VOT_nDSbh=?GZ{ma^;AEGk)DWR z^drurr6PMCE^hR$_|OTn=wzI~~8}2WK7lv>ciSyMGs0Z7AOqqceoOQu8qWowhhH( z#KK%tPdOCdO;bYQy`LmehqUKBcEE9LPT`SdTW$W~s2UT^7uHdz&-f@oEbDC}up%OG zbA8OwG_EC|g&o8ft@wZu5-g5r9RpC)au0@I+@oKZ-&% zDNkkkME`5~JMBXm5>}=M>8I=EolPCX7aFApZ@r)|0$xlhh%CEF?*^uuMyOtkWs)e= z3AI8{Zb3?{XnSZ_l*7%DA#{Uo$y^XlyW+tQ(Q0b>LqCPA#|z_-ljnIm_QFmvB`Ux07G zq4fOgGur@|fx9ICFh@}nW_BG(1WOH2612KFPep}YJ_>k#95)?OvJ6)@ak@E*1ALTS zcXMphd=i1pj^9`^?eJ8*gTCY9<9`2j(yiVA>&mbC_cMt(V5r2>tx2$kxZqk zSh#gW$XIF)d@-e-PEuKKakT(P@$b)qh8@P=aSP-bv7Tz!iL^{4PTg-t zssBylI!86Zw3dcV9iZ?hcArRlk6zdN+3g}cuf8n}fs-lUZ&8r>o`&8$QO5iSCqe5lRo9BFI z&31nxF>KRKKAxv{3aJD(d<`V)El$l>&n{I^q$iFrcaN4Km1qos@j-Rz`@JbZjC(!L zIra~!*>9j--Q;j|<)bzS~ju8N*jQ0Kkb zi{8CYmYn<@X@L?R$f|mR(w75nTfDRKzL%3@2Vvh1XpaJ|amU1caXr_uv^%r3Te)WH zqi@R(n{z9fO7E)=AFdV~o<>joX^&q?HwxT^{_;hSHiWugsuuh}T5UTzjqA5u-mrv( zI=6UYtA%&DJb5u?(ylJuB`m?XxPW>GUDI@Flh>=i`!>$n>N=Q5Uhs-|h8Xd=Hf~eY zV2f+%&1F2ZT2N}^v*gcSZ`Mv;`|C(ZizB|ix~urqi|u+MEpuRr@N2PRRVwi34>z9< zw&SVx8YU^zm>=1^zYEk{@nXLjgPp#Ay*bn9#wA!d(K5K)!#f!LA=NW5P9hcqKw@J+ z$BhEQC7a9S$T*r%P7tZ z9^S4uUfn3^x(kL*6!V$l!_ce*c_1{W5O>BQ?J<{hVNbH>1(*24basVOZ^#PIxva#T zjojL)y)#i>@(SoOeEafta)$N(pD`PeWA^+OW@87+f`j&!PIKU(6X~l#E2V(|QWPO|jdZd-EfL}k|Ixno z7-xS~`G=wzBIuC9>7!lZh-nAIsd^D?RYSz-?ntN$Sa`w*ZzIz@vNHPR1$m@|3ui@$lVO=BoclfnzA!|IHzDmy2+&(uyy#oWymdn2=F|c%_C1LdZVE?*fGj~9 zgGwN^H{W-65Nm|!H?ORp&{IT=PXnJ}P%6l#{!dxbw!z$gyuDm?*JE%22N>=n?}+E? z0i~Ieu-BLE(}IQZtGE`g!ZF}K=5^+tFXbP$+tlB>|7hDiooAj#A8giPd)?vRe)Ne> zIvfIe>pJ^3_ijtaZ&D^W*{-&tHsIdu1Q)8(*Unj+B0nTXDU<1XO2j|%pp>N1(BQKj z1ne=BI>S$E5I6lfhd_GYl3O>#r{6oL(U66uql`PF^E$ErI2*NLJB;^;oVu4To5apW z;>IHJPK|m2qzGb%_>oGIWuoQ=O3AP;?C&*6JIL1=dN@z(?9|x7xgEfJ+TMCK&Sl1> zJ54*YKbJp)CXItu|C-iKNUL-OoN9?0BPa{*p~k#yBe(MS9f`gH#L)ghB{3e#b4^G6 z$R7RJqqwZqfY7&vO6-_m5l_#YFLCwlJMxMwr2Ivp2R(P|f&%Nz-!+?y^C*a(%>ONY z7bq_>*C|L8^9`z|0S2FiA7kQRmfJr-{JoZMU=~seKLxF=Yol3JA7-2&G=*RxnO_)@ z&LvEGXUgyY<3_|167b{HzH1w8Z{6QTKkSo67b?#PL z%pw1XFr+h`ZF&2vlXIXBt^Z+C%b9)@jOH~g#BP92zzie~LrO2kB~GDCI6_8F{5xa+ zlzdSk*b{Q#eY=KJHDt@7lm1F90_^Xc;ch=J^rbTm_bEbJU2Hz=0n=n+x_3Fdckki2 z+Di(R6y3wdnG*RqR@J}Tnb~xwItvFDGND5r6)z}%!3VeG*ZL(p^Ka}^4^$D!pXOdy z|0jeev?=ah9`0Wwj`(@zlFQ=z-iJvX?DO{XB-b6O8U(?DhdcID)K@~qWVhd;crrKh z>m2EXC7k9Dp@hNO-YK)l^FAbQ=v}m=)~ZpC)M4OCDr3w)^yi=U{9H5$K7T6T{ZY!H z4BEZ$OF-!xfP9V%Z}Wx|%X`c6$@m1Sf#CxDw3(zADe&L)jWCST!;h_$@l6Wform#s zu?euJXB&gbcp+6`b&}82QOlXnE0M>Dwu``63G7Kosro}I%uuCDG zr9IxCOusiWIKNcB9s1ST(!1EBlQabmp@>Oi`lRt#j7-|SmZ>;;KS5i?I9w!X((9G78+q&QcZg z0hGxeysDT`x}&9Dx?!+tA!+4Zw(+v>eJ|OS385!!t#QXNy-FYH=cbut9WDKh^Z60gJ|= z6+2c7drFQ5g@Cz66^j6grmTP1daP};`51Uf$vf`eZS`t;4BnZU2L7xs6{LI{=Jy)c zyLR>a3kw%-c{dO{K-Wt<3(|amW>jTgFL5OyGX}W16ReG$aS0Rc^PW`-S^w8i*(7~% z$G6IteNRiduVKo@tvJ^;4DB zKDjx0X1=VERlEHy{)`Jjc?1KVUN5C6^Q5n=j3RF!+*h>{$G#p*0%l57C|E`Jh9Xo$ z|IMfDQ_VcYV1i1eQR7%zC(5*11s@?Wdu;V2fm_I-0NDrMSU6H7N0bD#xVVVYD8&m8_kvkH@;9of~qL#x)j;J0+sx&^Qh0 zjMBB3M05*-k^GKh{l;URW{sx0e_kN@tW=NxkwJsgt%%BK>oB*KKR%8qCmHhd4}1Ni zoTt7NG1O{yMx~K*>Z3DPVs`YfoiRDCW^W^+-9~-5?xo6gtcHJTLlN@YeJ_m|&aPxd zj0f+06RZ!UAG=~$J|kGM)OaGBN%uVz2_xefL#5cSJFcjJUWR8#Dl9g?+zg9={iSwt zlP2^YT`^a{43Esc{PC`vI?Foki$^lC#F$-jQap_sJ14{3^xm4qtVb#m`t6-^U8v@z zq!$!a4e%c)_^F@QhHsu1oNl;{w_;W;fF5Y;yY;esi(ma5N)syN-k&g5yR<@Fz(flo zWp3Te=;GBlKXBI6!Nqs0$&N*l#G<1J>Or#KA?Z)OcbA)r+XB;U+by%2=e%NO=L+w! zvM{|bq(54+(VxJ!FBI{h0&J3K9l0!c7HcjYE1QmEONvvarEKWV$(G>PSH2`>1{+%` z$aM8xF4{5A*`V#^{%dm1w&u7IgixD*aFzanIlVyj6Zx(MW*J@z-P8+ zx>MA#sXjn0ubW;$A7O&Qak)YA><@JU*krdy?ZTUjVZcj59Y&LD92$6a6wch$4e-^d zKZDOlV>CNL)b?`Y_FY=Y+G6h^eHJ*-j60XJ*&ezWuzR~VhI%=&quY^byYQ)b48yU} z@uQgWogNwY(pd)MO%HoCEHg8#-lNU_(#TR^o(jJJE;5D4BtvOV-lVS2z1aNG>PqT1 zHPOjOVr*B<-HCkCqFvHL);*WgpYBV-ol%)b*J)bbW(vW4e~|r!&6;b;BR3ycdk;TF zdk$}1tUhfR%}Ufcx{fgd4-=)CMANn$s1gOw=B#LM^xp2D?#ebvdJz)wQ>yOmp9PNm z&WM$W+r^&jK9PjX-w2__tNN=ob+1WL?yO=gV)w0G9B6=P0)wSqA%iDoEht;QrSVdD zD0&{51QQ}xDdDt$^lLw$7<6RzL!s1OFwH>KeKzfky8TvfVoxS~{meS?87zHy*EdQ) z+!?0^l@h6kiRIZjcim1J4Jd?Gq=#MoWGMqtmG1UTitrGgU^+$-?$*K(xWOI znlj82Udrr5Rs4w(;B$@>vE4mZd!g536C_C(9Rb|~uIcj9wImwg`KtNw{vq)(BBJQ3 z%6gf8Y-H@~SSird=*#iYfe6Gkk|}Tua)pCb5^^EsGyvyqq5>#fSDU2#5tqz;+l^^s z{;}U9)u6+^kz`8t%u*O1>YR8$zr+#kVB*m?qoC8R0{OLjfBwPslOXITn|rJR6Sr&^ zE%JHsrJKzJUD&LO3FH{;vja=&Xn5t9>g>F43(O3$K_f_~){@cw+k;}N&(Z~h>K}ZL zza%38{*|n0MAkih-F!2K_baf_XJ?+EggVf|jmDe}6HaM3?sR0tg6sbm{*lhsKZO(*+UJ_0i za6u9l>ISZIZazX!Aebq&{p22Pff(g1{b()(I2d7| zztCvbJ6shTZAqR2<6q!!2Ycf=eg9c9r@qdL$p~;tJdqNzQW2sX*zj9dG9cjqW0!(V zk^{3`&(-vEL-a)dr&17`8l9-lVhXEUduV6^yVoZ2QvbJiU^ohxZxNHWD_fczo*}== zzy@fPa(YWWk}yUfijdva@urC#oDJbDrq#uiwQbFv9&Zj&f_=S^Bve1_RQ}{vB#Q_z zXG;8BLAi6nJtdSHKM`xW0^1fwUo-snMV&tr#;^okVpJkMy{uR42Nc)^&fL_KVBV1E zHt1%;Z|EUh#4shEXII%1>IC;%kkoJDG{a%|@f)wPO9apXt)pM$IId$XP9Ih={v07! z9{TG3uVJgK-}BQPQ)y$k`#qLf8wE?s?-7{Jj)%m0^uCV58f>$eHo&_-TuXD|QtyhN zn6N>Jft?*=@g{#TK2z#fI7%Pr+s(RcFsWKd1S!q`1J!ysxM}kW7pAq7{k^<*6Q@kt zU;@ zci^dK+RaWP{squTSm*`rH|aW?%lDUQ$N&+=eQ=P$5&(5EpB=w759 z59Tugc`4*gq?%XSFME_VAIn;Q6;Dm*s4I=q5bvgOkHD3J<)d}dbBNg^^lhYSTn!|t zH6&w99^nmQ06af5$=7}NouY%2t{cv5(1Pxj?eDaeaYUkM5Y@n>*ZH^c-kf+PEFFV<%Hu`GvQcCP~6~3Sw3c zZGkaBAY-f5Nx{(%O528@3DVK3*LItE(P4d!+s&h%U>5`Y-x&_h({wmVZ8WKY$eQ0A z>}izKh`9(xpTwA_p(0#j6X;AvGP&k)Qs6{Nm?^E5pBau?Q>y$*5vCWrejGu=Occ6c zXQh#5N|PdsnKGoxk9^Z~A!Zm7=R4l64M^YF5Xl!P7w$1*P+u0%ov?vJ-IMz2{1Ky$*OE&H`5 zY0hZ;x38ja3lUZFTXy#1Vhw^eRPQ@@r1l7FH#2955EQ6W)i$g3D8U~3H&PwBHihD7 z3rZ9%$v2Ozx~m&sBMS2=cbGrG7H-f^<(_VcWm8C;7Fsj~EH@Mb-u9GRTwcyNE@dc? zAcQU$t~>->_LIQyJ*ZSoTtA49yrXlqLzdLr7xhjAj0d5>8>D>@+ZmUrD8??1F8b4q zU{NK`+?FVN)bSez@5BHD{5w?FMRu@3*LxKJ3pP`@-Y$?641(T1ysw#ZKctGf`twkN ztEI@o6!_6F<}9LpgmkfA3utI{8$U{~Qer4-aoN_TUtMRE*0Xe3uSr|d$e-@KX2_*7!E!wF zH)SE%6Qb9g4%f1M6g!i}t5vu(nPpmxnItjSc}L)uaXmg!p=**^+M}X}GZ*B?f6I~p zt*`yV#Nx`tx}mqS2MUIQF*GdsfE&^yxI_2a69g872lMaP^n^|wbv+|PN+M-rO-Mq6lzrN>PE64E5x<^2>M&RYJIcIxYc8S}$>H4H*D5)> zR=yuDWzRKx`g!Ygv>jje#Rs9WLVTp8Z;%ub-dDnul_gu`%_NYHRY`7EbQ_1k9`aCra>7x#n6ky6i_r=Sh?Y+Dr3Zb{C5Cj6HAwOVS_Km$n@} zuP#YT3?Q%5kt@bMis#;kQ5d~i6TT%DZ^W8}v^Nd5m9>aS#%bX*yQy#8N;zrR$p%X- zqT4j?Z2;b>%Iahj9vAsquZTz3C511tAx1%yI}ydNBhS^89W#UM8w0LD4&iE5k3@U- zPK;MIVkUVNNn;#-ef@hpmPCMx2GxV@daMKJu&**L+>;}^O^y(aU0Tu(x1}ozuD?%k zNlB}ToQuJD$Ik3X{P{d(vg1QKKl_(5zl>RR8-AoinqW`id^^uf-wyc(iuscZ+Ys+9 zJO>#ngEdhJ8M~n_Qb2|J_|5&N&LzO-Q+aw@6mjQ1@0#vO$jXHi+L`ixNu_^$Wh-0Yokh0S6GBK1yj$9r#7 zb6xEJqv|XCnrz>L(j-}V|X=5{0R46 z!}_{C?)vOw@4KJCwDWyTw98mAqmMUdprIQRz(M$Gqcv;RVPN}od`jmXuN!7`d4TDh zRJ>kabingqg2TrMqenYq@Tcs!vgSb5Qv^eXDX<(VIrcC5HIOW^eaBjXJSxNCX;Byl zT1Z+N#|Yv_?&c%c_r0w`@3MJHQpN~iO9M_;GhXZ1~b5cf+u~--LeaCqHVKv-vx*YP& zq}U8tX^Q@JAM3j!*r;v0$=2YxZ$1tjAP-U&i*;3(n*q1smk@N*S+v0nJtN7`{1A!H zAcPcQiWKTx>Oo}GD|6Z&baN*B>&I(`**%3q`9Y1`eTK(^EK$go*eZ$&X(qE9W<%d?y^%SG;HXvtp(+SEl`r2+xckD@~?)1 z*vuxhT3%GnT)|`!WXKs?*gf(;KCAO7C!~}Yt7cZqi}d#{ADfSOan%*Z<|K^$e)d{J zM0_Aj!?*jXrQ2$_dxPPSZQ6jIm6#!D5>{cL5a2HdP%pMnhG1L)o=9Gi72V-?u=RcP zA}p80W{UrPTQf;GXE0#{p@h=f#iot!3zcZi{f>y2FQT6cAKpd??@-962&a$k+#EQt z9Eyrj6lhvXq{qKS&t?RCJG}E0+5QM){GG*3JEPC>Zp$yMOoG43a}L8@Q!^u-yMlsQ zCxCAl8Vi-cap$m`sgmirvzD2f!i$R>gu8I`ak$jIOhUs0e8fy}P?e%L_lBt5mBpzA6Ar;GfMyTh_f|MxUl}3VMJl2q4~>(0L0|uQ5fZs&4;yA-7h}9un>4B9K*hT5FnksVu;*Rzb_JQ zJWO>t=!Utd+b50uO=OpTKScq4T;%V`ek=LNe2ccc#c2d(Dfnm}cS-7%5k)zbNg@|b zkLFrbMuxiUx{@nLUs!6VxcC}0KWe1`bNl2|TkbIS57UHGPcL{q_Ujx@_}6v$p#K>C zBn@9gWK-)5Ao}MMvj8xv_DPtY+WK89h?FX|9mx50_)9gSXERL34RCqZH>b%!{uGDX zAMWJgB#sycz^rCx`;xw`*J4+Uw89ZmhdjH_spwf<4Dgg$EyNH;z#89#{|bfO3;iRk zl~b5eUR2Op@x-+w%uKR~nt+&>q8!t5U2?xCz8t3x)ca#SZ27C+A#zx$c1rKpwXX7J zWx#0Ij)KQ8Max`vo=-uN9i(u4nUf{qcS(_xI5OiTQ8XFX zVp{K8U6q#rG=eQYZ5^X7zP|X(y=AhD$(Y~$uv#4OhVk)v*ka4QQ=tk1efXiRrTOUijBfs^MhXF_N8PjR48e!->C*`c#2 z`Yi49`1n~K?VfKyg6b-8(SPGRZ=(95e(7IW@-}V~c5LC%wdap-XrHG{WAh@VxAoTMZHg@pnqw4yl zR`$AChN>CRYWO=$b}=WwC?1vjrbIoCno~0F-6{0|$i4|+m&B~zZxcUE{Ow$MRwbsz zDC-KYTX4cJr18(6X^hsb7KB<}W&_b}jCm8><@9sEj}DD1Pzm*TehMxa!vNzsaDvUM z>MdEkKzs_E6`UgCCAiRW!fxY={!e|lZgTrnZH}208ieL|5Jq0vya5C zbcdae5H>%Iyk1d@PGxZzRY|9!zT^O5<+%+>&}kNdHM@WIa)5ZoFsSY-U5V61g|Pg$ zTafAv6hlp74Xe#Y9hQ|AWRB$XXHo2uW>8%mU`zGvX|4-XDezAKJv;-D58~EqN`unU zAvaved|lpm83k=Ze!f6HZs0x0R^A56qqrg`*#?=U*zVs!mCr{!Pd2dG021-0?>%Czt&DTK)kD&i=MF``# z_QhzgAYcNx?UGsy?})PkeDoIHXXm{bj&jQ-0^UV29qH2K^(9JE&e?J)~C zNf$osnzPd7$rXIB)v+b92IbY5kM%PDsspzBv-Rc;qwYUlbqN9t$wdveSULu8S-lU+ zSmq>R!~fE)1^mJwx9W7d~uYsD8FPtV{GlXUzLZ|`8638)U(xml@a6kOik9f@S* zUA(Dy2r6^r38mQzkiDz_kOpXBDgZ!Sps`MJ8R&h;3SJ>l#xGz!LN`bGNbuu3B#(1I znEOA>-81-o~u5bf2d z{#>KQuBl&?#g$TRR_LD6jzq~Xf|_qdGxc71RzkrTg~jUA^kn=!cw_`78ZW)?{b-}L zpwM1ITdks-AW`b)dwN&(r%b+r;Ul|`KSz{floaMK!t_)8)&JrT7KC0JL~2-p<$rjf z_-CkO%@6|bZNb9>c~2Vabc|U)!(UB!?nxfyDJGfH4>-v3Hv(i@C4-+ zSM%$4F38`IQXhsp>kuxYXpmX-77aj|Ovcp6d;9CK{JG42!HqA%5mpM&FzWKK`R5fY z?RjpIb-AXd5K64$pqU^k#k5Z-o{TI^M7M(hsl~j*>j{tpad=69A<2^aC~|5aO6m<= z)QRGitmMfC5FefLG@XAGhub0oEV%sm1`M}08+`{O z6GHd9=xC!AWTW=2+Sb3~qCL88T^5~|wruDZ({=G{G+6-T)-%|`j{tV11z^5@HbR2` zXEs1dd_S&dz4uF{`JY|bL#dA9;lMgT;s+T>7HTaSSY;m?PJ7F2#a+qDZd*zYKq61q zMN|iNJIuL?Jv0mpZ-jrb__Uc@*(y-*&(t7URi{evMd`q&n1^^L!!?Bmk6-WYmU{F~ z;K+_7o=xIA#DD0)&;!8A-RLy7^k!87*SlM7gswbD6L8z}a6p@Hve%Tm=k?JtlV7;U zXZ(;G;}~AuogwjPQvoP5UHN(Y(_c(i=E52TrW;t(^5i5P-wgVooXGex@@SPkxzH}A z(Rm`?b2UnN2DBsuI@(hM%VjPYlEXe*Q}cx$V+WpJjBttNhle`@l-W`6Ev({;7Df%3ks0fX3XA^^JC}3OTyA%6A0DU zpE8)ZnN7)mZ7%=gA2sV#gzt;|bknup5vqFV>@-=Y05d7j%flQ7jun*-^r%v!Wg#zm z>cnv;&8<^Uzdf0|VLjd7ldF0qtSO;UY7pebev3ly(;3%dzr4!NS}@dE&!SbS?oNz6 z1K$c^;(aWs9g}JQuW^UBLAIiIp$;71^C|VVi~Ry{APi{s$we}S^J!WpsQrY+xqfTu z+!^2VYxn<_z0alQtjEMOK9xcqTm|j}nN3hzVNU;BuKhcN7Fa;`?t6p`L|Nb`_5_xr zq7~gagHR)#8&afr&T>54j(Oshc6E>NoFE+>83#2O;45`4x*l-(zEbt^t;KiT^hNeR zEbNvDzd^(AtZoV1K>sJR_r%75J^s;R=inVl+Za^}JCd56Pn#k&-%kLV4EP?$XrcS) zfWK|~$~G_1QTAFIq?N4nXfw4odVV9}f;lfJ<~7Qyg~4S_1F zVv0JR-~2@}7*_S;SOgZy4pmBQ-Tl&@p{DcfY!VY~EJ+=-=xToc)SG5>>wm}uOWeAyg!?<2g0 zJd%*1fjm}~L<_&ba9e#CV}g)|C`v4`-gEmv8Y7e~7!3n1t>dnc!zwL~2vX z4lyZZ49b%St_2#sigI*&Udk$E@ornp>D4D6mk9W7UsqotJqF%$dFeK){P?2~{2t)@ zViqV^0#zDd9xC5~H3?UW(Z|CoIO$$@yYgY**RJ$ zfSm#h@Qkl6Xr^jEV9#^m>=Qn>3uiB-tHo{{9DpVc(kRXz!2~5JIwNf!Z#~L6hXcSa znLiQ?R{KkJkGG&;*00}P3b;yFm@atJvl2kA4A1p5p4%i$UrIX6HD0}|Q-cBo zN)ZH^|7~J);8P7#3G|pYju7{49}fpouPEr(0;GXjO#y>{H!SoUc(rL=HzrACL4hzP zq+CDKaZoF1iW*pLG?)fkzdPsSKoU;GdsRxQ%+bL@`=JpmzzY*AFv2mE965%9S?Bh} zV2L1o<#ow{ln-Jf8N*+Hai_faq>^8nRpZq@uJjp?wJy);rvfs*D_Vq-$LjTUEvwAc zaBo*sL>4$IY6y!P|0Q@WriMM(k_+};~dq)`quP@$UBSc<`Y5q-`5)|Dn>DzxTy#!6BebK7!St&tWwtgF@*y7*~ zzdosvq~x8Ljk2C2J{XOjil(%2?d4=}DnF=)$rCA;O`_E9;e@D z!(2GyE*dvKz1-0*(EFhzAzc1Np&MIqX*|Vp)qU>BcPGI#_pFQRGE9O+B68{bI_s)j zp1@J8HBx0(xR48(6-`PzBpT$ER$f3 zwF{4y_=ua-W9KHeVzBbVWm~3=MteH;*-=_8y+V_Yh4YsM!XFk)g+WQc@S?q{NkLceZ{(d3+g`NMW15YkWk+1PSRXp;xxsq8(PJ-UF4}+NJF;igy zE`;7oSVn<>nfQpv8xx&WJX8wLYbECIB*(p-OjA0wX4PR`Q=ei#I>Z;apI>ZHt6x7# zo3x>p)=AZ4q2{}xWV7p&anLDl8_a~?SP(~4+ig;o5_0Uwqribhj!(8|3He3GUL*}c zIRtW|tb3*?`5@`W5@sgi{l7S`jb|eQk5!E-b`N$IfEJY>jt`;w?)nFL(1+2ZgHwfB z=zt;)VzY*A=ud;oJsZFI-9oruO%~4L$ZPqv2qxAaRD{F1G6IPTJMBmaQ~QMBpF-21 z2KV9B3Sc|B_Bq}OJ?@s;=+@1<6Df*?EudWbC-H_jEaSJADTuEq7vYzOHhxM(sgnkZ zd&Jfp85zZ%hfY86WJ`Pq1I*El*n}ieM1%a70G`ydNIPEcD9eYsfXP!c&6&ud{Sa;u8PuuvDPsC z;_$$_ZgG`z$%kbzZa$>Onj&nJsygB858Hme?eWE1p?nf2oWey!gB|8sq$t`vBQEk_ zKLX{rBO5ukZYNNEh?!vsinl|R{tkXBDA@BxXo6@ojejMfq0*9|rH^pITUr+QJDQOJ z!AR_@ck9XQ?XRswOL;<{W8X&*iU>RG60+6(4lHe5a4Q+<n7<#DVyMJI}WydyMtC4 zzH}SFgt<%ZSXLck2?+r?5XI|B3Co?6AgJMPu!Pcvj4$~fVK)Vu=@3=d223lUP||SR zVAYWy)J}rC&l}S3x?y|k9l$_pW5cx=J;frkdJ_K%)pvV*?2Kcr4~}{sV%KF@aQTf` z-fM^knUvY@6t#jcSY@2X?qb4*lc&&)f-|+Lri`z(E|vK_J-MjOnhNv&ZZs0yd+!#F;WGL{$freJ$b2)SprTDkgF zqDDiDf^rM~oWD)Pa{rvJPvTukXpA89WJuL#`z+%nN{v~vuAUK~k&drz+08hnY8i#H zjh^jB%sl2*;3)i$oBi=g=k%rsQ+e{+x(Sf8);GSPuqqGPyMYtrK8x(mAv_S!JCg%j z*kn{Gj-2z)EwT3fE1E|<``O!?W^D3Bio8LeR3DS^iGX)=b(m~MfMpPTthBH>B z4-+!y*QlWF*Q7v1lgM{dB_{`=cC-T|UVeNgBO{#|&BeFD>t;unB=ny$AjAP->mb{s zNGq7%7DyM2I+YOZCCn+lO9lMSkc+2EwHbHnY}r2liDLTkhkFPcFyzDbC3u+HpN8Uw z=r_|3Ck}E9Zgrc7feTc%CP*MZ{rM^70B~*%ldG z(VlahW^voL(J@2$^33r?oAH{*shc=TPUWW=P3x!AGw9i;8DSD$Sg3cO0%qZQz{wkN zCs_BPy=N)PF6}Y!Mj9tUNmG{{r6z=t8dBVBl@aNUW6sz1_b$8jQ?T4q)1x#%~hyatL(;v>$mv9$2!kII~P7S{cM;tFVPqy8W+HPpFbDwRmpbPkwGv za>k+YHicW2SiQ$c>O)|0sYm~l!Y-Wpfr?{aoW3>!ROw>UWnIVgc0{55SU9JJ6qm4k z$Vt@(dUc_%Y3GYALN8+%c`!xG;WNLxlJ95VR^(qS=Z z*%geo9t#U6%Q<>ewQi*@mDTcp#;zdV@r(?(b)tB5r~$~CX07K-Opg#~?Wxr%P&Eq+ zob89SUAL2j)ZC8B00-fg4!aTRkxZ;y2`fZ)z^0w@P?2UQ9Zx|3E{6ofxqY+@p>fRLP1cm6L-urhEXF)MA?6 zbVeNO;Gz?buwHwa0WVd%w>2A z`?fdeye5_W4Js*p+nb-eo?Gb# z+BUMhXVzVhU~05F^l0HYbW=+2Bc%0$dgN0>Die+lsf_~5swyNn6$v`vZ+q(TSB#sO z)BXuqq*+qLRWDlD7(;9HLpc^Bu@-(MdYV_1tJ2il-9?Xx4HTvmT?Aw|7J1WgtD{S8 z3mp^&z3b*0f2#pR9x~K*J;lTBWs^)Y%+e$Dd^^zEulPIYzX_duN9)CBeAzi&nWtOR z1@?lGAMLk<64+Q)N=X2oSo&-GFiy;n{AN7Nxu6Lbi*Evw{qhQ|Yo5+ohcw7cls1<* zg8weoUtApysEKgwFP8YnjSpsYxoU~@uZi}`C!*H*a-4;dcE?#aAAsSc`%CLzVC43w z0C9nR?Bw3khE7IUA0wLQ5YNdfX12XnuZZF&!%OyI z>;W$es2lfNeZau-V^xjA8m-Q}ovBl+?_~*{)Y*ME*PT5~Oy27TGBK?V7h+ z?!J;QmO_9XD_+}t&?8xoR5gmy!LUuKu7`HsUH{rLdI`kGzeB)}vX0zj=Vq~h4Eegg zy{iK|TWA^H9%(oZtse^PR3DojK?P8^ePd=CFYdmucyt2Ps1l{UX1H#Y!#s$iUu)0N72ES=V)!BKW9~%Q9Y~RD#g%7& z$*Wm8KZAdd$`EEgGsLa(1n_RHi5d^A)*hSd8Q?H+KS*1Rbb}w)*yIuC2jXf=K*uc6rd;!n(W?jw4LTeH$OPT5x);zXmaS6hjXihKWZ3t))RX zQyS^E6qmVNSoH2XT`@(`jEWZrZ;~g5YIlFOqwdQI&rL$Zo#9Y|Q-u?)Qutt2#bun( zqhF4`%_qODa6`lo-yWdGN1xs??l01^ht=9 zA(o zaEOj{d=ijz6VAyDMkp`<3bEEs20^#?BzMqTPhs2BxZtLn;D-8oAhWv2YjUQtf=dcv;KjIVPKqltigrQ03Bft5x&!Krwz zXuUNkH13q;I>01#y&-c*PE6!0J_n&FXeCJ){G4}p=JJYGfM#10rV1$A1NVgFez!~> zPBBMb@DdU6ZAPyOC_8y0p-8^rQ#9^C-Bge`f=Mjh<9BWy+!`{f;!Juev3eSW7 zZ3F^EXQ$L$7fWsmpW6sMb2b&SdZUZr0%Y{dp47r4$oo+f&R5XPXvICdGJ7HRmPBLujKxh*78C0JLtq^SJOpVQ?p%|a|X z5X#1MTe{&_Wuu-`KM~mj3?cunA+7yF{;6hsP5_~=65)tPH%x%EwSJwK-QB<6 zq=P<@4Cn-8FB}vRY6@1Q#L_7!F30U*q(LazVy5iTw0y#CJi{&G5 zr_q?pl7gt@*YqchSq>6~rPuEq8Um})sTn!NCe;5%SV`8W?z3uhS`?$#&ZW*PI@*`aD6#^x<8vy0yLnMv2Y=?IR23tzLufDo}EZ00Lwm$P<>whY{_mwz^t zKOPy=f#H?JrAKccG+>S}4n_diKGVN;Sui!+nbX*bAixMwdxRuQ?B+-9t+^w4R;)>8 z@+v_jH+(`w{Hy5ITX<>Nk#1p27-8_1i+SFS?@?ZMLlEC}?bL0cE^lTWvQIk-q3?hD zRlF#+EVtKB-_;xOqJXY!c@`pkh}9FP=_?-JRtv7ux=|LexU0{b4|E>B+Af@bce!J@OFnu3&CI}0aI8L7p+ zkxt+B=y*;&ZMTTEIlf=@5cvPMX4R_)oa6=5sT{k5N+usc)JOrksEoj3DE(oW(XZc^ z!o^{<2z&bhK%vf8(l+(uGn~IQi$W^L6+CpntjLc2bU7tBtqMO}cVvn|MPFz^btp6} zYcQ}Ai14{eHndfJaj!hcJ#|b4!_r3N%*fa>Mo8XKD$^Vu$c3l>=i^D6Y+j#Z-ZKt4 zIr>pukAx9fH0$Pjb^}$-;I7D84!yi3^e#| z!+BrymWPm(f-Vt10wzVxMbIfvftO?mL}UJ zw-o%|ye0=&BEStzyH}K;szvw|)tVtp%xVwYwXZ1%Cd_u&#QmGBe#G3}go#UicQ%ix?BKL$}EoBmoZ}4@EkRNZAnT$v_N~Z?Fj0N_yW5Z z`vhMMkooZY+*-RLAjqT+`eB-c^(*?2 z{Ve^n$SuBgPlhwrd}%;52 zT4(!Nnh;cfBm+6$Cb!0DLBRTNhz1Y54GfAWRp{=)8SOHZ*0;zl<+Wc zmkdI2D6@!^H9?01jYSSjCy}Xbird5wMad!xJ3xg+hEr2=_c>|I5O%Nl^~VYe2L5_I zgYJyWG((n$xSYowc`~p{*bm`wIR4+JNbLJH*qN5z5!}Bo_YVCpnkP9!!&tE})9-dJ zOLf}zZPgnM_d36F@}O9s*~#AF4Rhhf#0kASRJDv4c|ES&M;KVd7Q{x|M|(W??~xks zefS=e`i&P~ZcdQ-_iq==0=`bq=fKrT@1Q=3I&@*a6%QF!Tl;xpI@WxsB^iM(Ry{qD zDnU3WS_VSX@GyBRP}YU71yF}p8k>U%0%V@Cf5Mi#xnp?0Vwh4Dmt*jFlCTFrnl{w? z<%(y?8R5k*n51c6OsQjnDF}2$0k~J47Xn)xqlrgv-H@_#PzXQ z=~t)eKMZ_S`d6rgW+#auc)vr;^*CRt^H@O5JzD=Lk2!DK-$zD$_?sr0`6;2}r0K9=us)K_g1@cmN-ML2$NVyYpRTW+0dUhqA2gU9FN{XF^C8g#Tw za$#o|Iwtk=)A6$EUu*as&RzfW%`yyS2fXz_Wod!=GWTrZVm50|4M(Hy5lF1jFIH<2oy-4_U;=P`ro9)+jO!#`4r^+GtL;D6+uga-_nXk& z0d4V?es5`6IH<(j&Eb^Rc|8t|HbGt2J8YpI)b|8?e6 z#!(!#VXe#CUmKP+NL3|=G4hkb`cKG=^3?e6H_%OVUhDzZt<2QKvo^B zI{y-vMC4Q)ClIg1v;IT~;RExC_Qml4&w_(Mlyf)XB8QxS-~f*j<&_%3_B=R~QdbY? zbI(DkdAA>$rZm7UX?UJ6VYEtyu~dJ`7I%HN0zyot0`KV-1>v2uYUDDT&zqTvYRSI# zDn)e^wYgvhfU%-n7TnILIa*Eb$D}jR>G> z=kNdcJ2JLeu5Yw!*X?TTt{sbD*?exv(kA@AmM23Y0svO z;v!QikMziSjqTz}3J9tXxjO^7P;KAhty}#4I5Mg5#8DK0l$w-*cUoxY#N8(8NvWJ> zPnN&E+D4j7$(|kQ{986Zl4BNb(e=|Slk?K-s79+9K=9yhv98bW6#C;Jq~RI2$>=oXkRq#0!w*b{RF7Wt zrRbOSIdeK-=3xvl)q-t+m>rILGyaL0^iznEfW`E0K#ds_MNcugkGpHyK!3yk5>K5e z{MVihO<-N|v?5pfLEvKKOFnd=wUrGN$Vtth_(#6`NVy!kzVG~ zKiKp@f0_if4a&=K;1_|e*gA-PJtkfjB9r~Xm6>z65vIG{4Qhav!nZ(&Q+&iE z?D{m2<(j;~^ld$09TNj^g~(5nyHwT>@A3mHWCaR?LJdMm0U@QEDFNk#Vn&2X-p+f{ z;McOt9~{SKL^g-KDrbY`=6yZryKW%V*MgW;OTPbkmlHK|X#&KJ9Rs00sh586j-b25 zjV+$5`XEa}j)@G=MWJ-XNy2mk&cx>hv`=D^rS~C>#tDfl(cQ@+`H>n`JuG25EUSFB z?dpJh2@g2{D2{*p{cl*0;L|t`>3&xS>-Y*Rv9BoaCo-zQi(fCFEt!p6bK&y6w_kh2 z^f5EzZ)y7wk#_!C?#rQ!xN{SgGJA0C{vyjBx(KlMtkr4$BmdB6XY{~7UO5?C2VeH`&Pi+)n+yRW4lpNuIE%9&S$vuC zq}Qd?=SR=wcCZ?|CELifojmowc{1$i=z@|`oQU- z5<}RUSSRtf&{xb`jaFJ_urmxgi(?=b-ahZnLH&H?lk3CNPxZh6;UmQ)-)A{7a&A?_ zub{S3tsUqFwmE2JHQRD}0eeQKp!e2EqwE_qi$7C^WD23eBf4CxEHg4`S1oGR_2B8F z0%m$IvI5ie*&ivLo#l)@k@>C~mbnCGl0S*`N=~jDgYKwA+^YGwaKE)WtY@;B!`7c@IfR%ES9oilDOA!MX`g6Z_ub;p+$~doz#l2j z&iw~|vf5>K?5O?stWg zbZ=&bW#8A(Hxa~NpLfQb35+kWF@!^&ksLdIYMZ4^)y|7ht1e-v>LSyh-Ral;6{Unb zIh>2eiaoT>|HOdiG-8d(iSpR!MlKVg=^^Vw1z46T4X4(+F_Pi0y!$0N0rdvu_e6=V zDA*^*u@&d%uPXvOJ$~=xkIg+2a;=QUdXIr=Jsn)o8RwkyiJF-B|k~DO=X5glsEV9Y*>GIBO)!Ni%UJa!6ctWcp)AT z)iE}ca%b-4`+$@dE!%~YW5}HT!SHAlO`OI!w0#3g^K*&*0R{1{!1xQ=hkV|?&jJ(E z=}}!NF=tZ57iy6cQCA{l?q1aQ@s;s{llX72j21J{)9`$pst4D9h>QXwsqYg%B@UN% z>V{G%8(F)>X-Gcm5@;2y*lJ~8Ds{`K0bP{3!S`Km;U?}KljK!r7~4Tiz24j#?-?;9 zYdC!7@ZQLnKe;l|x83&eS~?1AI#VGZ(^f9)dOxOl}NF+Er-2(c8M4 zAKUXAZ%b5xL~C0qlGBTgOMe_A{~}`S)NS`7hTzXfalK;BNuE;kVxMeUU1%|=T(`{h zSdG=|fFvPH1zl@$i5L>?Ck$9RH#5<^$@s1=LRL9!AJv-Yi9H!AxF$p6K$Ia^nuGlk zz+~l&QqN|`SDtB>nHuG@^YB<$9F&U9uo8PY-~;x6q^K?CSF9`ly>llE)oc`N9RQpr zz;HRVAN7;Ah8OH|D_Q8j3zK5cN;I@=z{~sYX<%qR>RhtNJRnw=6%WBCWhTnY6KY8N z9;>B+`N%^YHMjDM5E*@WyQh-Di%JAumUc~@@ZY` z+tc$H5l6k59QFG#j=5LXW`Do&l`u~mvo*CW>UApPCfYR`USH}UW(VikE@?CZlAuna zorTqB{SvG9#C#qLS?BV4B$1{SOao23Ouf%` zF-KY}7TvwD@f#*d&+7O;lZ!3fRJJhPDb4-;MOm_Z_{XRM6~ZjGE4HE_Nb3=uF>nQL zIgfUSg_pdDNwv{o^a_&ZMfscd!x5Yzd6$-e4?(@S%BMkw?BUaxhbFnapnW@rodSEgjwB17-Yi;%r6yYp$lN5V%?;LEimemLV?)cA}ju&_)J%yg)V5O+nPeT|f& z^6I{l#PJ9!X}N@TeJ7n5j(FJI#5LWxSrHh5|7F^P2dV%4k*C3R84tVt_2{jE&otMG zoxem8s4k74eU8&G4lAqsOt=0sL7EySJZ9<>dcK=_BiHwCT1C{dbeSuF5i(w=N#XJL zlM`mv201eW9>IlAgxhX2tmJ+Le>DpXDUgowAR)9#*?7fLR}}i!5F<0Ob^0e2cv?%n z;dT5jDFUyz^kxqD_R!U1CFFlzUvbWQODXL5FRXtaS&t5Y1dr)p4|Vg&#f|%;TD>0G)_ncnnCI|h7e+4 z)>d$QOLPpqio}5UpQS(VA^pOK)h!Tw*yg|%BF^n{>8bO|yW(P|>8ma=w}snGy++vv z^k@U>P|-=pennyOBukX*Bd(o}YP3a27WQX^nn(!pg{tsyU_qW)>2U6MPRccODmh6< zJ|QZE6G1L}clBc<=BkpMNFHy_*4ks3&Y2w2^ioEVZDK!@Kf66bKg{8Egn>rrgtc3D z<$0U5U)gWr{(@gKsWtJh%74NjEJ=raH!Np@)qI|6i(g*h<<}5uV)o_Uxplw%@8wZz z5!6ZS-MSPV9aWfR&%)A}-`jcL^ZM%Tg?%=bw+(gr_O+{gT3=Jn&EqFp7|CtLr3gu0C>!7h>I9Aw3 zSo)kcM+JI4*K=q$ZMauAU9tqQA;(J`T;h}zVGLLpn}3*A+b~RbA;n@P}JNC8J{P}neX#jySc&b20H9> z>ei2j>A2D@Io{kJKW@eB0b4}-Zlm}oX$(5jR+cce}m>u5e0Ee zl4`m}CP}&13VesRiTY6d?>dZuhjiiV{vHbA|-=+0R=ro@dZ%(z{OyY$(*Zu z26Q#lY;uRGSDZmnrxq+z=En{!TxF1iM+2yZ49J@OOBaXtckY)J&>Z(U0g*h*l;Hyx z_tHAihpZKTl?g%MTD$K6$J+DL2l3gh)xmb73#jN1h$uH8OI!E}#P8(1>PfAYs-sq8>i&o0A!XT^ zZky!q)4S={OXl$V8O)xBWgC6Te?Nop=ZC-CuB#FwIa15HTp?^1+C8OanX4s&7o|f< zEr7GjQ7pVHQ6OJq<0>4_Q#>iIdwY>!8Ds}cw&Gb&Ol;PnAy%$qD$rkY)RkoG%OtSY&Ac@7h=S7pMJZI7ag5n(yK7uYq z`0)ip`R0ZUp0%SqbC3@g9f|hY7#2%;c7lkh$YMp!fOlay8E;HR$IDd#%o#*Ym}*)PfqVQQ_+ypp;_6= z3RnKEID>;B=%`s9wj6SgW1swtIh^u;Pg6@sB*$Q|1qCwLMX0{ov$dw7bMM#!E{3ch zf6Z`aBCE&J&(5II{ztM7J^HRa+o^0wrPm+ColpB7-uaNnnt_Zm+ z-1phYe4r;z)W&@8Ju2~v6OKv%uJ|P8VrsCIL=$7964n$jF$~KQX;StfRK`W;@}K(} zy{BBkvrGOEY^qxZ$q0#7`9W%XFTvBWiHDot;vrzgT|tKDYaeSo{4fWZcs}vB9@MD@ zu5=u?8kdzeW}j&AGp<4P;@c>#bRF;J{Z=y&_4|Vxo{D@w_@P@$3YA%%K zopuz`hP*piG;uW)aSw*Ny?Ug8FcN_eSju$>@R=ea(DUba%~Yi0V(oZc$e#eNC>$Cj zHevXJFRW(vl3$^P`MAaInumFjtn;wd*sJxQ*jY6Mz4Lp?i`REb(rv^5Bl2Hrko`2L z$Wn~KV|%`m;`D;**;PEKXj7ZzAS4^RZnBAc#0;7Q)xCZF3eS&%ig7;Fk06Zmwg{31 zDQN$02=uzY%JeJV1@g^+DVx^BFTB}Bxi!U6I`o5Ps)K+fE2f=bt-o*8+`}o4MAL7> zSa55r1{csf?Y(D((*bPQG}OL;&vSHWPfQ+DAqHWB(d*G3;EYD(voK6i7*0?Fd{rdM zAN(YxI-1e>0k069zL{VML-11Q(m-icne9OM=WEAMhvj~|oV~`{Tif}3hIUl*zv*vV zm%i@4x8_}_q2~Jbi|BQ!B&7j`=^;HHTS&p~MqyxTMD!*#a z`8*_iN1nj^clggYDt|9KSz;;WZ#)#4pn3x4jbOivVXA%f+bx&@}w%eG}J>=lN2EY~QmlZ5JGg zCBSfSKGlCt960Ru9X?ERC;QGv!ySq@WBoG* zT^wC2>vYeQ`0|X56*xE9m)<@Xe~OmvppG?P>RlYhV=_pu4tw7`67i)miPRug+@n}6 z;LO;1r$;OfPi~r)=0;Qci{m(yo}L~_G?2Gk#8?xPEo=VF+<9klxX&A^$r$jmeDgH< zc=}GA1mDFwjH^kuJg;1uMM(@fif0^~1%4~Yw62g0aAmOk^B?pM(gAq|Q+W|nU6BV# zT=~LApP|$l(=n;k6NdML8~QgH5*ff-UVD#9yUIVn*lrchnU$XSudtxQ$B^(SV!I21 z1`dD-L(d6{C@UZ_p9H6aS17`9&@_;|9+a8WA7a@#nBZRG2Rz8x&>iS9fv6DO|6}Sa zqoRDjXzA{h7Nk3r?)U*R(jg$--8pnfilhum2}p;8faHLrQi9SlBO%QU9RtjL^?&bL z_XBJ3fiFDI^PaQMK6{_zw_lU&NhBRY*2z1-xa0oXh_geDv)ym*dsx`faF7k2$qc`d zy-!-k>EoQR*mSR#%vZ~Fm01K$dp-Ju5&6F|FU>+gR~~Qr|0Q2sAy%tyIN7-FN!9qw z&TA~Jv!ZI6W)%y!2_!_TtmMnsvE;C$@}^TK{j+->E>^P2PC9}{%599LLccXFk_)b& zKABNwa4cXJyp&?^tN`>hz33Z6v2sA8ZhIcE%66~8xqkUEEJW&Gf& z4oBBeuO|gm$^PuazL4Lw1SqJ{2FnZ!oguv~4#$PMPp=^wA;Fl@g`Kb_4AhQpDZ!G< z`a#8TCPLBswL4)Hn9@tz^zo3RJ2Z^y-SY6V@UOJq1ra}(bM=;+zy9iKa*-5+04YiA zRPLM9rp+Gxr9A~Q>^~k772<)KAEodbQmh`c8~=R{*)9@Jw;SNk(-?_c7ovv6<@X`uN5RQ81n2Y3x!#J)}&B*(oTE+WI(Ip)L;bMvXKCVsWhwp#&z3cjS z&5u5m$GhU8k zZ2|}2N`;cgjWxGF#O9s}I=z1Oet-C|`w`p3@4=0|;v3?*dTNdn#gry5qPvV!lOp=3 zqH=X-tJr^nJd6Cmv4t%!fOM-^^oKfhXI(=cRSI zRaab*Wuz8t2XUc0{F%`TxCP4`R&Q(!@cMl=fk^_t;cMxjGu(|{g+K3!RJ^}Y3`$zWLLVz=m^XyI}k2hh!303%Aqc6tc%#4Qog01 ze5}cONS>$F1O`(emF3Jju!9GUseKcFHRu8BZvCLv4DlG=nDW$D(nwTubMFwIu)K0e ze8GQjKAHO;;d&C5Y3r=MgjLk!SiMugE#u-E^t`x}*pgsY!*8uhW-%)1*x<2V*gPKZehp)thLdLfycc z@1ibRFMhNQrDRtPAegR|j!Lto3$~HcIS@KvK9gp5pCAu(xt5y^dGy(jT*w%+Oc zO?}kCEX-t98PZpTx;gqs&>Sb9*_?R!wWpf$#I`))tennHeKU+XMFf#6(sp<;9_`{- zE5MWb1Fq-ZiPHKT-PY%CvLu$J0C2h&Ve~ha>9GM|-GHr4sVWFr^{eWnT3Vm;x+GWK zQY}b;B#5BV);H%%*dunIWmXZsZeV?*BGK(4)uEEM-}Dn(HR!30-C=_!aibp?v=#Tr z>)`-7_Zke?s2=MO+r825A3NydXdc~~T~E4-^LA2#1yfD9xt#0HCbow0gbVHhr597t zXuODhF8(C`(CUYEVRz)7=;#0Jeb^q#PmP*l_`&==*W(^>^gK!I(;C0M7G5SQJqV$Z zM2px9h8d6Q{0ndPiuYfDh1#4$+DSxbR4rfiEgujd&ET#@#Qf9&JDU_PaF|*dgWS`5 zIW8kB8G{$ufBJF&#>ysuW}#b@T)a&4COMoiOyu7~0IId&EVQ9`kTD@NFCK=k8OgAT zzVZ>FWD}Ip6kE#Fz>$0*8C)X#=hY7bgk{W-7clS=f!#;`LMphQ-a=g1jqa$yi(+8& z6h;6H5yS9(T_E+xFIH`t9~ny21#_n+x^Pzpvw< z#}6P{&2ZVGbWb&N?ouOp?4o3S`VF|ye_4cr#6+1Xu_tY5A+77vpC9UX-MAJo+zEpU z#;OfVwli=cAVwPnF0@2WO_1jHmJ{+)o(G*nMec#*%z4Ozuk|L(sH$r#o%SCs3A*QD zH~JR*qx)gpS8m|1Jk66kd&HJk%GbuZFgYWZuj$TMxiW6Lc)pEe$50C$M;|UK6q6P@ zrgWk*dq^=LAaota$ZrdH2^1mp9jyZzS={tP5mXOR}+;V4Lw$ScFIjKzDAHMutfi3j=ow#@?ErLY;~T*VA2Y*d@vll zeNMv*yGsdpokM2S$PPx({JdA6*wqzfm43lH^J7Dn^;BouSd z=7h|DCPSqzaJ=LyD?n5b@#QQrHV(EJ)ZJRSE7IsuJ?}NiU27HqKl?G zNaCB8>$*^iVWVVgixxt9*iv&7U-1HKu8X^{CvaMJ{uml6>@RQbg|y&E8n2(Cv!nrPkpU#u`oyk-0Spj}v7n9FER_G<3H zh`6Fj8cuwz)c9@qFeUBEz^*zGg`v6IleHtAi{DJj5%jrfE{OT%lRYB4LBjW;o6;bSM0T2nz@+mBh6$h|5% zxR!z;L>wZxYq&i`p~97SqpdM=>V@5mq2=d?kv}s+8sOLS!hVg~m-akhPn9T{@hBnP z7uBVDio$;H4@+mE##F69eQApBXl*82S;3Q?`d8mxF*#k8Kouq4>_)b5T9|In{J@Xn zCZVMDPn$H)6qZtZUCzX zFw#lCK9DM=&tsyq^b*g zvxZ4!*C~Qzhqp9?Ka&{Qqua@%w_QPD=vsj|H{ae58LMso z_|c2vjXM>DyQts=4emetwR$|pus--NlL~MSec|A?)boGw<%>(Yf6R;Bnd?7BG7gEV z?;$}aN&>s@q|6Hw$4>HY+1|%1(Y{RO9(ytQj_&@GZ5J)_Wz6Rr6F3H@7|(EdjNWT2 zv_Jej1Dk~Ar+Us=gJgxIoq2=%?bC58g>ql-i6E(GrLKYjFJHn*_1BV#J)5 zrrIsud~m4vM_wrrx6n9B*^p)mDq5YsjqAD7C_))ko z$Rn^qNw^=>q!7}*9c^O^BSor$Z>eK@i9<8mP!saQT*8~;XdTY+jf;5=Do)|hOc|ET zC|zIeHJ;;0klmY`GCU0F-%s)E_LDQR{zZ!6=n2CQEk`viM(#f#kAZJu*_aA_cZ}c| z3hfk(&koz_MMHG!v3M({4%uf*%V<`d0%NrxSlDVhK<{Jw_qn1QXW)- zXu>pG@<4ydMo)hl<#i_Jhz5~u(~+8O_NG1I@u?roy^5yg?(TQ!zoR!_zrVoT_9SP< ziC{G%-FynizqpmMSVy}-%VSY1@EDfZ6BnX zH~HaqJF@_y30;4qh8=*V|IIj(TMr4vmI7}3?;Y0M~h&%E$OxCr(db_83_p;Ff$ znc!R2w0C=0sqV^8kA4RH*!mVjd;$>ff(B7KExj?L4lU=ep*VEf%Si{GcSWbcJ;mhm zGuA%jI>>%Z>dZ4T5HS!X5m-w2Q3-q>?uD2he-x>tQZY>){}FS_2{vnm_DWx@RO=_M zNV0MTahb2AK137@)OJwrmuD}IUu6ngkedIa5x8oN_~qWGzDvsTw$95i9Oqe=I4G(z ze%!>Z@me@&v5MQsO4^_TFWTTGn9`Mlm_sgRJ)Hi}6U~#rzLX2c^JD(MkAYZ|PBZfD z=`58BRd)?P;M&;MwzlKlJvMpkBdl$Z-}%J%X|mO+5ol@akYfr)ne$-fIHqy?2ZEU!vA*U>&t{5HvNW}_q+#$^;4m*7%SgGiAD1O^#~!i9BZhA zFO6^E9m*(Xd-2oOi|#)!9A5`viWM;W77tYhH@E9t+9S?&vbltF{|N9@fxy7i`f(|S zjfwH>Jb!d5W$4sc;~%nQ;58624t^un+haf8N|XzkC6JEp&r3`I__cMb4#V4fMJPkX z&UX`)q)5_5mc?ntWfANQoMOlR4|3SuT!Aku*#82~|9djYk62#@dv5b}ba=C7_?m4- zniTr{EkM!c9O%{~b~lz=x0F&)M)>rYLQ45PhNBS0z4|AM!_K!-94q}X+hL_#GmV6u zN&Q%8!a@?}c)o9U5g7HOdLEU;BzV*kdOoUPfPln;N)ZagfjmDN*RK_%u3=}NbL-zDstUJ@5>G-=!Y>G;& zv?*?>|41DNJJ;`djoq?Mbcrab>amp4zOLF;&}*dk`irM-ts%W!<%wUXHhWXYC15(B zUFLJ~a500|JaTMmMF9-`zZChx15JQooD`t(-VUsiq1?k;5#U!gOq;>8JyhadM-^r_ z5$PFFfD7e~6 zw&ib;miqT|jy_w@*1DeuL<|N)*`b=Ev8tL_(*Uuiz`V#e{6r7iyX8LZ7xQX4?a}NiS*GR3gK9UeXeS?siRTM?inw-?UOf+`7QjqP%4O zJ{hNwtuE7~bSU?~(d*+$=Dggi*MtwAi@8Wd@LQxbg>YZf!s4v` zzpzXX`?|y_n$O?HoseK2x3Xzaf7Q=mV|8e{U8nKSGl>zAkNPvGp7Fb%@326nh$nHE zLD<|BSAlQ^2+0}`#wA|+f=NW}caBKfbmIhI7(`qTJ*r8bE$!_mDJhJm_NZbhTZ;ro z_Cufenwid}8$naKE}LeAB)muC)>Y#1@?Tm?+f+>3F+blRwcoQbhM_v#WBch0%4agO zMEnY=i}A6>>A-hUc>l)-Y>s+Tz)Yhu>^R1 zokseptm&nlKKsj7DLvclC;k^~0OcxCW!<2DVXqW@Gd}*VXG4nEOhl{L6DsX$aJje-iL9#6w1iT$6>2X*r@A?O$8(C^EdFPO?M2n>2jrUDX#o~!6@i-kXa|(SoyQ8@a~_tLt1CP z8}*)gmwdI^VxYR2X7NWZE$Um)<6dFIEJGcK|4yhIun|fzE*7Ke_&GmIeh@^zkNo3< zd8y@EU&(H?PxG#UhkbJ27~7Cz4c88_viO+;@nNc?c7iZb)j)79gU>+DLWf-c1jhGA zd!cbyPV+7|E6zi-cT)sIxJ}((VSx3}{@@$LN9tMBhAIj?RqnF-ohsxK^8(8|g%HCO zq_n3>Rg?F7^_q{hyAvT#8dehgT7dcqycj|k7YQ$)&*-U(_wXT?$IF=j7D2dzC~`ak zwen*!FaCy^{}RWnQhEV^u4U;~TCq((`OdsCoJkyJX>{<29L4?gUDdx6nYhv9<5u9; zH?3i{w|(sFB^c;Uf1w!n=bOf?4An=zVx~=X!JT((R}~5NPk$?r7&-eWaD%tcB{6I- zb4UI}#*hPwQER+|x5x;-f@R-8>nyzf=?r2%N4yvEF5q6Nq!pj)ba0FSPkm@DXDj?E{hv0+m?)Fa(S+qv7-5A zTzAdPOK1r@Q~+rSD!Au?SE{4$p-G~L#NE(2?h$V#kGZwkEYjW>wAag?^WHysAkDZ6 zVg76k-~me4hOboH4le$1K~uAe?hVVE{KXtjrV?*@Gde-F2ML)TTc3}uJC zUCTck==r`1;GVK!6Tf_m%g7taM&k}QeRH71BuyPkT-oEY%vvOeHI1!E(t{l;Q+a94 zI8hZSu036s?+9QNzT=Pobpm_Z#WanVuO(%8eq=T2^RCY?cRpz|)GZ`>uiNE6H+%X* zW)FYU#;;UsP=CET|KN+s_fP9%Z;BrkslDfQSJX)^tA4Uul56?)UK;3DaY0eUtlgX* z%g!yIIH`eqm)Mt1*rN7Rb;<@!PIzTqCV;;sd$W2^#p?MjuUm?ij)fR*II?YA*0UmnlN z`>?5gfo9UVRL6AEVz415w4+UV9 zybXn4bVh`~1>up=DeZS--se0fYd+jj#Ik$-V<%pyd$$YnJ+Z zr$qZbN*5+AmaJC{9B2;+zxqnvmGyt9;N`nM-jfECEW|@n_Fy~JliMDur9}G{ zm3*B<{NzXRc$~zFREIve_`;i%u8-KwtWt)GpLUPZrW^{oMPqZb+il})H{u;7)*K*9 zAnEr;qCfFr81i3PL%_f+`2c8@C?UDeP#Xd7KB_$_?@D}vAL zbmz1$@P?H22E-oqbxv)nzso*qQ+vu@->xK7V$R_*KHV@>(WX%$ zP)mPr_LRzqF*09a#(qhoRC}!FmsDByu=tFCZNq~r3O6s(BYG^Q0Y|h_1x~q=_Gg7- z+5H`PHfCoh)%78ZmXW|!pvt^P#oAyijkFOWNr4Q@)XA}Vi#B3wRTcY`SE_+VV=+$p7v9{?*s4eK=1k-qSFD1EFRR@0~8ZAlqLy?8!%31dn& zdwlbCRi;k=bsuzbgei&)9kSjTeYLYsJM|9J*EdzYW1k!!Yo~Rtnw+5s%=pyE!bfN6V4p>&%2~g^qoIDZ0%N}#er+=B zGv^jU>(;87p`R~WDx-&u-2M4)J!(85Pj0YI%VY41@6vcz<&kSP7;GQ!Qyu|SFI%(Z zLU-&l$Y$cDZ7qHeRp`!hIJEtuN6(fYvj=MJ@aoQz<^?WZ+gQh>{@&dqJ~wN2*ezDe zP$F67)1ezb7*h*;s`z!E^*}_o8wXUSC5pvVrNrNMYatcCS+MLjF7hXv-2aYD+r95G+tBFjts*{F!c`0Hyon)cV*cnC0Pbx@DfuZkiy!{|}Aa~GmBzIzk zFQyX~b%5p>SewrRj^<;~%VPHwG|aZ_w%=i)0L;m0*2OvPSiND>Zf(Nc543_XK>ulY ztS@n9@R&K2;1|$K!QS#QD_UIGyoU%Ud&W0!#E+rX!K*Zx=#}R#w`s8p7(TcFc-R7q zB1J)^aB<{X;dn}gx~?gHv~_@I9|!E)O$t~^%JxMLMQE5(h?;Flaav6^tw;2}e+^Q( zBagzVA-!KBY_c=eE{W%s8`UXL75!fv?3r3+5}>)e%*yN017gIhZVZuuTn@C7&RL1) zWx6CX99S1ddC|Y{G3d#FEKuq-U&xL=zgv%i!2Slc;~FS+Y`0u^vE;wfo`)M zB-d?`v`W0%H&jH2?>ktMnFkE*n`zvArKcOW0$Bz<|Cd>e+Z}nxBTR6zANUV?kYX1% zSwCct$bc5i^ZF@*p0(8{4WSMH`(Q(J&OnJFDyX_tRuQF(x#)AC*a*#?v2-afQ^M;Z z=`4>qh-O5}d${&v&zUv7;)9{=L3Oc;NIj3xo+;V5;AgwZ&o&|eMPL>lx-HX^ib|jf zq`mO`p|p|TYV1O3CrCe0^*8=d`@m3`-Ct>@L$jlTv`{F|`_X+wn7m zHnoNQ#76q2p<)v)mVr$l_w-Qnux=6pd)4ZOM~O*ou-RW1gGU%JfxjokeNnA1^a$-L`d$nB(rL zZYp}F!>4yTO1>c{Nn@^wa23v~m2Le-{2-q1=bLOxQ~e44!8&7^oW7^(fyo9x`K}5$ zE5850dBJ;(;67DUZ}w7WhGj^U={(lI*_@H(!~*(F(A=LWnvdTZr$(_fF)!O*o)<$D z!$n5a;r*}-)PC$I2mz{G?EC5TNbdT|8sjIPC0HmY@&$NO(3QP@h|+hB>e@wl)4nr5 zxhpeNI?J(FDzYJ6R0Lwvzy}@$RJW}5nr;LJ5q31!Hi_;=e17)qHl5gwPB4wlgY3^nZQaRB35W&@+*6h|Jw3-LnM&(|GjVLkg z$)i`jfGJ_x;-ddq%fq^g0sL3Vusn(s?UAxPyF)-zFsV(YY(Tp@qIfwfc#RHh$DztV z$&d}=Fh|Yqu~~tfVtugbF_Z?|=%lGaMFr|OoK>*Nmq|W9oUE$0Zz7f%4X|k&D^bMl z+cKSL4O=cNv#dmz|BtUorR>%ws86UkAaXGw#H81z`DFM=q)G^wgg6vEvuZ_CNWTT* zC;S$E7zpTv_L$AJZrmfe$2#CTugT{x6P57JO#+SBIAAR{L}pt3D1K zdvee_7RDcC7`*ry6@qyE5?_8%^Vq{;2O`vlV2#3l@{EMV2=Q!}I{-?%bEM75r$(5w zZ50lGaW^9L6M!E>f|Z*_b1$O>xVyc{j0kOA27(k5YX)bzU_=*BemS#iixC+p?Ei}smy?GUU`)IS5@OZWyAIp4Bpc^M!@TQZQAgX-g^KUA!T{ew% z5}~j>b56tz#!+ew@0mXw`yy-_io+5t){xjoQ0TSAa0qNj~;pP_~#=NN1*( zdBf~g*brCZlXa#r{g$hb-k|M3Q1fg_%wP9*#Y5ynQTO~3{rOR!Wr87{3YA>iS6cfg z+-g2kQ%fOsUoS&q$T6Afv7=ckg`gdxTeo^do%1Y*Pw2!bulL1hvDPgJJ(E&8^BG}o z+6C1FtMV=9;!H=Z>=~hu7bSYmPHhoC7SVHR_97`Nzmx&10uC`s@D9 zSZ~hjzA3Igp`tn{Sz_7OeN{DA`p5Q-&5+-WZr`?~eAzx0y}Z>^dr`@b06?vxEf_8~ z&vUE@+8?~Mt0ix5nEpKs0o_YIpGEVcV6XA4aUvM6D!J}UQrz(Mb4gjMjDneqc{tFx zihMp1O&K|#UOJriFd++rPzt|je2=b+xzI&QLI|PQ=&&WT6Q%Vc(ix%w{_*X(il!ET zWlnwCm1tgZ8~&V|`;?oi#ZUMRk}TWNG@O2zH~o#*H2m^s#zV(_vJv^YRTiT?9rQin zwB#7GTM08@yg^}z zU?_Ty$E`TrptV_aBWIoV&-u8qIdXm<)x`U0MU11oljn}!v2R=NF*Jvy&lD^H)Gmm4 zR(6C-7QCKnA8P2ukGHaficqZNpLy5daQ6wABsH(n@$6U_h~8_KZ5g+b{1mrYfL+1S zlCG>CbfVPQHT5S9=ZAAjtA6e*EmYcr&>9@o^j6L*)LLmSZ*S5an&1&jkK>!&Ib z>{!~fI_EnR6VW{o`{2)@(Gl>M0Qk#0lZ)>LOko6fr6i=QbtGUU(M~&~=^T^gRbVz; zeXZ6R0R6nV%!2Rng$G&M<2@n!DKn6Sc(52!9R3Ybf0S?W2=$pgBj=as_iG+ZpCMx+ z>4jpn01AQn(33B`E6yNGli!d(0>7lZ!6aJMe1#jMhMtPYvT`p_&hy#1^jA+Ixi(A?jYAEk+VHB!E|pBHy|?_djK zU{{gLh4o1v6rC4jRVe)fe-VP$8(wD|xEJOe(hdRooa|nC<91NFYE6oq-vkm z7^>Z;*WBSFX=TWf2E?!@k z;We7}B^__&dJJ*g$K*RDZ}}f8WH}TQr)OnV(q%LP4mPdF2JRC z3)rn@6&gJc?8Z?hVxzxSvag$l+eoAb?|~7?J^i$m_E3*ly%lKOf^98j-}H@ywaciJ z2*`H*P|V~N89wXbPMGZGqO&Vq?Vn06^x*?*ofKN-#GBc~(9DWW1Gyy)6yifBdULVG zMB`u8ct(6m6<5zZ4IY`6yX}3r)nIkP5!}i_M^*TdWWr?k7q{4K6r z2>FrCJ&nG_X&ep2&?5+_KSzu!{B=vlwRX}`-+U}uSLddLEMkTVPo!;sHhQUFDSn4H zimzgT`8;>~$&Lv_d`<@58sRez32|~l1;L-JSN+K0S*kw?1O-_T= zp63&M`l_n>R`BurXwww+TGgyT#e9vgUCWmz*63`^tP=<&R&=zKE7rhJBp;8<>1!P4Y7hS7Yv(@O*HtB@y;C{~$D9P5VZ zOXADRJ?0y2YAUq4*4H1hbiA_+jm=*?MY~L}wd%#fA|4%v$pG~YX9e~Mm#)Z-!CI7g zY+oP)azQ+vT0Sg<*x()pNT-uS=F7{XBK~&|*5Rv6gHs)|>+E>Ct&X^!VP}e}an$xw zryS+hEkY`-)Q&-#JZmi+u9RNYHJ4A=q$bT zp)N5%r|7(xR36Is1B1MM3LOO5!+8Br@e~~lnFY@lgV%f66V)u&)yL=Hmx;Hp15_i0 zU0k}(EEV{9TmTU-lG=P8C=K(0?t{#w^RtxRLxnpsVA&}TQUSz=o@=;AvVv@WiP+y9 z7boy_qg-v1nmrD&dWwVw;=P#UDJtF_kl)gD#@)73TW(s~jSVYu7N8EX2nNH4E@hSi zE|(J!jVckP=Xx;#0u>H?&fw|noz{lJC|II`VcRom_0BY{r>kam0&)Ko;^W|E^w%7p z?e=-L=I@P{XdGd@KH?r&_WkrI&Rd108|rpaBu_matK%JA)sn)VtIieMs~T776O+}^ zJ!YUHz!Hul`+#!ayOY)|$))dGcmNA{4(>01s(X*he<*F|w><7F*H5=`+pm!cFj)1| zG#wWDf64XXZF04WgWR5!6q3(a5^Z2E3i$gxeEamYH<{J1jF5eV@@1Q|8h&`rRamfP z(ZQ6(z>njk-?;C;@i)D*D{dm_8e`}-k3*}?FGgZj9w4ITrK8xm(-0Dn33RzwW$rzel=-nyNp$sP{aFi1dp+kJNaG4l)#rPYr1PT?(OG1+Dk)g-wEnI zR>RESLl~2j&&9{-^9R0d8hi0$n=akmA3<8WeMTIk`zQAZNA1KB#qLgMg2;^^DEiCU zpGd6rYY z8-FIY4Bvj`s|5N3TdDWE<7}V0VB(=*#V>Rnk8{D89#BUp363O_tEL4OkgPwX&?JLC z|I*93{gkEi2ewOBg0#8bIm!&ES{*Z&@y=To*5t>)%x3RSa6(3m37-Q$i(+tySA#b& z*dYbBV9QU{APm1B>grVk_%4{nBNu-?e>T4x2tXDScQEu4X%tImonS><9e|6d`a7ft zt-3B6va$hPUOU9g7-mmd;cr-s_7|r)$zEp59%u0FC;)nDrHAdLSW~oeB1PhKGO|K` zG#{U16sHnCh>-H_NZ#9)6EJKVgo%vGuyli__tnFmb5a`cExV&JAv> zL5P%+D6RM}=OL_p=#P$3KbkvQPdA*P__46%?OT~jt_cS!*^_{vA9AuHldNnVKF;iy zob6zd&8}H+r@HTL%*i(c0UAH)k_hbR7YOhI_@ws(`|1bIElkcj-c9UlCDj~9A=B9j zsVwx@R>XlfR2F3|^&EBVG|zUdA18pxojINWf8f71%j`8u&hS& z_h#a#MB}#q2{Q0|IHhzV!m*sR>?cE}NdF(6}r@zk{M;oztV zgHqeS=rAX_Yb00i+)N*;dZM)8PH49oHPQQt+4E0Ba`Lp!Nk({syIdO1e=2V;*@J}N z&_N|M2AJ&r%hVg%W{09gDKGReS!2f6!5^MLOEUOYP!S;V5f-8@k(6@TWG(mKX6@E> zyrZf^PcCrpyrJA)n64a zn`5z*hR(JWe&A7nj%<=Fs!(eRrm1c(T-^?6g{#;S7HyVyAUIs#`S5#hH4ZIh~u-O7k-Hon+U|&A^X{)2#oM9E=_Cb=JeCm8`*HOot9qpkT!`(6!@;7`+RYP1 zyV3P%dn|(Noq;sY363i0Uf$+&KMZ^!(t|rIdbr3D=ULHzzrMg?zeSuYfei;f=R5WR z8>Kss;6*~B*bQ{Xf5o-OV*H>AE%$jJ=aXmw2cd14_bWb20cMp9j_bkP3EeD%CS3Jz zlFWB&ijwQ+%hE}{gNTktzT))DFYQg|>mgxl<*VWm-Af2`(0phV6Ot8$CU2g)p|^i} z_^Y-84ALRn+G^ABLgvFm({IS=5-&Nq$TBJu6n_DBy~mDz;yTHQM2>~DmfF&+(nJfD zPkQQ;*=V?KxUvi;jH8FRHD>E%7TJ_IW)vaDj+5H526{6kKwFCX1xBd zI1@q*P?1@v=*3G0K-IkOkQ0p-yLQnQpfOq9jzhjH?8`Ia9D276Ftp1&%{=SLfouSa zwSI9|e=2myYWCRs+Z*Lqr?L3l^3fsiVox`gwjxq~>4`nIQM+XtR`)x`OJ|+D_rJsr z$$YS^Ne?#RVTRY`X(tZd7rh*H&uMn&=oC>gJ8z!*-OQRKbimHbPCR23XFmo7WR9Sj zD(Ia-i-A-JWo6kC*ZqLR_v>TbK+5B?yFMdIqyiD|7e}dUQU88cWK>f5@mJORB#|VQ$Hz-l=y=hnEbR_c@sr z{9Bf$y#6r);!h4%16U#iyiy6nr{3M_sT#5t$7uP4Nmc=*;`}xDg-xD3okxt#A~@XV zDMyqhD&uu)*9hesWXY)UV-gRcGjCKk;tP%xUFD;ElYx0kw-UbOn81dN_LC*TJFe}G z=GRNuC9d4UJaCqKS*O82F;vvrCdS#Ot$@tSX_-6ph%%XsgI?l%O|ak=@yF^V9|x+B zl4`ik#5By}M2WNd;R&O0dAJ(4hE!Z>zVu9m1MEL*r!w+-J#A;60W1DJ_~gE|YTjDh z=$3Hsy;bb^8H&@l;z{o1C!9z+PvTWfYIP(lJODDbUxHyXn7gr}IB@=!FU8qRx4Wmv z$KFAH_|`&K8Aq#-ZdCu(Y&Ov4LEi~vKxp<4Xj$@Q$!bZR7B@~J8Xt*nqGcdojhRFf zqVcJJbaX2OhmbU*ok^Ob34A|BR$b!!IglB(!@_4ZZ?TppOYw&3?!!aW<=g8Y`(G)J zPKT)6lh?D>=z}&`A;ZOj0=CuFz4K3guPM`scK&CpB=lSFTkp6G*ZE3Ck(AqIXPKWg zH{6%OD9l%GKn83PSr%UtbL<9Bfs}s1PUb%IfJVk5Y;T}Sudm)57e>@AHPbQqol zh04)N2+J8$5dLN~B>VfcKHiwy50CNhErx0csuX*7gqupW7Wv_wltj7;mHaf-H$?Tv zcq#IP$`8B^Dr&vG%IgikyY;|P=F>?6@Y+L2SG+ZiC3NKs&T+C48pOXWDs}75NvO$Ke;eU z0I@V3$%0JLt@W!*_mO0w0^F_#GLRT(H)fqecw*43iH%kl40REyyQgKa8Et866BzW_ zcmiW~IY&F*@0&F>l~3Ykj+Y1*-?pz=VuS0@wUm_0nN7v7jnolIX!oLFNyH^2d+i)h^`WtizbEM_C&kf0&~HYQpx7aB~+nmB&aM;1CqBOQ9$mEVXz zmBMlu(hb&Kfc?zo&>L|?^%EE!T^c}$u)A{_KPg*mTLR;}M6aR~2s5{|XkzXm>BA82RQUE6LMMQ}mjwQvlk`b&$HLF~qKz%#d zE~%Ype&tm7lL$MX+(jo-we`$H5~t4944o%yFmCbD^<^uszLv(;-DvJ(BrU>zGq8#i#%Wgb10(NdrD1Q$3WLLBVY9g* z-oz|~zhbuE(yz^7sNK*%bLXW=^=A)i!9R3yo8NruFgSi4LWSehRV!&Cs&Xv2&+D_I z(EEz76)XqL<6c9dVw;v-Lb;GQ>nnE$ZkN^D&qwdl4zFP!+rRU~Xu=!ieJCn2ZrZkg z>f9)ni_(`RsZaI>R2}{e<}Ex-?2aHxFKbyEqhZ=5jznSC<&tp&l*>LWsl`_zDkrea1r}n`a;lWw2gDmHrsIO5A#EdEo-?WTGbU=m zegegqS*pyET=+Xq-`M9z=A|(olJDhX&96B*(S&6Di?!=9 z8w4YM<~H*$xGdWacH}&WMoN=b->-62?aULbvd&3GF(jKUZzU z3>kF1P?~0}7a7ULj(W@u_Ib@bqT5#DDb9W31De(sM z6W&6&($q$WE_C2nox;KzY{;<)Dx79Dgtt-;Va0vlN9s%AD~@C!u>*JmXvvV5m`b_G zm)tiBbJ=ntqi4vwN4}4^tIxhc=&)G2qno~77d<_gDU}gwu_3-!+z9+#M>VnJAsWj9 z3?Q?$w$;PS+Q>fbqJd=#(oSpNZ=$7DSUc#1?OO&m#wHY_@I*V3$tlLy`^Q=UxM^vZ zjLrwFvt;d2iBF(H+!eh^cvsjNJj>2Pb^ zz6Ig$ik?|yG;@vZO2?Pf1XEYjPac-7(-zW?4Jdh^BgSE}+>TLX1zD!V|CAM14`{g! znBQ`(l`m4%&UB&^XfR2%(?3BDP#>$m&eTU_=b(X>_Ms~G0Wac4#MD>u~?qXe#XF_)<265&#wO@s+X* z$G5Pm3F@SOGQ)kfwD{!zF!hyTQGQ?7z|h?x-6aB|(%m5)(y53jB`IB!(h4XcNJ@u* zQX?G-O7{%i-7w6&2Y>(Tx!&*dVa~bF*?XV0*Iw%_Zrzc(9Fl^`y(vx6bGgvhVnKaF z>sqa=DKRU6eElaW1;Yr>!6nzBgqCZo$d0I#_TC;k!@HPTqzIS7Im))SIfx|d`S1>0$K|@_kG!~&_rv+nBu9N}a>scRu{|_Jc2$=@gp<$unfmp~k!INSR z?IFYIH^M(m0Gh?Kld$>IKW!W(lgL};AOD`j9s^>H%MevcI##=XxR~(>qZne1nG;&d zcEVT2yr;L+IKpN*5eSkR2Nvg5Wy8515EA1~-@Rk{fl(syIu`OY3B~T2^zBg+)B2an zh9vpMq+j$gr~w@MY8Bt{+#6xKC2kDRvI=f8$`t)%LSQAO@qt}lR}aJbh~qLi!!1Yj zSwy@A{^$)s$pg~$FIINgW&$O*3XMzrhdYrTaK7f&{Qbph+QJ{~76B<@^ik}b(eRRm zlCKc9BUu$Zw|UpL>@hu~rE8hwjpsXy7m|&`6ErfjI1CzbJ zwvZ}b$>LK8RU5<%H7ch#-lyCQ;O`Kh>?XRj9uonjlO2ntHOIwcyrGk4@k42EDSy`r zHm6Y$OGWuxfm&6J0?V9ZXT&3 z1xRDh2spk9rHwL~JZh+ui5@MlS~AKY3{I!Q@xeK(pPZwRw^QsG*>#64wdnK*ik&P{ zC?Hc=;9hU}#Yph*7>0N=J&Vl$?KmKCBvO2fS6#cz-FzI||N6$`^_*$z>XxeNN4Ti=2b}VXtJ(;ZTGN9XW^OF;M-ylN+mPU5{hj!4(FK-%!X-zb8mmR zc&uj|C+9bph33eFR-q&7C7!`JIUs$o3SGUrAJ#>;JCJ$LwDAbnB1J-+8?{SV`*i!E z0)WR`Uxdi6#`|<*60~7m;1^Z7;3%%h{%(sq^q;2lB|dP{3SMxu;e)i`f%Zmg6f9|q zj?u#^&E?V&KAF%y%p+a|4foRkb2?)-ZZ zDaK(A2KtP>_KPZpiI}8+6V=k4h#`m62{q7&e84ROTI9MQ4M4+%0*NWX4 zWNAj(;8?(QEhm<)T`x8`c__x;W=7NkC!nLPDm)|#y)j#1-TWiC%;{!$>sq9j)@cSn zP~<}K$q%;!9M+hi*KdgZKbOTfYF(>l?A_&HuQjG87q=tGa&5$LN#q@GH;BG>POD{J zl86SHKV&(WQlA9g=LM*Q17ah!It^jU$+ecq`H$!R%#j_ZNc!{NIMb=hGkN+WQZHW} zfN6AFtLN(s3Dqn_EK?pJNh-1B!^;jWWw{iF$0Ss>OBdxYnwK+OKP#(i z!KGO7tvF3=^)5?fYp2d9NNtk`gRv`f3!bc-u4u5Frk+#b_QS`|LSAx7pqH2`U@Wf$ zBAEYIf&wh((9I(@OExFo^V{=`ShSbktFpf5`zGV6;K zqml51PuGoQZ1L_rJHU%zgho0HPr*hLx{G(b%64usf~yO?qCkinR#DVGQ<`~&{8m7m zIXg9hN89SdVhN66>`VG0t$Z+)4(!4lPa&1l(HFZE3{~Uu5>``(qNFfvmcM4XY;KPd z9QrgCiszS)dUit^ZNn6;V)~n;&__R=2N@i+0(qWJ(j%UMpSf$-S`zKp7t=7ayg#je ztA6fE(_!J#tvMkNn17mp!koK@Y$Z@@@J_$GOlA7xS|i$&ornM4{rooP-c7rdNL_VsrfZ$ydEf(XwL!{=5$~;_TlWzdF=`N6bmW9$P=G9~N77k9=LM zD)nx-^v0F55c*^J^~xAlDRQzx^?nqlz)WphyB~tjv4y+nwf0YOgx$9L2gfL(NMWyR@U8?D{+T9+~Q&Q@qMQQ%7zs=6&Q!#4P3n5%+Yz3d>CiXDor{k_E?!~I`* zOWBAUM_H93o5sm-j;Vhn>uzZE_1(vfkwV+{(P7)HFd!M5e+6Ad$6q7WVOLK+pK>+~ zLBOyts$1739UkN}*;gG8@xDG-^Agmam+mR$o7zXD47*M@XC1J=<14fqRD@pCmwUO0_@Rn2l(ylq6>K z3PiQPSM{z2IJYb8o=1E7#mQGN|3ANPu#LsU@-H%VAG%!ldP0P&Uf@>-*=;E%6F$-ul+FF7AZ!Fi zleq@_)*e(DY8~RQl@~5L>~E@6*E}KtOwf3(IqU7xB25-&={LJIy=i&G$#_FlVrQfW)8X@#eLYxE;?>&!I}r!se7ov*b4kY zU7n+F+;R1asYyO<`8dEkK31E3An3OS;7#GS5GVqVsEcxGlmWC1s4IOt zyPDP7ifS{&;If3<*rC|_!*#HK$*K7Ly6`zHnURkUoYudm3Q!Y9+V_b34yA!-{o}ZH zL{x#f$()|lj6>=DhwZGJ2wZoCZ)^*$orf2gyvo_pj+Bi|a%GM{{tGh4B*xf;dBIWC z?o8@kt#Ob52Bpb*HKCnFQ$J_#ZCG{OVka?9Zf)J!>udx%3TK7=gho7+*auyen05Tzx@Gh z+BL?U^!Gc1{G&jk{z8$ZXY(H9sO;cxg6Zrdi0i!!U*hH=an`QzQGDsjepJNx*IKE# zsiCpqAzqG#<66$llwUyH28iUsf&^>0Zo9SI2l8$MqK^947qO|3Uh* z)tu8C*0gpo-hh{^0}-%4ZB>J$n1o_YIQ#1RVW2)g5K3LxDwRK06=wwRQlJo(S*Ufz zp%U3P3?-LMx34`sWDL0jLa2s*{F1!yt zdLmkjpPe?g4S0&M*=AXKZ(i~~`z;QcDvppAc0wC_C`K4P7>CgL4C#5g{d>K>m-px< zrwacfXFH*f4oodGJ}}tJ1|zCd_{9)WVMeOHo_>8!9xP%79f#& zzdN(-9wmNYRsO=S8;1VZG%Kj5tmo3XouZ@?kGfP-&qNS=r{p*u{qN=Mh_rP2QSLi7 zD4%ck%e$OVD&V?S7xL#!*+E0WsEre>q76! zI}nY(3T2r-ulq$0s8iuJzPJYz{yOx+F}#_&p-QdKsE=}2cH`gvLemNPeDo~Rj6%{` zr#%0*me4MVp!ZZi=XuCb&!AOnlaOqY@MXv2h!ypk=t(r|IXzix)DU=ig6eQYBTS~9 zDHT--uskda0tQ(u;sv%ptoiF1SCe+xu8IzYOy&jbsMH-sFllPYL%GQ~%r*;MmM+8X zxZf}FJ)(c&wTdpK5|9aFw{X~2KNpK^b`1n<9m_=Qr#zH(A@%;RL7|zt#79gSN?kjF z{o1e*OCbsvPsAWhnBu#SLxVv->KDR>R{taGWRR7HxuzMwYdiM6+vAk6ccQD8|USGG^2`_ovmGaiVwuklE_T^{5P2xL0;qcqp|^$*AXG%RuwD$3c%f; z$a*yBm9vgt3Fp1$Amk>`Hq8snpo-m8%^W)7nw}+4t6EH{ws1=0rXTFAi}zDsLE*Yf z*cczR$$Jgbnb7TKod1Zxwz@4F&m7{GX7JPl?2T$fxBJ4lvy5r^em1=OL~nXS#tQ8x zDg}3qg>Aer;qBVUUzL#c?qA`9Az!415X?;2F^}Z)&j~s! zD1i`mp=s@P$o10)8)w+wr&B-83l8ZY4PS3LcrOLSv7u6FN0l3+L64*xF3Vf2RXLV9 zANyU!G+|HZNS607DfTl@CL+D9y?p$wnPFp=yOADAwR@#<_rU!iw@oC$%jQIXY=Fi0ry?k14;SDps;k*q=}Bld6iJbT|Zho>?w z_XJW{t4kbqFkV&<9|C!~>vo1FN->Jm%k|Xo#$QK2lHbN(O|t!EmC0{oT(U`)F!&+y z3%}b?VsFqbNaN(ASgo+jJpG#1lOFJvi;jY*(c&(m1AXH7zK<0qXU#dv56T}H;Q;VM zeCqZYEf8BKri;0j%o(kgczpPM`9!Hgh_Wc_%DN~BFArwz8<0o`$BS0aD1{%NkX>{b z-EtX@tP7ViPdGLdEA~a)5J8W7JXC3q4y{=yFQeC2f{S9QSn-3McVo=23M-q0jEmv7GGxm&8S>| z{3_HTlTcNC(u5J9kbJ^4NAoC2?)wk5b&?!BM1{~jpE`zX_5nTDPIUdS4)!DKD;Lq! zcP%<~y?}lOEJFPCcSyh;e3e&~&*yDTBOitf0;n#xc_b^aL+nm7qWv1p+)QLaC%lHj z2x2(48Y)zR72{B4;TSgY9d(HiIWAiMyMigIO4({Lyx-4_Ue%63IU)Z0#@pMt`~p}GqR$Ao#?^;UBimgw_;gRAssWF0to+RGh}r0=@xnd?&8Pg&oJgwMla#|9#oaBCR(O z(rqV!&$j59Gl>#fbUY^^N2r02&&gul0al;Yu;|i>uFoTzYFMx?b=-92`BY!&_g1S8 zy!c9P#A)jinWJ=5Lf?^E1K?4nBV&ZNa279mQQEM6ka1(XhqV3yE5M*KI8Z)_q4oY`5U{{AXoB*>TUk}(amzJIeToi{b=DQ z3T13%CBMig8|yo`CPFhW)milqG!j-)lhn+%I3>Y^m^>L1rht%43JQ;(_HMP;cccoG zmPn;Hg69gn7-fITW0@N%y6sr0M|R3NEL(Fy-Hbl#)PSGJ#~^=rWg5D!R6!R+Va97^Z|Yss&*u zCQ97FsQKR)>jGUC0hh$lSb3myr3ZBV_25B*N2SJnd)xQ{!T$?QWO)%|)%lyA+sb81$d=Udnc+%5UBMn(i6w#gO*gM7@cnFYN{jC%vC? zPN{_~#tXp{CZDmNG_}>mFT**ZNO-&@9BWE3l-u+0r-&5UMg2pKoJVK-51l!z2odPM zBU3PA2)7+rB}NlLb;ZFs6D~t!shlo#L62)|h(8|Sw*9LMuCd%0i#Va263+mQ1d@5@ zTTn!{&%M3cQ|uKO^OLIp(_D28sV>Gw!hk;_KoVQUq2ke4{(qXOb~C^S4LoWp3@o}s z+5X5`f!U~A#l*CoYtyygYCbU|&Dh=vZ_rOuO)A5V71D^lEEnYGTQF-NhgUeB!~M8g z4do}#H-qHWGKd!Jx63d7Y+nKqR-VvcI#$l}-OKP0znMM_B*k2!m*>roW%0l4@=#Ty z2_cdi{sS=^K^rO{Mk5&_3$d<2F-5e78tgP)dcrHo+H3GBEDp@!Z$J@0n2bZTf}R@> z6T;{+S&smdjfOwQ-?Oj?Vq3bWnXH~3|{YxVft}}*pSvBC7zc4t? z9A+2&oX$$c<{fJk&YlsNRu>d>{J{vq{`0NBu|qdJ){s_T)^C+x>^w7+8V7txkQWUB zb0RcVSF|px9~JZRz?mzdIV}WE$_G|P_~wb;orhg9cZ}W!9bNE%)G_r!GKWM!|3s=x z;go!sXp1ql(frGiPRDB|r}a&SYDFk)A2$no4ikaqD|B#Q3k{kHHP8sK0t@2FFNk|~ zewz#Ui(ly9A2*sXnrLOI0?o;PN#hQ${36+_7cV?=gd!RPe|s z-xU}DQ^|K29e$>~`Z|pvU%T&kYF&TO(vfu4&u{+I4@y`sru&c3&RHBZjfKS(o#qyp z+ns{)V^|ltl+82jrgLts2?=FcEz5b2NEDL$;E_S%lwDHF*eR~sYFyg8fd0W(Y<8eC za(&)?soe)X0WF9GLGR0Gj)NnG=F82+0)Gr;;*`0)cC>o;J?wy_Vr0iV1Fz`vtHBjm zB^&Ci@Z*tFD(zKkPTAX9<^W$yGX2TFT&SV)a!Abe4k&1DKa`dvpv*juty5e+E9IO1 z&BUhx2oVBGidH5^` zaSfr7zg4SN>h)7WYWCv-KMGC5_L;QX<*zEP z&s!m%*f~$~Aow-_bS^{?*`Wil!6in zwQEmGaog{WSKbmP!(1-cfOxUfm;K(DsD{& zO>fj!+LdT5`q1FPuEzFvQ@6c=juG~I5^U7G*WwLM*E zxhm(F;Yp85DmnQMsT)x;Wcv6KkLE>o-ot@`D)dIk!mIsje`xA`tLs515%eCDOyl!? zo=l$2WiE))tu#NQQ~wxtx6wPNWiIn7!=qpY=J%u|Da$ihDJcDvJSq{G#jj7)<5iCU z_)0k%TYu)D=lwkV-z%G|)}|jgG!R5wW&{R{P*n&O1Rae8e6W4vO;QmH-~oUSs6;9A zJXRbKID{$CJ}leU?+^Yek8EUL^N`H*XbeL%!j4(CPelyxZ}ehGD3vR+;drROmX2Ya zIhgw_gLd(OaeGw6YP${E9$NJV(Naj)&U#M%G^5ns8vOCvFIX0tVOmtPjN*G(BQK=| z`%pD}y5vA~hF3mWLgL=xzCU!UUqO_wnDmNBN7evpT zX5!YlBfvKBbKUW|zC1-U;_Wu^3qR~T6ca^a2sbh(m zTysVI9#JK9*)G%P^yxjKQ6o6x=cp%wFuU5TGpIN3tx4Ed40r6K$zs$VWHU^ z`msdJM>GC6)CaoP`?E?}uW{h-pyOvP;rwg${j-<3CstR6&9b*Tv=@6~RxFkcRzQ4p z4@;AyObpI=DXX`tvE=Z9$%NX}U?t#_QtD>Of9EIq-}xz-sxnJHbYUU*V4(=A>MUFf z3b*!2@hnkGk2CAi+?KHq1(x-EwZH-lfT;F@B3gbg(miF_aFW`ZsW3Oo%Ikq%C*dWG z4U6?23#yYa+lm-}T?l?%KHIJ;A#G4jpocv`Bv;IF6#RhN=%JA66t*vQHG0z@i9(VZ zY#yNWgJh1zBfY>m;D=+v7olHcC0==m22rrQ%sC&g0kURt$*nnq$tQ50Vx5$uJgKaK(C;%rGY-p0R_4D7)OSsdBlGHqDZQ%NUrV`e ztvs<+yE*xO#nHKdVl$&M1(vh2ZB4}xgWoiCYq(D7N;YwnB7r{U?^X8GTQ^0NSAx5w z5b4|BRb^IC`Vr{5f;KlB@$YkEcXW)qV_Asf8~9G9${@EAd_i~t7)=vH71n6MINI0= z*i7gz0h;#7;vJ0ge1x-|X%xiRJT;x72A+H7uA#miGtNh{%KVKF6Yydm1*J)AOTxJR z7JmGvyl?&d^DD)G8t%gD*0}R=Hor*LT-N#Jz`s}>ZOZ*EPHQXe&r`xt8aJok-MPZ6 zPvv{nfY9dQ$5G3g;tiAv&i??w)lO)c}G%Rw&QpJ1{5Uu zL?C|h!EDhj-WMmcA60XH;{0=NKUEP;OF_|aX{7?g8_NZKj<~7nrjfCD%!&PB5IvSS z26d@-unHLUW$djfw7zlui^ejUlvMgEYQ1opz|M;g_y}-&TH_rGr6+$rcn^0Ib{!$d z0*lteX&asxKej69T#A%7Enu9<%K&0%zc=q4;Va5~lS|sbJjS{doDn;*E`=?KJCbkF zj0o%hH#TTi*-W@(T>vlqd^ESuo!YF-F?`AXB-rQuYe#wXpNId8j+s@1FHm>wV6; zU4;vowY$x9SEvQXr8TE&J)7#XsAJT8{_V=PCUV3acgiu*b_u1Jp5QPfIw>AMg)g7M zJ~mY-rGiVdq|>lqM43^s4lU(nWm?1Ry_rj>5%h1sd_0$Q{t6-B2;Ou9ssyG7Q{|Y1 z71&H+PVS9ETa+-&Hk;kA%n(P6T$~_?1vUcniSw|)Ku%iLx?Q^~3;S<+g9or?hbp18 z^|sun<(3zMcO1%v3SruT1dek0qd+ihU`m0KTLDqAH3lFLf)v4<57kQtk_5eW}t>m?$HkSg9zBL znk9TFV+Yt1rm_p+HO)3=Or9Z%q4pu?82dOf&e_MJPqJ6ApxVU2&5zrr-`qRH=x-Yv zxCV}CUO>J6PRcjA5{?A48zXs;v6goJP~QjUdS}nFw598>t4^BuHeXdD zXi9HPwg!E2PDELX9b`bn2UT_P{wfx)=WmRG@w>YE&)!7B#%E)OWSB{l#^2rjaoj3YpTX^*(C@>g;NuH3cJ}896aCuAs0!wrG~yK%ycJYas^}0jOC?Hk z{BK9@(GT0>xyaWb)~D6Ab%|Rjzj7&ZkOCIL=vkO8^uEjo8aA$4oAa-F69VbDaBaw% zMD}Jd;`_!}`)i9qgv5TVxj_wP$wm=vjQxvi$q#ANPtvg zh1nvh5ye&mLe%9@3i2(-Nz|?9Cs65~6?Bp5Gkqf0fErJmN^R@731kzIi(r0{mSUXC zc?28k9y`{xk(%2Ozs%kAXBWE;68osiI@IGm;m9dgVp9g<#y4u-pQPE;QG*XyYYxpZ zY)f9N=9OSCMgMpTKZ-%Meb^*nn#E4t45mJ?hL#C;1(AC9)MH-IajC(HIa|KS@Z+5c zaa%D>zv(sA7u`of`IEkUkynsX5+4iiIlF;Awzv0?Q=W{-MZ@W}SPzH3LtjTePPdG- zTiZ<|;70CZ6g7AJ$qwlZwHKyC5f~FgTpk~N{`u%Ywd{*jlZ}7v?|36xj|i^&ko=k!U#~x*}kx4n+M!u#kqaGcZ$x>{ul#f>h@{uz@Z%F=gMU)JS0Hj*E1s$ zzruhyey2ReU%Si8Ohg5#`fhU*xAy1m!y%GpZEyw@`dSfB?8-S26)ccyM&X7)n&CUP zAp%VvEa{+1ko2>p%ZOb{>bnp?)5HD(qC@_SbKeS6P0lnfQ?qOl&c3w}6`Bi`+b=#F zS*-fT{}@8K^v zV=&Um#gfc9lTiAO6=$C36e(VL)=BQnkA|Z_=)kY~!)1E*I4O0(aXp_>5~JC+7SYMD zGmM2q4`6O`>~p_{(3cyaJezYX&o*wJN(=sOOYd zzwd7wh%Fn@02FVSTK&gb)Fzd#ON__l6uNKLIGGGl0KNg$s_u2;gQ;%vPG-m>^nHvy zqm+Nyujn@W<;9hEB%O$rl6c1)g}=7^4LW=pKqqA0TTag0`oGX&R3KOpUhUAZ43k!- z3Y+Ugeaeoc*!Sa+GU-QUymTW!`*j?O82*A86zwq+`&_yjzGTY2*PNXSxeS0Wf(;nm zaLeS3eh0(Y;~dEtGbz+f`=Na|S*q;bfcpOI6?^x*aN$;BkHepFJi%sv@@hK8oqZC~cWgd!+j7 zaW0{r*UA-6@}c>kRxsxzlW<=KJQQ(>MjY)Lg<5yMWSz)V%DRh@`aV3k1Eg{ZaJkQX zz73tyhxnwp8V7&$ndSC7jl}K-*5JS6#)vmD`h&r963dOKKPDJyggP2^h&t)fu91FUqx!Pm4=L1w+~40^MiVt^Xt=d_-GymJr+;QKDcBn#?e z*s{kf^{e+v=bx}^<@0n`9O)-0X1ECG&YM_~4YacazKmP|JBL#X_wJ+J0?@J{*Z9GX zCU8B_R$rfXwje~%`MwDKM^ucn1O4O32DhAEMj9%$sgB{#xF*M3F7I9pl~@OpKFS#g z{BK{Dwj#gr0zc@9g?AcAoYX=E$Hm_XEj7n!2omN|4vm0OEI%Ev_AXb=w$4-egpFvM zSWXZ>7so6;5!t&07Mbwu^w3LuNsDK6M2P+mclLN{>oya+hV@oT1b&6S8hT z{nK6&y{g-=;!46TG1`7V47^)(;Hncb!J3QvJ1-e;W+CT4PcEggM~}~Ay3)@c#}aS; zOS;blpLE$y_^X3dP9g1*ljz7&SxvIj^!ELh^k0!)f3w?tGNdP;|ID0EU!VLfB5f+g za^+??up>JZg^eU?QS%)_LS1`yzF8_J%o3%NAq}+}fH91DsQvDfm$j1@?iwSa0Awm) zyd&EC*031=F{5eqibdDC5bg!_dMJHw!ev>p|F?fS`0C${A3nQ_UYFPaX!QR;v(Ge- zHnp1mhWnF?s{rtFXLSM3{RvU1HuO*fsT#kTQ5#HEd-q_<#}Mt3d4=aC7a?Ja7)5Vy z9@B^hho?5DpRqG7jh#?ZIrk36D)|n1)L_e1FP|m`wQ!>uD{L3-6?>j;lU(Xaf&bi{ z+_x?1m9kH5xZ##(GTI%ar|jhzXJ|QSEz^5I14p|t;w7z9JH!nKZaeW4hGpeC><20O z4fP3uVOZC+w>K`YYiN$B^}#r$1}FG4fxkCXCHaQ(O^BmKJZ-or&53|#wCmGqHBVXF zadgn>j_5)<7h9~4CY=LjX05v_Jnjs+px}%3*;1h9noFyCkvqiI#*A{_Um@zdELX{a zDO9uk-mwZC_qx%t7kAus7KW75_*B&$5As+trZwfSDOy0Ad^RC|hy9)K1=tn-%TARagy90)0ThCCrm~&n`h}{r# zFz(V2YGR6mzzH3O6l3J})YF2&BOgp+oFK>j{ZZrd z@9pCPOz%oHPVPuHINHomwBq=pRlj)|pBur7OzgnKZ=v%=2NKm2tUtQd&wOOD=1Oh+ z?;i*4XFPB<+>o?j^Q(5CM9-R>S`R%X`!Vt+kMVU~#eIkjqI&;jGF{b6fMDtOKYSI` z{iX=Ad`ck6ttNa@&XExP2XI3vO24kOcM3n%=tITq3k^JJwz>PnhW7K=B;&7jKM+F1 z5IxlDFikJH@5$R0_!1VBK~D$A@JOyq{{T35WiR@%!ch*Dq9HM6f?`djWe4p7hHsWv zbuM1O&_J({sfQ~DlM^G*fX0-%WitNS8x%%|2%;|#1yK4%d1*CNj3P6khoI)n^xH=x z#%SojobJ-rQ@wp0FENa1+Fqxqt^~)etOT1n{D@$<#B;lMSm@(bWz17VpzaANwPJQ? zXS&Ps&>thE;axk`+m34fw+E;uOXuNEhcy)11qYa7+eGPUVdd+6%VVra@GRlH)b21O z^W{C@v8jrNSzygkjFNwL9o8uezQr`_70oFP+&}ZwCpSLYNGeZB-`>)`mkSKzgH(PP z|Bl`diphA?a%)m=w9e^eg9x%sk9^s~NW%T$b}NA-At!1+1%~nQY9x&&+C#w(4Ku@6D#4aub6Ph{1#}#po-; z#lGK~vD0D@B5ONP(MD;og;IYxuV53QYBzuirnum9<0v|k)7wa?yb4=s@ivVxi0ngA z7j-CQ9$P64S%%@A#SjpRX{Fml+I>wj7VXo34yR_fR2j^ldCsB(B49l4B&-_~M~1Pf zQ2LpwO|TZU%b?=kAq1YA;jMJunRKn!^ln^oAr_oS?-56o<2UZY_3sDnU1W=jh~IB? zj^8cFU9F_JTb5}tTG(+%W6(W=Ix=sn>fO`$_k4ZNW<9k^HelS@c}+!T_K!8T((Zp0 zyfXtMY&z2`C}Csso4}2FE*rJ)%nSGV$l5h9cqr*%xunJPS$aNDiQ3UpPiZaXc8es{ zxBlSqxeutTX(d-$E{VYy70*yOMK4j@LgQ#d-AU*BJq~k$q!*G!sExlAlO?t@7*h1U z5Vvx#t#;BWOE;1-j|@ra6dbp)!w2S77%RbyvV2x*ZH;vY#nMTDgiP$@1u?mT_I-#q z4_BEl7kGgla zsAhGG+v16D_r+S~(wd~{Y}F}9aL=@YjB3s8xj3>xLOy})x-k$BPX>zmFOs<$!v_{W zG(tS|))N%k$H#^SsSj7ZQYD^@O8AFQFk6TBdUu@sxxpwx>|w+Ep$jja(9wz__P2L$ zki?_pXj)hyQFixF6Moi{T_nwKe{pm6f9JRTr~Tb+R+xIgTlpf~!TN>2HnLZ`^C{NG zs}xsMSw=jn1&Ij~rLBDj&U(;R;Y_4Xk0F%=o^Rc_I@8-y zeBHXZf;n&RZw-2W&U85v3MDYB)6GgX%dB5ZoO>4lN7qqBqbr2QAzp z@Fj*(PKF!TjJRGKER0y!jF?6QO_gxR?1!aZD;ANY>ZW=tIQMu1lwWW*DP-tj8kQ zK+*nE%m_Q`zpR!A=})45A5{Esn^_CYHLbx<4dpgf)oDDxww`c8F#v5+3gP$YE;J%J zB#t2kzSSf*}tGt)YMjsk;kFB_-M~A!94$i-~ zg6>aT07(<&1pzR@1Y*eYWVe;whSV*sbws5p`Ta^D zw~FefO1wOn`=4vRpmCG``0a&;dUa4nc415Ef2cDUR;fVi4XVOObqQga(Y@U-y(8Gu zgU4f{lYLj^WW=+q3E^)PaDQuSora!ci+%od!TdevL%Duh95oWt^#NP_oKu$M;|2%E zh!}--RVQOBU`dtD0h0-i7-=$6a{Mu!)*1xz1v{S19jh^Gm2S*9?RxaBAKw^rMnq z&RSvRC@Vb&+mKMR>^;4Rp9J@wf6#Q zDMaTFLl27P9l!1iu{VME)Dd5W3-6*QbUJKFgZWu={~hlP4UG0Khc)T3RPjk@-OE<; zK9q#pTbv)-=0Y-#d7+v3kz1!8^Pknfqpw%?UEh6UlzG+F(8ouj?(PbIqE&=45kimE zvE4RSVc)TZ?J8&Rp*2&A?Q>k4PX0vzD50N%ACZWD^}VYyZDYgl`t3d2?MFZ5$5XWv zuk&~hdJ`wwZ2LZ%n^da*w>x}Es8clV#r%DGQ*uy({dZ_?!bnWGO}RUA#_xOx)sA3j zD-G&0qkWp>g+;t^FG#gg6f@zAa(#Vy;>tIIs89S#bkKJx>pp`EuzZ_J8Uf9-oF5;g zoVUhu23#wZ-KX{a#QjqxaMKS2(KaS%mx9qRC=Zmi1n14)G1ko>&)cBOp`GO-L1TB| zNT@dJWP73Xo(iC1Ffzb`<4&gEI1OoDzw6qRI>t&yF_QFo;)(lw@G6PBUIij`rE+HT z&_?MgDnFRQli#mn*Skb^Xb}Tj4BtZR!Pfxjr%1)UXf2cK)H(`afeh4f!q0|wis3x`w`?T3~) z=$NOt%fW3SXm62IurFDpmU)mL+5sz94>>7Ne82J(0 z&0;M%%g0x^CCqSWqozNLMio-{=J&=#5eRi{fvEE;o9eT?|%mVoK{3fm?hVWD`H zn&q78QE)*NNq@VvfiY^BJYhE@_K52-n;8>dBjDeFo+z;vClD+gSx|f_xPz~{R>9Mn z4ga_;py#vNMD}GRSfX};uRUFx;T(A2iDX;j1U(jBLFwFYOEr!*@D`6v^YKN=Z!6lD zzgH_b7E^{zi{%%X+@IzaRw@H1jQ53{ch~P@sVv&Z*B0(Dqw%NxTX&8n#tBfBBjwX= zVy7HKRx~TEI@>z5dvE*m{Rs~IY}gNY8csG_MT@#n^3X*ny-=Vxv*_9d!XpeV1dQa_ zxWdn%mEuW*1RTSNa)Xx*InlTtN=Qw$XwA@v!u}fk%NFmh&jiWlipzXH19u~N>iN(3 z*X5c=GP_Lc{0$JMXeauUq>S?u8!hW3AQPWEz{W6rYXG$)vG&$yMYc>hq`!)k}F}8zTGx400}Jgg9SPerI~NVpv*y zUH&g5%_yaH54z3!NyNFzj26*0l*Kkq-~EK6{~!u4stP5jrmOg}^nz~fWj_6kMpV2*%ef>U;Dl--^_e1|KiI?Ma zqS+TQ=^r}KH6`t=1ZQ9L`C7A07I!b+cXnHKd%fvEn^G~*Ej5jcLO0jgZ0ygO-VA%0 z?Wh?S##w8G_54dHS|tl>^?I>qtLI`p)%Fah^m5KwpWp{DUXYaW zk0~Uya~942$qgO0`HE`<nWNGfUgh>_cbav15_L5)0wvH)moj8NM1x&f2C14S&xykmLMIn-bqTnpLKaiEm zd5*g2&aeqxha_Tq*Ysw+%teXKIc|HYn*`>CFTZTX&GsU*{o@+HmodJ`ypEfm^xEBf z=@M#MP{x)Ih85%P`a8|dP!>w+d`eh-k;qS9CNv%; zNhN0<&u5n$n{+MG^!(P#wpONOEs=|{OPlByRxK`B@R_gu_VEWg5NX;-9fJo9i<~j4 zwc;wF0qtYadPk^d-yf-5N^`2XlL$1+IIjd_6faj{F3aqTUj{!TMwjECsH|znp;Hs6 z1@a=pZ#adbV9DEFUnlK#7AF=z6hrKU)(oGgN>K#;mGCNhC+9SExRHF9)+Pi-rz^u+ zVNf@qz0uP9bcB`PGRV_-e>7f!RuFoEX@A{A5s8lFvjOd2jlq%g>4uK_JkLnnw>yQDM3c%N zKb;Ay?E6#xCe<_X_&3)SwJ-hw&2`Q`rQ5H{j7Lh&p_8^@gu%EicuhviyXuEQ`+X*h zir)yCU%JM$J*W;UQP`!`;l~tI^U}LLSgR@T5xICr!C`VJNvhp&c8+?sSq9u8W(;ng zOTj@o8VP2{j|d!X?vH<%?^9=gl)IFjTCPQfXRSYVe)-s3-mOczjMP@e#xaa1##~2& zGd0=Bvxx`6#@D%a`3`R)Jd%z>`{S837i%R4=I&iK0eQ0m_EDTBH=BvfHh7H@&_&;A zfe1&SqCyhU1hI1P=Zu7Kth+zJC(YNYtxgQeNt}i?cjg|;rF_p&Bw8vXR^xEVz2Ykp zh%nX!dqUvk6>eHrQM+NCx-2kVw#77*YCUs(&GL39SjeqpoYM*yv^ZV0$b0*t5Fsk` zlqG5?yHIG%tFl}MVkvYAL{r_kV{G*;Q;MF_#2r|pqj(&fwekfmu@T?yO7?U{Kv{Xe z>XzO@Ub*EfD6J&a*`4brjwVmpS0hv=S8Z2H4iKjzYDjB^fiql%)ysHOc2sCplFJ*VT_ejV(ceCSp&8Hv-p+_)2Bf%mq=NynY2z zq(5gS29B>kavaMwl8OdaU{Dl3uuY)SSaOjH~f z1;m|`(2cHd`}lUg;R#h^uAYMz&|2DiXyPRqqQ!LFx((U`j-ITaiDbNoUOSnQvLCN}e8Ua)P-1HMO(X-En&$m)wRoqItNu$^(($Ka5I z8d${WEH6a3px;NQ3&^py_`N|Sn(kFcPN<}*TI5V4o?$wlXcpZS$kp~izxQG_@&wQ%r zss^>&EuhTUlWJ!-e8@}xU>;<=z7J&Xp-uqT1naWz0*Z6u=xwj?spb)xSgVYGV{G31 zJHpQ@WT%FIua5dCi1r@DH;gh9_U?KX`DmFQxuWi>GZ>#CBmfw6G}zbX2s_3=5viGI;e0XOFG?Praha{Z8q4@Nj{{6YD* zLgEE%EJ8oau&0jb$L6VY%^V%(-v*g#_^$6+sK70G^^KCzodw(`oI=3{?pu~QpAZRG zvEFZbQxGLQgi!ZH(%u1dBu!%8sMi@08rt$I3aGZN`V;~Fj8T`#jCsq?NTN%G5vzrGFr_uhp7jP>?v2o zR4+v;>#~CzrIw)=5fLEw`0@O}xqXv$mQxhcFr=(dCzj_ikYGgj) zq`~)I{vpI}zX^q`)~3NXn3QB>)Xgowq&~pk_Pf`syLrr0-VKC6+i1_JIeL%*UbgWV znAV|Bi~s?)@cQ2kegPD4h~qCRt_>+)VDh7wO2hT*#s_z{K%Zq@T5clQp{eOjNO+H; zXz2TQ1;2D!3nzbB`Xd1Y%9~ys`FkLLyH3U~_GLH~*H8tsGT)B-Tc}-fBb%Z*7Y%e7 zsPXkOJNQmU63tD-SFzSUvJQty35eW==O4Ib=FV$BJQ_UU{stg^cPFFv^Aj(g6go)c z3L_7g;b4XAmy-iZ8H6Ut!j4gb^72Wa^N9vLPkCzgKnvZcOF1DFFCZUzl@s;b+lQm3auJM6=FnRE{&H&O+%3|1bjR?4q18H$R#Dp1h$ti7!=z(qpK!N3)6- zG=c9v6zlw-p-e~N6sta}q+dlb-uPuc2wU>M?7r~9WQK<)T+<&g?gh)Cj=)iN%v^-# zErLp=cR%9&G#Nm=lcsY^)~Dgpj62HACZ&0({ZNd-`Xh^9Wc6@F6+VQOI#GjQue;x^ zMy(ZCscm3g(7P4$Wk6kYd`+anUb@1U)$Qlck$DG2F<-1|Y2^F9KcuHr_d1 z7GL)Eub-n^#|c2Z#i_?kw+~_-Wyeq%%@xEu`I+KcG&wD#el(b!;$9PLD@mq(|6G~( zL&8qu4Q%5U!JG33)0FznH2ZQ)0JPP6pGX(E6KTbA8EtJs3d(I6OegIu457_Bl}1Qs zaz{CR2N?iJrNgNYgzT@}vi$<)T`bK!6NHw+R1UYvP|_nVZ!8MQKKyD^jwB-ZKTw3; z4{AW+n%NsA>Q75fTCp)RTrce#6O>*YMJy?1*PaP(IMVn_&q{hnwA?op9@ferJK0Vw z1d`vi5I$&PVM;P0TzAugI`AzqS-)T=wA7>74Py9FDi07@66Wv+O>)7gjn#i%qiR)% zgf+PoH8_A8BBe9A4f^PEd)|F_EA#yViIN(!zGIn7^uq(ET1n#?v|ap}KZ3ZNE>6s= z_5k9;?@3-_w>C}Of)*tob^2`ioLJX!C1~0cJy+q;k82kpFrRbW*vYZ4fyQ*+{+i@> z&|5+z(V0O=~<`oDvO|s$~am-dsyKF$oRMi;ARymCz)>O z6F3R(rA+@7Ovz$*%9v9rs*K3f0O~^Y!9Uflvdzcr!oN*2_3WJ!#-AvjQX*R zhh!#o=868A-EaVI09Auv(1^0R)6I4P;EV6;?HK#(i_|#ow0~(*;APIXugTZI4gYTb z()V0RW+NPiF0{VGp9%OVy`O9vZI6a(q}4OXB)qgC(O$ulr0H+7QK~}35t2~~5voz8 z@B&Bxb_jxYy%5HyAR%6}CEDKTt-Ult;j55~thD_r3deeh-622?*lyA;5@-_3k$%kB zUD0j?!EKX-^k~1$G4~Wa<7M3J`xObhLCw~p{a z7Y~3^D zEO3#WY0G1i%c{Px?TNTK6z}+wDLAQ?bb~xUS>N)=l7_C{JhEF%=N-VJzrgHoFyr(aczIVw@MF>q2Ecyau%IzaP19rm1 zh|fYsdVTN^H`@}OK_%f;&wO6Wj&S^mCNsHZ^1@4l6iyZ*j09A-$#(^m<#kZ=K0{vp z;0i?8UUT_ys;WBuh3sb&Bx63^UiGtoTO&pG2iP^h-oOg;1-DOKNOv=`5zTq0N78)b zi&V)w=#k|_JR|-}8P7O3W(uI*_Pp;qSwfZ>Ys|Ov1h)X~9psS8=`^y=9v}D~Ajw{o zjQ!S)GyWxNKc6acUKHW?yK9mMY|gwM`CYU)Kl%S!EB7T5^l;XgPI}bKSkAAYlqL*? zXI>1lH2Ak9dx~wif?=w8Ot@Lb6`hrc5OBV0FwhlV4C+gUGWx5uR(~YBVRvg6eET8N zm5amGQi^dyx_PqIt~a)}+r~lTkiP8hmhZxH?`E`cZjEDc<73AA8g>UIx|>`$gCt)+ zUl93ea*D@|n+y&UJ!fMzk^Zh;8s8=A3gQhKUjGLyVB8nQ`~*g%##+_&snG%YyJR0X z;bed|P}|7a6BQE<0cF)Wix`i2W_$HgP+H5xN>B&TP5JR8QruqL*e;ZsPNK9q-%2{V zoQ`s`12VJ_*kARF>h2*EaDLYc2|&dIOgw<$P#z}%~>;ifiKX1rEiT$?8qDOAGQRbfQpwN}pJAW@UAR z1L_CVSm70+RL{twXA-zkI9t-cbi)6Q&*7xsxfw~UGk%4j>|07eM;bxnI*9TZMdB~vQ-#IvCpvPE ziPpZt>(zHX>BJ;63|HwPl|cDosnV#%QE3V6Q$^zqWngJH;o-*Cz1-fUv=74v#_6U_ z`y^>+BL?Ow7T!$sKJopvx;!7TSAT|qe|+wlqbbNHCX`m3@!YOYf#Jdusm|)UGd<3w zhs&4L=srA~fi3^23)r+`h8u$&avEAyQ19=V=z*OXfLmcS*n7M8G4VUpd32~riJavz z?D)Ixh|2r?dSqd{`Fl;qhU43z|%pAC|g4j0VlPHd)jk+Gj zcIGc=`1=uzHY*1y>Pv3SsPE_BWEa}`L7p>_=|K@fOO02%s7GH^7HT11T$MG1z<1Z86NAn8 zA~-(Cr#29QKDIt_UPL6ifo60OY>|PaamFP=K?s(c!yK=Qa)R4;{1}XciPI;JH6FdM zZ(=-GMI_z%DqKt(@r+3?RtRY%e>{>R(BTg7!~@)<+dlN6=_)HH z3DWSk11=w;jGPxDjaY#QMGUeVeJnx-*Tb*XAg&PIzKJrI*D06XUaD^o5;D1BCtmDZ zs|NeCKNm$<(_-5{9}{O^^X`gq*QS1`%lWHwD7q3^dxdq-11;%)L*e0&HO*jr70Gf? zC8Tos_ZuE&9r!@P%uS_=U}=FHj>{tZ!eBYDkF?3szgzo& zSj^?E>+dq2&%p0YitTi&S9hkl*>mH0t{kVL>{XmhZZZH_)$>%pq98sUy!efKS72ia zbuH|;;w59Fz-|tPlQ)6eIQQM+_%9qS`{Zzhb>0EvcbZ3cY13+5Pr^mRL&$w8C0m!=Kx3Wx`6T}rx=KIdQb zFps+>Vx|}_v0{_CIDAcayYh6(=JuF`_P`;*yT$T@f${>cZCMC6(CEP???tJeKlmY2 z`cWV7$v^y6O~%T`RFkozAywvFao~E9Ze6M|MSy8$pvPN`=W3{i~6}hLnuz_fc|dw8@j5~w{qp{`R$gyh+gUJfk4u4dMbbl zj+k-&KYoR(@!Rtg^$CxbB$WV?rjJ}DsyxSAD;$4+m>!zA09aK2VgF$#bX3^0ItcD${l)vN}=_L0U8bXbKA;KX`7CS zZcSNv=!(f=&J0tjgLt#*Ya3_0*5udKrw-FsOYLN7*;@B*EB04A`YGGbh+?-HJikj^j3Y1U7MG~Q%?U!fP zl$Q+FQ1ju>v~FJf_C?dNdei=E_t@@*rlY#;cBLr)QS1vo7*N3KksC}ses^tFA!o^kwE!V^Sg(28JYPkdyR>o z1K*NNnJ-ysI3+hIm)T-mtFQ~C)UP{f$qsxKiK4AV(wb7LX8yESgB3`l4RcZC|NdN) z$%^zwaBjSc^O{i~jj^AYU%~aU(-AI9Kr9~XlN-5XWv%xR`>)~Z9sD*;lc6R0km9Pe z-C_HyUc!TF+MWj=p7lP7{e$@IM{_&MRNW%%i?1e`a?vS^G*WlkaSDsx3#ANCzR!7L zW?ly<6Ej6jMC~d2GT`m+1tgLfPKCn9&*o@*`-EywZE^{n^?aRd2RRdBciOG*dUA1* zfknW0{%!OZyy+_SP%2y^)}N;Kps+=q01n;yP-#NPBJ<+qNhrOk~GmW5Mz;&ZdnC~?2YwvKaZzigh z)WpXf=Z`&=piU(O%@s%3I$q;^o^n`y*1O7b-m({`g3T=q!-mKcZtYHHOx{;tAl zS<^v-BC9oL>;;JfH!0Br&`l3h(p=faScOaZx$DORN4q_z97*B$M|YAq{oxJNv>*1P zgG@I@Rw4Rn-9{F+m!aX2px2UrIcDw`)Bd!HtXcOtwp4KZR!Z`(izm95TfWN~Vcic+ zE<5(-9W-~){_hF*b7W}O9??9PlQ##x1H?^;B(Y-6Ory+5-_8lmq_!Urff!B?hskb* z@&5KE9Str~=Z|XLARr$VM$iNtyQ@i-3MC!J2$D~+>^kZDHG@*iWIPnbkLeXVVBKRe z{24pA>0qT_vRu1Ezd0Te{APCg0+#Y9ozxx}tm5{I-ag+=wYFgRjyeKcBDYg@;Y6%a z2;GBiUWqRMa^@!AGwAMe`~xW)dqKgAi+|1uw=1Sx9pwPsK=_Ay#=AC$14u1b0?&!+ z%<&GPyT`9XQa7>ncH{kc6Z!^IqYvb1``@`9y9!qRxOp9@6se2RQ4OLqO<1HT7o3Lt z;3oOr^Gx(mLipt)&4?nv*tgwVm&!iC8*QdoXwEl`K|uhJ%-&eZN&f616H>C~9Lz@5jLmKJ86-kv79 z$g|kNYXC|O0 zekGK`IcCD$a#IGnE7$uws%x&o5B_2oNpI@(@*tqvaP5u~B(^75EFV!M86Wih`IEmB z!>6z+1siDwQq8?4CZs<9ojgp_n5{z@l(OT!JMUz)*lg}J$!-oxdOUaonKG#HBCO|a zbKaU-X!v5-<`y&?)q)Fo?4w7FK1R;hubP`c6Z1F{;?{f!1cZ}LV^WG16;Gwk{U$r8 z$vmF8UqnA3>?=P`to}?K(4?Bb4z)$P`F$o;C0OpSK;4MJIh1hFmvlfBvVtPYb51>r zVabEBhX{)fjP6@<9DOwsM(Vmf*jwOKfI^UOzUq0pG=Yqc_5kZ0PB>6>IPGSGw6BHS zB#B1cqw?e;!#YbnrT6vmnxSXSd;@c2%_o6SB9GOj>-Li2HfKmjYCrf4)N__SvTV!!brOeMc3fCIVc1>Y&rJ`Q z)k7B7dRP$xWXS!O{jaYilXoFqYXYPpk8<-}P-JM6-?kxRQs>BkEw$*<$~DEne6e+L zmV1yV=sK~nH#fKM{2U-ks9X5d;tMk=z3z5Fa0rd}+$N689dLDgG>w@$>9zIr|ABXJ z36bUd=|!3MFF(aUfbZ0?Gx}13?xJvNy^~x7$;a%Eo7BXQ_CRT@w7XU-&+PA#|3(^m zy|3Q${6S0G%qnk;^x{Q!ujBCU{JTLg9$J==)5n!HznVI|$ zVR<4vk9ofZ{9<0#t#qc@CLLt5P-0AdZ{De^_Yp6c@{GpB3U|U!Y2fuSSPU`m%swfh zCNkzmq!}J;2i?)?)00aAgMwHCe~;Sj8*W|RMWmxD8z6TZo_AF?MVd*x9%gf+WVtQV zNpV}NM|;}w>cwGPt3}Xi1hq+e1ZecYlLj0n{kyL5PC8@es9u#@D=$nW&oay>yvLj@ zzh~bVgxlxfRB?}n`_iI3&~Lj$FJE=V!}TQs#nC`ZP(DW*c(d_d5uICp-Tsp3=XW_Z zly1(e4`E!tEPDb31VVRqc7}kjY5#7U%}HBi7!MDRG$Qj85VS#Q#=S*^r7Jv`*C%Me zpP@UJno|2QIbj)g5>}tL7N2$6d))bV9ab5bh0Kt2L9zt{fG+twxi0a#(&B6iP)bxb zyzeIdVqmA@N5;zzw^gBSF!LZ>`{dzl{AqlEwLazydMvPkERw{P39!ThLHmKl4(<#0}sb|x!JsCL1_^V>F5HD`VVz(`ainck-Gg+?7-^ zFerAN_a$5=hyHA${jHFWi^Vub6JL*Pt41DTz3_C|on4}xo|&{sJ=l`^Z0eWQQ2~ zLsYOmQXJ1alU!dA5(bVwUln-@UG8CA1kDL9>kG{2O)8p>hE;wtYP3I)vi2j^3Z zK{6zyZ8j@A8~N%TGo0jIHPRDO7oq&A_C!Hyy0d4YusP!?-;LScBu%a_edCpHh*=mixjU7I%BIJlITjpLv=e zjLd^X3j(45t~e`eI^r-95veB@z_X@!^|oq`vc^ND*<*i+G};laNg5@g4G4(=HJ}l?o0n+ z(`pjE4{3Upuse=4z2rCJQeJ9M4EPpt?MkwvFT?f8BW{Xwkt#eV6+$aGXyofAJC-GSH+czI{SNW3QnjCbrS-R)vK98wJgE=JR z7$(E%Um*Z-^v*^#RO)P-y^rd6k?bvhOT2_(-N9WaEdwL1(vqKci60jM+MwQM=;FXiEUl`T zU1 z4DhRQX^@0ew#bm5z}~h75;I-cly#Qb<3p$TooF6 zNFmQbRuFJmbiNa3Jlxw0lD>=V>}>Hg2VhHzz#LX^^!HQM_c>in_6BkDe7oLycq`-d zM91oLQPy|;xk&KA3wga6NC$oa*|nima#LUw>2$+G^={iW@-11tF|RP7|B#Tp8CUne_3+}zG*cQ-j_Pw2O&<*)NlE`n0`Fu zu~8@W&t8iCN4I=tzhYZwp6`pUIr4PvqUnFUnUOpeax0S~jIaP?o$|m*s&5n!@N6cJijQUZ`i)80TdK|rNN!xaK;}d*eJ11_)F|KTm+`(BOp=@ ztlqb6;8|ZsJGLnU6BE+9M<6v&Ab+@Y ztnL0ZvYY2@Hdi^f75o#82=(D5uoig4n``sU90;RNK0!#JXJX`Tb(qmmpet`Y6 za3u9LiaRrg z(vOwXr9Oot{p*f&!%I?u^CmFBs4}$g7nWw8ER5pT4YQ9I6UW~Dx|zbDi1+(-GtDYS zU_)|R)TapC5Ij`K1hF_e2xvK8N<2tU)b4-2_T8Mo;ttu4Dy=@@>zi&MK8agLkHkik zo>EsTzrl&E8ze#dC{)g

^z>h5B_da&>j1RRFI)sa%j$TUa)psM zIdG}tinwx!cS;pqVZB8L1-;{!t+40!$OVjD1@s7L|1-97-_r~~JpIkHp#g8*UgqEd zaN(1XRUT&uPcNKJ*d(|n_j^_A7bVlal;6D|k!-M5M-4($mJGi8B`r1%;JimIFNAqvM0+=SVzqBn24k6B>T;l^{A7(wz zuW#ooNjQDQ38x&cP=&)r{t-w-NQ*5Mq=|mvm3aDROnrOMG&yO3rZoTJBvav~^oW#t zU70Vqb<4NVQ-=DL1XRZV!T0*%nz$OV^v0`jj*iK)foizp#zZ4UrpRJsfF7X7>QUz9 zyQhTQ8`NAke<{O3$PGgvO|gcygffl**+j_ZJu+G7bXOb$ZPFl$KIc1t#8naq$n8L- z;VbYo{-Nf-(D5gX#>-Gc@oRmnoa~7K8u7xjyDR9B`|-?G@e-48-r2)AJw5>J&mR!1 zp96F1z8dltSI+W%?xX~zqbklKYoFeIUu)=-$_Z}D6jLsI+7X!9%|LWG*^m_+zx^h4^a?z@h`w{4)HAEHzo16#E$TVozk0=y#`mS?>!7lh+&ygh@ct#UP z*}!AC46Q(afGO+if7xSNRj~G!e+oowv+`s#b826Fn&=Q=28`%P!aBFMvV6;i8U=IqLIp~zE?-DUgqjI=-d#=e_i zN6?>T`fSdZh@1z--a;DA+=o5?Yd#Q5CE0Tj&!ut2XwV!K8<@YMKpP2T?sX}8B&b|K z`l@}6C9lqRQLY}K!(GEG*!g`0y2+r6mYvK_bp1I8cn1qHpo%j9!d}SPctlH?B&HoF z509-0(5lue8!ig=rv=0RtaL!~1v++3;bs?_!i}G9)A!>4l0|D92tIeT105jt)s@V@Iv-W}(ey2`&mX8l zpjMzR)6ECxWtimDnJ0d;pG@X;=yd1eB=Akk0+38xFs20o$r}{d#DF39;);Ccfh@Eb zoOA*olgykxq$Ui35Cw&ko>5PDiBBx-LB0I?Rk^fls)GqNP+h|~(ceghS;zzw?YvSM zfhleS{AZPboE?_p*Zs644ddb*As*z`lwC6A{UL6Efyf%BcHFIPSWp=!n<+V?N1m2) zBcBGSN*vir5dohm-?MdYr<3@7?i(P9Ar>vwt$GdI+C`ZpCc|eW5G^3KukGwuvmODU zpg6~mCcEC!ccgpyJ%#E)L3j(M9)tdMm<&W><%>)rh2mTT!4|>32=Cv+2y}wa z)Y6j@9HZ+^OLB7PYaqJer(pbEb>k8)dtd8F-^u$wxCKjBhyu6D0ay1-o9-33u@&j09m@j8~>&79iwIsZ$mmad1AzhtECaRG62 z8%~0N1aNZ{17l)7eS#{rHZk}={!@!(J|^SNtmeIMYZa6u?06p#-vL7x%=K!6=hJb5 zSMoAfSbb2B^0Wmty`RRw@du}{vxCW>EUXY@8WteLe3t?Y->qBaiCKHvICtOM)g=LZ z9e;iV+Cr%)AcSPh`+*ic$4>9SdbJ!hhsCToRsup-;Z>yYM4@rd_5S^fMhOW~u zPQzHt>H#~qPVx-43fK{8+MT>Ohc4^}_%A3@2(+Sx%57kA{QkLTG-S!wZzfG8{A~&7 zlqB136$Th!+_qgW2BM(iKe})BMmvs*;2I_?<(9=~q^m9~&r|u!{6vV43cMj(IvPxU z!fpM4c8Z9NqFh`ULEpT0!uJ?+W?T*T5QG|AbO-0v6If!`QlmImTg^dO2Ro6?!e! zJ&<~9uiP2TId-FMFogq5A{2bAo1dMse_1|9=M>9Ws}loY1J>Hf^kq-~8=aReH$9(j z<|=i`zkoC&zrI@grW)XSv~NN@8ya;LuEAn!Z0>o5wxf&i%%B`8|J)%pOzRH=_|aB@ zKA@$quW0rafN)YId?5B=J=HgZ79&61Re;Y*d3uYA0x!~y?rx+T?#ih&ND$01m-x*v zFM;SH4EbPK+p}{K-*AFsFlZ|sO8=OQ97ODGocA?&AvQQG4H0`#!GC2Q1zyyBf#yis+5)EdHOV-uX`^IqyVIE*%(UJznjcAJ3}Td|;hio;t$w(9h0FcSK*p5MXo{K0MR9 zFG&)?Uz^{TTg9h~Y6Z8RjJG-kWBn-b4+YU~2xnQ(WfoQ+?VV#H*%3^1__2*=}+vn^T56DdODP0Jd;rp=Tu%rt{<7007C`OU> zKH&8dg>&rp$1EL7mVq&xJC_wN?VVn?Cn|+s-}=x)R#FVAO;0K1+a9joao=y88Nopw zi}z;8{vfa2anqFj;lw0ujie;)cBh9d#G{N_se)6Xj5BXLM9!JS3h1z!KK`K!7eu$~ zW!Y>{d=?8vrFduUyFWTt9X7Aohm2%lmm#fnCa-a1SqTh!W zqlg6xh-U?9(on@FmE01DWhpA!5LodckFPQGs8)CwnM=Vn1JYDJj20qlMED#EJiMFk zj+{|vx&v#fIaa>HyZo&DpC_l@*pxQ~V@mSwV#3~ie;H!vv=YR2DzO?)ne{TN@^zLq zSDXMwA2UI*nh5*frpwi!H|1HUwk&p%JO>Uw;jZ6sCuW3tV_caD(#oh7FuA=E>PzF@ zh{_yTGba`S>zTC7p+b=Mo(0G zy|ToP=ua2{F941&CWt$P#+enm*pqnl^l>ANE;!S$t~)_lNLr9M@k6xdvh`LQ^>>}P z4!Jakc?Z#OB#YI@#7UMx9Sq=S8sBoNHs}g2wJQSO$VBjSh~!c9+Clfm=VRZq?G6J^ zg9g3~mM5~}SGYC%mLraPYlSa7y3qFcI7|LdG^~@cV~&lEOpV)eW+^1;rQoF7gAyfF zW2QT$k^eQ?)~g>xYml_LqxlWvrqQ>Dcndw8tN}gEH;+o2r8LzYmnS0xqiK|96xM3o zAU~E1MifM&s0>U$9&YOopOYNXq#X6nrbT^G5Hmajs{5q#DiH!w*58*4VbtOuiwul0 zNefhI)o*R6Fio|^1-Gsj>l<~w`F4=t%Hi>vE@$6jRd8R*=g+e<7keKWW$o`6h;`Qz zX>3l4)RSorhaMALb~J%6unJwtqlSTlVxZ_w5w(8Yz?y^J^<&KKJ#&uz%OA`+IIB1F zIy93tobm4~!);@Pe=xQNmfqz|ay}i~=+FPkvX=baSj}pf)lzXlG^TRovuz7}ANJd` zZm^yW@@l13pw(#scI7yH=Q4%)4{-uj3NgPdFBJ^g=nDMqM%Hri`{6(jY<@I=Uk@vU zvGjx<%1rXlPQkR7+tm1kvrdKnDuY-}lx_{I(e>gw_@Aa#o%3=uGc9USI5B(*EBQJ8 zkYcUz`ZP9DR{!cwYNdLju(D9lT=1be)nYQUuT+jo?_7CGvUCid+VTnYDeYIzQN8F% zEl>YR-1Lh{yRpDF>DSI8Lim^@ciyd6weHf9<9#&Z>+G8s3;rq{)f`v!Y0Pd(pajsv zeg_{bMynIF-pOCivjB=dw<={q8dF$eZ05?sbsRIzsU!MpW2c}=LL9qc~#geKkL?h zyZUJ&fJ5>*acRGawC0mOf%eHiA&p}7(yc(2k3KJ4lN2V>`x8 zMD4cO=YSF+F{zDKfS9;?`p->jMB7&}F)2Q|`q{^BpM}aoq@LJb`D0)DqKXKBpjf)d zmUIddj1R4bR1qjg7X1pGZ=}aTfTjK6L=u)5wZzM^c%o^8iAKd#k1ckKM}ezfp90Mz@pEh&&%!1xi3u3{Mi}T2M;WamG&J;=qg?Jp z{txTSlc0r~Vt-ag`C!%&`+q2^6@=^HiJ+Bab30MZsIP4sle~f>fnQ5m=gwL)*Q)Pr zYsSvzrC6|Tvp>0$N3rnX$g9r$aNxGIZs{ovJ77Q#@7dsmFshi%8x%xa`aJ+kV1Fl0 zeQmPDg?KR{to13z8Y^#EqifJ+TAlDUfZzu|El!=X1FR#{mS_<84Ja3W!1+m%rp?pQioGPPIG84FmF!nyX3<=h|e-2=f6q7pJ z2st8C@W~q9zg3Vj6Y!{aw&~#=+dUU_z1+VY>}Bs9#8{8IR8+b|mDd;PM^j^J(Q+eb zlx#Qc^a$p%2vO~D)Bs@cmbYudl@`Pix_kOw2#;$o+l5-got9ZZ2c~p0KR$TdAHDmD zoinkMBfsEnHzQ~ADIZ1g~GhN0H%f8tI$t{^)E0ZkOB|iinmi+LNqND02FQ@*Z zPf*tglJ6usn_ri4XIj$LY#q(aQi`2Ae_K(RgYPz}9pDlz9E0QXE5%LjTm>cznE5SV z=>RvFshC9(z@e#gaG3IaTqjGiH-*`pBTib_yzwyFDzCNduZysGr_MXh?2|}Rfnt`m zy?lv_V^d0dMH3-;>d;4Y#@&m3DhOFBU%}~@V|yCA%?>rjr?y$~nr}S`{T;mZARL2@ zk4RQ^4%3H-0?MimE85N8{~(2VbvyXdk7(I-ccg~2`8Lz*FxKEJf@n`f@3^TQneKOg zcA|@Meb*w4Xk72d`{G;1ofptW2MZ}SeGh+EyArPt&o3$bY9dr|;8k^?vpTEe+J~4i ze){sA*n^SFnxqSfnf7vtX(7rg{efz8JWXrk->UbvUSTfYZ^CuKg||UBg2~W{8@@OZ ziZ6`F`!KQbKbbIzi6za2pPU0OuA}~4;htiq=k)9H29s3>p6YT>6TFv^>7picHwAd@ zpqTZF+AW`ku`UiA*I7cJB(8R1AJk1=r|cgWFVMcDbB>A4H&(B01}KrSgz*2Gm?LTi zgO#9c?~g9)q+F%nFy?PIb$+C7y9=mR3=fr&d3F?(;iLsB><*3j4fcj;kQZ z%ezlA!yZ2IX_{=8UX|qau5RBH10=JrDkM^J>I8J^T`rcuQv(~EKk_r){g&Xrsd{A4 zT(Xm!mW1?#iLX^}g*IADCpa(_^Au%zFg)jHf*4%k3_R3I{(j)dqDGm22cJ@MysuQZ zC6^MCK@K+`N`E2L*F<2mRqtQj9V)4LLlF^bt&jS!6jB~i>a;Sk*lMiaFYug&thQsj zB?Kdgkob@R>}IA0+Knd#$BR!G!jC%)+z-FhYHObod@o4rU6Z?sz%rimKiN*>Ly3U2 zLh|7A)pC?ALnvjQq?W>NFJaj^-xHW|5O*1lrT3{K&w<(dn~T;!T8AvB52HeE%jp zWD58}KX6V5O7Sa~E9eyYW7keUGg=hC`|}NWM@+YJAH^j}9BL^ssRsPfF@~79J)*h` zrsPhK-de14EV7+%!~@W*kZz--Iz{SuRj)!#Bv@6#ve2L<8^-I`AKJ~?HZPZp8*2~G z8(wV9VfxHE(P{FlQ*?A+5Cslzu{${oRPYGdnYPzN&&J4p=Yx!^FTM;pX?235h@jj? zf(lD8R;~5t$1IFL+M*!{V(b}7V)OmJo6AUy2QqgFPm}a8{taq;X2>kggly_`k2iL$ z8{|z*lre~MP`B_-0`AfSX23P^X?2yJ$+XmjQ@F=x=}G9sV6 ztk4+Quf=_z5+<vm8i4%7vyGy0zg$A z)Qg?Xc>+j?2|z9Ogv6!a|FOXA`6JK~W=RFTV3dX{e@~Aq)`oXvBqbI5VQ=89V2%1m zzh{=OE#WpnmHhH|uI&KJ>UKewhSTlp(oFwQLM0+W(!Aibca8Ac{EM}6c!8sJ4;HE< zMjKt8sD}md8&tSnibp!IOe33ZD4H-(UV6iKUW>EE=U%AI^Do=Pv0)PQSnX!zfqd}p zI6@L;I|vIF^W94SRIhW`E@>SXOGPY@JdiSCT8qo+FRg=_RCO|@ws=P$m?>BJnJ*DK zI6}@#&nMFb8XjmubpIC7`b!yN&rUcm{<(um+MFNldR@HOck3dr&H;ngz?6Ybt>nkN zf42&;jt_{I`-k+IUFw7LE=72^$Pw6Ts2z&aY)_tep$G9A*}<@eYZW+$OG!fseuMXW za@p^fO*4^L?}2wC8OyE!8Ub(uBZ{3nS4E}nxn)-#$Z{C&J(%JEjT(t?(vSQx~S6z z87vt$at=^CXmr?7?u;6%O2da&B;+@Ys@OHD|J}#1GsT4URY%Yb$yv&;!r-8YJu*_; zub=I*Khc`Vt{1&*dfE4a)nFW8cNXEM`mShau!nhWX~R5P;sc)@>4aNt<ykd4^ehZxCI$@b*~(62`rEPFM><++tKEJF zrZ-?NQ$5{NbLz^t4e$6Sr=Ntop^<1o`0t#@Gu5f&#FtZ7Rn2HFPG`PiAvx+C>1aP= zd?I`CYw71~xyhe+=`5D{Ro7e8+|>`-d7!#|udxtZJ2;uk=W)rsKA$ABqB_ffXvW^r zT$0Eos?&EVMaP7XY!m$9da-{6p16labRh4Di*;s9%g=q6^W3w2GRS5;Xz0IK?l{JH z-|5q`*^y=wkg{k(pWf1VlOEA7v1dpVN}B7<)}&bd(rBDx!^sWrbo(<{M5W0TGB_I@ z@dCJ5Z5aA@n%*+RtmZI6s0;-b!VrzWVY;F{~b=NWUQi1ZR=GN(T zAnI-BR!mA6vCsj+%c#8NBELI|c9aYfBD!6F>gfcH5OS8jq%O*` z<>^cYU)bNq$EnZ!F5mhxO!B->xKkGYv=mEyU?kH1QyRPSacB z@{|#u-6QExlH+luFnBt}OkVy*INxD+Rh(O=#XoNLkV~qwZ*M5rWfOu!O6J5JG*thbDCKpOPLok;4JWV&W**9erSD|vBiC##n~W@^(qAq)v&|yDzQ|4aR>N7Qh9k@X z0T1_{^$_6qme`huv zc42lnKh}1Y9mCzqB#Whf(dtn(fCK=M2f$@URphJK&i$rxH}DnEgsaBP(+6f6KK71( zR?CvYq$xzDAo|Xo8N!7M<(U-I2Bll*^?dt)3v1aeZl@H};mlxR;3^fLb zsQRBjUd|NSWpYZPWqSRte>*D*0ExE5mBOBxLRHwGN;_IZhl@v+2K{Yq4c^iP@C_zt z+<5I|G=grpAz+hOjIfozABPwLn19GQ{6!V}1P5(iNff>leb`+?a$ZC&+7oKD-y3wj z4Wk>%go=Utc(Jxz834tz=#h(HBS0AW`S(F1bq|$c zRA@_1C`US%9tHSU1-iiF_6>u!#SA}g>NIV9m#GB}_s)a4R8U&i%wUZ#eyhpzpDxzq zzrH*t18@?{5#%;Dz`O$I}hF$^0tOV#vi6Z-Z=5jOPJ$K&%Z!WkSPi2xK)$uYM^+_^{d74)fCSkh203a*r6d?Gy5>xcS) ziOp1+K6i_b?}V4d?x!Y(4&P8upO#%ydqRq3r`dC?5E`$G8v@i!1P!l$s74^ENc^bobbiX;#X4NuVWu~`)+FA?gkzdy-Ha&% z-#K2)X)jU%O>|y&-6i>0TuRVoI<`}FFZdEh53}K>GG>@nqbiO`JQ8r~_wNtScNj;& z_|U_e!v&A0zoe!wqssfCI-_;qwdp}F-TJnJurwfE8QHD4%5Quak1+Ooi!Wg5RIe=j zl|8(TM0VTjkf#S#pcw@sv)0YZS8{4OkH-%aGNA833 zniAh_n_@zU!y6Gc@j|Mb{4tjj}T)EgD%ANGb%Hs?_N5Id-J*&P|N zo%g7z>e(ahjfMkpAcLB6AKh7Q`76N!tdSMquSI&5#DaZ5c-^;w?%&0OPU#-qKFZZ* z-z06vo&Jbb)dkJ_#;@7eNR;*QkzxY{7meX3(K|dw`&sI}FNatZ;)Exn9mep#4e~Ry z;;WgQ`wO%_->=+V8R6S41^<2z6Hj`3%Gv{?){-_RbSe2(de zydf?g=erJE#{V6C-nwC5K3_1-EBtoTM;lV741u40f?VqVfYRpQdFI50jd1Qne@Fbn zy&h}7HZKWml)L#Mn~JqrEsFvM$(TYAgD)aGwp4CeGP@V)T%2OUio^Kc8qn?NF-+rjH(G39RXvcx`{C zgZec+SRvyXOw>|s>WGxN`LC`iiH5?KpA!2Zl!^1JQxgU|?vWa-Dk{-WnJBwT!DdVg z-V*rLhn=sLA|e#w_m%{>s+q+GciX~9u5Dy8US?Zbee@DvS$tna$@^D`RU4&|uW{eU zZkeajVy>V_woVq%+m%v~A|V%G+RjJb^+SUUw~fO!7B+T4VjWd{MyJl&cc#TV`c>%n z>%K>I#6St&CA7H=Q{S#W9@2P_> z^%BbhZvv~hEmk4ea_tV@3>z5Cb< zChirmb{U_KDa%9=%(Ce`60?~YtK**>7B0|_AsTMI+_%CHD%!#s-HWy|T7oOJrSnB# zT8OJ@Pl`>CnbT@!Y$fdopy72{L%=cwl7xA;UXbW=tjaphU3OQ`w70}vs!?vRPvUfK zo3WaYk8pg|9~S9($jztR^LbZE%S6Za$4pBS_7RSq@7d@|jTEi1G2_3*V%eG|h+2Ml zO0$04zOF=NrlXj2dhr4#1F2k)2p{&@-u;H;M;(vK6#Z-j*4l5xFpU>Q#1KAq@4E0q=wA?>Q0ae}HT zbBJHjNBs37S>9+^e!8DWRaStP?7&Muxjy@(ZeVfq&hf?ZJ`$h*jDaJKZRUv^cF{y5 zVfPgA$AP4C$rFZM%69Pb)*bnY*Gfh*6+8K#6louBie3xy)BgQW(h8+YdfiD0{Et9` z@Wxea*G-7c?yD=o_B`VoHm8;yQf~2eppiLUwQzkTh!~?qo*^L!wcy=gn=SL2r+Jk@ zdkhk;?*8TvTIBwZE*^RNZ>a|M-`GfjH87^&S~zaUQ$^->UVtq~F+y0+>*#HT?fB5zlTd^W$EBp3RKK(mQ(~Dc1>j1C9a&M|hl@Usk2$`e z?RED2-S4HH<7YP#@ZRDwl<|!cgJNd75Xt(*6-m&&U58!`E>or1$g(X_24Q_-u~7YKU3{i1trc&Motv*$vtw;Bfn}k zs$VqW%_WW7HQ#gH6N5#%Dh8k88S|E3tO;26d8aPus-A7k+aJsZR0+Jl4T#0zAH9H! z&E2Bw?N>bkeT0~W{Z1M&)qL1DBGUz@UciIW_NH&cZ|ZHDgAx{!uL5%`;f*^~$9#X{ z5vYL}ZTOd>q$*-I|E+y~0ZL=rR3sP#2SKuh{sZu)5~KllK}w(m__KyOeRgeblza5N zl^|@n(UVS`KibZ8JBeI|e#gw6$U%{&yK9a#n^BvKcJjK5`*ih(Y0D_?E825rAKssJ4KHybQ);OSM#=cMdYj5QdKLVzM!b}rz^0A;!IJl1 zqxOeJm`9&qcv>h)7sb|Rpt^mzWP%TqjCt^@mErg2YO*ys_SSt+9>_;(GhvnW0)Mgn zOkpEdy7SNyLWtgfRAi$F@%aIURPbouoE@7-L=)r%dtv1X6zi07&#sVjH1M>=6ufQV z(J*o<_yPEIMbtAFrN#?!sVGE%Q2mBJ6eaMduWq+Zd1fv&DB<36*J}F#;^iuc4#>YA zScL@p>32YeM)39ENR9^R#jBX5#)LM0HmjcZ`%dQxij+oG?V;V9?z0ggvT_OiSua`w zvZTMJ*RNq3iS$%UesW!r*p(v#m&kTaqIS$Z>kNvRj}MGvcHUzUg#?)}uvDd#bKLKJeAS|FEFiyq zGn*(u-ZWM3%AuoK(lM4F)93VEl~y?bRuSmCTca>G&UeV`-MOUr?)aYk87k>;2*>6L zLoFwVm0n8Sz0dZNX4iW#$i@+p?eTDOlErwZafA9GTJL>3ou;Hic~R>%W&-f|ERE3p z--vwAKbu&%?~-bC-B>6-DK-g+H1WSzHN3c~OOpu_ng7FZr@VZo$}qF57f=*}f%+4D z8MNL=p_`X}YN1SrzvDf!_`ii|Z`1XhCa?w3?z2HZAMaU)6irt5jf@n? z;op7jfh4BHUrAY}QCe0@^?8JOW`DrthD?0<6D7b~;h-&hIC;%(hm2#uvgScI`TSP` zU$Y6@Lo{7H(q7_pk*=}hx4i^W@3Lr9+NvqaAj~*yWIOuqEHf0L=VwAz&!gc@oksrn zae#L?N-!-Lq`u{rwd1Ye`8kd%?~7v@UszwrkgxPld-#!r~ny7da)j{;8f%TJ{8RU z8=ASx`J;*SsRohW%5ohGL5G-@8VtwtCKC#HK-q}iVV!n`L*nRNA6~F#0;wcXnc=Op zoNB9V{C>gqtyeEvz<~~fGAoaQquKzYYyeSxrXQ+?=axkm{9MF%F3eNRL0t>+>4j=h znqAI$$6brsI|j+#38fymNtjD_k_{t^j0xH;$J%pO#1FmOx9;_bfGPKi*<(cYcwOW- zv5T@e#Ah*v#^o~(5n&tv@^qV{3Jm*YzjPmv!J$4g<_ZdmS{=PM`SKOKQY1buG2b9L z)1VZ*;gC3m1A+fLNzoF$!`vr8ZUitg>$Cv?8pO|M@fdJhghIxBgpRD9aO$AgJbSN) zy>*e1$d9VXkhoy7KY(=#-evx2*V|m|3I&M-gNBPgW1puZ=MKxL+t2>D@^sPI7Sf$X9!;k9m zhvbu%Z%>lN%1CT9rY<5~w{o3Y{_dnm6#-WE$0H7A@9}OT;-@=mE|RK9xNo?JQ-bKb z^R{-m>>PzO$4ZpI*y^X8raHyQ-Yy;zg+g3UtLY54YEFl~+VU5`j#}IZS_JRw@jU4I zxd!u5jAzqIGkbKUDnXSSnGOjmCF*E57pJTDm&3_TSKno-ZFb%}nV6Kwo$cbV3{fqU z5#j^Ww_0MCOGTvyJQnut^wS558oHZMRZ8Y2Bvb4MoC+YA5P4jw_mpiGQ0Z&gRZSC! z`(!#h;O)0IHb}u5Om`=|9hmo`RC7VsUq}14m;a%R>QX!=WJ|J{V#>bu;VE(T*Q(R z&pnx6*3qh?Rf0Jkz5!Bl(-PDev!QLzZyHL?c>d_U|)m#*TE0Yf!l%<(1E(dyVV+XE{VP7?Skf97)YG zv6hYPMsurST5;D_P0J+?y~!b7B^@;e@w3f9kBeNt%7EI%=-WZ4aG4+_b`jd_WDoJk zsB#bHTj|iC&xA64zYb=&G%f`g8?xbEW4_;b7Pv2Tl?T!y1BG-JolO&%_b5-=IFE)> zI>(s|iJPeDh;9vrp<-AW=ScnVZ=0!6(7g}b4qx&!+6Z0$nuIco-BH6fms(WLzt5Ez zi`wLoA!Qx@`odfw;5sl!WK*t_0U5$`9F1Pogv$YP^8pY3jXiQYwJWe%61YfC6$82@h z?6#`U0Ira-`}YqQ^To zc$6wA!F6*4>lhNEFE=gC7m;jF?3VP1Hs9P3;3tKK1>2yrF>y-epl0v5-LGrWyB?ve z%^#2*7E`*rkRCXO-Sv>>M$O+5zIsEN6@npe9E^d^srbfb&OJ7e=!hczW;yr58?&cR z>Ost!pc2ER0YN-j^Y(V6!T=qsFP0tF+I170gJ$xI-z$3o4%b~OU4mZE0V1?;G-83r z_Puw^qcH(xYKq7>>JozF7-Sd&m@w+?BIXfSdTpDT|!pA4x z5L{8Hv78yVE98&gE!IJ!f1_0|gZHZ#SPEE;)bye-IF0P|X7ks56(Hc{P!y^cowv0Y zDbM1f1m&P`>LaBKp_DRrZ5`2)=j%BYbA*7jO6%M&p?T7LCi0Wxb#e!^?CIql{(%`?p3_t#;#NJ3~asGagc`^3=DMhBbJGi8&hONg`ID+Di z2tAO920JsJ7e}{?tBX3}`@#C+J^2J@;acQ!2sx7#PUWkZL-ie5gHrdWU6b1$Sz8&H z*MKBL1jv&O2bwy*_1i{3rm}(?DwTbYwQhA}gZ=R=pP@X4!7aiEs@s!gXT@C)?P6e` zCqJ&pB)r8vCb_GsT+cagu3Y{cAi9>btwqr7wDX)IMrBL+jz-iv#+3Nir!WHG6<^<3-O>lZ~e$sXzS%Cq^418_@~fJCbz&Dz<> zSiP?d!4V(`@H(`IkNW9Zz>1~btQXg?J_R{RFg5@RTo(Muw=*R}SLSrNr*i=L@nx7b zI6HNn@wo(|JGh}}vKVY>H;Z=h;}CdrT%2TL7N3=4w9E7z1(QE}+{fW#!R{FPT@pnH z=^u{v#M}&A&nLczK9q%Q&NY)WVA7*9H9E%1ij&Oi=qlgH>iJA{=AZ4rbc??YyNFXLlty6U4%V$tXM=*+DcNlz*({4jk zwp?7cF`0BIXrSFavc|q9=yCZwz+11qp%Ah#%J6jnI0Tjd4uLn?TBbC)cQYMi;aN1% zdD8()7oNdA_Y|$)S){&uQ#@;~3EfKy!b61EKvmzWXTjgejKsfx901f<$H@VD_{y7~ zip~IzuwmZig@!)?zV9bcmvcybS#AK@n(iUC=g)V`R+=ZNc!9rZ=S&7uun#O&LYJ#K z$Jv3HRW>W%12Oe;1Y*4z5h0bv!;}TbUJBrKu(afN=cm;vtV-$ZAl`x_etQ*?F+IBQ z^2lzpFPFQoQY3}1VWZM8OvNJBKR&a$5=Ei-<~W9HQwPizwfl!G?#>f5@-a5ik!?IF zQvtIdvW-g4+5*c`sT(HXi{JoM^8y(xK18EAsz&3X6YSje8`_a6YHs1-UG0nxLqiN+ znq&LVpSy-qvm34MUH*4`E9uSDTLHQ15iorioQV?2GXP09{r7Q4lPs0|Fj&?8!c-XK zd@}jESgUy0ojsYReP-Mzh`D?0MtRL9;|uy}B4?8q10r9BfoxCsh}hiXWAB~PQ=~v* zZ5+0M!13S7mi|mkf8spnAf}}H6R-9Q`D=srsr}PeHYP5WyTV6I_@yJ#5qXHa^(P~o zlaq1r>shjw?7q~QsXY>Y%iSNkcoG;E;69n_)hw}mt(4(3>5F6a{QoWXHk?a=qm&d2 zuadD7p*tkGWMxJDEs_<+WF$Et+f{syykNC;_Fy{_UkaPLJtErgBxk%YefY99{(afh zA-y07T^-18Z1|r<^+i5WY3sRGnHQ5n^F&hNpj&N}^MdI=4%D^b`Q`@k6o`Pl4I&__D=)U+AQ)n@ys)v@ zh{=S8A3^M~wEJ{(Tl!iGcxp{{sn&Mnb+f_S>C36la!`h=vAP%C4K=hyp`nOr<^z)I z>AuHDlW)HoEiPOW_CJdmg;_Ea1H&zQw+1qBQld zXSFDfV9*V-Y0w{!#n_V@hVv8dM$TP3SE+n;;+G*VBQzFW5dSf^+Vf1YmDm{i{0D_9 zo8+j>MRIbR5qih?4d4pO(#i+sVf(k8VlL zFq>YV?+|U@(Z8~Fqc8G`Ln1u5<=uh(evAq-H4((fHf?Z6-VVdOuKlgDke7@zlQ}M!NwT3{R?zri-y~BBiS?M zRyo{oXfp@fGECh)E;cy0kp3Y7@%t=OYFsDK*G$9^qrfvMyeyT9oo1zHHv1chY61Q- zQXMXi%2Oog9wbcrXN7+3dng-I@|x6Q1i3Wrs$Tz z^Zo=qrJ!J@AaA^D|K`mfa7yPO%R^Jf5)Z}ZbK%-vTk+`8G^(`V9jnu(+_3p;6y`U( zAZVWH!0cZxd}gEqgzbcU)jmM|Zi)+_%aIgisXk|~J#jWcw1?%T8&SzURXjsc?`OC1 z8pUc8FDb=;IKlua%CQD?bJ}GQ?6%mkVssu1)lcyV1*pJT6WL4ofdqgW@(Z~K&pbg$ z@WfFKf4J79_nyF+R=msg=7O2v-CBpoUHEj>1&sNK966_z3!;a~GOFXqKNFx;ru-g5 zZ|q4Dsoyr!3+EwT@yR)!Y_D}66aIr|`1$LkkCa?@V8sxmooUI!3rORs6Gv{-U3bLK zdR)jd&%;oAC|B3}nX@om+5^fgyVl_nkb3liHl`d?a213hmF^M0yRCEfa#hVuzMm~bIac5gKKFvBX zgcalNmVsKV@4Mldqg{t2Sf3gh9UmbKX$@1XtT=}s=`*Qg0GZj;QTL@MK>nN>)1=H+(h#OUy{3v*gFPtR1c~o=BX5+}~@eP&-#~7CVlNo0t}@e=G!Z zy!Nk8{?OO73zr<`6@}}C!4~J8TxgIDjOpY;0V{U&%^fNOCO2@3wmQVi%w@`mfk|zJ zm>Ks8^5Nqu)RydUjPO^Sm@e47rEW)H;ofeG;ENqU>BW^W2adC*L+ld{b_DA;W}!#UVa;3c~XN@cwVCLgrAoJhsLODJYh@wOYapV z{mUArXx|#B&7Ns6}cw^0xC{V4^&TL?`o? zw74^X9>6##v}=%gF#ar4e)mONY^8+1aHj(f31<1oBa2HLRODmj14!Dj7IT<+$o-wS zQTRZN_ulXMcZxf>;Pq{BH9xUR@PJFajyFwwhMeT63OtY_AmHspSmO5wR`bS(oHlqTBAeiAC2&PD( zl}?KcB5>RZ;fM4fmCi|#@?nL^zSsVXP&C1vR% zK_RIjB8l&?TOj?1IT3%~@TIDHQ}>83)9K+-#deN@B|P(IXa_VqnMpSSnVp^I(81HMn9kO(R20tJEH(&>(QrMd$b#u9>9 z3XBK-H|^1GKkDA7MIZ1~2;Mt3>R~2)127`gkD`FIHv+sAw;e^n6r`zFTlh|Uj240d;q4SMzFCYk zm{vWQ1%HkS1>I%^Wfa<2O0jhwMxW~d$0N~)6*Hj*F^pXjp>)dCV)4ADAvKxyR73ZI z897bh-8@qRo>ms|K%TmWhhAg}(mr+FK~Vkx{@s0x-a#H0iDJa2v}pHs>d29v(uGYU z4$gHpmY&Iy=4x7Tu%ANod1SkAzhGpfe0&z6GkOAOQ@nehMWWLQ4Cy~+OHdr1_>9d2 z%{}{yRPO)P1wBXVFrh{}qg0wX+1%K;+IZW2Lk<8bK`^lYk;J?J%X{7=_|gYTBubd4 zbJHK3iNh);C-N&~VFo^&yox!8$UB)hajt&eKY=W%3=_?t67XfM?ksh(a z(pCC~Pp1Ni)#EzLmrdVw6Q`DA69QQAw>^riZgIdooc*y%o?nk+`WBG8UxBQ05%R5l z#L^Jl{*wBst)EiIBO>y9^UF51SbTx3n_au9suaV@D{cHvi3mUK)H!or+tOiYra~WW z?3hBT-q)x5xp5Rj8cM;CniuhNe*S7&S3wl2n^D)Ci7bCoIz(ys{3{UK(cc!yBcH_u zlgh7o$LKyXtph=PU{-tI&0rX)l8>8~YRgZ#h8KC_;HPG&F8yUD3~T)1{Z%0|f(IV4 z8_EC{Xv%TP+>ShVQIV+ajdq0v_BEYRFgyGraAV;Z?_wDIP1=+2TSajSr(3qQY#S8e zQfy0X_@Y#3f^$DVEcTP`wD6?gCO>v6N{%A_O>0Ta9qQ4CKA#&|m_=0BJsoqH?|0k& zvt<(bTOO@(aDw;_GVCiY@Sh3QnnW9WAlIxxGQ+Xw0Ai~n(fMvZM*10v&utd=bQk&Y*py4HJ?mp9(FK)TvSQ2}3m@xRweq-a%C@hA zUTYwgux|13B3tXhajfsoJTtZ$#Ws@CK7A9q85^~QrKgO$)8v@@(box1X!%&Ew+aJS zZ|DCoIx^zFq#&9k&i6n_G>0DakVym8&qjf6$^hK8Xg|h8JQyB=O z~{!hq3d?ka3a^}dTWjmX=;k28Dz*j%!5M*8{17Uh&+-CX_=Y$3<4VO) zuG$eNtUSJl@jqyP5tz{-I+&T$9oS&Qv-sj|qP9qdFaJ-gxB(AnSTU1oss2!aTo$UKVylKzi8cdQTDMn-a>ov|3mChUw_2o9Pp|j`@)s-)4Ks?WK)y|4If`;{=zg?HhU|fD#{*N*=JPY6 z|CsGJ92>+<{2@=0+^Q#_Tt0I;`)4{10(--$(^#aTvHwi+9MFj5XM*{K3|PGYb@&5N zK3&gQ_=wBP4>YlGx%fzQldCmG{s1s>O1=#*FZIlgPBbn=eYZ1keQ1zdCf-s*;83=0 zfmV-v!?|G$4pf0nr~51%IlV_hVi&<^gTNChc2m9Bv4wJdHG)453xh@LO1W~BzsGGQ zit%;|h_5^X-Ms@*vRU9eC%m5Nc?YIs%k-Rh zVx2;>kR3xUL6(;;I1^V^dyM8HGwIE;I{@Dgj4L&5tk)usFkX^GW#LCB!)4UV~aIz zm4pn#wLRsDiVNVZ2Rex)G|NN|e(+ty_R~1>3RftMn2|I<*+ai=eYDTBv$?7cm|}&3 zc4yb04L($Zd0rJi>mTzYxdyw!OhP^xi!3%`Wg67mbKc=Gt;CPV(fMf=8&5*x-MiTFk%KGkV2Rr+dWem;U@trS`h5U!uCxPob z8(q$%O9;_g35}7Fj+~-xC3fEF1kE3Qy{bcsn_xQU1pm@uUW-9jW@~i!q*|~KI_Z41 z+{S)w%6Ou$|F`V9TxBV71KtP<5$bCv^$B4fha1khbq8X3$1LlBnT61D#HWgYnx1@~ zIJ@2G?_-5=*Uz5ebrC|qZ0^Q6+pdcj!8btM`Mn|SG!@Ro4-RP@e_B`0+X;*0&R275 z_@uduyHvwM!10Tx9etQ;lz=qBQm`mGA-?N=$YQqJ*&Tfp2B9(T62Vf@ zZm)dPw5&L)1^rabc{*J~^BWsfnul88qq9g?23w--#%ySba3P=Xz#`vM2K6G6Vx%N2 z_EG?cpmhZIbZltEQa_zzUxb%JkdT#uZwm7?crHTp@FR2ewgOB7&Z@ub)Ujx8_GNej`ZD1y6^jyk}7s>wm8| z>99J8kX`yLW!-oPq0}p4s*}WP{`{NgU-?U_wM;>_}1pkR&tH+HWhIh>;;H}w8{z-MN(tLqq-#~ z7S<;Zc~ zP(Oq($CzB`hm|Oqu!-NCNn*y&VgHjsd6j?#T2guH^^64+*Doc}PFsb`*vj?olMHrt z)Yr8u0|?dat2?B;pq|GMb1scq#A_w?DOrn-A;ckrqwAROwMAc~Fc8+71q$kb(P`he zZNf{2Jns6}w0N(yPZkVFyS6!KbYY@1@tF6kAD3ynPCeYFs`xI*VCSe`)>!+@>PYi) z#7HP!+xPpd#Ze2ptPJ{8O2P#_4eHsV5o+iBD5h+!Q-AtHCy#NfVxjzi74p@+6hW+Z zu`CrQGZSWG_q?vhu@?=tE-TCU&73=*`UYe@i1$&oQ*nrW%{$qtI`ziWh{C{92`8=8Qk-RK)Sj(X6*xw{Lz zYZ29o4xz}ukD8zh#6iC77tq?g!ju$W@Lk}xdL;|}M86)KT#!4OB>wKwdX65s>G<2hG z4pOlGw@xY8`fJVi9x1=}C#fi%FVQ4&$Qj&f>)vhFch-pugf;v_Ojw`qv}~@?Nog+p z`vUI;!<((e?%nTy(%{u9>vz?W1WkH*sCHCs+}zn+r`>PX$Po2pB#@5hybdMDiVX;f zN1sDKbWFTMVzs4e`Y81f0@s6pV{hY0{z+_j9_##sG`T~^;ZB(f3C~%1 zZdJ*X;b+@=hw^WT4bj_}VN0hTH3pG0<$9lI98a_8=a9#aW7i6Cs?>o4#y3)5F!9J= z2lT&I!f1gW&bRB+%sc=q39O$0hW1awwv3)$9?$#pvkL)|l9Ofs$t-_GBb*SmC>VFqVF z>!>04rhHDg(($UCkTFt+&rqm(*js{47C+r7pyuhJBZ!!3jw*tU;#r}Er(RTtXiWvr z?7B&Zy>jCz;~Nyfbcc{L^zR+|Z0RDg9p8($=w7@5aiTEjg{q@`k+!h<7Wb`jHD{yo z%Yg&u+;(}Ti*5{wN*MKD6&_oOoT-m{eBtAqs?+#8$B(L8>{=7l<4L&ZP*#}VZ z5vT&GKKCr2E3L++6(7LbSD3O#CNJ9Gl_G6BlC&D-T0UH7DiDbq?`~L^9ti8-1;^aWrAdrxY_yuAv zqhyIsn?aWG5J(lpD2yOo9ju+RK5mdk>~93yC;10 zOuLhZ6*1^$?~5t%SK*S7Txc=Y(F&^_)oPKvah<+ZdEp^@*cK;f|2bXRbBoiAE0Bz~@_gi6^sRX!5coo1 zCd8d%(dc70>bK~pUh-*Lq1EW3gf)Irdnb1*T;c<-n^GU2_rB;Gyhos(!$V%I$IB+Y z35wyp+1D}>i2eFII~k~FSp4&XNtGaA(BB~70jY;7Df(ysz<8(J6D8uV=zyo;^5;nG zEiAt(Y3ajerHV$PXXThWt66#*Fh*EF)Vg_2wTxhZP1d>0rDQabaVYcWPcP6XP*$Q} zp_=@}bCm#3vr#?pJpicpMGf~m|Eq(mUcc{TLj@va$-vLf=p`M3SC>;nQ;h7k7Eisu zQ}|%8=*AlM1x0><@{*djlm8WnYr3H8f=WJ)gnb%eG`Ml=Kiv7&@ar#M{QjuW0WaVY zsI79+JxRZ(as=P$Ct6>?#!5f~>#+Em(Ar|&Qh@-iX%M{sJ}Y{zDf5IG_68_6+33wm zyLvep5Cida&9y&Kt}_IR&*HwkkZYWO09`G^vv0TkFNQ}5J{H9j(}+$;rz{G*t;3i@ zlcCSEr#YW=R?+?*(rwD8aIwdDb5*Wc)h{70N@yAEmk0}sXTlduo%X}_j_^+ZMH6Ye z0AFwjx5y~{RjvK$7gvk=9UW=r5eVjL&-Ta{o|dOO_+r0Ei#!!{r>$A0R$$zr9c3`p%Q-iJGg#8e}C)peKJLyBW2n6zctw@OIn<= zo)uoNeenjb97GxW}iZcGFwNeSLrLHZp$Z_1cD3O*b5?F2(`y8cjNexz{jMROVpn&a@L@rUx`@ z1l{)$t=uXwMcsC9jG+Dy3w;DTWhlCCCW8?Vt)pueM#+5ZR83~|p#Q-lt@hKg*%l?B znc_DiOAW1I5kIn`Wo7(zanM7{{Q#ebP#7%|0+s>_NQuaR(1%`S*rO!cQ;YD>GfU>- zmBE$$%j8%9k@a|jY#VC=c#No{zcwmKd$t|av zKZr#G3&w|2VOUv6bQ1^MO%d^@b9sT|tUfOGVqu*3gj|%re;JBxqY|L+_2PGLkO9q3 z;3>Pmz{;d5g3D2g-_~|BwxJ4a|9mXnx;_jVD7O1Qn!Ylu>Gu7b&XLlcV$hu<1(XsH zmF|-6ZX~2d>68=+rJK>xC0zq<96fsE_W$DVd0r|nI1YC0y3X^Hl1wAK^V^m?*}`l3 zh>tY4g=Cxhy*kF1?v6HZ1_HjG;y+u4erzA{o#60YDK!>-T9Pr)oiTF4f#_FVUjGq0 zh;HDK8K7pl7OHHGzF@O_DVAb)zqL#uPUuDxgudXYKWA83PKMLnwa$cf%n8M>kPR4$ z*OLrRgh)ZBcpi1?`sJ}283QGYPmqBFI(g8g(8K1LEu)&H(e%BQV2Q^MFy?pF4GqfG zR%I184s7cfiB?T;DU5F?i~5T-18#$V8P%RZtecQyy(GL2eL{%*=i4g# z#pf56NvGhx_g$F340A*I(IdO#QVPQO*o9FpinVw7-}eVzv<91ge0^_-nIS78X=%Cx zD;@?4udJry#xv;+BqSxEWEv3f}HQg)S`;JGsRN#hvtj!Uz z@1p8GOJ|W-+l5TBJ^N9^F!pEQ;vmzX0uaAoN%7;E{h;H?i%?27CXvouoBc?r6nECN zI@w0^9$>pa09#z@f8F1=L4uLxiq&2RL^hX&x|-cin1O!)ILZbP#@YBkBOh)(=_o$D zvazw{2>c2yh+bVr^0MIMfP@lc_VKmk;n5gJ$_29m^qe}8J{eNoq}Vr#VM~b<>`^0{ z!=k>0-RhP`A7Tbv*b5PKSbO*#>FYMaA4nm9(m!7wLvX@P!WvAj+B#HQ8ImM{Qy_x| zMK4~NBP3<7NFQx}jY3)Yn_9NKat$)$+q&_;%iX07--lJ7`yzcdCc>dmo4)P~>2^%b ze=ia=rA+EF*%|spxTS*u17H;Xfly;hSQk4ZK>p`IgKYkA9V7_@%EcFy(TQ}8}srjv}W3aHh?>V z{*He@{nNNX56tFy8ks3o*78CXS2N#IK95@9z*YOm%Kr9W;jCJ_WglQJ{s3K14%Kdw zaFsZwAE_md(bLWy!Z;3qcGaWqAFMSJv_LZ?{TGE{4?D>jA*L-E4cGgX0`5E9lL_u1 zCHOBIILPRq4&GPX{Tuyd@{{I2D)WAoOZeZwA(SEhr!4h4Kcf5bx=YC3J{skwQpP=h z*v9m3hxnd|YvM$)II4hdCa}Rj91a7>BDx|}&`nip?-5wwZ%#S5E0JH~1DQ4{t|*Tm z0d8&*4cI`zMw7Cne**ojf;`L+uxmS?Z%YE&$Z>;1te?$`Y&wyaoyUX>cB?hOYh$?V z)3n>{$4D-Ih{M&)GI3x-Iy?>X{@{Wt^eA|^LHfB;$P=}H(YNW`b}^g#uQ9tcHk2={ ze8Xe_q6bjdF;&N9K|5{Ns)CSMyt)asi>rxbmad5%q&u(9T^Y|v7KeEA(f=Yg>91ww z9(J#lX3%#x9jrW@K+D&)Px>Sfdr^mW#&Vr8J{sAHZYWvjQUfFdb^f*WL9Ud3ebPd- zF{tfO9P>N=75-{YAZ=kz1I~pz@OZQXL|K>tkZ{G32{s*}4a9h=dm@%Uw%-bz4h=K8 zUN&|MkPSK=maWg7CW?oDCe)AZL_ARqJh(5=C^j})*$|*$La&1JUab64r=udi4?CRZ zXkh z#5N~nHO)F`s09#^4w@+)=SS5b)P;ft( z(c{+N$o7BINnwo&J3g2fX@Dx%!Z-KPks;=}^8HFD`SbtY)id7WBfAZl@vqzH6@E`S zV&xX;;pXfWnD&18^lWQF7|PH82cXSSm`~vz&3o&jKhqPF*3l<05*2Hin^^IA_d}P- zq^9dUyO8`kub`5~>pk&>*Q%x4BcxQ-04vNw64R0}PDlGSs8AmD9?+p}SvV~F$fI-X z-_eTYK*BtgI_gH%U%@a*2fOHdaHv62g3Y*64UJuifXuw+XW4{L5(aqw)aQ%(^$Vwf z(xMc(eFkz4st?cUkMG%AgTt{Xv3@b7Co2sBi9Oh@-RL(A0eeiB1{^e`9B9xNcxM+? z9&SJN|7ZOVk@)fS!8QQ|d(vO$qy5{_xiRu+PFM2TE>x&lMP8?!U+XiM#Octi6cBFO z#0EI-fDGh+Etb+^U{+;rO&zd+O{^0%NAKUW94u&_1j~tbT|QiewlUpuhuU%e|=jc zTHf`_Jo@1hG$sEu6c8BH=md>EpSe$kD5hC6n)e$Mn!OXYvw>d=c;o;s+%JFxyLzgU zB(M`a{|tDJ^cDW#6nngad((Op4Ep_#XaC=XQjvfCE84Sdy#k#NafQqwMLgN@xVENc zu9{faLzixL7XBb-l&{NpvL76jh-cg)%?y-#jek z7p>nz_giQ836@l%_a%d9*3h}fX%Lnx@2j@TW?&zDL=TSyV3PQ}G@`|BB;Hy7Xb%pP zPy9S6x+~(%Tk-P496wcw)K#+l!LU{_P~2tcC4vncJA-FB@E3e{pXf6MiV5_DwD3*J zY&j$sjF~`9Q)qkGMyGdU!WzU6T@S%n4aUtl%w_^WuL0!e z`jQWj?R^IBrxza%nWiID9Ge~a-vK_3EWqByANTsj2azU=U(T9KUx%evrEGP4rHW1k zns|CgxhpT0{$AQHU|wM&Jy%txJzGn0j;mi?%>+uRV;hoLCNE1ir2Hqc&`rdfYeOMv#2mu71Ax(`0(3s@EdG!c*7!^-=DM9?`k8O_e;$A{2 zZ;asQ$@8?ivSAJAyV8WRFMdYYRae`+Lp`Q{kY$a8=i@Di?j zAbpTY&!0UyXmlk5+(Hw4XpqG_*|*e}BcaSQ5jxn~fRb0$H8g9O)Q#_7V94 zmIAH{KW2c~&)iQ+uX&4nxIre_GbMnVWC$zmF%X1_Wo;wbZaR61xXJi(Bz+V$ebEPx z@d{Y0MD8my2h)rlAXzL8s;zKQqfXNSS|m-!{(ZxdZOA&NVA-JAqze&^ko&wd0iJXZN}m9G3=?XHCE z+fFD}y~uArc%{8IfON+)#w3(~;$N1T;U*k1@W zvuqc&dD0v4gJ^nX7VQ6rWnZBmizdNMMykQ-fb@b7-FX_d&TxWQ$vHX891?_nJdEM{ zO(Mp|>5~`MlyoZA+8F%hxFn;e$A01^WX3R2Ywza5%{b(+MReiIW|z9F#E;&8iFE+Z zsPLd1P2LGn2oA!Y>W6YN0dXwb{8T;sH)78z_CIvcGwMK1}i zzKw`9H5lg)upH z5%?Bv%TRA}z>KO;pxIagP8gF`!AJ5iDDH)ig3#;Qq(295#j$pQZ-$ ze0BKK5F!w$b-s5vlAnXTi~VUy*Wo+5pR=)gh-MXh6!%sFIs&gQ#3#F^LBO~S;UX?3$%Tkj$QBu0{y&=<5Cxm!wRpvY z^Y+cB7XRtpy#^xMJ4S;xqMegQe+E_Ng7)NiWsvHz+Ub#{1fEC4S5aI(W zd5jt}+JCWS_gtHx5%o*jIQn$mgsE3`de>Dxng#kqF0h~ov(m7V*0&nuAvS)bc|~1a zZ@gB3lGH7&WO6xEKwLq+XY!XzHMYi(Y;ZIK+4T)|6vp9g^obvIz%UtDHBEb~@YM{k zsM18`2r!AA^=EX7iP6U`2RpST4sr>#eJ{{$PJe@^JKhJhMSyeUf3mMmO9WtT7G>fF z798e?hYx)_u+(K8Zy`1x!Sr=m_KB{D_Y)$gpr)o`#jgmFJBWzWtL`AdZ#NQqhnr=s zZwa(s;A@W$KS-6Mu^#gBiRM^StYH`vnBX4@iw@cq=q}8Yb!&y$RTF5kGcT-(jxJ)R zh%V1?PYMw0L4?$K!3@;7CojCEYrl5r5Emudl0uvy*`I~^0j**MKsNv@Iwx>Fh&&_@ zM1xnA`LtiZo5;T$A+t0vm)j}|rRf&E8G6!ZCl)VQ@reePWESz0E(G^V*n&oy z%+03QPLeo^(VB5Enk{Oh;mQ^%5%f#vq8i8uVowY>qu&i&Ze*@?y5*^OsVW#yv@h&*vs7Vlt=_z}&u9GA+ zJ8g{ABS9ZE0MU8EaJ`w9(!;&`)ct z53!;-_r;9R53j?|S8Ac&Jo6>&;qXwreJi->(#Gk1pzLe9Imd5k_w~8Yo`-CO2I?AT zmD8+V_EyNt7_5d$s#ZxV8Qji)eRP-H z{N2p-UFgh@gfp1_I8uIC2sy5dpX*;9L2_G8{1M}8pQFJ|V){KB_U0(pJNK5%Ey z#@Y$<#}F>x9@BHCTXrQ5HNQR;XKFgJ=<9!7n^G#@{HMQT#6P5_ptwIK?AE&&tluS2 zGC}>M$c_#tn#e2Yva)e@dcr(r%1t&a1wq^AD=ML8tzbL|Sg=M4I-ih+h}zbO_2fSE zVOU`%3JBQ^PrK;?hPP~>ZeqN)($74<1oO>_7=-ydytoi{ZGBzE(mde)Y3;SYEl`fJ zM({rfC;p#&b@0R_=DKMHI2oqjyovbqDgH9;$L3iFmJOa@+RZ65+e-v@4PK{L1Uhj1 z7bJ#f^W*dZ(%H}Y+w^vJN9$!_72fl|e5AP7`jD>`i1k_bwLH8Z|DC8BZ>f=f*kFVN z0c4?Gq{kP~X2;*y@yj95GT?l5M*P4gAIdA(OxxR0Q<>HF{W6Xe+<0)Eas=nv&T zAF~!m8ofUtzRRwDZfa55%d%(VUN`bf#gz{i8kMb>hrpe+XDV@O^z3M7zEVvO@eR+LO^cbnmSBi7)B88_d%8{XPP-n&M31LEx#sqm`Uf zwIB_9yP>Jo#e09^ix;n!rRV0TE&baqY3G0l?gj`_m1SI$I`<|b2L0j|Sjjiv5wk?S zLdTvpUs-sTwsSi?ZJe-;v0>lfz?v_m;mR*B^*=E9qF)dhr6lHm+Z^1c)C}67X3Ly& zMm)hHH%G*drnBCW@ znxk62!BA#4?%9wR;VV<9E)0B(W^>}Crh*GsI&mQU1n{{h+%a4H!)X@qjDs0{*>$qF zO(GjdyYo}Zzt8Bs4y23qM+%VJU(A4cv+^;5W5toC5w8dCh+{bd(wu9@XEX)|$%fO{ z(YV;<3GOS-$ltU@1MNDHZHKNgzx82{`x2PzA*aKF(^THw#byKdiY2q7)HV7C;NyQF zzy;D1)-9lsz%H#OY1|>XO47StIE$Y+HG$fD-(CUeTJg;CU)y{nYp-Lb8Wmv$c!ud= z|H-2rnKa+>Ef^bvWoY)<-ABdgsLz8Zj-y?v)}@8MRhOopd@+gkS_>r@TyFfLtK0g_ zK)tDvmd{+5$c2g3Vpu2VMErA2;DMTxmh|U272~((+}Wv_q(Q%4B{?ZD6r@Umb?Ykm z21tus7>C^7M`PtTUiQ<;1m|DAXqjnQM<;}cE;n|4vSL(k%>kgpG*hDXWdJtRERf&l zdi=-WZ_%=m(F-9=QLQWPE(BET$ErP5Fgof6dU*BxpOb#_2`Lz_obJp8whK%waUu38 z_N%(ZmVwAB@NI8v^;xjUpWIq4AY>BjQ1_ln%vPgf^RV58bX0h9SajCq9`-uY>C_95 z*DwuPtVD6-y&;p*&xvAC3qib&G&lRc$L#j)mF+`Hvph&qY~R0g+!BtjF_0iVMH9IP z+&J}HO3*1lFwbfmvPX45QIZo2;DELnxYGFMPn>y9&U7PF#Gf%KFC?szTFV>{N1B%B z^Ixe%uD9VmoezAn*-LBt4kx$V_tO%Z32`9BOQRsX6I>Zg@etyq7XJN>S1e8sTvMIW zZy@pUBayV;M~Ie}qW_c4pMlmRegP~gHt?y50J1GJ;_vTfYR2YHRD~}b!n8Rgktz_F zr+EfMikX1N+Pr6B^+KEJsW!A%Hvw@w2b|5E9JlF8Gx`5 z9AN`t7;TB-$a%CR%(YOfl@Pi@p*D&uiDO=9Js1qrH5A?LlCMQ`z#}@9SN-pTE3}4f zs{JgPB{ZS+$z4a%gybh0%_Jv3XH&=JCGL*12Oabvkq8xYd*n4C6|pX9Xx)iJS(*&_ zLsmZlz+rxc!br9}Woh2)KK)yfIAgp>)H8j;_vu*Li$?>Rj@_;V>v?XI`Wi@hvIO8} zO>vblLk)$9%-@gl$baSLd1io^+z|S0WmQ>+9NBWqjH3TtA~&oE`{boV6!h;2L% zl6>uy%R9a^8l1k`^+nGS>>G8_0+M-_8m%$P^$Yc+#nKe%O8okUqQ@9s$h zwB8>m<*b-=b%^{IM8yj7I$YrEp(D30YRCMQAfujIi&9g4t+W8Uf7kK%1BWjfM=uJ+ zN{d1Wi7}$8_6uDko-a2JIzCXAR0NEe5l?(WGaE*ciB>3Jzi4%iH;sFp)zS2#`BL|{ z^9=0#lkaULFAgEuQUf&zN^2;l6m8F(2WqGMKF>f$o$DqIaG1T0!N=fBnVpmAPc883tV)xWv68@%IL0D0-Z{+F0)p0>+48gmF6bc}n6aM+R?r5UkKFW1tj|;gb7F*>!a%Xx83^k$OTOMW_c}pgp86;KT z%T|P6>_S`cmQqz|Ux6+%xz;NnQCPH@UrjK9JgVU=s16W@= z$YN{i<$6Tg*hj7=%i$9~Jq!GF#EH`C>e9X_e#cT`_4ir$T(3R!{Xfb8pfBUFlfvXF z4t9T`-BApg<>Mf+V=Mf@&ufA1p2g>0$v9}B7o>6zDNp|bCQCBUGXGb8b|N0RVG%cI zuXQRO%mtWRulj<~v;UT;$|RH^GoOG%#zk#W5Oe#UlJN11L0wFTM1XB71o znMIeTyxWs}bMvrmaMUO~>(b0i-TY-v#0%7z2H)+`F<8m1DdE<`1PaxKvKNTXWD;xi zB>Xa}&+HGk;*smq@WlS*C!IM+oi6W)is+myWzaX3-S&D<#e?$~uaX$6gAPQ9-%jO& znw?XoJC7@#hJ3s14_-P_9~qq9ir)9r1)n`#P3c*rC4}?>4V+Bo1(Jidm2&~&CiFMR z)f^7oy62CgJ%ZoD79yNrrmxPq@1!5rZ}SI2^mBxebfOPA76p}l)&ZYM*CBuS8^sk% zH;Bw*-1?(3{OW|@sA|Jtm_%61Vq`)t3*#ig!Y#H0JXiEqfC%*5L!U-EUTXD}uK}L- z&EtGZ#yuQpX^$zg8w2rMF;`Ro1F?*H+F9n1t64RhnWG+KOCYTFTlBB0r+W7 zs6AVMBMf9v1V3m&MkZF=dvAx z6P3u-zijsbbwHwN*^ncD^}dnyzp2K&W>}w=1N0zbr|eRW518=LFW2ILX5)@Avdl7xo_VhGR`{4%HMzg(0F_)nIeH8HsXesz#(s8Z15l-a~0Q3hg9nDiLVBz*ncP@Sx^=5PqD6L=s zynq7V=bN0fPL_lLVv`5BjP%hb1cAbz69UHdU@t0a;uO%5EcDhMx&w^Yqrftzmqdv- z{?_wnOiT0xIZr@^JTThCc%Sp(JDqh_;LY!VRatx02lakBfTKjM+$I{cowcDq zB86DyY2(esN8h`xP@rV0lhEa0lU$Z9#@F#A4`Mp=#bmWorAr5p- zfI}NaWIANMwP*FLq`v0yi72U9J>TgPwX=S7+^*o0vR;-@DWFbN_WVF!o)Op^H(4fl#X zTBLTyyUw-`AMt_KzLSc#15Qs2_ffZ|M+u;jhyeT^dD67?I`2}}3tvRo)(X@u!)Cx6l@!;j3hOJE1pdZ45Zrwp`K2(@b%^u#(QY1C^kb9xl13~a*?6cC{p2lyP#UokTRWlB$YjNb z?6(2udY@B#7Uh_gVQ*l1D+#~URJ|`lK4qed(l_vw0Hq6a5>t6(&G9th3g2+h&=wjy z;q9(;;DWo7aGSks_m?|&&2R-4jETP}~mwjZ)e$!31E z%f08Co3Ky2@n{>|;Futrn+!f*?&8KCpZ3~#fes_8eR#ey@F&sle@gfHdd%IK+w$)B zDW@uANT445@;HpP`nsm-LhHGAo)^@;NHQBU!18Cpohd>A=l{P@#RuCp3gxh%rZCm% z{|rh0&gC}-b%|`k{jqJ2SOPcG^S8j2mK&X%plE^)@8tahAOtXuaHptUl36Xgw+y3%d# zPat8D$2C8Zg07#G@*jvGaRqLU<}4z8iI0Q&h632gDO_KVh}0;&$29tNjSOf$KHs`J ze3}n57*!p3K)2pB>Fgqh1Vy@}F4Ha_6sCI$6{8}Lj_}Yp3oYY=1 zlO38sjnQ>{y=Lz9ojl>`pn&StEUwGHB}i2?v9xLY55@_dKu35kpSGWYhO6m3UUfnz zLt%5(UfzlptjZq6tNNOrk#RDq>J#sPVZ`yMwcckkmJ=&zKO}_REB+nZMFCfRhv|z0 zCFVcyByE{%V@SX`%0+&URhDF^pq=3*Z*z;5gTvS3143;;X$tpEhr2G%6W8Xb$RbFr zZE)1b9$04%>^An26h$ZWutB!*LrP=hkqwl$=J4rSW0&{J$F>eX@W#C)B1#+vgQ$?A zbfk`^?vHcNosIopVi>K zdaT>`-Bpe`|HP5Q|HzuGx z4cx}Bj#%D}x=-RI*!&3@Np2t+D@cwXRBjHH?U3O}FAXO3mHy20x_>qKFAcRQ=~|}H z6C=X*NSnDNX6)bu*TikWfbIcwQ6o92x7*|pQH{cDiyGIY^YeJNa@AxqG;F+q#Nv@x znFJMz!l;$G26uIYbMyHNn;4*O?&{m@{wRpx<=|>4VAT`-F@8);(mP@iDcH0Ufee=E zrWhR|RZ*a6#}hzCir8dUVqr#X$VIG)>#C3%EV8iw#hZ%HFp)$OX6P?*e9r()S~I4l zZ8gZq!(^nwoVYh8-fl{E-X+dPH?h`ALh(xw zde7c=L+0Ch%4MVR#p>)XAU~l6&NAhe^jM+eav$X@+9iIZ;kb0%R?Yy5CN;7xFZ(0; zY8$+1(f9tJu)sQf^jgUr=vVli@#~+4w~@S>_$W={NrW@WRWSZf%?O2Qo>$hnK*YE` zXyre<0MX`jH`ec0^4aDb2_cNHx(aY{{n8~2zUikgCzQ5RC>jzl)pnaR0Gg5>+GGb% z6nST1(7`)G(Ptl>Y-0Wzk6A`A;Og-HzoyYZ9KP9r*<_$6g$I^X-I|xa2F2Rz zt3t(3(cah6YjWkx+1HYTKv9ppvc})Y`olFMix5bGHQL=O%}V7y*j@Q>#x0;lksRWU zc%+v;#^Oy^b4JBkACyQ;^QJlh_^y8iXgm2Rb#1;qT^l1A^Ff*me|S z5_ZlYWud9bk+D8(!oSPd6Ol8dwnH4p^cD5`=@cb*J@sn)j8v4qy-2{J^8I4Tmal>|H&278*=&FnijOU}XYsnV1NmRR}@6 z3(uV=F7-_DH_6XC5r=L^7Ol6S7v7+r=sbpoEHoTxumHNstC^b4-b9tgTC)wd16NM8 zzpR?`ma{Z7yi)#Y*Xsm4*stZ{!H4t%56nM!DAjN|d2qdOn{v{vi7ZJ7N~y8;MYmZk zfg_IH#O22GaoP{=AT*R?C5MGix|c{?m-ZCTPN7$>$wsX=#W{*I{kESq8;}kfdFpCH zQoaY{{3jx8FLj$B*{zOUMbY>)$zzx|yT~9MX5L%U!P!b;rn(!H2GTZdmRYs}Z3%pA zOKn-&$GOHvZ)R|r^bBv7m`l4f3l@zzLJO!FyaMTJ4nDZeK(Y)H6u&*Ax`bxcY^00# z@Y zTP;?3Qrf7vi|5aj>w_GY&TsxLrX0O&2H`72U%rj3&+YYKt?PKwCz~A%FsYtXn&^UID4+aXc!WvoQ1u%29RCZQ`7AV*IyP}}-OoO=w zJ@XIEWtnUslI}0h&FGTE^8g-yjPg-))=R@kAAy>Pb0}yFeVSZw1jzOfWieH1j3fd#WECV858yF)ka`IW%s6ZD zSnngPRWm>fcfOm21ICrNNLcfKqcyc2Fyc#fMw;THJLCKdAd)_89bM}W+A>iK(mII1lWSC6h1bxpxDDRJFq@NnU@?3O(PFTV*8AyZNgxpEP(B z1It@4M%?j1ue^F|z>BL@mE%iGZVXZ2Gqzc|7YiT-UyVA|T+#KdpV|s3DX=C;^{Tbq zF$t>v58iPidSZ(`loKKmBXC-W4ucmF+H~b1 z7*)ORpNC?4D&`UWDpdEnjTbY$4;Tk;1Q}hlG1uAE^aF0HbwGgSP#+RZvJxY1gfI{F z@-fKidcNH0UcRpOfH40zRI&|XipH94Hpic01H&j3zUVHz5+Zj8LO!1SIhnu-!4t?x zS*@cP?{|jaMkdn; z8nuoawvl5j{;ytlT5Z3}pPfi@)bb9ledG_S>RakB9YqY3qkywV^~Cay`x*OFRgtp^6o#+M+ck&Gi)$GDmWek2Y6D+l8VIX~V7 ztTFS=xL1*8vN`~rC=TKhDtwW~=cV6fTde&T!1G5A5Ceo%*E9X0)F2q@BRlkxhv*wHB` z82*dXgSnvlz~BN8b?nxu(%tn$F5Li!`RRo+_t=hNS&l;66tpcv^|z*W|LVf^W1F(G zQcZqF$LE?#@geM^qdggHOk5sJKG7vW>^Y(E`63B6?}@lA{-#m&v?;+GT#@ihf+aU@ z%;BS>O&KeNYJ4>>k7kgMWb<2f_DrW<;pkihqm2o#!!?%qtNGQJQG}Wy>TU56I-`Pa zB_k^n6~8t}d#ue(KGIyA+3<++XQZ}T(Ye?@6VCm9sBX*IGZQ{ocvh)V4!o|;Nn}P# zP^01;C>h8UKk|brAm^fS2?n}-#T&mryC+I+*7RyFiSgJ?U_I|N@9tkpmoFiMt6;ER z{t=KiOnG}>pL=0uu)T>FB|ijViOo>)O*E!XcgDs>oHSr*tU3)5R?c3B) zEzSZWF*dSw)AQhcrT78ZTPBBA zEdZWnHM0KBNO`dOv!@wN;ax2k1W1dIEWhK-AigBa8o&QMf>@-Q{Z`*f@c+Ru8m=n;qP{NrMfg{?7@@; zXB4VwLhZW7mo$<11*5KMa(1)mt58_+dvc2vafck{nb1cp+DBU%KU0*FABE*#wKtjf zbBu)+dPfyLx>ybJq#7CiGMu3?$}Q&e?NVci`za1i?8lEB@=^W0;Pn?LtJm76F6`}F z!Gvp?H$S&is2lH4oUI{Z$I8lx%R>;K^J$l3>j(??KR7G+8^Ml)QKuoXG}U)Q)MF0G z!v=^kPxciLzWv}K;Pc*ZzZ}h$&F?@2P@MhcGwbeovC!y1YEFc&DNfLggHP%=%3^v9 zK%4)%T}RbZN+5t+NK79P2fWO4G#G~n*fcxs_~8B%HUhgXp~u840hrZ(!zK&+5(p%% zJ&;Z8%{peVc}P33AInAF^dAt~dGGd~>bUf!%ODF;FQA8pp^F9Nc;IOeET5Am_4j&i zQKwOP8O(1NUEFZ@GLz~}H!_rXusX6pzT|~aX!P#=M7$WY9RC_Sfj{M%@&X9i)7L4| zf9|Jn@h+=F!uA+XmoR%U>XRy^ffN4{S+?_rwi0YMXKhfoQ1=qMvRx zesJur_`5N(kaoakFy+R+MiB$!h;GtD19Jic z8H$B=M?8d-Wxmo{jqjo@6pvu4eFSWnQV%IDUH3@tqh{nQIv>qnS5VH;>@LW2JTo22 zNFXeRZ1B5<8POgmfMI`;j%QTC$Od4jLLeslv*e-yP~}=K2#w-|WC1#mhZIc{1OQ2u zVTke1q}UGQ($HKLh0)}j{CB!ay=y!d5|z2gG%lF}S8UT|yi2sCsTQE=Jm5-S3+_n(u87hsgm>4s`rLnoeN1e$G!h???>0h<<*JX zNN8J>KH}a#(Oiq;5BoZH3iMP%>(Z?8N)f?)ZIZgZMomT&&-+*qE0-x%?%uO#UU}uM zj!X!0KjJhD+wZ|AY*95>3b{~s+=qv5_zD-sS4vAGXjAIvXxUT&F9pXfXHJP$Tg+EZ zJY}4rRX4W9j40S+kc2O<-+#2yTf=KN z=|aIxWFtE~q#DlNx@}98oebvZLtHvqw?3yk1RaiZbS~~h`xE%6z8YZC0lpV{Ks6BrLHR#%MbQ1SF(W0Q zZu^}qCL~l~W34{yHw5!7B01y{NOeCLNS^0?0qAZXu0u|SS*KiIhGN?Lcu;wj-m0`@ z{!1Cr7>#c;)Zf76pq5H+kLJAkeNdzu<(Q`lOq7F6ABbA(%P&D*N?GZ;i`g! zmcPiOlHV>)QokmZjO1&e;+-vUOT8OYB%4cc?!r@4kA=`!;l7~8OCG;nYfV?RbB zTJ+Ijym)^3xmR4?Jh8`j*}H4D%{8<*Ldn`4-*PwlHIV7*KD2%4fU%E>V7e_Jv8B*lKnPby;(^^)nOtK60#2aN;KSk`WxJknZ^WHAy;lY!Pu{e5N7FNNFYaaVEWp3#~1M%#!+ zm&^&}HCkJhy%u_Zey-tB&sY6^sH~Cu!O>daH6eYp7uxITT{N-O8fKjPJ&{{x#WvTc z`ngXFQoZq@`;G?p1IGmIQ3<@{ggDRj6@5Iqi{;fT7GXSIAJXEHh9t43j&8hr%WT06 znbz}9q8)BBJ%XS6|9FY=)7Ut&2C{ui2p}(s-~tvX%}q7CmDn%t&MII28~#FzgHp4eqq{vk9e zh~wvXKmz!g$;{l0lx3ow;&O=QD1UG@tT_)k8Jy7K_-d~4&ii(y!Qh5d<0pE{Fd*~u z>d{_p6r?OZ&#mrlqcWu7Rt9y6M9m*dDb!Kfi>Yg>(IEYsEtjadNO|IVs`%cL<@vFJ zmb}tS`sh8UdA9_CmSdW}I9)PJpEtG@MW$EAO*y_fKR=@7+P;h%7y5jRbY>Z_>6*qF z39Wm>=Pv?0*{t!zJAhm~plr-9IDT^U#&MRpjPz|v{9ZZ^u$v|vLgZN|h%8Q5 zX*YcC$BijAz$TJ^j>zU$TM{YOKzsmhbdLQX>UWUVL>b4t?u5?`t~Z9dMfxKh@Q;dM z`)sZ($a-;RToe2|kgvhWi4)n^u!R$7htKPKq;1Q6tE@SErO+Bp+D-YhWC+0jJy<)e zZAyPzn0=g{P2%+XY)?O+KqoW|kmB-|*yLs@A{NtTcmnt0%^4 zQ)2K4oZf!_*yeg3$)xh{h)!aP`zyS${ZKal;$zX-d4yX5b2%AsB_zG!`ZwqRe>GKV zpnVwOsEboa^7Jb@{elR@-(dR>-U(JRF#K|0YTr4D9>+`|lJNbQ2^WOqZ1Ll8rH`0P zvAUI^lo0seD;k>K+>H`rWLd(UnCd5fLBIf~rEQKtr~J^hd$xeALIzm&B+&gIOIH~c z_5XC~Zcw^Aq`Q$;LO|)1?q)$+5ReAx773B=hNZhDq(fMc&ZTyFzWn~r3*Nvv9?#Bx zX71dXxp!k;{ckuNhPJueX74nhxSZY%-ng4}Y*Au?--+0|t!!{xp2F~x(s^Bj-qMBS z?uP>QO?Wyrp#6j6X1&u1AqWUu@!r$UDn`?gc*Jp~T^LMz*8 zW5xoCNRCQyVd>?#mqXR>4GqGs8>_g#i-WJW%&>i2JIaoQ9lEK$kinpUvdlZ!gB=s) zboFsDJ^3N|Clm{_VVF?DLoP3JDkB#(C}zM0Lu6t`3kVEi?97QEsaC_KxWLBca+d zi#AlgE*i^BKt=85jlLK`F5(T4q~zloBwmsYwt-c;u!@lHzCdd@hQXhXE%4@k)XzWXlrF8fuG_j_8VdQq=9$iXHl-WJhKe zfgRJ=HwUWUTICOJ-HhZ~cH}dnajKa@Oc>0P$(Onjb7Mn00DG-}k~KI2z=&_e zO<=&UFfEeLJnW9ww<^tMf`E~g^=s3^bku+|s?4C^joX0(zH7c-HE=SFeXAuR==SHl+uS|To1R+ zxsIa>?z~NZKbF6fmkl2Tr1xr^Yd|L|j|ITlu%)n0y8LC%04`<8Kn*ou^=;XP@&$Za&L5| zuiMT$CD>a7Gl^#b#-*eHvJy z+|3kd+9<&xJnL7Y{l}Jysgvh|`?BxrGLQ064BEt}nd8Zy1AOD5H$rzKd{D*qE!%!B zIUt`0zD}LYDf^K6A!w0W9;&gV6f;>b+<&LK2+f6Ka5%ethd*IFw*>ms)A79P%UZqp z_F#+t@{dbi5!Cjp_0pw;?WSm;m(0ijK^n$}Ni1BGFa`BjYMIi_Kc%JK%De%u*)9cD zeCCx-K*mq@8r@i5#{B2IGWHxcV1*uX^@K7}$OnS3Lt{egjT`Zfe zLBmwKty&o|qRrdeD-W8Y7IFFumARt`?%rMm*y~bNsrz?KSaf&d&zJGQk{h7-mB|nj z3fLAJOTFHEC|D*KJm~6P=>cL@MdE4ABs)+&d71RwN4)r)a|3Mpe*;`^I2qB_m=*yD zyTnCuz=)zFD>rwWAyRHm#~(E_nUEF$N`5Or(V)7j61=}9z@43XEm+^R;~OE~gZ3Bs z+9VBFMDk5$(dqF?0R2AD=ivMH!3J|=GRwtmr{qe%^KB>Zm|E%Z62WlR&0SJ)J2)p| z9b`EkSUaqUHu$x3V%E~!oYy?%jAv~}RL9Zzq8-o}obdx1Iv4TauYb`I-`l4NpK;t>tbJn0-G)6KPze*?K-v9Sph_s$(F$;QFi zL-AqkU<{yv!&_?}TByO5(i_SalIxRdgNWF^pW#mw{kG>6oA+Xmc>=$tazdJ4%?<~L zg+8B-+epwvicWVc&duDQthufK*f7C)#PAh4v)%lQD19ovc?r%`Nn0RSu}2D#2zl$> zcl%;f3+$g5yAU+KTOMMR$d7`LV5S^9mVgGw-~yE0fGp~%er9Ug|MvJul_D~>4cF_XWQ?-OPHa<;h#V zff7$7TLF7w_q%a&tCBR(~`ZtE;Ok8apoMAaG$j)(WG zem%jH($^jdr@`~PEoFq`f;B*QZoae`Vco5}*t#0s$YBe}a}P`ahnM6_r0j}RXu4o& zQK!~|+}nCB?&z~e>w_VNrONK(>)^K{bs>LCitU ziGQ~%gUQ#hKI3shk|@9L(Y+G?dyLSkKh zk-?a>zlZ;&btJ;Gdn${kGfu+g=YMpFQOyc3Dx&CM{C{Pvg!lP8K_2nz?V}^Oj8l?i z+MemQe~SL*JaJ0<**S#aD$#Uwn%`U=kjBCHV-JC}k|7&DT>bE+OiJTzsbf-Ac=KXk zog;Xa_e)LT?R>a8!?B&jNr_A&xDLpE)eE@l(V6ihkst5ZD0&RuYapoEAiy^0fId8> zHihEiE?r~4^FGuEGN2L*b?MfV+Iv_d+^LV}oAbT$trsLGBf}wx&)bBkNhN1azK68+ zAy;AlI;26Hl)hlaocAmIr;NJ#_HW~f+2m|fELu);gpF7v6J40-Y5vYR?3g;f*+*@A zN^qLOSO(xh7?Nh7b9vWd#U9o;I*Wh6=G-4Sx5z(1=zEY%ml*#BIz8r&Yk6fHk6Ups zAq61b@(UOs?qNMsAfiil0A-c@Y|c~v0^5#)L4;1DnU=264o-Yaelpo`tkSvPOcX~{ zO4>qhL4V8PhI}S%VwHDN2ZkaWg>VusKlyafx|?>fkH^vY-694(?NocfM~3RIzd!te z()oS3aZ5pZu0(&`r$`JCe*>#8J{ZeqPiG*zRtup-Kvw29T>Kb6#nCqzuY+Mc_W4_RucYwwmy2;^NQ95C}dKcxE%)(*zC#J0y_ zrpp`$Cb8xrgb>=GMb29Set3iWFOh+wVf8WjZ1T5Lb^x>;Z=0QVej0WW6R;qu49R4= zlk@QY{FagnnS0hV0YkKUQQVba7NtJgvo5a_`z>4iS=6`(nqP{D#!>C3>XE^ZHq-oy$@dvaQQV4R2P;l=bsLg z@w&{D*ejv)Kq~tKq%x(k>&CRh(vQA*bsTR@1(Pq&6Qb0K@(9jgpH|rme*IddjcGo2 zuiDn%6wT+WF?^_+_K~zRex-nuE~DYL;;)LH4KmPtbMFrF=3D!Nzj0o!%(fpRx&j88?i zk7$H5G?9U-d}#}e-A?6d3h*M2KpzC7=4AaR%9iQE&zo`C!n1uB-oNF133%-OLwz5%#^e3tcLH?d7qQ zS~0@&MYugsF|^HdXXi_a*CY6QqidJtM~o1-fN=@Qz9IBX^8OmOH$* zIQ-%EkL8aPm&a_sFW;9!0L-Q$3D6|w!aG*|-&;krjZTSGeA?3GgDqA*i{V2n`sFD3 zCS~i)c;pJ>xYeRL}#<<)OJ|9 z`9$_cHC@PBTPFa@!Yz;VkL$#$0S%(p$&Sy9;%e-vPu&FXzSU}ve=tI(NZBfgK=IY* zlhS;KZ#aBQQi94>I9#%N7Z{w4Y8JMaRyk zG1^9EIR%RimW*p+@C$C}s{uO%1D7-gn@EoG&Q&T|YI&T_yOJ^Mf)2@XGa5yalV=bxJ&&*u&tlsqC9< zpTq6}g^@j)n*`r3J%j?(BMiR;031Y0OZ7`}D?25Tj&Fg|86+talb+DNK5ycU`>ckM zX_=vSpnca3Xdc=-FUH7)D_?txj1;%swY$9T4*gxe-kH$dNqy_OnNG7o8;yd|FqRI( zNHTbMw?kWD)|tGKd(ZB3vf3k!F0I>D*aJ7!Zd-)iR3%7S;7I1w_k4NiFQo*@x-@u6H&$Y&eSnLc)7m-%$zkRWbXSY&TKWlf@w#mbor!kQ;-xvLhTiN_z+<1JSOpI3SYP;drtt84iyPleP2#@_&4 zRy{VlvM7jh-3#_|>l+b>Aqa=(XypG2+0q<;u-a?t>{KOs5Rjo8T28Lwin! z#yzJ=6;IznrjR$}KO^D+^L^bSmeX4Bx6splh8!#7XsZ>O*~pE$W#JUFOEIXZjZ(L> zjx`g>Nz3=aKLb>Hd4U}MNB#&gH*4ML&MPKEN?gDd*iS&_)`|c!`F>?DAk}6vfyvL@ zUM!3d&`MEe%&ZJka8R*IG@{cgpMglBP!{5Rp2@<6vpm)xCP%HTz^i5@#Fqe5&knee z+d+M*7wvpbuf$kcNONeT#%UORn<9B|2@*O!J+nVcq?3yf#-vqDbZV4Ehp<(kR^LVe z?F+o(GmKmba%~#RUkZ}3Sa(g02Szrne7qQOT=0hNATkBm<)2uz2@fHFhClkJ=G^Jx z9ravw=Dj+lu%5=xmw|l7=63IH9m4(a%2~7e4V|dC9j@!k>;<)xWrU&ZY#K==U~f(h z{Lc6WwYqk@Mvg>H1i*i{=2I9DLohPU#<2p?L9aPF95WWZjcO(OR@(H-(yeRWk5f*0 zH=;D)k;r2{;{r!fR8f=`r7!pCAx{eXMUG(4P!YONq*5H!Y@g|Fx-b0O4We|L9aHog zqLF(Wy2Z@=%#YsPPcNRARMnh2Y8IViI`N-5cy|y17qT$0m+X=J7SWD!R1jC#f;TQ@ zb)S?%o?o*XyrC}|+D-qDQz@YRrp!$EHq#ef+v&=WR#oAvn^%ocuU7D$iLg-l^}V1# zE{?l3K151b=MXa;)r>g@v31bgVMo}G|HbNo`=lwx{4rBs=J(wSOywQt;hR3C{+e!D zI3jId2-3u6P8_vyx9J1l+V10;;0Mnu zsp12C%EZtf@G~Ozd@)2f`F#jk262!OE9V%@3^r3EZRH@sPW%b3X4E29!e?p%etcDWzCgV?Ul84QqGloh99scb+aM@Td;PznAA)8 z2kj_EEBCR$P8?cB8v}mcTgWH9g=^okA+dP+T54At-s>p{$1jxh6Zij#E^js_I8l?j z^Wrfnrkg~dsFsB2fyyr9?Yb*^WWKqE!>uj`gk0X-0-K{mbbO1?$oMMInm057$U<9$ z#o=d2O!PC@m-6dFc%q|H|IJ1jn?QFdcGO=yTt=$M1q@S~dD8k@&M& zIn(8Q0NY#O9xa@C%XjmR1|nUUy^!tg*(UXQb~_q7*p2F0mgnIp7$ePEu7xf{K9usT zRQoh4l@1H&GyVbi%bPX-u zyH0&uCmrm7aQbfuyt7aJ#X0$}q3V!U$?> zi=L z&>m!we}Jgl%Q%5$zMZ;dS&KzjbTl4P`8|eR<|1I)R$FayH?Ix8aU=-(E1WqesxQgYO6QPwkf=%$gDaI{_VGp$KF-0{I+dH}Lhi-i;=e zka3*Zc}PS+RQ`9(kAlGa#ikv6hKO3p5s=5t

f;e;%t|uLw~qMD(LXSt;2;aEuOu;>8lH1Z)G^eH`Ese+?Tc?g)VwXt>^fbX z!QS)Si#z`a_9eA=zxsde@G)sBy8lR)3msYxsz%7M&&ph#r>Al~{%MI6A+ES?Sy3^7 zvIR_AydozEC)d7$Jm!H(_@xT??g={}@2n!T9+y$U5}E&E!(12miho1@5jzxiCyO`o zTAJ;z&=4}<&HWMh#Iqan7Z5;*GV|RsrIe*UVT+nx-vUWYY~T_t2Rx)Y>|N>Qi%+pq zHyX9Txop@Q#7B~{Zw+!Ua;q6au`BU{%ky(ZfscJqYCD+xdEl1{bbf`q&s-yBaO8rF z7W*E*&A)M3WK3y?0c)HE0wK!#t5WBoD!SHC68t7upc^`rjUW&22Ex5zd%e*y#$qRQ zE=JfHKh#*pf$R#sTj#@BBnOZw+SX5(Fg7QF`_4*8m27O=n56U&T_|eymC2rMQdOoR z&NlSF5C6rd^}uD)KlE#?YQIius>h(p#F`O?X(q^D7Kk+Ifb8qk7gbeVekQ_H@@Jkr z8>{uDSX`GN2#U@Iu7|(#p-rzkJHt5SJQvPcz6XcMGJQHF~Vnu47ALF}mJPA9*B%)f(#C z2dY3)_W4rSQV7*uz7P=1i0TEaWu?%^(FlO~5u%iS{+#3)UfL_Dny)N>rFK5OAYdALS+aDVN z$3?uGKiuLu2M!-6snicNX?5fDcdlQoN)7&*z#HmN=)N zD2Te!N(~lB>1$13ZFCQ6nAh?N#X1*7Bw_we@P}-d9HH%HusLZ_loIEB#Onnny57pOcnTxjd%B$+l zPP-=dmDqLgdMPPvR7)UAu%ryVbw$7N6sz`5Sj5CO0ZgX=y+m$~e}d%bk2!nUXg@C% z=B<@8fP;+}fTQeB?%mSMHfxVy!jaepLc=`~mUmN_0xng+=)zq?-un?$?p#9c&)dvT znF||cAvF>I>O=s%gFbwT?N;o7E_@>j57&F0G;gxR9$*gyplZd?pE2ig#)A6P6A}+< z7j6f+uQAwrV_?O?qK0!FBPU)IT8%3G3kDV4v}_Xt-9IFmO7+W>RBee6)9zf1e9P=M zr}sZ;l8qCq&bsD&ZOgT|8X(HKsLdOFc}8 zAZ^hkvA6o09kb<4lw3~Qq64mON_XGjXcK|EoTuPq8}mDc%^|+4z*P)^^}KjqUHG^> zC&2|4>z$GCVZ2=Zt}aamJZuh!&@;{OGs$Wt!Ofsr@RssUaVZ zlPnrqEs(cx_ppTNCZA3bpMWi-V9XjoWlfJ)B96JUSM^uQYKYa$6PhonoAg;e1~z!* z0GD}(`}W}lsoR3cdY^Z&WVVzJdY#);UwFS}Z`z zmg1IhD?_wI!r~b;{f;G!mGE8rGaCY6DGXVFQ{T*2-HlK*k#_KxiRS~w(xcT=;yxaj zissw}Y5axYX0%V`A2^OhUB`a{PKMM?L7WfZ_ zGVRw*ipsnly8RB8Q?YqSH{7!ze*#}HdguA9K;3_McdP-#+~LZ?C0(YcfOesKQ}ro% zmKtY_$yF)Nf8>_jDZxNq2QlV*uRccl6K}*b4yLb8RfXQLOT$CzI~kk5K;QlBK{M`i z^oQkkO5x{z^`iPItJjaEymJ_xHn1Tu_vL#H`AFUq$(h7j`04M71wL>bhCEnbhQS<2C(zMAE#gcv-7u0W_oJq>qvsZd35(1k`4W7H2Z;lTTJuAf- zy4#_h`l9xTg}w#oVZ*eaR6hX`uWDi{$-R_Tc7Ytks+UAZ?WD=IFq}=swmhK_=)bJs z_9>|<)UF67#12Y!+?MXqB?zM4VPN0KWFWZ~8ZS;rSIa$-q2HH{(Zqw!!gZDlruiqS zVRTOBchPBLse%S1{qHi0N7S~NJ>yaH2dBwbjLSx!aKQpA!ah85`}>-541H$h8&arW ztD2r<{2|n*x&|_E(5Dq`8|1o3-0i=m9`2h>W!OU>xHWQct77WuPgG^)-gm5uW8!Jc zy(4K!#V-7*j+m-Gx~`sS4dH(S3JMO$yHwB0$;@G59f80;?ar_N9fwFlE+waI3mXT+ zJXnZA-O*~Y?_7l3D(o-6YnYCIOIRJcU{?0L_Uqmo?au3e5e#GYY})u*3GziteS@0K zuT~zaM<0*XjmWL6{m&cMQdV=8jGdoUbUY^`(BYMjcGeN^=#0Ci112q-X6(tE>nX4ua#rNL@i>a zmn*NbevId<}0LJXq--Ml{}>Z|I$mX_^C?AMJ9(^y%fQl zvckiSA&aK>Oe_-{rJFg-1q<%>sbWgygAYg_AbibHS45pj$Ef}LGGnoRM)c$Z(wg%I zw?8)tT#|BG5iiv4^3Mcb|nx{l>7A1lnopBY7bS&oVmcipb_ z2_H14K2>*;3^TV`lJV^D%sUJ4bGUkrZ(%@9+Wp@~dL41ap(R^{U7;&$jOxaV)}&OYtmdD3`FN6 zEqfgSn?_uMb?M;Hw$`z1Nsio0P}oaw)%$v7FG@}<-_Pr6>A%=s8l-RN5^4yVQ~2-f za`Zx5CdG4T`+r*4hO{=GoMLu3?)V5GRVWDQ^h6`3YF$GG*KA{ME#|s&7-AEIS5jV! z>S47czk0#UskSj$9`znA0|ox#>mPCQ6rt0z*Xifi?|#Ljy8JDpI9;3VHL?t&wqAxv zF1XlaT<;RpFeYaLhPsv;nJT03?)eI6Gr!}bU(|V!Owq}4z@?-#egGOD!U<9b(a41e z?XB20f-mQ`*ZJYg>P}ftJSs);^u`{0YJ(M?-eJ*c%u(NT;R2TmqmUxis$dA-K&w-~ zvbf|%?cWi4yp`LpXE+R=pE8+lGIh~*;V%@wa?c?)gA5_3(PU4rY#aFM(PukTP#%OQC5A^H zWfE31d6IYXQ6Ev6W}n{L5DCaQh+O<-gkGL*1jW3Dv(XLa9D`6e#+Mz8{*5BOCs0l# zrNjDBWr?%TPQj=Muh#hc`*z7LMIxEqmN%Ns!sWVkh5D8UnV|Z?KYj`ZKjGIhQxH6q z<%l+WBgz@jx4*dXxx!?qTE-N%R2S}WzZ(!@nM#OSXLM!K?6~uiAZ$8`e)y+FHmWCI zFRTf^yhmjEH#l0!HuW|7=_}_+P)OLtN5n1B-G22AsV}eI^1f0^-5E8vj5G3iPKX0c zMjS-SWea4DF-ut`|2hQ7-PA_2V5_lEU2$NSKErjQ(Z9#f>1AR5GKDYpc1AZr%Xr0< zW|>jG>uahn!Dy>E#<5msZxN@IVtaMHo-kD!Rxwrln)Q$uGrf=9RZ5y`hUbiLzAVGC zydTe2y0vcs``V~m38zNOz^{@qr8PV=TJ1_|NdBT!!8Va6jEX{^)>QMj21;DM$BnC^ zq=_vQkxAC$#ncvuJHCsXvm?l@y5o-Vth5%XfG(?s;(Vmy znC)C{A$~RbQ!CPza97b|X3sB20xeYCt_ZfB#|hgk z!7MB-a%1iHaZn$%>^n=CyXB(h zoW?(4ZB}zbSt2x)P_rkA?YJkYWjp&_3a@XCUNFvcFITAKso@*b&CFqAPK@YJs?VM_ z9n5=h|1E>YwgtAC4Eti;J&x#E@u@i$J3pGu^yo23+u3n@8nS60svABfywTfIHg%o` zlHz=K3Rzpmh$GAK&rnXAnp^xCRUsNhZp1E(N0hSq7S@kP8??Uo$%g0BMIF8DDlA`C z2yJ6Fh?0iyJ}pRHi*myAY%kDhckAj|TdpcF7gA_#4yk<(zDDvVkL=bakYwT;1Hnv7 z@L&(g@>fA9m2j#P`pD#0ww9o?V|fnLLas@BJ=<(pj4$Q!m~UxPLt)618EyBeyFz9M z(ZdmSyVeJ3ymDWhxN!Rih3t5P* zbgmkmoK=c9&kvPou&14%Fc0f}(uPlrA14yOBCm2R$$ZxO($x>2Z-R@?q}GygWcx~( zLu~m%Fmuzj%XMV;P3;spCe;r~`|mC1wV5=Q#$&2_#L6>M4J8$Q50onXbjt_*9jlJ_ zB=_X-R)TO4+R-8>c2Z+uxjF$AICW=x#QD9)nM zpgxk`3M9`4QQXD}=X2uIW7X<}v=b^$;1h;D6_NYO#F3#T$fc}I2{=EFaGOHAz^nvc zKo#&I+`~MZo%=?FRsWr0E}3gGphT(?#AubhXLx$2#vZ~|*ioi=*h#=fzT^A*bgQq0 zvZ1N`sW(NGZ950)R~lVe``f4sPsB+=J_+c7f1WV3dw8hna-v95GkAgWRFE@tXuSIm zUgLo`Jr(2W8EhuJJofFh-KxIgyzIAYdi2NSfllEQoL`OZk?qrZkHbIZ)y%}v{UK!^ zt|ItlPS2<+?)wumA&EkliB=P~zXN3KNsvp;^KF7rj}yo;crB-mBQNoZE3Ce(_Xc6>smOKlqS5_Mp$w za;eYSG6l>`A{1aEI#V}3o76U)Q0}6NCFQRXlVe$|DBhcPKHUW=Wj0i9S(m?UsK`z% z$lXGQgx^j)Bozk^hI2i?N6-3VFg9UdH#I&P_4tWbld)E5t(8MyN$Q8aPL-QG80VW( zU$kUX_!M|(=J!Emolb}|XB4jdxs1}UM?I4KpXX)=ws5PLATvdhjYjOwcKfTxZfr6+ z2K=rc6OfT>mAL+V`t>LorIhh@2Ge-W4BIoa&B`bS2&YNMx=vEVITWcI$;T_l?}Ko? z#j#FB$Ng&?*G}q{<0Xj^Iwk(rSrwM_LOyLPZnxh647GO%;QE6MP3&JQu&%{`Hk51R z)uqXCZS5puwJ0MlaGxdPx)PrWtU99V%4kC z&cQ>AOKu5ryvnvsi{a@Mu|-7hse5qZ#*pcONHmeijshV_ar^uGF)Mwh3I79Oo;ruv zJqb4+>t6?dbN{QNs_A|%m`{_IfAC_RUu*{Thjf<=SelssT@yW%?(Yd6inqcSqwfb-)IGA{t=0OgUH&f!t-KKGCy;lLG% z6ggPnTQ(~d+Rg-cg<$7NcsZbpEu-fSA1tjR#n6uN6d4lP?iGj5P<9dYSwZ?FLLnmn z>^M~4{Y3B5cFPrE1DMxZ{dAG+1=lwyfo_@&s=i0D-x zV*l7*!f7_AWk|z++ipkIR!gVeeWbw6isomF-Oi&PO-96QiuHJ#0rkloGp;2j?A1uY z81i+UFj(7L&h=5i;oM#R*#CWpXK%f*@PXqQvhZ&K!zz;vR`)4U^9jFMLf~Mc*g>tv zvNBUo|1>~?Y*6}BXIgzowtD-?4ufYzJCmn)XAs-WKJOp(%yKr^aCTyBYd6|D!Z?x( zipE@teI{~%)1~P4&s#aB?6HF6v;VJd-+v4~?ejU+*XSAQ(d2{{tr>(W6!Y}9mQ4PL ziaeKSybHJ_*=El|h1;_vl_I%*9ljn&8pj*Tw)JN_`&jhYm)_yib<;c7a(Mq%zk3f8 z2u_54g)PlE@O*}(wXLLUJRAa?J_65&=G=dHd!yhQ!R;3K8x??8_S(N9JWQS6cE+;F z;P*>0*jUhZZlt+$*bf%*f7sp8ei5vmBwVNxnIou5Y@`U-=6h{~?`3_cOnL@wM^P`6XZ06f}c0PRYE|l-FZ?f_;?Y zn>P2*d6pye7vnYy( zAU6Ql7V?)to5-y&?lJ^()$yfS0vUV*xue%wgZf40oJK{X4Xnfd-HDl&_`q054*BJV z&SjUgY~3zfWqr>Mv>U-yxo&4&xWL&eF3H8yCG{zKmcijMq2#RGjD(}|oa^#bi79Y~ z#^$`6vyi0GQkzvu-5vkzZ4rFcS!Lqq02sS1z(kK>X1wwHLo+>AH!b~}T=J+b5NSKI zF=)$v^}f6NVhIMSvF{UiN7^R@@?9NY!3wz}DPl1IHoWjx<*|IFPRN;jkduWCa7O{u zQTZj2Hd;x}JtgTCY>yH7}2WnA|D>j%;azu+j)Z__69jbi=}mh+)X zy05&GPRAxrm9vkD8$>+l?3Zr{vNtN0H-FIQ%DlDoy6~W2%zR<}ZeiAM6{u7btIQvo z7nco-ka`ts;xMyp=J(H|8ZU1e= zSb#+ayvosOTe75fzb1J#guF2* z?NLW88CrBzKD81obH-gX=!eyU$Zq7O*17$0C&Ig;!-iZ>Jy)%)C6<+@RWE#hdOXjM z4d71fnZ8jL|5voOfuiLOygKr8{}x}SZ!4(otA4{4^lcXJ(!MPSr)KqF*{mi>f986h+^OyNsI0;@=Mp~S>xl8dteCf%c?K7 zTk|y&boOBDJdN5PTp>grCby})7h}p^a|e^gcA482!Ouw(k3u2Y(l;)>JcJp=tw-3z zHr)ew4+inHiiRPS-qeFZ{5>-U=EL*wWdd1JgllW)WiTpy_@ql1AIfrA!)DT( z7V+bAD_-+*OU%Bhv$0HInXpce8+eCx{BlA(K#4pShpta){gsE76%KKH554u|heNdn zB))rfuLHQwl_^urEG<)+($Unl@6&~Mog)!wNRsolsQRhsZxT$K4p7z)jqNGI86ce^ z@iDSai8z865%jWa`Qj8_!-rPq8o}RGsBdJDBj+omg3yg)JypNz4jz*9P>YW4-LKt9 zgt*lS>tBX529En_Q&R;;x7Z$wX5H8TW-_cAuxge zQ969zQd7_}oETa_xM1;7OiS`hN_HS?VRNgk>`LDhnf=I9#b~f1CjN5^KQ0jJif}q0 z%|A;K8*G_EgP(EQ74L88&fG$@gKuL2@+7ThbhTQibPkfB=6j^Yh|NH~%TE&5pK6v^ zVuY>^&O=}kl-RZxXTK=_oL%YUvY`?n2gQgsH2@V+Bs8#Sm>xU|q}U_ieM6)JhbJbe2O zY?9QHqNMmS$KfRbYviZ5fKd)x3X|FJjCA(LmQCcVMBDMAkJvnu3Q$hVtBnq{d@vr9s5%R>Pj0Ayu>- zxyIj`5;cFnW{2Ia?ZNy|&umCD>kEdg<2P(|8#0G*MxVO@(WT+;Z{zna!oB3O<-wHenK7i!O5APkpZ^3_aGhQ`^pIb7S9{=TMuqtH=>PH5PyE z?D3vf%8a?~bPWX1bZJZ*Fbcl}uyJ!jt8Z z8|8FHfTQI&ocN=jVQ9axmx624n8k`F0E#ZWlNx!I{HmURNGtBX&<-W&T6zD8m2vUR zLtf^EeBH?nJThf6>Wi#NpraDrao`LT`Vx5csZvr5d8DLi+B%!DOkCiaGfl1X|0(L+ z?H4NGck8i$5!jNg(8mJZ-ksN*j4CxlgNV+^GL}Wa!?PFouQ*~SeiGL>iX?jswt%~` z3!5hRs+tz7FM%pv$3pz;iwTbd1jJ(Ior8tXwEG3tlCCvndZ_gt!^)=~a6u*@K27Nx zgxVz>n{hISAt|RpU>C<8fHm6y)+_=lB8}T9@Zv0YE`u& za^zM8R}Qihq$c0`ul8pP#W2!8{QMj)FOL^DO?Bxx9!FLIKhW787Uz>du|mn%IlF>< z7Ai(NEC|L4X8sUc=Al`L=hYg0)H#PH2#4A4vo%KsxP3g*%)ya#$p30hJ*!EqUoO*K zw9tz)(yfXsZf4>wV+mJg)uF_3{Ox153ZXxCO|@d-UnQ(lGO&KWA{y4c!cvXebzdt{!%)?&~(++K`I*WU^rx0h312r z2l4*QO4F5o_ykj~f(?~bbio`Jq(9i$?Qwmq&Dd}Z_>oD~dR&ufK3XOV)WQFzLP|TQ z0p@>z7zP0`B-}-p0*EsphM}U5YK3KAbBDL9tSScB+cYqhoUMMNbn5ADHMMoK+DTD6 zt?#v`+=)2XXXIdf#~(C#`Q83Ar3ZEi^=c0NONLPh4`{13wakV?|6fg9YMFV`P^~Wg zBza^03z~=VQW0td7PagpcEPkceWMNoBEbc|rr7Ks3gtB0;p#H3%KfGM8BFKGO|MF{ zl0@2?t04H!9TPG-6LW?Ipnc0R-ayhLc2r@`Pkyf>z zuzY7NV2}YrroPQx71%npd!41(5j8|iaK@y(_ zk1#b(b@B%HuMN57XKlODeJ2n`bMD3bXZA92pA#kPQr~#@Q@9mYfG!wT-IqV9to1l9 zc8M$r(M?e)91JebZ^gfTc}ASQ5fKVP)&Wa|1Og{=KmN5h9NZ@phltD%cYacwf{9Yj zYw{C2m`OJLQ>x0k7ZNcE5XJ|VRVf!_CZ^TQdgxXd*_);9tL8M6^u%ZM0rdIuK_%&n z3VVoC3T+d+ZK5KMAwUb$ifxu`?DTJ3o7GT#xa1gMK7!EniU%A< zv?SEM^-}74+3Mj$i_6#?D*AYqj!$3gJ*$@89Z=`FaI~y?Elvn@fe86B)o8vj;mL;% ztjis~q`(bq+!@?@PmR4Sw>n-NA+hS>-tm^PMJroF`hb7X$kUkzQj4_aiLgxLi+%Pq z?)x5*Mq&0*vy#HPkidX!H`B-D@(O|bBJh-sP%D8 zU4nJ32utj?=}BK(i6_;)L(Z?AkZ+bJYfu&jK>4e4~<(X61zz?~iV0^}$r0Cd+2eulrvyUdWFCXdH@4BpB?&mAbKFFX1 zOmSTWy>@d|WxnsgJ%25U=W7iPJS{M!=-uG@G^cdZ1@AWYJ{ei{8<5Ee+UMrT77?(t zOIvaI7WMgpQ-$QXoQh>X_Z^o3+7(IM;6^K03!t2zyTBPXnJZx25H5P#GEZM^9pA-) zOH!jZPOT)GR2im12pwjVaCnj3sf78&epVk5w@Tj}fxB^nG@c5_CW8z4X zNQ;poWd~t$J7N7ku6MrioG9P$pgK95KX}$vq}>+AM~(}=)#Y`W=(^^##NecLciw%| zxu`SkpvLUDvBmNn47LI6*yL=YJDVMud4dX)#_ha${g$XrSDKJ{5{ z?e+`~MA=HW3$rcztjj{_$e6?d)J#B$0c|300fgA|;(@`h3=enMUNdx<>S@Ji?#KN} z^JrX2{gQlGHx-qyk)2Ay3Z8{^whB4C7dm)XgXSp64m0anxn=rd=gfsH?rUEke<-h{ zwwzP;ff-`S&YI~f_PZFrkYV0wZI*J)?sm{w(Vx-gMxmTp?j zRg?U!hCoVt-eGnvaYQI{th9xNea?l5o*w*oX15C##q}jjcH17^yFXr zvYS4nb)Fl@V6edaprV=2yIX(pFe28$ru6X+dB}c>lQJ0JmY-e4EC#%_4SbIY`544- zo-?7@%NA7ijx6N6VbcW@I-8!Ud3*ms%u&WmmF}GIV1K#`f)}}R5~kzGQmBiI!x1C+ zm8y0it006Rvb9ZAKr-yY$g$~dr!0qmwGs8Oh0CQRF6 z1+*+_K`D|rFWR*3rM$-HQ1@TYncfa-F%;}x)7|T7(?zvU$#&8g2o)i|KrYIjRkKC- zyY0A9ZlV%h@sIwISBmo}b1EiS>*m5+5HOhP{8;cL+>AU$og(JA(SPk-PlcX{>HLo- zC(a^oRO=EK3Pe?xsj#PW0woUQB(T8e9#huG`sPG9z$P>D~ThWK9>Uy|BJ)qqg?;*O<>G9r~LlQKA_Y|Z_Nd@ zqeg99C3#*+#&i<2HSzozx5?ro64_BkgrI%vAc|;fG;g(;A?}2C>{;h%(VmMwniZCo z`MbHfXx4C+xgC^>BF>FzJh#Lixe+>Gguubt3*vy7IeRWgDY}7)z-Y05t@gyZF)w(N z79HZZCq2`x@2A@w0G2vVu0cgYvJmvMvhzI>PJp;f->RU+iSO6YuR|y^p+2h z$&a%lVuhfMFTIy~JuzAo1A24^at_q<(9Ye>S*4uYeWVUx-t|D{-qTPlvh9gZtl-k^@fl4$cVAP3#eu z4~;7A2YcpHZCJc%ozFyOO({7zWD*}-p;f80=oAG~n2!M2z#jjuwBK9;$m0baJdg?Hj}_)$G7VL-GZ1DR_496S5_rUgYUd=y<1Vt+Qqt>gXd8&#|$`EyeX^; z{GUyV%(&z}xehppy?nIXD zq$g_r&#uh6Po!-_6?F=#I*KQ{Jqi3oR`rS(np(?)P?w(Jo=oQxRzm@!USJwK3@m`c zdoNAm=MPF4EKzd8>gmLG-~I+rZ%5pH2bJ{aSac4Frba5=tO28nxOU4f-N^Q}R}Lmd zND_xH#I0V~{K$kT{l@Qe@$jJda;uZfWait3pd(=IoZ?&cT=WMJ%pyc&+=n7330wVF8BX*HekFhGxYu z)=@{}KR7Iq>i>Q2USDs7Dpthm&k6A%9;ZtOzhmXgdmn-BcB7Z$;4Uzy9N&}qmBH3L zT19jCzQDgyW+lGt%Jpku3&rI1=N009Y`Z&$zpbk3$=vyXnxYPNX0uIlbE9|1I}&6( zKujr~HBaUy2b0om&_1Bu5vgMshyOVgrx3xJZCfHe*#@4X1T1T7UwhIQ1NvcJ>(GU? z_5}$5$bR~SBJz9)=}5p?+Ds$^^NwQ ze6E-|5alTU_*K?VSYzbjHB)JmUZN{rDb_Bkd&W<$ADHdClrwK<-(B8QmQ4>dGDIg& zR7q739}duqlYbNVbRw5~FvYey%W=n*@+?PP$|lFaAvb40RM1m;O~|w5>$KfljtO(J zTdfHXxIxO%^9XdtzW`$jqdA#?5r+SCB_E5;*7iBc6<uYu zud6hfX`&)~F9V`4tHv68i$9Bm!ptqk0u%HPQ|Z30i5nd@>(p*Om8s{^z2!QZtx3nR z@i6}>6!%*cc)3vQkE+tGG$ME{ zxI^V7tj2q*PkTJ8HHnL`OOK^*k{h3jL8ld7U}YvfTPvT0QH9BQ+~KmJABz_#>PGwt z0>)-d7Vh;fgX;C-sIkp_CWX@)lfV#_Oran5W4=Ri&kZ`KSe~KJ-^LSSIPF=<##(&Z z0D62B!06HE2>{-WU1ZVto=&`LKe_7+VWKts7nZ0}!LB~PedoO(`aF6&!n?O8jzSBC zvLb3I*8MK!xR+W^+hX$_?Jk+3*KYwi|FU0{y-Uc_EgyTlJgB+uBb|ncXJhO1y?vA3 z>q}cyeI;!1jR66(mv2G^SaM%FysMBfiS)ER49Eo>fu}ERf$#FdaZ_bxxl++EmX%Pm zK`mk1?eKlKff4kyWv7J0#!bFL@~eT*CuOSuJYUIC=G0S?9YdQh67RS8+gbga6}_Yf zZml-w?|%Ua@2hBx%6*=}_~{;V)wo-kg#aX-zFSpXY!rNnc{4>A!3(OTstuIYyoJV9qNBYYnnbXsW~0w zDW7Ta!i$hhCON?q$(J4@5)SNY)9-_kI@*ay>s>l6==_&spJ#cl5*SLl^BFjSiCjHq zBO*IdyCu7o2`oo!fIU~&wz<6jR1f9Pv`I0;ep3Y$#9@u!S(Gcmh?4E>zaYw)>o``>}=II<$OTXCO`vFub(;jnhYXgs6$lt+xi$%re zm&ME~V2M7<%$Hf%`Knab)+LW#-Utfbo`f*CM-5)!~ky%&LzYHfRy+sMhGbNx%#v=To5 z%F(^RiX1YFOYGU$S3e%TOpqIex+=aoTrV&Q;)xFY+OxA5+Q`|Am|N<$Kem})(Fz^3 z{@Q3u{IZ6YD6~~Bs9X7RF!#64QeE!MICUi_X_8piInK2Bda+_d^vtzT)~ztjf){yR zVzD%^I?wZ6P&REt@XTEq-AV4HXvHzF|8pwV^Od;46Aj@RPU5 zU_SH7c8E1|BCc77%9?xR@*L^s!Ujyf}hV+OBkH1I|6c@4Al-YF-cy>i(z)5n}R$H*1Ym>Ql0a3U7vb4JG9l&NtBn}mQj3&MY-y{Mw2S7Z0C(I8&i45>z zOB|kxQFra|*_iSOpY%j=0_hK>Y=w-EqL%4> zhy9V0fOylDn%V0j^vx7)#|6i#^ke<#vRRti)9I%mnd17Bv!g!zjPL1wcJ{oU zwwyXK!mk%}0o(d9P;QB#0o78kJgyD*6|Kk{bC1lIBL*}wz|)cyO!mSNH6X@oJOBqU z$|Z40$%So-U&Q+u&BO%LGM0h}L+0`ifg zsH*AzbL=n#P@k_w&+k=)bR}+(E5Xt^-e&Vr&gC0vbZ=YEm@!?lNj!u7ZXbABk zL5~`PYNx@PeIG?Xu+>*MzNde1bpLjFQ0U%+GVFjBNlMMlwld||L&_CE&s#^iSX|ucpNv}e?z<06yzHVirder#$3D(M`HZ4aaIg_i~ULeN}l!- z^qRGfugi229yd0?kW3cF?Y8i=Q=&SCFUAO?`V;GPE5qAOA>5t*WQ@lpeT!3-s9Dej zlta~YZS8pb?mdHpV_$!;QAnrej$^p&iACRy=f6f!>2_ih*Xr^45P$~=Jnb^*sa~DdyBG-j|-^!o|uFU*>itm1^wenzGBsM+7vsN4 zCf+nN$Xk0wj{nHz<^m)D?3sV3BJ-e1ePKl&2Sp#{BB}Ov z2|0_i(gR&Q`VXmJ^}@in$kB5iiJc0G`*rjE+7T(q^LIc)=DbLt#}0nP&qAxs?}}}I z>+k+p!k(Lap*13q`0&>T;Vn{9R$cN%8nn+rmgO_V@6eSQSN~bPj>YmORZ|+84lV6H zNdCq^ec}y(vL5EQl*~XBUN)W!j*BZ*rovxj=DE;|ONN4;@*OGr!>O`y8Wk@=oT*L2 zM%U2in-nMh>_o=zE-#UBJPN0oP6We40QIZl#Hf$>F~*p9`~xXCXS ziqTVTgi~Szf;5A=@Aw}Yu`6KA!D_z023Rkg_OhjaMAVJO9d~(DFTL5~1>+zi@V#h{ zWchPVA}zASu!kf(*^d;K1G~R_|cupka+k3+ke ze^n3NE?}i8cjM~VpqyNGk1(^}<(r=r=poVP!F`V&&k2 znwWja*JraFx7n^dy10h}{2Re7sbiP(OyKr&?!8njIGWNjcSbC-oj-V~JwV{d?54fi zpUT&|#44ME7&Mo70O?r4mmkPQ+K-XjhJPWuzQoK4L%XpE0vM*+OYvwOr`N-scT1!0 z(%6gG_LXy+E_VtK93i1IUb-9zmc~}%qQL*^=`TM12~kupp(9^L4kSe*NJYHje(npl zHWK;`B(Z*<`j>%=Z!f@6a*2$`?<~GWqCeae^y+~(U4YdLMxg@FzPtadsEJl9S`~jX z|G&+QD+l6dpc!FF5;MxTv?D)?UXRR!)3@2gnMaSuK3(}c=5|cElq+$uFs-60&f&8d zo07bVjDLwO(_A{{&V665v+FGV`l_t-AU0J9!E6)FXB7MA%;B3v?KjA!^_o3vSxoXF zMoP5){zNL4)UC#%{a!LxKOZx(Y|8~>zE+uFQ1xq^S98em1jY`tWj>23S)u?h|KU8_ zG&u$MvTXaBAcME43Oel1?e3l=sq4o*Q(bi+Yslg|b+8@ae6THGA;7e3K4?qt?~mZS zP!$b0UXxh2u3mft2%n{5Q%g7ljoTdkhv_<#2R7fFpbeqJUQ{tC3f6#?2(lc;k_J)n^OGwUo_1c^s424K?^ ziSNzAI-;a8E@b(J{&cm&U%Cd<8&KSH<>c{id`O1=9QP_cF;T~O@^2g|t(4K&qm7Zf z1{1vLcdvysY5$RDY5m2?2>n_Z9f+ik<&VzW2N7Bj{No7guwf7;9$WwUZKnQVhXwF> zWEu~j2m)d<#G>KRuj&i|wxjxhYAUhXe2gkLajp{vvrY#Y6ZjS#eDNMj4Rz+Slq0yt z>ltEyCKwP~C=UP#gD{cgeMcx0%f=d2yke@)Woe##(|kTgyUTm&_9@xu zOY?C6O5m7zcD!_Ee8X5+dfi8zWfR4x&Ezzf;MOoXnFv55(>;ws4|kyrbGbPRS}PT_ zcISYptMQMacPbJBcT%PmuyP33$nk~K;P0dC|6X_5d=adu$M2zw2e?`JQXHMN_gh}y2WLBNMqi9gl=f@>opA5+T?=V;r%P}P05&w#(ypourtZ_ zdIqX;4Frqp#m;f%IZ19qM*J*9oj(+5ym`<5?d9zw8^Olg8Ld0bt9>Ifz?!Y|g`{*^ z-ZRO2E5o6)Das7d1odVC5H8#TU~TxIW9BJ$LsJiY!gi3hjYh>ct!qIBLCu7m6au@% zAGvQo3xcn7mYOaJCD!CAE>EaETxauu&lWDIP~+)A0qnLVt2)0-glya^zEdFcoBajJ z9)-o-&Tg?WmJY>L^8xAG7aYcGrs5+&zaw;cq;VqY4N<93?}p#z1O^q_?q8r?D|Fv0 zKK;BvfEiQ}uQ=Au|Vs-a4K*a_W%tF(NAI@w3(Tb(o*Y0(A4)Dp8 zfUPywf8CA<;1eD{9q@uc6(Qh>lYO>fm17$-?oqU!+h;_uz_A})AJ+N&XKEjmOy?yS zfpbgjgJeSaO7zNQe`+8kVz+Ou_T55Fj@vsCs)bPB45AMU+A%CP6v~X8yl{`t15Xe( zJ-mMk>*B18R14@kzktK19OadKhf3!&W)vnrM%Qd8l8XL*D{i8B8LjiOrSTJydmtip z`_EeS!4`-8O{^d{$HVNjCnM&$$K_ox ztKe~>B~ETf3l~oS8N{8wOW4dBoClGMJoS2>c)#t`Egk>KmH$>z=$|^EyxY_+*)5VS z;D6VLWLM;odK!-6k_A-66+oRyTAM>x^#1)aBE1!2aFh%BfO}|(yB7y;m+I>3`Ck#F z5`0hy2b#3At_ZNpCi-B?d}fU@jvj#OS2;41{F+{0%I@KT^61lY;3hl{rDlNc=6Xm$ z$93%lT)PSfZ#@{)tnaYUSPuLK+&4{l$o%nQr@2qpJ^;*`Dc~m-!p_$Z-IDm{y?OLc z5gd03Ml{RV(H&*raT|vDUKzRb?=m079!4^_Yh@?bF5u+dVHcpJ&Ij)?x=k7C@&H64z#QhV>k1V=LBOi~H=uabBFI5YA(ZhdU zzS`&KMPmYpx4t%b)y--Va`JPROb?#vGp^=3yz(*1G9eS|pArlUt+J3t_Cv$fqx;}j zyd+VU0GgKga?1ErAwm=@jeKY+_}9DZ3-*@_9CP^$=nH|*#u`QPCAf+C7a zr+;ddS9)ASA~ABijdybT#qW3T3DWnvu-K0I-g*rramEa=+tp<^*pRlD-dUwN0}p*a zS2uzOY(N2p963H3;MzwJpR(x&xlLSKB}WJnpSISe3!PgtWo`*!#kJJ+Myj~21KW(EcfO@KF+eO*o$$IA9* zlqY;zr~L}Mz^R4duic7inhm6DQtg!P3#&DTC`6ZS-^TQtg#sl3$9cOxI$E-C z< z#HV>g`#2JVE6ukA zy@>Q~Zb8^!uw8ISf`Dnecece+1`BZf*ey4AFz3s2($jTw{AZcGA>{mD?~J!}g6`X{ zAF=P_l3rn5*OB3JGN6V%?mPe*a>c8^dFN@pLbQw-N(-fRSeL{#_%D?BSVGsZ99}O7 z^?z4UlOvvSOvq@KJIWCf>j>-hqEu6wrNlhN!*(0JINzDLm*4Q^T{-b@jad6uDkdu; zd0Pc(Pb?B2sFyfwtZV*$o^jZ_dHqMsO;>P0Vd77O3q=efiRPC0sdij@w#d1wa`p2a z)s(1Tnq^wU-;|g_1Fi9R$d65zm+-)i`F)%y=Hagw@s#BYee&i`y=JteC!z&uT@qpz z{VZBF6^Jwp`Yt+i@8n-toWQI>pNmV)>IjPn9dGsGD< zdEBnA+vaz*BtwP5PqWad>;_8m=HP_g4_C_f2$6@W2Y6Xr{g$Fx?h0rF;7_~WJ+i2g z(qcuWbEpwe#ET1pJ5N*-D`i>BDutu6?wA0zi!0g7PfOsj<#}v1^Ya7Hw3Hy^_o!Z< znX&4?;?u=gR;uRy1&&sS|I}h&Md8aEvU4VJ5RDhfm^$CWF30wpr=Cm&nlVxD!)4g3 zR6Z^gdyorpW)Tx|JnPl35v|hwL9d8)#~6dhG(uo5n@(c@|u=oqerWnES=te0+tpYbi5F<8 zk^cu=h^WZ+8`_&G*qApPLrv_DRs<^MGSHDJ z{kkoUbb0nTx3*JJb9r;&3}byJC=a0)LC5B$xi(Nc=`ppq+m2MSd^;_l5VQ+&V+@x& zK!rsAH#QM+ISM4*nIH`^443%m-CHj&D3)v4(ZdMwzd0_KySgs=4T(y88m|J36e-`+ z>z6!4v3V7xX(LKi)Avd{Q2lI#;^ z^PHPu$Fcg<7E0l!eOweBO)B^-`Zg0Y)Ayb2+ro!N8)TQm(*8sOrswDeXDj;J1eF3R2fAA+uOFzyG~;|x zZh!5{zJ*2HEPl5GPF~6lMnTH;}hOHRmsjEStEs!w_d!c9U8n2ONh2JmiUTjKmbc}QqxyD zeVvTcFQNk@^S=Z=>NM*4{mgy3yl5Ry-<$?kUN@(}kUi5Q9^R3$KmkAq*vFp&`&6UZ zI!3?N@RtCBG@V?wKFdQ7wFB3SE8o7IK%{h2iap!0rk%Psu6H!qp2WU@h>h4&hH6ijwH%5zG>sd2OJGn9yCtRoucW1%1WmQ#34Q(%%g z&Oa=#TS^2jY!E3#T?`|2QcXJ^g>J#q!$Q#+u+16C3UoJSbT^)a{JK$vdjB>#w_TT1 zm)Od~BI0A}!DN(QlUe*>Ggp);MB#!gM+P4ByQk&z$Fp4GBQ~1>v1mDNbKH^lz9^TU zFzZNeV{%)YOtyIYrM*wzF7kb%LYJ_3SQ<7pwuXqZ+_qFzin{v`@r`)5!T=Xz+fY-t zlSC8nD&Yo|{lG$)L{lKyRRVeHJ=uQJRsEbqWZ)X2`sO18c#J*cc-*n71_0v8-H#*~ zF_Vu(uos0+kSCq{Gk(RkT7SDHal#?IBeyh`z?)-*)(!C1CkRY+C5Mv75^^RxN=891 z)H^Yl_mMeI8hE>t*wHtA53Xc10vz+dlnbr1F(bjRhcr%1VwW! z)Fj$W4mrhXdAwpbd^f^NhR99~$_Jk%45m~)?yKJu3KaX{o?bOt*a)1pxjb1C%-J~B zp==Ll{j<6$n%$d%l~N?f;S16VH#Zrer|l6>>09zPHw_zTBfOAbZ54D4EA$AJXaA;D zrcqXSBvfo1QqSACUuV(#r_oXW_-OyvyAsa z?Sr;3r3+(HW}g(3LrMPA-WPFyIy!)``*yK)rEe^aPhVSC4Z`k!p&iPT1i6$Kv24!V zHzhkq4|#{dtD;d&2};ykyP$&sOF}u{fJ607x2c)m$I+gPR2N_fr?%NIc<8mQka*u~ z-#pm%WO}> zK?mlW33wj`e>JD0jBp*<>~h`G^c4qOuUHvbSc!G-Kq7|RxHJiYSq=;!MSB00VIv__ z*lT*#uwZ=6s(UxiL^FE^=tL=3-OUBPPL3~M^8>s_!UI8VKVKW0UcZI(u55O9t_x`& zB`ZdRz2mPR?Vg5sic2+*p@9kCa54c?D@<%1*aW#(!K{`HEmnSi6T^{Ro{)?nWDgziXKr>%GlvC?XP?>)fR0c0ZJ@xfV?#E6f^OCr7^e@owi)aOSI z!}*(uo-dDdj~@v^+mF>4b*;>w%-o4AP1UniRq-kbSb5bYAwUk?AoUEuz#N&+I9zr(%=&S-xgce#+yf=XLHEag6U4A&3L*v(G1 zPL=OTM2j)8E3sUEPLNfl!e2KG$PF&sg$)h1K7@GgA|m6~Bo5a^l-$VrrFx?P1C09o z=YPG(Cqy1pfGfwiC3TZZ^5pg9MD7uNd=+cjFPXr5{ z#Ti^#5A1eSbf~A#FI}h`anS4T>N=8OT+M%VR^VM}=T;%>C@N66dwA@z9OtI3H+R7L z0c3-j+j#A$z63J`DU{UJAkW5b?^X6*%it)VOT=wcj{mq)JFVigRc4O=IHR8;eim99 z?S7EA{rgdI>zy~UXInWKMLxo65-7fz$O5GTnubxU^nZmsv zR27(d%6)K48IpEN*~7&_1e%;x@aGnU>yxM)SF&cWdv^;P1t8+Cm)QCr zloKjblN7Cjl1AGl)@$$6TNEB@(1osB4h6fXkPkKM(cHow2PZ86D@#G zT~KDpuP_P8UFbCUk3ZHge{8qsso_R;2I2r$5~l*YZ%T6WG+ej@g-l7LWV=JcPkTnW zd8AHeOHvw%KNHDGXIP`aDT+#7$VcV3*4(#wbv_!iSR%bBsVC_;p=%u&`a7=Fl=?8{Z?9<02dUzRvUcux8LkK?7$|9HPW zX12Lmi~wkn)}D@vf-gy2N`U-6+P5Tg&9oRn9A7SB1>bzSwZ#BY3Gi zz8{X46${Vq!$S3DlkzxA*B*bF7W-(LC=vT}tFa98=4*v#HM?Cc1>ZshB@+?=8Uu9fyG5#b#EIN zo)*dpu61LDIrt2zHw5_)0LfCm8Qz{gb!e{vlQ@6#bxm%7rhN8b^0Z=_r;FZ_q3wK! zYcJjS4l(F>+%DL&{VsrmFi3OU!|Lve=?LZ2s49CywA&NnalZCjQ;|)LMSCU7GB2eB zQg`AoEKmBefe5 zS0M3DbHr`zY2gQpFPRe^I#i&aqHFK{!4Q<(l1rr*$^ZNb)nGyX8RJ>H>w+^3mnqWy zd@0h*u9O)ojpXW2A{P_aFD5Qcny&*W8RrqGG=ox4hB|be?s7xg&FAm0qV7!0r2@!M zE`AR#c_hwSdzG1JmOVDp1Hf6Sk27=Msgx zWqxj1-c(_&@Es4G{zR9tdA4O9=j4OWqUwD|sz#q@)Tzn>nqYCtb{3H$4LlmPbCuP0 zNTOyEV=Kego4Qj6<@=ZB({xI}ohq|FUfQ*Zsyuu)c*7|+0ufJ>-xK3d;>V$zI5T~T z(=oVlNg4ks^Zf32i687|G}C!or(U-<_ia_TB!5uo^J}>90RlSjKM%a)jlav^G5g|1)>17Xth$#I{cxI#Tn%Y6VNwC;>FB7?z&l@$AWf~-PiOfsfcMfm%58__q^`D z`?kPSI9je6;I0QSHNd#hqrI^I!80q2;fjj6R_Bc7vz((vM1X+WG^bTI{TdJ?qhH0H zQWY9Y2`D|;o${a{LOxk)5d~lek~YkFk@2Dtxunihr7JbI?8gE$C_xG3 zcI+`{c=YfTcp{5!9~Z$9?r7mka_O^px@{=wSP}qLW?OCVXM~8l3bdQN8-A>Cx_nN= z@O@6wOb6H-__tTA%LjfK7Z^m~`+*F*iqkX==|GN*x)Kk^#^DavH(E0#tW`%(8N(T) z6Tj9JW~kKXG)yb`j|wHp01qS%-LxAL8>J>W|F!r%)8ZID%DcE8FciP}-jN(r`{I{t)BLgG zVtsv<)xc+9e2X7kx*mmit^a}T-pXMCGjCJ$jYQt&t<7mH({F&@oMd--5#}27_L&DS zyqE~YcmhtLTOI`-gQS@?yj;q3iM=zym!Md_Qd{OZ2_%_dZJl$v`AP`Py^kmNZ%3Ck zl8}o=p(9F7fmku_MPw6D?APH8HuqJ(@;MVX_vX5ZkFSgwuWhWuT zJR+eR%CT0x^MYFJnZ6t8$+c=+;;CaGqNYgqn6Nb?4d#v0G~em_dzw36-YplMzG=S2 zE%;rnx0Ht-87G4|7SoeAq;4srWvreWToKb#qc(XOs^1vtVv&U-ZatBV zkV$IUh}7ual8i$ah7c05vu4K5q?8}q=9Ts9woS6GVd!|SVP>>v*&gb}qUPm|CM;R6 zux3*ufFO&`9yDkXt}3s2ufldG;SkvzM%M!wR~kyU)#AYCHg3g+X3(mq z4$L5%^z`tRdv(Sa#qT?3_JX#=?waOCNq6U@^8(C>j`ARv@Sk(cuDm~$%x`eZb>or) zDjmjqgGg;=Y~R3^wJ4nG9w)iBf9_8pIv2gHzV+8z#u{OzFZDsGNHwpBGuNypT+y5* zocWK`mesl)sXL&Us7s5RDiS{Ms>KtqYkIpu{!9)8*vqoCdp@KNF6+>%Y$IRd>bLl@ z+1@g~hFSL1cp#VlLQd{G1-#x<(vjrz%!l0h&L$P#{-MGJ#@e`+@)FWrXZXgEzu5X| zq5Zt=)BMr!1y+up;aOfRKggiR(&&#>1^IIymCHi!X%D`SY@L=@o)mkF8b4D%21+_s zIQ{t_sHh$2%o_vJO}Ehaf`N>13u`)$JY zn~7+)#=X3aa0U&ms=Z29)4KNbdPiJ)(w^hRXlNXLI-Xs6DA_@XGXbH1<_Nztw;)oY zx{Fbet3;&lIs$_+Xj@$IB|*0}fe~~(xIXw4GVAfOHq1j%$6ppI3;QsHX!!q+cc>T0 zg~4AmV~%B^|9TIm+dz_vDMTP7j+ptq5&UD&5!3o~=8h_kZ&;qj?sS0&P=*TS48MS@ zM~!4A=S3tmH2j1`xdHdDitTn^Xvh7&T1mU8In{(M3!m-tSaMd6E=SlgjF&)%tF|&O7 zf)9hiGi`SPJTYvDW>hKCBMF#7G`!L8iRT)Ek75L^Wkrkr15u*P*;crEAeC2ZYmEt# zIDPDsaSSMiAJJ3h3_hR8nLG~$asLoaD;8jhC|?fm`RYGN=fn6TkT(&E5aHihe6FtO zAP^ZwZ&rKF?yMJ9?Lag}Gf*Qi)G%a@W_`cYiDQETzI+Q@#`=B)2(E zL@IqFz97&cnJQKZG_@$D?$iitf7>#UBml%l@tM6euqgQb>#H-A^Fok&ynD&Z3Y56H z6Z^d|2s}Tl4p)xI@EnNk-Ko)Fm_9xF1a0|xA?}n6@wJ{AuWFT*ZuFmZNEL+VW%8a= z0U&1jaK@1(o*pWHYV1Ocz7?%=?h4J#ymd*6Q9pnYZPKU#ZXDU}hfRT*L*cDD8D>?% zUDqy%AHOM-8l>K1$$jK-iXf{+ttz?))GYW(d$x=}<%cb#Eia0zX2_-athf*AqSL^a z7qdXZuFQ|HSQK)`r0!OEj{~@KmR@nT2?|w+2$p??(Rg#0%p(tol9fTO>|P`7CP%UV@ppW}cPu}pn28%U4{SuK%@z4!jWlC?KoYLN-?;4;%Ipf&#ZLHA{Km4e0mz_vbCyH`fvkqfw+x8T|jI ztY3u*1k!!b^t#mlJCag^vPc2@f<8i(A-2-PUPWZUSNY+r?Q}LTNpSq*cZi>Bnllw6 z0Ad)w7M8(E9623A0nrw1e>S|6|I<6rw< zmizwlUR80ob{xrx7lEKm{IqX;_gu8aTBXFrq&9K9Gv-3#0iVi;NC7CLaUCL%SMu?|rz2Xap;<-NK6~--i7DLmZkw z&?NEvik9_XHSj#Li*DrZEk(*PqtmI;{GGUxIqp@_7tK!}00%VD-VK8BfnGJrZSdV{ z2@j}j(|yr!kZqPjnWrFwAP+V~l>Kj}Z5mak>W@YFZzkjSqmE$j=mF(iMizV|hXaHf z7RKkG^4Kiiz_3HqOedV?cVA$)SZUXBI{=OQ~B6$rpK0O8z445=pjx|{*udV zvt64Wk-KxUu+|+T1ard3IrF}wa?XTYmaI~pOCLBJ^W?ln2|7gT3NAcC5NUKB%kWD< z&L)hT>Ge>gqS3sPFQ<4tV)IdG$$qaV?rHc{NJh* zhj?Dom(y%GI>htAZ}n5H`99*z`8AXCYQ(KN_BGu6h1b@Uh=gpDnN5rM!6J_tZ3=$r zIzo3uE--G~o?IsONTFCgA5%rvy8~sBw4IIGS|%Gn_UM;JfS8^w>AuZo8%DzOZ#XHd z!xS}3S;CtWqFXV>x#Dg_${20rnrej;X|@NC^+!1<g7qG;V0 zj#6f++cer*rWv|K#J3H8S#+}9n(the5c@2UwmS?<+2}{fUPilcVWv|)I}t1_eshTeU2&`aK)juAiKPped@HJ zHaA)TH6N&L$81rv0&a&!yW{(7AVz*X@6nN*3@r-(vwBmcmvz^DxAdl9Tiwd#_-WtN zRj8tEZPjRgISGf^9a8;oyAQqdB`v4rfu8`juTtNIKuxMGLzfd6t(%}4I3nJRNxp%K zgB$=Bo{rSwBDnvULzqux6x1$b$7Dd!Kp38X(kzntC0y7Ah_$D{oH_d`e&^Fs&{r9{ zF%u+;w@|6=aus;0Kk{2_ccPeyk=iVIt0#`m(zr(`XWgMoIX!SnfI>F5_&mHxWDMg$ z;4rfKQ_S0#@?-nNk5=rz=rI_@QD?ADx!>Z{j@AyW<(V6`SNB)v&WusZzaJGJ4j1?t zQ)XGN`ohtDDRsqoW(gnIJvg-?^*$723CHqY93j%X_dvNyi8~OR09U#E;!1QvhbAmG z-WNaL`p!B;+uv1F*|5W*ZM4-Pl$77l_fyfLZ6@R4@2oYRJ<~~`Fn;=OvZ*td2H!+= zp&I(cP`1T-8+A!*mMfQ8ca4CHbTd5xVy{dLc8!a36Ga{f#xj)dzMq)H7qLYBv5u&H zoPKRuAB+kNVkQfo6>Tu)Gm7`ErCIu0 zHg~hJ^E#5Gj5up+7?d6dDraf1v5b1E4*V`n5QL8~K16debpR%+OkWfG3zf9BKdU6) zXuk+tL=tnX1(|p!_ld7I$X(JG)n5UDRrYJ{jL~mJhgUB9i`AaLH$zkj-=r8@+qq(Klwqy;1t z5$RM~ItPN%jUcVGN=f&IluAj+=naM-Igr?38~eTSbARvO_x@v#{Ur}MTyd^*Ug!DJ zhimaHwKjvQjS8h+qF0hOc!ohjcFnkP{Y$QWeo#_C_1O6PwOPwt0a{)wn^92%Q7p?m z%lw2(p$Y`$)tAm+xme($cxJUBq3DPVz$<61{0$NMr4Fg$u)1WZ82i9YPKfC!I%b7v z8Ldu|39aLe;oRz|bGmg48P_?dUGf&*iz&J*fkLI*KS8ho=+?EOv{}~u*|?U~nF|a1 z@MiaOp0b`6gc#gLS$7o6O9u<2wk*bYct5*j<>}mYRjjoh_&ElzT-B9TX+Nr;-VFNT z1k|~izyDWu433?nRp!Jg?d)zRFV+lFF3*gMT{f2Wn~+DnjwG?n>1^A?yI|R^mQw(! zROL3&#np_m3efBn~#8u)Yoh zR_L;E{pr``57x}?6Zz!}xPnXutJ~Rr@0p(LoBk_qm$)6^iUXvQ4X2;M5<7JN3cIUk zN!LbY3v*03#U`2CeQDB6nGRzS(l(8w6AfprNAq9{@@6W&Cy`tT^uziwQe(y`D zvH&Mxy}O3P-%wCNT5q?9fn+sX%tdkm-m*@na$z3@qsi&xEA!PCH)w@^;0N>$f0h$3 zk|UJeLQJpD8rXkl&EfnJi4&YekfN{*xYvmT38+N%m-w3VJw0Rd^wUT zj407B+VkQctNqegxB{XQnx}EG^H7_X#glJ5T_%Q)L)fkMQev4DaW_3y_W>D#nr7MG zm46bbaorMY*+8~nME-A@%s*e7Z%!{fAoV-$G4{*gHT~^V;)`KIrO;LJv@+7Yf93L-l-d_=lyPw? z@zz4HmtRviJlepd#U7K$3@kfy(M6Ji2G^XQx#>NT*K8l#@6j9u0bqvJHKoz#_Qu&; zfPtrAuR?XuOWMXW4DY%`fJE8S%hADL*@FcYjU?skBx^>HYYDL!U04A2`7nJeSx$xY$hlxp1v?S*4s9V;5@>QCmEXw#$OySyd*sMn6v-H^DO^QKSmNh`OWMeGuME;YgUcXc4_;92KU#% z8($`=WVxr04ADv@E3nGWpprAUn|d6b>$7vZ1x|U7EaGm@Ny;y|EG@SeU4%+kCLmc{ zu2ReGBBli4$@CNcN%K2DH$$;+6~76HWerHg&?}7uifaJ{Cqwy$Q;JcbvYp zE#bXsFuU;j#T(ht1fS}k=ZuYo12T?!0hfwKwga~Zj|lP*!1TiJrc{_HZjz|<F#{rlAE21s z%!DPU7!%^jn)66OGuFCX)^{K~XO>5Wu_Y%*{N*9r7fKg3|`}5l7RT-tNRDpe^vD>G|wgwC^8iz4x zlKj>fz&EZNqbz$ERK|ojQiDJ9mu@IOWu%x>`~Gn(sTQt1SI? z#BuT(7CAM4%?AnJKX!X)2lcb#Jq{d2!^XHAbdUX3{$Bgnw~0!NPy+cJ3^5DcQZGO;r1az7$cY?WcptZJaBtEchdUp@^AE7=$*oQBLaA(4t#8Ak>iXj z6Ma+??;Kyt4Q|(>Sz^(GSU%h69Ga8&!NTH#7cncDvlsY=@8R4*`Q_FTO!_OxA%=v@ z9X;rW*FQS98ybT8d0S*0LmufFcPg_Xio>Pww=qHA8xU-Sw=&GI*) z(=9wl^dk!pn0M%7#jUw~oDJB30|*a^)17)KzuTUR z+l%ygDSM2y#S2_?yd_?Sn%x)S%m5xps2Yo#7m43SXq4X;m?++ZR*5F94+Y0G2xeM| z5QAisD$-% zVc}Ha-L8urmWwS5;dOC`ebwBn15Jjd(r*G9m}rqvA7Wp&Fv7Dd!{20e3>-J)1?xBO zSBwT_*YsDR&;5?Lu-@YGHtZ6pa$M$g&BLP2$Sf>_s z63<8HlrFZvZW9mbi483b{tRR){JSy@H>Xr5c>MBY%GzLQ==q7dJ34}4c!yKYhR!qj z-dzIbGxSq$ME6HPx@b$I=5;J}SsrUZ#A4vlaXq(bq3Vu)(RPmp_)dTSY| zDi|hh7O4QU#QA->s0;?uuo2S$HW1YXbREXV{Mb79)vXIa>~$s@`(1QmVs_wmfSAEZ z=MPOC9A#n_x!CBR;MKl`o-Mh;j@*2R4BY`gF&tGMlads}lO*o3E9>LpN{NO z@ecc?fTaqk8Uf|BT<2f*kc~sM-}|a_Zhmh%9%?recz-D*_v}MX(d@R4NqXSE>%7ZB z#?IeGKMG~Gk4I6ohoyFx!y&9`O+sU zUj_i=4dZ`zg!kV>j~_lQFZ|Sk_LIFtraB9MQn=)GYhK}`*Hr*-StsX6gyaY5!;blY zCAMDm|17Z^%B!NQw6*64br3Nk6J{S|M0|Hb4rW6ZLT~;sC|ACG z;Ur>Ort`z8Ry_Eymo2bRHQ@Pvhn%m(A*Vgfcg7aMaoxjlB3ilq3m>?Gybpa%DJL`K z!BtW;{w+ZQ$8^LpVz;;o{pHEqvQqvG3EjN_KWpBhA}kW%l`8Xq@T5a-!*w3G>ihfvW8YI z2>1Wd*e1PdYElvL$*97)n>TjBf|! zo^jy&7v7suZQIT$b5^Uytf)R)a^q<=<(O*&<^SQBd~>Ae{xR#b(nyy;vES-pk!pbN zeg}71BZyw+5}7W#X6;A8eXk7NM;<{HlBVMNq~a)OQ*U7}uT0LEkMiR4oEIY~2^TVs zGa)OoeDmwf0bK1pc@%$qtjNqWF&mESbU;tMOr|bD%q#+IuA;r7 z{HlhC`7-);n=FJTXIf7NP7zBU`4xp{$lfK0Cr)33q4AvdyDSHx)`D`1iYif_WZu4= zcsT}Ls${`vUHWQ5jS(=Na+PI(tJjS>U{0xp{C~$KiCZr7scRJAfT(au>DBgA-?8CO zYLe^>^3HN>`&8Z1Fn-bBPpTtYD*1TgzRTS6Q`F5^i4R`qkVG-3BV z7YY!~hQz%Hs?&;ji&p9>)!wy=0_q+Pa^viHWPr+9)Fw=c07|BO5Y{}WTr+;mUaSht zqx{bny2^WpaxIBii7W|q1$dUE?+JA6?bPai7dK0`-;K%2^~p2_%H2@^tI8BA~gpIj`*s^~O8Q}zFNDuWmx^*BLW%3`Uoify`hWGy-HLXcYPqn5En$ewP@9qh>mr(btdTNYF z)G7j&mA8j(9kRmn^oCzW2^%AI2M3Sb0_;-T9aNGdH!NdxT!I{@4Bf z1L?HD*Fh(eg@Gm38l?p5UQbnTM8gEPeL$3+$VQu#O+i@Dy&YCC9r}i^lrO0-x#OM< zVUI8gyTy%=8)@=@`dA&Y zlSia+&upK(6Q%1eKTDU7Xcz${;de8d2*P);9UmDDfvJQR#o6@#$)T8&S&237r{KWk ztEsau3h(uNQzB3zYA?`Uv&jIy*+XShyx@R+^pcW6Qrimu@BoF24;b#+43l%3ATI@ z2ypfn@l}2+w_xvN{q$X$mplzlHip5eZnm;F_xdUVylY3}7uuiAg#*ednu?{4AgqvY zvkFuj(#|l@{{XI#kh!jc_Fs+2%#V*^L$jAX&|pIIWN6Y*cMArlB8j5NBM9`zmy-P5 zi~h@1*|Sb8ca~Lm>TwcKp4vhNfY6V z+)pSX79^B#Q)_m%=p>HRr_3|Os`#`lw@1`sfEpL2Ufc71W#V~WG{>QmoKH8W z-zRo*7JePV?nre)EJ?@mp8s`U#SASj!ZY2J%W!`7nkedLUYk`I!8FpP*C$-KF|EJy zx34r>auwT-3yJhc9Fy1-!s4vNsNpm)-^5MtC2ZQ|~JP?8ddz>vXD62rC#ADnr9e5lAak!TSUO_KECd`%J7-*A1Pj%rDgWo`T z`5Md4b9{CLw)SV?#92n)kgYx>#&TW?{t%4YEYvb-8d_uYI2C`fT@=%+=~sL8VhBsH zNhLb7Xx0n!SP`HqkKmT2f;vSj1;V==^)~SRQc&D0b&#TQ(yD%#;J61@;`Gwqm*}&b zOoz;uqZA$2q9}#N!7%2o-WOQVHv|uF+37Tmw=;11;%}`E7YDW|Dfr{gn}Mt7DD84P zr|g>~v0ma~Dn3{3X{rYKI{>~UMSgWVB}eq>p#&shic@bpO;;W^#d7()!~tYf-AxGM zBd=By4`%3 z%NiZKlX3z~9T_b|rEo)zfw;HW>6avgpU0oUFt0`A7ONj~1jDWLPc!gU^^FMJ7R$ntZ9s1uec!wIHJhj1PUA`&cTbfcoVgH5cmKuE%A5Q7kss1a4Y@G0 zO}T%YSy@UONTuF)iUxSZ^1`Z+&={#S_A_wc3q3IU5kSh=~ zp-+dguC((LeZ1A7ZfUM4kE({y)V1P_t#P<~$+ej^GY+ZA)qReGzego`Y$;vC`tfco zk2NfFG@X40RqCfdOun|5`2!~L8Nn`2PR4ML^}(nbVe*VBb{d-+#36Kt(sbZ0g#I~cc&(fW}O9sIsT|}!oV|S5HvOW6a23m7sEP!|dnMuc_4wqrJp5&TP)^M<$ zy-4%^Nc6~9prrk%9wb=M_~S@^B#>I&pEy&-MLnea$h*+d_u13HtaaJzMdx4W1|VnnEMx&p z-n40!wHYfWEt#~wSMz#nBG|gPITz8+d^BIBqmT6l%!0U=9!Fw5b+}nJt(_vpAt3exRq@nlkVNBOk%A09;n z+28xjR#jbzFuvdzOwl0?=>y#>I)|+GL-*xg-CqM!Q0|4$-NUBs{Z?kG;D*YA)&Ov{{G!(!0VxCH5`s4uje`3bO&PqVUt| z2*_@&#^bj9(+}fY#yxVn%#`g7NelHTiNfP;lDM?Nnzi=7^~O_N3=kNA$HpjSmJBs43Mh4;s!YjWEc+A{$(wR zx?}wsDdZaAS#cT1^-|i9Rc+VhJ~4Qdi6HxH>@7Ov;z>{?e$`Mxb&7A&4mT$D=JeO2 zoP+oOliuH?ysk}|>;PAVs6eDM!|IDS)Ae59^YVwjMba*L#j~Z}AcJ=*i%E^17%#TQ zrE7=wd**$$E4X|tIvqZYM?|*h^MnhB&FL1}GX1x!Vd7sW!$#H>ld>c(Q#dq5>HCgA zPUEL^GpkQWDfh0G7^5sP5?PWx2>rY*Rv*o&w|iw{4;c3!kQ(ed*;rp!lLENlANu?y z7#Y0Bx6JfdVlE^sCU1dpTw;$-qbgW@dBm);$!T?W*y0&_w{(Z|+$a3LFlTuliBBSI z!svL)F~$#U{Y$f~f^sIp$18&;MLk~US>jW5<=)8i+8N$i% z@N8%|1G+@lnwEbediSt&9S;nl^~<%2pIIpKYqLN3e=1ZC$FAk}k=l6^cw4wy#l(^@ zgxsbrl4D*WDHWK`+*iu_&dt2epDmTtImNSW4P-@6qcrLszDK3tt+3U8CWVnY#4W)e zC|_$faN?=em#QA0XMQd9H?T;-Ll-;|zodW2yKzZ$v;@GC0V$_2X3vUfjnTC)=3IpJKgQi8Bgw^&l8@Zg%3i2^OmeN zM_-mvAL4nQ2c0$LoaFk6PJxdw`iW&dXk@X&Hs!~%gW{oq(8ZBqf+n8gxOj-GA_$3! zL1ernC?!)*W4ml8roAV-9>E%-bjWcWsj4^q>_(c9(d`&{enITF<0+}L)9UBo^66Wv zv^F48Dd9z9yOms%Z1?Bvz!aItR1ZJ)AlhT=VzLe}wF=z(?PP0(>7=Bj?N1pgmc7Jt zyn6(F<3sS6L~WvUJVeb6f+;PPdHHZy<6rW<1S@4<90De=bEITa*_sx|+Y(-)>J*Z@ zQvo!dG;xFOi%#_yEa9g`)IIZDA}Evua1la*7?LT}Y{@O^(IK9t zI$Z_LukSZ63pJ8B;1Iv(Bua4$k3 zVrV&9*kL{2m z>)MV1T;JZL;=aXn4`+G-a!IpaZA6gUnM6k?XMP&u^?hQ%=FHmp%&=Wluxay|q0Pp* zN?e{FMBw=aGEwp6>bk5w-OR`yoA(#w(D;`I8Qek|p1_UYc%b3%9dG45w$ic()5~@^ zx#j~<%OtSTzYaF6URHLv$+d8I#Q^MRK~oGlG1&cO?NVIM!k0N{I@v7L)8!JMvjAT4 zyyY}nRUotH3Aal)7@@;!Hj#2W4EMDXFX|#()pr#Cv$_Xn1ZIiv3E~y5CXLnIC}f`0 z>P&a_&AAqm0{m6+XkJqzs3LhtTIP4@#KqM7Z+Hb@btihM84&@wrAyd|eFcEtJBGbt52Ik%Vn7f^S#rBno{mhe7ZfgRW; ztD_93BXEBtCd5!o=;R+JibrWC^v0CQVWBxF_jvMc@7%Yh@-}YL>u$A$B#hioRDl+? z?Ed)6FOp`{+irTU)hK=jtc*SHu?-8FtE^Uo5&bR{*7i|#Ze)D<&|>iLQeZjtmMXE` zT>)v-pvv1uR=)y6FBnk5&8Wb!lNW84Y8r4xL`ya^7cUJeR31&#``v!3K4e7p&sA%_ zXW-ixVBXO-4J>*(z6qmdCzEZJ>2Ji{qNS){evUqkY6in)DR2E>7@Pg~uV>lgW=!?cGpE2+o|uFot(Ty%My% zR&sN`y2O|)Vg#^reMg~R#o|7}US{sR?OotgdEWQvt1i_!P^IgZ34Ztb{(dBVh;&&I zh&5|}+dN@P!|4)lU?1Owi;pIb<}FZhVnI_h_70r4X>(EJzMG`nl$%?R6gu1lW1C^ky%XK-!798Wc}^hk{59VfZ+9UBXq0XS!$|{Hb1OjI`PKA2j9Q z5u{-X#DP}nH7Ao{^f&Ulshz0!BKud%)c`Y~*oYtrp<$Cr&hU9hYPaurVVQ96&|OG- zZw)d4K}B14`Hs^Op#ZiC3}{+y0^eVx+U)uz0(Q-(C$xIDL=vNJ{?WJhDKhto*9TYO z3hz#L%)MlPB=~_brRjOM_->y@=D}RFk4PxC5+cq2<~JpW`JHN`rPS$nwl6zFp#vSp zsw_;#T|bD*lrdZrX%y7Y@7M&3JC8TN6kqbCEpFJZ4?)$%jXVivewZ@k_z^gBXoKIW zGB4f=o{wfzno#s_w`|ljmBoUOaGm((u|niE^3W)O%i=p` zu1n=yQKgE7w6R-*9CRvwV}Vih2uvC{~1SV4)`=nR_7 z@8wagU1ZI3rd3hG#1MST*V{Bx-5ktiy}AfwHs`0d3l0pFomSM~IZq@WCk#36A6NtG z@WJEpWrwnBk#5EL7$c%!BGm$aD}~776l%;n)JrDDUy*ly1^i%XxNF7%9{sjELO=2< zFu~MC#`pT#tYpdHO8&shcQ@z0gNf9O?>@~b%vFOywRJ*Nl5UKjmfS0E&KqKEM#c>w z#g@6r_crF53i_U>ig~9ILko99nzxCAY8`LwEQ%PxK7w5T4;O1a&y7!$vYLZ?kWc}< z|3^lhCpJecfRj31*8nP^=#*;>j0GG?CLAwv42u156zoswYp&5jmAqjHb6tfE{INt{~y_$!a+$OO{c^z8atb1er4+$z2wm zei{^FV5W8o+D8>}q6sW~I+0-HyHlUY!S7RX<(@xOBT9vrDRPBUC$1T{$eAtDk^1+> zBe;w_U2cAR0Zm(e68wJTNxK9~@^1hGS2hmK0!SWV)uq}k(xXE&5O9p0z?*ZkaqPzu zwsrKm8oU)^NG}pIGUhX>`GY)yFrhOYcd!JBx8gBQn|A2|u^V3+KebJp->AV)X(4)%G#Ah3 z@42q%inkW15^vbOx?csJOOb5tV8^3$1g46M^ms{E)1B2KYEn^0(r|EKSk8N^vlprO z^tO;YyD2HRxhOX}nEj$VnDD)P zgV`q*z&79oJ(Y#IkE-^ca~XHxaYd2oqQ6$AWcfsAANzMzNW zuOd~o*R!|I)}ISKJtP#m@V(Qh>PUd*Vq62Wd`!mD3@S&aP!h>+V3lwW-dLP{1fuZM;e4qwf^*%Y{z|`&W{JbI za~n!(jtuP6b83qZOiC_X=CB(R8N)f6lR*iBa8pYSoA581Z+d2$0CyM}h zPTJc5Nrcw{V8mEiYXW}?Nj1_Q9{uy68(Ew98NJ!LQNUnWHbo*NK;Ifhse z;k($1AG_bC%X9Ceo{h(GP_se9G)j;Ip_`!vNc;qW#aTZmq_b;a6 z_okF@D^F{%fY|*!;2Wx-OlJC2LviWOej`Y!xi-fy4c_)AsETN)L?56cripC;D_@Ky zIW@@rz_(&x*`bL#a*G|(oDnvnByf?HM~KvZAq}LKQ5tZv!I%@~+q?`TzkcOKbh7r&3E_xihC<5t#`Qc9DypNR5!dzScZE2=gMs#d;YG1zx_m(p@U9g|Vdl+9gK7T#VjVuSB&gas#vv9X@ zT4|}U%_`n`iSnz?po0%ri0YxaU|~IBRI>A*BPYBv^cz-MP*{NcEy?OcU@jJk`ghE< z1Gs{VM97H5SMk=;1e;PoH>J^Z$Bg`d@srqDNlZv`sS8V*PvXuH(CEehr;Ho${T6^_ zv1g7Z6%IL89++2!XMP%&2odo*_;BV=d8nH1Rith_`DtPQCduc#y?_$W6%=VaZeTU- z#+grWAz5T;(V6sYB(mZGb-3zc3wWiMWeLqw-dI{a{ydJ#<$#gRx-bdTmzx_<>ey&Y;f_l>@K>q(i+FF$}LG0-@Uc0zqe92{mgWo8EX8)+OT zR17HGv7aL=cF(Ip%hK0ojI(OyF0g7$JEEjhb9jo&-#1 zu{>^+jh`2S$F|f9Giivci5g@v2QDYdg~UY|s=<8kpWHjDD$);`g&jS#a3>$ftvEGP z0h$(ol3453d)ng$jX>Rli?|-4^F{3d+%;0uJhFyt{2!qCP#s#8w80@bJW*k|`v^34xT;NQ+Mc34Z^;DN1DP% z2t4COy021T31&CKA! z5YDlPW*Y4GA`MaD!HzzHCu@!45%$8?uIr-w26$2_loGFgX_1d<+XD{vBQ5_@xBMso z*?WsuX{(3KZ6x{k=AwCAc36lKK$Ge^TTo}Ew3-oNSzN~7dVw{~c`PP4h1IOFv7ERo zfIuB}!s^v0k6yri^zsS8*ddpmFJ*sYml2BUZAeY+~>}YrIOt6_PB60<#)%&s>c*J^| zQ`zqWQq@7g7NdOBm;hdKPs+rn;#J#0zhoH1Cr5Mo`BNQ_Ong*%w8CFtK~r>qVlLCM zKB)ULufv&>?9MX-IuEAk(~x=kg~t^yn0=#M-ef;WHOPHSGBs)OeiuKiP+Iz>o6gmbUHXnhO|lkm}rW}K8WwIn~&p1 z^lb9`@%n!xie0OfH}JP&XV#{y&r^=I&%}@X+T#@}zI27FrSC3WLo54=^f#|?@4Q@g zBf?+vttC2q+1y|QOkNK{KoR3;{L?`diEj!3g7v|?0|ev11+oGGh=3mi4cAV~pZ|}h zucn#%kPz;#_Y}W>r%i*RgF8f18g`<0qa6=KXcYKt0sDU^;o0L?t0sa4d{4v(y2E0P zlmEE3Tkrc_vucyK|F`LZ7!d-Jq7OwkRg09k;mZ1XyHYA#8rT2!3UM=g7*CFT);N2$ zE|nP0F=Y%5up~_fx7rbvifyPi2Bic)Ke*LRoi0Mg6z&B-ZYReSb_U$ z&kXt)kNZZ`9(q65UG-sLl0z8yL0;JjNA*3QQIVaw>GXeRAQ<`DnR}iKjdSVnpC{j;(9L?zyH{5;dJ{wvUVlV%}>$u zjnUMm+JF@9mk)@msxxfP%H8(8j7X4kWDn;Wx{zHdO>V(@BH z*6-?6n;!C@kqvtGs@=bziRO)#8J8ITJ*`#J^ldHrn%V=#0=Y{hNfDbbOx$Y%Eayw& zOV^)zc^$3}x8gx{h#vyR7Cj6hg$pReW_KV&BU3_cjxCfc>*JKqaBnz(bD5m+=J@1a zTqa7~@xN3HIW-JgDd(*3NDsX9?yTd9f(e5KOExv+l8Y@lhj#lCSh3;V5xAvzzl_WW z-rW@Hh0JHe?}>U5A(>=zArfUPG@%0>;@zY29D_w^tRr^JzFLc!_S5+aRM{WhSLTPLlc62?IVyeD`hiUYa|GG7{h!>^+Cyn};}+{fMeeIcINBQ$*-)c`q<19f%i2u2oZG^w9~`l( zJBRPP2|p6VV;J0`wJn;d0lpFee(G{}tmyb{ORi=$uipF04q&7D{cqWfsT0p(D4Yb& zsuzZjq!<3XH70w@y=HWRk^o znC+W>2VQDyl>DX0VcNrhm$If;aeAt0Q28w0`SJ6-^_pL9IlvUv0kbe~8_?l$mq=AT zIemQaE9;}nGPk|XRfqOlP0vmK@=ExJNS(#Uo3t)vnZF$s8_5~B(Ohsm|L<~JioMiX z_0^$g(1T6T0~k2VgvdhEf_A`7#SO?lfH(e?LJyeR7HA;qOP@`|@MNh^I$D-D;-n5$;E&;s z@I@(GWDYxP6l`l!IHq^4?LlML>WVWPNCzbhtg2ob$Ea(uK>rnentY@Id&THMq;T2( zvZ46XzzQt_JaZ~?uP>-uJ-041G72{JUiR1Lxfd}99P_=-7Tp(FH$$FUv))KBCb0sF zzH%|R3<{i*z?)K1y_R(uNL~z#?>S~t(Z3TxPduR%lz?fn(q zwB`TNWSKg#92&#(blA_d?LT*U)pkW<3QgLTS(SN}NfXI9NrVj&SI-Q1hf1eb#8wXC zi4Tx-Qhq(<(UyfC6Vu(pAZdg{l08|>`$!|;Y)Y3x<{W8oHmT_;x1`R_+ zfzgS<`nDIDrVc3KM~88MAb?|6;(RHw@9p5~yJs&D%MN6|w|rAoppt+|kG`JdZyCT0 zCp%$g8%jSC?IU1Zg-9TVSS1{3#NNMoFux`x^T0n}nUN$I&|?*UsJ`nvlIhHJTrYvM zgDM*%-JoVUHBEuzYP-971>xWb$`GOGp4+J}AYbE&e{_j^OmwS`tG-WXl8C(Ig5TmD ziR5_VJ*+`b9*>~kN&w{7Uajo9cJEi3>RiH@wWt2~p?*TsO;mb|dPf6LeSHlD{!7Ms zFZQMBzBTL5U{3X#37I8=P``um73m)OaBgn9GH?q1{PvIz7ye^(Heo{`eF~oP)!RoD z-L%0XDfmi7(E%zcsQS)NTL(5gHDRfF{((;PRg6xrV$^MX!tvQ4K&ngPx3A=D#R=|` zu0RRe#I#XSZ=-KdTqU>Y{c-9ryFDf>j8mwtbmI!#p5{c{d?K9ZJ zOo)R?Gpx4?zL3Em+TZE_QQ+xywvuRXOg^`jQ{aSlVL4>UbE?-Z5>Zdjkt0y%`ga;} zrtoYjpeOZyHvDHkl{9_!zr%1pm6ead%8j3DIZyk~;)K@p(9>t6Jt22X47uE#ymD6$ zpP29^xk^`#HI80}rsL?SeedYQd9a*b``;M75Fo-}Vh19hfj@db6_{`y*mQ(Vc9g=Z z>5X$1*n%+|UW5BDrt~DF!9WoVpl+c#qyB%xa)rAJU4#>LBu(NXs<)G&^1b zZ(2TZE^&iAhUY=!EKcd60{VcUmZlMS{4{II4W<}Zu4aGP27r1V8mr8iCA~=WNNQ2o>+?wInV>?-&9Osmd*1yww=Ewt3orhkBiXvjaM@9&?%&u) zeWSu558N5iQpUpEKsm>7A!SM~W3(a~rLLe(B5| zgAQPcsWhzgn)kf^x(%nYJ7`B2f&b0p1?X~3jcswCh}7oBfZ(v<2V`lhz647U$V}&W zO|a9g*%mMM{oLrzs0=qfi@GqQOm$5vdR3kHr5>QIA3JhlCh8${4As4OA|EnWlzs4# z9QpU9ZwU_RI4Y7!qRc^6@o#*tlwUTS^AA)OMSt+gkYFnhY%n5+UkOG+BpJt%mbojG z62K~QzdY+k-uyI$@z0=9*nQRprc_SyP1)@hOq=tF0nI)ep@CyIF-Gc0geE*LdVje= zUR4pu5CdHPyW(U2<6O+nQzzDI5GO|MvuqK9TF);lU3<{W1nQhh!fs{c^%`mIn!7x3 zqDAx4z7mo%1tOoI=Xg<0JWwR2#6mUc7OQaX*x(n1hDUBK`fTUF1B%u%7L^mqB;0TB zIA$X)xq=aWE0|oWHCra5wqOqAw+|MqE>+nn)3>V_9v#l626{(+j*Fx^4}#B5iY(0s zp8-!*WrB!=)iEN1aaDh=bbqoeJ|sx}{hrj%d`2eINU47%glntL#}hV`Jwgx}TaqH) zyH$6HxSpRy^7uwZM+P|cSvNL#m;Ij9l!{xHx9lDt^55xVy_e9thNJ!T@f252i08W7R;MfQo3P}y z@;aFxSL0bRC6+AY(*ddyV!ia!c8M^&5D(_?%c5xFv8L?-(+y8H4#S$#fNS|={eS=N z%tQHtHc?AVXw_f0qcfcWJjMuMSHupCLp>&SC)USSHWd%s9+l8+-{#m9;9jiH-~H$l zi#SrG>e80~d<4UkV0B_eBGr={7nQ$-yKb>DZge$=aFWM=Q7W*W@7)~$rhcY>s|;yn zd^G*hlyzeICuvOw8(pYd4i_0S;UPJhDq?v~SMB`zb5wK}EVr@J|8BGLDZ=w^r^EMItzG9A zlGK@D&Fxdgq8Q5KT9)t=qg~q^chTJcUF+x?2gVdFZU*5Zczg{cSi}b%W%gCiyet7{ zpK=J1{p$hO;dou=(VmU2b3SbZYGz@!M{xt&5aU8C;K6yJ`G}ky79T~pNtw~laTZWxy)wkOo zeA#To5m-g>sxZ@y-SJO8uP;nAO98pY7!TX}QaPg~S+3~SIP1w-ZK|SV^h@Ub_33$W zGD`dt{cI7VhGy&_y4+;`)Jv?WBY~v;d617Qv;=($Q|@ zb?OI9M|cn}Zc0Ni(LN{hUHqQwIwEjI9w}X}L$d_)cR-)FZ2q6k=2ZxJiEVfMm+bgj z$H9bLWP7t8Jc_Pn>`6m9(^Yg;k3Dl45R11`hheW>{fg4i$5O<+!z;ks&HP?UBeiFg zYSxReU}3iB%jNz1?{sLi2JQqkxZM8`^nNtlUFFUOgO)27ss>NlCck|5uqHxvUHShb z>MO&d+}^Kgq(hKyP!I$O>68IRP>>R&W$1>HZc!LuC;>q!B}JvBYmn~ln4wELhMxb! zIp_DjAG{PlczNw--?i4-_fosceQFmiusc9muk9I5zdLf7dAyMp!LIEB7_Z=oQv!mL z^2jkSCcs9A;H(>PX|X#xF@#3&0G^9?J&UHQGk9?6s(rqrFXmim-FyHyi&qbmpEg%H z3f$936}WSvoi%#v`#~*ih9A%YN&9+n@(PZLBcOVKhLm%Y|uXqPZYKD0ztaNy|BT9vg<;yX|pIL zWVCefgZC(aO%^>_Zv;}7j3WR`&RZX8(o73zKe?GuCGS(=T-N|8(Ej#}A=wwN%6}R5 zi3LAxFKR~Mk#MB9LqK#8@6VTQ=EPUo_GuRzmpP6Lt9~jA#9!iiN`MW@y4WzKN=hA> zq<;G2kY4fmf%2tsiS?xtr?3&F=fu7xWxJFX)&lo>t3-*BCK^2^y@wY~5D_Z)mTrY} zy$5h6%dPHZDz>pX2{h>QAm?5~fqOty-kq`?m0|=R9|2@E=)5V;`Q4|5*|C*MCr-l^ z1@IQe>+m^h5T^ULH((bkv+s$@0Z-IN5YzBBZV{-NC<20H7m^8tWhEhgbc# zZ!<$la|Gy7@W)4u=p9KG;ikWlV^3Yt@3Mex4S4{sQ_=tDx(UF5z5_6a*9*Roi(nZg zZ1I{fodZCdcOAFn^znf{JtS?Z+i1Gd@s7Y9-kEFVCN z1=4Pho{4%J>Q8zP0CtY}x@il02L$0Z=~51ybMuD8e`ohRcYxrW=^9iC15A3TwdJuJ zCOW-l31xR@?w8nd?fbkum=i3+zrw1)_o*KAyb=3Yw117D2$dnMapmbthcKM3*57E| z+|{gl48Ygch<};hY*1EQYWs0-|I(g60v7k-1lS|u=T#v17NENBSa_p~5P@JkdA(%v zw7Q`n-@n@=gKC^V@56#tuJC{@Ew!XIN*bGzJb%gh>@O;QJ!SANAguS|O%wm&O=_qv zseKOk48)P2GXN&lzbsUyQ|h?metDsdt2l~FM6n35n+by=b0v1eS7#Wv@A<<$+sTiM zWN&%KCg_W}K9)M***hN)VR%b@i(-4g>fo5b_x0`bVAIRtpkhZLDcyPqgCS$qx^e`$Q$5XVy6LHH3}$OJIdBvB?PyAzq0_2qXoDn1{^2GT7ZH_ zFmJ2BsaC_;P?gl%i_e~Jm?`1N8X6OUO(El?YaRjAP22Fasm_nIC)O$szNtU7eY5}B zG;zV!ZuUmbLn5>j|O>zH)x%^kn zShm~beSQ0??tT?v6|R>`Im#IyuyHJFiiLu_G0+!#4IMaJ0P20@s;7 z-xym^TuBj|*{m6>VbM{~9em3IzsXv(COLPV;JxhwwUa*mcWaIbD6mR!cCiGpW0jH^ z&BaODe6{OQzybXM7-~VpXT2D0nYZWV>M-H&fHTE|93taYErj6NPvy)L-#!XG+c!b@;*=Fdm9gX*KFY)T>|a*q+$V)kqN1vSSl?Kan60XZH3BsvS{XWa>a z|H;-l;sgD?xXs{pr4g^eSvEKFeY{T&ZQeAR>Inq^$r{)P@e^P`H-VJ22EI>+|Da9G zlK1CW;Qh^*u5-z8#t_;FEh5{n30ag^#I?)Yse(5HOVIk6o$KF4v%Xt#pWlAj3U6S+ zMg#08z$pTx-JLfWGy7$B^=kF#o%Ob8=h$ny2ybDyzo%bylykhWO2qav>4sT83SYf^ zU=Ior7m{C)ty$zp$~mQ*@JIPG-nKXGu^#|eH&Re1d#vqzc5+#6)%my6`r#C}s`$AYSjtmUDXZv_tB$%L!#A zs`@G*$O8}B5zMwUwue4jXCKC}Ym&yXGn`!g^`|Q}PIP7g-brPtGE-co@40iQ4fSql z5`E+ScBBckr!fOWmzOyS|0=?a=i)$CCAb4>q?jyaPC*L%Slk8Xc9JYcwoB=K0d5^H zp8bwHCKGt4Cm$$;CsTQ5o&@&#Ombw|(x~EBJ%^e-M%QGu22oUPeyL}{2X^8@AI0#s zAR!f|((j?|rm>0S=S@0JpQ9MLY>C$@%66+$bY8UXzN)we)umYHy${4gvv+-;1~UTO zdfoISjyZl%6qN5X52Bu`{bUw!&yDchyhvl&mX`8PMRGwSinR;%?)M)_QJ=8@D^gz; z>V3R6nUud5%>!im(2nne`iO7WK|r#n9>j05w(3+tsD%dh5nAN;%fD*7^in--80=GS zB9onclT{QCzIlON>@3(aa-;C9bR z0cB^4(#h}0wAv8U@D!u-W<+0v{w+ho`z@yfv+=Uz>rm+JMRi|30$(hRQVn9*IEVe2 z68!vL*CpmpCIgY43=~Yl)NKWSVCX{wB+@TI^H&V(7k|_^RDS>-dcevZ7LS78bw>%X zl-`7{)bqCzjLO?Q{MT*oJNJ62a2@E^%QWcflH44_I-Gayzc^IA7l_K-9g&HcLs(r)~HKxWC+Qo%gh2h#5D7i z5jB5tuKi^4#~5&|JwTji>l6k6znF&y|EZmvfS4$zA7ZdGa{AkdUt zHl&3g(jORpS@wc^Y6d!f^L3dPH;>j;$RbInj&6@CGko4zjm>p0x*fQn6Mc`iS5K+A z+k;;jt81G~lSgt6;wn5%p9p^{3oJNpjQ@UWBz|}9jIH3yCnSXy@Q}Tkfp65NtRvt` zb({j*|6*$QGa{=`5+jn;*+jxea!kd|)q0IPXP#&i>kFc`_3MGi zy`Q{MIt$F?S9oVE<--(9&KNnA0wVNmT~t6S@>BlnF4gYK&`GZ0Gw-KvuXm1_!bZq8 zM&tYA#s6fbl*IfcD0==1x0*n}IB_{xVYd@0Dg9wY6`Nn3!|ud4Q2c}YU+4Zqzw!{Y zb}z~<&xJts+P{#(XyHk@!vvx&0!(Vigelaht{ZhaJ40aZ|n@FgEju}4rs1$w`gGpP_ z4w7n#K?`wg-i&0;zFIkW4e55dl0Zx&bc^NR;gSD(3cp6a-F{cVUsE(ua{|u)L-KjK z*?4{H)=oGZe&-*?M?2|o-N-6zN$R4pPXa52lPdVzKxK-Zy-|jpy)@0VPh|MUh-H^* zkWJ7cLs!0wz{*Z`L{QkoA7*PdMe%@g?J#-seh-Lcgw`FzV{+=^7;`b1xb^ywf9%hVqsYmMdjN zvvD$wUSbW}GBd@|n-_!9NnE|4eU4q>-c##!Nk^*jwLiW)5<;H$(cfLG$|0qKJkJo$ z$2CMCz7M)sV)J-6q#+2A526Hdq;S#N$LP*q4w2%R)&G6R(jUTQ<$F zYv_E$AkLrTe%%;atP7wq<+Gxx;Kwp8{V-1DF*#+IU#L??=(bvOrMpD-L&LpO3gCj% zSg({$Y-!yInp1uM;xh8Xza7CyDa$?s8ePL|-AvRF3A*I}khcISuG)Rm{0+XlNEYY6 zf4K?vcNHxs`m`-qbj;Ld`FenECEc;SL7~E_5vfy+SnWEx4x8|n-$Oq%hyZ&`uJfi) zoHsO^Y)NLFx<;@}2rhaEEboRF6RDvG4V`b7okvkS%*1zX zxr1ri3{ehf%ra@x)n$bLwFzqUO~Ys5<&Ln*zh{fr=R??|g$qG+6Tb{!kt3A}UuN0a zJG`YhEQA&Ff!`ZE7-Ej>sDBznG5f&i%a?~k=WL;2QDuhW;GHA%LgMKiAw|Nq`0pm}aWExB&xv=-<5wB9ogRJro zf(9^0w2!Nt+vm=2Gf$bY;KHu94R6(&vKHM-V&nr$M~!A*p|;V|<`s^E{Vwu7b-tAG zf?pT9A=MXi$Zsx!j`&6z?1}SRTdl5ebv|0Ldg-k@%R!p)O)JVp^=L@QaIJ34gf?fthXHq{wsPWUh8Ff31BB6Zmgs0ksaxLWqNwm*-JW=1 zWiD^%Io`(sm)!GsW8`xJvjU_=<{*v>buG)uXqI~uW2uvn8>GWA@T@?)N1&RzrlVi! z-ZRgACTTY7!9M59G0&70etRNLE;3BK=F+9AyO#-}&YjKF#u6#?H zDY6>;goQ@7v%8$4bV}j^#oiQYfe2f*Gb3-eNq?MusS+GuxgTU1cpq>)HUHL3Jgt+? zG^~(Oxl8o!RUBAsA>2D?(H^k`($ICx&MUmXf*y*Z_gq`!^<(Eu{A+s_+`E2~r1bX^ zyEyLwb&Ld;&S-{I)Lw#}{g0yfpezRMibqRUBKi?+D0+xPjPOn|i+^{<0B@q~9CF`R z?iK37;dEo~sHoCZGhg=TXo4IqT2#3M)AkMgbYOLlGiBlN2(4?;PT9m7V~(n^COVFt zX;LGB2FqMI{qZgo+KCT7MiGG>LQ6+JL5hD8tf82-qvm2~MkmM{KRXgmdO5u8u@5Sg z=-@VGQU}~@u*s_?#J?|^Yad#2?n8N>#T(HsVZB_x*;9sN0(~>NHY(W&0(dN@`R8js zYO;Mi6q?07c0h@@h3-jm+W{0!zwygfK>6c)n&v`g*d2~xY};t24{pU!b9?G>Ih@^A z%cuX^WYX}=&B5r=#_{Qmu5}STx*@?F1n8rX8h_MP{p|CzRDJ~=J}hySbgEd8xJ%G` zNgSUwy5CiCopt#HQ}J;V~G?dli1 zv>G4bFB&(wMkg{d*I9$qXpT~Yw5g}szfc`mxh{LB*OZr`Lf z`>f7gg9v@4;|SlhD1}-HJst(b06MgkDnv5oo=~U4Df}t^CstfkM~;WGYVmTXWr&hH zyS$}C%a!sH&Aw&iK6u(M&%UJ1#^RV^2SrN0#;YBeon!pUP(v8}pkMtfgYa6`UuXke z>a*Y-vjw?B%XPCiHa>uEN7wTj0sYdC0)C5nE2k}GY_n=|d+q_7AT%`&Aj zW)mje!baKtj-yk z2xOR3Zmf^+_MkB*NoS1gaO4{HQR}#@U})3%ONsKE0e*aBX=t>g%}t9h`w$$>e1)LY zDr+W>3)}iV9P_#2&Zim9MpMsPbVSD6oPcjI-!X$equFKn&S$2~c`)~x+cPY-W1o3f z*@yPIzbmWejnWu%{Gh+{!bP^E`BuL+*X^D30*`K?44#;~sAkyK(97v6Jah^u`;uZn z#NdV67`Y|Q@Nkb&+V2VRI>*gECz*~^tIw4g>Yt4r;KD`4F;=R91F9okzwKY}^~8VA zM>wb|Tlk||5%d?UhX$*@u`i&^NaC8Ppa)?lS4{3=jAF^`9hkR+=VY)@Of`(FJ&Tej z>yoOV3D~A5SL;I~Np&W;;d5aocjmEM4^tH)mj87k7PxM>Zi1Yb z=5bwEnriUB6!j4Un~HZodhe$oo+0jYxdj&XzvrhUd>_mejxmVeKoGt5X1Iakdz%J{ zZ%_WR>YF;in@zhzm|)kyMIAHA!HU`J_{xXK20n<|)aur}oKqMG<#Nm?j%}y@TkMHn zgTlOB^T_(O%(}aru!WXtVS`mTbECP@2Tg8HPp?n9fx`?@Tl|3`Z)0g#z&%9G(iw41 z?-#b9vdIzk+{3HBI_6!cun2dg(d^cZ%ZZOMgriBcVch-|yQbA=h=X(?cymohuPGW; zZ0&~U?PqNC^1d?>`dZ;bF0(yOX1Am~Q38os=y$RcJlQ>YSb2BE+=Vq2XDcR!$|%ih zWU;AQxBPd}>n@vMNW$#P2;IbeBbnS8%}46=YbmM?Ir1{0rbU&)j?QrtN!g^I?}o~$ z2au&<8FQ(6MAP3Gtoz2Y?0b2M!*Z_96_r`nW!UzPrJ3d%gzvfQZK#l5nJY6NOx6az zs}IGHoV_mLip5o9-wG7cck}<{x&6Uu(4HhAB-)VGk@Gfa7_Qxm%yKgR&3A8;(e{a6jD#G7wOzzr-V3IS}Gty(l`}5Z{4s-{h}D>Z^?!czQVe z&D2XAp8*wKj)9rw^#nbnSe29TdSzo0JHp6uyQnfwk_#fg2xzOye*vZ9@FFzYpxyf_4HJOULL(jUplb;I$M#$nz9Ol1=R_ zARD`6YB~U6RXRm@wn>SspSa$AG*sCT7qoo+5IveQxJ=?Ena!H0vyg`MH==8UO~Xy4 zDcI_@aqbAU0O8H@gi~i-?I|hB7gVm$l?ezq@ZQ ziGfEG+DSwIL8g3KnK(gVP8Mi(vm4vTk~0>$heytMf*zCc-P2(17Pk19;|eO35Um2b z^1wh@45~;rz2^N2SH>?Nv?p9xFNVQb++3ZTaSup%{XR^Nw%E@~y3Q#VS`!dWRuXoP zfOx6|>WKr8|Aeh@tyDkhDu}jiZ@LxY+kBL%RGgB+nuZ@`(@C})$+Q@y(GN+0?$@zC z+bbIYqK}g)Bw3Zew0f}2g_{uCSXsrNqdA)6ay>J?0A4sM{U{V(*_zYQje#SR$i1JPrWymaOblq{ zzkf)V3=Wqb)Qj`2t5PI?8I=udsg)i?HxQ;rNqz|=b7!?vWiHh{+7IV2>Ai11SO*q^9i&Jx$-bfrD0%(aplsd$kv07a2?vn_5OlV z49^&9s@~1M$?^Y`k-Q@n6Quu7k47Z-zqGif*`|Cg!fm_97P_n<)`?-3WbC$09Z>bo zAjHb@R(Qa5{=t=piw6S^0!sB|{D8!ax6M<<7N0#bQI4lZU2ev5e{wN@t>m7XY_lVMxTvPKW7 z6YJMFa8nl%ZW#An!>O!YvsckRTslIe9P(oBEeVt|?aQEScYP13C)Kn(p(AV|li_Z1 zcc~(($G-5JFDt-Wha@N?&Xz-5$rq)Ah-A}N&s0$yC>_x2y`Z*k3$=Hv1O9)Cs$*63 zaFB&4al^eewD0Ro>vc}mV3vQ-_Hsa2d^_mq-25UaRv{(Fcu-J3w}vc`Q*(n&a=vy4}sAQu8SjEXK;e+_d!oQYN*pMptXHr;lLZnTZFt zQJke0r1Z3E5q)E<;V>4fiQfH-<$?%qb=3#&9!0>Iom;r~GZOekQ#PF(okzxB+Z^jk ze3(9ipO1MLR94B&GMOd?vP?s(3eq_k)h;x8lnYTmM7lSdunogO!Y-k?j2EoH=G0K8 zXvPp@lgpacOK|vd9W8JX3At&^gP0{oYu~?@9i;Y$5soOtHv%nwC2iCs*&LMX! z+M8*iA2lOzF8JlPtdi1MlcLTv>hv$f@$OLVYV?D(2kpnT-REsY?0GKL!jS$`;(d~~ z@7DpDlcJ$FNn+cS%b1rmc;Q^eXyV5Y)IQ5w$e`3wE+`C6=H-j8_|IO%7k_*iIacSZ zpu5Ney+YEuCk_46UGT{O&&F6CeiPp&!#9V-oF)FOAMc?gxt}1w184)BERgt-5T5+@ zjl!Ks_UCb#hGbWG(|WatZL0|*v!EsU8~?!cb=HOt3ljBZflP&rGR3Lr$M+&9rs`il zfPHv?-+ZvP7`TbF@z;fz5eoY_Q_B zGC5FS8|&B;-*^r9{pAz~GAc2jl$r##?nFTt9?neQ1VYFrha12;c zMW_D9ZO{}0FDhlN{20CLl5hJ9pmD9a0NgMKo68*DDV0qlIt!0lIJsS2M_c!41$&KP}3ptWO5w{KR zI(f((!nvQdF|48loE;gL8irJ6t~V9yzabTSghIn8iBAgbh_JBYR)RX|afrqy0>!afI?dn1v^3$bA)UYf5^o zGc)e|=q9aubPla&U~}y((-so^pp+;3^hm1u1}u^4v^ar_!HQMWxyy1V9k+pH>2h0< z6Juku2@wT0Mz3*Jf76p0G?B^G6O?|JfA#%s`S;B}!mac_z+G(Vo@BZVbZOdWIiw6b zNrvgJz0B&KNw{}C;GFrACOc$^0N6+(b;^e-aJfG9=GF&D@%6PM zU#ZNW4iOcs`nS2K^go3W!~8Fc6*vZXwyzkR*-8s@KXUC-?I}sPioWz~KnGaewR;** z;RoG>$i7uhFW5Cg$dt(ThI=~Fi+TmbS8KXWdc40xCOHJsM0U*Hj*($8&7&bIz%f@n zF2Hd^1OJnE!K{aG9e&G@TZV~>j3vlqJdNT(v`oyXieYl;9C1Klwj)G;w-&1N=UgO# zrKWcG84U-<$C4FHJ>7|~tP1}Z4R2-K{!IWy7x^}+L zS3(CX!!($5f9keaz=g@=9i%e~eJd3q8QE}Eacp_Kfc7GWrtOZCEH0^)?GR_2bX(Go zyUs^ggQcy>bHSgl^sE797%L4%d(VlUQ^EcWj1aq2 zJaM@(g9m>p(QNb8%ldhH^4byq*uVoRjOMbA@Gmq0*7W=nHk%6PmAB2;#X#9|qTl*M z6tgvNos9#G8h+nV`oAREx98itOAjH2SRvt}yd-v`u2xc;W){bGq!j|MFZH^elH zhFE3i@!eY!n$Hu3adb?4cpatb`GcTxMqh;S3+S!*M>z$bfA9?3qMacl61{>G(%6qL z9>^6y%lq~uc*u5b4GEr!e&TZ{D;+YLT_g?fXWem`g2eYa?$J7r@1)ZaKPwitA?AT6 zRZV!+RskzlG7VJ8v259gKbKrED_{fOg%K5VSC?$zYgR{8U-4^TBe}_&?tvV$CKBx@ zWwBU0ZZ$i+Yx1p*J45;plcOJ7!V5(^-eQr6bbND>D4E!9_`&=7oblttDjO{6<})mN zR%^b-M=E>6gK_^e^ZJFrjk?>WUSe}L!YykZ@Qrann4jdmtt;v&xtu;r5cyd% zj0$xGPU@h3<4+Y?Sx zlkyX7ZbmI&9#kb*rz<9~0SfO&;O>V%4nE&yW$Y4clp{0zVrL)q!F2p9P3|gTGvD$M zzoPROfqLo&OP(N@%N>ErZf0!<(7=^?`Bm+A{K7xtF7c*cd z|H$It7`*v~I>110?)#6?Y{08P`7dM`9G4@?6Q(J;{5|gxr`dyL@xrqmw~8 z^j6S`FX15Ls(TgAQUzJ61Txopqa_~h0eP{Qj?_4Mh~OWYEvPu>LCMjN?6V^>bl>R% z6t4vv`hpwnFOYpFL`ED}*b0+1cwWV+_@(;yAic~V^d)Pl;0{J2)SE9eYM~K$4&y&! zmbN(Ys{l8RAV9EjHc&wU#QgWwE4MUfx1(c$hS7kN{Epx&+Ct#w(^%{MWBvsEk+^#i zjECZYjV+W=mRx-KEz*oH4|F;(Tp@OHT#Pk+8f~wcvHIjAXW5|3@rK%C?TI3@MIG$3 ze3b_JX+0zI27)WjWgjHizzmoHVE~3mIv^yAZ}^ft;b@oDA>liFvt8P2*bk)~F9t1E zV6A%X)2?g-Ng=B%%-(Q71(41~?JFnlo8ny^!yy^?BJj$kM(q01_~9yfO#&s(8yl== zDTfxh%>{zoezUzWlU;HwKAx=gJ8Q6|cH4MxM{|vQ06V93gCrh$GL)V|vwNgd)64m1 z+0;&#)OBCq_iaAKIr^h);rue4Bmlv$1W2{XlBO)FU3PmjOX-q_Q9^`R5?q=FY`9ev zXHAb1u8uo7qg?b^2O~YP2la8`{D{UCNKLRPWZojwIHZ%rr1|H(;jvts61hb4d^CNo zci$;iT1N$J<_{^_v{AdoxoV=n_cO83=jGrGWB&gbHNXGLs5-|cj+e3(aRIybskxHJ z(;%LrxzR40k+}GnY0(hZkLG5oT4w%U!k9++0a5fEqI@#bb~)U0fC!PY9504vuEtDv zD(J}rT=H9(q=0kXxRq6kEwUpxri;sbTQ`?66(H!gfQfsYP|h_w&%Wo5$&J-cPmdjY zw3ttn#Qff?I7r!IP?K;zd2sjm8V=G$G)y93Z=bh%#8&o;HT)SPgi-ZOW=qM+wy`P4 zHxK;cCHn$_3x2E@)JdK>N)m4&Tyi52$6eEx`#pMk>tbro2@3FRKc|p+(1}7w>FD49 zLbi?S+j!m?y(c|{F}(q!6X$MAtcaj;T;Yj`2!!T#3e(N zlhs{?_L#2lP62}|b|=H?FL}|f>)+b4Hg}EM4!zCrN%i$12qW2dO6H!Eo&q1Euq;w^ zURnMNZU_TMo&^UDNJP|f02A^qSnP((o8t9RJit87KnoeUjlSGtPm^h18v(kS=k?_x zjNn891)8Z;_cI^J^NQ_=%|4-*dO<%2w<}2OL!cdfeFvpX!dNz{)+H@S220{n1pVkD zGo9*%%wb*esmPOwrWi0KGLHTMrw_kkE`6LN(E`>LOM;m^vm}8J?+SWmdB%L8c7R@Y zY;UwOj~*Dn_)8z|xK$b}2zUhLow)qF^EU1EsnYyPBV|aUbAsQ%I z?!zk?*vidIbo9><78CRI_|uCL(Hjbn7XZj)E`ujfPa}M6d-y3WZO>z{s`X7m+Gx<~ zz!N5S7{-hBWPW$8!@Q<;_?26|vnu@j!6oya3XS^~<-hnuA@BdLyRaci`W-QBBEZ#H zkdx{BF6e&sM#o8V@4`x?OtE!$k#oaEU)V3x@!ovn7dCV6UzAPgj$`g|Tdw-FVYw4c z$Iz+(l+Xj9m%$A?A~EMKMTODFD!REU^mZXFm2;lp~osgBLG4I9s7@JW+j#g$3h6z$l!9b+aCc`F0c zO;ZfCj;i}I4#ze54ptS-%)YE=)Y*>@NKm#ea#)tUgxzGTB1Jh2g<}yxVV6^)Ubtc3hJea%O!#phVG&Lwo$#BX5md^4Q3ZnEdr;%4+dZNAAAT+@*}PAKqdJiC1z0TSb2P}wZz zyW;J%%Lve|guw5gIMQSw8gAXXA^5d=yYpXJn zE{@?TG8uT%2rpLG*>0oRH$_Ft*?&A%om^R4_P%GfkYnk_2$zXCLwl)mM$kZ?{je=H zm^=Fn%9lOl#%{?x&7@7dAvm-iT#ARD(+u9q{B@g^%2Me*>fn@4Ow?5E<~@Jh-(R6& zx)m*6Kuj6sJ4mm)m(C*%7rqy{ukg9WUfwU^&U|1|<;ld17t0}Sdx~pq?V1EEA;1KC zu#srV=Xc{}^Sy-e!H6Q_(o+STXKHls)u7DH1T|RhsR5MkZwJ>>Pg(c5_l-g0Yuo@C zB8Nay7QAOC?-!~$U$T>EYJBxiVJL}~?Z9A)FqG?mQjMXvnM%DKumju|dG=HB7EI?! zkM2Tyan`b7!oTClegG+^D>sh?Y5Q)L`TIaO@4oH3d=kBuL4Hph=|_mDdy9oTbteE9 z0E?;0&kqZA3~aa=UE5`v_upC+8mt6Nxowg(*JyDq6*IoaVX>Y zj@tQWzmahqy{cx5@wp}O5?q)hLNnzcdmIslFv(H;MSTw@ zj1mo&pqC>&3s<7nHW^a~ZNQc#yt*5?l@$xV67oJmG$J10nvHq@s`EC?G|W#iPiJ{; zG>_El^!f14jF;U1D#xH<(YvAYv{#`(@QA1zhJw!8DTz>n?BT~q_VAO>V80L+;Q1_P z?`6-Xx&Io6OASi$RC437{NZ`d=4?&ocrUU&RjDaqkUfDB`BdC@mmoIBO*_)}Ze)jl z$Qlp?{G7I_O&s#QERM0DW#>1}G(dBDD^MtQe%`xGB2aaVQE#B-v%w+*QVIuYZWMJq z1PlJN=f)0KT9lf`-_pUU~iLR|%90O!#&c8uCrGQ;(Rwh){ z(Yf5NBFQ9}G_pgpfc9Ci&aNX)2-B#Uf1%=fCT!)@8I%Mlz;8l%&ywCJiAD(Lj|T>u zLFdILtJZWatVy#R)$1JXJ;SdE(904OTD`J1@Rp)5o$IgBSJ?vF8{WHVpVl9}rjfj8~0#Trtnl}3&bt|zQDL1SAN`f}7#ujA-9epWOD zs?P*I=U=kUhhLk*%FNN~G(5or_?+-`oWJzkhsYXt9~F6BS<5T7*oQ6lcm@>y=~wAP z7b7=8!`DF~Ieo(5wwqWyZ=)c}$kS#bZR+nz0+IjRXZuc z#9;1@>^l&!^`j3-`unk)sCC;^Y0x9I`E1V%sFsEPp0S>5H3@xKWhN({0-<<;nD2W4 z&|YQ%YQ#SvHBK~8mYsp41z>8{0-cxZyKi!|%DR2l`31%JO&s2tQc1lL0#1}=<|J8U z#V>C1ON75p3fG*5K0EDaeef3sr&OoPiPIXpwb#mWWtCN}M#j#L-fi? zhM2<<3xXSD=F8`XvrhPS@%ru0TiQ-Wd0swrz8T$CEW{D|1(jUK+F>isB-{|> z7TS-)`Y;fFId4BaQuN`BnJy3+4tgFGoO{`vh{?*5%B&yb>L%V3tj9t^ks3n#Bq;T# zcKhfvGye@OQL5J2H#R`en)lgGFnJhojOOMn%bKRx7CjX@H1ZfO@k$*#{l%-2!zlTa zMuYK!tb%`DOMVRNZuoxf6GYaXCge5qM^>Afzj*0{%t~$rVfwJUi+PA(hBqhm@!DaM zvf|4nlA}AZ)sEG#Zg1nJj&A$pMAMUtCYm<)uw>$v4r2S`X_@`YtSA__f z)`r1p81xeK?kE2osR`*^B=3^GNa2&1tT68q8P?I=U$>n{i}o~TKmNSbq~yN?Rbyvj z5UPzptIa#w;z(doaOf1<*81-9p-VAhVNfl)#7J1!pQe?^bF!yd{IA`1wHprpaLxIy zN;S-1a|3CXFIouDR(Jy-uOFzmT4ra6#=;B`d~pGZmhRAh1AqoR5znvks^^$6IXZzSp}cQg@NfhaapwKTp_mQDe)H1b2S)?MN+- zujX%lF}wDZQNWbNN_EcL$Z>Wa>5T8R-7VnEg8FW0@B@Hu)r%xv8A-Swoh-P#5N7hh zKH~u7-=#o3zaO*+MQ@tI-O!u9a{!KHaa-=0ciq1nN4UevY?`U+ z2CQMDEgyFMya!+T?DU{(wtJwyJDY^Hn7UfofYCew{}bO1SCK-2rX--#wwE;1q^ZE3aCPA7ZUOzo6G2bKma>UcL&vlP*{-14IE9dvA9Id0Cwtu;sb1dZ zy0}SN&t7@g$nL8Xbfii{o)bQfv)B~K$BBju?{KBEva>a$7mmane)#j#RiaKh#&>LW zPPRG42;C^qbJ!?==T$jjCj8Vh&38~&d4?dW9fW4_#zx{bMbT@rGOzi@sWQ_F5oF?5 zJ=KE?VtKJ{roG)_onEVRu!t4DFJ;8i2aM+QkdTT{G%dMNr2ggQCdr z2n~Ot{}ioHYrzyvn+5v*f>e^yp^`$z^76nf{<3CR&jXATT^&hT%x&U1-(Af=G$&om zA`<00^EuM|qgv^8m#vyAoc)^K2k%a9B6I-havsSY(dI{P^G}xF%vDd^&k$~qS~e8I z&S{@Rj}Qy=1IPZ4{1EOId*~H6xyAo|_Ls-@`&SYj64>=*2PTOjdpLtNN2co&+?}{o z5^B3~lDy)HSqFubmpF10Gh-&zk7rHR(|gm(8hlS0jitD*N<(yfsaYygSB7+sK z2{1808c_(f2tT<)t=$Y^T{jB>@2M>xOSmT4b7QjPU*A+oS&n)wNP~dp7gU z!Q$0Jk0#RHHzL{e2Vb;=6(Idi7Aat{rih9!$zo3DXq)C=FTw z9NqzFat)rtP`ius@RaR`zb>x`&lvV4EJ#qCAbq>hkUivF z|9J|wf(H~+0LafD;y@oQQ34yjgxp9!R(=15hx8pWnvI7Pe^EV`#Nmq)DK`Pd9@~6w zjlG;-?C2?}vCYZCZT1*+3B(?(oQs*>)PysIyHVWj-U-p)+kIkAcxZD71*gX3{*w74 zS3=;sUr#1U4Xd*qtfZY|-JX}`H;(!_?czL|KW}jRF~R{)vsRU#osM-Iw?FnIlK~0| z0q%mu2XhUlm2eSu?N*J0xVMi8%%6&v-@u*31eC?&f^Y)xx^e$T@62{F4GJyp0_GOq zn1tS3*Hr?cP$$ro3Zx&Z$c}CLbaNl#Qr_W_u>}4@IXtwRJvU=8+eahL6sz@ZL;>fp zj{tQHI(J;D$iF!&eUlV5%x+Hwa70{GYDfIJ!GnYjMU_SNoj^w7(a74% zU7#QRkZZQjgjlz!I-&lZ!5HVIYY;mBeX!_35b+huS5!}20oQhb~(Nmwz%44oHXFSN&{wbs+sc&t+Ru+1>5M7l?Jw-!Z$ zXr6auny;9?MnDlgA?tn=?qlk~#Z2le7;f$h8YycsP&vjn~X(*mFq;YipkQX)n2G)27frkFnT(;^T&)_LN#hY4{^ zGjq~Z^&6D0*m)Pm@_x|`m zd3LbK6wcQezx^U*{7b1koIwiuA&yImQQt z|9y>UAYuS5GwXFlc=` zj-sd35#wNbifIM(zrPGSAeh>Z1LqaKJJan>BK8_TI^ga8m|qsp8Fq<)PxAkD*q;II z0Xd*OKo7y`)%H&L#A&sk*d4umB1!L##d~LBM$pk&&eBcYwx4&S^Aej3n>(LL^zs=& z$#(pi0{PpM)##sl1O}KlZ^{R^I~RAZaLTb8rszjM6+HI^BEG-a1(=->Sy{@N7#)i` zKs$$e?C9KBDgJs(-Roq<6N4!*jj*Nc`~wX^4!O2rD6dr`{806<)Sh;&1kw4 zz!KapM46Y`8!8imi<9Xs=f>kESzd5y_@R1U6(?8cDRU^WqVsk#Rd)w^t1dTf9^p9U zi~WDp3HNqE;$?!$aJ68ZSlboxVNs~s0;=qO9aUuRjv^e-mXk>_jYDLX?I5%B((v?x zM79)#p1VYo7#{30IhCJJv^S)fa}39|7T1HtG6BgB89-f`ko7(LE#~Q~G7u37q&wQk z4vME^%vagYHdv;>ENckxx*q|Kg}r_S?bapc=1R{KIAvftLqBQ(e+I~P3Jm7;L^emx zPFOu>z`>bgj~7?_L^_T93!y>X&-p)2QzQ$0WAz$;oXW`)9`ik zhe2B>Jo&AGYj*1K+M&kaTr{Z;xed^2+28gQj+wFIz_9d*2nL?SJK(;^_~KDUazm`T`F4@zb#qTl{dsZR{ThD-T01r7>WDvSEbm}SY;i*~Rt5wv6D2B#cl-}zxa-P^pXu-8f<$~EpCZ$nVwikRfS&j0u)=3$ zqPH~g6Hyv%YZV;7sneoxnFGMj07(I$Y50fsnw8^RS5^VgPH*&MCf8-i6H9O-b}*kh zj|?t%e#|Y&N6uZnNmG=`A^hPtY(C_C1JE;dI!+eIjs9NDc*WgF)_(wSygB2`l{RRZ zHEoHaO_6JCo}qQzNzTakwY;+uUC>s!%TAm%^Ev(c0 zIUuVkttP%ga);I4Xti5&Z0}kn>L2se7w1L%*4_3ubX;1gt9dc`^Wb&w zfQ>H@Pylb`CHIayn%QvR;^x%|glVE;!PPi^bEGS{$oI(&R-(iYtztQ9K9>S5m)&~W z{hf!W!w=|yjVZx<9g?J)C`BVX$bX7Fb_FUqlS>j;%<$|QY5Nvc@;W5?TobmLQ1mUM zDrNHG7eF!0YDLJC4Txr19W;V$Z(wBnctH%!ZtL*?n)4rv?S*^7=?~+i1~<%F$a^lf zg;@^qcPppYIu_Mjy6PHFy;@aW&(rLQYhUb)_at{6sXtFN3mW?y1RDHG5t6B7X<(bg z$)R8HzD4u{Oc1FhnKcx@9(kZ)t9nvALM!K-9W(YZZdQd0i^d9(NCe9whFCqneg3DY zgQ$w0g6>b^ZZgDTWXol&mdoQ>LtRh%*CCN3mQS~=UTrjiAw*Km+GBuUw%A@&9%mzk zCdbT-d8=f^-e6lb0oYwqfN@aWGcPPwto#tgv;t+l9Mj=KxbD*}6QW+0WX@;7b>+2Q zL=nUMf%BdeoKrT&f&7!)H59vse&pVD-lt5f_*DjXYNB|`=x>O*idJ(I5`T!M{&Th{G0Zc9V?tzeNsifwil+oovulZj&=MNwdE+iQKy8pUiYG6Y9PH_S`Yf%C zAPj#`iu%W6r@x6JmU6fNc|3Yu9(OBngo?z7fgI;EYv}9e5__x&jB=EJ=PT#M`5CD+ zGC^&tBKxsf{7FV;vr)!?rt$6WxNob8f`^SCSJT4fu%YGUH$bz|5b$+ko8hVUL6+w? z@mZapH_a2P)GeE;GNkpHBIS2m@(>T&8Ab zJog7JNiJlX(*oKw(UnI>PV$XVkckYgabUa2cFxuf*5oX`>w=qUFi%0(`AeE?(tNi) z+>9rNIJdZ0ufJ5yL?fE5(hf({Al+M=eeP>-!M^Ab8JDi{#tEA~SnUmlF?qONo{y$l zp9tYK@UEWI5QZRVAm%az0`!A;3Jo` zIt*pyTh(kiZ8PhZ%PJF;^iD@MeW5gi+shM?$_r(z+URU{qb8U0jP$bgvM(d5v?2JN|5)P0qqROn#>Ak z_^#uDTxJcTy|qiwLY>q7n%qhfD*O;010<4**pktkg$b7zlje}zR@HUFT~cAFV1anH5HE%zZ#?NeJrzo zk{;~?*{$xa%7$RF zZhQQR2!-`kcCkADUrP?NegxPl$<`!WL$nP8aH_3P><#(_iwhzqP}+J4lH8y zWF2v%_nH;OFgtDedWaVgVrXMnzwUS?$Btt@pKzbQzrZoG(B?*J8F z@J~PzqnuCXoMrGC$v&M18)(BjD? zS$z2vSNjKiAvJq_Qc}QmNm8Ezy1ildwz|v}g~H-*Ai4AFt7k+sXWW&Zv(A4Xf$ztF znvEnX452gu==(43z+(U*j^6X`9!o1-_%M9Uzs+30XHz%HQX3Zbw$Q8lUpNn)fAE3e z!uAh7n1R-+GT$QR{asb`3|6xbuKk=_iGvX?|Lu_O-@sSic+R)!fWdx5-U6BsafE|7 zfiv#SiyRVe5}6^B`4&HFnWQOBH%S#?(B960sN&kbPWx6pic-hO>IJoa49@_t@>mFb zo&4SzYEJG}K}@D0#A-UU;TQ!nKj$!p?VXC$HT zEL5vgEr#7aot#bnds-S)cp#UdIs3;LOMSpzePce^d0#2+azZ#?=&9tQ`pu1jgM>dJ zPd5kEM&sqHXqAeD?2=){vuexlGZbSec>$k_7Id101N7x@RPNFaTE;@4$D5|68t|Ct zL;B3vXhhPsJ@B3U7|>;RtwZH}3WXp@(&;e~wFiJT$j7&@(iAU>E}a!AKV^?Px(%fc z1T8EKZ4$`%2?F3L*O054(-iJZW~N}1D*{6Z&6#(aPzX33jD_b{4ReRA{<&K_EajfH zb{bO9t}3n88VbJl%X=80WMU8>KD(k6$xx#dc#Fjk@pRr&3rW*OJ|K478VxT;wBV9! zUoQP;?nt7a)&r+@TLq6IwplC3jI%8|<|?Y3R{^%UsZupvO;dJXJYI3({BIsy?HJP{ zAozgR8hm4Z=18ChA_K@bB7g?HyiySTC2zj@+t)Co7+`2w8>IMO%q#6k^!g^A1dZ%aJ!2tketd z*5LxRVH!S}526SNQ+|9zpD1Cfrg)>@Jf}@RK=_?D5KV)V_mZVxlMSjyyV<+PhxSF| zj4H#2V$W^3!!$%EwIEMZxtoI7=Q>2j4`F%sJaX?*hI+tFllg*hrx*22xv0tT))oDp zB9!>|YevM6rK`iPXP37ZR@b?A=CHUPu8!Xe4)bkzUaf!TY-rGEnp?jf?g$qz=p%FZ zPekv1Dp;Minie5en}qa?@JLyCkax9A%2p=~WR)%0ZWD49$J7lh9DY(bEeklLIk=ij zyWJdun*I%Qw`&`SMTyRCz$hre!F2GVL-RxN>NA?#R5l6*iZe!!di zV_*w19974ga=kOW`Q7}F%==$;e*K_G;%F)At!SWO~JqHw3`%ReE%;NwEusY z1#@QWp6H03Ip^k7k-tAvaeVP9aLg7j-WwLG$Zv|95Imo+M}FD)IL=9X7aPghR%4ks z8eP4t3^-Tb>%;?;a|A`Fj7MM#w2f!7&phk3-rD_-X$HW|@Bargk5g}SE*~sEhG;G` zWSeRCIMwlYsyc@yiykjUbGVUM7g*SpmER<5o|L*`m_5?i+qg3R_s}Iini*`FzheYiAMwsc_Wadlmm>VUR!iXnMoY0>$CE zkCPk4zeQ`no{n3|XP@c!&!Slo@yfW#)Di;7ADKg-w&kpu3($enkW4M;@B{dWwS8n) z5avp{D3ET{I(Q_!7?s!i)5^(*3|Y4|r6E9C^Ej9n4fgcjhXusVl1v;dOFY$_E2w=y zX8h1+*eJ2=q;fXvWth(j>AkIOgLM$@TOpSwK+0MS`SH4Cf-q~95q@22!YB7lY<230VpLWY8K`qhvr;K zp-EHVNAT3$9AveF#et^IKS82UA-z!xRRW7zpx@PQIZNR!-|G+0kDQh#SANcay&z%q zgi0qhAj3L)FJvSzF+w5r@2|e2!!wJH|2Ii!t9pK zo5D1r$n4FJe!YrdgXzzGjJ9!&;^E>NV26p3e;^u*LC!Jxf4tGJu5p9tfE+<=@*SULACP?v%P~KqsR!EU}#x z{z-WQ>#jwOqUl&Nzu^SOiNq=D2H^%Tgj7il+p6UYHcU*sf2titaaWzMt*;1W3_?zd zY#+iX5enE2e~U&a#v<()y*c0o3`Di32?KE2GGSz}i3-)=m$Vg7;JEpFMcE#5LYY8d zs;L^t@iYzy^Su9uD|+aTa)`LvoB^V%2ep*C?yrR~m^#8m;8ws^)hNI82zc|p0GOhJ zK)mILQZ=M{dIR+rAP1bS1+vx=*jm>vAKIlU;or%}YH{P~mF`O9XE@pLn+ad*v3^*Y zHj9pEbmkh1Z+vv6&wia>`<6=INlX4t$H3Md8hEH_$vmqqzT!6w8^*g=nZF%hzSkIa zoKD*dSkhXnn>jcr95hn6ZuJ|I20R0V72zu|7Gob-5SyPFUbASt{8mKwE}NBTf2=l>#aWKzzS zXEY(>zGch&bP5z)r>T_97{XW(e*p6dCa^1|w6)LNmEpM@0~n`HlDf^=gf{8r zbT98}RDDSBVtt#HV+lbLNyxVC2 z46%SL1WdRT*g1!6GYuMi*HM3BT7u0J)p=hdtL?K;-5|CjTqn~nF0C+dx8?NY`{sz4 z-6@x$mz&j9oA!VN^-y;Y$Kvn)K&7GQfBQI}c8ZbAUjk|WM>r4n%S>^p6Qk8z*0#fB z%oRy=vog2@-Pl~};&iiw3Pq@Bj&zvHcwg&@&FPB{>Wi}WlLDfXmz{3(^0VyVOYSkS zv1rXU8)#Mw*!o#UZ-X|LIo@Z_Xpk|!LIFAm+tOORLD3HLf;&^iG zo*rmzD({nZSs6NgDZcGNoe$}f^80-uV)siyW5AUQn+}oSsj#CogMu>h$#`+cTTD0& zv;B-$NV#N=UJn$vbxZz0`nEfZM@Oh>UiH;1r%TCN%t0 zm-g_*KttHh`k`6$i`}*Qj;|o)Ox@6Z72w-NlBLKZxRnI;G%&~j((Ej-y02w0u{8o# zmehe(eJz4M3qE_kU@kg>;dgx7lm3tWV;!|3Xcm<|AWS;@SevF&eoWY)9Wlkp(DfIV ziOT#F!=&sTOT!;;viin7r4XY6txNvBJ!RSKYd!WQ7u`-{;7q~FGV0_|9#;UX5PUNy zZMTIlQs1cqmH|Jt+qm8$!w^|2ILJWh3y%5sgbRZ9`)km;3C4ljkhCObKsd$3Qtv9C z?P$4o?T`389f#IjNUqnohj;Hj68Em&62rX9F%r!81=tp=Ej{#9#MfMm zL^1V@>DsP*Pt>sf&q?BSg&L}mK|#@}XuPGEA@1H+XD@0{=1ag2fuXC3tAioedto!D zaxOt_C;}W_k4XmbDUGtcpXy~6;9fi?V3K7yHXI@@FRO2?lNcz}V>KJL!)+!UW+!I` zXBg)bN5J076cE*LLv{z>w*XTh^|~fL-p*8clc(&FnzJq z;Huhv>i;|_JcvwIeE$(#*CDf!rOWqc4=vE4M)XU9g{T{_uj+gSMCTS9<6C!`6ODmu zF4#vd81>DR%=yZxzF8+ZR6@9#7>XZtA4G&BfRyd|Bi2j6C=7J%J(m@|7HU69iJS!F zg@49x#b-07t7c2B9Ya?&FW8uMH{;~5C<_@i#lunPUgZEk0=1Y&uNenpTw_-w1_PaL zOakRxj`vFqYEkE=6yCgP$VB;XgXM^MA%| z7h4*9J=b9hUT|pVHZVCLobH8OR`k0Orumx-0Iu?p+Z0dhm*S5D3+o;M8wCzVT@yuK zCWPRc=sf*kd^+ALWfs~!nqg!SNNl~_-26-JVS9~L#pV1GuomB^hEqY3P9ufR=WAcQIe5u z{HJknXZ6^z?dTCejsoEpJeya6{zN>z`9llav~p;s91uyCmu=2QKk?5x#FdLE246ZwMs*$x zKYZZl4tqW81lpprI?Ne6$^{``E@(c~9HE(pqh`BO--X@8tYvpCHe5RD2ibZPH{d61 zAc&pF7psob5)g+COM!CH_f`!zU$N#NQzv)5oR1c=MvyeH!T@QU_F?A`a${Ou{?OLs zQUeiVo1CR()ogx#zj&_gnNZ&B4I-^9?SxT zG7Yqc;@C@1Dn-Sewx=0=_%|@bfx%3#-?9c_mbKefTux(UbeYnKd++Ar=rcH^g*B!b z1R`3SIf)&T7ucceoh*;%2hGg-7)|4)3zIwr>>ws*-`Wc+)7tMy-{#(pWh%|e+mQ16 zv`m(B$bd2Sux=|AH`T!ij>>Phc?di+$WrohA#XKIxg8~tWkqTMXTBGvgJO_Z#_$%! zlhFpP4PR_;@$$vWXK@y|yEtwJeDD{6SN*3seZ1j~jYPZR|&U|^;8nVz3T*6~64M@Iojwy&DGHpsTLCnBw@+-cg z+Gk$GR@cIn_Yr%~5vJ`vlg;3_SBsJYUFTxJGa~?RsxYLW`mV}aS&`Ix;IR#E(Ne`d zzs<$5S_=r-BU*dBJ!BPFUwg4CJexwUGCJ$SyXHO$sn3xuv45G`?ffcxptnA*cG;1d z`h1X?b3obEGO%jW!{)JOZ>u+2A<7)-_AT*P*1NZi@>hQ4_Ke)cu-)|f;O5{{f{@$a z5GJYAoBm{`^K=*;0c*A+8W)NcL!{-ai$W8ZA#1*%s37v^EoB{#;+3&AF@}G=d1zN~ z0re;h!Tiy7K_=3~c>0~g`gv z-biGZ5G%Afm;q+K1elTtZE$DLkargZ?yFE^GpH2Ca#bA(mpdW0$ zCVoZ5;fHr&vtN?A*9kGcY#k3ZqFpMcbK};Nucs2~|7lN}rW&3ik~!LE2V(4fMgth< zXbqYS0%hibn)3+EpdL@eo z+^-|5FQ?d@gxxeY?(K+8>itY`vs!ZA^e_E0rx)^b6Zl}=3?CkdUbz@VFN&etD-I%i zxZKOCe-oizasP1?kKe-;Kz(i4zzzo^;j37CYnualg+4l^g7`2Gqw!D6{k^|^`$eP$VBIV;+G8#6)Szje9`)HEFjK-! z4(9Pu05Ye&dX;D^?VQovnRfP;>?rzYiJTb$Z!5Htl^7zpTfv=boO`<+gS))(Gk2A<5P5NW;tQ)McL=5_{lr1A@o|2;~T z$qcrO?HJBT0?MAU_YoyyJ{0|m7~s=&p&a@?5u(xrQLsPu-f?{kx?%F><$D)ebZi)9 z_vqg78Q=|$WqA{nn%xj5$|V_PbqGy+`P{eCpQ?zG_*w@=Ji%HltUHvmU&xO)UKLPs z{5P4*r%(@m>HJz4uQm)8R=*i{n)HW7^6m|BZ3;=?=>aH+8o1P`ZU1eRV@^RFd5XM7 z>?$9Dd*o@x4?lM9g+e>!&K3ziHK}RtPJRmWMBFbU`)-%Rdf1)s^5Od>ox%p0d%h8JM{u4uXzro0mW*zMrq?o>5&Y%EJ!_Cyl{DR?1~0|AOkbeNL?Fk&@)j{T9;qdwa3bx<=KQ$V=02vycWlI~aUfQmV zfP>x;-{m4~K{tEor-pd<^~;~X^;O?!W}<}AI0LQ`$l3>raC?^s%ys|AC6)ocU=gdn zkYmrfTY@T^Z$0|^y}`T8DeBA0K&U=uV*X6}2;X#2JwsY}^{je+{31inwI zuiMn*A~j$(8Eb==5T4FHXIt#oCQ92(8P%@~a$kGG&Qo(fr>PM>EiXe&_9wA^6@6hF zcJz)om?NIV;*gtv6~P=y^$($RS?d0DWsTCU%=zgNjUbDd*0O!cVwvtHyh8mY)yz-( zG0r07h^x#3_+p(f0KV##Kx@^FsgU_L6=+9@T;4KtW@XcBMP_5tO6TZQ9h<;cncQNM zf}mJ0d_~M4H(@tR4Rlmzf8TQYhIG{TuR^Cx+M6pRhC1DCPrQBGG9a>wc;(hP6XKUl|X4AzM9g&U3n92y}q)oKFn1^{J5fPM9(KGjZ> zYE-vzzZ3?2? zuV%@-eX?9FAVV#!-HG_oeeVcTWs?@)gY021Djkh~M5$*=xG$u?iTL@ffnx%7A9C7G zlFge5(Uyyz|EPv+D{^$$kfF)Pia3y@2#lDu>1NTV`i6tl9AZmyp*hRGJ@x^PLz2PG zCDwrpV?5GR7a~<4kM}`U&x0=+(j71((0lu?vRBFuSQ|FKoqGF?Ohjkv#nj3#?3R4caeZ<=z%|IF1iNlbum4L9XU zJv<`ArQlSil72BQLJc>GfiYNAPCpZ?Uw_FN$$CeO# z^jR1S7LL?quIKUezAmrxDaWt6is8#Q>*dwocSnF60$PmpV}biYRHQjYC%2$1Kp&{B zBb-hR-o_nG3#(5)bD|K`7je}W3H@7D`lgSC&Of49Vbs@uWb;Z?aq(nWftSjBCx%A} zvu}&j+5QK^n*Dp_AYSc-D{ed`N1n%;jqlbn&=LoE=+{YJ=c=`Qw=czWl=0+Bl+S7W zvy=PeP;9(D%!o!-6V-*{=wHwWI}f{4WswNX&_4 zC7Hm&2oaVZ9_IlyDLN7uhwNoqs^xzcy7#b7MUIywPmzA%VJcLN$C7iKUbO}=mV_7? zWYNMFtw)2R3`*f5qJmX|Dws4m!g=}A27dsAR+}zyv}DP@DR&$g5VL@T;B;@-?NuE| z$)lVWIyKq^OHy91|Io&uwJB#FNC@@+y@lCRv0v#EWh6haZrL{(rvm#Ygm5+Oh z`aB)W>^-+hjC+OLJcZYC@v+B_Vod|^zuK2AuL9xTEgRiw-zT?-rBeYI%ho@EE^LlT{qL&`R*t*vZ(5y* zlr_heC6a`Dtccqs?$5hf?MFI%jvN$GFa@S=BUZr80GSLY|v1tW(xksHxxqG>iknmhry!iF4iFfR>x2x$0kTiI2Bz2bXD@9}ts2 zhEtV5z5Q4PP5h)kI=~j@kZ*l8(SKcoXLk73y(Gi_&St*jxmP_`ppQ`wJcB(cVFuZxFTx$R=H$^%ToihGW zvmH^b3Sq?rWf?CJv3zt@j6t+m*|jrPkikvzKIVb@hkCg+b|_|x-lyF*ssz&36jQ=; z6RDh!Z^>8wE(IL3J2W0KA3!}gi3NUIj_ufIpam7)-3!B;VfirstLJ2AJko@cK-5TQ z?9#KHtwn|bi?B!ll#^~2a4tqMgAl{~vdz*_9%tlv8V$QP7j1bke^V`fo$;du?@I5B zStdj*zHkI%Z?cnp# zPSfyo;hJ0{J+D{Gef5gS&fbmswm zBOso=k4`y{T;Vq`jd{N_UuINuayVbPp(SVk1Pl+>_q62#3otpsidU;QtZAsiSPcz# zSe@m=-)zKku#B?zG@EBh|Cf)tB}>gxF6WYQk1@@=@Ad2?uzgJe@Mr+&&5p8+HX>tB z@<&OK7SaHD&C7`MM!tRK#5>yzke{n}Hg_Hxf;C6R+^vhe60aQP3)hZ!|8mATMi+aY z?56QHEdU*9YwGGJ9!nv~^v0!T3Uh(u=ej7JU%o3BGO5ccnX9T!pkUUdy}e!kX4Uko ziD-BIQo>wGCiEFSTW-?h_%qX2LZn_3tLHx`5Q0CJ2uo9M$1sD0d^c8)ywQ(dII-j$ zkXms4vj=P>ov%G1=1xz?f+$X{{`G@fA%Ao^a=sxSO8~)m0lWbuNdomwnY*qnlwViL zVCVmfUxMt~tz_t0CeRm0%fgt0ml&zspy&aQ_CBvw;y-3(9FZx+U~4AwDx@I)byWa$ zx^uKT0fZEqt#>4<6BJM#l+EUsn+1wBLrMqkAr$vF@=d5f>~tSWobBj`nnDz0jiUiR z)+TO2Gh6%cS`R@u{*{7%CN48TqDjN5l9hX&qB7}M{XVrzL%Xs&d1N0${nz9qS&#Fw zEZnaBhc%}YX(F0W1*4cF)cDV{td-8F56Dvzs`mLFB%4AL%bnAzKEeKdFEV8rb_)m- zq=zglr)k1To?7!^wP90JRNn5xV%|+||2(<9JwEHZuQ0VvKoBQvAq@8pH^!d_FQ8^M z4~ZB0b&3BJYaiAkjwaiQM=8c|pglKhdrm%fkpIw&0oyaEmYq-h*1Zv!;(h9%&ZX2y ztkC0!zx}d#l~)E0q0pAt-}w2AIr5N8@pI=;{MHUtaQXrw+hWU`_w>VyBalVN0SdGJ zJ+Z@LMuc4n4GMLr&@(@D9%-5|il+gO?cS6|8O)rLWu98O-sBgKPSqz2)CbT7WfQ>& zA-4!;#rt!7?mr2LG~fyGu&A~dK%0mx07U_qi2ZwY40?Ba4QUcG%Nvqn%#DVkh3glZ zBTNJDQtZTVK}l%I-ndsf)9c4$BrlpMN= zA-Uq?ixHbb4U`=%y?x>=)&O??xbup{HgehYC7Rwh6(bA&6|E9C9=%ao=5r(aeEIt3 zrsEx3*XI*pX>iKkUgz8~sJ9J|f5q|kK#pedI)Tg^&*p5 zOO=diBux<21bxw^0zoK*#e?IBNBv20KMpGv>p*@SMgG$zQ!%Db5R@Su;@L1&hcPIP zE53=c3A$vGPXp{V$1Z!apw09x_lD$xb^OOiYN@==QDtd0>lQ3_br=O7ao?C@7U@Wa zQ~U)4L}W_U-1*5duzXZV*^&0X-yc-~OgChv z4&!#O-}l}7GVu}p8(rIdjj~z=eOu_B&Xc;DNr#VRG^^#Cp0Kh5>d>9twjIXY8U#Nh zVTSSPq@S(5QT|4?XBgrMrf7;dAj+55l*eCk-JPPp#YVWjH^EZ(9HRVJ1-`Q}eVYVj zvVV56WUFzd3rm9W9PoYGqmo=*yflLI!fSCHnRu!SwRYq)n0FQ$kk>+ia619DBbuKE z&|9(NMpvp>eKBAY{P@s8%C$3UvYSY)A%-mB^70{lY}H@k z-Y?1LC~06kkU z-QfQwc_V<;hVIu8G!^fyQ48t{qur!-g1F)+3ZrKn99RhrqOiLsJh4KdExRiu4eUrx zo1E>$p*7e!61e4ZwtXQ7=J1=3Ne}+g0c*q+=sye>Ixr3`dW0LQ7OXbksG9&iL&%%H z>ukDt1b+utok|TU#a@!5rjC^!@60Mby3o`JROXO$FPnkrAzJ$Xw3k9C;HiEoxyr?5g>98k(aZ8ecXbj;JXc9?r z&Ly{Ynhtne*AvJLs=z`ZIfHXd@6xCQOE$UV`?7t&fF^NahR9;@C{0dIYK$S1j`Xa_FtIk}d4^5tB~IJTb_1*D4k zp^eziBz+c+rd)!9q4pVDzb3Ojl-*^xVosAQqS%Ic_1Z{vS!;uw?8|8!3)75c-{+Kl z>Pi*4#Y3E@lzjdkJ-87|;T}>+6mhRkr{U?cd!gRWZYjjx-pSY*NMLjKy%TYM0N!{3 z_W@`}fp8DF@}(F_vPb(?V2SUBp2=_f+{u`bs3To|0|=X22Sw>h?*EtP$%(WUNx-R7 z`RRPV0gmr;k0@r4QD>8ZbI39xtYH7ZU3Sn9xK-D@>vWm3FjbzegLtq zH}U!AiwFS4Ed-E0Pi<8P(6F>(l($SJ7+4JHB^oH%Z0F|yk8*t0ysm3D?}dwzsEh*# z_f#R|y|qhqhZ$vMH^ms42Ue5|j6!=i`pb-#xEr$Tf)aQzW%96u)kh!reILwkW5cAA zqfYhI@U_QI{J3uIDb5!}hf40#5}55`&4pB3?f;mZjZj423Xu^~Q^xpi&!2ay$Y-Z< zDb&(l+gy%AYp!*kWOH?hK{yo?#&vIXZ)f1qd6~Ih_MURJ+4m(;QEr`^%0cy5_;eApQO@98sa(N{TEGM zMxbNEMtktFzET+?Y$^{peTf%B<=DuJVH~EA}<*6L-JWX(hoMIDozF z{}1+R_Z6aOz@HwwgMxUr_!&oHFBx~hj!eBMnwTPUr3yNrx2f7pHIv5nWp|S8HfsSV zsmWQvMJUPpuIW4lARaqk;lX}|oY^EDHep-@sgYoBkp*s|`tu^*3Bz{!z!xhSR5H{) zk880+pM3pHfk<6;ysd}f)Q4pTvt@923_aFpp6bMGDc@Z1r;ZZBYXRV(oV5AkWJ^XO z1kG$HvH_L@+W=MgbA-n=(_TwU_)ll=_kF>Cr$fn&O3MykofyInZS9w)O0!|Ia;?#JF9zAp z-GR&mMpH*A++Y>nNfuyb*i+dz0cc$&XML(f4GONM)XGnV3&Zoeey9NURVeb%=6Jjj zfO?}_pBu1{YFP;#Uv)BNB{o;hHF$obL|oVhpl2=WJJCEe5T@5aB@j$BZ*A+otQ02d z$xgHkn3~u1d4IhXcj1SoiP?~{!rndJQ1j%x<8@!`H+aUgFVHqDU%kk3Le19vn51dnNq!O3(5x?qys@8&HuT{%4 zFGIDdN;pjjphw)E4h&*_jADy3DY`D=>8xQKi2&w~YQp04Ix`bYC%ijC#LtCk-zR3) z$L35cHD^}sN^nY?bgV{}RYb9(ez=^X2$5~{jA^v@425fgwptMftYO5w?2dLN=)#QF zk>fcQ%GAZIe<#dX)+VPmkzCQC<-{fW^}GV(!1w1`UfmrIxufW*?P`|dEM;!cmbzSD&8f$2ov(Tyr2ikh;E9S{m z%xFKZb8&tq8_o?ZzrMAa+hc9idyY|YOwm0P_!V|#4VWUn@*zk?Y!JXa(Q5^5j6Imh@-qu z8R=CB9>RDbisrR&Cs7HR;t#$Tuk<8f4U&L!&>v(G4!)uWae`>+8(ct&&uR|QB+-d1 zJbkG4$LT@J!rJVOBI+MgA7H`5djOGbrF|?GM)5;p`Hj=|%3R}Vuj`iaXiw9` z^U69dK2oVIr-aG@#m^cAzkSFUCl>WEFNYuPsW{}`ya8Aez%kHm*B9%h;58o+z#++Q zw~b_p0%Nt0@fPnw1J&`GI{lz6&M*%s6rqibRcy*HUgeZg$#aK$z0Bc`UkPB|;jwOC z{f4sdS#*Yb?5|B29@#NS_}%%dxdK)t+HV@_0@Ski4uO#CFkSvl>1Sf$t=h6cJnJLB%VuD1*zA z%Fq~l`MAgZj`-_mJO0H8JJo=%0a&3Oif)VPuy!INbF@kvp(oSmJ)+krRSY7K+UHBF zzvQNzmLv_lZMV%$?cebekYgLf$=WW!d<<;&vt+!W zOXq9)m!R8WaFnh5%-1B|=|h{cg{?ps4B)ZamJD9a5uoU_bURnFwa_YWi^lQIIEUS1*(<7IUghpPX&)k7l zGO~>B!}zJ%r~GUmG;8S$lmMB4(QBFajEVXv%%pw75Z>v5gKyawgRZuD^fzsN31=t@ zjjrOx%S*oEX8qZle1btL`LYn2xrb_6YzKVX$;9H2`N?uc^e}Sm_<{5%^#n*qjbv$V ztSibR^4n9fFP}_+>nL;d>8DF7q8?%CT#`CDwm?LvjW+KkNqejU#Htv!#b=;dYrz+i zC*AhC+zx*V^yYNQ@Y?0drWoa?+|2EjOIpha8tbF{@a-X`S9Z*v-U395_g8PTFYzz+ zeGDD04FP6Fu0`}Q|8!yg*GJEUC6_Xp$SgxLqL^csIdVk>tL3BwQ(^BXOk<~J<{{09I2_(2#Ebh>&jR-=HOBaT3Zs; zqSo}XjNCRjs;t%^Rf<-UE1KuL^D8G3R%MEP{J#6={Xz|oEh&*En5AW>kV-Sg8c&Fm z>(Wa+r6A9l!n`vST?NGbSE(npl!h^kifbZ1RLASyM^{n_^SKMWb1~#^mb$Da4(!#t zjRjS}e9tIQN~)`qpH@aIsx>{=kggJyXOu2jh^pmN(MNF*&}6HGz%XCcW091a9`o05%b2nqxv$$l1zcf8@;c^EUG8+a25j>3;}aV zuSMV84<+^KpLpJU$VGp+s5gnm2X1H-!O(-R)$Ib8FKH%c#TUda+yRaNKb1Kpz+Af( z)YNW~Xy5IrJ@|=j^Tx7y>7(hFzTb-|2tGiy+HC;!$-q;so4lv*x9A3nt#o3rF1&cpy(5Jl^gP>7I6qP zd2CG-0`hLEXKy+sIPgB1+_^Ds3yHi=9vQOn60NX2@r3J}dY-6wk4NQgiaf&p_%17d zPajSzYqZYR-gCJNxDw1bED&2bdXlbKJJsCmDLlUwEq8T?q8yI1000+535xhE$A3L0 zD-u>A^NCl>`yZfa!IzsEOyvv2H!=~Qig0Ei0nWe-Sk%KQnWep=s1JWB-mmw-Qk4yL zQyJv%%*A8f=}Q0$?dW@`Yz9Uwszkc6)4#b2fa$27>l%Qo{iY+Yj3uP@L>se#tw+Sd zTxcN(AO_e)+dOuC7F6R~)Dh^~Ov$5TH7Cn4UVElztG(NnrO98Hmm&S7@#RkwaZcH_ zV?gJmBVulb>j+->2VvkLD^RgCb=ZtSPaUn0&d4Z0p+mora^ci?cJdOMxjwBeap(S+ zxdaff*#!dIT=j@)6ba+wIwM65&*E^cunORSPJ zwpqLnX2au|7qb2yg0mq&EKL;(vHNO}Acs%>GRl){7zw#8PlFo!YHNfZg zP@iLi?1HspDrx$-Y*H)LJ+n$wS%8{WTgUS`tbHKZ*#@D(*v!;NcCe`eSy6uM#J+Oo zMtWq`e$|E*GNBQ6TAHM86e~gW*Q9pU93nF$5@#Oq-gq+@)XN|J+Mv{Vo5k|#toT|v z+R*F7;Eq1!yAi}rl1*B)gN zofESSFC#=K#|U*E-;X8kW?TA`#W#ZR;QD8`H})*ex!M)!e7l6KAO3rqs*sE;>->=W zEq=*}*>?x;i!^_#AV*NNfFM~?H8}yQ^dOq*t8=8v4nS*BPXfCjB{x(6a)nz_I+L z-M{k$3*zHR3p2bO()|00CgPI}>HR-lNq`jrcA8ilE4Z`W?XS0>)7L241Dx%3$4Ckz zE%Q+UMdhg0EnW2KnV9A!ndmz~M#9g9s9g*rIX8{Y*QWH5Z1sCXQg4EPB=%oHMWjS+ zUHylLX4-d~Jor0rZ7A%UAA7x2_!X959albB;6r_Yz9T(P8}*K>SciIs(PXpfdRt2K zS-2}fco}_7!|~}Y^*XSrG{9G2JmPzLugjQ#n53~)h#q5QxOpQfM;#O=M?L;&4>)91 zZp(7y`zQ5}WnQtT>#K4diKKWPPR1rmX zQqgJ%%qMb;DZKACdjs=j0WCUHKqQoBco;#Q_HGz7NUf#Jr5kxG@ zzU2r^<)~Z0KrzVBL3sm9z;!dGAe)?x zmTw3#_I;V51<4W>$(HQPP>g+4&C?lT=%tK zpAV{C(!Y%2a!my9D)onyYqrO*g1>JDP1e|jT@ERPVOIifO5A#V{Nsr~zYcYoEj#sg z4DZk?O&$M?`D37tJY()UM0~=Nm3cy2v*L#X6ia8SUcTVNqe6Ty4s6$4E9UVCcFD_c z=@aepFN6eJ?d60Z;s-bpSe(9a1>{fdMAmu5fgP|V5K{71e~gZgexraHH$}=-K0w{? zEJcJ=Eb3q{M*(*Wbzdjoa51JozYwlp1d%j{^n!7mn#A2`a1l5B=N%3?quKUARMv|O zTW~>dCMlrx_z&sDoPYhl|9leGWZ(6zd1w7_UG11QmrUy+!d3!i!R30F8=_{#Z`Mek zxSmVP!2 zHBii@B)Yr$&ENaAc)`Zcp>6HvkzLZ*A`Vjd^7UORZ(D{~>M;=Gn74ZUE%J1-F^Jm! zZ?NrC#s3{_lY9flq2*U67gNL5)7z_zHPv1vT{?Sh?~V6;c^Wg9!efvik@*l>b5zRS z_n635@t*-7N4UUU_PIs_f=plX?u`yPS}z<~$eJn)*Pv^U;w=jveH*`T!4bXX`*(NF z3iW`?^>*&9YKU5I@LsM6(gN;>pHcpz9|SIsfpX;YD_1)y9%B83Gr%-urhUtV&=5~I zzAxs_`@}8i_N~#mcZzMoX?7j_zV7+SYx6233(^%*WH(MUL#DsxYGQ$hZOGOG zJ2;_vbYP}s+QE3bh}Nujhdl)ECiACj_0U{1ms$RhHQy6Z5leSH8cYF;u3M!A-=u@Z zieKKie0=MPU#6602ycp+6QZRfL`*amqnA49#LxVO3QrxV75_df*u@vd^OIB0={M1( zJsbM>ca8Ri!?*B{Mj!s;UhVgAud<1?D%d(Y#DcF;1@hyu+`T2Hb&)UkrUzfAx%!eu zOxYGsB+6M~vd>%C=P3rx8YH2vo7UG-xMYnq)m4Ao+PO(mO<394!J-W5Sa6=Qc{wp~ z{9%7Qy=zO(s*WX=f!RELm%rOpoP0%-^Kc6taZe$#10gbr!i}Fz*~OA@CQt^J%Un zGX_mRgE+0(rDUzpy8B})``9~~+?wPwn| zKPAaJf{1{!JnVjK)MS?Q3kd+jHx(~25%&#GungEFTe>y^x=+jFzZF$fBwDwVwHZK6 zMYtqQLNqt}&;yAqGmLAnwXsYp2nJ`PI3exw{&Vofa|DTl5l<>XFzX~wqay3}v3p=A z=~UsUQqnhge?Zm2gf~whKRQKD7%j-$+9(o!zJ!!8GyhaC6;CXIRRlP6`>JL@RL|YK zOj>=3Xbcv(<7Ybm<+l(-Ck193v+VoTX*&F`M#1AhkRE(} z`Ch#z(aN)I1@mE_jOpo^tguo}j?6%uzTTc!={NNgt}Ou9<(zs;W^l2}FU#_E4}>o| z9gVB7qjspRH464cw?T3^s*W}K|MAhnIhw~xujNIO#H;l;{r1`&d#E!>*&oZDPRH2C zsKjO;ppU*tyH7Zw#)jVYip)7ft?n)Hy;v7hq>&RZ9x5D+6)}DN?l3rp(*3qU?>1!R z%{p@XoNDN+Bp~$kl{Zz;hoC{|^r3}r{B}q{`$Z5!G+O4q*dFg@^B!=IQ6x|s&U(~Q zC7#GB4Tp*aT3pGR0f(~kj^pdTJ9M_SrOsC<` z;=tQsa7U|JWo*(<-Yipw?DWV-B)Of@B#5j@fs;Y8u8sWLf(V zh8T#7e7>tTcR*sqJLw*|qcAAWtE#4t20%f^@RuzYy3cbk+)kxWCQVPtpLKO%U?CCAhJjP~X7MMxWS zux`CBKox*Nxss0D`K2_$5^t--g2Cp!3H8^kC@xC0LOcy3@LH0k?x%Cyq2R*brd!Jv2`*nUe5Tt(LHzF<<1%3~(yI8a(4|cGexqXUoJZse>4koQF^R;uw9QOg0SUFx?FAAfN480DMV@Vy;a$ z2G1Zg*ryckf`+q@#pU*6RzHEPtxX;pzhi^ANpWLQBN1%4t5r#7=@;M zxP9TFv~Co|WySv{)P9YE03l2N+HPrq?Uzjv`Csou$J98$xwDA2WJAKGK(MnZ9LWG1 z#r>C_(+kdtb|Z&7sLu_0aGaU;UYJaGIaTg^c;R=dp-L;fQ_oFx?YqJkjCH@o`?~LQ zd<_=2t|k|BvJAMi_xV?EJb2DoqfWiWz;=p zAO?B-ks44aN`(_7#uJeTQYv!xUUT9HS9{BHkmGkFf}{Lc=u@0%7vFnBuRR`-QzYrv zY;r92yD6J$gw=|9(VOSgEXIU1$vtNxp?8H=IH%&TUM&s?v4F^O8pQOL8wjmH^?EKn zdvYA-f5=7g#w<&YCEZE}+`4^Rbe3&YsHaA^j zEo{f}&8_h^%v=?Xd!MmwOV2bx1oEOEz46CRU3r70IlX913VURzUm{O_*({(v$zn-R z%$&da<+ryd0b_PEx2iLy5|1FnuB?HuHL}P;+>5cvQy?o{yac;+S1u+N^VcoMs3P_(c+zWS%Zbgk*gMHlB$Mj$RvWl6i-jif{&(tgWFgpRVYj2vjrg>Ep z=AFc?Nt0%1`)SomwjR?9cKBLy0l!fI?YIUfd>bBD4Us(t== zO6g^q@aG&ZKdAFk(dtvr+XTSE22P7vuaL0{;R^TryZ zHpED{q$05+`3X}j1&piPG|}@Pc>K@Pix_~8 z!h`5TV%;$=Nqu^KpAqoE?N}Zv;i1Oq8g8M+v4+E>U4$@G>AHv)3bo%a@1b+b;P2a2 z^{Bb&-r*$n_gNd=AyZo;9H!IduoiBVM~QKfa*y;}dX6oueUNq~4;P^7cgjzSVpaX6 zFq&v{+k3CX4Td29CGUyoRBz|Cq?K$vj&>`3K(o4(+zdl06oYh;#xKP@g$@!}VJe-(FDSIP?4aEJP*Pu#(oGMpv*j}$dYE8c0 zm>_DFz5XB}d&&l@V>%0b3UBk}CsDC#2{(F;yUuO-Rb2X%1SE_Y%lwJDnYnXN;SUf_ z3Ve3%w3N%v<>MN47ydedfAmK{$`PE6dzkc^ku-dAAj+WTtL|JJj@9rXWj3)I$^Y3m zCZGEZ$n-FOFU2xsIW7we+UOkDjU4+yrc9Xn!n4$|Xnf4ldBbbP|De$lt=5-4z&+M$ zpJneqq7cij6*NnNz&x)DerQYxkwM5L7gL2>ceRDoZlJEt-uCrFMt<7&{G&lD7cQLh zI3^+u$+A@o`Es=(g2B1wII5!9kzN5hBt&+0fT%wUMSTS#LgW8*(a0Y47E^M1ne^WHC2!F8}r zU&!E5Av0ypHeY3ut?B7Ru_s9;M(S+gH@Fxuh6vpM3sHJB4&@D<(HWZ@sm&=A_ZQDz z@(<&CKqH@?32&3Vm5?RkeCCm%pkty{S@S0ze`CQvuDj}fFPGyTnctFE?b8WEr*hqV zazSRvr>MU9KPLDN_$9ZJ|B9{lswm*HG%Xknk~tQWgw=z?Ol*oZ9tGUlQ#g4|%3vAnNa*|`(>zUKry?>^qu3Hv zt1dHf^;|?iWpB#*2vh#g{P9JOD~+0Fl7IuO>{w%+Tf;W)j6$M!_W{+?5!CONYd?E7 zizR*CpFdl>8}PK_%Og@GRyfuncI0L6?#Ej*yPwt804j)}V%w$Dn@TuP2ziVYnSX z9Z9v*zE^V&bX-j_pM-}@KWR4z)W)y22!qtSt=^MX;F_EGbA#-^pEN!HahA1A2hAYu zkY)0qq!KUlF!YGRwUUJUH=5Tuj{wW-8AA?_y<0+)D7JTn??b)k+4-x8FFQwf)ku@* zh`NMNfA5m+rEXj>U0Z-1z4hVL8dnF8z!9-)9!#e{lUE}P3Y8q3KzQxrJ)77bRua`> zw9_)yIi%S@wR!&Y!?rg9>OEy+0haFXm5${~^|V}=yA0`{hD1G!O;nXLxl`Wpa(>=` z;~Uhc+sWwYfx`cYW6ANTdw&xhyXfWC_U(IyO6eM8%xTZjeJ~*XIx1!G{hn+F zs>GYv_x97lw`~lQ3F?3b$N~3hJRHw|4HR158RI{DTZ3`STk7o6Xx<+Ap(upaOl8dG zdfK37cMd;OVSs_-oKJqb{)q!#nsLTL=C#EmAR9}LahL)y5DVV1_^RtG(EBk(r_Ji) z=dhflD~%5ueY|%${FFXCO5gpnJN4E--An6<#IYGb^y+8{|t5}T)}k`o&a z7|6=+5#SNUc4NWl18iVPvX5{ZI+2UL?Qu=p=oEWO`(TrVL_XN?{8RQS;6`qecEyDj zor2S(d6i(VUN4E2*^3JO;l#01`RH^4-=k_N{z&xKf0^h9F%KD#OxQ>=jW^Hkd}$Ua zSM|1L1!Cjq?a8a&}fNWa85S5BhoQ))6P*qp=1=))c4v!bIk z9zRaM=gM{5>6O6_yHdhBi&q{s;GZ2Lckql|3D<#~e`O?VAex*R1W*4?%O8XNFcg?N z7?mjC*B~H42lOZxKq!M_t23t_O;JN@dp=F98AM*A9gJ`jlezIw=t$7 z`TM-{c6N`DPIV<{{2=tWI>)2cmtXd7*GWjIU5q&{30PhhV9LmA%Z)az{~pmvtmX*$ z0U9tY{wTUj|8Ve|A!!FgpHi~erifvt0rk|i^}ogk;>R=laZLsqB$t$%&E!@Ovh3?!<55WcishO66?8XA;Q z;|*vq zl?e-bDhT8UxVTg+P1?q^M+*SKw9@?xTu1un?)4_?ey_&3Y3x#4nv1NH*@;$L&1zrs z4_KGp*W;0nDQid1-8BjG*Z89lahPILu>3w}2X4)>+KV^EPADv^@3}xT*@PoQQSN(B z6A{>Rlh|^iSgls_@%$EBqSkW~8g=NoIDu=NgfM=W8{_^m0idrLq+H55wPv!>5rH^n z?b5yR$q+NR#)!_cZui{-G*2o&ogD(MpjLG19`BG!05P8%(mG1OL1%P_6&Quy7}zXq zA?#M71a`ypr-h0M2_m)fSHCaa#*$+%QUN#Ypyb;%`NK1PH}OiM_QxvZHDXYGGV78i z0@q`^TLLuMQZ6M&e`x6PC?QbwJ5u-Zp8Tb^`BsC&9XI~Y+6CxJ73VG6t()nC_Zb?) zc|4^o6Vh``=+Wiyeg5K2B54fO{d2Xx%iUB7_9@EqSgHh z^nNk7S^w<*`UJ7cJpxV;SQ_rU_w@R2p0W;F6}qJ0JP{w0%9$#Enmh8i6<+FE(5fml z`?&g2xeTr{c2$J#d*IFE%Ukd%?32~Q>2F8&=#7gbS{=@Hzy9702XQ77L8@--e+kEQ zzW!gHF0rNh=l^*2QfKL_g0zN-OAh4%K=@65H1q`stxPtWC3^8?{+4rAfeKO&_R3ty zd%)inQ@6R#VYw9ytca2;IWL#GYM_l!Io=LSKgH78E(wjV5}RBfj;9S!Fe2J#Ui`)g z`gS5!&(%o_fXwG$&w}^C!oWisImG2As@}$$Am-*;Zv49D@k;n~sstPI1MF@ejwK$o zfFg?$;sEt5#igkxZDC|5!2A_f_Wd7NvX~p!n8y)%jnWC^%?hKouXRSHDpy^H((PP8 zaUIfidW}Cpek`F>W3rKNaD)idFgMRUOBj)EM&7=GvOj&HL5&%Und{hl;D2rssH`-`#!? zdUcYau?D`-uBYd`KRY{v20dd9SWkag}lYSx4&E-jc1HE4k;v zNc}})Td?ZSBhR~CzJjbiE=O^9pN2-!&RexlXxHaP?fh3uZeE@JOt6$#pJ%-{TV z!aCh|Lb@m{A5CI3bib9D{!wu1m&mn$)~NXP@`XKXv>^N8U7FxYOnjN6!WDD551yJUcG~uU?EFe+3_0v@aIMQb$Dp!S;lW|V+%#fS?N(1#7rk)N!>`7 zZ^a2MpG|rPrOJhyARb#9)4HAEm4kub!96DzQ^td2ufpV65MBRY+N)G>7dWCt%sKFW z7vD$+>h@*N@9LU6Ei*^{ZP0*<(jS}+hTtb&3pZT= zJ8x&;PM*1dz3mu8TH)9Nkdg4=hq2$Mh7S}=dv$e$?xk&)ZKO1C@vB+1Alw;*9v zQ95x=N;O{JwEULnA5W8`w*K$dvhX8{9##d)0E~ z*6W{DNa3r}GYxz=>?OaX|PAL3oge8g; z2Hv}UbOvc@%%J5TBS^YGO8X`5-s1mA^dtYDqVo?W3IP(KG*X3jqxhENmuPrmu79|<-1QD=(OSWlc!XQ zw4Hn*v7_2&_1EC4EF)SBOA~gk=>E9+x_x}+Jx@aAToDEzU`uNOO!vrIfq8kb&f6dMpZRB<@%wK>dGH$>O()W>~c(dWO* z7*;VJo9#9Of7As&ECI6R#6_$Pc{2w;Z2U_0ZfZ<^jGyA9 zsrX4hcpuK6c60j0XHlRAB-WO`zjpQbITJx{bvA}$#cuYx`SAeU;d@@KP)FNBuK~xw zQ+us~V@sji)kyP!TWG0UcfAa6y*^iiq+WTQ1yYwZ9Mb0YFKhdrd@uEwMcFDgu+V=^ z;)}#$eaUtAYALx$^qc=Znx}p;sJ-$~Ydp~|V8ANmxCMv9KM!5_kg3{uU6$W_-`$;q zSZXXG#!^0j7Vu zR=(g^Uq0k?tN$Sj|5#!xa9x2SNrGP;Mk;m{Z0x_9>uM;m>|C@1Cpg|#elnWFgPK3T z{rrC_(Tf|}%Q|bL_f;!~cJ)VrMQM}0qIB^}4=bQ`wj3nrkV?lfPC5tH&Rc+VPKTJ1 zBm`+r)Pcdq>XAB&86B154_Y0@XRwPaZ8%7keO-D-@-pQnHRWjbm@q`~*eNj|V}bi8 z_NrxuLY*NBM}*rnCE?w`8TA%^0yRV0trM4$AhvldY+ytc0yfHEvNGRi!eWzvWyzeA z$K-4{fWhh9_`a;X?RJ3uuzNY_e(mS_ za#8;n*FLWL2Mx0^rM&xeZ@sv1$=S~NXqChM)_cE>JD%$rBZz}=s1FHigcPE*}Vbi1kCM%idM8y8Ba zYeK(;4mNkA|!2;?cf8kbo@ZHjX~iAx=9(deus1Xxdd4eQ&@2#6FtPplfkf zJzVr~kgiU6)N2K^NyYi0IAFK~snLcVRecB_-o1VHo{HHdu7|-2$%Ms-n*tD(pGe`! zr3&0gL{$gBpT95>@GXJMGk&Ar^tb+Lz>`UI)ttF@;D_E|^k*VT#Wzg9k;oR4jo#t| zVMpM>+wxegkJpufnyuPQ#8Qm7fb6o4R`@B(C{BZq^!_Q}uz(p4{1H;X*j z>v3$L=VwSs)3DqSXSQ!C_mHs6)(lPa8GwX*yRob2p>j!I`OP2_0?Jp^iO0`5i5kv7$JClulN2L^4gBq;Psf#QfkRu z{mkiY2j_r+jDdOY>slJOZlo)iwff1zX{s^_T3s62x9!t~c0VCt)2ph*+jO>-oziv| z`rOhJ5Bx4HTU^%R{q|h~>J7Vbh_eo5@w4G+v>BByu=;0R7vejbB&gYDY z2W+#-n$7S9o^Eom9z~t~Ol6YXaLCs9(jh|l@*t!pE90L`VEj?zhnz0fkGzU{1**bg z$43v_P}$`Mlw(o7VYA%=#%!4kUr=2oZW1G7fz&apzjhsonr0iTD^b_W9gwRF<;w>` z(?LzR*z`{mVk2Diu(I&CVBLS7l|UXvDegr63{el$q*Seu<&3ix{9edG8*gnZ zk=X`vUwDC;$Z#6UcL@*Su*-gy8GM0di&lY$682Rejg+PYUv~a$_qX!Hw(lzJn=bJZiLn5a`3FjYuxY zCNPTKpemkD`9R0@P{igJFJ=O6$ZnvmNOv&1AD1GfXOma>jJ<5YdBQAxXE7Z88xwSt zcvRT)aQ#|K|3}69K^Y3Gi!KaA`*Pz@Ll{gbN{ljKJGFDePL4t@;x1M#GIwr07$!?e zl4(gLaxh^84E@pM{@T)^Nzp03HWaH~ZIm)S z3V@1KJ+t(pXvDu~v7pt@KaMd^7wT7w#sG&6q-jE=z!)I>D=rlR`{r_)aytftYd2>7 z5t_yv9%J_T`Yn5$5NIul#_musbf>I{^1XXdePZr#GRnL}7MQWccRa z`~b#k=*Ca`=}SJXxe<{%qR}g(@PnK{t|on5m>MbQvr}KF>v+~_ zF3RgwgH(Tdsx~MMXuv;d(6k0L(AHfH*jJ0kc`j9Hs7ZSbbd$H8@n!;CKdM zVLN}1^eUXmmE^F!XELLx<4ueshJz4!XPLXiXCM7bDv2K%Z|9cuzYY#@0&k$Z(sCRC z7p)Y{$B}vH07*~f9NUM)ieZGG38RVHk>|=IG+N|30UtNk($k*Zdv>~?l4YV~5fRk8 zEt?lp4qxxUqzO&Y$pVx@Li4OmO_BL|7Gm=0k8;H7!bzpGf!k(Q?kz5J<0jb(X2Xz+ zshZ5plE3DgF%8xrLk2Ck*qoD+oUgFjK0~`quVKQ_2X+HJm4{*P#IM348?Rkowq)Bm zuO6A{NE6@ffZ_7a_*JegJ3-h%%YvZ>GZRz(J-5TB)2P3nA(!PSX!q}apoyFvGRgbM zk0tVS9HuFddZ@$DLcE}J2cwB`vBT|^&v6d;;kZyH-L2EI!#NGDm^LzV!zmg?{8$fk=@Vf z`Ck?&(e?+eOWY@G?zgW9z=yy0YVa;z$^#G=;RAqjq-?t^&47e&358hkp0b>c<%))-u>e!K77ih&TUPcE2G!l`Fwy;_mJspZ)!QpH)Aopq@>HE*U7 z3NrIJ58#Mb_z!j*q?t`VeK%kLev-CODjmn^w6E>IcPTTB6HJV;AKJ`*71IK(iG<4X zvuZBTyGJXBKf?glGWz)ola@g_Zo~naxLsu#OgG^|QyMPCXLwB1)|b`fp)9ud82*_C z^VMt*qS&=z_C+5#G%y?w0kXv(BE=|E4jnMXm_eu`ZmO*0pX!{M3i`aZ%+5&&!Z-8#66Nd#9#?$s_(n@o0q%7p*;iWcu!5184!ZL63+;CHc)(}!2lY!U(EZ951r9@B*ma!sROQ0IfF>u%^n zeR4+l2Bu<+mXq4rV9fl8&39m*%GT84CiVNWWD~u`c5?tm+iqKak+ShYm@SdFJ%#Cq zH^SU7d5uY+&mk7@?{g1h?lAo}4?@rWoa9YvO$~OAs)PNdJ(l7zgRc6?N6lE;2z}$75Z_z+D%Z~v^JMZ{AZnn;ceu63-RVY%%{LHw^L9XiUI%5MF-`@No8+(M7<reYSYu9|aN`_l_#`tg&uuvzg8fUOk>2s@V%BRiV zJ*ruCbTLLBWx04(CWekw#v=DK^+^M<7=EVkq|JEEN_W*z2rr1BfD@W-oQ}b0aQzMQ z{<>@Fu>N3>3@ll0bi*Q5$Us^?_ICcZ#Vm+bJtu8~_Z18~KtnA{1Df~g7zfP;2JcB7 zoXmVfiyIuU~YwN=MCxL&5|pS}~jGOY08QUe>NB=}D|FkAWm@ za&2&+V9xUANp9wlP(Fr=3emmB&wxE2vu7#ClA$U0brvjDStl_}L#M$&C(1N<=!Rn6 z=8|Dmf7WLhngaBj>09v^3*cYbS=d&H6BqOB z>I1s_{q>83fAjDEQN%26z9&r#M%%u}nsG!9Y3xvb<9p^iI^0-`i1$QX zbe*bPW9psJ2e|25U?On)8^vk3NNZxI!tOm>F3RW2M;9zzLD^wY$1L5aTON(tLGp%; z2;~XG7#F+sxuP`Tm4GELLNM%MD1Ke0r6zUwq-j*3ZKZ14pN4o(Trii%H|Q)agjRe5H$SF>s1 zRO^)7K!QJhrUcX|j!vW*?xuBN#gXB&-Ea$u5NQd;d*}!0MQ{o@r(bIb*u)?OqPXB* z6JB%&QVrAz%0z@3urhV;W;gyk$K2XUa6kZZ;$l-kWpMqDZ({WbJl*`^Nl_ z4VKf!dfToRBF}J8_uHyv_>zS=XM*siV%UBZ>#O@v!zxQj$l_8*FdlICn`!0s(9H`& z*=`+S*&FAVRamz6H!@)zYAp*hit2^4eO?iE@S)n3^ikK6FvpH zeg&@*bYkx=#miKk_wddM&?qC*{TttzrWa+eAJW|->+RQj5#qnS=>hkx?mBBU@|P+>~v0Fa>tZ%Z*8j1)F4v&Ziz zg|AGd@TJzphbp)5hnZ2enH;2C9c}v=*cE#gl74wRfF!K)waKVnL4Pf*s&%@=a zHzYy?n%=sG3)g&nrLb6=&jE%YFI9h@gnkR$KFUveG0{8MMAzMRK_q1A`gJL^VRWxd&z9EHsrLTukA%b;|+LM6IEo*KAq z&Hiaq-cpZI*p|DU>CswpV^U;M6s0mi>AUd@yv*y{}@S!`+hb2NQ zlfkmdat9<#jiQJ?$AS%oaJ~Ii$aarS9WP+)giLai@{8az$YLA>wl8Yex&tsLQ1w?M z*q?~Ba`GSEj+KL9t7Hd~d&kW6@C9?)sO}<%`O%Rb8sNa5&#ab`B@-W6h9UU)*Rs zW|pd3{X4-<+s2M0MMrjbpma;8%U|xCK%+)555BBsMs$czR%|q{kq0r;$Q8IRLLLU_ z18;Eb=^FpFZ=x8TT?3z1)~P8v+TCH<9>YU3v2A8;H0-4A`bEZT1^RUYCZ6!qXjb*M z>;2!)3xZ&Dwj$MBv9qe^*Lhch^t3maeea z*VHL$Iw?eu8vd#K=77Dl11(`d8Q846Iq7%tCYFv-J&PK*J z!nVX^!x@HK-boZ<3?LWV0mO#c-CY!(w}5l))+OmZ_x& z%NfjrPk?G`+{>{I*E}y?R;B}I2BdK-v#76UR?_)-gYF-N!ydS6#x{FpCd&+E-~_y~ z;)w0&%Z3&|t9=1lerkPIRGz!(MeQqR;9fu=7Q@{kL~}y3=bWaK=>sxtFkkLGNR%|i z2dBoCiY2bD0WUo91F$|E-6Xto8F=YLFQ}P!$1E$4(_UTIV@(X62){xD_LFKjh(s1E zJ3Q)Tm@b?XD{s&?{aXcVXdA^25&*WZ+7IT|Xci#-2j;V}%()nYz8j6XfK}uEZB-BD zTQ%;_fRk`sO(Eel;08MPC7gNp5e*$0k;~%FXw_#7Xp4O^eq)O4KU5f7Uw99H)28#^ zxS6wl-{V8C6juMxDUm@)WdDWkY0GTvjxzcq;7AgVL4GmkTGINR&skHlYU+0Z#u+6F z=Vn{_4lFYZQzQu^~Tf+24$zC8`h7PLnt3cu9oh3 z`2DK8BxEl?FlO@VX}ny-L0dGZ5-A@-HnO*7l4F6Z*&LJ*xyNM60n4c!z%#?hzRho7 zUaMBO>%Z#Zlg^LL?UrATR@l`u(}UnrER@!z#AcQr7hx(#3F{ zsd+GPcl~O^kzNEc9;?g(VI(ilN}84@{ufdgmHa&(GB~{vU9-q;>s{MH0S=_|6b71) zzm;+kQ1WFBU`Ses-BwA|ne}%>`h`69N~n*orVobIUx0zOsj4smJGD4H&(%N6SaL#qc*Q zd8}?|<7$yR)R!yI$V;DtB08xMgS5nZDxzih5Hhq&By%*MAlaOsyJ<0W>;BYt}S!cUIk433D@F) z^pN}3D202)4qHwu;ek>6v?tob9fOL~6g+vOE>M!O^PB)D?e3&&3=R?s1+*weXawH3 zbh`q8+byt*v6Z1D1B1F&B)}mNI=@ket>KWfuoq#95Qxa^u`eVQbRUQ1Dq9tqY=1=Q zaH_#Z2%Gi>^G%L5rn+wHNYM%#BC_x1ZQ7>#;blVojFdS%4)=nIEo5?yKi|wAE?p8R ziXD3c!~qdG3U&HU>}Px~?jEn;jK`pjQRM{qC0aM`r28z5>#h9o+$(wVg7w}w@cEhz zqrgDk(>BOAA~U_}=h+*wWXTYTuycJnp!kE870p_Vrg?JSZ+`#`?MMKo75`&6go}39 zZg5wG;)BJMJR{dUxLy(cLXRto1Fk%Q;bTfu>Il*F0Fn__aj4-J@x8fe76Qu4MWTbRgt01}`j(wo*QRG!2Cp%}gY9}76#H-ne!Bk-9 zrb$HY3sX+5PdmrN*=*|1|0+Z|U9TO_b@I)1_Ck7^O`bI4v2D)qpU`psJOgGQ=^^Q$ zt#TM`=W|>*3BGlhJzK)h;CbEL3A4t@>mHR$m<;i2fIoFx*YhBk?A#|a2=HXA6VYZ! zU0p@6q=ip2yUp3%@of3& zZ6i6X{WK-Q2Qy;>!6K)F8J(9*Yj6CH9QZ5m97ZP%&L4KfitB zmCyF#eoJpbzgY3z)H4MNgd89DH%7amYHcf`YY+C4c87rM6ED$+@9c#oo|R{{6a`xM z!jdcnvlil)JG4ss>!D;XIBL(Hje?liW)!TVrx-3{i$?;N@ViBg6i@66|@fv{)9 z^w*}1y+$YthcIN_=!^TOKYa;WR+tzaXgnba@zOK+f6f6u@F@&(m)Bxgj_J!;TJgx4 zq6!|L@Bq{*%kqjtll_?62jiqU*DTf7Y_!bM(W|N^SX&NcW(h@k=2_(o+K#=;Y70 z^Vm(TyNlS(7!1rPwH1YD^MY2(MLeQo$IC3k19d3{-nBO@`h-vVsApbN zYrmU&%gkE(zX#x>&dfy5-vLAPIQl;O295SF|2eDlmD%&10JHE&opUDk$?VXU8vPcq z{PQ0vG$ys6UNLOlx*MT}(*KN{_{w1Lp;efJKW#QcYc^3&ksG|2AJ61~5X7n*@!L`+ zpseY*$vcIZpQ&BLg>L7I3y;{aotkfV-i|&}QTK6fbCVFroXx1oho;;a{eY@fSp2Jy zwP+`nH~;)qRkhyQ59`s#Jr1A|TIB|f&`#A}IH9-t1t{k0Oo1GJbtbr-3Wll{HSeE| z!}hhQ!o7AJB0ae}WN26HDq|0#a{~d+Q0=?|3uARgWps4l%9`Cj23%BZgXQ4=%&l*f0qe0$OVhF{pa<&Wq&{a z4UDu1o0qTUgbdq^WHPR++MhCOS)5rt+P5$4rQ%vcz{EYUK{qQ7fDz$jr2ueZRoS}! zmh}s)h@Ee{K`6w_%;uFq)jI{xZ01Fkk9kmpK-j!~0H)(f!v+8<8`P0As_RfAaPk}% zoA={w&s}+JC^ZiEJd!8bKT){3ci!fI?u=?xFA68dIOC3l+Sx% zxTNbbXaz!>f`(Z}?28+D-odeBc5c&Sr}xgYymy}K))%TPj)8C#ILG|f*lmUDW)Jty zBc&$*7Ryv)Glv@*iTsYjOj{BR${i(&x`1sBX#}Jx&#AQzRsOvBY zAP^=u`GX@rZ0`Mcoa3w(VyU%cb$$Dx05F>MaS4g4Fes`RL%mcWZ25eE| zM@L>yh!Rbc)EY`-PZ{D*{4TeRT0KW`!)if@{7m^tpZ%pVPHnY$HLUi{k)5W=mJOg> zf^At>4F1Gx;JBHVV&Azwi6%_z!=LkFsQUiIe>MRDny_G#nKhELJNwPnC9ei^;LEv4Zr;0EK>n@=1h zUgKvG^EI>noVd+wicqd*9zJNx%J*;eG;1k$Sw7l#`s0{`{6e6Rww3ku2Aed{BO_eF z{~TLZkqlO)P_lYj|Bb7WqS6o9Lrl{fJ|E^B&<$H-i%zC!sy3yp3qt{EZ6RjY*|CK} zj{-1dNG<+9bzON}6Ia{K!XmP{RFn!XZIHTvh>9WtDs6RSvuaR-2-Y=V00lu=B)GQj z9jYjcxJ1xEz)BJnM50zLbwNV`4O@Jz1;hYWHbKev+&c*f^?QHsAN_;L%)Rq0=Q-!x zk=LOp3)*W*^>=|B>%^$l{=z46)7R)#;8P(%H=SjW~&0S2; zHdz}v8O=Sl{x84K6Hwtsm->8+GgJN8p7?ZvZq@c9&E00o9?KhP{w6mzKd9LCleGJB zH1n8TTKlovxwgAdT(0Mxe6?2PHh1f*q8IA$RWE)Xe5|?H`aZg{sK9U(Y=G3}>7vEkdgCUqo#ABoB>LHyRr5ito>0-L0XYbphc|qn^ zmbqB2)IYlAeOH=%0u2Of%scLuPN$2j5d#xb6!7P+jF6X5pr*%M@;<;iGOCqPHWWIQ)Q1^d%Mk8oOM=S~<2D2;XVN70OrdZUr}o7ogF8*S_o{VQf@Yo{ zqU%CRZ>#)iYRk^OXTmW97DnsG8qjV)=ECn&WNw(OX`0S3MzAD1^Na#Cv}n-Fq=x!Z6}%0fU!4 zVlJJVrp8ZYxQyuxQ@TE3w8m9c_qfQc<-1=wMYQaK1EWE*5{CC_yN$Y?Z<>12&a1v? zk%&{7Yn(O|-Ot-T_Er_<&@9lxzn!9dG+UVB56wT7IJ9II8my9+H~2L3X>%e z_j6jH6nct;ih5g`#ksZ*jbWo!x?fFN9{?K@T@~_lK~IT(4YTu@xa=K}K&L-yai)<)X`rg5c?In`%gk!@jIB61)!*(CDfs#R zqti{#cAl}8x?g`|VYh;9$et+;g!?C%p#WHe0$|X?r?-E0iDW`^w>teB%uaqS;mWbw zlxHCRF+ukqlTeiZ5IYEXEQl= zzv1D&%I^{cy|uG$CvaWOR?52gk<77CC&Id$^>-aKW7)o2dFe)JkHwBig$}=?ZH430 zJK|#VL|1?vCJ(mRS)JDP>ZlUePht~Mx2J`jT3=OY?K)%avxy2b^<>PAl>XV`Pf9NV zO*OC4_!(B*zA1ik5YYP{qxm5MiD2g}<%;;`i~A1b=&uzf#>t_qfZqTTDsV3BwsN z+1R0=GSQDauEEUmz?9v#(SuvkxS92?!#XV$f$z`jHZ~i77}a73eu1%iH}*>}ez2yy z=DKyf^Nx>X)cjRlw~3zfy6I(Rd|l+rHTrW$?yzZLaOyvHHMtb+`15vLcBkKK{_|ly zru;*`kFE62EL=P+oY#Kx^o>FYJ4VmdGKg7Hn&OQf$=G6sZ|Idj{ysD$ar0zTAJItx z&!uOj4zCTWv0S=eEuDO`XE{gN^FpRRr_yW5DX3htD0#+};V!0~GdYt}T^T(98k8Gk zhw>{*YxQp)C?Bk3ZXQl|*qlJSC-Y6W`cScaOvS=#|5=;Im*=y8nepoW-SIZ9MU9j0 zjHy3*dNdBG*N!=0SrCk#8!A1)ahJW#G;&&)taBy!E{j+C+x@RDl`I6U;~_Jr{${&{ z;?MVSiz?~LtD9&cH7~j&N4M1Pt*p`A;n?CIpOex6-;*@iL;73149N-fG+00h~-u}qh-ot_F4TFbMOZ++c5QcZe_ekz7> zOiEkGPkiFj2De{C3H-ut8A9%sO};@8|J1>U75eK8UhIWMOPVFPZfW+ zIqF-8g!_bwE2#d-k4%Tx$6L;RDNNG;hi^E1za`Ul!YVKObx?pS>&s+^Hm~i#io0suR>U%y|Dw~7NI}EBTZr<|0 z0Jy^!#*B4JmdLWkCt2LSGgs5I1j&F^h`c3i5sj&gH*hndcUZ6T#!ZX2&7kvmQ^`A7 zbki^0ZTA6{jMdMg)w)++RHhbG)-qzowU`!Ec*C?(!aD6~&ln?+6g7tJH|v^u{VpP0 z#c;;Vs=+K1fk2(3PohS(UpMUSN0onvZGNH7qkGr7bu>oCcLV5?OzJdOs#U?!I-TDr zUE*S4TpWw=U1Z&u`xA@`Xb;(C04_vH=%)+er@04~gM71JX2G-C2%!HEaguzvawZ{n z04I(qH?yfW%(OZuk5ba~lQHV;;X9uGyA-*Spd)qU&z| z!TmFjEm~1FZk9<+Q zM4iYlxdA_C6`J!ZfyM2BOkD;4U{5pAJ(p%A41A6&Kmn=%?WeLw$cBN3^R&So6Q=0| zbF0%5fD_J5CGpL)CZ^A3-){AkmLG=S1J`GdOm)%=c$;5f14pc6HYM4;u?Q6i%`yY; z2vJEXcz}NJ5@H`1b_)y6%IkntD_%^RXCi57mucrD=t=%(MJ?(vO6R=8(IHBc+8o%s zcjUux)j#F&1wdfwR4rrQ5q{~5-Uv6O<;Nsg7Xq8(LwEQ1&}cAdkl*3G+hx%CmC}^~ z=DsW4odseudYa*f!AoG^7o;Yv2g)o>5O+xJsa(!B&X;aS(b7Hy?VYtSPT9;-so!QtMoOyP8#|!gf5ov<@ONdrw~kqS2D2pDuF0G4uhVpq*QO3BsJK4% z{s}1O)k~`ZVNwu%?R%nwC}9LCRs-(5hQq-W9&yCh*vIk(YOB1?MD(y@;bG^D1Jj7mj2laqKo*XK zot;@MgAfb;t%8*O;FZr{ChwAIU7yg>M^q1~H*6osb<^=>mVXhCI!BAp1_S z{)Wp){&itej_@~x=E!zy^xFZbIlC#xD108oHtCgX0km)ZEbip@YRgc)9qq3YvnJpB zU<*S+J54>TbF$10#eH(Z`k|vr6}Q@+BhhP%1{jNrP-~{M*_ohwwFOqaG2ix6`OB@8 z@>RVcN5AG+`T32P>)M^NJG&?IU75S?T_woYzgZAfr5u$7BvG#f#j-R)ZAiv08)mb` zar)Xn)`B$q19=W!WA#@d7kSNUQ$Bkfn2vvX^$T!-XiC&A&+mweeN0~{47@CK08R!* zv``pPk09 zww<(5%ge6fm^DE$o3zvqDkap6>Cox*#(3B-whuy`{*6w{Dp?%;%sNL1P$_E<3vwy6 z0_+F;3v9_s_GlkZh|nYx^Z>6kNGxO!9(X5ZuQU_k;cuEAQVsGJW{B>p#T8BMj5__YI9g{y=U446fyE!VZJ)0-mzJkxO0FQ+B66x&VJM!#Lj|aI!~D%~+0;^t-$cl>Ol|vp*!V zs*ej5mxSLbzY*PEpH{$^uqIdUn}W7PK7xG6TBT=e?}*$e?6MoT5DpRq0kh0M-h}HvlC%+8q$|z8nMuN7N!xi zR#R|cRkiMI%22zwoq#(F#pDR~Vv=kLFN7RR0=KEnC5#L6rk|#Nv9zp(F9p)<(~DnlgJaI}!aex}E2hD16h20mg&<*Rzsx|f?>c6q*LtH6_|^UDyw4DcEY(O<-C}cuKAS}}FV9ii2F*UL z0fS&$O#r8>PD;AO5UMe}tb6!n`J*CZIS3)XvrYpLA1T;lm4=bo*<7PeUv5VG0BREPL^sDzUng0 zlB$J`&!5+=38-rO0LQb)@OdmvlJHTIjCQD$3`OWh5L*Hp5q_3kW^YFubIR^-WKoa8 z-~pgd4l5U};xvCQ$H$E~x%vzkEC_&Tg##pQyeLkwHOZe-8YX*%a;_a-c* zd~iT9zL`@-(EXX|lDgNq230HAdo(jGQThjLgkbXWvPpLCjmG)Ur^B{uCo-tVskn_a zG_AgY(nENXN^UNy6>_uBq8mv41emXMweyv@Z@x;3fT&=3E&=|7L;Gj*NHbX0W9wA} z=05-`OfB}P*cg;r9+6pMr96WN0E~MD=w%6lE>U_-YaW9iv36U^`lonZvuukQHm$CN z+6+FbbXoXixGEn-Ah7~f&xSedvcYy#hFo)nL6h3}ij(UdiU-a149Y31GqS5!grN(_ zC=^TKOn~kM${jkhoz^}>BKbEMxr5W~FW%cCMoNaH^mUjCv^g!QL(Vu2FN^Tj=o%N= zEL360Dmt$QUC@%gMQsH8epw9)RL$}Y&}c{x9V^o3rX|R(HLjfmPvR+p zO@G;B@&3u)wHf^9*{YLhK@D>Nr;}o1r1{cJp?430-mPgN+$3mn;8_qmtcrci04QB- zgUm{-hI{xLPdtspe=V*N#3Hw0)&we$EZ3um@x{noXb2Egm47I>YpK+syc3RCq} zZjEe3U2tEq73`T%{FR+vQ>xwi;j@2W=dv~3J3I_8>N{beM5re|a}lBDr%|cd)~l|d zVmoILX_Sz~?1-$p5j%zkqR5Z9R&b;7z8`|2;Zsn8#B5SLmYNYZtFlq|22;DXdn;T} zEUEYylqkPZ?cM}TC5KWFS=^#U&>Ib|EeZ-Ls~ZLigmxl_(=Pb3vv?{9-5o&}muwBF z@|$-8Zq}Za9b0y){IL))i9Z`QTJx&PQRU>03@`ND6u(Stc;45N0bHZ?Y1}~+?y#uC z{L<>{K_IkfGlW$gh3`Xtj+}sw?}>T{egd3r7!mHBPf)d?|K2RbU{R^}?qbl#9>1B0aKoT#9$AgzR3Po-^ zjD31~GA456cxm`bn6;8%*7`c&NV$)&pG*Q)RfGivvFSnwVc^i&iyI}1I$Oy7#T1B? zpP*nnLrXJi$uX9ShnKZX1KpK!U_5%=1q7Mz@WVP~4RZVg2PV}_CSydjDoP=5pvJ2Mm-Z4Nfd+)d?eS?Qcm0b-6z+>q^JSz(U z3avrm4DsiRNCbA-+1@p|;!CawIrNS3cv3_uVh*z=AZZ)0AE0X6{THsbK-|EROa|dA zuAvMG9awEuQ#B0Jqh7U*dVQ`cxhv(| zz8?4Bx8Mi^XZkG^M-zPz2RjHPR=z5%kNsh(j$(t#J8^_(tSv1JrTse0n-Qfb5m`S# zWBig4CO&foh#e3H7E_He!mHva*CVLpuTA}`?F>Yp6LKfS`6EY?;UCD6#4<$L+fcq( z1K2mbMu44{ih_t(h7c;tc|O~Q$>iibb2-2-CBCQfof{367Fvkx1;AR=LbPlQ%X1cb zQGaEk+@Q}MoRVz!23d5isJ>X8g4V=8RDInC_WTpPPRh`|{M>qpqNc@A4hrCTgwmiPv1w?RuJF=j|f)HFH^2f6! zIu99}V7fw<2F+O8=5CL)7O@2OXV8d%o1g(B z2~>Jurhp80!*3Vl<0DNA+6K@kq)C48A@vC5T#?OE$dA=*o8^??3wvRX?!@)|EC&nj z2dh;Kpye0E+S08NQ$*47L_WT%;Ut1sj~E?Kqbl$Tk-`u_5hiCBp#db+(9NpernQH8SAJp-BNS7qLMvB{ zrto@iq2(5!z9X<)rb&@8d7q|;e9cKrZJPI|Heqf>Rg-Ya#-{$Z{OT0DH>@jX*53l; zC@7o&Wob^RtLVrNY0IE<`(Onct^pYZT5!7XBs9f-stg(73#(#71Cd@Tar{JQhZd`Y z_ClPAkrw}g*zi^CQDl1~k?oC8aH&$uzb@}f!Zt|#jwiM$9gbc> zx>peNkb5;Kh8*GYe(u`B==h}8ibvznIJ1G3zDk9ZLP`Nth&QXtEHL zmZ&wDaps(rRrNlmrDqVN(a7E<(a$$)yRz#WcTA{1_gStLxh z4_Pwn5~f%q*9J`8i|tD#BRLt8(J+d9VzYs=if9=^@$PeoB>X~t#DYc{(Upfhwy?CI zWw<`c&!7Q@YzJz9t|z-psg0U85^kd@xx9U#V{9ytev5-pMQxz}WkfS}56lzkYiXxH z9p=A5pu|Fp)9QoZb;57Cdnx5cy3khB54F>f5D^-4`?xzLL{O45+0Mjo8O(cB$z5}! zx8w>MP5>OKN*#>}aX8bA&t$*`c;kJKhZiBE?Fc{^tAW*sYp$RH2~j$r6EoW!`*9?K zk7(jyS&q`C$+4PG(?ov-B@l3&&h{4wSgIAc&cGbB6|8O1o1LS(tBkX(HJxP6%KQk| z&j1o}Elw_GrqCxda9(3|0h$6ubMOCrv{D$_)#h2IEx#n1?`Qc{Xx5YK4Q&PQy}}7PAxjcqqeOtB1fO-jewo;3ojK#cd>d zA&@>pLzBvHWGy52PH4pKD|cjjpg$tMO;Ak@wHG9fXic9G zBt+?L^sYP$DV|z?^(p9&z*BF-JhlAsYsK5FQpLO0Uc8QZCjl4E7eZG>9>hls>-rE~ zTIf_eud8V4$#2tWR=k}^vwC}4q{Zt=KIrulz~2tGJF9B|j9Z7bCOxG78n{0CjLRnY z+zILX0pJ>JS}NM{rN_{mWThM=ilmNbQh;6l$Q|Y+bKnpQO6wS(IJHO?iU^h;TjSM= zGU&KIx_78;C~i=^KFsAsKw*L|(hF<__fbr+{0<=CNV|5-Y;LQg0VobD0R?9J!=6ur zYFp@qs%=oo*Eo!%Xi6vY>1>IS5e2e(oy=fi1Aj3@QE5Y%8FG&HcJ9~6l0b&b9muYqj%3+Wgpp@}uyyN}&XUKH36AX0f=5;q(8{)Y^|kc>-djxl%@73=;^98a*}Uat zjL=`ru232(X4wVFzu*k{r93#j1behJ{!D-|#?*Ci3=G>n%&xUMnq)=B!%5*;SwYs* z()G+ij_P^(M$^DnYQXXV^UQbhhWiIU=4%uQ!UCuH-eiV2F=t zICfx1<{3s%_9)N1Y@3Ila3l4KM^r4u;2|EG)ajpn8cy>@hWch+SSo z!m=!{rIp{jh{Yj)k=dUc0jgKtv>2wp!LTezD`wd5YE>wfCnjM86SXH# zb-$+oJ5p<$fQTloU{TKQc%}u`7ET4B$W6kMI>9)LJ4nh|-9@orDzN1vCNlfupQp-? zUhGdE5?DfK5m71Gvs$Nw9yI%gx1G{zYT)rih{DoIX*yaM`xuF|QmQyp6F1E16@vqQ zb}&#rMAErFXloBSGYQ2QEq8cg0C!0BY)UX^*lB=>iw1~zuc`3akXpX+VlTCh6-yS8 zh*Pm4=`%Pze;V;m!r}OY){wVFM9_VEt(pn*!UoiV1&u!J$uhp#ytY0wQp0Pln0dMN z6EPD25{CAI(Mu6GqSNQCT#O2B>kb%@vcLkMS~kD}!16=JZD?}8YJC9nt3UApJdrFk zXWmDm-zVBXKoIzMTH$?F!$lMlS=pvVBBhf6&W?g8nsBjXB7nbD82l0W!8ptnX8%PZ zo`*EFq1na$v>_BlOsEi*8scz4BfGjUIl`A9oyKUjKr+7}j1H2)dyOv)>@(}}u5&9X zk=9uT?vy?+j|rLm2p%!=_Hj?;O<|Hq+Z2geNKps>iU(Wd0}9lgs9fYtV1fG$j;V`l zHBjXKHB21(9i$ov1+mZ>Yj+uqQZtb$XVv5h+#+ODMd^_|Fg>_V)B`SrGlOXE6VtMK zsY8XSmK^cWk|UJj4+smZ)6dRMgD|_693!>An?a@UDhK z1G$z1Cu}ql6i7d~$;of7pbTw)*C0ciS*r-?HS$&se|XdY!;$Er7>)>H@8Z1DhsPTL z*X6eop)n$1oJqw}-zT+Bk?cPZ@>1aNW`auc}epJ{Fj^4rEIz$EFzAjS{>Y z;o~%5gd>Ah*)=g15c=Q#KkOlCLcL$h&1}hnAYDqSK?wriJW=^$TBKC$Fc$TYY|o#l zHx<7YS7?~e9rDjM_Xi{G$24GFv~U1eC-kXmoBsXhz(~6^n|J?I`MnGMwM;@jpK1q} zd-?Ua4h_F9uR&%6ghiU41tyd?t&;|+;cIm8jNxag3KO_JUfCb4i@PC|4ud*YaMWcJ zw{MgcaH%z2?xojtn)~Q=+_VuA8E71Vi3_(L7G0YiLu>l7Ltzg8{M>fgFHk3__Y`id z&5f34kQ+6+iDdASitpEX1Z6%QkQl@<41!sH8A6UOXf)z++xp5ZxDfAv*caYm@fur3 zW>YKr3lB#yo__|X3#<{gLZ=)yq2|$d$^l+(0)Dj`O`Lw}g6^*XuIdu9SU?(rSFk~` z4k(cgeUu26Fk#Y0f(vx*y&B;u4n6@vuS4dl(ix44wOP!*K{or*e(Djkk(~&N3&^zt ze9<#JwMgX0R!8Q;2;NNUits%+0R=ojB7UJe`wg-U;~F)DVE`=ZQ^F9=a^l*@;^ls3 zkWJr{9uzh$T~b(|i%tw^O;vzOAK`{W1_KOcmrV&BYg7Lw3=us6cf*Gu3oWywRN>d^ z2xkH!%u!lEfzZQ91P$5)DZ}m`5UYOW`=F4gbyL8(ep0A$t^*=NzGIku^)*Fyv-9J= zL6+*+dbV=Ks#ffS>E+c4c{}boWW*9Y$W}2|gP~We^`{pKgI2(@a$s3t8tE1K0fHch z6l}X8rS;d;Q4U#d0u3yd?WD#v@|&U#zDpn}JdPJ8x1rvz>b#J{(4$xpjbkignTA+T zKTi?sK3YA4P+)0-klW&OBH$R?U8>~_pLikq3d#KLPx~{5V4}w*iKQA!C5VpAA{9a+ z^RvPqZ0A{*b9vtYd6m(3G6B|t#b%8hzDoIp&C2TD(+Q;_G*Tf?Ra!kxkjYdmi4Re+ zcQ}~W<9O5fbR{O^}Q_>vIoQ4GDSFKAgvyCH9un5I!^S@ zT26#I;sZ|@iAO4;8%PIXpxNyCkRW`D6-fs*+@*NbY$9m#Z)Foi#&@?=oLoS~Q}ki# zRUHez)yOyd9X=MIIXDnLQ_HBc`iYouA1Z&lJy1~^pw3c8HYT`rzotwhy>4AN??A;; zJJ@jG0}deb->vDz>gm}wzn?0faDD(IqEW+H+_X$&?*XgsEgo25X2XYZBHHxG&71Kj%#mYUAt^pne`c(AYnkfNN#EUubLL`n&yk7EPz^8`nR}$ z*ex{Nt(7rlHMo0R@d|ngi_&;lg{Z=Svfx40m|rz#;Kc#gkPk-pfnra-gK?u+Y8*Sj z3XX0?ttovuoCV93P2?=OQ8r$=9ypPmlclq;1Kg`rF%xPn)G|{l_L3OXeZFY?uRFKW z5^MZBInn!JRp5ruo+2U08O}JZupmD0q#UT>yViOH-A8LejzcZ*!(WAiyHbMq#`xjj z6Qfa;9R&?bi6}q`04Qu z*gPB#f;C9OaEA|EOnvWyeC^1VtAekZPy^qp`T+wU3rp14#DC757*>Ifr}nB}meCsgG z!iNQ^)QI1X&)NBq550m!(!D(}m{%e2(p6LyW14OIlT6Cj$%BbcL_JAS6E(CKMJ-|J%@ z$oba>#ULCWIoA0H#R$kB;Yk7nZtUp2*3P1B9{>K;&$Q7X>rP>rzbRAuk8CfA?AZQr zUA)?_qO*LmoBEey@F{6@bKU``De>?h0^iHRd$I+jRlvFKYl?%NZerfQ$C#|=I^WBp zI_j=H{K&cy<6cqq%@udAghM&q-*QR6L*cRqY-uz-M6>77UwY0_ID_yHkc1)$A%uFDd+&SBJ@=mToag>OKX?|bHP>8ojydKS?>okrMCxj*UOa#GJOBU} z)zy^s0N^wn0M2|pcNV;pYkNl?ywJZ?GxY)h;hTScX#5M5e8HPnyj4uR_1zu3{hoQ+ z0}t%nZS1eByFPQY*Ry|S7vRxnuK>_!wy7&WFz}yQ$6QRdo3!NEGghm&Hy6D*J7pWA zXm3gbfe-rIFNR(mpHXAz4MzhB*IPIXFIokBO?>W6e3p=8S$9r7|DtK^bsm%L$K@9n zzMfT(=#kwZL*E?Nt`z^Rk^T)KfP? zBS>{fJ4PV6q9&}8Y_o7SO;LLvwyiMH7>v2pYGttR9?SKFEe>DX@ zh%!N|{D&u`<+8MmWxy`_!HyXUCka_Da~o0TfGU*(BGD-aNK<5j0zjvcMM5h0i@4gK z@BHKCKc9_A_)P;|{%wfD?5BV<%Pj5Ha;NQNwV37iR+SWuF92{I9J6@N_!^gH^sGLW z!4Ofh#QwHFWzhtC=pqnbK&&Y~d|5duFDM6e@{SfT0KQL)#!a zKb@4ipq9)+p&KK9WK#m}uYpp8z44LDvUT!sUdmxE<|2>-dsQ44tK-5)MlE=0SRzqh z*S5djnRn(r4J1EF6$YkmB*4F68t`@_?+q%z)*6Y5zfw z4hKT@)WHE=`X;0`QF7dP??yA*wIBUtA-{Gr9~&{`;CtT^aqmNPBl~ zf^n-nnv(-u`8sLY}M7pnD$t(%JsLWOL7^z)VBw=?QuLrWZ+* zF?ORHYj%eTm*;2YNmA0Y^B5-&iZCPue_AJov&Lm4{n}`o;Kog{pvj|RuBg+xfi8x2 zKqxPsRBUtee3d_hs8iIKW|OVxVoiiwe=dKwx3UFPG)0VZE1I}Y3Zmm zJQDVE9CQ4^dYOaT!fb2PJ!Qw()o90iO4Pje_p5G}Fu~2r{c)DB*SAXc>66qFl^Nc* zyfN6%%b1{(-XjH-gn07Tvqol8+^S+rIY)wxn@_%-6$-|$hR;g-yEhb(^Ui#?q&8I# zUu^lSH!mRI@h8W^a)YC;x#L@*ucyPfY_INea?+o1Fqko( zD2dju<6*nZVH&(`@`Vm|7F4J2zQIe%dzSXJVMK-(-k@)M~gFpj@A)w(VA^b(AjVs9?fB%?3GOyI9Lx(p&Mse zF9WdoKLcXZ&zlrC!+aWY#Y|331QFAqd6{q}iO;5WzRpi}-K<_<#Feyh1#D2Db1vyO z%}*xTQDPjNQlVYsHTkjJOKRHa?#*e^LT!24D?*`%Ib&@4-Sis=B+nr$N$KHL9P2}H z4)WulXn%8wWf&EW2iP`Khnw>cM$v?wv!xc2cIMSqgUzhAzvmJ)_&jo33~O&US8G=h5G`#RynYnZB|+n!SdtB*lX!_n*)4)q(Yx+@kTduFw&&TL%#>X=3G)Ls0U?MA}peb?8~_3e|d?s z0rkkC(`R+tE33=3%&E(hCCt!x7N!BnhPD^QG>i58KXu?YSAas6+!{0OZEFr?S;iHG z&H7De7ed8c8)0U}YcZttajQ|tuY}fl1^J}Z$*H`R9^5~y9zfCtrxn{Ju}%&h8YS{O zYy`HBukFm-I&qz-HVBu zPs178=&BrrP~t|GHpFa3IdKL5BHDI;*%gynWESt~YBj;z$85XXD%~J_HDC4viP^Rl z?$wsXq8|3B`0jLugY}Fwqts?a^f^G3Le4O#W;!Tb*h(`3QcQ2JY7kj=6gfXSspl-@+xt_U&i z&4H?y0y=EX2bGiNI?>G3%};L!LEW!0u;l7+G*kvcnZOn4+$meZtSkD%XK#y+ve31Xn-fY3$)Q|YptyhZ^QP%d(*WhCBjPT-D@7wNXmhNL3{)v|p`Lp(QL`gp)rUh*PwEVDkNr+_E?;H+D&_r!wz_l^%exBp~8 zE^<|RH&DKvxkF*liOt}xcTMX$R8=n4drUYxs-lq{g_m~AXx6MRLHaNXBJqQQ)^alkHaivX=h-W|( z2k8C-qy1;7>^}om|2_8m7bfd$Od%3$9@2xLy z66_~CGvh`&S8E28#>J>!Bz0TW@3)sz^h6S!UO-O#IbiA{I6eJ|HE-So4`Uy($jj;p z<4qE6H33DF1WeXM?CHm4Jdv54Jx=9GlO69qM5c(`DB*L-;c0#Xc5j-gNTHQPB$=4wk=+YIOtsi@L<^8@_%av6N+sZ{R7RV30Yiyf0vY zHD_x%C=(r`m-^-`$mV5pi7igCdD?CkO6!pUhZzigNk)3h6|Jqod3NgBzvrx!5H(`{ z{9LI0lfd4`u5< zAXRP5;#&Dj-pe&li-q|grI!cser7?)E0&?Pj}IPEsSTR)P^#i&WWo5O`B@Crr-BC( z0sx|wpoSL~xdjvF%LkLu$;{FTERm;sTY8>9@LC{~?wO4%w5u1lxJok17m@ZUv3q8W zb;p!zkvfvFsuddE5NQ`5m=ge`L3)1Eq-8hX>QgQ}6VE0Qpn!Vr!`zpVp=zmb@S)b-6E&BYJh`!~2r4dgzq@yzh?_LWG;mBeP9SUZ_uL5r@lu znAojgw2p2!F@e68>l6^$#J4~zx&+cQKJi=?9j_UphYBym>}+@arkiWWbn|LXK$MnZ z`_s5lA?itE{dPz92{R7b2NFNFNHI_{j3jn=PLl5pR4Iz)(F`hIb3MWZCdxZ$k|Uk`q5T`8d`jt(?wpj#1D^wG%N7(CC~ zm!`I>{BUVkNSk0)+Tx74_fs;P;|JQA0dF^U8&k}G8Ku$Xys|v9Axpp8T!K0*rfZRU z#NKJgH8`LOB9T8ESyLzLdt(Ua?3A{2g~sxx+0%+jM{0k$RW9r3Yg%ztzhVW&gWDB6 zOGnzg(67g<95uIlsKrT^($hjT{CM>n|1>N5iH?m?Y_gNXx_-H8dp~IJzmcQ4_p)kb zu3%lUcuum+M^l>@JsY&8-34KKTC9-WZ}})YaE2RP8eWjDrd2d&{ICpwEqI_Kqathn z?!(mQmZG&}-|I6@9DX}HqJ-JwnKx{>@M0joSJT>uQuD@F6l#n+Sp^M`aqmdy5U9_m z|L8NG960J($o*(V5riTALZfE7#q_X=6%m9o>F>bQD8IW zVoSsZ3|=v^RT|R(WxT~|IEkT;u=8c%GIXXW3Y`XO)WK*%4@t>aF3ZV<5>iSZDPYtw;`r-OtPyVTNRgHMI5bTdN?@J7HfT(7PxVOHn8M&q5l;}Xmbeok93rtMV z!IoW_WI zBdxWQzq+M^qX;bR0)xHoZDMfPGr>T}_~Ly5F~tKC>1&amY<7RCKJ`Z^xDeM6cxmD`r-wXy93B$(M&@KqF+uYoSf^E%HY9ks-u z{T6Z+ci{10m9`iT4_n1%rdGxaC==Wp3P_Q*UoMJE~^spnTpL%0QBW{_NlVb+w99Ss?K2$Nb80(Q3}Gk zrIgWcukVkl!ffdto;~b2+e?%g?odEtxu0QUm*CP!rT&rl>1ODUv;v0EDOi1@PI9-_-_$mCV1iH(uJU^8BBDQ#4MEtKB=B0Hg&oLGQ~X3%u;D z+o1uZ67lq^!TCR>oxW`d}$!Z+Mtc)Y8^_daeQMr2bMpD*ATu@b9DI;i?AE=A{LI zpFUH3%C8>JIM0Qvj67F!Juz&y%VanKytYjoHf5&AO#5ChU?w#h)N_WQTfo;iYS3Fv`tMhKmXb9%K)a^A_u*v~5O-!IG(i26e@t|V@6iCggDGZl;r@Dq6T&iOFNek8)LaR!4$S~OwGBQYP4^-GFb=Q#Is@%7wb`g(zju~!6+KnVm zC<2|nP7Ac1g9DZ=^Y8k@av$XIj*{*RU}`%!Tj+o(DIqwJ#z5uUd$~Exiunth++WG) zk4FYjmoIg6V*)K7H;5p69oBt11dv#@14?>4XoL7bL99I4#D7X*7?eK{14LPyy+K;{ zuSh&cZ+k1;>^9(#`iFXn#tHtR&9K*?0RFAX|IaePxIoVJhgSVr6QENDA3l-?a=ey* zU(x6d3oC9GFf|kEskYZ?BcG8P1TGiwf$Pr;|8JoF-(Li^D=&L}p$v=w34>Dtvj*TZ zhqQlVjIe6Otbg%Wu&=5q@Y8=nbb#)qKdt`*e`T93B@!jUhcUlE*8_Y~lw>pq2I>&WV7(3eHwFOD#?hE5kmFy5^)cnXGDf=C#1eU;6$6ew`tyo9H< zpgC=wUWrct5I>$R2V23<2s0@-7ju1M%+kQI>jkI_bkq+GZE4^J^r)5zXG5>CGT%Eq zaCKY470)I2Q{kGG!Ms_IEN*rI;vp5_R$I;=c_Ppdbrz_4CF9{QnxzCU1?BZQAUmA# z_d4T4geD4S(9VyXEFu=Wx_Rmdh-l$FM$d#^^D-5%)+4vTvamhARv?K2R5dVl2FD?C zelj;(0WZ&xe{Ey7FsVP=`JY*w{~yKp5Ap|l_>5D=M}fQotl+P?eC*^aa2q-ogVH3W1JHer#KJaddmfkFTNC@NGuSZnE&{{WyO#on+YKr>h?&lMO`hMp7PnI4f18P< zb)NXhF+mku`s1$IK@w!-WbNcZ+ek}=37d9Hgjg)mdB~>H@}2^`Ai@*e@rn58-UwQ@ zW-A_c_l_IL)B@rjzfQbex8x(K02N6EF{aA3Q`_3`c64|6h%0*6?3Z_G)<8vUbCwD= za`Ar1-D_RO>v+vyp?_hwr%-Vh_DGIIDCO|Qz4Eg;1}H6DHGD8wLIgFpOci;8yYq~* z5BbQ(bT*YhKPk~49TER!$J4Uo7!x3ebo4yhD=1&hj$8^V5wAGUc~`RyI@}cRs#|F- zfk-4cWCX~i4k<`|@f|k$%K3Mh@hqX7#V0eU1V0u&;*;)s>5%uX)^mONx~yR8@=tVZ zZ?4a1;sn%%6k3(oUtX@1jF>2>p>+sTFV{KPgNgg`^ z#TNBLlW|GqjbFHXpOuRjkvM&2cpl}gV^{c3B#c}c< zC-TzZGX)DnCg?51H%tktx=l>U+kGD%A9cZeDs_?XjzEY{bQ72(qHsbq8CPf@OVC@h ziyiJ-sojMeqTSbaS&LiquObq|_pH#CLVSpNiYb>{)^gk;sp-o>MloE%`0t~hr(==# zk1!wOaigbxvBnl~WU{=-LJh#P^BJCNg?Nv>PTQY$ zpv!kLqdbszlsPykZ+c0`=%_SQAWZbIWhbS!u?gSsR}^#EgD`TiFp~X}|6!_rfFIhO zx^y6Q*vO8|+={ZD4=qv_%w)gluV6+vEHdDZGAWWl7)Y4D+ZyyM?4}eDR}Q}y=?56L zUn}=bjoqT{4&F)~Up$6WK3kyt;!GwSxqNQWqyAR<`8=1MZgrPcs~pbZ$PI1Mg}Ctr+i(GN^izNDWbH@P?nU&do4`@{?MbWp&o5A#I7ZS&tV8(QDZQL>VrJ+Np` zzYw;IdeE2s`=o#v8`g8l>B63`-~Pcy?m6Zo?Z>yuxRdx(f|Tv~$S$w8gX#<2XlW7F z`2CZU?Dm@{@J=kK2PmVFjp6bj_GHpg$M4|bRls8|#;Xsj8Na3nJwbW=xF+JgHuk0H z?x@fQZU&pC?Y%7=PW)jPf9|PC?cGDo{n3+wjItULk(MuXNl5cNF!tS=_s~eEe9mP- zPiex}zM?fa@Y2cAFFhuGm0pz?674ZJ>v#?ACQ4%9Tugp;_(G}l-jV4LyH7|Rz9GHT zd|#PTk;GK28}3M?9J%aURT><<%Ix4xJk!2}d-wa!fKUMSvypR5nvsH|LGXPZZlmkzkq=Miac?Vs?{Tqexf_c&^sGMRVXe5!qVl-Mu#%=zJ0rhNpfIFhOI zZ^|ZJo>d7a0;1CRSBotfigy@a9H&eKe2t*z4F4<2%i4;YEegcC$$7^%+2Xfv*_!ns z8-7V$#@x0!jQ)DlqKP0S5DtmB46Hm3o`Z_6M^ZTu=7a@K636BHvPLA&_$@zKK6w9A z#GT3Tzn|iGNX>%Am~O9t@4yi44hHe)57=Q_Ducr%nQQ{hBJPC)-5ZttX-R?Cb z%q7Y?eqTAYEM|gV3-l>}mU*w5d9Kf;W%$T zvmEXc+%?gd5y{p}M@+UQl|$=j?8# zuIOvr#8zjum_U(vdX8XvND&iVV*K*?r5rIV>9_=eUI=!QchooSW3>m;1V@`Ck!ln0 zd&r=YV~Mq(o~f?v*5RXKg@pP#xt05+H-~XSPdMbK9y8#k<>ql!wHsrW_Mpo<79udsoC3w)UtAJ3uxu`(frVO zKe@$ZYlLxw$1xbTg2rxr+^VGSg(v;K^GI66-tG!ok01>zrALvq1nLtE%*xL~oOnlf zNX1;&^d20358Vhsm>mw4pw7LBnvATlV$63HK6p!$#@b}>%Ee4q=NTK#b#epAqt#o9 z){-KP(#!@sn;k|QSc(6n`YqdTFFfd-d7hJTJYS|!5x*_ct^PB?sLciqxv26M`?uQO zb46>wvbq2JkcMS52l}&7fxBzsfknyvp3v`GrP&$l)FgvVjY>+Z!6kRx3z*p|PXX~$ z2^POfIjewEi($@>W(R7n$ConqPWyg>Fe!pzxm##|f~4g5j~@ygkUXeLm;9f! zuJlbz1!?(cU<$;n16^wZ&j2+KK<;0;cqQ_kBCSBs($ve>6&wXr z@@Rq)2io&F6~5Fw>^5kZz#Jw_proGc$0+I> zhh#~jME`_9?mP;vvSK=451V^p-tcrme){8-u<_A^l$K5bk+{=JS4d^-LXR3)rMf|< z_VxLKFDzc@jO&j??ruYxUj}>0Sz+WhCUq*erN&ciErR|Fn|4} z=zl+qTG9^*#RD+B=R^Ct=2}i; zzMxCpY4Y;^nuo=;d+ifnx3kkDKazV6HurZz@iwRYEN`z^i!YFP7t+ithX;Zmem+;> zgyCuUTl)Fy3g7PC_fwnN{6SY)=L%}~h97&uXUy3KIK_e1MT}55?ZYpOMTlA?9b6}_A>o*bbK{Da| zLc|lB3W<8b`V&lJU$(-;XTA28+fv{0WlvjZB%`*2{4b(k^;?~mZMG29(Y?e5x;|0{0w1l^JwyZaVCY3Yb^+A>nZ4=)9dw9pfVg2s*Ucw&5PD_OyHXw*v%4aq$ES6LwvezFUMn9T}J-?hVu{CTYP*2`FJ@i2I=60=uT^7%C zMY|8`0KX4>-6+-SGv5`wb`seH8dfyr49 zv;I6v)#?!~8#-omb+>r#0Q#aXykXK(aVS;DUbA5AY~>X%jLfLGKKtGJw(>x!e~c?| zNqJ(APxBEbuq+t(6;tJw<PyV>GN(<#yF{|$?J&ZU%E_>^6<{dw0C z@dLR9`Y;rf5=*XRO_&Ef?W0kmLoh?ep8wKrfB3vUpA>e&|GCMj)lUK%NMzSHy^Ne#?uURptMY zg-@(_c9ZX=)rKu7p$T)!$>6(H>3HLVaWN137WeD!wkKyR#lBt4IOK7_|J_~43V#4% zZaqia)bPLQ&0lQTZbU8nT{K0M`ykAbvj)|cZiZ?+T+iy*CEZY@gj1q72;~Rv9K^$2 zv7KM%*tMnP`F%?#Ozz*jaQeueR{Qsa`Rr-7=&j&aV5hvC1GS6*fz!aP!|B_8Z>dJo z-8Xvn#NTX!^-u3WrC*2TR*4UBN1IC!D z;Q{llH9JA|-7|xqUVnA6WV?U4Bxa+YJG4dR#vL<<%`_Z{v!d|pP|o|@8xRvV0i_aP%r=F43#x@cJ=Yc3$&dwGrh>ItIx7< zC5RjONn2Q%;rz3-XJ0^58)OF?>NYDc?I|@w^-N@f&ibR%#$R((_798hvIA1JXe12)J+@(7sC-tA$&n8uj~A^ zW{<&8gXQpWZQO>B<(Q^r)%|+$mkKpnAZzZx%0#|?der@b^qDu6NHi$Ty&9SR@!Nzk zJBr7$_H|vOIwF2rE%#x7PROtO!b>uePr9XADtr)V)k~dx-P^aVTc2BfKON1v967%+=%In>k*mn~CjH!#*{73QIHX~RAwDct zNyYh4&|F6;)q1tLcGx)9!_!xXa9n+HLK3tM*=|deh`)c0ow?xEcfpdj>;B--HeGwg z_*$!?Aum?Z=9ZtNkdaquZCKN~YwODX+o2yQWCOXfO0mg!* z5%b5UvOGl-#A=s2sBkpI2847nyVZAH1>^EY+!b~*CloJk%N+;`!C?vBZ$SOiXM*Bn zQw6Wk3F_l@|Q|pJ7Pmv~j}aWzJmOTQC{tG&O6B6LKHBciW1h3ueegDWFr=$wErL zW=#6-YM>xJuqR@iDn%3P@#@%iQ1{cgyG+}PdtrBK9XIsFPj$feA$QTHGGXE5<~3Bi zEqh#~QVJWQjr^O|quL<}jbAEw-wgA(TQ__Q^btBueDJj8_>zrPWrqvo1N+6BS-gl5pIfHy`;QHMwad_d4#<1 z2%FB8FTchNv%mHCuwDt15~s)b;@oeJp1N&#!4_CK;AB)CgK(b&t!#M^H*|jDB=bm#_2^Co*v<KT+8!X_$$ElUuktB3EKMRS#Rr;79<)P4U zHLYNe5pG>h@%Il;8pzvV3lCUNM1nSYy{FNF>Sg}^)zW%k+~%e$z?=jE8uk0Sw{Cn>BS1BC<{Re9hy2E)?l#l+r&q9nz=FncD5aH8TB>b1p7;Rzvl|IT*g8OCjAP2BY$2eqXXiu6@TJ^ z){*M)`*QGWc6`zL!p9|4i4;#mkx(4^z;7w&?0VGE(hur;9?%pxwmt28t)8jt;{B=V z=^1Hlo4kS%o=YO`P-?to`}Ap+REk}3pxfjx_5xz|4u+~J;GPYl zMWJH26y`7$2rjW=;d{7TVp?r-F?hr#wGiRoESo zHahAWL2&!s4YSBOq7*A6ZH8D2h;aO_o%LQaQ|sl2C$b& zab;!YdO(xj{-qQIbNt{>bNQnC-DVPObPNSmeNO!`U3$kDqB2lurND8~L-G zHk(*dqLlI(t3FVq7b%z|wsJqFo0)a|d7D?TfOTTOAW@y{ppH+wY`@SG`7<$TzAZ^J zCg1hi(82Flm#t4s%ETXz!F*yGsudsyJI8Z%rOR8`g)1TM8psr=xX_7|3VUlFwQ;Il zl%i4$4@%z2RMHyg)u-xEmkHvAC#O_v=iBA}l#^+pc_8jLeLn5&v0*(e5fY&3n|EjZ zV|KSRUVKpG4>)ys*u@qR6ZSY$f@c77GfW_^`fIz4u}$7#x0p5mJT~fm<2T47XZ=0y zGUL3u^j66Y0z`U-orFACLjMvH-J0v^n{m4x?EB61_@uf0*h^nWJ|%=n$-w%$k=;(PL1teu%k&+~c0g@K!hE$jRI%#323 z(jrRIuPE$7f%7T#vtWom3gXCK(H~#^By-SJ;`NNoQb(p*W!oZi=skq7r*r3Iq33G2 z_9q+8hVE+l5c&EbWIOs(13^D5cO%On3pEWw_`<-sSCiM6Pz_N=kI~(uV?%qPPJ5XxLvvSpC2^XDQ9v66N$^4w& zhNqN{_I_xFphRQk)JU|=cTS0$pnfzn_8VD$(_0mJ7q0UjUjdlyiAFt${9Mo~VWuRp zJRv<`{!#g&mq1Sg(=*uXvPo(0g}?9B^>XDafa5D^pd*~ z+dZ=jLXmexZ99CNY4K<7n_jvk^Ctf~*gVj;O2^o4DmSphl=(b|KQGG?H8bt|$|cTZ zuC%9r(0cLg$7mL{FGYhQggzR`rf6L8@b@zjZ;QuAT)j9Ou0R;lp7|(#z-&A^V(PC- zPAv-0)dYRA+-m5c(R$AX%e!46J_^WrBMr&0u-7Ys&opMIlrN0IUEVAr%4+v$*76qFhAW}+5@!wzj~NXisy2P^+IJ=jmP3Pf0|3aRjOho zggpB2T%+7e6+8#4FD&jO7PlG76C&>Y`JAU<7G1A}tEqJW>{8h(j=P3>KVi3i_}ZPA zKYiD?cZrs`l_t`Wd~H7Ec``H=h#AXUzzz-Bazx8h+Ue+iu!d57Klp5_f#+=dm9`_p zNXE;v);I6Q{M>InY}6H19nNP?B4>q+!n@@Qov`97C4Tun8c+5!owYcC9i1{__1B)h9fTgct zi;RPf5WRb?ByEE^35+4ds(447hC3p zch*8Mi}GTu%Ac0))VJw;e*{`_zfh=GHGyqzWY}DLb;YCUFP05u zsEqt=aZPCvM(yq8%roFY)u^Vca~uthdU5%#*_jT4?`t>GP91+#ygc=HQY^M(Pe^)# zE_uOcV@n1%`lZN)@UZhOK56@w(xIpUU(l|Oe+DI=x%gJj83!%ycSja^+22`NUk-nR zgCr{>$@g&`q`~ZChI1u7y@K(6Hdm?e#zfWo=XWUeVp53K&~13=Cql9Yx`0^`7{2oU z856XU5B#PuDZHzF`(RQh?30|cb zN1PV!$CMeBj?#5@c-{X3yMvf~JpK5>VrxC8{?N#K4%M}VJHadN-RzG{&)ZY7PcgLa5 z^y;dlSLt=%H`U2Mo6p)9#Y?)PAc(>Vb}1pZj-@X@3zfMX%RJz&Rgj^h`3nC~ zBR;Jk{)3IvQO|UKnIdBrGbgoJpL^@wgUnZ^CHg%oU7#zlY;NP@6{Q>-f0aqr`Qj)B zw>Zb47ik_Jm1)Olk!(ISC%!mNc#uAFiCWQ(tbI!75htwC8_Xnbn5Cz4PfyQEag6nx*rc( z!nUOgRhi~A-7H&q{EVC5^uN?Z6IZ38ZLcYO>^=jCz6A@@ZgI9`*l1U9UEN+Q8tdB~ z^{~E4dCvoh^m6$O&3nIYl}@)D0((8LSIc6)D+zWiCL|A-v#P(X(>iX4(r$@qzmC5o z8)@x~iT|9q#dY(nIa6hZ738c2kG)jI15CG3$&ll*oII_N(&NYx{Mq=8nNV~_x6qNR zY_MCe>fv1BnjN>YU+#(DKGuzsDG1XGz_h&=_p;rsi_~A{@OUB)-^lC9CP9}f-rhYt z{tNP!QJTBi>$}7lSn2iy5;$~FEIfLdHLY~3f^>3520IR(cmJQlt^cF?*sJNUyUF08 z3daKS6hWU#DL#Ax{%?Rg$}Xxi9nDUocMpgtZsu#i)KfY=S){w_wJnztLODIdUF9tJ z9iet9C$Mx_5||PbbNR|%M6@PV@7;>+ zXcGpL_W4WH)iL796MISY(L}_>mFAH4bT-wijKRW_pLvE>kF3*qDw7`QM43_f;A{g$ z1U?-_{dfn0}# z_W52!0;m)>uo$26# z_Zhfz$ZaM?guFm>@u92nDH@nCA$T6clI8j`iI&l_0{5aAi|jWfl}r}jq^A2BW~k1$4F0$83>qNiI@N{^?Yj>NB{>6Gze z?w7jZu$4A35o61@1zKO;yjrCOP>myOUitm4z1mwEUDMnh>W+OU7!H=Sd8Ssnp|>io zE!vD!E~m72uJ03D43KBCVGU6i2KmNIYrwjo?%(*|lM|=Nn_mF|G z4zBmY@&%P?$Z1^CZ_^7tr1tppXE^)x<&OQ^4^)fc5uiFR_N${BR$GhX8I;%dC!1Z&J$(my@ntnM)LAATBY>V_@XD66Min> z{y+oHUUM?UKnCW9rbj(WYyii42kU8-tqviAcvg+?jCF!L&*e+N2cd@JBOIKv_4eFg z`BLm`^K&-sFGcVH+V-jMJ3Xz3-X()=*5JYDi-#fsV9GF*n%uhv7saB@DnXZfhTttX zfbQP3=v5BC*xC<01;o6}ZOmrtxXC0+0W&K1vx`$7s_!Mc%8KYL(@MB3zpsryd?yM3 zj}Ea90g@2?!UF5|53q&lmquOROVPz0&CwzzeFwuJ8j3PbiG>LDbu1Fzu@_5OAeD$a~d>1;q?D7)(1AVQmJi+nCgr+5!Hrm#VX7}kZm1GtB}acaN8 z;{C=ZOm)yP+-j2@9U+Powsf*SM2s(1<`W6Und}Z`yI`5qnjaxXx3fOPxkFyaCVd_I z1m|%%2bXSe?6Cj8*!s@6CZ4F>pn@U-DhdixRGL%;q=c^0As`?<6zS4i=m9}NL3#;- z5F`|p-g^_3P9XGzP^5+~y@lM(|9$WMbmtR4SaxT3&Ybd`^PDLres|QDwPw2YdcwzW z+18f@XQZ|`r$6?-QULIXjMXpiC*h|4Y%MJoy!X1V=@e1YnvQT|d@a7M@x4j;j-}~z zN{{XLpcI|5x9l3W%+yFye2+#UT$g%6Ry%hGh{%HqSw0xZ0nKE7czcz)rz-s{c+8-B z(3VSV)R*JDCMJ;Q`K=+%jH+hyyV(#)pO2(2>9Arz{3w(EY9<7nBF|{YyCfqLaq-EV zHsI2SItGS-L+>bju?Kp;r2If`4~@Es%OmR=YR9vSyykcP{lUR@{67`v8=Lf@U+Qm% zQrZmKfwCXvo1WW%jnB-#0!&d0px=!2gIeYz1wN-&t#>7(7lTU2PZh1wj<*QvCQW=Z z&C+<%KbO9vuFc?B_L7r}Zg5R8M#!}fr0rxXM=Hw!AcZHrSgvm#-;?p~wUzcWi!YF8 zEf$=12fH70*N6T*2dF^C(y>tkX2G#fKI~T42Q_{W$Tj^zxQ4mb_66WB!qkO@t(lKh z-dTUW_wA%oF0IA4=C_e4KyN|xp!0WX^j$XqBK)UiQNwiPDD|8XZ{Y4$@r(&b2uR<+ z)V=2$9;B#Xy5}*R5?>&y>{`*|)c;<{B*`IrdCrcDUJ(`3eHJrb5=6m9(0fz+MnW?N z`wR+&uR`peE_E!gvgjQZ2m6`?#a-9#YlR?(e6_ZBKcY{qtSGbX2JI}Twe?B5T$7?| zh`hAvN7rZyvedRTrv~N^Mxga{iwtUh(bqLcXrF=F!~iBnUn37oZ7D;n%lFc2^7n5= zqlO6rhD1gqt30+`DM7>GnFj<0=nDfqLe$vL=<ra_wVhW~1y6*L>ey2z3N_ zHc<%>o$(h|rab3iWqwHiPsinnTUj4CwbvdcY=3+)d!E+LPYhNXQ5_>ryRHTLn%@FV zPy-x|w!cyD2F`;5^N5{6x+F{D6cD3>Eb0DR8-IWQ_d0ExfNH_7{*{!acgDO%!6DaX zgESZHrfC4;%@rV>0ztlOGT^o37AvrlZx~A2NnYPqm{!^OWZoy#S`KQXBwymsCrnBL z?$lH1ici}btMqi?PJC|9T>BZ?%5@2(KwgiY($T#rJZ)O~&VEuE}M8c^t6 za#I5uP97(^g+>(>s4#lg=fMp0NvJ5OEp^RWL;4?3{tPOUOo>*-j1&jHW2>|01_(V)-G zPyx!ZHVXZ9?7xLL&7?9SZ+%=1I&lqBy#tz1@Z~Xo@$<6LJBE09&1m6UA8E>u+P!aj z#;6J`*t6e`mfpb!)+T)Wm^(E011V|py(V5VXCipr9`hIX;%}IFRHuY0P@VI36Vmhn zK&KwWuh*~mJS!_R*cHjQvY6a4b`Ak8H<(T&WUht}m`w;@La*k&{=yG%@u!tkZAnWS?oks8_Zlk!t_+?Jx6cR3&Gfyr;NKZ)rdr);CY>DHK0C zjmzK3{3$k?lv+zKl|X{MOlK+d_qPjEL$6@>TlDE(?C_xf{ysa#zL^I|oQ2mnK5R`c zxFPbkCg=;cCT6a41MQI}G^F=U08uGA$po~~N5|}O=D2a|_%m!MJ38e)?kt}&OT9r_ z`OBOBu~)w0t|7jBr6qsr0{Tk~_#Qmb^Q|_{8i83ylvZsV!IgWzS`!ZbZPeU*ZAk7r z2Azj-QlYqJ*lE8>2)S%a>yie{p8VO;>`s;VHqz>z6maD7{fqNdsi|ESBP8_o`ou91 zRXr{Qn(vr+vparinjQ+6Zuzqz9pSvo;$`gJ@prF@g6FUw%>l7|Ft_Xf^^1#CyKxAN z{*Qnu1N@^Zw^D7Z>~T%fnbg>nJf=mDXDcA4pov?U{uNW>6*|w~S6W4*XS?ECN%a(Q zna;sObki^V`Fn;(jKdPQ7gT;spHaO1ht5zu6A3==pjp1yYlrh%`Vt4x_6r#5R z{xcBhXuj#v2h0=t=o09+bd{d)9_4G=w(CfSu;WC?AiV@1gGzyHnrGJWnr2JmDg*CN zH=6d?=wIn?(G)!;sEw6NB7kApUCPisUebpf@WNhvdj7BQ=VRYhM%e6$Gooxazd-Xhz=leXU3--8z)a)#^Rx5oDahuu6y3M+ny zR91+zB0n%0L!l|J_IDNw58?Ye%?~U-h0=%SG>z1h*4Q>b4~dJVd@Rqxy&f*Z#P}Ei zF~tnKioNyfynV<0r%&zW#rr1Xt5>=$?q9zQYWpb`9rWaa94Kn@-3n$F@f!TYEg8}k z*p$Oh=#cRIy&-CI>F34V{!Fz+lrZx3S~-HvzJ;^GHcet*|~Y&R|Z z2O$@l6NIk`#N2Q>T8K5^Jm#-(AP@s_t55JWm{*OYd7GCd;F{6V3Py3O3aHS6@S;iW z?GBwU_Tkny#;OBhhoUww^UUI_TnHB?DL{El=e)yxr@yZN6vK*q{^!*}iLLdyJoYil zC{{5JaC8>xw*gh7b4Y~=Q#^aKvo88LcA8rnls&Rh{ZqJ^YxW|jZ3ig5IaoG-+gqmn zSLL_}+hYX)6FxNtdo(wJHh-4&j+R_WwiEk1{Aw16y{6om%w+_x>HR*7*A?|2EUJNP z)pL#i_gb~5%(O0&&XY(cJLnCK!-tNBuB&`brSaZ{ELs)Cg|7V!FIMY@?m^%e>;WIO z;SD1(>=Mwg#>iamLyls~=L@2+`V^`t2o4H9jAj3fdYkUGla`hHJ@P(I-RfL6t32fw z@VM0v8Vvv&(uPsypJIBZBhQ<$Weto%Tf8GbbSzAN(?rDxkyymWT3kPO0{7 zc==e>(fylzzwR32hn+1qyumGiu=gz^NvV~C0^mWWexlS0LVcB8+@(rnD{u5(=$DS{ zn2UhIeHiL3mJb}&14cG6)H&?KQX$TCUq3o8K9)E6)^TY70DkOTYL_0EBgk^Umcf*8 zyUmQ2iZ=BqK{Bw0dF+>R#6ZVG33TJoqUjr4jPm|EB%mc0laT9mDbo`r1y44Ij3Hll z@2~Y%HA)#W0CO@DVTty8N!|#aeKn;I`9tfyr(O=`%Wl4f9jD5jJ4&QSst{B&PWMI1 z9G8hhvxx)$fcrO~Mr&)lg|gKcL~vJM&xvek(b)=3Yci7i6xD41u2*UjZ>_q>+f&Pl z=O*+d@9Q~5-MGa2$LW~P*eLufAy%j}K#U+F5a_HS4wYbjiJ~*yspu_S%JCvjh-`u} zswyWdi?)b`7McTQwYQwClc-krV_U3*QgUx^SJ?ZfclKmfIlZwNo4nWOwXXis><`moNod2|Z4?$S%Pn$ruFc?S$7s(u?XpAFeTMQ|NfR&uS%DBv{;? z3<$Bn%nK1eaNJV4=nEFxZ&g1csW0rXaj*2}w+~(gFO(y!9kYMq{kjpc2NQjw-*QfC zzV@78;U5oo#TC7!!B^FUxhhGHp$?rrH!Hk+b=V@FkV2Fe{DMYeEjnT@?D8T=`j{tD zkk4E2<=*`-|55|QdsW8P*}ckNiZ9n;N#B@4P=MgOb>g`)HEX= zE9A9*?c5{2+2)Dv?Q_TbY9EmVpLA|9b=P3hz3Gq-qe0nwF13SJ+4fVm$HuQQb|9tW z2$$Ab<-&`{d*d*YeRoct1i|yZvQvMT^5#+Yik&+t3i@FGo%Gd%mE1ljCCb1DZ^Pf_ zrcMP7vO-(Fw>sk=f3GaQwuEq;vHE2eKNrxTouPJEg&cM;s6@7Ga~ZB3G@aLA_$r+N;kBBc=j)TvSi zHmC4*?Y~8+zti6-5D!>xdN}`r46_#Z)OqiDg+6R zzGC!aSx>n|pl|s##DCiKPq&&coUX)Vw_#HO7#ydS*^3CxqKRB6n`s1NG{i5Ecqv9_+*qtswUw zzzILzN_UZI-9~vd3NO7&vJk2#YpMkU6b>3ff;QFm zGKllR?8R)}mdf-h8($33NKUPDN3Oz-k3IIRI7y_InA_j0xy)SQ|G~S$j7%;pVIWE@E^!5rL~jEA6x{AwHjVZLn4 zxla^5E9-ijyWp5l3!G`kR7R^KN$^; z_9s@MU6ivVwB&5Rb~{qo{6W^0rg+uq&8~@~aCgl~?_5kDAz2K4tMtYKi@Tf}9!+mO zkmL6e1aTxO{~UBh{=nG8r=fJjn4yzj61-#f!iE%`xaC+P0~4dNtDfT(rhX?*)s)w9$VJ4@TCC23k{h>Uq|W z4V~GMwcz_PfnnoA!7?d3{@A7F@#$r1TxUvR$e4fwJUDUq5=cFdpxmA{1?a_I@bhBEDhD$s*ZUn@2i1@ zp%fA^8f`*^ihf3KV9zVGlU+NV`!UMTRi>_S%D(m`FSpJ(Lj#i2y8Pr1;H@P+(=2p`SJodQ_a zLx8@{vY#41DY2KLD{;+fhq>P+mShi|_mtDoQ|0K;6Ys?8^`qWeA&rI^ zAspD~S774!s7BA8Or3)-K}P<2@8i@KP1u8d#8@7_F7$&e%u-`yb7KBAF8KfsLIzNt>Uc91y~cM1n|p#yo2zq7m*Ske~`SjVJVZczmn z4Hr>-E|G<4CBh(8!{t^e9+_Y>=_McW2RI!ZYjId^4KeVlF8`b?(i8P6sbL0Z zBnQD#;=t+mqZW9p z7gU-@2nPlJMPI*ln$;*c5ED05?$Q}^fvY)91Vy6fIp5?ODK3~_g<34FSKA+FZNDWB zGk_@q27J!eChY4Ue=VT`C8GqZolt*;>xY`c@fR-0Yx#N~2bTb{_^lFJ=$`2#aH7V5 z#o9h$)o9uEoW!3w?K%eb5mX;LSdYc3^aYx;4699kq$<*xq>6&sp&L<_+P&az+l}qh z1bev^uZV2zW+P%P(}-21&l`+wq=8-40Pfmqs{?+ucf?gQIOq-txhu=gIkG=zZE&+i znoe>Rq_bKx5?hUb9^fA&f0Q6WkI$A(<_EUoYG0|{g4-6v;b@Iym;`sJu_zQa?I2Y& z{u^IP&G7Kn{$;0p+U_Z#GZyAK8!k(%XmwkYshx^ZM2f3ai7y(gL7?^hh*1`yT6K5X zE*A9547Q0EK)lPon1|G)G4|ns{1l`L~T8`qpOn06(de zra!j9toYXEX~n&%ZH9T39vdTiiQ=FVqs-#d$t=4aFP3_7-rWz8YyCg4~02FSgqHl;(Hba2!t7pgAa#;vTphTA^X8?KD`>`e{Q@3GjZQ z>so1D69C6UI{*IG#b;LULynv(iCY0WDz!DarR-WG(QCgnugtC>G;AM0jqpg~Cl(3^O?px z1Y+=q*e8;ztL`S*dGoGxR|&gg(6cv>;UyoJns$>kamNZ=#~}182`R~XF#-2Q7K4mS zPo46tJA(wjPLF!FBa{D)enyV;@l`%aGcp2jvF zwekHh-Z~)K2G@wWj&oZaB#k%`Z!^6Z0_#TpwfHbuOcgM|IojyqdZ2~O5O;TI9FDN8t3P%($B z^~DKi!GW89(iHk)HQ1Q3S}T4la^q%amvV~h4xP8$hQZIIt-%B5<2%ikBxvVKw(U~f zyg3`c(hKkekM;T1y4hewQ^tOj$yoQeNV9FscRGrmJPB3*^+3kGp$08CCyr%Loh>%b zWCV?ePdX*GdNZ0I6-e#lI%D3-9z1h!4qHF_5a>FbRk`Gv72dN2%v)#(cDk9i^@#Q3 zkNso+8SdfR>V2b|?eS=%unjuNqb{ z5fNeu-Gwh}dUCJA4$atH8XZF70C@)SO2|L66fUHCOJ&HpVPb6=907Ic z(B-+o&e`88BFNG`r&5w>B?Q13I`N88Fm*$5dMt8RNbKdr0-Ee5@jjx-Khh|IiA)uU zJ3~6pOoj6%VW^K+pEh^YG`xOq{>v1gtG=PzC`zzA+Up zBhO1la@4!RSmh*#GrcVMYvLTrR4z(mb^HY!{8m;nqZ8q;Fe+TKtFaNRYr9X6P=%}n z_l3(3g?-@D95MZR3o6%LbZ!Ek+MgwJt6oOL;K2}Z@A@V~E;78PAa!in38&HsS>-aB z^IVgg@ET(6Uql@?>zO+#B??6nX%eT4dlRtgw*tBm?4u~J!@Z(*Z}A-y{582o_MwrS zI{;GliS|JV8aq9>Oo-Fh>#uZ>|8@I+KEnbFd$T|6bs^M+(id7C>{Qly`7PUM_CTF~ z*d7z_>C?63jrqFf+N_OU>Cf$X&~wpJy=%ZsQ`aM_+~s~QeL5Y|=&0(ibk!)<#{KCH z{%c2eZIhGO*}nW<$y%A2`+%$jN7+aH(L%ElbMh3CB~M``vHtyz`)9O{3e~(o<1r5F z=GlWj7uwTuP2rF&%_p7(DKA;v9{hKoPfzc}+K=41vfMuDi|Wk_Qdr6n)6X~G#KZ48 z;gCEVPk$1>^lb+maB~5Uu8qLGQJJl0H&`XouQX&-#4O`SfNnzol@UUjcGTr<;oHC-2E~)RYHamiEGEruBSuU+J1zIhzwz)#Y23q zq^8UO>4kWRDum+?wUnX!GjULx7OWV0tL7tCwB{q-dSXeZw@pP%1f;^T)PK~r?CKgP zAoUBQ6#nMowTTRO^pxc|Ek4jEF(k3v@RDi1JzV!MCYt7M(Y3F%T(mt$y&XcAYfbOk zwqMP&T=(Bonruq{(v~K&Bi~yOrWlN~&t4%eYW&QS>PI2tG0KN#1GCk-R`2LTn=&(PW3THY zf~i;Y$O}-dm*N^orfB76cFiH&&=p617O%L5dYNGGpQ9ytQQqW?Nl3G6q z{Q@*C)OZmtJ@?@a?U-}lPz#1ghbYd=l!k%(lV80U3)S`OM6dgi5g?6UE783ID1NleJXfb`NSC_ z&4(4bJuE(E4MUW4jq-Wg#B~Bey3+Aw8^vPQq`g9$=WkjR%d&>x$rf4o%Xsmn;G~-M zMr5H1i+J(uOrY1M+%?Yova;wa2P3%Wz{l6@RGyZ(Q*XLFU~t?u<1A(Q|8VK^u4 z)KHKtSkcStMmyW@|DF&bot^?0oexGPdbj45CiZ*zmbG#_O3xEltNR*6Mv(EpzuVqk z_#iG+Ri5)anmu8pW>IC?Uob?->AD(=#G18vpb7uojRM!KPa`qL!xdgB&RNk^Z6TT% zc~8_(oblM)a+f(MEru#M*JY%(2J>cHxS3M};WCa399z13iR4y4q`JB-by8Qt@9?yQ zEZ(;aB2QwA^z)mGV0^c?=)0B>d)&rfKF`Ek@0DMRyYWygU*gJ+n@g<4`+9arRYOBa5BUa}6(wJ>q6uLnygerDscAsWan)Oj44!-zF<01wt$#n(y?kS1 z*VG5wUcb}!59+LezhJW4Wt3=G-;|HP4btg>rJYaY7Wz1z+I1w>AR)?ZtF83atfO&G zr(MAf$o4Ptv;E}U6W^-=K~F2#j*=KBle*HyH0JEjzAxU38$eXfU5zncI~xO<{js1J zO6vecRKbRFYiO~uxi#CIJ@>30+xgBz;$p>fSfAPWYF=dkn}_2)kU)*xn8JWMrpK7^ zh|qvyueTee!&s)40BPH#$$J(^4&N!)Wab$Q)s@MTarp>;$(To(SiLx(4vqhFa5u%sXn ztBoJAM1S!mQUlfiy|mNaGuQO-ZWST_85y6BorI+TNF{-?cKJl9tK@E+(9_j$xqwNd zI*|m4X6mQqAs{7`u!`IXB!#fZ=znA7tB}1~}^ zK`;DSW1iy%s!w_05+c%t@mP@>z(b>u>`SILl<^H#?nCF!_GR)eHfA5DiWS*gn^ss| z_xKSlcHXWxg8NXew^oJ@b7D~LRdEgL6~=FWN|fx$?(tIV&EJ#+9^iz9jVg;XRb0rU zM2xL>7C*aAhMeu4Pq`{CsP@OX8>4ePIA~*P8l_fH4}Hb_hHI$?V`U&bkDZSelv|Yv zr0TCbRgL~qy0iyXBI$0Oq@C*CGg(oqMII0cGn~+`J)v$AaM!Stl^8nOcVAL(U(rU5sv%Pt_8h7q&W-H$TN`DH3G7j14~Hx7p;>OikPk|sF9NcM`2CHk zxv4iyj@7BJ?-`3+M$OI(18@xp61&h3SdB+wn4gQxl4 z0YT-;_u(fS_wX;mpG9so$%HEcIzvB8zig`#va{@zb^B2D#Q#|Lm^bgWzk{W6PZ=a_ zUAPw8?I~GCe>PE{lf?MujWQc-;&HeCh}L+`sd&3sYH3L@%K5xFS3YsiET-~rTBb0) z9v>(>*@d4~v6x1;i0KUDq4+hc*CXL7IjEmCbPfzFawnPHq(CkLn0WT5*fxUto5c|j z#v*FTi@KOXf1E^e0@!p_Zuyz( zq}j)*;?^%M=FCG|NGn8~#)-F9WhFt`tGdad$9g;U-LecX;fBFWz6j#YJlZ5L*Q(d! z`GOn9?|02qZXNfI2#NTjpT#N~EFUv*H4gw*_UuherFU=5Oy8{Z)+rZWZr+y-#8K}u zN~5e}NJigmH$r9Rlo6?%#F_p<(7DYkaJT4!eXo|3RH@GeQuVZ^Usoe1UfEHw$g1LD z=ZodZp}9`hOz%nM1p%*mGY`}a4X`KS2fyEU-33^dJdbUq-nCZK>t>zkPru)@hH>|-s0w>>%vW=R%Na*E*Aj=Ebi z3uYMWA6aJZF`iLDJ0+AB5pz!_DjSh`X^hjnL!qj;^AQC#H)Hu|XwFi|%f|Tq9~P=E z>APoXF10sTugf1VszcYXs?dN(b0j&x-So715576+xD!Uuj+4cP`Wutk`w;pn@UGDx6@Nd>RdRWZpw<-(yY#Jf>Q_Z62MBR zx14{#yCy>OHiK#f2fhAa(jf!TrR=yEDQ9X#+G0qZVL*~ zqJ#B*UhG&3-)RyXB4=YbDoEmFBj5(|Jz%J8_hA}cGrKm5jx3y3gDN3v7^)uSNrSD5 z*>%^!y89D)@WY9Nyv>yz>4hzF{xi?P+D8^SQ?hxu2G9W?1jL*c#DL%XhO}TS7bA~CN02u2tPu_ zV8f3WovGf!IYYTId0HB9{kYgZCtUyH5mrn z%WU4#vW+-(+qPZFC z9sPP|ydWFBE6mm0@9K8>kn|~cD`D@Nu|D;sK#(QOUVWP_$nu-LOMw~L zz}{-DIz&b$)u{96N@ods2oRx^hR%&VoprbG&1VIF4UQGy%c6vftyEg`+f@U(*8vZW z0>R_?r@g&qReySf5Uwe!6Olf}Y^PgaONzhf$*DSZ9^Ev)0NMt`0;Gckg~F}{FAtWg ze*I3s(7TLj{G_S@m>^FsfNuKZp-)h-?3JrZwOVS0 zkES8QXf&`M|6My05xY`u856rlsCyR*i6S0l>j-a>+QaS)WykjfCtoMe9vC_j8Lqd2 zq$VB28an36GWTg-F#ehlJh>?1C>okG<%-*Szz^a$Yyc9SpPt;Kqn~nsWc4NvI1CoN zK_&n>$EcmxxM?*5kb-ME5SV}nz#oPjs-{*F1!zxJxD4SJmczSbdFojZzwFMsUh(>LqS+HL7ovc3sFGp`9!%ftI`MdBRH{_%Za&?N*)(_GbJ9o<#^(>Mxq72~bC-IVWofFHUv&{Eu#v21G{ zR8KB%f$li4Sx_{nsw^CK)#Oz$dV~L_ehyN=7*|ktjoNb&N76|0?0VzyC}&d>o^If< zQxki|(#AL4O4uI2Yzj2HHN0%I*9J2QhS;Nqj?yWw05uST&Dt6PjVzQ~4edmiQ_oXg z<4X&h#v#vFvC2B*2SpyozM+-$D>?`JsE%jZ`nHFwqgV(HxN#w_AX*2_&&kJ{q#G)rcT~dQuD>m80LS|u$Wh7 zu%EU@Hv;M0PJ!UxS%q7N$2UX9Jj|VN)m`O#g^eEtx|x+bos1l9b;T~9pc~k|Eip^OoLljG|I$ud4O$x73)J)ax|b& zSLGKq4y}fC&cULVPXB4c zges;By;Wgp1%sK#}g$ICgMFU$1?pRu|SSsfBA1IucRE z-IckEA1J#T8-jLi>9qK zp@QE3%suN+_|(OwUf%1?^z27U+q0*8h179F5t9(?{qZq}wOTuko{V@K{`cR&s^qlnun8+IVX;T|v?jmS)Hz<5@RAuUn zpA|A+lRfPSF{b(%V2@p%W|Dzp1JL8;z+RlQ7p#ayhqcTc4slY1PQ7~@)Y^AyFgU#} zfqM8pDD)e0nI1xZlV^M-owmEp3zzs@C9W7aHxMq$Wl*202WI(*$hk=?*=0f5nBaCU z*Q%}Iv}^T4dD4Qt1@oz5E5n~0d3~l{mhl{TN;eB=W);#F^Q@Qn;KnUKU(Ifw;VyUp zIJ~K1x(>L-x*owo;9!o&(i_eeRX83O8#TTIqY$Z{tPJbqK9LGE`@s9$x1Y!ALZkZ` zMgR~^M?D-Yoj{C0bQ9*qJJ+=@$}xpCit}Os3FjmGA&-&x*@LB9Xc~50u~myt81B?@ zcOXn`W41&zK_O%MfZ{9uR!8pTb{Fn?K<-l%$@vbciKv%yZG%~Vzr)2o%K6qp{24`! z_w^afd##_g3gM8<0&gfu!%lNPq{GI0k*a_~Pi7^%154x88y=>tZv+BAA!pruKO!z6 zU!|#>GPZrTW%up%%JAr|GM%-Le=T1;3q$4rc>WJ^GT_rzS}9QB;%%ws=7zoUe%k~5 z)md1zQM}#xC@o*sH9P4yb|dB1mep@I+|q|+1Iake^!ciU?WqPM8dtPfgIc)ME~LzP zIT#Es|t2m`!f0CKJe-7EkZix9j1z9?-(93{B z{=!H9%c9&FCb*++2kmKC^$Rf!4Lsw|PinDa9goe+I%g%Aty5(N<2!qD2U?mVTVxBm zUq0fYkvY=%1c_U_rz~WTjWac9q8fV;Q<8(;pf#mCZ^HYGKC$vLUd7jprlfBU-Y|0& z3oBt|C^DvBHPZ@UGmrXIf!p_~W1+N`_#38@u&cMWb+NEuzghzCjc~dE>cP9>s^35G zPA)6SfJf%)r4BR<^%ysN>&TKefdoG)7mx;V4o93DA3vC&Zs9l?vl_IB!X;>^ozz6d zV@PWUUtlksb&ZL-)Y8l@rh0QX%O5G)7%!o%cn{9TP|JMB)G?;?A|#2g6^sDMzkN)A#iIK8Vv^xo1}o9v6#= zHvhQu=4oB?%5ij1hl|1ub4l7i>%S?l7eATS^k+M{;eB!hw~@c-JAb9JE)U@fBo62L4IhH0Tt_l!Jx5Z(ZarN7|>88wdIDpWM`6(xZ%EGwnImo zGW(J6Y4lyqF`53y^NLZO&ggA6Dld4%gC%7G*CnPsqc1R2?>1Y^r?w8yu|{lL3-i6h zj^hzb>@$r!guJb_2a%US@qYtzCGt1sgjvmLS}Z&><>LYI=FISSy|FgowCsTf?=xTX zD{yWU5BW9ca9!x(_j|NU$3v7JyKoz+2A&PoO2>ooN4!Yy7SvDpV#OcBs=3kfuaf~n zs~=D*dp9*MRM1q5*f*~&69^~sB}u}KF9(;~2GE;gZw+t-SxkLEu~t`(R^sYTdC_A> zQBbbiQSC$ipD&~%;CUr)r{LI4+!ekfXvUHMu&=X`f1#(vU##(dl7!nY&FS^t=Xk?+ z%$I6SY2?hUR9c=tGOr6)ZDxT|l(Qa(2!HeSNhIRkb5kjw0JY2x!*QCcG9?2Rm4A+w zuI=grXD_*b+NKD#8S-ZfP*m~h$Dc*Jjk6K~!lq4?&mOU2qamlyl?ri?EmL)G#RlJ5 z{K>m`_ggJ->Zy;#xhXnnn0ncmFBJ(SKl8*JlelvsIg0F)2y^Cw-TSP_r5$#gfznT- z(OFTUP!_S}kIjg4^`mkP6tmSBo?3TyVq=d0DkZ?s_N|35}%ug>@*z zj3QX25dnIs<+1Gj*0^$nmoX9EwtxqP@{!-EJClCn))x#UBKA(%D|4!`kIq`VYo#$K zgR#HzH2ciU0H7s_aanOLRm!HUg=4}b1SmS~B#CbDYak?i|<`9y*$BC7B#`x>mbX|WZ~7^tSim)Gvohl4J#n5eFu1uQ?d3 zw`?N4+bKw}H42cLiiIBdWct)pqgvRef~6Xgn*@Ic2j8@_M=9mJz0fG&JRF-)+kO9$ zQgg!5BL6zt&Hq?eO>5~&S$_C<=?3;DD04MU^ z#3CnCc%zVtO7ZLopC)tAP`zmh6$xY6*C5UOeV$-F@CIn1Se1;Q@l;8&=cheii87CS zaX>g6UjoE9ln+RPf3MY0?{li%%{HNajK8V3cPv$?$&=$@ zZRx9>VR9}R>%JWawIXZhfZv-+OE$*&mR{|9x^f0U;h4Z7OJ*f^IC}Vz@j2w__^T)) z?bM1c*Z>M7H>!UEsmlMxZE~#xd1SvPI}YTbf9-#x{Lm->FZ=ITI!^%M{BQ6@0NRZ_ z6n_8TnC)8{QvxMuXV5_mt}ML-I&?`aZ)H zy>HOztEds<1K0;)7RNhLHtN?2meIi5s!Un3Mo_{6i ze#oJEPIyKsvTOrv+BBV_~km%O)`bel$&-CK9}P<1tdCE0P+kNl7w zg*E`!k^`cLtM%_3{)r84i&R*Bm9sJBZpza%{LSN{!HOo&of?>XRF2n4(+i9QXK=*2 z(TCe=WW>xM`43X<CgbN4&mdVSz zEOd8{$9DI2j~JgpXNY0kA zB_AxT&kmG1d~2vpsVZrNVpybPcqgQJhrgvEvw=TyumO^htP529Bb?6-)wGq)_kF83 zndu^HwHmekAt+9yi-Sa|7Vyz~mfohF9o+}$XlPiNt{!1mF^*))3H^Acv2~hrk7U;a zJ$|)Aw;<)4T&1}t1&Gr#*3z&MXM_S`B!U;m*7SuXxJ(9TIW&Xoh7se)MW80nxjBF7;@*6+->Z zHZ#AI)S5C+g6};12Z$>-nGCVMKTN3>K6@^Rle;_oWb@bhazDd)tE!8?c5&LN8@rwg z&thlvBasvzC-*>U-I|%K?JsuE{N1nzHD3lI1$xC?k^@x1=QH`S?18ZtLGcaGDM7ZQ ztaOph*@~^Vk4YcXVxJ`zCkEGuG5~!8@9tc@&E46;aPPD~ZD2OI2AZie?bb^O%GP|i z20qVf82d-P4CF??0|;B$I_qrQM9=e+XhO=n$m3p1Ig7;FV#OcUn@jb~KOt>1i6cu_ ztknaAiZo7W5HcZM8JxtB#Pj(JJ$oVj_kSk)oL$~ed{uv(`NTG0a`mXyI_@j5ZVN!V zGL+Bz$|es}Xor^~A{2gGiel9d&}Zc2K6uV4!sgwMGjJ&FR+1x9qtowCG4Oa~cY z*k9%=vT6gjQ6PgjwrdM=LK&Ui)RwpQ?lb*&_rGLJIvFu}(8v;_%wJ~_GJ3}5xDXO5 z@QfDEAjRHdfw5l*Its3!(pWuD1E1p+(_U@tHfs{fzq zxC3l!@*wYAWj%}uR8IJRx365RgeXqepk=@6P9W zKELnzZ@YIp_n!04*E^2$?8l$V*8jUrOY@JUzJnw;-Jv%nT4vZY0&yi^g7*&zE+$NM z!-)2^|B9G+*e$mfhVJR>auD&M8306!o@Nb`;i~c1cY((jcN+`2BaF!M zyuz`5^Kc(mE3UWZ*XLe$EnANQ3HW6v#YNVU8bEWckwc=vq0JU6l|GcS4&^-r|J2x7 zPajKUum_*tZb!8EXb)9qGMdb4+C&~{bS&)gEZ&fvuXu)Ry-s$p4;~2d@THhm>@gNL z>E6{2={>q+7>;=jhk9SrKIzrcaks?REh6{%MdYP#26IXv@MkeUFnB{ekEU`omdP76b?rj5kFy ziFP*rU;?(00tlIkDyKvp8A;c?==bzdl;B+4+<3{KmIWC_O$8&GxVtwM4rhRKs}Abz ziV^oZBAc>Kh1%Hb=@x2DorIOLmA_2KrG}pBXtX+@l@tzoft2;Fr!y0Fk(-)n^aOJA zTGrAlDN7Ow#o7tkp(tP#iGqO|UZNFQAdczzjY+eXr028THJMhaE#wtW?h+6JMJJ!o z0Iv*nJf9GZYV5CWn$h1I%25#>7eT$+@ki-bZ#&POzgRbvS#C!J=-}{D zuQCjKL^$ManO;!IjJEe3J=i!)1P(_Q zi@|%*c077mX0V7+1Ndh+i3qOu%MRjzR~8rJxH~#g`slO@YT zOl&PmN7Bk$Wyv{mKy8<-O14&3uIs5%ch2iDMu7X3SjdmccEdTD`JA<1 zmb==FzP~r*a)D<#!z)+1uszZhWb0obkTI1i*$9A1|6U%6 z#Imr;D(-$k2{+atKO>uXt(65Rk$%TN&z~K{Qx+s;5ErY@B%U;e0_SpMqBcDyB4w_VRq}R23(mH$t5lrv zkDNTp5i9}ZoNr9D*-hp9AX`t;pVrQlj#P9X)8b{!)wX8e<2pXqO8ilzZk9I<}-^ zOl1$KW_`J7$oXg^0A!+Sy)>+tHXMLZLg@(8qoEK-QvL^&L%;drWaSP$i;i3fn>8!T zAyxRNnXGAeE=SNi$!7ierVLCq+SQKn`_2<-RsM>|-sHIwpG{WPqGz@lct5JaBKZo4 zPn;(|qV?o52xs&w%B#s{cuLE2TDnpK-EN+_S`WQuU}S)|6n}!VVn=e{2afkWs z9A1<(p6F$r?%GaZ7|_%k-?)fvY&r*ee;Zq;#Myv0QSnTnDyy>GgU-SMqIxC}R}}R} zj&w2=LP0|3^vLRiL^uBi*o1L)Bq;PlsWSdWUo_55&Wft!krh@LR9nkRvhSmAN2f%V zMX5R5s=KnCBg=F+L}K#jxoIJp*H&Xm%zQqWI^1H~c<9d|jPr@$RG9;?n;@e8X4y!V zmHPNs6NKjq>pGX$-`SC5P2!&FfDG{6`e=OfxnZAVeJ@D7<$k>d|MSSPcoa6Db77U0 z1)E*p=QjhCde%>biwTF<*6XD}^h2qGsjI%aU6Gqzqburg8%-~yqFXbpOLt@1kq7b| z7ewD>)_$$AG{swO<)Op6P+l4Pr+P|ZVmBeRNsS(m_uT>#mIE#47jz=%Sl={%QC;}OH4iWIP-$4OkNurXNkB;jwl)NScKEya&S!|0mnCZNsyOKCAw}@mO!89Grng3y{6joYkJ=E& z)~u9Q5iG4+w|z!%uv@2;e*MxA_Lw>v;1qtom&A6ok?wqgK6G0z&K7QU)4x99zYk_` zXGjCzvp*tXOkT=KWLwPHw5B?kalXr?%&eWFC@E1vsn9R7xuN}ZYw)m8{N#@4ex&!G zCvnEB^ILKgv+HX&M=EFWH*bxV#k|p*6ujPR=>6r(J-4;{8HJU@bzp{;i_>B!dzYfJ z3Np9;g)a#H*X_Lx@ItpJCULQ2E4p12R7tY8n)>%DHPV?A3)*f#&{u}p+WtbXo=Sri zu23d&ZCFz&vcUoLC_PBSyZp`Me~al>`YfbaX;5};3%@Wbu~KCwRDgUXV;aZNNO`n= zW`K+t<)0J5-=Ny#Jaz*gCk7v&;x zQ`EBRtST(hs7Tj5$_i@gU-2%dGBv=UWbUA3%-Nnt3Xud)m36f zw59v8eo_Lu;l@?E8~zl-pIq#Hq^y0@&6EMEzxwP7R`l?_#KSmHkVfX|xy zBeU00<)wh_k|e#HyEp6V`IHzhnCwPm-RWwBJ)ppsPv?gH3>>dMEwTHN@9Ia4NYiYf z#Ykb#(i_dmitb`L`VxULQKQh;M6b;{e;U3p5OG%PBtj5a7&qsk+Jk8wohjpv?}#RB z(RtR)*pf9|uX)fIQrBO(&zSBej&TQOcX~oLP^Hs3XHNL)f2s^NbHDUe8{yA0*WbyRI>cJ zSj-$H!Lz@o*;AK`+$^YEH{aNm*p{ZMHljj0XDADh*A5y)jQJ#gOnjXUC$68KG8w!z z_nv7#Z9`)_AELS5W2p+GT3;$I&&aw#;4^?`dYP5MvUEpyGep8zb&6de!dZS?o+?em z`oocF;!c{@5%$Wz9=j3__wImqdkbRnTgnL2M8>7AylYQ8ix)c9|5u4+a<2NIoH7-E zBv0ffr^u${n2TtFvTgs>t)ei^M`kwt?*=B*Nw#Z!EK?;TLuUs2CKN*_6+I&0QRp%s zV2I8F8Gi;2f(y3+j8;GdTLg<+N= zZ?Th>x-~@4zYtccvz6&!Y-R!34uE=Xb9f5>=TgKntyQdcA=ab(fj%p-K;iO#*1^5{qh!vs$e-5@6BDpEE0mnMABZV1F-Qk5jRdTnvR^CcO)Dd8`%|u-7t}(uPV$m?z1J6{eb$tJ)_!S;$%>E%@ zw1sP!&j(uVJg19YYLE{d*LiTU?9B496y-xp_wcwdGcE$J?tJ5Q%^$MM@6!fiVa<2YP?ZE=eEePB{|o#9 zfCv5ij6u>KvzR3MuLMBFdcZILuPFqGzEySm&m8iU1OwP0QGFoyD3u=h?rC(_JCnBd z$6IM~8hC9~=u5xY+R<1Q&3bKSUnDo@+$oUqACujz7SRacf!$jUrhEzIEOc(6>6))w zXx5F%b`O2Rk2;^kuGdJp$8*R7_O=U<{irV;_7_e2>knO7Dq#aYR@|rpIHaq=DRb^Dv_=fzjsq!EG0q@_8E zgtyG^8OgwFwm*SGvNPoT_?sJ@u4?!iLB4`$kCzOXMeQqM@Z+22SBb>Z2-^?rStu)y zIyn@kDf!5L8LGp9LJdUUh(C7WQo#ZTn&JFizuZOu<}_fGO)2R>nZ~ey#0}BC6#&nI zivqu)+^rNJjxL%`Z)~qFdCus&xr4^EO6UL_%TyySl>pc^aksW=BYYtF zyp<#O-JieNPr4P`YUOu8uQz1@-`POxgV5T4cvkN%AYu{9mFUhuh85uup2@=X~i<1q&2s~nR6^DMz?=Y$QC+Fj*vh{jEQnO-R zfd*DhjqJgGwbkYC;DaT_mm*X-BOh)&T{8r zmW8yJ`!lBL|qNB~fCp zb8t81?df_)_RO|}Rtf=M%sTekvP!pVH}!Vxb4<|W{nZUV$T6b#wI1+SCl78RG$Ph} z?}!q5>jgUZON zq^SQQuGrcTjiZWdt^ktZYCV~o8~yo5pZHS%tVw3rHvjCOn@(gdR6`_|iU>C<8mul? zA{)1jV~YW#Kw!Dznn{vWHHDys9`(-Wt=9N2xQJ{5mXl|(Q)7J>AR}b=^;9P#&;-L& zfNiDKX%P)m2*2#Q+Lb*x=ch2se5|VeD(3hpn$U4Nf%{*ojQ%CgzK!kJjn%sWRI7Mx z+stTaHxJl`3Y^cv+Z4_snm^3}tjA#T>MIxzdCSAKbytuP@}4^Fe(RM>djtm-}-xWqPx#WD{(6Fu4&l*_l^&wg^RL03@ht=KkylhI``c+7~m-&JpsMfQTO;aoX z%F*<*d0OR&R6pE*pR7Cp2xiE9fLEJ1Sajuxq|^E>Hx%iuBBTH|Qcj6DvX_R0A1%y# zx77d1`IX+^7!le!rT!;_nb)JUaGa661*TVxg+Rv{^k6Fo5&m9oiux}a)F@bf5A*?1 zfG)`C{e%{yGnUf=Jr8{c*k41x{(}cqk^u^5K_V*2%dQutXZePFdCsIJ>YnVnECZE8 zKQi3GP&1>EhPN>(B@@7ZQz_8o5=gx;9Npzb*ST~nH?-MPJ#qrT4@bU91m5p|CK6H| zYDpvNFYX;v<+w6=0XhlM70v|mRas-62ERh5YdNN#A}!qN76X_u}}P zyIuyn{z(n9I)NrBMz61=tvHHOw*28wc`OEGX0~J$*AIRmv>SWgc2wv%dq@2oVA522 zL@fa5!XqTS`;cV)(g#dh(Fu%g+dyPob%?Ay=YzN2Kmerx3Ad?3C{vmoYaJydJ8y}^ zS(uIC3Ft-mZtf>f9t%h&Y7wZXf>4RDtZ(84-k_y>>J-E>Idy3?-2u1v4cZ*xDiOFO z{45-U&ZR_;RPHxxw284`y*V{4;C`Z&m(`{wG@uXTfcXM4ARD1U>oig2tMaXy2x3sO zu~Ie$NV75@+v_Zg5`gAPw~^BE=Qk}8mpmM<$sRKw-^#Y&Ud1qMyz|;owSKdoCCs{Q z-*%x*_ZhX3FN?_WEQY{V7_BR1hM)Nf);7Okl|6}_duJbf^<=C>n%DZ!v-^_6D<{Uh z_szix!3t>;*Xj+tK$KGC{t5f`xh*qq4q!Z_zRwrT`A0YB!6564=FKhBDo^z(XPRAl zQFFuUWvtBT-kky#dM?+#a z87&sl^TntEbrpEPBHi+O{WkhY*Y@^0(pz)L#%zzA8G5yYo!pPZGJD^zS_oC18Rd+0 z?j4^kFY+mF_6BD4p5%Y*aU#xH^1p0MFQV?Rm&lh*`a`$Gb+;l884;LarhDW-gyMGQ z+CVm;ix((^*e$XO@NN&0a33uTwW-fgtGMzQ*zj~s1c#_BdIF`|cg5f#6wXMUzk)n9 z_u699mZn|fvSP5tCg$>3{PGOf=2!7~22vGqJufB`2iNoO)h3V@}V}b2WYRC}BHB)CXn^tkN z+6uq-S7662-?h-Xlg~pO|H|&hH5r-~#&yD-F15Nq*IBVYt<4;r4o+|U6o#DN4z&^O zUUKtXteh)a3B)gQDNda9;v#;3Zgx3mA@`1co=EU(`m~Sa1{sxzj6C|##tP}?C@Q(_ zi*B3|GFgWZU)49ueO#@gi0KaDJHTyL7*>34Tb_8*A^{CLnc?|TXtUotTR<18I=69j?tpywMUbe zfextEetch^=i&0^&whEmVlQ3_>u^pG2;q&pW>VW1>WN%)L99PODi?`+>Z3cD(vj~? zMh7QQEA0?ov0_@d`Uw{buat_Ox-sVEK;&&zVw3R|SOz0w7R1?SvM} zM9E*c3Zi);B{qAE`NtkKi%@tOAhsuG9yKsP6ifh(3A#SVy~gTjj^zjSor!BX4bu*Q@EKvQ72bpQMUVWToR7 zFAm5;OD~~ZcLREUKL6${oE!VP+-SdUmeh z{(y2K@3qw`ofv+l@nrcyk|xV_;G?k!N=-UP2aH_}$l(Jw0zD77p7eAQxTm(QDY6`x z%avw_U0rxQ+f~cUlMxqxk^r-t>+C%lwy%n}MxkkKUp1JyLHN5jbs^C;T2AGv-rJQF z-MUK)JBp0_h+Vr9zf8C?W|sj9j79Cl_Z3ZzVVorY`Sd$ynEBxM6ja0#mD21yJS+J2 zLC<32TK4_&kMCL%l_#lwdX86m)}g{dq6`+`%${@SlOpDk*B5B3ONnl3KZLuLpyw$Q z82V-gMyX5LP|&(4 z6&=h}D`Z4haUy6s3Os&bd|vpk8v!y!n=O>%zmbZect z-i`nyHTue;&gir7B|DBK5jt0BrVu4C)EfClx86Cyh&Q1Eo?AxFQSK4LJib zwo!pJo1K07OsS9DO4r0W7SX+kernuM;_TpBsik2;|3D?{1%6Y!7#t*RLpHgg#KmA1 zWE(nUqvd&R;O*4ndr@3Sk=64C7R@%sueH+2vtQhNe9Omng%}XpCr<5$n}@1eWXQ65 zxA1arNQHyN-#6JleH$C+vRwxzY1Twz?D^KKF)EqqbEUmV7e|6ZWs!J$jixWtnD_){ zOo`gg>Q>RA)K1x-q(nFtw!Zjxg$mRc7Vs>r)U(Wfs}>79gw1nkbIzSmVcgZ#;iN6^9%zG8yDluD4qrme#E+V zIxCNUu*#4(w?7)V^#o4^FzqEh-d^G{HXFZyeaEW1!?dhR0pLd5US{Wc$J$fEdu?xM z-Ha{_>yA3x$N%QG0V*X|s6nuX$dX0o)B>d*0N70-BT5Al%@Zar9gSrjJa{+87tL}%V;@INC$dpHI>OaI5g%s&Te zuoj6GWJQ&#^1ldapTu!epMeHB(?-n8{{x|v$~dVXsg$Vv|1^WCUo;a-lvrL*uh0MY z&lYdU>+g&wP(T(l8zsym;1T~JKX?r@`2roPr#YTivCR9;kN$Irk{w@AD(=?`N$*BG zb_3B`Da(zqooU%~?ZlvqaMnd$%$|2Z;T72=P_sn{RJKaWY{qBmtORX(mmBRI+~`E! zXbx%odfe-Q*Lwy3wW=0*<2yrNMHngk()7j)ak{1Ax*}lhQi;_4^im7fN$fR61&eTie>AvTszQPU-IzxMV%PWbI`ZVh} zk-~D$(PObN_;be9gThP_)j8Rcq7W8o2n{30VQr>j6kgVdII8NZ*Rag&r@<{IDa={WEl~D0<`u*~K|*69jbJ;9hRU?E3-H4^bK*1#H^% z5E|*7IHO6Q+)OJF0g1HXO6RIPL%DR zYrrd+ovs$IYr((MutB+ez)}Vtz@%AYj_`QMk9`-{bEBdnt?3x;PnoATW`tWLotc7L zVsH9P#0?!ye)(Eyex&pXE(DU?&_7HsAhl>kaROLm3>xwDS7^P+EHHbtRP&<5o4ccN z$g}0WGSg4a>TCDdmD$iGp!d7dy~C}(NDVrUfdU%wGFt&Hg+<+c{u`QK1q9~t8YBCl zQcVxz8y?M{;J;YS^|ykZZ!y%Uz30VInu7=@l7OdN1xr9_b^zZ`kP=>$_p&UzkJ2hY z{r^7;a7W_Z0eo@KD7Yf>g7}O=gkimjLSdvd)ZEAvL_a4wq!!nxGVZQG`=ti(HV@F= zCI`@ewB#ZDU9(9F>f`gT-o(9)(WhMaFVP_0J+C-itIQDZ9Ey?)RMXdYH@6k1EC!L3 z=7!EyFLg9LB$}U*L9$I5dS1;_+EvuLx!>NkO$w*HexO-KXv4})LqNJquV6%nQ5_fl zv#WK${sAw$l}+R=!5zZi!rr#HS69=1D_8!!AF(KyzI|~Irc@6tGux_SIgz;@uely| z{yjN7tLDX*gIGWHN^w_!4CLh>swL-NG#{!F|0OFBs2?*~K@tdSXK${nTCxF^1nRoU zym$KFd9^%LZcS=q@dc#cVSmsdwjTk=XAock zLA8f9^2c!6hw+$G?t)?T1_NjJfwCXpbS3A1E(hX#r)?D+In8;5#!FhaRLuT<|Ic&8 z>-1V48R|Iy`&9AJpKBR9)g=lv7wS}}U)q2k1Yxk+mMN;{A%96TdL4pk0AC#X#4vi^ zVnz^#P>LsCNL8Fj&1q4sQOj_=#c9iStK^X&~0$|4`5U@H&XQa;w_|#%m&I z92RipJmG&iTDt^6zWLOZqL4G(zeKeUC~Pg5FA_>nQnt`WWO^bq{ZXG1oYR!eL3=tj z7>1&I7G_hr!0us#$QdK5Z)Q!{aUO%qj0BNP*#_bHAY=Dg?@64BgNv&ShxJtxKY2hW zI?8%3SPss@@!)KiE+>Rqo^^O76{jb{miVwMipqVLiBjn9_A5&~Q0x2Y4e?<;4V36l zQ^{?ogFCWw9`M@3TC)w_gUDCiw(sj4|= z+96LqboK!3Z4tV>59V%s|BhV57!wO_U$ZX)o35;R9u_ns<%9u>=jD*!Y`s5T6uN}OM2jwGIGf@=lt83yB;o>BCW>ohG0#3 z>~aqqYqxaaHTZ@;{e~CuZ6kQ(d@B5ECgNb44{Ti_Hb!fi)w4vCFSkB@CXyA>;%b8w zBL?PWn&K`Aek@KCECeLAgM78p*Gs}}z-z|eZ*An2i7xD{x^`gk;5BC29?U@b=~$Z% zMo0n)3l_eQ_VB&!mVi-s7Foez#&QnvGlJ9*R#UKzX_*6O8(Nt=hakRb;&@f@Uach;JBO)Oz)fk5IK_pK!#vPm9a zQ+d>4OM_s70JBlV$Yfa#xh(y-%W1mx82up1e1_mH!fzNd18VNN`_4BBbQ1~RxT!!O zgUAnNSfE7sLqM2bX-W^t{;NSXdePb==_RrzZ{` z=>skO{sritr<(LPmPxh(!CI|-CZXnb|B7ECMW1b(U~iBi@vr=1P#)W2s}z^hq^!>q z`dz<({u%#OJ{eUYN;1>w*u33rg9b(zbh(UQQ*AOKcaRGR+FfB#oW)~IxK_;~Oq z(WmjLj>Pcy#hyd{(^ywwM%-G$CLOX^J-SbItZ1@z(+14PyIjJbfLcfBga7+AALU-( z+mBo}^BY*%KB3=Ubs5j0mgZ3Tcma8u$y z)zb&4-@W;}kAxp>bj16405<+tuwpw0TtNyxybfW=obFvRWB&(l0!V3n-H~4>MrP&P zwQD|tfss60jB)eQ3rigT-(Md37I!$9Q0)){lK-F4k9TNv)b?*+90YRc6eRURbH?A% zI-~rLp#SG%ylk)4-+Q&}?mhSATa>u~NE%4WRZ`C&m@dZz)J#ct+;c!#SWAz1__{6N zzXvXhzYi9Ukr5Xj%X#D_5a!YTcUv>@G^Y2~dp0+!7m8?v=}F<03$MV`?x^Y!;#?}zL46(wOvv+3{iDK!+I<@-5rDvfKzl(NH~fyJ^P%n zh@;;`u)ug!Ytq5~lP5Zk=5xY|-IObEq@3F8nBH=sLR7fp@bdhMAE0;27bo3y%kW@y zE4R=mNQg~`9e9AI{?m+EM-*@ro-16TXw^$kLN{Umju4Cgh>MPQNe$}zMR-LRfjDSVqX_opRyVd?wi2{A= z=|qRnH`oj717Wy0MV;+Z_$@r;O7`$3X>`gixqKK)%eZ6RT7n;3`VI&t?BZsMcuK`gL_-P&r!YWtf zhkXWD6Ub7Xk1F~iW=c);BDIYZ%D#yU{GBH462%~977wqKT zcyIg_t(pL*VV?%4fI?Gx_tAW5o+q%A$t=dYhQ*(KzZJ1faY5Og*pI{vUGEzsCa#d* zQrUWn^=`@8gMUMweQs|p23+t@Ye&UD@I2lrG_9>0clbX@#E-?1TL;cJj0c831b@3@A17T{f-`8+5w98$&?E_;C%}>g(sbSfKY#CO;r^_;_mm&*UhDW2t z)cqo{=yAts?)VM`vzr92ri-w|oA(+W8Oms!hl^eB#4`r8dks<}z$l<|dtvBw$E@Y?x6<-9#&1tY zO*-!TwtuF=U;_)9)HfVdb$`o9<2NC;+cC#ggkLZ%Qxm}L)w=YCD|(AV7FG_wP$6hX z>*gm9?K3!Dif2cBixk*85BG0E@{ub#N%4>RUVU)-f!oT)Lhkvbr6`fc|A(*lJ6s-E zvOd@Sb05`Vfj8MC46T_{jutuK#VqbZ=23@&jLOanAF0IV+-sbNgdme&`fme*tYv{- z()(D8a+Itgi|ZBKIBwnZs=_n#K8EVA$@&GeeBR|?k&d5@B^_A#Ov|Y1I?eky`*JY1 z)L_v!NtXmw3Kr$vX;C2l0-DOcJQ<+&+*0`XyZX^m$OtNXU{l2S)!~>W*)A1nnLJ5H z;K+6M803L`@{qnfUkiVxd@*4o zbA)ityXIA!1L=u3D?MD-!)bh>eZ{2l#c7gHbBd;v#-CyCGsD7%`Gu7&H3HtZ2pgqn zlk-Su-51}`mXGPV@U8aJ5+Y;yO5>!wF~69KkwPw7Fvs`%!RYM0{&!wy>s-S`BO(bT;Y|ULWPS!#xDh1Atim?rJEjj&0Qu#kLN)~2zP(M1qI%Zjpvx> zqZl|7_-_SYW>$Puy?$ovOXDP-GMqiu|a;P)Y1()@;foo!OgwcrIaehp0N5S0gZ<=G-8-b?{)j!-xU&1@{PY6x#5m5Vn z&S2HV-_(dD{RTb7F$M&&s{YKo2BK0@x>h9peiL(IA4vn{&mX5(-@4mmM8YtS9c^Xq zipFAw#Ey+>5^%B?_9*B<`6r-v>BrM6S$@n_?>w2}kV=90a&+8m+&7cHsUAD`5a; z|B|vc_S(+R(aX&CxzBH7ht0-62utbMV9)QWS;+D> zJ!of4<;G~7|GptlY0587TBz!qCU~OXMv?oE?QB;>=g4mM$;*()YDpht=}Q4oGTWu; zX8ou~nGSufugqvrv|6i={S@o$Fq4SK-uu$%8gBN8yv6O>PO93H*Rvo{#-AA}c1q!l zFaMla7~sU|PxskfAZd#vfc!H)u9Wd?urTaw(P-m_GXt(6mvoBN`fQo(afb=lU^X@R zkba-jvGQ1+igB2rK-CjQC6U~2R+Uar;CFZa`nYtw7aaVw){`j-gV>v%b&L>Iq*5L8 zlokSe=qwtKwR{0SwMY1}QDon-04v4At|+oHR8i3NqNs^Bumb-eacUk@j@+VemKy;p zDj1Evs4fm-zqG1j&}De@X3pQ8`>cm62b;bK{9~?sno8d#RaTg~DjGR8B~sN0#fQ2x z2ZFIm3yy^|Q$~)jOlF;-;#?P%>#*dViC`^+IaRRG6qZ+vx7URKbZ#W*Yi4mbOz)Ps zYq+7NkqaODH;b(VH4isG*LI`f9)k$S8L#EU9r6nYINESD~5c~XL} z^t1`pc}%?Nw^8o0y%T)l7BpY>rd&xK`dFiWz;M_>hnyC*%+z6_wb!&kjs z?8CF`S#YEIp$LSUO-|-3Yv340%;_W9E~jHx=sIMmnRRopsj1mb^n*MsNax*9q{9wn zI+1h(EA(Db_7+Gz+xc2#ZQrg5Mb7mkHM}-2Kapunkn6g^%_o*jx^cg<^7>xg){v%@+g7~cG~i9=RZ#7P3LojW zFNj6Bm26MjOJ+wCTe2}D7A({C=KgT&c{d28%9m`S#(XPH?DiXe&y$#e&3akRIscqA zO;g1lZTfI5Z9lr->Y5Ivcsjc^%I*2qr&<3p&(M8p^gGg8Zq2sCmY-%RX8lB!i_q-o z@oXl0RsE~;K}3HtE96~yZp@bN&5@l>7lh1qHk(^GYIX5xGpV6JRs*IB3~?yKx0c={GCekx^Q55JGaaMSICEA(svmG!w2 z*EJm)bcqi7-UONkX)|J|{UB>&g)oh2k_=ykp zZZjLY#y5f@nhZU2;07!nER}_O+@5on_!R+i`{xjD!8~M3zhj8&kcQAZACIs88P!zZ z=>C)>>{KQ_UG(F#!ZDpq@rGWO8E}eTO|&Cp){VJmOzKm(71wQOSi7db?>bQ;MA+U| z4%Q6iU-;MpEaWhFdGC zaCYX`+FQQ6C1^s%!Myl$0w0N55PNCW^g1?8g(jqwNd^mw7#Z$(sEt~5GMe0iR>Y#?v{q6S+ZdTIky67^;$@9(emZHJ zgQqcBf`oR^UW`}3Tx*I1d~#VeLA_%vH{aG3c3s>*Z}lF(c6-%0tS$BM*;zv53QH0; zfKqo6v+TqL+ivHZfBC4QtxBn}jK*D56;?Whj*gW#GpLXvUzxa@8ab3w@SIi2GyR2< zPP`*)W?N`=s%cs1`{redoQIR!U6XIF=l~F6^Va@t83vZcZk1TJM9VKIXNydK7Ipq8uBKxacR!6F%De>;d z&IOpH;2a$x?yNJB{O${S)@P2=*gQAq_X43C#^2>agh@SnztXdhyTUUBJcsp4T0h=P zQpet1^%Hp;@%t_Uya%s!v!?Toa%k1qAae@iButm zvD0GUIfIT%*cr~SUhd7boJ~|HlBX$8H-~UjG<*M2iuhR|j_O9(`(1%NNGG_3c+)AL z^WBUruJdNE8O1`du=tlGnIItNCw+2P;E^8}G_uG#e;>8CBOQg3$IX75eM{WK=_VvDjT%s_k? zf8Q~$>QB|A5+VKrSqxFkaXt0?O4V7q^whEW<;&Omi<-v8Co^_VQpTBc0;h?^gE@wN zjg#IL>k60dO?XHnch!ekFgIm6auC@*h7SCe-^lj?!GyCF_9%s=Jl_EF)x-d+ zmSKe_LH)TzFEX4RUer)h0r%0mZKySMG?*Eu)%Q)<2r|K=W~Zu^_beXVKMQ)BVz_@$ zHr{uUY{Yi)prcqX3*@KB$GgZd5)yqoJ0hf2cb)U(wrR#6S+>wpzSKVRWceUZf;tbH zV^#axAMa8}UcfJi@-xfDHa0u{_l7g`N1V&8$J#BkMECM4Tom{pm(2Bn9mifVN;L6` ztS75DKHS2w@(MpzN+}V6*DSQq+V^}%P3^&tD}wi(qmK2bOMG%5@Jd52BbnPL&#~f} z9YgAzyp%6PE|OAYlbriE38KESFz5>-2nl>BFaiOZwO1Nn^4X|xMqs*MdCgjbTT!%+ zlciK=#Z3owChN-<#ui`o|E|$)b%$qEAY=$)tXv?q%vt@GlBm z7jQ5I+A=!hHAXwD1PiyAi+DHTXHS0`HU>JxMAw-o?zE>>^<1#(h>1`?zSB=-IRiUh zzfEdG=}tMF_#~uXJsdtJYM)oN)vT;L!&E1GU(drN68ip`AO8C}iX=OkH#(0ya2eTI z2N5Eip=FXTwGs#h1RAW$vSHOV-g>KL0f(U{H8jp&WwnRT}PV>a4 z)Wj98SNO*pVs(e(RrpkdYAWvHNIg!C=1sO2Zvv&Y&M&BX&Q!Z4%KiF`o0nKj7dCxU z<}YQ?6&+7}eSx%^J{xEP7*{0 z>^I*ccGIC(-x}0=qt`_^^;qGA<(#DcTpwmJkv>;vtBCf zC8FGSCLA}9J~OH|)OIc}j*^p)$z$T^mK}4orwYc=j+?4iU7+7yhRP!jp~e&?G`5GE!bJBdf_aOE6P#ZH0eKlQ9<8%I#vG|R$6A~)kAd?;;oln^hHaw$s>u~ z;{yRVaGaGwjjoZlMj4>0tSsGUvMcDkle8jk6`=c48@(w&t-B4} zDvk>D&qzH3L%@#JkM1o`kZrxd3I`=*q>#7>yp)L9ir-AkZm<-t zH<7{H)NQ^0#>zF+`vyDWSb@lvr%9}lFV;yw)iiJ_3sV^93p%Y@jc1G0D;anMUfB74jjRjZL*Q7T@p+Wj)r@C=Ysq?g%AXSPfao97e zTyL3nR{HUwkr=IybisBYWg?PlQ&yIsxo6S%;DZmJfATI8rT!S_`-0z-c=F6oZ9o4b z9g&^Z3nwR_9BKYhSjf@^7BY(&(I}!cpL3f;; z1xvBg1AnktrtsLgly_lH4cbf@td^r>kL;<}O=P&0=93X|=#TA8{(k&Ava-^qVEwe7 z3e14Qzd+EqC?H%}1VuP;H zrn#l@sl4?3e`VH=$O@4k5Mg2keHscLPNmx{1ZMHKI>`&L<}#T$I%pW}U&8!(<0tb< zmMHvkQuKu}gI7h1Xxc(UoB{v+E|Wh=+c{ zu?yi)XM32deQ7i%0m)0W>pF+qrx79V`NW`oDj%x+$S7^Ld$P5T5$c?2pE(>$9cFjY zE^KE-8f5=qNPv!*G0j&$f9@=5oO~Vuk;rWHC0oCw`K70779Htf1iyJ3)|kW(u}TxU zxL#F|HJTykby!Q7U_mfhNIIb|0ue?*>!wC}aPSdczc#Ku>w&{5$e%S~IRbW&`=Mia~xP;agRvbe#9 z&PN+)TCC|4!uZu4mO}(Y$Z1^Ilzze1RMB|Z%%Z^^wb7YbTtcI*Z;SW9?{cqs=bF~? z+=ylaq;wR29vLLH(3*oN?~^zCBAv~QbN6{64t4Ye)5P|#O>#bq)*tiy#|`t&3sG&Y zjele#V}1D&StmTi3H2*K|iqBQC`5qzIB;syDS)gXSi%f)(mu}k}Gtyf~-dk)z) zn@RM_%k7gG5?xuoZL8QtP#^3&y$&DW(Tee?$egS@?$5gy&rH}J4=hm%2NeG?Lex(> zQJ{$7dh#|px5bUxw6NEA*tjh}hF_~S1v0Hs2z)IR%0D1&b<58j^vvH^yV2@0HHs#X z+aGvuvFO^HiKt$WDYa%sd|?76E@w%VwBXC8HWdWl$1t$@NSO|kypFeBq4l|bY`@ljZ55p_` zQW7c>j~obYUOL8W@Fl7Z^)XYy7}3&tF$$3t{nl8lPy3Vup@TT{CVy9S=eB?Ec{0(w zD=Ib3aC$VlsEr~0e!($1r8VVxiq6eu?tQy#@r4)Zw$hiPfz(~{Z?+f~2p%!@th#jpiDTyziubknjcjHm7#57X!XZs8GZOcH@-i*6bA5!hsgJ_4 zR`i`%WT5iigemcgjzIL+ZGgXY*|DN!=s2-nhPK_z8R;Z#ANPBRg|N>~j_N~XHM5eb zGO41`rRVyr1~Zq;r}yWc|NSaBkf}{SZLhG3JUF&|RPm#icNPO?JD|?40_SVM};)H8o^TrO} zN|oQAa#?!&cEgXKsKo257Zcon^zopZbeZr%7(e#HBJC9~Hp>eH!MpNn&1gHZ9eTB@= zijIEQ6e{WHjD7oLBPNlvFcqhbpKw4EUJRO=#t2Vp#|eA5F*ojPG|Ek1z;RUIO$kx*QAUHxt^gUzGF z-N5ZZ^f50f4_#?K89fY)v!Bmt z<-f?Wala<4god@OmtRg5(Vr~hB*1g@f*3mGYdv`N%qV2#1nse?4igWNF*>EzjZitK z=A~}3@#TKarN)PAXeb0xw~{cfKlfv=#J`W9M(lk_l!f=9{cdVg_@U~pl_&p_1lV#5 za51_l*?K1`H}FK!s#j`!{e_*!PY3%i5p2h6HhSsN;O+@t7nmZ5jJ5&ZJA{*TY->S_&-b6* zHA(VfcXn-lA*rAZ2rjeHp4q>^cSYP^XaA~U>S%bX)D=m<5~9%q|`9u z;1Yd5$^d6|_LEOjY#*6xN1Z0HLsxfkR-EX|py>lSrfjA{9&NzgQ<&0OL2) z7;bXvtlgf8%m0q~rSFmg-|f!5!cs=)@a=!q`fq1B3cHW}9_?Ek<}psWu6ADfLX)h9 z5w71G31qhxH@Alv2M4nKrF$E<{pl^}JwPd}>ZBa)c}Kr-_?~DrgFYCh=SFxDY)I~W z4sjf>rY7<-+OH$CR4aDrAbKmp`&=5iL1?zcanC_v%H>@;F zW>i88MHwd4E`5!uy#acth&;CKe(e(9Qm@RTx7u2>95z0sOlrjD!|yxFC2dYBc8>yB zu==eG&e~p(UzI0cy%>3{O4L%vH#isTEI_O3rv11fT!FFoI`+*5PhdAd(g|6ylz9p) zv-WdVwPo&TuN3)<4?q_E7@xK|W8bQKJR7f8+kLN!8`wQwNmJ#h{{Bw&!r0|Rq#MN8 z?i3}g^R~iGXS)cD&&M#|(X7mJ$mYJEObk?5iA!U%XRNzm5zT5-@y z*^<~!!PYO6IOl*I7aF&G9q)?`qBk#knaj!rcsgj)y8XnSJD*h)OTErMScuHh{E--c z^T}=}im<`J%{oBoq@hqqFRj`>A3j}}a-}%bd)W5!mqG&`wl1=&3KN1+R zCVVyrhu7jyiC0;N-NKv*XE(O~^dE^HN;>6q(}WDb&1QNJ-xa#SR7fKQ z>-H56oJ2(xVOo6l-8kCS1sJ^@GsWFN)HWtPAVGAR{i_d>8;tAnY>-q=+Z|LWD%QKc8`-bB0shVgRx=_jfrv5V*MHt6?|9I!APd=v5%B{mc zcJar9Zs80}Y`_PaRTfPI>3cmf^S5Wj?~g0^@|zd8a8TkElV>!}Ve;Z+H^uWWxTZy1 zKof!$B^iwfe7~L#e?J|#c;F9-Z&I_gCE~ zT9cjYb0N*8UCjNM5D}kHEyJlyCM^?w$H*_VXwLC-o-Y7$B1W9qfcMDJ~HrYfGutx;ieM&0(5e3;+tIsDC6G44PCqpM0*vpkii zN@N)QwlUxp+S@J6-x>vy=Dl_M(nzW!DJm=hVNboY~N%Q1=y zc&|oRoO@xE_Nn}MxpdTT#MXO@$+}<^Y>+ojW(!U8y-ho7x|j!znSl~x(E}}HD(PUk zD6)om?_~bKf$fn(>jgpkF_TD+P&{=Ai`8m+Xx;c{n7#v zm8ja~j%V|k%*Ro!e=D0MP3vhzbxNR6E!3WQ4^!e@r4}jZd>yoY=NjBuB&tn>W`QZ< zE*T^E^;+u7$%jN?E~HS%z^+Al`_LAuzec>EEb~5x!GaD|tH`#-X;S z9x4^>V5{NMTgGR*VROZ%Ydvfi^HV02!s)I!oOLOV*eK8W?VbXQN1?>L2kt)L4c<()LcyO5}TVp!SZ z`kJ9eMRp4O82A07{PDiG%F>JNfEuU_gyAYfCKE<~<4j``GU$Os1=%Fp*t}X;aifjp z-*_V8fhI90`1|-QMfI&SVB8(7g3PJZ&2)APbQVs7yOZZ+)s&NRN)NDAT;7pjH-YCq z&qh$AJdDW{rS*(w#?Jo*s9mT$`V@2@UI&Wy<=+pWvu%VN0p0O>&EJ(ka*f z^aI8H&PB>Q(8rho+xvBG>nGj}ehXPn{YMb*mZ62wB27ayp7u;paU!RR@bTc}X%-pl zJH`qJb^2pq8*UTc2VlS3SXapc-vTK zJ}PV6AhLEN{o)>6B=yB`pQI{7aXVnR%^WNN;Xk(1_9JS1cx%7ZAXn-H_HnvudX!9$ z<=_ie>{K%XjXNz=MYH}7)&-cC)t`Z<;6xKfRohMBZ@6fT$Foyfz^dNm+?y6x=P=E% z?&)JfVdXsjNFdX@9MkV-6zfM%BO;9H!0qDD4(ImW?%oOjDxcY^6g(?)K6ZPITxvAa zv&Vu?H-mpeJ|%PZzCIW%r~@+Lbr$Zg%lP`!V^Wqj z*F;4>UU4pREt2bncs5ViXeWE7>{(Y%EE}bZ3@lcnpK@UpY{k{DIjbxYSBpa|ew{Y& zs=67(hRu`fLeMR1gnmLm@9x3R&Kd)p}-9QO;zTeR!Wm@yt`6?cd|Sy zn|BOln++)We*T}PwCd1#J)x5f6MgR!>qH^Tb=&J+>>K-#bT_G>IVzWAF!-edvsl1+ zOZPV1Z<@h^5t;F)!mM)cuVtQ3@^$*E)mS&V|Fp{3hlz>CJD^v*DuVA-2ChToB;EGl zZg6i_Vzf7x!;j!aI2NIZYOkuM;VL*Z>fegKBd}!Fx%C{Frc{Fa>`vBnLu$eQ%<(0$ zTqt3>WZsLk6jf0OF0X z-O{kc%SjClIu>4CxzcKrhR_z(F&;)32>c*;OaS(umg7ljEY{UQ@IlF<=a)xO`QdL; zyiWuUSF?A0o^yV@8%?2aUoM7~%`|#B#GMKr4QvI^9_KI^OAO_ashp=;BKSDCnJgG> zXppDmb%w|17T?~LW9z`y&xdk6E))7FL>#4h9jN|I=LAg%M=<%O62KFV*WP_XXFVF4 z{-*e%aFWr&Xx+^vBB2(1R4b=bzsFmkyk72$6*Apu&{k5Ut`q&=^L9UQCAe@qBCyTx_dMrLtAVHfyiKTAQlvwxga@xy%x;&_Coj*WGy&-Zy9hp zW-ZZO8FNjbv9)ynn~2%@z{Z6ZUWfHd;R&xsBjAUfcBr!0V`s*$q5E76l@Z-q3g}e9 zp3s~Bo3;rK9r(Gd*rfnr8$8MI;)wNJ)!QR@?Ma-rniLkN_q7BO;aD9d5r%ibT5i(< zsD}T@>`0LbnwF#zU^ITdSk%g^SfX=J|gXVhk5R zx0_{y77=X+x0m)E#01TtVbi1!tK7 zB{2_r6|lek=PjR%3*?n^7S&C$Qs~SN#|xa;k@i1hHB5BhP)!NM1E5D%_we z=fxhB`3}OCYtdphRJ=xA>ITsYRke)!?4V(JTC9KWp3lcWnq7&-G1<;T*`BJ{3G%9s zoDo^|t1dd;596@qx>bU6RFT8=L@<*@w*PctP3I9qLGSm&uN}U+vKDcC2I0*jQP{1w z2GahUGK156=jVPmf2vl&ha$A&P|e%k*tx&q^Z~iuY_KfO3}I>mli6aN;FC6Bg#r8) zwBQ+hx{sk;7kf6du`DXhIonSukE&J;gfm880Az@+LkN5VCSos`z3f!Gst@VU#T2)@ zJ*J>@64)HsdM&G?l#cESt!|5H{o63T+3fqxt{<>V{9LM;b+ml{x`=R zpF#I%;bqJDQtKJ#3_OAPzt0Yd3!LtJDU;yP6Ry^+-Nb8)=49_q2zpH)un>KKUp}os zB>Z!5YIpNZ2PdCW?YAX_3ZeIMszr+1UduEP_z0j!aYtB<#6Q2;Q;4Vna66 zOs`qMEEuP!v(CYfoc-gF@Q$KdOB`Cf3OmVh^%mJlB=$mA;XaxdT~6u1d0%{VO6H#n zV+4N~m-kqB+QT0T0NK4s*uImYofQ=wt=VDg3nhMb8c|5T-&t8<*z>b+Gxb%PqBmYW zyc*YL*;BJ|C>$DTaGTCTbUfYSaAQ&|mvJR~9)7jMuRBxmI1S@2O!wr-=d!z>&wD@v zCF1-u>O;JDXoZsFkmz5*b#M1_y{-Hkd=H{7UKwB&Lhe*iCryw$mn<~LZw&0r0ANwF z>*9yYJThfzZ67DA89U=V4qGqWcJTC0ye;gFBfixkDfT=Q1J6R4`T@f|#g>Gjb-I9KaWz`0{tDXqh1 zRr-6s@6&&~FHa_Ye#l9Zo_M=O7@L`;eLQ{Pf~a!w&jPqBvF#RILFBHie}$HFAJB$9 z{B)FU2(njz#pieh{li3Kr!BjLq#A|agNX=XKs{c&@BnV{>Nb#Cze*cIdJ0ATDbg0~ z>S^lV@BI<7G}+A28yQkxUN(p?$SXSxgZZXqT<#f&9vkFjtxCZLsQsVTJE| zBKY+98RsuySHlrk9o4MgQ@w-+vyZ~A>?`Cqj83a^Ok^Rv7u81ta_}S>i1m4T9#|`X zve84YJ;Fa(2g0e^HDIMaWX)J@C;*4-h4nMgQx2e9Skl1o#JK>hKOus#zm1xK0yRU& zgLuz_mj=j(KlzASmo`NN%3X;TI=r(^0;edz=2>QftL1b6!zCDQh1uZ0PevrBB)Yxd zay1_V&)WdfOkPUjP6Q39<#zBf(+pmW&DBpGXNDPz)K#MuzDn;~mxU#4{hgP1!7wyk z?w+*#BuHg-yJCwmvI1v`pI)i(EJkQ{%uk}h33?>PKGgw7wr;}%u$fx8k#c6-5Oa=4tg>qu$TC3Qse1(*LNg9{2p@2$km$AaoS*1tjy zRI1ePq)!U@lPj87e8?^6JUr@^o}v#ki=vpHgs3ZaJj2oV0NE%-;oGNKwO7d-4qBcJ z(2neo&k!NKQ73%i?P`_ls;e(pf~A42R^elG8}N@YwFGhW@;N z*VVfVxaUm7ZvJiOUR zDw(YHaBjT)e^0Pt#`kK3JO-~|Y3bXwk7Y12)h{!d6&l<`bL_+raSAL4hTZraXj1w# z6KHSVV%5u=z068q0bOBU{%z_Wv!6ANK?@_a`%B(1+JL@iXcy%!jr*4C;k$y51A!lT z_M?+!+|{^^st&gkCD94D+@KYEw&8r?c8)e>6^(=J<VQ%1QlGqAoe5LPG!%G7vXYRe=*c)bHZh+wvTkfI8mpW2 zXft1aOaU&>N3Ogp)ot*;ooVbwUHB}GjU+yJA~UzAd(AkWc6ie&fdE&6P|8CByE2ov z@_s1{tqfPjQt~}{$Kd6p_5FvSiOu#8ecRH59K(AC*?lrdu}IlR>YC(Oo|&olR#4;PUU@=i^qGh zXBus8qmaeXawld{@pSI~t;rWSr+%MS)bE2yOrG}2JISX&0LwKO1}fwUrmmINeM^t> zqF2gz{r<5F#vM64%BSi@v}Lsdq~)*MejA)gt?jLlnsHOP6fre~eCHFjKR1Zd2f%`z zN}BlYW^3<{ms+5ahm7NC#-mx)V$tcb${biJEO0T3=bd8UmFO(TWw^d0sC z;V}RW!+@MH>oo8djwk*iE*2;|7rChMe#tR^o)n7fXesu2nGe+(Gd&zO&mrw7*yANo zJ$j@n;UiL_q^TTDKxv#gEgI5W@3=|*h4m5w1rJg|T6ba5Up{4<`u1ir#`l)+>uhY? zYEeAGSh|{bIbXL}GfX#3Y}=}4ncHB@@nQm~;5+^RBsBe~;oc|fI&Ds^G$oT%6LD~5 zb|Lm{FCOa$KY}lRv0`)ld{Ae?Qx5LHmudZBUaQnxAF`UM%tOh9Ni%DRgAT+uacEs&VVf|E6ov_> z(DMAx*J)@N^Qp5=07uFTXtr()}cgQ1q(J~S^mfs8*#G7BfqNF|#(}Ll@ zG`G}rU>ib0wp>}|tC`VLL~9lE*PH964h`xTLKjD5A>qBPC1YuZUJ?kwbk|?r;Idv{ zsbbCEkC~*k$3jW2d%MBbZ=!WZT11c8Uj-mvgSE>rkG3|q1C%Y-6AuEbiOkg(KR&m!#paxuSo^y(aAnJQJx01zd(I^cC?Ry zRX;*vS@|L!nV+-uxALoz$Kq%C)~uJes_Vf&EQ{5t5Bjy#%NaLq2r9#`l(xU2)NE@=eZqA4_GDu9(Mu2>fNleP%_b8Lh?KJ)@MW@$ISt9ap zE)4;-ak{ZfBDWi}DK*GY6|C}${jUIv^+69GLv!`q02~LeHbNihFxEiZ4hu$k{Ovxa zpC^MDCX)C!mm8T8X+scy7oyGfWSlakdlc;fGx4DC~9G=Q3YLZsegyk+`T0?N1X zX!~|{n(bv9%j`BfNnTwyzu&6~gdCjEelFJ=W&DzNh58cqh_v^1Gjkp~(-f5&vIj8M zoQqKvm)F@8nD4bB{B&P*^d_#6&Q2ETtk{m*ywrr4)7>=xsf4Nj`N_P8jKveyZym;G z4y4)CPw?C|K1ON&Fca#wJ65%7M{7-*m@ZFQ#mee)XpG3kX2sklk`(IfDw1Im_QHzb zVVijAtlZ`k$m6WBhafvSY+|);6Oin86nXR>@1U|u?#9 z|7ufYF}&G6?#+;^?ru->_8;Bo?etph^_^{GT*!O{wgLJ%n6U#o>h49epzE(V(v%b!&L=>Of& zoU(7#z2YfgO147IhBdlE+??`Zs)P|pXYlDIhn|3Cbi8TEPag$*vi6DhhzqiynG-?S z7va5U!VwEVbiGv)`}y<#KHBG_>1RARfGhMX!)H=VF6b-a_XY)$l(A6WWlVcdjPNukh+D4xDa}o2fN9B%-tY52!0eM#Y z{>S$H0OPC=&Ek6jfgk&uaKeudp#c`rYfrMrKCb~R2mji0y)R!cXGYy%qs_6B& zD+G3^;prgSeeE*r9h+KkRg-U$N7mEWo172S&q2f7$yh!aYAm~W2qkwCFTC&}ag(Lj zF&A=LB87QN>hw!g$hY}lH=c<-sIA-p9+qVSM(!_G9WE96hg8xe7OE>VhKHV~eeLNv z_P-DuNW~$!qK{3*6%Climuy}_suJ`cncIR4Hf~0qZqSqW@o-NkV{XL*iKpJa3wHGp z?}uSQ5vc{gtN)cedygaGgvV)L3u z66WW>8z-QpO{8j%kJIgK#Tg_+#i2N6mIP&Dqex~#!PXK&i5W6noX(b*81lW6KCjL%F~M%L|NZ|LG4g$&l)GQ-d7`v zmepQ|01YmGMa2%`0LixMZyGabuja0c;7@VM7a-3MM{{NxV8Uc-_!jEejad)(-Cn}A zr)#);WiE_w^Exyuj9L-XbrDZcH&%#wbbZ|C0LSUQap2gDa|`LCB!Vx2=3SST%2M)$ zzP^U+xg(|Hcq5>Z6IPU+NwKP**hsLCJS3S-zZ}ft|Lw+QtT-CSm*@{G~EZB<29>+ij2vR$>mY9uyhe3>9i@M;<*|J}Wk`iiniyhxiS?9E_5U+cy| z;VPvEe_3i#6iwutK_(!X-qTvL`JPWKPu=bF1@9!zl`YNc?>|cZkDUO7H2KwcZM(&M zubP5e_qqA4Z%4tSaHYEYm{If^CM*9?z#Nzr;2HuWWbe>>Qa+tUMfXr*dNPN0lsen~ zD(*ndmBAu7ty-f-%fc(v5UEh>VV!cTr(ot)Pv)hhvUna9S#rM@MPZX(q&}R=JF3wn zwBrD$Q1fIU5xOcBWOnAX{B!ZJkBJn$hKlo z&+%ENgw#oYm$ue;#;+$NB!CfB#C2alh^aZ`OfLgTz3dJ1S*9r@i`3N~^!O8{$DI*M z(7XFNPOn5Qvh9=>z5E;WZ|&7LvWO#s9b!xROHyAXHTfl+{Si9Lg6|!($XESlMISwQ zttMfdK1T*v`&j^77B>XTbzVBLY-7dsCs?*fMd9w465O7Z7{k^*V~*X!8y6UJg-}}w zCbJ672)i8Cecu~^qJqyOQw&mItmh$#{x}{zf^z+`5M9&} zo43FftD*an%%3ztZVk0B&GlBjjh3g?!`tjSVYfVozt&0XI5U6yk8l5358zC@6-Y~k z1H1>ddWP>9!GX^Pc{Z7vb~erqvj1j$!dN)wUA#~qeX_O72e~u%TU17m7RwcUuvpuE zC2JsPNDb%DR;xqcVw>~gAYT6RU0{E|M7+e=5|314e5}Gs+|)eH>|h%N$f*D)Ut+Rj zH@T+N>FUEu9j}-&M1s&MYYf})G-a0y`e6A$@m~6RvHNO7@}3Rw7!tF-fE%J^2C)I` zUcB3VoG0dU(~Im6EX(*0!~v0Hyd8@PJ+`V|y0rQ$7y0-}Mug^ZrLhbxq^%vWtgyz= z$JCGOp6=jxtS`&)q1@~42EJ6nI;>S?K06=StPX$p=2!jRyzi)lN<5l`52GAqmUQp8 z#d6{1mc(fQeF=-1`U#NP5PnvdBKTa6SJXd3zB;R^CuukK$z^!U-r?C>#A5W3cdq)v zLIL z+m*OAaNkZ2)^j~UVsnnC&U`H*|AT#iX}peG@At|-fZc29)0ZmtA6~mbT$~+Lzy79X zBA0Kod68^s%HZmgQ=00MR8$a4J>KbQ)TBK|py?W1DB zu`lIV)@EYREX~7l0j|A4q9gsu(4oQ?SKjH*xxZFK3J&#B|H$J}aH{A0OW$obJG2|v z?3@3rD%vHdP6aZv)m@Wv6V43F4sqA`LhEuri-Nbh$fwncSDDMGXL(x7Rw)@b76+_^ zm;)8hz637f2DIsPdbBW5za-D^FSHHm-o{bvwnydP`pB#(1n5+T+zgn8-)cu!92jibm3{Nz5h zm`6p}djIqTA~eV-XS9K+!N#MX>ez>B3O0cgH5X%kvq_th)uJ32P55KwLy+&6-I#}@ z9TsiKK1F-t?0u&FwAn&;-EfAB`dS=y3=hir~2Una96R?YQ?1e2$r;HqWL^o z_1=*%WhdoHOIG8Sy0i%_F+d2U`pxZ3tudR;t6tRU!Zc%4csb3hvyu7(&}K)Sj)RP* zTDi=Vg3SqGOsr(*F!LRJqX4W%ybEu^gZn!}R2m2LM(6UexH)3ZJ#dQV!E?=;d}i8P z+1PvZ*Ppe0hD737h5(<*VnH<l-4SIE&L`f*GgA8aWsTqej5}1A2M&LjD7h)nZhm2LD(S>J@>cdv(58C#D#E2 zK$q1fISJAfSXb?HaoW?JYNXF(;y=D2 z?6Eda7cLys(n0=?Z!9sUYy+3O7Qki-lf8C{JzL=oePIUWWyL2lYgb-ZcF|@}l)Kw= zG*9NBs3Wd~~Y};aYk>7}1S{XHub2@&mzJ=b((Vo=bSfWry zmyaSv@#WE|_W3Sk{+$QYG^nK4=<0%9b&N1Plt4l#OuvEnSy=4~^}Rn~NkI6s`V!If zw*^;dl*X1_TJ=#C>7U@5+o#`yRPmSwBtK|9KH~6a+D8eK>0q8Y51Qnj`xixDwLM)3 z#f4Z#f7dO#<9znGC-{thSUcl;b)a_pLlP&_iPp7^^+dkzzQpW2glez!+=0EyW8C-( z)30$F=HQ2Cm!IgQlC+^n`4Ganf1IHqEbc%c{(%c9_$=(9p`QBBZvEcPuWBPGN+&)Ey` z%;YVSk5*~;-YT-mt+^m>L74+MiLTvP2Xzq9kK%#T`ILSZseQb?nWu3xO*YIc2_6;q z2GXD7x;mDo5ORRP8_BL6u?N}U9~i&v4_*|h>&x=$RbU>pf9z`gBtrCRKN{$WX8;kk zY=8JLIAd%aTpG3Oaz*J251)9#`U2^FsEy;2NDR0dmh7@Wj_F>K@j6G%<=FLubV-ut zRc|4&V>PQ~kk%rHnVQuA2o-Wye?T-K8Sn8AY`H-)DyiMEi*xJLdh`T z_Oa@Vl?>^<%t<5bN<&K7aCEXNyzjf#j<1nF`fW-bg_FI_c``~Y8h3##YcVXAV~4|I zTl3_!dbMj}boMXu?cPko++TBu|0Im1w&I~Ap!eL2HLDvZuB_Xe_l6u4F;M2aAWgCf zB$$1$U$!iDMOI^U{oHk#Es-`L{uycj>CgV_oi!>G1sSVab(;Ol2(gb$E2cegYB%em zR6%;X%VyQR=JT!h*6%p6W@Hj?If z`1Dx`XRNDzd*GEJN-eJ8Q7a@h3#yfQCX{0Xs z_-L}UO@O~!l5?%F_;da*h1il{jyLTD^d#gxw}~}DY?Mgvw|ay@qy9@egQpfLL-tFeG+ef9tfz_Zwa})5Q1A9%8iZR%D@9V8>&%+RzQXOD)EPjSno; z&2>aj1d&Lht8QC`*Y5e6AJ2?OIL@@KT_0nZR@`!bDF=F=I@$GT(?wd#ncz@v86COI zUuuc<&ARhEY7+ntZ}kn99W^lx16zzy+1Og;K{H^Jm~vK7ag_5pL63$ z>!-e&;Q-F*c^>I+A&j!7DCzZd*JqE6h}wC6FlL0tQHZ!qfZoPK0>_C<4NNK${8?rZcw zWGrP|X?K^5*sFzhcNJ}55VLYC7Tkm9b4&zeR>XdA*(}aj zceqV2oyCK_%2|n{(LDO5h`{HiHak~XQt;Osob_*GI3O4;&$It zwA2(0hJy>v4(@R%Gh?+)Vf!sn1{qb@#}DohBFQGxP5Vj) zLvK3Dp?#T*w~$0{2;1tVk@@M*Krv2{4bubiU+hx<(j$Q~K0$BA#bJV6c-|Iq)xS(g z;bUiE@Sgcg;ch^3hNMex{=kHNQ>(CLabK608c>kTt~95g?anoAj+~)Uk0Op8a5M}j zHM3jtmK?Qy#xTrl2QUMnU4b;zn7jF0JrI~Arnp#%b zOUsISEW`?b-4Co;F4=Ar+wOtW1G1s4BieK!4(V zN+$vj9FHMLio+)fV?VzJsuFoX60<(xG+B|XTwNpL;<2n;oX*JezyxZz@z)j>;BDV! zYc*Jsa$BD_{ekf*U}bABg#9-NRAk?*jGbSDa)asnKac3{ZmZ8%MpXfQsXjbZ-am#O ztnx3ZW4ou>fmpF)={^IavWEWLJNXudew$-ZNi$v%JO7uO%nx|OTcj7~C&+W5L0>57 zYu{nLF0kxlhm85J&{$1>_@wRr8VNow3hGV$XARkQx7RIR{PE8ua$L;)qZ-@*L8u#z zjYS4OPA2q#zecs&O zxl6}Pr*t$nEkX+-yD_8t_SY+6J|E|uBd2ecUoHMnL2ipUc()_pS$xNyh*rKT08~LQ z@<=L6H_cK0vsL?bxM`q>Na#?Jj!7vc{BFpOH12eI4EqF~O|$de>(lW;$h;pf-FVMs zc6&OcEXvl+b<8!(TI-?NN1K3_a(nx5)z_8;Fgf~}N`SD-czKgcm8qmj#~${=>LWZd zM#NCAniF+@dlB|si?}#ZeYp$B{$X-()!P||##CX$PPWa}wq1K^^g)i3x9|8D`HQ-} z&kw?`^V?|0$ByQx5do2k%{AW~-_uw`F56u+j0ErBiKYTCO*JQEmsG-Q1BW*Uzuk%N^p5>~W)DF-Ae)#(5&#TCf4{+~LN?0*Og zEuPrgB5@zQ!dlh{SW$vC-iHBA({{{8M4lQwS3(CYFbC0;bk1&26?$STwglOBZFGU1 zt{q=ay;__o0NPsiY=am;y^RIAIeo8lSxL$KmA)MHdUV6)EvGz~o_DjHdpoKfKSITz zywX0+6D0_T2~MMCKrYq4o_PJgVEs)Z8Nz&d$lH)x> z-`)YY-64qnq5PsBFJA)+XfXqYPf^>zUjg}5t$#_9+;w#m!(q0?{q2K5(&GOso?e6J zRDkv&;m)?;?G29GO{xN*S^L83FQi;||DVkW> zs(fCl*_}4awb=wLy=(kKx*57mr-{$DZ-;(LXL*BwEPCM;yX{}jEv6#^dY|lhY91lm zi*&b~kJUdm>o22--8|a^^-Zk1Os2=wW8$%G(i~&@yOI^W_I3d(1=aW;jT-6@dcrL> zz0~)Q4O=^zb`Ngi;oHlR+$9?7`9btW?peS%ij=svCq?zzdSFG04cfa5Zi5s*tiL$| z3Q5|r(O}fQoEg<0Q$xj+suM0@F4N5Y$AWrt0zj}FtMB4E1R{#$;}RFzXl9>ESzWRc z&$tefd=z0`dbPx`iS6JWvg=##pV7wLO3$!p{R_+pS!_?$YOa%MHu>=_J!rmVt1SL1 z@axtpd5%xzDin2dJhSZB0H}`}n>J^13CJv=zCO)IT`>0FNp&7wQS##{UNJ7+IDy3o zR$b2MY{XesmU>DK<`sbfx6QyF!E*WpzUAx`MFXo#+fXAIGYE8sGp&wJ1NFXEne37e z@*77Tc0S!SnvR*>+x{fgJX;Vsyj@YssSFWK@}N;@(6(%~?{dVyf?n;etx9)vg-WET z6VTFN0Rru~P(;cEze~>>85{aV`-zNtBJ>|)#`@~YVCp372~JD>A_~cW58m;^UwYt& zkms6??thnkGwj;#WLxaAR2q8o!ffIYqpz^xt~npf_Au+VBS8<1C}#MeL%Ht51OqFc?q=F6^Ads$^3d!Uw+X zC~HSu-2O$^x;`s=zvxwUU~YNUxUnMczRD5+&Y>+TWg%kXwysng_`x@8JBSk7Oi-I#8% zxX@3j9clym!1Pb&8P6`@!JszBrmGx}nsV;8HDZHK{hyHWAD?u0zEx36v1H5W;q9VQ z?wyk}q0Lp%UA6CSzCaBaVK{}``^)uvNcuQiCF-F8`{uC{59jtQA#l0+5gEs@f%*T` zw}YQ#f~|W{O-X`frd??FaGMa7P|yARaI}w%HcaUK&w$#Y|9d1eYBlD;SWDlBD{RDpq68t034`bq>ZNopi z6mA=>l7cM`_y}ivr+$P>N{tWz4?8et;T4Pn0I@ zQU}zr(3qb2I5RVVg43_lUvB`ln>FE&OJ-f1kUQbsmykvM{w^BJ3?KdD5qo&$hLIiN9w0o>fi2#bSt> zkzO6@?gYmZgzQ!#KQFhJzSCAB_QXhADcV-_rex47(ct%CI95c3?!fx}?>Mmb>VF)i zs}<|O_>WHaU&Yh^jst7u*eU2E@_c5G^po!z+6LDDe?#}R7mfLd1}@Wf-NRKt)D$l) zue?vS`>9U{1r!uVirjONt^a=LHma(naMdiNEWj<)w}hI?H<)n`C?8`Z$WIH<7g3uL zP4B1w-|ra1FEZ4M9I`~flch72^h?6koGoI5W}}YrTVg1Kz0V_;qO*mI&{jrA?qkxvWJXqD9aQvWoHH%#x~4gFc`-F zn(p8IZ2#wd-uJ`%@$tc2=Uj80%W)q2aa`wNLW|Hnu{aml3I_y_gMdo5@1N6 zdq4a${owS{j=7=(HuucF&G5Fz1%t1w0BXHF{%NLZJSd*>5qw~XG_RrcSqJa~x zehC$3HDq(gvj2nvlrQKlLe4O2r0}1kdK6`i?9V0p7>US^YT@-7%`0&O1|#!u0R4B= zziCy{!zVdjE4KkjY@PY@z`^kbk+!Q0NDf{bd%;m#uZ5ynq*{LboIjI_a&s1N{suH* z|1>hrU)F7`fv}=pNKaI6nu5!c>dounXoJw!hBRf+%#cZqSxN1(o=w!)%J-qAnYxSf zai8_Hp3EMwX@*?Q1q9vSySNZtHt)(sVk!RQr6!(x^%mztmfr*owjRMb=#xLI6-}O|{GHEn7wF=4)iH@kaKwVF-Ybf6$Y>kOcvbVkM&KSJWAy;3f@HQR4MDx?5Rk)zSe;w zLRM=oJc7d0V|>j#((b~pg{)83Lo4j2eTf`?pP zzi$i1!EVIBF5TSGd}rpDf5S zZnWVKKSa(6D1KexmiPJB^|oKv&;2cVoLA3I{2I{n*oi(iyC2>D`V8>s#CiDkem3y) z1e;;5xd2Lm=JsBJ0zp-=F}OeHS|dLKs1tJZFb7171Ng^}xcqQ+?R8qQm@@xHKT1wV z;?jgf@o%ozDzO5`{+iTRrGJb_2%bp4(hNNR_+QUI-BH@Ea#sWyrA(y-UfiU*a>r6m zX-D`Mnw6yZkQXmd)ulYc68WSj_HH2l#ac*vF2N&Vn%rrv`1Evfz# zz8`PcfLo`%H7WL=IQ%ZWffKj8V==Ci7Eq(lmw|P%DRtR}308c&!d0ND_`o4YM}%B; zPi`IP<;(A0o-_$Qk#I0t%-nd_%h+Y%GJ(%0hav-y-wHNZJYg+$C?mbLte5E7egD;O z@hyj|%4%=HhBXR4lW;g(6maTj*)$WLpMNQ`L}M-3s-j<~c}R8?WK{@Vpzes1Jfw

~UYzp1IAPS^`S%`FJp;-l-Z(k3VOLB@8(my}bUnx;^qR|u4Hr^RlmHhuhbPoe$eWWUz(0|bSdTd^wr3{bMEtN_=1!)7knRwOQ? zS&*gQ82JvmUv-xw$?a{~IV!$q*THret20NG0|-E2=3`J-te7I21~;Z9><$cZ+yQJ; zAUq3_f59?Wezx$UK~LB%0FkGPoGO(jBv`&S?*W3F)ASs*L4qW>Ni{z^clG%x@IWQs zt>6!fx&4);_$UBU#@}u@j0GOTwaBYDaYIDp_}6yYOW+1jv53iPW~xp;?vuJzU$wX^4e$=Q zVK8s^?ikBFf)n7=4oJ^KeQ-tQ72sQ7vAS>w^feA!;rt{Wpt>8Wa|H;{5wrAlgVOCHj!x` zv@3__vp*)u3X{Z+phEat3WxN_8rbqrI%iw5Q@jR*wDBP0A ztRK&ATyM~rvC6d>^7)yae|I}cUzK|@+06zQz`HUn!z2olqm9#*8~3wgD*G!( zUXm>a_8s>_h4Xo$zD;|NP3j29Cot#ev05a}_EF_Uk#-q#rV+&v`)4%YpCZ<#To*w@ zio=lg0j=$+b)3-G4*>SUlq5CHG<6diZ)KTNin$0clXQ@!(D1nPfBd6ScUrK2{P0F( zxU%(O`%Ho6W`Jq1Mvm&jd{#1`O55^1?=2|P?%dExqnR|)yLV+%o;;De#FfRIa#yJ< zU{Z<&D8*`K?i`FY;rPe;=;wa9*$$}1CD+S|TV6uBDxWTSKdXG^?r{0*N(}Ocyw|MHhZ8r={EgbU=&RB?hb{pC{Ua?xzd;J`qDp@R&VySj! zFf2Mt?ZwPAoV=GrS-T$;Om3NfFqb`L8j2tc>#TR;PrO4M^lcKsmU2u+k!^tkv^*DaX!UWg@NlEYC6UG2}Qme~6b{qzs-f9&p;N@yYt}%ti3yev}?CMD#Oj+5LHKCL-sjJM9AG|pR2BOi% zyGihguiLcrN88~}u`9^4FK%K8K_XUJT+7zQ$ZyAr4{q<6Nzu>wxM6mY7U&I}@^ZV? zC!ilr%n@gPQAE_u0+WZiW{!|`ntu;*y+wI%oU35nWslxqENlbA#g+EP1eduw??TPt z!CCZkv0W#)2+)M2nO7}Ut}EO?HYMH1(?9NIBkCYOL6jv<-5^o zm)ScAJ|aSosP}|OMeIdZ%k6rdD=XEGrZ*85c*}pm&xI2lWjkB4Nb$XIOYnoA;`>Fz>NW7Vkd~SCNUCmaa}t1E8yT_Ql_&c77xArO zqv&UYy}{^O;5rYu<^vrAN72_-d7;!C0@)k?Av$sEDt;?z6O1RgF;J*5!TKfOh_UZn zfjqRBA=)^)wK$N4qm4BawD6VBHEOrPA|hxd4Em}&xM1D4V*-b|Tdy(B4iol-Wd-MU z_Zn_ZPX+VPMh0nSl(-f4!0Vu0(=Y4`ezJbw)nPYeJSHi)iiU9vjz(0l3(*!qS1qJe^^bAaL4mAXR#w zI;de@HK|W!j>o+1EGJnOw?)|c*n5(zfWy}D5?wKW~?0cOB~dxUt`iTn8TLo}Zy#>4R#CyEWebiCPjvwU|r zaqFHtthKzzzpVK$l3@uV#qnsH{4HP@{hYxhU}G@smQzWAh-^8Ryg^+&*lOzY;Dq{| zwI&9X2T&7Je*H#`<;>s&Tzrh=K}24DxWo+F5PviExMpO2&+)d$KyP(|FK!~;74XTZ z^6lzTbVfH_b3CS1)<+65OsqD6t$<*D`Sv7Z;mGn{FZyn>xLf$Ww{wlp#YF z{=`RL=Fj(j28H*G2OSj|U!^oo9Y6Zx?98D@!fcwZvN5Qwb+XyA_S}E=HVUNzuIXGRmPR9~FRXe;P5B?FEm@5TI3xTAXj->ZX)^;{vgdak;QgC0>NrPI@w#2f-iXZ19K^(tm28>qM56~s zibU49T_@>PtL{6v+CM`uOkJK^-P%4kt=N`mKur3@Rp4h<2Fb`8T&07eChkI#%M-am z*JCteO0-hDk1x`MJsg9oDm|a~oWvezRW#+SR=X>54D^o9CE7AxlaCo60<~E63DDcZ zPl(1ZK!q$BoNbB8t55DpYChZd(H?riwp0nsRTO4`!X@e-OyW6Og(|u4jfJEA#xS>a(P;U7FzI5Up-m(8w{Y%MK++Iq_Yrt zof6kHzQ@gHgza8Y^8s9GrN_YJw)16sa(49s7#?r~mhjS^$7N4Bm3 zfzrk4#||V?F~hsupk;pM{hHA^)1~$NyH5HKKG=Yw0`q^mXRClsh&vV$(rAQdgMF@t zaMXn8G%M>F8m^UJjw+4xkW@8`A>SZ@K%RXr^f;H)?QbT^$J@xSfYnNAJ|en~`5$r@ zKoVF$vt!zNKdnNFP}G;t?EZSn)n<~i`h+FHV^nqK0l9X+#X>}ujED!$Nwr2CeN8{I zGfX+Kw|Gb^i0Jr>_t2;VAUWX2txPudZddPakmCkFQ%i(_-!2^&;#qT!v0yxugbGe| ze*^CyjuI9FW>{}8JMTgDYW|KKmx&*`XbB~hH~{Aysh6Z6yEa)%5Vh9Y3+FXen%JFb z`r9D&#T2)l*T>bM>D}0Z^_@LmeK3eWcY}7|bf%Q+&xlK@FiF$S`rH@nP*By3$dAJu zcy}n zUl`?MvWf2;;AiCWQMAU!vs=O_-EpJ%A#+u~kMo`-dqXaD@2LYNtRW&fI-tCm{;3^2 z*H9k{K>M$tKjLDP5gMs`(|t7FQXDEb4!rXM53Tay3Y%4|-p?y?{wj*# z_nW_LsxQk2)*87WmAtW2)A^{#6x~8<*tX2=%h3$o;jM&ALWrzU`{d)q8(08>Rnr$c zA6ZhIOfE&1Blbdb$Ed}kVWWx3Od{J5s3h^Njt1GqkZ}lUun4_L%)oGvb9@H!ySb1Wm;-$HC-= zEo-BMyI+c5L-*;67HFB&6ocZ`)CF-_7rRjL)RDT&pxPzv5`+Z9VXNFPgQxUt^Vspu zrQwxzO86MGy9QzE@`Hmuo}~R8ve=#)aZpS^R8~x7Ko`nfrR7zNob~$l5jh7NE0KJs zAr2x>HN2={T_Xr6*VoE0gCW*6e=E3rDsAQGy{~Zz7y0JOu_HAGdR2S*85G)qz2uZb z8LyvK+1{Napr9Tp1ypZ+)2y-y!=O5|#crRTo1!DOCeJ=fgDl_MxCh47C>RJY@#CC2 zlxNV9Nt%+j;3nm))i^t?F6F%s-VxY~$zCV}6Li$*KVowFMixOtRQ_L-}`RQr#5gWH}w4~j}pk;j!Z|_syyxqU($b#QQ4D0 zE`fi}K)fInDE~~CE)i$y{Tr;2>lWjXwz_jo(wC=H!Uytp3QUAG z8K86KdOaiN3JJS7pHJ!;o{ORjUdx@}UakE35>MH$>OZMJY-6}V?v@M?HHo+MtoBrR z@6?hOZho+sa=YgoJz}V?RyW7+KK^k4?Pl)i<5QS}ATy{K0&Qy#EiE)8)hMaJ^HGq+ zwI$xx`FAJ=qgS^&+D2<(fy)m4X0`(>8V@}Rs-m<0X(L-Aw7wc(;#IuZ>@&vy+Paa?;&;JQ2u?K-A&=L2vKzZ;;wNxx$Fr;iym3?$&ZD9Wc zBX_Uu9T;4Ayp@Bn@Y4|a)r2<5F{brdgKx%3?}Jsx3$R~%Kz!vxx`z6P}r^xFjgCq1hqYbv@3b%CZ=Nx zAng{Vpyky-yD#i)6EIEvtRzfNWM&0>q*EyfWVIpOH!xRX;Zqn9t$Y9q+R2oeW{oD- z_V&-kSxg#@{0Ys|1x0!8o|vhHt2;tGPPs)*5UZEvy&|uCa{9poY6}DuxC`EB0l9-$ zyev#@M&7HH50|cV1XNWh*R|ydtS=atW7U3;7qC{)Xg{es{JJ@4S@sy%Sq!m|4~3c# zZ{s7nCaSnxVf3?rzhuiA9Aps;WBGL&FvKg=Oo$fv$u5Vf7*|-BAaI*%jSQ;gA{=VF zB#Lkz1ymMbGxh;9ynXBT?-4+GP*JAW5EOdz3*c2n2@=g4yZ)X9@MZ9fu`$3%Z}t$) zq}p!Ff%1P|@b)QKH)`ZH!o}{qO=9ecdIL3#Q(IL`h+ge9-qv-+$ay3DL{b&ZJbiV&vw2fKHd1AU(z4pmtmQR+q! zgB(>h!nov0!bCW*?`B!>cevyJdZgJU9o02siBocUt{E~V)bTtfWu5=VzNyqEl>ANk z!pKD~hMY^56Bd`fn2as0{WkJE8}U^?EoHQFZ!MdZs2WkXQLRvyxkobq9F-a z{TUf>j)%`?7x`}uDX0lx&Yg=C*fWq+?H|c)xZh>r4O12B(GuT%ELq=A(yh)s^H}H- z*L@$Z+X(@otzYZF>KCV|A?K@mq5hiH)+5#EgeUu`IZ3dtSs|h_ z`)1gD5VD{WYlku+(x@{J%5HsXwk&&y`cBYRPAcf}=$#+Y^UHQg^%~z`NF^Dj%sWEZ zuvSxgi&F_|CsG7vgvwg1ObOw2)(M&|1==8fHGq1HEsDO)n<{5*cdT#A4%?}Dc&rY- z_6xFL9Nv9rRM446LluUry?8Q`uOP3USUJHcXf!(70fUyqeq4#W>XC7HVF}T<*}LM9 z)v1c=1s{r4pamtW(9Q4fOnq9=5X1A7#Z z3wbuwyw#OJVFEWzpW_d#t-9)Il`935{wf-I7Kh?#4nz(YlUFSu65Ca?DQ*G`6p+-R&9s;go>%*zgp?MAKNYD^=?QZvX{g{6WHaPb5LbV0+MN~T*&Z=F(}ePI^5o~w zz4_(RNZ{np0WVp>r^16;C;M7UH5Pg)#m1Z3iLU*q?2vEzv2P}nWXNSbfg<`p#+T5a zg6=SAu7XRE*8cl*y3sX-6)$IUylqp&eGa~P?~T11+r;(})I_XYT3v76NBG(*sbxu5 zJit^x#Gz)!rn(b|+vc;4Q%q^|` zf&pYJ=0UiWra?gj4iM@(Jz?ZtimG!ZP-1147Tns^v{=ew5_ zuGzX(_(LHHU(lzLG!q^=MlaMTegC;Qz?fjK(RhJT`=V8bxS4N#X(Q_cXii#c(dkXl;NzCG)hAbjM>X`fI|gZc1*uws)8imh~xR=JP)!okfwdGGjz9*`AJi6S*yT)Z}@HkEJ^qfp*)-oYX z`C*oQKm#aD`Zbz=VRPR3mj0)TCES+!B;-VO ztp}5&za6&s*ZwvVKjZnTgjn`5TAYYUm#Z%!KwHtp0W9UET9OUkHH0NGUt*#^SssbWTl)UTMJ$pwL2XZnA?AZU}ra?A7c1s_8tzfh&a*fDf@R)9R@I7#2yddi;CZVqQ29b1A)PCJr8~aB|;6&b@ zXuH7$=f>QSSex@Z0$U;GNm5A}it3+VB6))>TP(YlGvTk>HQWrlIMQkimnH-7IE+%F zx3bS<(w;@_IP!{(Iwr9~4P!DRWVbEF)uy3{h#D@J0nV~7uJ7&mp~Yrg4>hisw#vP` z6lPgl?`UiVD>WI}nl3ARqF+ZYK1F+1xGQqQqXv!b0PVdKdK2`xtS8*PskbTK4wAVq z&$dtHe>xv-!;>mjqkJ-0z?7jWpah_lY`VTz+b3NS#dw`iAMLGyh?z@!YBMlghXHXPpA<7zJ^-4CD+_ zN$VU*l)Rhw*cTJKJguznzp3*V%MbSv-2RWs?$}wrJ$FK z&L12Ojvw+$D4sFYGv?~>zi_UvPH3K}Moy~FIERg^d$XcwNKAqCfmK@AYzxVJr|R7$ ze0FL->z=JA+h{ihB(nU7RzT`z-OKZ347Je)ekKcfBnQ_T=jN>0{`}!GyhcxQjmoUM zBK5WurD;Zk!Q6OnoQg}Prj0je|MfEGjLi4lxZSiQNo=(V&N1atd9Pg-d@u;lNvfZ9 z&8e&u9H}o+-_q~UOrVz8&(hv?(x@ICkc#YijPd2GlE=@aE0~VI4|{Nm+-`tRh;4G; z&Xxsii16^iF7=>J2yxf0_N+4|W14k!(@$^9GP<5^*0j@9O3`Wk*W0zT;trh?$>u z5C5F~Y&KKl{0{Aw{@w3UBN{%v=BJZ8lF{(BKKeB&s`haipQmEd_#^5t;pP{jFsZ(* z+}9ju>r9G^L6t9VH3)eor3Tt5Y3ECC-8-$HX5R{X5QOX6{7WEKGZ95J2lE*ZYe)Dd zCUa}Wtf3*#!zFw@JTLeFb!f2FHd^pP+oNCuz-17-)P0FipcxFn1sV=v}9)Pmh^@@edrU!-^_1$#! zfD#-s(1z0fIiiNxz`F@$gzbx_(vh7azAKY+ApzB>)gOeV>!7MQ%tzMfGs44rC0-)0 zryOJ6PXDDUrf_oqv7{VNDeioq-3K=k44`&-wqJ0tPml#|K0&~@eC#8dc&%|jh1WO{ zC+&w9dxtKc%(V8PHglPFLWJrD=gPY#{9a_jC+2rlJfW$ZJ|7r%gW;zFD>pM6iH%m& zH#;BQ8_+e@&_~sjdH&z_Ouz-U4!t40qm`Vms5->vxT}7^+jke(W^6=mX(gkB6}L$5 z=0X~BXJYB@f=E#CnP9!82>WL0H*4=t@P;U##IR8_y#2^b2;7#Y-b{pK^H8$C1@xOu zXvQ`Dg**NbQ=KswqE%sdNT}#dJvN#R{1Y-pa9fYa#vE$bH4MahGpyt3M!kVkMQCgx z3fpyPoE`yCce+BlU86HV-6x7&t=MKLZ#GYoo=dy5X(S>uhSZ&7M~P7(pSD`o(~9#o zG_lpszH;Lj2nS4lDJsmGmZdB=i_;CK%q77uCa470aW&nhd2UtOONWlTeAl<12lRNG zpl^^_l1BtIyWXA#>(KUqpPCV(H7BT0R)v6oY+FUr4j}h{@qM@<4~j!9cgA7W2A~&G zPEGqfF9p~;V-!xJ)>YE|x^x1aK;)T5bI6yb70*2n94xqitOw&na)^>wj(o)JWnBWK zC|IlT_`)@^c!ijKA|OW^lvWp)?{GjW><0=Ehl~Q=v5+wrQZeHv1deTD8p}fLJ)1^j z;Cgp+gMs5PRxMebbATZIUs@;CC7n7fwh@BgHBW274BHX_E9%Cwwgu}%8*i)s=jxNL3L4-&jPd_jT~ZpTwzT{*|L^%Sz+0k;Y#wbQqlDzK8C2rz?3%|5n3&z3HM%ccEmchL13i!~ zALnO{hlc_+_b{h??FZFxbFxceckpl*d%^k9tAjPeDA30HR+pa-`Int91)H$f{c;&p zj~v%RFCDWdrZo3sQH94*BcDT5D#K(x%H$fP`L1N}c^;n`Y39Q1P1;jxG{9%j5AgOh z4|Z7Adtb5nH;}_RNxM>jhh+3~_c=|^pHKRbu_AYU&zB+&wzwM!bbq%$KnvGF%NOed zSR4X)+&Uj6&y~*Bi4_G#`epbE8?Ny!BISx#dI^0i4l^#wm!R0Cj9XhEWzP7dgrTx8 z`s~$QJ;f)2ZquR-CQNM;!*~LH70GIZPYzQEoPA>OOM(b|gyl9-!a;|$-X<1#A;d-> zy6#?WOTAFJ=|8BmR}*{3__B;&vHDckr7>2#>6i0Zp64BY@E7Wf;#*hQH<1OeDyu8c zls?6lMWf1P#4#uCUS}n}CPdc(&a2 z(+UAEpER;fr?{m4+J1~!WRD;EbAwL?gVxskSU!3xQfSS;A-TJzL~Al&z4=PQf+ztp zWrjE23=bIa{t~W^0gakI+-`fEirgc6=_&9EwM^e;X%gq!qc%FH&IX`!Ap#?nHJ8~5 zr|9=(wh|=f?hRB+(QoHWm`&QgCPnn$?|JsIox9CHMme-Vh@WYIU*dL|54(0HqVgL`{WGjtVk^xw<%27@s51vsj_iU++rAG| zCfnS}xSN8e*+;`nFOqc!X(*#wCHpCpzUr_YJDIh^Rarn%k3*W~XuT3^RrESX(%#Vx zo1gum3ezbt2SjuGW>;=vqp7QLt;)=t-Eg8^1zj)xnTTi=QC-D%N2tj%_lcdphA^*8 z`Ox9E378>YRSLm;+2dZ0urqrh3k798(XS|BX}YiJ>yo^~nJaBszlBi2F6a|c(PJ;C zghu8NnmFBD7H-nGlFU@MQqQF+0#Ch$a4nB&{SKh@e!4T&tsXSG4ro)RfZM1%;cEB# z2eYyw5^@gnz8>WivleR?<;^xbzb3w%eezBEu_vh9=YsL-J)T26r3F2J^MSXzsQ0Sj zCi-hqSklvuJ00N-&4pzpqDJU&so|b)t&sxNP6>^wHd8{ujS?&a>*^{A{>$&a`Ex`u zUIIBH{Gtv!)?4E2#-d>a?&$>JZSK?Be4RO_iSrQMBjk(cR}rFz1+t!S>!&xn`HRnGd0C}2*> z9nkBnXHn&$=`|4_j=iTAxqY^HxIf!yzGO8lim(y6#2(I>Ij}<~KK_d(-u@DP#BE zro=^p~HQ!STR!{)XB%UMaM@q2- zr4$Eze!TDO)!LGf=uy3EafR!a-z#FnMxEY_XT$5`Z|6#Or~>TLSw+qBPq91C^t$_U zF6ao4i^S@E??W#0j11Z6t+Xt>N6%kpQdBs=itMK>wzxH8bGS7cT(uH2w8a#})hf$y zib*yqJ7I3ho!XTQ^!DMs_7W|}{kPk%gO<4sfrLyan|AhRq|MQYy692$pMJJ|AHIB@zNTCPxUvbS|00Naq3XWLOUe*x3p%ZCMjB$y*co zi1QV4>2&>T=&^aOoqKsM><@qDGc zpMS`As2;d)L=Mc^nKh(Vu(I3E3VWw;n~9Y;blI|kR2b#b?59jK&mOPJ0_0;zX?`N% zs@5sbeNXtaUg^|<5U)^@i!d?)b%X<$ALSOnj#@N7IeBTWx+`f&S|&l9Oc!SL-p*5U zI!U-VWa2nx#U6M~aPs3buGNR^3Q7JYCM-#!w@pAVs57H8o;!3TkQl+JEzb;L&QOZU z-d<=t*B*P^dH|CgxH6Vf7>Nw-moK&J6)|}*t;7-~Wy5~bS&zwIH=Vt}E9ZjHcS-M! z778Mh01v*4_hlfGF6Ql6BIVw3)@i^aho^LQAgO5IPR$tPoWDogxmlf=6IP)PBvw4- z;;?coQ^&5;{n)GhF^>g~<>*Snb8@qW4jUpUwR0x31=g4RD_+s2zjEs_K@V8o?RO{p zhdRw0yG2bJe6VHPyMdv+os!e$xOcrkx?)+CEZ}pN2LZ_pK$4Ah@q8IdW9Ldm#r#0+ zn>(+$Z_hM4`OE{$+{yrKBvkhetY8z$-}q9PpNm*3Les`kZ$Z@2G=Av$JCEv2j}1R9 zWhRK_fTeQWe9)T*uWl?~M#buVF7`WJk02tmcsDD-fZzXz0AMPhCZDgAvVQQ-ty8p< zP2Z_rEiRe8j}?u~H`?lGE%xv~X}ZaTuO<`OTe)%PdtJ`*m5yoOtq~{9bq*yx24V!G zHq4v89)IF^GeID-t-ATP4iKWa>djqzMk$Y6x$p;bqmx%z*e>!ugbV=qt24zUk<#oxy?G74CV406)iZHanVF0dp&a|){2J^n(1EsP!?c|_ z3lSMh{VM;OaOS1}iX6wcJJkkT-@D~*oOTC1`MbNiCWi~J$XM1l3O~96KoATN(e;lK zPyDmH;U-&U;o(IM|2(OW&LO==oT~Q{=F39jl_l6dp-+ME(RxZOZ9YH}AKOKdo(MI8 z7rZ62fnk2v+|WS@R*r+}t-0QBHd#Ssufg#ES6vndW_lY40HLgVm%e?=_6XIsp(p2W z?^X{p_j(8jDDY>#`Kj168zyFZ6o7LuU_<>|gaV|4{f_~Q|I&P1KN-6c4a99!fi(be z8`99I!QUeSt*Bf8*1+fQXh_~q_W)~n!;cHV7tHW=d%$gmYlFS460oy6t^eZ?vMynH z5}=@z-vN{Qx$1Ch=C(8Q9RJf0|35UJ+|zizB4Z3p`Uez1HY4`xmcJu7|DHe!jPjo& z%xx2)VZv=d3g)m7s7dd4FiWb3=;sJmAHMLfFF<*2|1sG0-!+}zh{UZ30--lhUL;^b zyb*a`&Rnhz*KfG~D_Znlfd9MMCNJEzb?M)x>{aOr^by7QcgX)=VEN^U|2yWS%?y#Y zwV+~Go&XW3->v_$w*R)-zH!@2?sq8b0N}3j+9&OpTM;D!;3Ghmor2ZjH-P;SVSf3` z@%1qzyYi7X^8YoTC-)jp;TnKraX|}UfZkM0neP)Uoc|womE2ic9p3uSOxs$-xglI0 ze?(3E4}0_9&L0@^@96OFrC$e-m-ZX|Xzz@+wU~$oa9-dy{}JywzPl@BS~&LA0py{> zTy+$XrhB}c*%N>#z{h_^iGP~-1YIxiPo96!f-hkdZTJsp{=cGb2D=gq#|SXIiV)$m z#R)U`T~Ah>QV~O9=QG#m%8G3#l4xl?g_cq0TNd^5-TLRm>JEc$rz;ildmM=p7Ni3~ zUC`7vGv&FL!qbawhKr^Gxz+lmtU8|S(hSNiqJK&A*yA#a5z%Vk4N#FJ2uS}sIKmIA YfB*XM_lT#x%(dz3n%t console (primary mavlink, usually USB) + - SERIAL1 -> USART2 (telem1, DMA-enabled) + - SERIAL2 -> USART3 (Telem2, DMA-enabled) + - SERIAL3 -> UART4 (GPS1) + - SERIAL4 -> UART8 (GPS2, DMA-enabled) + - SERIAL5 -> UART7 (USER) + +Connector pin assignments +========================= + +TELEM1, TELEM2 ports +-------------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4GNDGND
+ +I2C1, I2C2 ports +---------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2SCL+3.3V
3SDA+3.3V
4GNDGND
+ +CAN1, CAN2 ports +---------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2CAN_H+12V
3CAN_L+12V
4GNDGND
+ +Safety port +---------------------- + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2LED+5V
3SAFKEY+5V
+ +GPS1/I2C1, GPS2/I2C2 ports +-------------------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2TX+3.3V
3RX+3.3V
4SCL+3.3V
5SDA+3.3V
6GNDGND
+ +Serial5 port +------------ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+5V
2TX (OUT)+3.3V
3RX (IN)+3.3V
4GNDGND
+ +Power1, Power2 ports +-------------------- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
PINSIGNALVOLT
1VCC+5V
2VCC+5V
3CURRENT+3.3V
4VOLTAGE+3.3V
5GNDGND
6GNDGND
+ +DSM port +-------- + + + + + + + + + + + + + + + + + + + + + + + + +
PinSignalVolt
1VCC+3.3V
2RX+3.3V
3GNDGND
+ +RC Input +-------- + +All compatible RC protocols can be decoded by attaching the Receiver's output to the SBUS input pin next to the Servo/Output VCC input connector. Note that some protocols such as CRSF or FPort including telemetry, require connection to, and setup of, one of the UARTs instead of this pin. + +PWM Output +---------- + +The PixPilot-V3 supports up to 14 PWM outputs. First first 8 outputs (labelled S1 to S8) are controlled by a dedicated STM32F103 IO controller. These 8 +outputs support all PWM output formats, but not DShot. + +The remaining 6 outputs (labelled AUX1 to AUX6) are the "auxiliary" +outputs. These are directly attached to the STM32F427 and support all +PWM protocols as well as DShot. + +All 14 PWM outputs have GND on the top row, 5V on the middle row and +signal on the bottom row. + +The 8 main PWM outputs are in 3 groups: + + - PWM 1 and 2 in group1 + - PWM 3 and 4 in group2 + - PWM 5, 6, 7 and 8 in group3 + +The 6 auxiliary PWM outputs are in 2 groups: + + - PWM 1, 2, 3 and 4 in group1 + - PWM 5 and 6 in group2 + +Channels within the same group need to use the same output rate. If +any channel in a group uses DShot then all channels in the group need +to use DShot. + +Battery Monitor Settings +======================== + +These should already be set by default. However, if lost or changed: + +Enable Battery monitor with these parameter settings : + +:ref:`BATT_MONITOR` =4 + +Then reboot. + +:ref:`BATT_VOLT_PIN` 2 + +:ref:`BATT_CURR_PIN` 3 + +:ref:`BATT_VOLT_MULT` 18.0 + +:ref:`BATT_AMP_PERVLT` 24.0 + +:ref:`BATT2_VOLT_PIN` 14 + +:ref:`BATT2_CURR_PIN` 13 + +:ref:`BATT2_VOLT_MULT` 18.0 + +:ref:`BATT2_AMP_PERVLT` 24.0 + +DroneCAN capability +=================== +There are 2 CAN ports which allow connecting two independant CAN bus outputs. Each of these can have multiple CAN peripheral devices connected. + +Where to Buy +============ + +`makeflyeasy `_ + + +[copywiki destination="plane,copter,rover,blimp"] diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat new file mode 100644 index 00000000000000..f0486e5b9ca53b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat @@ -0,0 +1,71 @@ +# MCU class and specific type +MCU STM32F4xx STM32F427xx + +# board ID for firmware load +APJ_BOARD_ID 1140 + +# crystal frequency +OSCILLATOR_HZ 24000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +# flash size +FLASH_SIZE_KB 2048 + +# location of application code +FLASH_BOOTLOADER_LOAD_KB 16 + +# bootloader loads at start of flash +FLASH_RESERVE_START_KB 0 + +# baudrate to run bootloader at on uarts +define BOOTLOADER_BAUDRATE 115200 + +# uarts and USB to run bootloader protocol on +SERIAL_ORDER OTG1 USART2 USART3 UART7 + +# this is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN +PA9 VBUS INPUT OPENDRAIN + +# now we define the pins that USB is connected on +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +# these are the pins for SWD debugging with a STlinkv2 or black-magic probe +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# Another USART, this one for telem1 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 +PD3 USART2_CTS USART2 +PD4 USART2_RTS USART2 + +# the telem2 USART, also with RTS/CTS available +# USART3 serial3 telem2 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 +PD11 USART3_CTS USART3 +PD12 USART3_RTS USART3 + +# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters) +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +# define a LED +PE12 LED_BOOTLOADER OUTPUT +define HAL_LED_ON 1 + +# we need to tell HAL_ChibiOS/Storage.cpp how much storage is +# available (in bytes) +define HAL_STORAGE_SIZE 16384 + +# Add CS pins to ensure they are high in bootloader +PC14 BARO_EXT_CS CS +PE4 42688_EXT_CS CS +PC2 42688_CS CS +PD7 BARO_CS CS +PC1 MAG_CS CS +PB1 SDCARD_CS CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat new file mode 100644 index 00000000000000..8bec6df8eea62c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat @@ -0,0 +1,227 @@ +# MCU class and specific type +MCU STM32F4xx STM32F427xx + +# board ID for firmware load +APJ_BOARD_ID 1140 + +# crystal frequency +OSCILLATOR_HZ 24000000 + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +# flash size +FLASH_SIZE_KB 2048 + +env OPTIMIZE -O2 + +# serial port for stdout, disabled so console is on USB +#STDOUT_SERIAL SD7 +#STDOUT_BAUDRATE 57600 + +# order of I2C buses +I2C_ORDER I2C1 I2C2 + +# now the UART order. These map to the hal.uartA to hal.uartF +# objects. If you use a shorter list then HAL_Empty::UARTDriver +# objects are substituted for later UARTs, or you can leave a gap by +# listing one or more of the uarts as EMPTY +# 1) SERIAL0: console (primary mavlink, usually USB) +# 2) SERIAL3: primary GPS +# 3) SERIAL1: telem1 +# 4) SERIAL2: telem2 +# 5) SERIAL4: GPS2 +# 6) SERIAL5: extra UART (usually RTOS debug console) + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 + +# UART for IOMCU +IOMCU_UART USART6 + +# UART4 is GPS +PA0 UART4_TX UART4 NODMA +PA1 UART4_RX UART4 NODMA +PA2 BATT_VOLTAGE_SENS ADC1 +PA3 BATT_CURRENT_SENS ADC1 +PA4 VDD_5V_SENS ADC1 SCALE(2) + +# SPI1 is sensors bus +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 + +PA9 VBUS INPUT + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# PWM output for buzzer +PA15 TIM2_CH1 TIM2 GPIO(77) ALARM + +PB2 BOOT1 INPUT + +PB8 I2C1_SCL I2C1 +PB9 I2C1_SDA I2C1 + +PB10 I2C2_SCL I2C2 +PB11 I2C2_SDA I2C2 + + +# SPI2 is FRAM +PB13 SPI2_SCK SPI2 +PB14 SPI2_MISO SPI2 +PB15 SPI2_MOSI SPI2 + +PB12 CAN2_RX CAN2 +PB6 CAN2_TX CAN2 + + +PC0 VBUS_nVALID INPUT PULLUP +PC3 AUX_POWER ADC1 SCALE(1) +PC4 AUX_ADC2 ADC1 SCALE(1) + +# USART6 to IO +PC6 USART6_TX USART6 +PC7 USART6_RX USART6 + + +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 + +# USART2 serial2 telem1 +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# USART3 serial3 telem2 +PD8 USART3_TX USART3 +PD9 USART3_RX USART3 + +PD10 FRAM_CS CS + + +PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) +PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) + + +# UART8 serial4 FrSky +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 +# allow this uart to be inverted for transmit under user control +# the polarity is the value to use on the GPIO to change the polarity +# to the opposite of the default +PA10 UART8_TXINV OUTPUT HIGH GPIO(78) POL(0) + +PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH + + +# Now setup SPI bus4. +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# start peripheral power off, then enable after init +# this prevents a problem with radios that use RTS for +# bootloader hold + +PE10 VDD_5V_HIPOWER_nOC INPUT PULLUP +PE15 VDD_5V_PERIPH_nOC INPUT PULLUP + +# UART7 is debug +PE7 UART7_RX UART7 NODMA +PE8 UART7_TX UART7 NODMA + +# SPI1 CS pins +PE4 42688_EXT_CS CS +PC14 BARO_EXT_CS CS +PC2 42688_CS CS +PD7 BARO_CS CS +PC1 MAG_CS CS + +PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) +PE13 TIM1_CH3 TIM1 PWM(2) GPIO(51) +PE14 TIM1_CH4 TIM1 PWM(1) GPIO(50) + +# Power flag pins: these tell the MCU the status of the various power +# supplies that are available. The pin names need to exactly match the +# names used in AnalogIn.cpp. +PB5 VDD_BRICK_nVALID INPUT PULLUP +PG5 VDD_BRICK2_nVALID INPUT PULLUP + +PA8 LED_RED OUTPUT OPENDRAIN GPIO(11) HIGH +PB1 LED_GREEN OUTPUT OPENDRAIN GPIO(12) HIGH +PC15 LED_BLUE OUTPUT OPENDRAIN GPIO(13) HIGH +define HAL_GPIO_LED_ON 0 +define HAL_GPIO_LED_OFF 1 + +define HAL_GPIO_A_LED_PIN 11 +define HAL_GPIO_B_LED_PIN 12 +define HAL_GPIO_C_LED_PIN 13 + +define HAL_HAVE_PIXRACER_LED + +# SPI device table +SPIDEV BMP388 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ +SPIDEV BMP388_ext SPI4 DEVID2 BARO_EXT_CS MODE3 20*MHZ 20*MHZ +SPIDEV ICM42688_ext SPI4 DEVID5 42688_EXT_CS MODE3 2*MHZ 4*MHZ +SPIDEV ICM42688 SPI1 DEVID6 42688_CS MODE3 2*MHZ 4*MHZ +SPIDEV ramtron SPI2 DEVID10 FRAM_CS MODE3 8*MHZ 8*MHZ + + +define HAL_DEFAULT_INS_FAST_SAMPLE 3 + +IMU Invensensev3 SPI:ICM42688 ROTATION_NONE +IMU Invensensev3 SPI:ICM42688_ext ROTATION_NONE + + +BARO BMP388 SPI:BMP388 +BARO BMP388 SPI:BMP388_ext + + +#COMPASS IST8310 I2C:0:0x0E false ROTATION_ROLL_180_YAW_270 +define HAL_PROBE_EXTERNAL_I2C_COMPASSES +define HAL_I2C_INTERNAL_MASK 0 + + +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" + +define HAL_STORAGE_SIZE 16384 +define HAL_WITH_RAMTRON 1 + +# enable FAT filesystem support (needs a microSD defined via SDIO) +define HAL_OS_FATFS_IO 1 + +PC8 SDIO_D0 SDIO +PC9 SDIO_D1 SDIO +PC10 SDIO_D2 SDIO +PC11 SDIO_D3 SDIO +PC12 SDIO_CK SDIO +PD2 SDIO_CMD SDIO + +# battery setup +define HAL_BATT_VOLT_PIN 2 +define HAL_BATT_CURR_PIN 3 +define HAL_BATT_VOLT_SCALE 18 +define HAL_BATT_CURR_SCALE 24 + +define HAL_BATT2_VOLT_PIN 14 +define HAL_BATT2_CURR_PIN 13 +define HAL_BATT2_VOLT_SCALE 18.0 +define HAL_BATT2_CURR_SCALE 24.0 + +PB4 PWM_VOLT_SEL OUTPUT HIGH GPIO(3) +define HAL_GPIO_PWM_VOLT_PIN 3 +define HAL_GPIO_PWM_VOLT_3v3 1 + + + +# We can't share the IO UART (USART6). +DMA_NOSHARE USART6_TX USART6_RX ADC1 +DMA_PRIORITY USART6* + +ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_lowpolh.bin From 63c198199bdea2a6292bb3eba5a548cbb5220dfd Mon Sep 17 00:00:00 2001 From: Cedric0489 <1406012633@qq.com> Date: Tue, 7 Nov 2023 06:32:59 -0600 Subject: [PATCH 122/499] Tools: added PixPilot-C3 --- Tools/AP_Bootloader/board_types.txt | 1 + Tools/bootloaders/PixPilot-C3_bl.bin | Bin 0 -> 16120 bytes 2 files changed, 1 insertion(+) create mode 100644 Tools/bootloaders/PixPilot-C3_bl.bin diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index ac08818115171a..80214304e8b671 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -252,6 +252,7 @@ AP_HW_SPEEDYBEEF4V4 1136 AP_HW_FlywooF405Pro 1137 AP_HW_TMOTORH7 1138 AP_HW_MICOAIR405 1139 +AP_HW_PixPilot-C3 1140 AP_HW_YJUAV_A6SE_H743 1141 AP_HW_ESP32_PERIPH 1205 diff --git a/Tools/bootloaders/PixPilot-C3_bl.bin b/Tools/bootloaders/PixPilot-C3_bl.bin new file mode 100644 index 0000000000000000000000000000000000000000..d66cce48dadbfc3aa04f4f947aac519ed633e5fa GIT binary patch literal 16120 zcmbt*4O~>m)%VQ3ciH7bU076DP?udy(A5ONL?X5>yLkCn4MvjIVA|}0N$#TP#@MGM zO)H3L{b-+Huq}b6wURb5d16FE-%vx=NYd~2-Brnh+BP=EY>=kC$m(7`_x;b^#hA3u z=L^5tIWu$S%*;7wX3m_MO9W#23njWGGl=dEggvqNONcKa|K@P`)=#HzF8eGzP(XAu z?;^S)ggS(05k8CaU!~vqU(}hRnVd{?^AQ#=|L?Usap!*zZ;JjuiyLqI-_y7Yef?)N z|9|tii$o^MWN_Qh?ka5<*6l99Z#;hQzOK9H4_67*xolSn`5nUD*OxvT&G8LaJnb9a z`ZOy!c~wTq?ilV=NrgOTQ^)EHjp8INR)>_uYe1JAx7KKD;9sO z-}{!5Ll`Ug~*#Gh-?|p5h2MDBEO_y{PRB! zYQ(`H@v$*cqCKkXBJ$H?2Zv1jdi(k!U5~b_=xPejWziR3QG{F~e>}z?{gNV##g*+> zvUBr0iA7i22uNop^6WRL$y-8vrJ%KVK&dd_ohp7$$u?=l-Qvy@?y@bg93)c~piRO8Y) zGwSoZYa~lIXCm^h@jOe7OW#9$OF{Q10@2kkASN&1Z0G!PeOIQKF3}}Lej&fbJ`$*w z4%rLOn4IkrKSXNyYYmPzd;V$Yl>9Ga8BWfW<|Xny<3^`(Gcg-Crf)GmoWAA$%~c!k z-%|B()s`xcU2fp2+*KZPEH)yCtTVce$YF7YXWP#zjPC8%K0+A>6Jdx^%=-p%>}P z@kDo6M|5t)dk|hlVC8Sc;$;a$*BPs~12AWbgugpUa%^(yPSV~Dz0>*TVuqyTb6Fbb zbSiYZY4mUqI)KrqjPi47%aseP))SLEMUwM@pSG``E98)?*Bjsah{*gjyJ#~)(fdTKV!AI}e5h2&x*pt!-(mGv4rb10bM2d>!X29CDE8f>ix!6hmxE-{>wdEM zXMWa>I4PhVaG{Z!D%TKs^C)M^L0?M8KsWxu(LJMULFLiWIMLO~peIM;hiE*>84Ao7 ze=Nqau^3u|)WVspsAU;jCPI?AC+ymD1;8#DrMWiwxkh2xaB#Vk+{lj2p{?e7-eubciIJyjtIAlzG7>Z*N2k zri4K)-(n|M>l%N4tzicl_B7t=q%DV5P5)Drmzzf*<2JJJE7VGtejNN2 z#{9d9=$I=S=iQ#%|H~m0w{BI!%eTrr$?>fdXO_`t(u#?EVU)I|lt!|MJU&`+q0@HZ7|nY?vE&L1o312hg#rmfLc+P=T9NK2^6nA(tfu)=&;T9LCGj$yzCrgU zbWrPWlIt8zp#r`s#5uOis&bFm9b~%Ds4!iKT)+PabYaGh(0xaux}bwD zth|1=+S;GS8GlQUfOiR}ichUt8T!=`8#IoBqNbV6n%^k8Awf5!&bmnW9Th(p@;IwP z-#fy1pXAq>6Alyf^qiWz??`l=BJ#D7Nci~poKh-hjv0=syDM~8e}w7ov?GjDnintj7E`?rcz`68MBA*$d?O#yWt&Yorxb;Ier$4;B zNc`Y3n`Ns%oG+GtSP%U=_)SU{4}=}i@yAH^th;Abd`HpR$QXa^dn3eDnfc)8E`|CJ z*$sg&D%pgWsQHXyYMwTvrB?A*B{WAHNOV4@Xi1Yo8hF6>D#V`aA6UzNNhCCg@!{^Zd( zsrYZANz8r2g?)VrkMY3UMdice@ps3s$@P-#94WuP$*wy`&VRcmg&U_}AwC3GlzGWa-WC;eVESH1#TP_9lqUPeF`Mc~h zz4TmjW~J9=WISd4y%#b|MM!a0?M6T7Ub{g|^7+OKN5rmLiAmk+)HPfQ<~{wiIwR?jM(efR7& zGb@PvjqxneP)g*Vj%Q1$rPXyUn=B#pr-sU!5tFDdBl3?XSgu3OtqA=kKi?%}--mO< z>u6^Q)~TK`x*}DM2%&(|vv~#49ax6>fwtHjvDs&k?Z_+WN<>c*F;mQI6JUJ{Vv;}J zNwU(!RC6T!d_-_jF-K(DN#yUIDCn7*J5#hKgE&=mwIBWaaD1a=mawC3jQo9A)5JU5 zHnr78|J!SU^)b2lX}q;6o^TUhTdj)e`$yd6F`8BXNYkPzPZw#v-g;_)By&SLP64-x z?*|wsCpn~K2X*nCX(h-bT=^NvA)n;WxR5F)woj!?Ka;K}%(g7@D-Uc8OZn1yjUYaE zY+7H`j;sigM}^!-_z#h-p@zruT~P}%S|(sem?_`RFAuPjQbF9zz6EiHSUq8=fDpN2 zl;o^AugfyciG*K?R9xTjSfOn=M&pUNS$&)0Qe*gM2Mm@rdqTjn+0l8cY}2k3^r*Em zDH7fv3CC)jRW@dykqVDvWh~Nr(n_pagMX&1n~~%rSq)hqX-j=YvWdQ=#x}Z%#i52r zZIIN~$SZM=Nt(U`iYwJ5rbEKVM(>bbIrgKV*Y$sbpw~!P% zi7A@rjpdb}*mc`f-ovpx+ljyCv2)7w)ziyOB7x;|-{>^w+sXq=lU7fQ<*Xh}RC5wn zCzg{eV9Acr1T_cq%*WdK6MQaAPK^G?42Fyt-3bOmJ_TLN*YHo01!=x%BDD(QNoC`` z`oNveR(o;a4xB>lA(Cg@XxyU44`*yi%(?|Tf30#>c_90?GOM)LUU8+8@P2x&!M)dB z9#~jLi@Qby(m6IfOmg1zS!6BYWi9WxV&f0*ZgCCncE~o~;I{5@$ds>i7lnjMhr9^- zL_-JfAr^zH^IF4JgH$Oc`F2<$mR*W#X+h5{^k;^DCVo!^^sHBMgI(8C+m+3_Ip9l)GrJYi=ZqNg^}Lp6*qj2{huZs5p}%fVlBJL2iD zk71uQP@H4u@ohFod^_P|WxYy6mJzzIbj=iZN^zc-?1^Hdr@;4=^e@IP%>2aDX*jJ$ z!c7w$9&2%jyF=QL(c#Jwm7b(?X<{Bq{$=9TjK4_B#oXdZ*gJ7aDl8rhM(cQx!g+u+ zNiFs;=nEpF>mLwYcY=1}X-4;p6E&b)1G+gPqs$+bd#0VsgM}Fhmrc-TFG{awEEku6 zwq2z?5M;Gh0RAAT?@A~p*}ZPAeV6Ox0Q@imn&h`!oSU!K_vpI(1Dd=RI}PlVc6RTS zXx>g&Ri@pY?nV1~ZT4(mujFtuE!;H;P3>W}33gEI{U(bbPRIE&dG}AGpLBLehdi{f z!&RBt;htG<_FzBsU6MN7mpqA`Cb1R!Ow{+Gy|@In1d-R^Jof(ir%>D516!(s(VC6( zqF>2uu8>U$dr<=WD{-dyQ0GFC)ro|QBE0D8E>i0+M*Sgwlxls3YDGQGPIl19W)rir z+V_FN$HuwEjM5*2(J}YBlZ#3FPL&H3<7e^|#A)IzF}nV|AiaQ*uyNFQsxqtHbG&C` zT(~6Fd@>gJr;>M1jpQR(%d~M$N%@qPsaZWTK%7l|Fi3PDpp{Jj}XW+pTVC4T!6ScmdD`ZfLU35G;axm`50bJ zG%t_geF-qL8?fi~EQ9_|FXvpuYzLP)Gc^k$w>?oL&1C2SinV_mqw=#!a=;^eWzIhX|U>3r^%8BWc1$f23GkfB}N0+D== z(O^`4nMHJolF7UidY~vvP0l%iX3q=uK86yfngO zHvg+zWlC{I8{eheyOy=e(ouWqepvIEMOlK#Y=z7Su~@zetlX#$z;iI4^}c?b)tdiR zDwj-{<}fN0)HM;4YIQ}z>wL{haV{^rc#~BdXjWF4vKCgzgy;L`EsX1Dyf-f#3!EI7 zp3h(8%Xijj&8KSkjm(1ytIr{rQ(wxGib)dr?uv| z!n7KOOBWezDP+0Qun$c}XAhMJ#@Gt`^O*m$pohth$VYwD!h4D3 z)xFh@YQDx>Qh;?cItDWTpEztW7ddkJ?CB1#Z)n^Q*S01 z>+I2ko+&tabct#sdu>#%e4UV;5+~D?omf9k4hZI*ZYrOBU49L`6H4}cAkq2Hd%k1) zoMTm^1^Ru+RpXN1pz_~QFN&j8aW<+rnor?)y4jw^!NV?yychEVJr?eJXX8`u24(45 zB6mh=qzuW@$++C}k=F*Rw}-25P}Z6plE%z=GvF;2vZA(dvzi;t)5P+;UCqkUT&C&7 z0*bjz5+>-w_mvu{T{_-<0D5SUU79=m1oj%0FONp!e;;M-8am^U+gcI_yJu;xw@2ME z;dgvZDbIa>Q=5Ia?^4Zyk>cFTn}`*=Bj0e9ZzPN1lWB-IqlSs?tt9L0z;p|f;^UYt zEa!ai05qPLcfbncEVip0_IV<|(~#AVlj@FA|FnK;UFqlGk!@)p)??6~)!d;P&isCj zW#e1HZvrD-f)QP-Em7JlIsvP8@ zeZ+!V`9BB>Llt~S4Fz3Gy^t(x>p?p@2v`eX2o25#Z@tn0!tbg_+H&*~9 zCL3aX*Uzc6PosaOxpU%pc?LC!34KIvi_jdw&%wWx`l{907PLBBai7!}8CFL^FcRIX ztd0RSj{A*qCXwr-^4Q2LK`Q@k3tlM^2%-pK!?*5=7eu!jlGt_s%mafE`H-V*EQ{c(lokIh)P zw10**um8P|czM~9B|3B7lGxv}W$$b{3VnReo_e}h%GldAHhh&IOS!MEJIdE+E0OSW zwPy*cCQrYZs>ZRE!eSKD)!xs#vCiyOsED^}n7nfmD$XIcjWiR#?Exi^vU`>{KW^TA%MjT<2E zzQ9zk*lhemkaH4q?*Pefb9qbdg&%-mm)ps_RMNB3e*4(zDv5X5U3%C0Sh)`N3!8uZ zlRWw;Sf}}|-7Kx^ad>dM<6^dh!;SqK^Ym)akGmR!tI7pG+^6aGf0nMsneNeTPm?&w z=&E$3xv@5HpA7%1oAoKT%bA(D=37SvQSY~U63Qt&tndOtQ$C0Y?U)@%Ye%e}^&Tzu zBluGzN|4oypT~3{X-$#a>S>hPFdnRr{ZadApDzvdcSopYk(-K^?a^IzGW>Km@v*uB ze03R~W~^_m_5<)nv3--}>$`NgKQnoZlG$~yi<&KNO87BI9i&{O1UPwGaun##TROU&C+V%^0nMimTwvw(3JyIp5L;06u z^>jUDopDY(MwSMt7+emQfYJ&dJNZP%$78&4ext;>*1GO@Gag-kGivKF%hV+8vXekT z4=-6<54cuA&cVr0P~+r>Qn}s%jTv;7Fn!XdppM!nr3*W##aLl7t8Z^+?i1sA38lbA9`X6HUg?-G9I>~n?Wji7iS%$P*8Wz7zBm~UPB=0*kaq^iQew7vc}tD= z7su$!+)}+5IQFl0VTcoGzY(^q0sccl;W7n&t0DWg{8fyP+G+H})FCN9!BEMnuYA~8&o}llK z4hFL^hEfF92Ag;A>69&m#jPXEFQpm!4JQogNqku(yf>n`_M2@2G(D~?Iv*Q-#P`4o zoWj8i0W_u~q$7A?i|L?wli})#UmSyVv6Qb*?1s0yCl9;DWY~eT;&6bPu7m&VPF^D> zA$RqJwd@zia-hBMMRc9Qo!5`$l(AGlQhKCnZkyKsp7QNxgoE!X2O1ELW>wr)FLvMJ zWjE?kOG&Aq@>3_~-?k{AHJ8DXn+zvStnDs@?te|HaTV^dG@f{(W1IGl#HD`;>dg13 z7-QovcF%Ag%1p11kLU7|6`h__giIzK*w1vss%Q?M`L{sYQr#Wz1R<|Y^p3ZJa%{W` zV*L}5dBW%5*Fnr)k}!Yd1%CW2(-*RWv+26xaf|R+cO)!Fv`(XkEcE%}%Bx)5(C)k{ z7gnZFL$%SR>-qWTv7Q6pLLXVBgFiQ;z6EvOjlieGZrJU(VVB@jT4#*bQDdY(Rd;rd z+%>B|X?0SWrT%N(No%HyX%@_;YWS1CCMtpzwz(YPmlt0TP}mgrC?>dKMJ2Za~e1g&Rq8nk|Pjvi8_=dhY$wf;kd-N$6-rWKzuCU#R(D3}6IjT{gPAyXf# zGdqV_c)GXO>r(J;Yc_!!b?B24`6>|b*-p-O9ZcPf(+l{wgBJa zPTXy6h+>B(7w=x8aD}fNd)eOWx2Sb2?hoK|`z3g$`U07rltJqCIh`4h`sGQAw+p%+ zVjcH0pRLXt3154Y_?V99ySU;w=jmh3SljhI#hK(7lNWo7bn#dS^w#DO+YD!JSLW7i zL3=iHYjKEd&wNCUi!&cdzWcj}Q`VbE@%dEd47DkQyE(Ie>M0cQY4&?WxubcIX}Z!4Jvxjl27 z{9prz+X=^MCF$gs>i(#}eV=(+As01+ad&D4ZE5#NkFH8M)2A#gpk{6quPLq&@{Y1p z2cLe^8;ag`WRUV5c%@_!`<1k^=Z_s9+%-e)KOj9nB*fpZ2s@U!o*#_Y&MOvf5BFyl zCl()ot#&qO0^j#gcAEgdqo+M?{A>!A0qISBmu5Ay(ws_#e9%$z5a;Z82zHB);r{^h z&D+J-Q!CEUfrZZEx>kEeV1cu06a3&@RZUf$8b4H3_u2PB)3Y3=4W7yHGvjlemt1pk zGe8P(DpJVjPg*RlEp-*4wU&;Wd=E7JJhkMzag!;VC-XfQw9$TL0%m38mY>3hjrS>$ zP14(nUb=waRD?{)*`46*aD)5#%qPu!`W-HBPn?s@1=e>qzig?*#uF1qR^*=4At+tN zb$GFXvlKg{9id~MNBQCXo`3b_ z-yJv9@P)W*L?jEA`@gtX7+O!u=rYIFwS7uvTB73}=&Ci1;4POvz0yN(b@W>Pn}hp&dMgc^2WG=-@? zhunaBC{l?r6`~{s(k^t!f&-E+WPUq#kD0w@OI_Tc%^-+p6y4XbqI|7Do6z?zbShmN z*QXiW#b=2Z*u9L@S~9Agr>AcizpLROM zh*M>DbgfM+WqjTn*@bnJ-5%m>H!57+w8wIV<2N<_7N^o-f0oFVqO2$l>$p0{z!xw0 z;;7r~xkdWWRZhQf!U*p$F`ZKM@eAQe<2kx80pmu$b^M?`RgZCFro^ZEY;wa|n@rY1 z|Km}@#vN~y1sld4e+H`^Tl?q`b@VDr)4V<4`EB62$>cIgx9#1P&NzNOWV`aVjnOa` z|02llQRbGes?!V>8_=2uT=EQQXZQ7C_MO)n`UtpmPI7wYVeH?xr=32XL2fm=9&|-V z&&J*wVRtC`ajeeL9BS!+H$K_V>=4Bk30r!i9N|@t@QwSxk&nQU){@IXcBWzcVD~8B zTm5j|S3Ji(b8It14eP(+)`G%hn445@h$>)Xzd;tKoPQT9;kQeFq@C+y5Yw7pAbwX7 z3fR8*3&gNvCv!Ah-_Fv>@Yuv*Aqi5|6&U2W8N-q#fTd6 zI*NM*b(9@-?b3sz-x_&#)ynH%e-$tO2FsugWC0hlnOR@W&_uF;ES!6u#df)w?b!>W zd1Dt`b!E_l&EsZpBwpo+1svJKeAeJdnaYt;V9Xh(%YGf)uhsdmel=(pw)*fgWFI#~ zxmI7rm9(73AeRqbaEuG%L7cEcZceC@|B=aTbe0;v32Q3kH@7pV#!aZ-V z%b`+q#3(x4#Dd#_P0`mPUf7S(`@3(}ejax9ZzCG`{=bRYor5!JNA3HyIO}cbsK%R~ zGt3s~i+NuD4*KkTI&~KePj~zt)FSg=63;3*M^E5>H$K4be|m2JUI2?SD7I z?udKr{ij)LzYgY#RpLbWhZ7yO8;ZYN+)@3d;$RT=|CF4vASVO66G_PDAuXZ(?N77pQg-ss4zbCgG7hkBY=q^(wb`TO{ zD}3&h#I(zeFAm0OzYkk_wrIOOdvUFK56y45hi(Y)w$D5 zZodyM5SK$VCh$Z<%jHGgJbb?EYm9Ere4fe2$9z~6d1^|9*W(r}n$ONN`mVIq zli@4lli`HPS!E4oHh1<1Io?5fMB&j)Kg$L!Pm`=y-f#NrHNi>pK8tc!dn)3{vB zJM5=l^RfB&iBFL)zXxx4HW*v&WBn?B&_}1_aP5XI@0-;HoXnG~-^T}%hL zp@JCv8^HI*V4RDGyfOGqz~7F+uLFKD1|I|bb`1VEz!ziiPt~_rL_YAk>L(za%@01a z?_wrK;46f`q)cHRg30h4%u96)@E1L!h3C7EWM{ggR!te>Z)+?vguR%@?gC;wdqqa zS69{EkD$J*S{Hj)wa)mkaZ6&kUb2N6yn0vKRuZy#*<0GVzKT#oZrUU1k5s|}B9B$N zi2Q|awJ-2lEOEj&02;aF6(L(uGQ4F>qnX!izjnN@O=73}Hdl_bO-hlIxUm4fjgd!a zx~q+0h8pr1<}>_wU)5Gtuj-LG&Z@1=s5u8`5JszEo6(hCUMbx#jQ7pLy~8tfyl-}S zn~OL1D&ID-oLTt(YnC%3FsnRSnuYJaW(90lH7Q2$v<>w+w2r+VZR-|}2CDGBt-)Tk zv5LJHvsXR5VT-o}*xPUm74yNQ-D}g51G@_tpOZI6eS~b@6`h( z6t|^QQ;t;UTG;%W0p`cH9%DY|$+wbnC5H}9X~>Za%d z*M9>y^Pl4Cr|8y#ZtWD^xEr{$o%*gSPo|V=6GHXds@xrMLZ6|$1=xOIyO7eC8#bZt zrq+@yq>{>8kn$t-zDDSaFE?yP*=AU-NNLJjkn$rHUBk}6mo~*0<4x^6X|Hlu1AkVz zp$@g{T1zZQp;e^(NL>_!z8U3)EhyX4TJmG0&?-`Xq^gn9l^eFAY%A&^g;tUBBNc76 z_06d^VDFyh&WhsT&S3AtVYf z&8?q;@@_y&?_9s0P*XlOk|Ij=Rg~A?Pqq3b6x9fO-_7b91VT(PI34i97@P%oX$)rf z3hb@p)cZ#AJx1Xl|9(9a!$BBA_!GhaLLb6g2(KVaAh22#Z+||<+n)u9XCh=FOhXt! z-erV40IPVhCW^Lg{K{I-=B?Ywe0xRFy5jkZ?RcP5xoTZm(dzlY;bM4m((&yUf(=(g zi*Tp00%59*kKz0t_FMKaX%2xIS5C| z$-H=^>(J7h@suHjQ{QW~;qS^mt851x2o6@al>OcRDL?@4qjqk6}gZ~Ko F{{i|A1XTb4 literal 0 HcmV?d00001 From 41850ee550612984c29e539036f4eb0ef6f98cde Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Tue, 31 Oct 2023 16:49:06 -0300 Subject: [PATCH 123/499] Sub: use gain-ajusted deadzone for pilot_desired_yaw_rate --- ArduSub/mode_althold.cpp | 3 ++- ArduSub/mode_poshold.cpp | 3 ++- ArduSub/mode_stabilize.cpp | 3 ++- 3 files changed, 6 insertions(+), 3 deletions(-) diff --git a/ArduSub/mode_althold.cpp b/ArduSub/mode_althold.cpp index 3282054d7329ad..9102ff9f802e72 100644 --- a/ArduSub/mode_althold.cpp +++ b/ArduSub/mode_althold.cpp @@ -64,7 +64,8 @@ void ModeAlthold::run() sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control->get_althold_lean_angle_max_cd()); // get pilot's desired yaw rate - float target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); + float yaw_input = channel_yaw->pwm_to_angle_dz_trim(channel_yaw->get_dead_zone() * sub.gain, channel_yaw->get_radio_trim()); + float target_yaw_rate = sub.get_pilot_desired_yaw_rate(yaw_input); // call attitude controller if (!is_zero(target_yaw_rate)) { // call attitude controller with rate yaw determined by pilot input diff --git a/ArduSub/mode_poshold.cpp b/ArduSub/mode_poshold.cpp index b85e359ede568c..a5cb3d9bfd050d 100644 --- a/ArduSub/mode_poshold.cpp +++ b/ArduSub/mode_poshold.cpp @@ -78,7 +78,8 @@ void ModePoshold::run() // Update attitude // // get pilot's desired yaw rate - float target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); + float yaw_input = channel_yaw->pwm_to_angle_dz_trim(channel_yaw->get_dead_zone() * sub.gain, channel_yaw->get_radio_trim()); + float target_yaw_rate = sub.get_pilot_desired_yaw_rate(yaw_input); // convert pilot input to lean angles // To-Do: convert get_pilot_desired_lean_angles to return angles as floats diff --git a/ArduSub/mode_stabilize.cpp b/ArduSub/mode_stabilize.cpp index cd75be241b6c2c..52620b8d5d0b6a 100644 --- a/ArduSub/mode_stabilize.cpp +++ b/ArduSub/mode_stabilize.cpp @@ -32,7 +32,8 @@ void ModeStabilize::run() sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, sub.aparm.angle_max); // get pilot's desired yaw rate - float target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); + float yaw_input = channel_yaw->pwm_to_angle_dz_trim(channel_yaw->get_dead_zone() * sub.gain, channel_yaw->get_radio_trim()); + float target_yaw_rate = sub.get_pilot_desired_yaw_rate(yaw_input); // call attitude controller // update attitude controller targets From 01eb0fd26dba82fc9addde626facc800a52d213c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 10 Nov 2023 19:24:19 +1100 Subject: [PATCH 124/499] RC_Channel: unfriend SRV_Channels --- libraries/RC_Channel/RC_Channel.h | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index 46520602a1d038..bf9d70f5bcf4ed 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -17,7 +17,6 @@ /// @brief Object managing one RC channel class RC_Channel { public: - friend class SRV_Channels; friend class RC_Channels; // Constructor RC_Channel(void); From f3914dfc16d736b1e46e97f1db495400a832a935 Mon Sep 17 00:00:00 2001 From: muramura Date: Sun, 24 Sep 2023 17:59:17 +0900 Subject: [PATCH 125/499] Copter: Change to Boolean value --- ArduCopter/mode_autorotate.cpp | 28 ++++++++++++++-------------- ArduCopter/toy_mode.cpp | 6 +++--- 2 files changed, 17 insertions(+), 17 deletions(-) diff --git a/ArduCopter/mode_autorotate.cpp b/ArduCopter/mode_autorotate.cpp index 414401c2e9a571..85f278ac0d801d 100644 --- a/ArduCopter/mode_autorotate.cpp +++ b/ArduCopter/mode_autorotate.cpp @@ -48,14 +48,14 @@ bool ModeAutorotate::init(bool ignore_checks) gcs().send_text(MAV_SEVERITY_INFO, "Autorotation initiated"); // Set all intial flags to on - _flags.entry_initial = 1; - _flags.ss_glide_initial = 1; - _flags.flare_initial = 1; - _flags.touch_down_initial = 1; - _flags.level_initial = 1; - _flags.break_initial = 1; - _flags.straight_ahead_initial = 1; - _flags.bail_out_initial = 1; + _flags.entry_initial = true; + _flags.ss_glide_initial = true; + _flags.flare_initial = true; + _flags.touch_down_initial = true; + _flags.level_initial = true; + _flags.break_initial = true; + _flags.straight_ahead_initial = true; + _flags.bail_out_initial = true; _msg_flags.bad_rpm = true; // Setting default starting switches @@ -114,7 +114,7 @@ void ModeAutorotate::run() case Autorotation_Phase::ENTRY: { // Entry phase functions to be run only once - if (_flags.entry_initial == 1) { + if (_flags.entry_initial == true) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL gcs().send_text(MAV_SEVERITY_INFO, "Entry Phase"); @@ -130,7 +130,7 @@ void ModeAutorotate::run() g2.arot.set_desired_fwd_speed(); // Prevent running the initial entry functions again - _flags.entry_initial = 0; + _flags.entry_initial = false; } @@ -160,7 +160,7 @@ void ModeAutorotate::run() case Autorotation_Phase::SS_GLIDE: { // Steady state glide functions to be run only once - if (_flags.ss_glide_initial == 1) { + if (_flags.ss_glide_initial == true) { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL gcs().send_text(MAV_SEVERITY_INFO, "SS Glide Phase"); @@ -177,7 +177,7 @@ void ModeAutorotate::run() g2.arot.set_target_head_speed(_target_head_speed); // Prevent running the initial glide functions again - _flags.ss_glide_initial = 0; + _flags.ss_glide_initial = false; } // Run airspeed/attitude controller @@ -202,7 +202,7 @@ void ModeAutorotate::run() case Autorotation_Phase::BAIL_OUT: { - if (_flags.bail_out_initial == 1) { + if (_flags.bail_out_initial == true) { // Functions and settings to be done once are done here. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL @@ -243,7 +243,7 @@ void ModeAutorotate::run() motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - _flags.bail_out_initial = 0; + _flags.bail_out_initial = false; } if ((now - _bail_time_start_ms)/1000.0f >= BAILOUT_MOTOR_RAMP_TIME) { diff --git a/ArduCopter/toy_mode.cpp b/ArduCopter/toy_mode.cpp index 922a51727baf7a..d212cb43358817 100644 --- a/ArduCopter/toy_mode.cpp +++ b/ArduCopter/toy_mode.cpp @@ -890,9 +890,9 @@ void ToyMode::blink_update(void) // let the TX know we are recording video uint32_t now = AP_HAL::millis(); if (now - last_video_ms < 1000) { - AP_Notify::flags.video_recording = 1; + AP_Notify::flags.video_recording = true; } else { - AP_Notify::flags.video_recording = 0; + AP_Notify::flags.video_recording = false; } if (red_blink_count > 0 && green_blink_count > 0) { @@ -954,7 +954,7 @@ void ToyMode::handle_message(const mavlink_message_t &msg) green_blink_count = 1; last_video_ms = AP_HAL::millis(); // immediately update AP_Notify recording flag - AP_Notify::flags.video_recording = 1; + AP_Notify::flags.video_recording = true; } else if (strncmp(m.name, "WIFICHAN", 10) == 0) { #if HAL_RCINPUT_WITH_AP_RADIO AP_Radio *radio = AP_Radio::get_singleton(); From 45fc140e1d3e6f9721e758646d023e7f59141106 Mon Sep 17 00:00:00 2001 From: muramura Date: Sun, 24 Sep 2023 18:00:11 +0900 Subject: [PATCH 126/499] AP_ExternalAHRS: Change to Boolean value --- .../AP_ExternalAHRS_MicroStrain5.cpp | 20 +++++++++---------- .../AP_ExternalAHRS_VectorNav.cpp | 20 +++++++++---------- 2 files changed, 20 insertions(+), 20 deletions(-) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp index abdc63250ec587..47bffb606a1e29 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp @@ -245,20 +245,20 @@ void AP_ExternalAHRS_MicroStrain5::get_filter_status(nav_filter_status &status) { memset(&status, 0, sizeof(status)); if (last_ins_pkt != 0 && last_gps_pkt != 0) { - status.flags.initalized = 1; + status.flags.initalized = true; } if (healthy() && last_ins_pkt != 0) { - status.flags.attitude = 1; - status.flags.vert_vel = 1; - status.flags.vert_pos = 1; + status.flags.attitude = true; + status.flags.vert_vel = true; + status.flags.vert_pos = true; if (gnss_data.fix_type >= 3) { - status.flags.horiz_vel = 1; - status.flags.horiz_pos_rel = 1; - status.flags.horiz_pos_abs = 1; - status.flags.pred_horiz_pos_rel = 1; - status.flags.pred_horiz_pos_abs = 1; - status.flags.using_gps = 1; + status.flags.horiz_vel = true; + status.flags.horiz_pos_rel = true; + status.flags.horiz_pos_abs = true; + status.flags.pred_horiz_pos_rel = true; + status.flags.pred_horiz_pos_abs = true; + status.flags.using_gps = true; } } } diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index b7c0bf4bff18cb..b8eaf3a4ac500d 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -744,21 +744,21 @@ void AP_ExternalAHRS_VectorNav::get_filter_status(nav_filter_status &status) con memset(&status, 0, sizeof(status)); if (type == TYPE::VN_300) { if (last_pkt1 && last_pkt2) { - status.flags.initalized = 1; + status.flags.initalized = true; } if (healthy() && last_pkt2) { - status.flags.attitude = 1; - status.flags.vert_vel = 1; - status.flags.vert_pos = 1; + status.flags.attitude = true; + status.flags.vert_vel = true; + status.flags.vert_pos = true; const struct VN_packet2 &pkt2 = *last_pkt2; if (pkt2.GPS1Fix >= 3) { - status.flags.horiz_vel = 1; - status.flags.horiz_pos_rel = 1; - status.flags.horiz_pos_abs = 1; - status.flags.pred_horiz_pos_rel = 1; - status.flags.pred_horiz_pos_abs = 1; - status.flags.using_gps = 1; + status.flags.horiz_vel = true; + status.flags.horiz_pos_rel = true; + status.flags.horiz_pos_abs = true; + status.flags.pred_horiz_pos_rel = true; + status.flags.pred_horiz_pos_abs = true; + status.flags.using_gps = true; } } } else { From 87f4509472794262f28b70caa1ab82b8a0794f9f Mon Sep 17 00:00:00 2001 From: muramura Date: Sun, 24 Sep 2023 18:00:40 +0900 Subject: [PATCH 127/499] AP_AHRS: Change to Boolean value --- libraries/AP_AHRS/AP_AHRS_SIM.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_SIM.cpp b/libraries/AP_AHRS/AP_AHRS_SIM.cpp index ff7e042d47109e..c1e26f18909b1e 100644 --- a/libraries/AP_AHRS/AP_AHRS_SIM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_SIM.cpp @@ -152,15 +152,15 @@ bool AP_AHRS_SIM::get_relative_position_D_origin(float &posD) const bool AP_AHRS_SIM::get_filter_status(nav_filter_status &status) const { memset(&status, 0, sizeof(status)); - status.flags.attitude = 1; - status.flags.horiz_vel = 1; - status.flags.vert_vel = 1; - status.flags.horiz_pos_rel = 1; - status.flags.horiz_pos_abs = 1; - status.flags.vert_pos = 1; - status.flags.pred_horiz_pos_rel = 1; - status.flags.pred_horiz_pos_abs = 1; - status.flags.using_gps = 1; + status.flags.attitude = true; + status.flags.horiz_vel = true; + status.flags.vert_vel = true; + status.flags.horiz_pos_rel = true; + status.flags.horiz_pos_abs = true; + status.flags.vert_pos = true; + status.flags.pred_horiz_pos_rel = true; + status.flags.pred_horiz_pos_abs = true; + status.flags.using_gps = true; return true; } From e25d4dcad5c77d2caa334f080bf8030fe0b75bd3 Mon Sep 17 00:00:00 2001 From: muramura Date: Sun, 24 Sep 2023 18:01:06 +0900 Subject: [PATCH 128/499] AP_Parachute: Change to Boolean value --- libraries/AP_Parachute/AP_Parachute.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index 213c804f939669..9b4075dc719642 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -114,7 +114,7 @@ void AP_Parachute::release() _release_initiated = true; // update AP_Notify - AP_Notify::flags.parachute_release = 1; + AP_Notify::flags.parachute_release = true; } /// update - shuts off the trigger should be called at about 10hz @@ -167,7 +167,7 @@ void AP_Parachute::update() _release_in_progress = false; _release_time = 0; // update AP_Notify - AP_Notify::flags.parachute_release = 0; + AP_Notify::flags.parachute_release = false; } } From 3811de3e25df393ea12177410255942f6b662f96 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 9 Nov 2023 07:38:31 -0600 Subject: [PATCH 129/499] AP_OSD:correct xy limits for panels --- libraries/AP_OSD/AP_OSD_Screen.cpp | 238 ++++++++++++++--------------- 1 file changed, 119 insertions(+), 119 deletions(-) diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index 3a76f5b577d11d..cdc0e2a59a9c19 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -84,12 +84,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ALTITUDE_X // @DisplayName: ALTITUDE_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ALTITUDE_Y // @DisplayName: ALTITUDE_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(altitude, "ALTITUDE", 4, AP_OSD_Screen, AP_OSD_Setting), // @Param: BAT_VOLT_EN @@ -100,12 +100,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: BAT_VOLT_X // @DisplayName: BATVOLT_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: BAT_VOLT_Y // @DisplayName: BATVOLT_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(bat_volt, "BAT_VOLT", 5, AP_OSD_Screen, AP_OSD_Setting), // @Param: RSSI_EN @@ -116,12 +116,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: RSSI_X // @DisplayName: RSSI_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: RSSI_Y // @DisplayName: RSSI_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(rssi, "RSSI", 6, AP_OSD_Screen, AP_OSD_Setting), // @Param: CURRENT_EN @@ -132,12 +132,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: CURRENT_X // @DisplayName: CURRENT_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: CURRENT_Y // @DisplayName: CURRENT_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(current, "CURRENT", 7, AP_OSD_Screen, AP_OSD_Setting), // @Param: BATUSED_EN @@ -148,12 +148,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: BATUSED_X // @DisplayName: BATUSED_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: BATUSED_Y // @DisplayName: BATUSED_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(batused, "BATUSED", 8, AP_OSD_Screen, AP_OSD_Setting), // @Param: SATS_EN @@ -164,12 +164,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: SATS_X // @DisplayName: SATS_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: SATS_Y // @DisplayName: SATS_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(sats, "SATS", 9, AP_OSD_Screen, AP_OSD_Setting), // @Param: FLTMODE_EN @@ -180,12 +180,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: FLTMODE_X // @DisplayName: FLTMODE_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: FLTMODE_Y // @DisplayName: FLTMODE_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(fltmode, "FLTMODE", 10, AP_OSD_Screen, AP_OSD_Setting), // @Param: MESSAGE_EN @@ -196,12 +196,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: MESSAGE_X // @DisplayName: MESSAGE_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: MESSAGE_Y // @DisplayName: MESSAGE_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(message, "MESSAGE", 11, AP_OSD_Screen, AP_OSD_Setting), // @Param: GSPEED_EN @@ -212,12 +212,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: GSPEED_X // @DisplayName: GSPEED_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: GSPEED_Y // @DisplayName: GSPEED_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(gspeed, "GSPEED", 12, AP_OSD_Screen, AP_OSD_Setting), // @Param: HORIZON_EN @@ -228,12 +228,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: HORIZON_X // @DisplayName: HORIZON_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: HORIZON_Y // @DisplayName: HORIZON_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(horizon, "HORIZON", 13, AP_OSD_Screen, AP_OSD_Setting), // @Param: HOME_EN @@ -244,12 +244,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: HOME_X // @DisplayName: HOME_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: HOME_Y // @DisplayName: HOME_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(home, "HOME", 14, AP_OSD_Screen, AP_OSD_Setting), // @Param: HEADING_EN @@ -260,12 +260,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: HEADING_X // @DisplayName: HEADING_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: HEADING_Y // @DisplayName: HEADING_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(heading, "HEADING", 15, AP_OSD_Screen, AP_OSD_Setting), // @Param: THROTTLE_EN @@ -276,12 +276,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: THROTTLE_X // @DisplayName: THROTTLE_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: THROTTLE_Y // @DisplayName: THROTTLE_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(throttle, "THROTTLE", 16, AP_OSD_Screen, AP_OSD_Setting), // @Param: COMPASS_EN @@ -292,12 +292,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: COMPASS_X // @DisplayName: COMPASS_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: COMPASS_Y // @DisplayName: COMPASS_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(compass, "COMPASS", 17, AP_OSD_Screen, AP_OSD_Setting), // @Param: WIND_EN @@ -308,12 +308,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: WIND_X // @DisplayName: WIND_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: WIND_Y // @DisplayName: WIND_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(wind, "WIND", 18, AP_OSD_Screen, AP_OSD_Setting), @@ -325,12 +325,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ASPEED_X // @DisplayName: ASPEED_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ASPEED_Y // @DisplayName: ASPEED_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(aspeed, "ASPEED", 19, AP_OSD_Screen, AP_OSD_Setting), // @Param: VSPEED_EN @@ -341,12 +341,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: VSPEED_X // @DisplayName: VSPEED_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: VSPEED_Y // @DisplayName: VSPEED_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(vspeed, "VSPEED", 20, AP_OSD_Screen, AP_OSD_Setting), #if HAL_WITH_ESC_TELEM @@ -358,12 +358,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ESCTEMP_X // @DisplayName: ESCTEMP_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ESCTEMP_Y // @DisplayName: ESCTEMP_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(esc_temp, "ESCTEMP", 21, AP_OSD_Screen, AP_OSD_Setting), // @Param: ESCRPM_EN @@ -374,12 +374,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ESCRPM_X // @DisplayName: ESCRPM_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ESCRPM_Y // @DisplayName: ESCRPM_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(esc_rpm, "ESCRPM", 22, AP_OSD_Screen, AP_OSD_Setting), // @Param: ESCAMPS_EN @@ -390,12 +390,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ESCAMPS_X // @DisplayName: ESCAMPS_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ESCAMPS_Y // @DisplayName: ESCAMPS_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(esc_amps, "ESCAMPS", 23, AP_OSD_Screen, AP_OSD_Setting), #endif // @Param: GPSLAT_EN @@ -406,12 +406,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: GPSLAT_X // @DisplayName: GPSLAT_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: GPSLAT_Y // @DisplayName: GPSLAT_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(gps_latitude, "GPSLAT", 24, AP_OSD_Screen, AP_OSD_Setting), // @Param: GPSLONG_EN @@ -422,12 +422,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: GPSLONG_X // @DisplayName: GPSLONG_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: GPSLONG_Y // @DisplayName: GPSLONG_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(gps_longitude, "GPSLONG", 25, AP_OSD_Screen, AP_OSD_Setting), // @Param: ROLL_EN @@ -438,12 +438,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ROLL_X // @DisplayName: ROLL_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ROLL_Y // @DisplayName: ROLL_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(roll_angle, "ROLL", 26, AP_OSD_Screen, AP_OSD_Setting), // @Param: PITCH_EN @@ -454,12 +454,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: PITCH_X // @DisplayName: PITCH_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: PITCH_Y // @DisplayName: PITCH_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(pitch_angle, "PITCH", 27, AP_OSD_Screen, AP_OSD_Setting), // @Param: TEMP_EN @@ -470,12 +470,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: TEMP_X // @DisplayName: TEMP_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: TEMP_Y // @DisplayName: TEMP_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(temp, "TEMP", 28, AP_OSD_Screen, AP_OSD_Setting), // @Param: HDOP_EN @@ -486,12 +486,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: HDOP_X // @DisplayName: HDOP_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: HDOP_Y // @DisplayName: HDOP_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(hdop, "HDOP", 29, AP_OSD_Screen, AP_OSD_Setting), // @Param: WAYPOINT_EN @@ -502,12 +502,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: WAYPOINT_X // @DisplayName: WAYPOINT_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: WAYPOINT_Y // @DisplayName: WAYPOINT_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(waypoint, "WAYPOINT", 30, AP_OSD_Screen, AP_OSD_Setting), // @Param: XTRACK_EN @@ -518,12 +518,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: XTRACK_X // @DisplayName: XTRACK_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: XTRACK_Y // @DisplayName: XTRACK_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(xtrack_error, "XTRACK", 31, AP_OSD_Screen, AP_OSD_Setting), // @Param: DIST_EN @@ -534,12 +534,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: DIST_X // @DisplayName: DIST_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: DIST_Y // @DisplayName: DIST_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(dist, "DIST", 32, AP_OSD_Screen, AP_OSD_Setting), // @Param: STATS_EN @@ -550,12 +550,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: STATS_X // @DisplayName: STATS_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: STATS_Y // @DisplayName: STATS_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(stat, "STATS", 33, AP_OSD_Screen, AP_OSD_Setting), // @Param: FLTIME_EN @@ -566,12 +566,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: FLTIME_X // @DisplayName: FLTIME_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: FLTIME_Y // @DisplayName: FLTIME_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(flightime, "FLTIME", 34, AP_OSD_Screen, AP_OSD_Setting), // @Param: CLIMBEFF_EN @@ -582,12 +582,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: CLIMBEFF_X // @DisplayName: CLIMBEFF_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: CLIMBEFF_Y // @DisplayName: CLIMBEFF_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(climbeff, "CLIMBEFF", 35, AP_OSD_Screen, AP_OSD_Setting), // @Param: EFF_EN @@ -598,12 +598,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: EFF_X // @DisplayName: EFF_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: EFF_Y // @DisplayName: EFF_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(eff, "EFF", 36, AP_OSD_Screen, AP_OSD_Setting), #if BARO_MAX_INSTANCES > 1 @@ -615,12 +615,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: BTEMP_X // @DisplayName: BTEMP_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: BTEMP_Y // @DisplayName: BTEMP_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(btemp, "BTEMP", 37, AP_OSD_Screen, AP_OSD_Setting), #endif @@ -632,12 +632,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ATEMP_X // @DisplayName: ATEMP_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ATEMP_Y // @DisplayName: ATEMP_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(atemp, "ATEMP", 38, AP_OSD_Screen, AP_OSD_Setting), // @Param: BAT2_VLT_EN @@ -648,12 +648,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: BAT2_VLT_X // @DisplayName: BAT2VLT_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: BAT2_VLT_Y // @DisplayName: BAT2VLT_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(bat2_vlt, "BAT2_VLT", 39, AP_OSD_Screen, AP_OSD_Setting), // @Param: BAT2USED_EN @@ -664,12 +664,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: BAT2USED_X // @DisplayName: BAT2USED_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: BAT2USED_Y // @DisplayName: BAT2USED_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(bat2used, "BAT2USED", 40, AP_OSD_Screen, AP_OSD_Setting), @@ -681,12 +681,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ASPD2_X // @DisplayName: ASPD2_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ASPD2_Y // @DisplayName: ASPD2_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(aspd2, "ASPD2", 41, AP_OSD_Screen, AP_OSD_Setting), // @Param: ASPD1_EN @@ -697,12 +697,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ASPD1_X // @DisplayName: ASPD1_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ASPD1_Y // @DisplayName: ASPD1_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(aspd1, "ASPD1", 42, AP_OSD_Screen, AP_OSD_Setting), // @Param: CLK_EN @@ -713,12 +713,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: CLK_X // @DisplayName: CLK_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: CLK_Y // @DisplayName: CLK_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(clk, "CLK", 43, AP_OSD_Screen, AP_OSD_Setting), #if HAL_OSD_SIDEBAR_ENABLE || HAL_MSP_ENABLED @@ -730,12 +730,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: SIDEBARS_X // @DisplayName: SIDEBARS_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: SIDEBARS_Y // @DisplayName: SIDEBARS_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(sidebars, "SIDEBARS", 44, AP_OSD_Screen, AP_OSD_Setting), #endif @@ -748,12 +748,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: CRSSHAIR_X // @DisplayName: CRSSHAIR_X // @Description: Horizontal position on screen (MSP OSD only) - // @Range: 0 29 + // @Range: 0 59 // @Param: CRSSHAIR_Y // @DisplayName: CRSSHAIR_Y // @Description: Vertical position on screen (MSP OSD only) - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(crosshair, "CRSSHAIR", 45, AP_OSD_Screen, AP_OSD_Setting), // @Param: HOMEDIST_EN @@ -764,12 +764,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: HOMEDIST_X // @DisplayName: HOMEDIST_X // @Description: Horizontal position on screen (MSP OSD only) - // @Range: 0 29 + // @Range: 0 59 // @Param: HOMEDIST_Y // @DisplayName: HOMEDIST_Y // @Description: Vertical position on screen (MSP OSD only) - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(home_dist, "HOMEDIST", 46, AP_OSD_Screen, AP_OSD_Setting), // @Param: HOMEDIR_EN @@ -780,12 +780,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: HOMEDIR_X // @DisplayName: HOMEDIR_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: HOMEDIR_Y // @DisplayName: HOMEDIR_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(home_dir, "HOMEDIR", 47, AP_OSD_Screen, AP_OSD_Setting), // @Param: POWER_EN @@ -796,12 +796,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: POWER_X // @DisplayName: POWER_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: POWER_Y // @DisplayName: POWER_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(power, "POWER", 48, AP_OSD_Screen, AP_OSD_Setting), // @Param: CELLVOLT_EN @@ -812,12 +812,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: CELLVOLT_X // @DisplayName: CELL_VOLT_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: CELLVOLT_Y // @DisplayName: CELL_VOLT_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(cell_volt, "CELLVOLT", 49, AP_OSD_Screen, AP_OSD_Setting), // @Param: BATTBAR_EN @@ -828,12 +828,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: BATTBAR_X // @DisplayName: BATT_BAR_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: BATTBAR_Y // @DisplayName: BATT_BAR_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(batt_bar, "BATTBAR", 50, AP_OSD_Screen, AP_OSD_Setting), // @Param: ARMING_EN @@ -844,12 +844,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ARMING_X // @DisplayName: ARMING_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ARMING_Y // @DisplayName: ARMING_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(arming, "ARMING", 51, AP_OSD_Screen, AP_OSD_Setting), #endif //HAL_MSP_ENABLED @@ -862,12 +862,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: PLUSCODE_X // @DisplayName: PLUSCODE_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: PLUSCODE_Y // @DisplayName: PLUSCODE_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(pluscode, "PLUSCODE", 52, AP_OSD_Screen, AP_OSD_Setting), #endif @@ -880,12 +880,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: CALLSIGN_X // @DisplayName: CALLSIGN_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: CALLSIGN_Y // @DisplayName: CALLSIGN_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(callsign, "CALLSIGN", 53, AP_OSD_Screen, AP_OSD_Setting), #endif @@ -897,12 +897,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: CURRENT2_X // @DisplayName: CURRENT2_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: CURRENT2_Y // @DisplayName: CURRENT2_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(current2, "CURRENT2", 54, AP_OSD_Screen, AP_OSD_Setting), #if AP_VIDEOTX_ENABLED @@ -914,12 +914,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: VTX_PWR_X // @DisplayName: VTX_PWR_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: VTX_PWR_Y // @DisplayName: VTX_PWR_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(vtx_power, "VTX_PWR", 55, AP_OSD_Screen, AP_OSD_Setting), #endif // AP_VIDEOTX_ENABLED @@ -932,12 +932,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: TER_HGT_X // @DisplayName: TER_HGT_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: TER_HGT_Y // @DisplayName: TER_HGT_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(hgt_abvterr, "TER_HGT", 56, AP_OSD_Screen, AP_OSD_Setting), #endif @@ -949,12 +949,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: AVGCELLV_X // @DisplayName: AVGCELLV_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: AVGCELLV_Y // @DisplayName: AVGCELLV_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(avgcellvolt, "AVGCELLV", 57, AP_OSD_Screen, AP_OSD_Setting), // @Param: RESTVOLT_EN @@ -965,12 +965,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: RESTVOLT_X // @DisplayName: RESTVOLT_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: RESTVOLT_Y // @DisplayName: RESTVOLT_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(restvolt, "RESTVOLT", 58, AP_OSD_Screen, AP_OSD_Setting), // @Param: FENCE_EN @@ -981,12 +981,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: FENCE_X // @DisplayName: FENCE_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: FENCE_Y // @DisplayName: FENCE_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(fence, "FENCE", 59, AP_OSD_Screen, AP_OSD_Setting), // @Param: RNGF_EN @@ -997,12 +997,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: RNGF_X // @DisplayName: RNGF_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: RNGF_Y // @DisplayName: RNGF_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(rngf, "RNGF", 60, AP_OSD_Screen, AP_OSD_Setting), // @Param: ACRVOLT_EN @@ -1013,12 +1013,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = { // @Param: ACRVOLT_X // @DisplayName: ACRVOLT_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: ACRVOLT_Y // @DisplayName: ACRVOLT_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(avgcellrestvolt, "ACRVOLT", 61, AP_OSD_Screen, AP_OSD_Setting), #if AP_RPM_ENABLED @@ -1054,12 +1054,12 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info2[] = { // @Param: LINK_Q_X // @DisplayName: LINK_Q_X // @Description: Horizontal position on screen - // @Range: 0 29 + // @Range: 0 59 // @Param: LINK_Q_Y // @DisplayName: LINK_Q_Y // @Description: Vertical position on screen - // @Range: 0 15 + // @Range: 0 21 AP_SUBGROUPINFO(link_quality, "LINK_Q", 1, AP_OSD_Screen, AP_OSD_Setting), #if HAL_WITH_MSP_DISPLAYPORT @@ -1073,7 +1073,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info2[] = { // @Param: FONT // @DisplayName: Sets the font index for this screen (MSP DisplayPort only) // @Description: Sets the font index for this screen (MSP DisplayPort only) - // @Range: 0 15 + // @Range: 0 21 // @User: Standard AP_GROUPINFO("FONT", 4, AP_OSD_Screen, font_index, 0), #endif From 2f9bfb648f090430f063bec3684e9c60f23abc77 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Sep 2023 10:14:40 +1000 Subject: [PATCH 130/499] HAL_ChibiOS: default RTS pins to PULLDOWN this avoids issues with SiK and RFD900x radios getting stuck in bootloader mode due to a high RTS pin on power on. We did this for Pixhawk6C in this PR: https://github.com/ArduPilot/ardupilot/pull/24169 this now applies it to all boards --- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 927ddf861d8030..5730f68585304c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -411,10 +411,15 @@ def get_PUPDR_value(self): self.type.startswith('UART')) and ( (self.label.endswith('_TX') or self.label.endswith('_RX') or - self.label.endswith('_CTS') or - self.label.endswith('_RTS'))): + self.label.endswith('_CTS'))): v = "PULLUP" + # pulldown on RTS to prevent radios from staying in bootloader + if (self.type.startswith('USART') or + self.type.startswith('UART')) and ( + self.label.endswith('_RTS')): + v = "PULLDOWN" + if (self.type.startswith('SWD') and 'SWDIO' in self.label): v = "PULLUP" From 0143bf22d4d0a4a63a760c2773ba63d9d39a05ed Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 9 Nov 2023 16:37:52 +1100 Subject: [PATCH 131/499] autotest: understand verbose and very_vrbose for wait_message_field_values --- Tools/autotest/vehicle_test_suite.py | 20 +++++++++++++++++--- 1 file changed, 17 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 543bb6d5d04963..be940085b3b3d8 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -3915,7 +3915,16 @@ def assert_received_message_field_values(self, return m # FIXME: try to use wait_and_maintain here? - def wait_message_field_values(self, message, fieldvalues, timeout=10, epsilon=None, instance=None, minimum_duration=None): + def wait_message_field_values(self, + message, + fieldvalues, + timeout=10, + epsilon=None, + instance=None, + minimum_duration=None, + verbose=False, + very_verbose=False, + ): tstart = self.get_sim_time_cached() pass_start = None @@ -3923,8 +3932,13 @@ def wait_message_field_values(self, message, fieldvalues, timeout=10, epsilon=No now = self.get_sim_time_cached() if now - tstart > timeout: raise NotAchievedException("Field never reached values") - m = self.assert_receive_message(message, instance=instance) - if self.message_has_field_values(m, fieldvalues, epsilon=epsilon): + m = self.assert_receive_message( + message, + instance=instance, + verbose=verbose, + very_verbose=very_verbose, + ) + if self.message_has_field_values(m, fieldvalues, epsilon=epsilon, verbose=verbose): if minimum_duration is not None: if pass_start is None: pass_start = now From 18ea26768d0afa5d07b155a67df5d61552b0ee95 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 10 Nov 2023 16:58:58 +1100 Subject: [PATCH 132/499] board_types.txt: reserve ID for FreeSpace PowerStack --- Tools/AP_Bootloader/board_types.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index 80214304e8b671..4db458378dfa45 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -254,6 +254,7 @@ AP_HW_TMOTORH7 1138 AP_HW_MICOAIR405 1139 AP_HW_PixPilot-C3 1140 AP_HW_YJUAV_A6SE_H743 1141 +AP_HW_FSO_POWER_STACK 1142 AP_HW_ESP32_PERIPH 1205 AP_HW_ESP32S3_PERIPH 1206 From 02a699c21b5d3aefa7e41e473db3b18c038cc0f1 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 11 Nov 2023 12:09:55 +0900 Subject: [PATCH 133/499] Copter: fix 440-beta1 release notes TKOFF_TH_MAX was not included in Copter-4.4.0 --- ArduCopter/ReleaseNotes.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index 941e75014cac48..a0e77748da297c 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -232,7 +232,6 @@ Changes from 4.3.6 - Touchdown detection threshold is configurable (see PLDP_THRESH) - Position controller angle max adjusted inflight with CH6 Tuning knob (set TUNE=59) - Surface tracking time constant allows tuning response (see SURFTRAK_TC) - - Takeoff throttle max is configurable (see TKOFF_TH_MAX) - Throttle-Gain boost increases attitude control gains when throttle high (see ATC_THR_G_BOOST) - Waypoint navigation cornering acceleration is configurable (see WPNAV_ACCEL_C) - WeatherVane into the wind in Auto and Guided modes (see WVANE_ENABLE) From d2984cbd99fc1d8d21d7a297bd0ad80508980b6c Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Fri, 10 Nov 2023 07:48:29 -0600 Subject: [PATCH 134/499] Tools:reserve ATOMRCF405NAVI_DLX bd id --- Tools/AP_Bootloader/board_types.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index 4db458378dfa45..c9c2cb0ec83c5f 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -255,6 +255,8 @@ AP_HW_MICOAIR405 1139 AP_HW_PixPilot-C3 1140 AP_HW_YJUAV_A6SE_H743 1141 AP_HW_FSO_POWER_STACK 1142 +AP_HW_ATOMRCF405NAVI_DLX 1143 + AP_HW_ESP32_PERIPH 1205 AP_HW_ESP32S3_PERIPH 1206 From bd97dc4de53adc94b1f0341a19d439b81163f494 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sun, 12 Nov 2023 14:09:58 -0800 Subject: [PATCH 135/499] AP_Networking: cleanup backend defines --- libraries/AP_Networking/AP_Networking.cpp | 24 ++++++++++++++++--- libraries/AP_Networking/AP_Networking.h | 21 +++++++--------- .../AP_Networking/AP_Networking_ChibiOS.cpp | 6 ++--- .../AP_Networking/AP_Networking_ChibiOS.h | 4 ++-- .../AP_Networking/AP_Networking_Config.h | 19 ++++++++++++++- .../AP_Networking/AP_Networking_backend.h | 2 ++ 6 files changed, 53 insertions(+), 23 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index fa1b422008f5c7..8a21c95d248507 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -4,13 +4,14 @@ #if AP_NETWORKING_ENABLED #include "AP_Networking.h" -#include "AP_Networking_ChibiOS.h" +#include "AP_Networking_backend.h" #include #include extern const AP_HAL::HAL& hal; -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if AP_NETWORKING_BACKEND_CHIBIOS +#include "AP_Networking_ChibiOS.h" #include #include #else @@ -96,7 +97,7 @@ void AP_Networking::init() param.macaddr.set_default_address_byte(5, crc.bytes[2]); } -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if AP_NETWORKING_BACKEND_CHIBIOS backend = new AP_Networking_ChibiOS(*this); #endif @@ -211,6 +212,23 @@ bool AP_Networking::convert_str_to_macaddr(const char *mac_str, uint8_t addr[6]) return true; } +// returns the 32bit value of the active IP address that is currently in use +uint32_t AP_Networking::get_ip_active() const +{ + return backend?backend->activeSettings.ip:0; +} + +// returns the 32bit value of the active Netmask that is currently in use +uint32_t AP_Networking::get_netmask_active() const +{ + return backend?backend->activeSettings.nm:0; +} + +uint32_t AP_Networking::get_gateway_active() const +{ + return backend?backend->activeSettings.gw:0; +} + AP_Networking *AP_Networking::singleton; namespace AP diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 0a5628c97eac79..10637c5367f1c9 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -4,7 +4,6 @@ #include "AP_Networking_Config.h" #if AP_NETWORKING_ENABLED -#include #include #include "AP_Networking_address.h" @@ -14,9 +13,14 @@ Note! all uint32_t IPv4 addresses are in host byte order */ +// declare backend classes +class AP_Networking_backend; +class AP_Networking_ChibiOS; + class AP_Networking { public: + friend class AP_Networking_backend; friend class AP_Networking_ChibiOS; AP_Networking(); @@ -54,10 +58,7 @@ class AP_Networking } // returns the 32bit value of the active IP address that is currently in use - uint32_t get_ip_active() const - { - return backend?backend->activeSettings.ip:0; - } + uint32_t get_ip_active() const; // returns the 32bit value of the user-parameter static IP address uint32_t get_ip_param() const @@ -81,10 +82,7 @@ class AP_Networking } // returns the 32bit value of the active Netmask that is currently in use - uint32_t get_netmask_active() const - { - return backend?backend->activeSettings.nm:0; - } + uint32_t get_netmask_active() const; // returns the 32bit value of the of the user-parameter static Netmask uint32_t get_netmask_param() const @@ -113,10 +111,7 @@ class AP_Networking param.netmask.set(convert_netmask_ip_to_bitcount(nm)); } - uint32_t get_gateway_active() const - { - return backend?backend->activeSettings.gw:0; - } + uint32_t get_gateway_active() const; uint32_t get_gateway_param() const { diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp index 511408084d1e78..b79413c2aab448 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -1,11 +1,9 @@ #include "AP_Networking_Config.h" -#if AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if AP_NETWORKING_BACKEND_CHIBIOS -#include "AP_Networking.h" #include "AP_Networking_ChibiOS.h" -#include #include #include @@ -174,5 +172,5 @@ int32_t AP_Networking_ChibiOS::send_udp(struct udp_pcb *pcb, const ip4_addr_t &i return err == ERR_OK ? data_len : err; } -#endif // AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#endif // AP_NETWORKING_BACKEND_CHIBIOS diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.h b/libraries/AP_Networking/AP_Networking_ChibiOS.h index 196f621a0780c0..d193469e893b1b 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.h +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.h @@ -2,7 +2,7 @@ #include "AP_Networking_Config.h" -#if AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if AP_NETWORKING_BACKEND_CHIBIOS #include "AP_Networking_backend.h" class AP_Networking_ChibiOS : public AP_Networking_backend @@ -25,5 +25,5 @@ class AP_Networking_ChibiOS : public AP_Networking_backend uint8_t macaddr[6]; }; -#endif // AP_NETWORKING_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#endif // AP_NETWORKING_BACKEND_CHIBIOS diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index 54926c6d22942b..b5f43eec42f6e5 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -4,7 +4,24 @@ #define AP_NETWORKING_ENABLED 0 #endif -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#ifndef AP_NETWORKING_BACKEND_DEFAULT_ENABLED +#define AP_NETWORKING_BACKEND_DEFAULT_ENABLED AP_NETWORKING_ENABLED +#endif + + +// --------------------------- +// Backends +// --------------------------- +#ifndef AP_NETWORKING_BACKEND_CHIBIOS +#define AP_NETWORKING_BACKEND_CHIBIOS AP_NETWORKING_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#endif + +#define AP_NETWORKING_SOCKETS_ENABLED (HAL_OS_SOCKETS || AP_NETWORKING_BACKEND_CHIBIOS) + +// --------------------------- +// IP Features +// --------------------------- +#if AP_NETWORKING_BACKEND_CHIBIOS #define AP_NETWORKING_DHCP_AVAILABLE LWIP_DHCP #else #define AP_NETWORKING_DHCP_AVAILABLE 1 // for non-ChibiOS, assume it's available diff --git a/libraries/AP_Networking/AP_Networking_backend.h b/libraries/AP_Networking/AP_Networking_backend.h index 3689f40aa50458..c97377c9e054c0 100644 --- a/libraries/AP_Networking/AP_Networking_backend.h +++ b/libraries/AP_Networking/AP_Networking_backend.h @@ -4,6 +4,8 @@ #if AP_NETWORKING_ENABLED +#include "AP_Networking.h" + class AP_Networking; class AP_Networking_backend From c9a3cb13c1d4820eb7521e61d6d78d075a5b9940 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sun, 12 Nov 2023 12:38:26 -0800 Subject: [PATCH 136/499] AP_Networking: rename _backend.h to _Backend.h --- libraries/AP_Networking/AP_Networking.cpp | 2 +- libraries/AP_Networking/AP_Networking.h | 8 ++++---- .../{AP_Networking_backend.h => AP_Networking_Backend.h} | 6 +++--- libraries/AP_Networking/AP_Networking_ChibiOS.h | 6 +++--- 4 files changed, 11 insertions(+), 11 deletions(-) rename libraries/AP_Networking/{AP_Networking_backend.h => AP_Networking_Backend.h} (80%) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 8a21c95d248507..c6f51ad9297170 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -4,7 +4,7 @@ #if AP_NETWORKING_ENABLED #include "AP_Networking.h" -#include "AP_Networking_backend.h" +#include "AP_Networking_Backend.h" #include #include diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 10637c5367f1c9..a72f7cd3d5388b 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -7,20 +7,20 @@ #include #include "AP_Networking_address.h" -#include "AP_Networking_backend.h" +#include "AP_Networking_Backend.h" /* Note! all uint32_t IPv4 addresses are in host byte order */ // declare backend classes -class AP_Networking_backend; +class AP_Networking_Backend; class AP_Networking_ChibiOS; class AP_Networking { public: - friend class AP_Networking_backend; + friend class AP_Networking_Backend; friend class AP_Networking_ChibiOS; AP_Networking(); @@ -167,7 +167,7 @@ class AP_Networking AP_Int32 options; } param; - AP_Networking_backend *backend; + AP_Networking_Backend *backend; HAL_Semaphore sem; diff --git a/libraries/AP_Networking/AP_Networking_backend.h b/libraries/AP_Networking/AP_Networking_Backend.h similarity index 80% rename from libraries/AP_Networking/AP_Networking_backend.h rename to libraries/AP_Networking/AP_Networking_Backend.h index c97377c9e054c0..9233442c44da67 100644 --- a/libraries/AP_Networking/AP_Networking_backend.h +++ b/libraries/AP_Networking/AP_Networking_Backend.h @@ -8,15 +8,15 @@ class AP_Networking; -class AP_Networking_backend +class AP_Networking_Backend { public: friend class AP_Networking; - AP_Networking_backend(AP_Networking &_frontend) : frontend(_frontend) {} + AP_Networking_Backend(AP_Networking &_frontend) : frontend(_frontend) {} /* Do not allow copies */ - CLASS_NO_COPY(AP_Networking_backend); + CLASS_NO_COPY(AP_Networking_Backend); virtual bool init() = 0; virtual void update() = 0; diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.h b/libraries/AP_Networking/AP_Networking_ChibiOS.h index d193469e893b1b..70c4f0b49d2f8a 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.h +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.h @@ -3,12 +3,12 @@ #include "AP_Networking_Config.h" #if AP_NETWORKING_BACKEND_CHIBIOS -#include "AP_Networking_backend.h" +#include "AP_Networking_Backend.h" -class AP_Networking_ChibiOS : public AP_Networking_backend +class AP_Networking_ChibiOS : public AP_Networking_Backend { public: - using AP_Networking_backend::AP_Networking_backend; + using AP_Networking_Backend::AP_Networking_Backend; /* Do not allow copies */ CLASS_NO_COPY(AP_Networking_ChibiOS); From 12642b57938aa83e4078394645e1f7b4bba05959 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Thu, 28 Sep 2023 11:02:31 +1000 Subject: [PATCH 137/499] AP_Mission: Remove unused rewind param from set_current_cmd() (NFC) --- libraries/AP_Mission/AP_Mission.cpp | 8 +++----- libraries/AP_Mission/AP_Mission.h | 2 +- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index a000e7ba91116b..3487d3a974fcaa 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -538,7 +538,7 @@ int32_t AP_Mission::get_next_ground_course_cd(int32_t default_angle) } // set_current_cmd - jumps to command specified by index -bool AP_Mission::set_current_cmd(uint16_t index, bool rewind) +bool AP_Mission::set_current_cmd(uint16_t index) { // read command to check for DO_LAND_START Mission_Command cmd; @@ -546,10 +546,8 @@ bool AP_Mission::set_current_cmd(uint16_t index, bool rewind) _flags.in_landing_sequence = false; } - // mission command has been set and not as rewind command, don't track history. - if (!rewind) { - reset_wp_history(); - } + // mission command has been set, don't track history. + reset_wp_history(); // sanity check index and that we have a mission if (index >= (unsigned)_cmd_total || _cmd_total == 1) { diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index e01c372ffa3c16..587b690e9b3ad8 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -601,7 +601,7 @@ class AP_Mission } // set_current_cmd - jumps to command specified by index - bool set_current_cmd(uint16_t index, bool rewind = false); + bool set_current_cmd(uint16_t index); // restart current navigation command. Used to handle external changes to mission // returns true on success, false if current nav command has been deleted From 0567d8576e44378cbb6a26f7969e8dbe14a75fc1 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Thu, 28 Sep 2023 11:09:18 +1000 Subject: [PATCH 138/499] GCS_MAVLink: Add explicit handling of DO_JUMP_TAG --- libraries/GCS_MAVLink/GCS.h | 1 + libraries/GCS_MAVLink/GCS_Common.cpp | 32 ++++++++++++++++++++++------ 2 files changed, 26 insertions(+), 7 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 7dbd32ef4be56e..897ef275e06ea1 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -639,6 +639,7 @@ class GCS_MAVLINK virtual MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg); virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_do_jump_tag(const mavlink_command_long_t &packet); MAV_RESULT handle_command_battery_reset(const mavlink_command_int_t &packet); void handle_command_long(const mavlink_message_t &msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 371f16a8641a74..93b2f53c0b3a95 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4452,8 +4452,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_i // the current waypoint, rather than this DO command. It is hoped we // can move to this command in the future to avoid acknowledgement // issues with MISSION_SET_CURRENT -// This also handles DO_JUMP_TAG by converting the tag to an index -// and setting the index as if it was a normal do_set_mission_current MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_command_long_t &packet) { AP_Mission *mission = AP::mission(); @@ -4462,11 +4460,28 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_comm } const uint32_t seq = (uint32_t)packet.param1; - if (packet.command == MAV_CMD_DO_JUMP_TAG) { - if (!mission->jump_to_tag(seq)) { - return MAV_RESULT_FAILED; - } - } else if (!mission->set_current_cmd(seq)) { + if (!mission->set_current_cmd(seq)) { + return MAV_RESULT_FAILED; + } + + // volunteer the new current waypoint for all listeners + send_message(MSG_CURRENT_WAYPOINT); + + return MAV_RESULT_ACCEPTED; +} + +MAV_RESULT GCS_MAVLINK::handle_command_do_jump_tag(const mavlink_command_long_t &packet) +{ + AP_Mission *mission = AP::mission(); + if (mission == nullptr) { + return MAV_RESULT_UNSUPPORTED; + } + + const uint32_t tag = (uint32_t)packet.param1; + if (tag > UINT16_MAX) { + return MAV_RESULT_DENIED; + } + if (!mission->jump_to_tag(tag)) { return MAV_RESULT_FAILED; } @@ -4735,6 +4750,9 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t #endif case MAV_CMD_DO_JUMP_TAG: + result = handle_command_do_jump_tag(packet); + break; + case MAV_CMD_DO_SET_MISSION_CURRENT: result = handle_command_do_set_mission_current(packet); break; From a29cd0321b38d2447da47ff71b54f4d28f214308 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Thu, 28 Sep 2023 11:10:29 +1000 Subject: [PATCH 139/499] AP_Mission: Add is_valid_index() function --- libraries/AP_Mission/AP_Mission.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index 587b690e9b3ad8..b50fa4d9822b0b 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -724,6 +724,8 @@ class AP_Mission // Returns 0 if no appropriate JUMP_TAG match can be found. uint16_t get_index_of_jump_tag(const uint16_t tag) const; + bool is_valid_index(const uint16_t index) const { return index < _cmd_total; } + #if AP_SDCARD_STORAGE_ENABLED bool failed_sdcard_storage(void) const { return _failed_sdcard_storage; From 59c509281048c3bb486ba640e907df3cf0cc6345 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Thu, 28 Sep 2023 11:12:29 +1000 Subject: [PATCH 140/499] GCS_MAVLink: Handle param2 (reset) in DO_SET_MISSION_CURRENT cmd --- libraries/GCS_MAVLink/GCS_Common.cpp | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 93b2f53c0b3a95..19b33b06c56a8e 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4460,9 +4460,24 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_comm } const uint32_t seq = (uint32_t)packet.param1; + if (!mission->is_valid_index(seq)) { + return MAV_RESULT_DENIED; + } + + // From https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_MISSION_CURRENT: + // Param 2: Reset Mission + // - Resets mission. 1: true, 0: false. Resets jump counters to initial values + // and changes mission state "completed" to be "active" or "paused". + const bool reset_and_restart = is_equal(packet.param2, 1.0f); + if (reset_and_restart) { + mission->reset(); + } if (!mission->set_current_cmd(seq)) { return MAV_RESULT_FAILED; } + if (reset_and_restart) { + mission->resume(); + } // volunteer the new current waypoint for all listeners send_message(MSG_CURRENT_WAYPOINT); From e2e05af9146d3bb5cee0dac040a9a3bf589b88d6 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Mon, 9 Oct 2023 11:05:51 +1100 Subject: [PATCH 141/499] autotest: Add test for handling of param2 (reset) of DO_SET_MISSION_CURRENT --- Tools/autotest/arducopter.py | 25 +++++++++++++++++++++++++ Tools/autotest/vehicle_test_suite.py | 2 ++ 2 files changed, 27 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 1cb332597dfa97..02fe61759823cd 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -3226,6 +3226,30 @@ def FlyMissionTwice(self): self.wait_disarmed() self.delay_sim_time(20) + def FlyMissionTwiceWithReset(self): + '''Fly a mission twice in a row without changing modes in between. + Allow the mission to complete, then reset the mission state machine and restart the mission.''' + + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + + num_wp = self.get_mission_count() + self.set_parameter("AUTO_OPTIONS", 3) + self.change_mode('AUTO') + self.wait_ready_to_arm() + + for i in 1, 2: + self.progress("run %u" % i) + # Use the "Reset Mission" param of DO_SET_MISSION_CURRENT to reset mission state machine + self.set_current_waypoint_using_mav_cmd_do_set_mission_current(seq=0, reset=1) + self.arm_vehicle() + self.wait_waypoint(num_wp-1, num_wp-1) + self.wait_disarmed() + self.delay_sim_time(20) + def GPSViconSwitching(self): """Fly GPS and Vicon switching test""" self.customise_SITL_commandline(["--uartF=sim:vicon:"]) @@ -10544,6 +10568,7 @@ def tests2b(self): # this block currently around 9.5mins here self.ThrottleGainBoost, self.ScriptMountPOI, self.FlyMissionTwice, + self.FlyMissionTwiceWithReset, self.IMUConsistency, self.AHRSTrimLand, self.GuidedYawRate, diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index be940085b3b3d8..9985b72ea1ac3d 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -5911,10 +5911,12 @@ def run_cmd_get_ack(self, command, want_result, timeout, quiet=False, mav=None, def set_current_waypoint_using_mav_cmd_do_set_mission_current( self, seq, + reset=0, target_sysid=1, target_compid=1): self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT, p1=seq, + p2=reset, timeout=1, target_sysid=target_sysid, target_compid=target_compid) From b96acbc97e189a336e5a0438f98238656843bda1 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Mon, 9 Oct 2023 11:08:03 +1100 Subject: [PATCH 142/499] autotest: Test when invalid item is selected via DO_SET_MISSION_CURRENT --- Tools/autotest/arducopter.py | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 02fe61759823cd..cbe3f29592bc6e 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -3250,6 +3250,31 @@ def FlyMissionTwiceWithReset(self): self.wait_disarmed() self.delay_sim_time(20) + def MissionIndexValidity(self): + '''Confirm that attempting to select an invalid mission item is rejected.''' + + self.upload_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 20, 0, 20), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + + num_wp = self.get_mission_count() + accepted_indices = [0, 1, num_wp-1] + denied_indices = [-1, num_wp] + + for seq in accepted_indices: + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT, + p1=seq, + timeout=1, + want_result=mavutil.mavlink.MAV_RESULT_ACCEPTED) + + for seq in denied_indices: + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_SET_MISSION_CURRENT, + p1=seq, + timeout=1, + want_result=mavutil.mavlink.MAV_RESULT_DENIED) + def GPSViconSwitching(self): """Fly GPS and Vicon switching test""" self.customise_SITL_commandline(["--uartF=sim:vicon:"]) @@ -10569,6 +10594,7 @@ def tests2b(self): # this block currently around 9.5mins here self.ScriptMountPOI, self.FlyMissionTwice, self.FlyMissionTwiceWithReset, + self.MissionIndexValidity, self.IMUConsistency, self.AHRSTrimLand, self.GuidedYawRate, From 64e6a85e4b38be1ec4629edb7d0f97c69676b5d9 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Mon, 9 Oct 2023 11:08:30 +1100 Subject: [PATCH 143/499] autotest: Test when invalid tag is selected via DO_JUMP_TAG --- Tools/autotest/arducopter.py | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index cbe3f29592bc6e..f77e3cb5b9dc5f 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -3275,6 +3275,22 @@ def MissionIndexValidity(self): timeout=1, want_result=mavutil.mavlink.MAV_RESULT_DENIED) + def InvalidJumpTags(self): + '''Verify the behaviour when selecting invalid jump tags.''' + + MAX_TAG_NUM = 65535 + # Jump tag is not present, so expect FAILED + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_JUMP_TAG, + p1=MAX_TAG_NUM, + timeout=1, + want_result=mavutil.mavlink.MAV_RESULT_FAILED) + + # Jump tag is too big, so expect DENIED + self.run_cmd(mavutil.mavlink.MAV_CMD_DO_JUMP_TAG, + p1=MAX_TAG_NUM+1, + timeout=1, + want_result=mavutil.mavlink.MAV_RESULT_DENIED) + def GPSViconSwitching(self): """Fly GPS and Vicon switching test""" self.customise_SITL_commandline(["--uartF=sim:vicon:"]) @@ -10595,6 +10611,7 @@ def tests2b(self): # this block currently around 9.5mins here self.FlyMissionTwice, self.FlyMissionTwiceWithReset, self.MissionIndexValidity, + self.InvalidJumpTags, self.IMUConsistency, self.AHRSTrimLand, self.GuidedYawRate, From 55d796537902dc7242953ec1467e2d26c915d48d Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Fri, 13 Oct 2023 11:18:28 +1100 Subject: [PATCH 144/499] autotest: Rover: fix return type for invalid DO_SET_MISSION_CURRENT --- Tools/autotest/rover.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index ab13d592fc7679..c82dca3c0210e6 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6055,7 +6055,7 @@ def MAV_CMD_DO_SET_MISSION_CURRENT(self, target_sysid=None, target_compid=1): timeout=1, target_sysid=target_sysid, target_compid=target_compid, - want_result=mavutil.mavlink.MAV_RESULT_FAILED, + want_result=mavutil.mavlink.MAV_RESULT_DENIED, ) def FlashStorage(self): From 5bd67d8e04a67133f9d547bce582c009d88d3544 Mon Sep 17 00:00:00 2001 From: Gone4Dirt Date: Sun, 1 Oct 2023 18:45:39 +0100 Subject: [PATCH 145/499] AP_Motors: Set default heli thrust linearisation to linear. --- libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp b/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp index a87e85c6c7aa77..92d4f800c9b676 100644 --- a/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp +++ b/libraries/AP_Motors/AP_Motors_Thrust_Linearization.cpp @@ -17,9 +17,10 @@ #endif #if APM_BUILD_TYPE(APM_BUILD_Heli) - #define THRST_LIN_THST_EXPO_DEFAULT 0.55f // set to 0 for linear and 1 for second order approximation - #define THRST_LIN_SPIN_MIN_DEFAULT 0.15f // throttle out ratio which produces the minimum thrust. (i.e. 0 ~ 1 ) of the full throttle range - #define THRST_LIN_SPIN_MAX_DEFAULT 0.95f // throttle out ratio which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range + // defaults to no linearisation to not break users existing setups + #define THRST_LIN_THST_EXPO_DEFAULT 0.0f // set to 0 for linear and 1 for second order approximation + #define THRST_LIN_SPIN_MIN_DEFAULT 0.0f // throttle out ratio which produces the minimum thrust. (i.e. 0 ~ 1 ) of the full throttle range + #define THRST_LIN_SPIN_MAX_DEFAULT 1.0f // throttle out ratio which produces the maximum thrust. (i.e. 0 ~ 1 ) of the full throttle range #define THRST_LIN_BAT_VOLT_MAX_DEFAULT 0.0f // voltage limiting max default #define THRST_LIN_BAT_VOLT_MIN_DEFAULT 0.0f // voltage limiting min default (voltage dropping below this level will have no effect) #else From 927418b87c018d6970a0e668e85265d3a1a31793 Mon Sep 17 00:00:00 2001 From: Gone4Dirt Date: Sun, 1 Oct 2023 18:48:45 +0100 Subject: [PATCH 146/499] AP_Motors_Heli: Fix DDFP thrust linearisation by using min max pwm in servo library AP_Motors_Heli: Add H_YAW_TRIM param conversion for DDFP tails --- libraries/AP_Motors/AP_MotorsHeli.h | 3 + libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 106 +++++++++++++------ libraries/AP_Motors/AP_MotorsHeli_Single.h | 11 +- 3 files changed, 81 insertions(+), 39 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index c32ed28f1cff40..7cf311a84ca50d 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -162,6 +162,9 @@ class AP_MotorsHeli : public AP_Motors { // output_test_seq - disabled on heli, do nothing void _output_test_seq(uint8_t motor_seq, int16_t pwm) override {}; + // Helper function for param conversions to be done in motors class + virtual void heli_motors_param_conversions(void) { return; } + // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index 5cdb3a58b527f4..2fa953ee5915d7 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -176,6 +176,13 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = { // @User: Standard AP_SUBGROUPINFO(thr_lin, "DDFP_", 22, AP_MotorsHeli_Single, Thrust_Linearization), + // @Param: YAW_TRIM + // @DisplayName: Tail Rotor Trim + // @Description: Fixed offset applied to yaw output to minimize yaw I-term contribution needed to counter rotor drag. Currently only works of DDFP tails (H_TAIL_TYPE = 3 or H_TAIL_TYPE = 4). If using the H_COL2YAW compensation this trim is used to compensate for the main rotor profile drag. If H_COL2YAW is not used, this value can be set to reduce the yaw I contribution to zero when in a steady hover. + // @Range: 0 1 + // @User: Standard + AP_GROUPINFO("YAW_TRIM", 23, AP_MotorsHeli_Single, _yaw_trim, 0.0f), + AP_GROUPEND }; @@ -216,7 +223,10 @@ void AP_MotorsHeli_Single::init_outputs() SRV_Channels::set_output_min_max(SRV_Channels::get_motor_function(AP_MOTORS_HELI_SINGLE_EXTGYRO), 1000, 2000); } - if (_tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) { + if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { + // DDFP tails use range as it is easier to ignore servo trim in making for simple implementation of thrust linearisation. + SRV_Channels::set_range(SRV_Channel::k_motor4, 1.0f); + } else if (_tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) { // yaw servo is an angle from -4500 to 4500 SRV_Channels::set_angle(SRV_Channel::k_motor4, YAW_SERVO_MAX_ANGLE); } @@ -423,6 +433,11 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float // This feedforward compensation follows the hover performance theory that hover power required // is a function of gross weight to the 3/2 power yaw_offset = _collective_yaw_scale * powf(fabsf(collective_out - _collective_zero_thrust_pct),1.5f); + + // Add yaw trim for DDFP tails + if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { + yaw_offset += _yaw_trim.get(); + } } } else { yaw_offset = 0.0f; @@ -490,66 +505,61 @@ void AP_MotorsHeli_Single::output_to_motors() thr_lin.update_lift_max_from_batt_voltage(); } + // Warning: This spool state logic is what prevents DDFP tails from actuating when doing H_SV_MAN and H_SV_TEST tests switch (_spool_state) { case SpoolState::SHUT_DOWN: // sends minimum values out to the motors update_motor_control(ROTOR_CONTROL_STOP); - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW){ - rc_write(AP_MOTORS_MOT_4, calculate_ddfp_output(0.0f)); + if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { + // Set DDFP to servo min + output_to_ddfp_tail(0.0); } break; case SpoolState::GROUND_IDLE: // sends idle output to motors when armed. rotor could be static or turning (autorotation) update_motor_control(ROTOR_CONTROL_IDLE); - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW){ - rc_write(AP_MOTORS_MOT_4, calculate_ddfp_output(0.0f)); + if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { + // Set DDFP to servo min + output_to_ddfp_tail(0.0); } break; case SpoolState::SPOOLING_UP: case SpoolState::THROTTLE_UNLIMITED: // set motor output based on thrust requests update_motor_control(ROTOR_CONTROL_ACTIVE); - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW){ - SRV_Channel *c = SRV_Channels::srv_channel(AP_MOTORS_MOT_4); - if (c != nullptr) { - _ddfp_pwm_min = c->get_output_min(); - _ddfp_pwm_max = c->get_output_max(); - _ddfp_pwm_trim = c->get_trim(); - } - float servo_out = 0.0f; - if (is_positive((float) (_ddfp_pwm_max - _ddfp_pwm_min))) { - float servo4_trim = constrain_float((_ddfp_pwm_trim - 1000) / (_ddfp_pwm_max - _ddfp_pwm_min), 0.0f, 1.0f); - if (is_positive(_servo4_out)) { - servo_out = (1.0f - servo4_trim) * _servo4_out + servo4_trim; - } else { - servo_out = servo4_trim * _servo4_out + servo4_trim; - } - } else { - // if servo pwm min and max are bad, convert servo4_out from -1 to 1 to 0 to 1 - servo_out = 0.5f * (_servo4_out + 1.0f); - // this should never happen - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } - // output yaw servo to tail rsc - rc_write(AP_MOTORS_MOT_4, calculate_ddfp_output(thr_lin.thrust_to_actuator(constrain_float(servo_out, 0.0f, 1.0f)))); + if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { + // Operate DDFP to between DDFP_SPIN_MIN and DDFP_SPIN_MAX using thrust linearisation + output_to_ddfp_tail(thr_lin.thrust_to_actuator(_servo4_out)); } break; case SpoolState::SPOOLING_DOWN: // sends idle output to motors and wait for rotor to stop update_motor_control(ROTOR_CONTROL_IDLE); if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW){ - rc_write(AP_MOTORS_MOT_4, calculate_ddfp_output(0.0f)); + // Set DDFP to servo min + output_to_ddfp_tail(0.0); } break; - } } -// calculate the motor output for DDFP tails from yaw_out -uint16_t AP_MotorsHeli_Single::calculate_ddfp_output(float yaw_out) +// handle output limit flags and send throttle to servos lib +void AP_MotorsHeli_Single::output_to_ddfp_tail(float throttle) { - uint16_t ret = _ddfp_pwm_min + (_ddfp_pwm_max - _ddfp_pwm_min) * yaw_out; - return ret; + // Note: yaw trim thrust has already been applied. the output should only be from 0 to 1. + // Upper limit + if (throttle >= 1.0){ + throttle = 1.0; + limit.yaw = true; + } + + // Lower limit + if (throttle <= 0.0){ + throttle = 0.0; + limit.yaw = true; + } + + SRV_Channels::set_output_scaled(SRV_Channel::k_motor4, throttle); } // servo_test - move servos through full range of movement @@ -635,3 +645,31 @@ bool AP_MotorsHeli_Single::arming_checks(size_t buflen, char *buffer) const return true; } + +// Helper function for param conversions which are easier to be done in the motors class +// Called from system.cpp +void AP_MotorsHeli_Single::heli_motors_param_conversions(void) +{ + // PARAMETER_CONVERSION - Added: Nov-2023 + // Convert trim for DDFP tails + // Previous DDFP configs used servo trim for setting the yaw trim, which no longer works with thrust linearisation. Convert servo trim + // to H_YAW_TRIM. Default thrust linearisation gives linear thrust to throttle relationship to preserve previous setup behaviours so + // we can assume linear relationship in the conversion. + if ((_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || + _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) && + !_yaw_trim.configured()) { + + SRV_Channel *c = SRV_Channels::get_channel_for(SRV_Channel::k_motor4); + if (c != nullptr) { + uint16_t pwm_min = c->get_output_min(); + uint16_t pwm_max = c->get_output_max(); + uint16_t pwm_trim = c->get_trim(); + + float trim = (float)(pwm_trim - pwm_min) / constrain_uint16(pwm_max - pwm_min, 1, 2000); + _yaw_trim.set(trim); + } + // Motor 4 may not have been assigned to an output yet in which case this is unlikely to be a conversion from old setup. + // Prevent future attempts to convert the param so we don't put a non-sense value in. + _yaw_trim.save(); + } +} diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index ec67fa0ba11f47..595ce98a04f90e 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -80,6 +80,9 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { // Run arming checks bool arming_checks(size_t buflen, char *buffer) const override; + // Helper function for param conversions to be done in motors class + void heli_motors_param_conversions(void) override; + // Thrust Linearization handling Thrust_Linearization thr_lin {*this}; @@ -100,8 +103,8 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { // move_yaw - moves the yaw servo void move_yaw(float yaw_out); - // calculate the motor output for DDFP tails from yaw_out - uint16_t calculate_ddfp_output(float yaw_out); + // handle output limit flags and send throttle to servos lib + void output_to_ddfp_tail(float throttle); // servo_test - move servos through full range of movement void servo_test() override; @@ -118,9 +121,6 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { float _pitch_test = 0.0f; // over-ride for pitch output, used by servo_test function float _yaw_test = 0.0f; // over-ride for yaw output, used by servo_test function float _servo4_out = 0.0f; // output value sent to motor - uint16_t _ddfp_pwm_min = 0; // minimum ddfp servo min - uint16_t _ddfp_pwm_max = 0; // minimum ddfp servo max - uint16_t _ddfp_pwm_trim = 0; // minimum ddfp servo trim // parameters AP_Int16 _tail_type; // Tail type used: Servo, Servo with external gyro, direct drive variable pitch or direct drive fixed pitch @@ -129,6 +129,7 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { AP_Int8 _flybar_mode; // Flybar present or not. Affects attitude controller used during ACRO flight mode AP_Int16 _direct_drive_tailspeed; // Direct Drive VarPitch Tail ESC speed (0 ~ 1000) AP_Float _collective_yaw_scale; // Feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics. + AP_Float _yaw_trim; // Fixed offset applied to yaw output to reduce yaw I. bool _acro_tail = false; }; From 399398fe64ac685e70ae36a356dac13496ac4a83 Mon Sep 17 00:00:00 2001 From: Gone4Dirt Date: Wed, 1 Nov 2023 10:29:33 +0000 Subject: [PATCH 147/499] Copter: Add heli motors param conversion helper --- ArduCopter/system.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 221a92bb9a2700..6679766a3b41d7 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -524,6 +524,7 @@ void Copter::allocate_motors(void) convert_pid_parameters(); #if FRAME_CONFIG == HELI_FRAME convert_tradheli_parameters(); + motors->heli_motors_param_conversions(); #endif #if HAL_PROXIMITY_ENABLED From 2fe100d7bcaeea7a03597b4663b0871664fa49c2 Mon Sep 17 00:00:00 2001 From: Gone4Dirt Date: Sun, 1 Oct 2023 18:49:30 +0100 Subject: [PATCH 148/499] AP_Motors_Heli: white space --- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index 2fa953ee5915d7..fe13951f4d1dac 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -260,9 +260,9 @@ void AP_MotorsHeli_Single::calculate_armed_scalars() _main_rotor._rsc_mode.save(); _heliflags.save_rsc_mode = false; } - + // allow use of external governor autorotation bailout - if (_heliflags.in_autorotation) { + if (_heliflags.in_autorotation) { _main_rotor.set_autorotation_flag(_heliflags.in_autorotation); // set bailout ramp time _main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout); @@ -270,7 +270,7 @@ void AP_MotorsHeli_Single::calculate_armed_scalars() _tail_rotor.set_autorotation_flag(_heliflags.in_autorotation); _tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout); } - }else { + } else { _main_rotor.set_autorotation_flag(false); if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) { _tail_rotor.set_autorotation_flag(false); @@ -484,7 +484,7 @@ void AP_MotorsHeli_Single::output_to_motors() // Write swashplate outputs _swashplate.output(); - if (_tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW){ + if (_tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { rc_write_angle(AP_MOTORS_MOT_4, _servo4_out * YAW_SERVO_MAX_ANGLE); } if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) { @@ -500,7 +500,7 @@ void AP_MotorsHeli_Single::output_to_motors() _servo4_out = -_servo4_out; } - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW){ + if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { // calc filtered battery voltage and lift_max thr_lin.update_lift_max_from_batt_voltage(); } From aa8c477a26fea9034208a65fd937f70fab661ff3 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 30 Oct 2023 21:24:56 +0000 Subject: [PATCH 149/499] AP_Motors: Heli_Dual: refactor swashplate mixing --- libraries/AP_Motors/AP_MotorsHeli_Dual.cpp | 155 ++++++++++----------- libraries/AP_Motors/AP_MotorsHeli_Dual.h | 17 ++- 2 files changed, 82 insertions(+), 90 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 290a3f9a2e1ee2..06abef19c2f76b 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -302,81 +302,61 @@ void AP_MotorsHeli_Dual::calculate_scalars() calculate_armed_scalars(); } -// get_swashplate - calculate movement of each swashplate based on configuration -float AP_MotorsHeli_Dual::get_swashplate (int8_t swash_num, int8_t swash_axis, float pitch_input, float roll_input, float yaw_input, float coll_input) +// Mix and output swashplates for tandem +void AP_MotorsHeli_Dual::mix_tandem(float pitch_input, float roll_input, float yaw_input, float collective1_input, float collective2_input) { - float swash_tilt = 0.0f; - if (_dual_mode == AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE) { - // roll tilt - if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL) { - if (swash_num == 1) { - swash_tilt = 0.0f; - } else if (swash_num == 2) { - swash_tilt = 0.0f; - } - } else if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH) { - // pitch tilt - if (swash_num == 1) { - swash_tilt = pitch_input - _yaw_scaler * yaw_input; - } else if (swash_num == 2) { - swash_tilt = pitch_input + _yaw_scaler * yaw_input; - } - } else if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL) { - // collective - if (swash_num == 1) { - swash_tilt = 0.45f * _dcp_scaler * (roll_input + constrain_float(_dcp_trim, -0.2f, 0.2f)) + coll_input; - } else if (swash_num == 2) { - swash_tilt = -0.45f * _dcp_scaler * (roll_input + constrain_float(_dcp_trim, -0.2f, 0.2f)) + coll_input; - } - } - } else if (_dual_mode == AP_MOTORS_HELI_DUAL_MODE_INTERMESHING) { - // roll tilt - if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL) { - if (swash_num == 1) { - swash_tilt = roll_input; - } else if (swash_num == 2) { - swash_tilt = roll_input; - } - } else if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH) { - // pitch tilt - if (swash_num == 1) { - swash_tilt = pitch_input - _yaw_scaler * yaw_input; - } else if (swash_num == 2) { - swash_tilt = pitch_input + _yaw_scaler * yaw_input; - } - } else if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL) { - // collective - if (swash_num == 1) { - swash_tilt = 0.45f * _dcp_scaler * yaw_input + coll_input; - } else if (swash_num == 2) { - swash_tilt = -0.45f * _dcp_scaler * yaw_input + coll_input; - } - } - } else { // AP_MOTORS_HELI_DUAL_MODE_TANDEM - // roll tilt - if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL) { - if (swash_num == 1) { - swash_tilt = roll_input + _yaw_scaler * yaw_input; - } else if (swash_num == 2) { - swash_tilt = roll_input - _yaw_scaler * yaw_input; - } - } else if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH) { - // pitch tilt - if (swash_num == 1) { - swash_tilt = 0.0f; - } else if (swash_num == 2) { - swash_tilt = 0.0f; - } - } else if (swash_axis == AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL) { - // collective - if (swash_num == 1) { - swash_tilt = 0.45f * _dcp_scaler * (pitch_input + constrain_float(_dcp_trim, -0.2f, 0.2f)) + coll_input; - } else if (swash_num == 2) { - swash_tilt = -0.45f * _dcp_scaler * (pitch_input + constrain_float(_dcp_trim, -0.2f, 0.2f)) + coll_input; - } - } - } - return swash_tilt; + // Differential cyclic roll is used for yaw and combined for roll + const float swash1_roll = roll_input + _yaw_scaler * yaw_input; + const float swash2_roll = roll_input - _yaw_scaler * yaw_input; + + // cyclic is not used for pitch control + const float swash_pitch = 0.0; + + // Differential collective for pitch and combined for thrust + const float swash1_coll = 0.45 * _dcp_scaler * (pitch_input + constrain_float(_dcp_trim, -0.2, 0.2)) + collective1_input; + const float swash2_coll = -0.45 * _dcp_scaler * (pitch_input + constrain_float(_dcp_trim, -0.2, 0.2)) + collective2_input; + + // Calculate servo positions in swashplate library + _swashplate1.calculate(swash1_roll, swash_pitch, swash1_coll); + _swashplate2.calculate(swash2_roll, swash_pitch, swash2_coll); +} + +// Mix and output swashplates for transverse +void AP_MotorsHeli_Dual::mix_transverse(float pitch_input, float roll_input, float yaw_input, float collective1_input, float collective2_input) +{ + // cyclic is not used for roll control + const float swash_roll = 0.0; + + // Differential cyclic pitch is used for yaw + const float swash1_pitch = pitch_input - _yaw_scaler * yaw_input; + const float swash2_pitch = pitch_input + _yaw_scaler * yaw_input; + + // Differential collective for roll and combined for thrust + const float swash1_coll = 0.45 * _dcp_scaler * (roll_input + constrain_float(_dcp_trim, -0.2, 0.2)) + collective1_input; + const float swash2_coll = -0.45 * _dcp_scaler * (roll_input + constrain_float(_dcp_trim, -0.2, 0.2)) + collective2_input; + + // Calculate servo positions in swashplate library + _swashplate1.calculate(swash_roll, swash1_pitch, swash1_coll); + _swashplate2.calculate(swash_roll, swash2_pitch, swash2_coll); +} + +// Mix and output swashplates for intermeshing +void AP_MotorsHeli_Dual::mix_intermeshing(float pitch_input, float roll_input, float yaw_input, float collective1_input, float collective2_input) +{ + // Direct roll control on both swash plates + const float swash_roll = roll_input; + + // Differential cyclic pitch is used for yaw and combined for pitch + const float swash1_pitch = pitch_input - _yaw_scaler * yaw_input; + const float swash2_pitch = pitch_input + _yaw_scaler * yaw_input; + + // Differential collective for yaw and combined for thrust + const float swash1_coll = 0.45 * _dcp_scaler * yaw_input + collective1_input; + const float swash2_coll = -0.45 * _dcp_scaler * yaw_input + collective2_input; + + // Calculate servo positions in swashplate library + _swashplate1.calculate(swash_roll, swash1_pitch, swash1_coll); + _swashplate2.calculate(swash_roll, swash2_pitch, swash2_coll); } // update_motor_controls - sends commands to motor controllers @@ -516,17 +496,22 @@ void AP_MotorsHeli_Dual::move_actuators(float roll_out, float pitch_out, float c // ToDo: add main rotor cyclic power? _main_rotor.set_collective(fabsf(collective_out)); - // compute swashplate tilt - float swash1_pitch = get_swashplate(1, AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH, pitch_out, roll_out, yaw_out, collective_out_scaled); - float swash1_roll = get_swashplate(1, AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL, pitch_out, roll_out, yaw_out, collective_out_scaled); - float swash1_coll = get_swashplate(1, AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL, pitch_out, roll_out, yaw_out, collective_out_scaled); - float swash2_pitch = get_swashplate(2, AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH, pitch_out, roll_out, yaw_out, collective2_out_scaled); - float swash2_roll = get_swashplate(2, AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL, pitch_out, roll_out, yaw_out, collective2_out_scaled); - float swash2_coll = get_swashplate(2, AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL, pitch_out, roll_out, yaw_out, collective2_out_scaled); - - // Calculate servo positions in swashplate library - _swashplate1.calculate(swash1_roll, swash1_pitch, swash1_coll); - _swashplate2.calculate(swash2_roll, swash2_pitch, swash2_coll); + // Mix swash plate + switch (_dual_mode) { + case AP_MOTORS_HELI_DUAL_MODE_TANDEM: + default: + mix_tandem(pitch_out, roll_out, yaw_out, collective_out_scaled, collective2_out_scaled); + break; + + case AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE: + mix_transverse(pitch_out, roll_out, yaw_out, collective_out_scaled, collective2_out_scaled); + break; + + case AP_MOTORS_HELI_DUAL_MODE_INTERMESHING: + mix_intermeshing(pitch_out, roll_out, yaw_out, collective_out_scaled, collective2_out_scaled); + break; + + } } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.h b/libraries/AP_Motors/AP_MotorsHeli_Dual.h index 5fefd3201bdd1d..1c56e07367f6cc 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.h @@ -17,11 +17,6 @@ #define AP_MOTORS_HELI_DUAL_MODE_TRANSVERSE 1 // transverse mode (rotors side by side) #define AP_MOTORS_HELI_DUAL_MODE_INTERMESHING 2 // intermeshing mode (rotors side by side) -// tandem modes -#define AP_MOTORS_HELI_DUAL_SWASH_AXIS_PITCH 0 // swashplate pitch tilt axis -#define AP_MOTORS_HELI_DUAL_SWASH_AXIS_ROLL 1 // swashplate roll tilt axis -#define AP_MOTORS_HELI_DUAL_SWASH_AXIS_COLL 2 // swashplate collective axis - // default differential-collective-pitch scaler #define AP_MOTORS_HELI_DUAL_DCP_SCALER 0.25f @@ -110,4 +105,16 @@ class AP_MotorsHeli_Dual : public AP_MotorsHeli { // internal variables float _collective2_zero_thrst_pct; + +private: + + // Mix and output swashplates for tandem + void mix_tandem(float pitch_input, float roll_input, float yaw_input, float collective1_input, float collective2_input); + + // Mix and output swashplates for transverse + void mix_transverse(float pitch_input, float roll_input, float yaw_input, float collective1_input, float collective2_input); + + // Mix and output swashplates for intermeshing + void mix_intermeshing(float pitch_input, float roll_input, float yaw_input, float collective1_input, float collective2_input); + }; From 55242445b20330bcba4e1835b672d20188aca115 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 30 Oct 2023 22:21:44 +0000 Subject: [PATCH 150/499] AP_Motors: example: support setting and testing DUAL_MODE --- .../AP_Motors_test/AP_Motors_test.cpp | 9 + .../AP_Motors_test/run_heli_comparison.py | 227 ++++++++++-------- 2 files changed, 138 insertions(+), 98 deletions(-) diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index 48eb729434c07d..d65c940cd86f89 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -120,6 +120,15 @@ void setup() exit(1); } + } else if (strcmp(cmd,"dual_mode") == 0) { + if (frame_class != AP_Motors::MOTOR_FRAME_HELI_DUAL) { + ::printf("dual_mode only supported by dual heli frame type (%i), got %i\n", AP_Motors::MOTOR_FRAME_HELI_DUAL, frame_class); + exit(1); + } + + // look away now, more dodgy param access. + AP_Int8 *dual_mode = (AP_Int8*)motors + AP_MotorsHeli_Dual::var_info[1].offset; + dual_mode->set(value); } else if (strcmp(cmd,"frame_class") == 0) { // We must have the frame_class argument 2nd as resulting class is used to determine if diff --git a/libraries/AP_Motors/examples/AP_Motors_test/run_heli_comparison.py b/libraries/AP_Motors/examples/AP_Motors_test/run_heli_comparison.py index 69bdea9a6bb120..118a5de193fcb0 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/run_heli_comparison.py +++ b/libraries/AP_Motors/examples/AP_Motors_test/run_heli_comparison.py @@ -96,9 +96,12 @@ def get_fields(self): 4: 'H4_90', 5: 'H4_45'} +dual_mode_lookup = {0: 'Longitudinal', + 1: 'Transverse', + 2: 'Intermeshing_or_Coaxial'} # Run sweep over range of types -def run_sweep(frame_class, swash_type, dir_name): +def run_sweep(frame_class, swash_type, dual_mode, dir_name): # configure and build the test os.system('./waf configure --board linux') @@ -107,19 +110,29 @@ def run_sweep(frame_class, swash_type, dir_name): # Run sweep for fc in frame_class: for swash in swash_type: - if swash is not None: - name = 'frame class = %s (%i), swash = %s (%i)' % (frame_class_lookup[fc], fc, swash_type_lookup[swash], swash) - filename = '%s_%s_motor_test.csv' % (frame_class_lookup[fc], swash_type_lookup[swash]) - swash_cmd = 'swash=%d' % swash + for mode in dual_mode: + if swash is not None: + swash_cmd = 'swash=%d' % swash - else: - name = 'frame class = %s (%i)' % (frame_class_lookup[fc], fc) - filename = '%s_motor_test.csv' % (frame_class_lookup[fc]) - swash_cmd = '' + if mode is not None: + name = 'frame class = %s (%i), swash = %s (%i), dual mode = %s (%i)' % (frame_class_lookup[fc], fc, swash_type_lookup[swash], swash, dual_mode_lookup[mode], mode) + filename = '%s_%s_%s_motor_test.csv' % (frame_class_lookup[fc], swash_type_lookup[swash], dual_mode_lookup[mode]) + mode_cmd = 'dual_mode=%d' % mode - print('Running motors test for %s' % name) - os.system('./build/linux/examples/AP_Motors_test s frame_class=%d %s > %s/%s' % (fc, swash_cmd, dir_name, filename)) - print('%s complete\n' % name) + else: + name = 'frame class = %s (%i), swash = %s (%i)' % (frame_class_lookup[fc], fc, swash_type_lookup[swash], swash) + filename = '%s_%s_motor_test.csv' % (frame_class_lookup[fc], swash_type_lookup[swash]) + mode_cmd = '' + + else: + name = 'frame class = %s (%i)' % (frame_class_lookup[fc], fc) + filename = '%s_motor_test.csv' % (frame_class_lookup[fc]) + swash_cmd = '' + mode_cmd = '' + + print('Running motors test for %s' % name) + os.system('./build/linux/examples/AP_Motors_test s frame_class=%d %s %s > %s/%s' % (fc, swash_cmd, mode_cmd, dir_name, filename)) + print('%s complete\n' % name) if __name__ == '__main__': @@ -135,6 +148,7 @@ def run_sweep(frame_class, swash_type, dir_name): parser.add_argument("-s", "--swash-type", type=int, dest='swash_type', nargs="+", help="list of swashplate types to run comparison on. Defaults to test all types. Invalid for heli quad") parser.add_argument("-c", "--compare", action='store_true', help='Compare only, do not re-run tests') parser.add_argument("-p", "--plot", action='store_true', help='Plot comparison results') + parser.add_argument("-m", "--dual_mode", type=int, dest='dual_mode', help='Set DUAL_MODE, 0:Longitudinal, 1:Transverse, 2:Intermeshing/Coaxial, default:run all') args = parser.parse_args() if 13 in args.frame_class: @@ -147,6 +161,16 @@ def run_sweep(frame_class, swash_type, dir_name): if not args.swash_type: args.swash_type = (0, 1, 2, 3, 4, 5) + if (args.frame_class != [11]) and (args.dual_mode is not None): + print('Only Frame %s (%i) supports dual_mode' % (frame_class_lookup[11], 11)) + quit() + + if args.frame_class == [11]: + if args.dual_mode is None: + args.dual_mode = (0, 1, 2) + else: + args.dual_mode = [None] + dir_name = 'motors_comparison' if not args.compare: @@ -161,7 +185,7 @@ def run_sweep(frame_class, swash_type, dir_name): print('\nRunning motor tests with current changes\n') # run the test - run_sweep(args.frame_class, args.swash_type, new_name) + run_sweep(args.frame_class, args.swash_type, args.dual_mode, new_name) if args.head: # rewind head and repeat test @@ -213,91 +237,98 @@ def run_sweep(frame_class, swash_type, dir_name): # Print comparison for fc in args.frame_class: for sw in args.swash_type: - frame = frame_class_lookup[fc] - if sw is not None: - swash = swash_type_lookup[sw] - name = frame + ' ' + swash - filename = '%s_%s_motor_test.csv' % (frame, swash) - - else: - name = frame - filename = '%s_motor_test.csv' % (frame) - - print('%s:' % name) - - new_points = DataPoints(os.path.join(dir_name, 'new/%s' % filename)) - old_points = DataPoints(os.path.join(dir_name, 'original/%s' % filename)) - - if new_points.init_failed: - print('\t failed!\n') - - print('\tInputs max change:') - INPUTS = ['Roll', 'Pitch', 'Yaw', 'Thr'] - input_diff = {} - for field in INPUTS: - input_diff[field] = [i-j for i, j in zip(old_points.data[field], new_points.data[field])] - print('\t\t%s: %f' % (field, max(map(abs, input_diff[field])))) - - # Find number of motors - num_motors = 0 - while True: - num_motors += 1 - if 'Mot%i' % (num_motors+1) not in new_points.get_fields(): - break - - print('\tOutputs max change:') - output_diff = {} - for i in range(num_motors): - field = 'Mot%i' % (i+1) - output_diff[field] = [i-j for i, j in zip(old_points.data[field], new_points.data[field])] - print('\t\t%s: %f' % (field, max(map(abs, output_diff[field])))) - - print('\tLimits max change:') - LIMITS = ['LimR', 'LimP', 'LimY', 'LimThD', 'LimThU'] - limit_diff = {} - for field in LIMITS: - limit_diff[field] = [i-j for i, j in zip(old_points.data[field], new_points.data[field])] - print('\t\t%s: %f' % (field, max(map(abs, limit_diff[field])))) - print('\n') - - if not args.plot: - continue - - # Plot comparison - fig_size = (16, 8) - fig, ax = plt.subplots(2, 2, figsize=fig_size) - fig.suptitle('%s Input Diff' % name, fontsize=16) - ax = ax.flatten() - for i, field in enumerate(INPUTS): - ax[i].plot(input_diff[field], color=RED) - ax[i].set_xlabel('Test Number') - ax[i].set_ylabel('%s Old - New' % field) - plt.tight_layout(rect=[0, 0.0, 1, 0.95]) - - fig, ax = plt.subplots(2, num_motors, figsize=fig_size) - fig.suptitle('%s Outputs' % name, fontsize=16) - for i in range(num_motors): - field = 'Mot%i' % (i+1) - ax[0, i].plot(old_points.data[field], color=RED) - ax[0, i].plot(new_points.data[field], color=BLUE) - ax[0, i].set_ylabel(field) - ax[0, i].set_xlabel('Test No') - ax[1, i].plot(output_diff[field], color=BLACK) - ax[1, i].set_ylabel('Change in %s' % field) - ax[1, i].set_xlabel('Test No') - plt.tight_layout(rect=[0, 0.0, 1, 0.95]) - - fig, ax = plt.subplots(2, 5, figsize=fig_size) - fig.suptitle(name + ' Limits', fontsize=16) - for i, field in enumerate(LIMITS): - ax[0, i].plot(old_points.data[field], color=RED) - ax[0, i].plot(new_points.data[field], color=BLUE) - ax[0, i].set_ylabel(field) - ax[0, i].set_xlabel('Test No') - ax[1, i].plot(limit_diff[field], color=BLACK) - ax[1, i].set_ylabel('Change in %s' % field) - ax[1, i].set_xlabel('Test No') - plt.tight_layout(rect=[0, 0.0, 1, 0.95]) + for dm in args.dual_mode: + frame = frame_class_lookup[fc] + if sw is not None: + swash = swash_type_lookup[sw] + if dm is not None: + mode = dual_mode_lookup[dm] + name = frame + ' ' + swash + ' ' + mode + filename = '%s_%s_%s_motor_test.csv' % (frame, swash, mode) + + else: + name = frame + ' ' + swash + filename = '%s_%s_motor_test.csv' % (frame, swash) + + else: + name = frame + filename = '%s_motor_test.csv' % (frame) + + print('%s:' % name) + + new_points = DataPoints(os.path.join(dir_name, 'new/%s' % filename)) + old_points = DataPoints(os.path.join(dir_name, 'original/%s' % filename)) + + if new_points.init_failed: + print('\t failed!\n') + + print('\tInputs max change:') + INPUTS = ['Roll', 'Pitch', 'Yaw', 'Thr'] + input_diff = {} + for field in INPUTS: + input_diff[field] = [i-j for i, j in zip(old_points.data[field], new_points.data[field])] + print('\t\t%s: %f' % (field, max(map(abs, input_diff[field])))) + + # Find number of motors + num_motors = 0 + while True: + num_motors += 1 + if 'Mot%i' % (num_motors+1) not in new_points.get_fields(): + break + + print('\tOutputs max change:') + output_diff = {} + for i in range(num_motors): + field = 'Mot%i' % (i+1) + output_diff[field] = [i-j for i, j in zip(old_points.data[field], new_points.data[field])] + print('\t\t%s: %f' % (field, max(map(abs, output_diff[field])))) + + print('\tLimits max change:') + LIMITS = ['LimR', 'LimP', 'LimY', 'LimThD', 'LimThU'] + limit_diff = {} + for field in LIMITS: + limit_diff[field] = [i-j for i, j in zip(old_points.data[field], new_points.data[field])] + print('\t\t%s: %f' % (field, max(map(abs, limit_diff[field])))) + print('\n') + + if not args.plot: + continue + + # Plot comparison + fig_size = (16, 8) + fig, ax = plt.subplots(2, 2, figsize=fig_size) + fig.suptitle('%s Input Diff' % name, fontsize=16) + ax = ax.flatten() + for i, field in enumerate(INPUTS): + ax[i].plot(input_diff[field], color=RED) + ax[i].set_xlabel('Test Number') + ax[i].set_ylabel('%s Old - New' % field) + plt.tight_layout(rect=[0, 0.0, 1, 0.95]) + + fig, ax = plt.subplots(2, num_motors, figsize=fig_size) + fig.suptitle('%s Outputs' % name, fontsize=16) + for i in range(num_motors): + field = 'Mot%i' % (i+1) + ax[0, i].plot(old_points.data[field], color=RED) + ax[0, i].plot(new_points.data[field], color=BLUE) + ax[0, i].set_ylabel(field) + ax[0, i].set_xlabel('Test No') + ax[1, i].plot(output_diff[field], color=BLACK) + ax[1, i].set_ylabel('Change in %s' % field) + ax[1, i].set_xlabel('Test No') + plt.tight_layout(rect=[0, 0.0, 1, 0.95]) + + fig, ax = plt.subplots(2, 5, figsize=fig_size) + fig.suptitle(name + ' Limits', fontsize=16) + for i, field in enumerate(LIMITS): + ax[0, i].plot(old_points.data[field], color=RED) + ax[0, i].plot(new_points.data[field], color=BLUE) + ax[0, i].set_ylabel(field) + ax[0, i].set_xlabel('Test No') + ax[1, i].plot(limit_diff[field], color=BLACK) + ax[1, i].set_ylabel('Change in %s' % field) + ax[1, i].set_xlabel('Test No') + plt.tight_layout(rect=[0, 0.0, 1, 0.95]) if args.plot: plt.show() From 201c66e417f1cc2eb4db04d9f39d5fdc878cdd50 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 7 Nov 2023 20:50:37 -0700 Subject: [PATCH 151/499] AP_GPS: Fix GSOF autobaud detection msg Signed-off-by: Ryan Friedman --- libraries/AP_GPS/AP_GPS.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 34fd3f82f74b11..0b984bf1df709e 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -754,6 +754,11 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) dstate->auto_detected_baud = false; // specified, not detected return new AP_GPS_ExternalAHRS(*this, state[instance], nullptr); #endif +#if AP_GPS_GSOF_ENABLED + case GPS_TYPE_GSOF: + dstate->auto_detected_baud = false; // specified, not detected + return new AP_GPS_GSOF(*this, state[instance], _port[instance]); +#endif //AP_GPS_GSOF_ENABLED default: break; } @@ -803,10 +808,6 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) case GPS_TYPE_SBF: return new AP_GPS_SBF(*this, state[instance], _port[instance]); #endif //AP_GPS_SBF_ENABLED -#if AP_GPS_GSOF_ENABLED - case GPS_TYPE_GSOF: - return new AP_GPS_GSOF(*this, state[instance], _port[instance]); -#endif //AP_GPS_GSOF_ENABLED #if AP_GPS_NOVA_ENABLED case GPS_TYPE_NOVA: return new AP_GPS_NOVA(*this, state[instance], _port[instance]); From c4e2c4f7cba406b74ae2ffc4b174b44bf83670ce Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Fri, 10 Nov 2023 08:56:18 -0700 Subject: [PATCH 152/499] Tools: Expect different GSOF detection string Signed-off-by: Ryan Friedman --- Tools/autotest/vehicle_test_suite.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 9985b72ea1ac3d..d8eb3fb01548da 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -13181,7 +13181,7 @@ def GPSTypes(self): (6, "SBP", None, "SBP", 5, 'detected'), # (7, "SBP2", 9, "SBP2", 5), # broken, "waiting for config data" (8, "NOVA", 15, "NOVA", 5, 'detected'), # no attempt to auto-detect this in AP_GPS - (11, "GSOF", 11, "GSOF", 5, 'detected'), + (11, "GSOF", 11, "GSOF", 5, 'specified'), # no attempt to auto-detect this in AP_GPS (19, "MSP", 19, "MSP", 32, 'specified'), # no attempt to auto-detect this in AP_GPS # (9, "FILE"), ] From 61aec54ea77f7ffc3cadb60aa504e7907c193884 Mon Sep 17 00:00:00 2001 From: olliw42 Date: Wed, 8 Nov 2023 18:42:46 +0100 Subject: [PATCH 153/499] AP_RCTelemetry: throttle CRSF request RX device info messages --- libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp | 6 +++++- libraries/AP_RCTelemetry/AP_CRSF_Telem.h | 1 + 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp index cd21896afe7d7c..43f68c4c6a13f5 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp @@ -468,7 +468,11 @@ void AP_CRSF_Telem::process_packet(uint8_t idx) GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"%s: RX device ping failed", get_protocol_string()); } else { calc_device_ping(AP_RCProtocol_CRSF::CRSF_ADDRESS_CRSF_RECEIVER); - GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"%s: requesting RX device info", get_protocol_string()); + uint32_t tnow_ms = AP_HAL::millis(); + if ((tnow_ms - _crsf_version.last_request_info_ms) > 5000) { + _crsf_version.last_request_info_ms = tnow_ms; + GCS_SEND_TEXT(MAV_SEVERITY_DEBUG,"%s: requesting RX device info", get_protocol_string()); + } } break; case DEVICE_PING: diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.h b/libraries/AP_RCTelemetry/AP_CRSF_Telem.h index 9bbeeaf03a29b8..431ceebff7acfa 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.h +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.h @@ -335,6 +335,7 @@ class AP_CRSF_Telem : public AP_RCTelemetry { bool use_rf_mode; AP_RCProtocol_CRSF::ProtocolType protocol; bool pending = true; + uint32_t last_request_info_ms; } _crsf_version; struct { From 4681e5fba62ca973edd986ce046d11a84ccb5eee Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 9 Nov 2023 19:23:38 -0600 Subject: [PATCH 154/499] hwdef:correct JFB110 defaults --- .../AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm | 14 +------------- 1 file changed, 1 insertion(+), 13 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm index 0be0b0db513489..285c4f17142414 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm @@ -1,26 +1,14 @@ # board setting BRD_VBUS_MIN 4.9 -# setup SERIAL4 for BPort -SERIAL4_BAUD 57 -SERIAL4_PROTOCOL -1 -SERIAL4_OPTIONS 0 -# setup SERIAL5 to RCIN -SERIAL5_BAUD 100 -SERIAL5_PROTOCOL 23 -SERIAL5_OPTIONS 3 # setup SERIAL6 to SBUS OUT SERIAL6_BAUD 100 SERIAL6_PROTOCOL 15 SERIAL6_OPTIONS 3 -# setup SERIAL7 for debug console -SERIAL7_BAUD 921 -SERIAL7_PROTOCOL 0 -SERIAL7_OPTIONS 0 #Three IMU Setting EK3_IMU_MASK 7 -INS_ENABLE_MASK 7 + #RSSI Setting RSSI_TYPE 1 From 0f0bc78de9d33bb599dc4d73211b4493d15f5ae6 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 10 Nov 2023 17:19:44 +0900 Subject: [PATCH 155/499] AP_OpticalFlow: increase scaler param desc ranges --- libraries/AP_OpticalFlow/AP_OpticalFlow.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp index 8739e0282fd1dd..137a5778b55c8f 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp @@ -39,7 +39,7 @@ const AP_Param::GroupInfo AP_OpticalFlow::var_info[] = { // @Param: _FXSCALER // @DisplayName: X axis optical flow scale factor correction // @Description: This sets the parts per thousand scale factor correction applied to the flow sensor X axis optical rate. It can be used to correct for variations in effective focal length. Each positive increment of 1 increases the scale factor applied to the X axis optical flow reading by 0.1%. Negative values reduce the scale factor. - // @Range: -200 +200 + // @Range: -800 +800 // @Increment: 1 // @User: Standard AP_GROUPINFO("_FXSCALER", 1, AP_OpticalFlow, _flowScalerX, 0), @@ -47,7 +47,7 @@ const AP_Param::GroupInfo AP_OpticalFlow::var_info[] = { // @Param: _FYSCALER // @DisplayName: Y axis optical flow scale factor correction // @Description: This sets the parts per thousand scale factor correction applied to the flow sensor Y axis optical rate. It can be used to correct for variations in effective focal length. Each positive increment of 1 increases the scale factor applied to the Y axis optical flow reading by 0.1%. Negative values reduce the scale factor. - // @Range: -200 +200 + // @Range: -800 +800 // @Increment: 1 // @User: Standard AP_GROUPINFO("_FYSCALER", 2, AP_OpticalFlow, _flowScalerY, 0), From ef6105c5e0e1265f9f5d5711c17ce2eca1a9f5b4 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Fri, 10 Nov 2023 23:01:10 -0700 Subject: [PATCH 156/499] AP_ExternalAHRS: Specify brand on all log messages * The VN driver was likely written before there were multiple types * The log messages make it seem like core AHRS problems rather than issues directly with VN Signed-off-by: Ryan Friedman --- libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index b8eaf3a4ac500d..8e8515b70aa17d 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -176,7 +176,7 @@ AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend, auto &sm = AP::serialmanager(); uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0); if (!uart) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ExternalAHRS no UART"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VectorNav ExternalAHRS no UART"); return; } baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0); @@ -188,13 +188,13 @@ AP_ExternalAHRS_VectorNav::AP_ExternalAHRS_VectorNav(AP_ExternalAHRS *_frontend, last_pkt2 = new VN_packet2; if (!pktbuf || !last_pkt1 || !last_pkt2) { - AP_BoardConfig::allocation_error("ExternalAHRS"); + AP_BoardConfig::allocation_error("VectorNav ExternalAHRS"); } if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_VectorNav::update_thread, void), "AHRS", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) { - AP_HAL::panic("Failed to start ExternalAHRS update thread"); + AP_HAL::panic("VectorNav Failed to start ExternalAHRS update thread"); } - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ExternalAHRS initialised"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "VectorNav ExternalAHRS initialised"); } /* From ef5eccdf627305b970210abfca7fd3c90fd84831 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 11 Nov 2023 21:54:00 +0000 Subject: [PATCH 157/499] AP_HAL: correct neopixel bitwidth --- libraries/AP_HAL/RCOutput.h | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index 366b13963a481d..0104817c2040fb 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -406,6 +406,7 @@ class AP_HAL::RCOutput { // neopixel does not use pulse widths at all static constexpr uint32_t PROFI_BIT_0_TICKS = 7; static constexpr uint32_t PROFI_BIT_1_TICKS = 14; + static constexpr uint32_t PROFI_BIT_WIDTH_TICKS = 20; // suitably long LED output period to support high LED counts static constexpr uint32_t LED_OUTPUT_PERIOD_US = 10000; From 7639761d28635c3d0ad004d96f6746de477fa14f Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 11 Nov 2023 21:54:15 +0000 Subject: [PATCH 158/499] AP_HAL_ChibiOS: correct neopixel bitwidth Use 64-bit timestamps for dshot send checks --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 7 +++++-- libraries/AP_HAL_ChibiOS/RCOutput.h | 2 +- 2 files changed, 6 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 1163b903eab2a1..223e5844d873f8 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -1071,6 +1071,7 @@ void RCOutput::set_group_mode(pwm_group &group) #if HAL_SERIALLED_ENABLED { uint8_t bits_per_pixel = 24; + uint32_t bit_width = NEOP_BIT_WIDTH_TICKS; bool active_high = true; if (!start_led_thread()) { @@ -1080,6 +1081,7 @@ void RCOutput::set_group_mode(pwm_group &group) if (group.current_mode == MODE_PROFILED) { bits_per_pixel = 25; + bit_width = PROFI_BIT_WIDTH_TICKS; active_high = false; } @@ -1094,7 +1096,7 @@ void RCOutput::set_group_mode(pwm_group &group) // calculate min time between pulses taking into account the DMAR parallelism const uint32_t pulse_time_us = 1000000UL * bit_length / rate; - if (!setup_group_DMA(group, rate, NEOP_BIT_WIDTH_TICKS, active_high, buffer_length, pulse_time_us, false)) { + if (!setup_group_DMA(group, rate, bit_width, active_high, buffer_length, pulse_time_us, false)) { group.current_mode = MODE_PWM_NONE; break; } @@ -1698,7 +1700,8 @@ bool RCOutput::serial_led_send(pwm_group &group) } #if HAL_DSHOT_ENABLED - if (soft_serial_waiting() || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE)) { + if (soft_serial_waiting() || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE) + || AP_HAL::micros64() - group.last_dmar_send_us < (group.dshot_pulse_time_us + 50)) { // doing serial output or DMAR input, don't send DShot pulses return false; } diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 5dd9e84643f7cc..b0984b3bfdd8f9 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -414,7 +414,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput #endif // HAL_WITH_BIDIR_DSHOT // are we safe to send another pulse? bool can_send_dshot_pulse() const { - return is_dshot_protocol(current_mode) && AP_HAL::micros() - last_dmar_send_us > (dshot_pulse_time_us + 50); + return is_dshot_protocol(current_mode) && AP_HAL::micros64() - last_dmar_send_us > (dshot_pulse_time_us + 50); } // return whether the group channel is both enabled in the group and for output From 74c9520449663c28a52ac13f969ac7476159a79e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 14 Nov 2023 12:46:33 +1100 Subject: [PATCH 159/499] Plane: update release notes for 4.4.3 --- ArduPlane/ReleaseNotes.txt | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index 2dc429c325ad95..ffc5323e418edf 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -1,5 +1,5 @@ -Release 4.4.3-beta1 4th November 2023 -------------------------------------- +Release 4.4.3 14th November 2023 +-------------------------------- Changes from 4.4.2: @@ -14,6 +14,7 @@ Changes from 4.4.2: - protect against notch filtering with uninitialised RPM source in ESC telemetry - allow lua scripts to populate full ESC telemetry data - added YJUAV_A6SE_H743 support + - fixed uBlox M10 GPS support on boards with 1M flash Release 4.4.2 23th October 2023 ------------------------------- From 47521b145e9118ff5e4542527b44d4eec62ab1d5 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 14 Nov 2023 10:54:24 +0900 Subject: [PATCH 160/499] Rover: 4.4.0-beta10 release notes --- Rover/release-notes.txt | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Rover/release-notes.txt b/Rover/release-notes.txt index 95fa148ce58834..ed572d2ea1e262 100644 --- a/Rover/release-notes.txt +++ b/Rover/release-notes.txt @@ -1,7 +1,11 @@ Rover Release Notes: ------------------------------------------------------------------ +Rover 4.4.0-beta10 14-Nov-2023 +Changes from 4.4.0-beta9 +1) AP_GPS: correct uBlox M10 configuration on low flash boards +------------------------------------------------------------------ Rover 4.4.0-beta9 07-Nov-2023 -Changes from 4.4.2 +Changes from 4.4.0-beta8 1) Autopilot related enhancements and fixes - BETAFTP-F405 board configuration fixes - CubeOrangePlus-BG edition ICM45486 IMU setup fixed From 2e5af08a102d10b8b7d54414c7aa4f12f4a80ab9 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 14 Nov 2023 10:54:59 +0900 Subject: [PATCH 161/499] Copter: 4.4.3 release notes --- ArduCopter/ReleaseNotes.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index a0e77748da297c..70cf715b617ead 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,5 +1,9 @@ ArduPilot Copter Release Notes: ------------------------------------------------------------------ +Copter 4.4.3 14-Nov-2023 +Changes from 4.4.3-beta1 +1) AP_GPS: correct uBlox M10 configuration on low flash boards +------------------------------------------------------------------ Copter 4.4.3-beta1 07-Nov-2023 Changes from 4.4.2 1) Autopilot related enhancements and fixes From c17907cadc7dddf4607410104cca7a130ead6276 Mon Sep 17 00:00:00 2001 From: jfbblue0922 Date: Thu, 26 Oct 2023 16:55:03 +0900 Subject: [PATCH 162/499] AP_Math: add CRC crc16_ccitt_r function --- libraries/AP_Math/crc.cpp | 20 ++++++++++++++++++++ libraries/AP_Math/crc.h | 1 + 2 files changed, 21 insertions(+) diff --git a/libraries/AP_Math/crc.cpp b/libraries/AP_Math/crc.cpp index bc059535daefc4..ff320588ffa8bc 100644 --- a/libraries/AP_Math/crc.cpp +++ b/libraries/AP_Math/crc.cpp @@ -384,6 +384,26 @@ uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc) return crc; } +// CRC16_CCITT algorithm using right shift +uint16_t crc16_ccitt_r(const uint8_t *buf, uint32_t len, uint16_t crc, uint16_t out) +{ + for (uint32_t i = 0; i < len; i++) { + crc ^= *buf++; // XOR byte into least sig. byte of crc + for (uint8_t j = 0; j < 8; j++) { // loop over each bit + if ((crc & 0x0001) != 0) { // if the LSB is set + crc >>= 1; // shift right and XOR 0x8408 + crc ^= 0x8408; + } else { + crc >>= 1; // just shift right + } + } + } + + // output xor + crc = crc ^ out; + return crc; +} + uint16_t crc16_ccitt_GDL90(const uint8_t *buf, uint32_t len, uint16_t crc) { for (uint32_t i = 0; i < len; i++) { diff --git a/libraries/AP_Math/crc.h b/libraries/AP_Math/crc.h index 6850445b66bc6d..cf994a5c23c8b2 100644 --- a/libraries/AP_Math/crc.h +++ b/libraries/AP_Math/crc.h @@ -41,6 +41,7 @@ uint8_t crc_sum8(const uint8_t *p, uint8_t len); // Copyright (C) 2010 Swift Navigation Inc. // Contact: Fergus Noble uint16_t crc16_ccitt(const uint8_t *buf, uint32_t len, uint16_t crc); +uint16_t crc16_ccitt_r(const uint8_t *buf, uint32_t len, uint16_t crc, uint16_t out); // CRC16_CCITT algorithm using the GDL90 parser method which is non-standard // https://www.faa.gov/nextgen/programs/adsb/archival/media/gdl90_public_icd_reva.pdf From 2af98a949b07d7858dae60d91c1be4d77950cf41 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 8 Aug 2023 14:34:39 +1000 Subject: [PATCH 163/499] AP_HAL_SITL: add JAE JRE simulator --- libraries/AP_HAL_SITL/SITL_State_common.cpp | 9 +++++++++ libraries/AP_HAL_SITL/SITL_State_common.h | 3 +++ 2 files changed, 12 insertions(+) diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index 320fcf9615f78c..10b2103fb0221c 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -233,6 +233,12 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const sitl_model->set_ie24(&_sitl->ie24_sim); return &_sitl->ie24_sim; #endif // HAL_BUILD_AP_PERIPH + } else if (streq(name, "jre")) { + if (jre != nullptr) { + AP_HAL::panic("Only one jre at a time"); + } + jre = new SITL::RF_JRE(); + return jre; } else if (streq(name, "gyus42v2")) { if (gyus42v2 != nullptr) { AP_HAL::panic("Only one gyus42v2 at a time"); @@ -315,6 +321,9 @@ void SITL_State_Common::sim_update(void) if (benewake_tfmini != nullptr) { benewake_tfmini->update(sitl_model->rangefinder_range()); } + if (jre != nullptr) { + jre->update(sitl_model->rangefinder_range()); + } if (nooploop != nullptr) { nooploop->update(sitl_model->rangefinder_range()); } diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index dab0cb0e5aba70..bed95fd9ceca50 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -17,6 +17,7 @@ #include #include #include +#include #include #include #include @@ -126,6 +127,8 @@ class HALSITL::SITL_State_Common { SITL::RF_Benewake_TF02 *benewake_tf02; // simulated Benewake tf03 rangefinder: SITL::RF_Benewake_TF03 *benewake_tf03; + //simulated JAE JRE rangefinder: + SITL::RF_JRE *jre; // simulated Benewake tfmini rangefinder: SITL::RF_Benewake_TFmini *benewake_tfmini; //simulated NoopLoop TOFSense rangefinder: From 2a2a103195882fd4fa86aafdfb1c3f3d79df3976 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 8 Aug 2023 14:34:39 +1000 Subject: [PATCH 164/499] SITL: add JAE JRE simulator --- libraries/SITL/SIM_RF_JRE.cpp | 50 +++++++++++++++++++++++++++++++++++ libraries/SITL/SIM_RF_JRE.h | 46 ++++++++++++++++++++++++++++++++ 2 files changed, 96 insertions(+) create mode 100644 libraries/SITL/SIM_RF_JRE.cpp create mode 100644 libraries/SITL/SIM_RF_JRE.h diff --git a/libraries/SITL/SIM_RF_JRE.cpp b/libraries/SITL/SIM_RF_JRE.cpp new file mode 100644 index 00000000000000..ddf44c67b79e9e --- /dev/null +++ b/libraries/SITL/SIM_RF_JRE.cpp @@ -0,0 +1,50 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + Base class for simulator for the NoopLoop TOFSense-F/P Serial RangeFinders +*/ + +#include "SIM_RF_JRE.h" + +using namespace SITL; + +uint32_t RF_JRE::packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t buflen) +{ + uint16_t status = 0; + if (alt_cm > 50000) { + status |= 0x2; // NTRK, whatever that means... + } + + buffer[0] = 'R'; + buffer[1] = 'A'; + buffer[2] = 0x01; + buffer[3] = frame_count++; + buffer[4] = alt_cm >> 8; // altitide low + buffer[5] = alt_cm & 0xff; // Altitude-High, LSB + buffer[6] = 0x00; // reserved + buffer[7] = 0x00; // reserved + buffer[8] = 0x00; // reserved + buffer[9] = 0x00; // reserved + buffer[10] = 0x00; // FFT + buffer[11] = 0x00; // FFT + buffer[12] = status >> 8; // FFT + buffer[13] = status & 0xff; // FFT + + const uint16_t crc = crc16_ccitt_r(&buffer[0], 14, 0xffff, 0xffff); + buffer[14] = crc & 0xff; + buffer[15] = crc >> 8; + + return 16; +} diff --git a/libraries/SITL/SIM_RF_JRE.h b/libraries/SITL/SIM_RF_JRE.h new file mode 100644 index 00000000000000..d10c77a5258909 --- /dev/null +++ b/libraries/SITL/SIM_RF_JRE.h @@ -0,0 +1,46 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + Simulator for the JAE JRE radio altimiter + +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:jre --speedup=1 -L KalaupapaCliffs --map + +param set SERIAL5_PROTOCOL 9 +param set RNGFND1_TYPE 38 +reboot + +graph RANGEFINDER.distance + +arm throttle +rc 3 1600 + +*/ + +#pragma once + +#include "SIM_SerialRangeFinder.h" + +namespace SITL { + +class RF_JRE : public SerialRangeFinder { +public: + + uint32_t packet_for_alt(uint16_t alt_cm, uint8_t *buffer, uint8_t buflen) override; + +private: + uint8_t frame_count; // sequence number +}; + +} From aac949e2277c927204bf815144ea611473a41c19 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 14 Nov 2023 16:44:20 +1100 Subject: [PATCH 165/499] AP_Notify: add IS31FL3195 to default LED types --- libraries/AP_Notify/AP_Notify.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Notify/AP_Notify.cpp b/libraries/AP_Notify/AP_Notify.cpp index c24defb4953328..c085f31eb8adca 100644 --- a/libraries/AP_Notify/AP_Notify.cpp +++ b/libraries/AP_Notify/AP_Notify.cpp @@ -72,8 +72,14 @@ AP_Notify *AP_Notify::_singleton; #define ALL_LP5562_I2C 0 #endif +#if AP_NOTIFY_IS31FL3195_ENABLED +#define ALL_IS31FL3195_I2C (Notify_LED_IS31FL3195_I2C_Internal | Notify_LED_IS31FL3195_I2C_External) +#else +#define ALL_IS31FL3195_I2C 0 +#endif + // all I2C_LEDS -#define I2C_LEDS (ALL_TOSHIBALED_I2C | ALL_NCP5623_I2C | ALL_LP5562_I2C) +#define I2C_LEDS (ALL_TOSHIBALED_I2C | ALL_NCP5623_I2C | ALL_LP5562_I2C | ALL_IS31FL3195_I2C) #if AP_NOTIFY_DRONECAN_LED_ENABLED #define DRONECAN_LEDS Notify_LED_DroneCAN From 044760cfb941a833d9e843b40c60ab64ac945083 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 14 Nov 2023 16:46:30 +1100 Subject: [PATCH 166/499] AP_Notify: document IS31FL3195 LED type for LED_TYPES parameter --- libraries/AP_Notify/AP_Notify.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Notify/AP_Notify.cpp b/libraries/AP_Notify/AP_Notify.cpp index c085f31eb8adca..ad0dbe6d955755 100644 --- a/libraries/AP_Notify/AP_Notify.cpp +++ b/libraries/AP_Notify/AP_Notify.cpp @@ -213,7 +213,7 @@ const AP_Param::GroupInfo AP_Notify::var_info[] = { // @Param: LED_TYPES // @DisplayName: LED Driver Types // @Description: Controls what types of LEDs will be enabled - // @Bitmask: 0:Built-in LED, 1:Internal ToshibaLED, 2:External ToshibaLED, 3:External PCA9685, 4:Oreo LED, 5:DroneCAN, 6:NCP5623 External, 7:NCP5623 Internal, 8:NeoPixel, 9:ProfiLED, 10:Scripting, 11:DShot, 12:ProfiLED_SPI, 13:LP5562 External, 14: LP5562 Internal, 17: DiscreteRGB, 18: NeoPixelRGB + // @Bitmask: 0:Built-in LED, 1:Internal ToshibaLED, 2:External ToshibaLED, 3:External PCA9685, 4:Oreo LED, 5:DroneCAN, 6:NCP5623 External, 7:NCP5623 Internal, 8:NeoPixel, 9:ProfiLED, 10:Scripting, 11:DShot, 12:ProfiLED_SPI, 13:LP5562 External, 14: LP5562 Internal, 15:IS31FL3195 External, 16: IS31FL3195 Internal, 17: DiscreteRGB, 18: NeoPixelRGB // @User: Advanced AP_GROUPINFO("LED_TYPES", 6, AP_Notify, _led_type, DEFAULT_NTF_LED_TYPES), From 3f99891404b79428d71923133d36fdbabf55f0bc Mon Sep 17 00:00:00 2001 From: Jonathan Loong Date: Sun, 12 Nov 2023 21:46:51 -0800 Subject: [PATCH 167/499] AP_BattMonitor: Merge in polynomial fit structure to FuelLevel_Analog Update parameters and make current false --- .../AP_BattMonitor_FuelLevel_Analog.cpp | 56 +++++++++++++++++-- .../AP_BattMonitor_FuelLevel_Analog.h | 10 +++- 2 files changed, 59 insertions(+), 7 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp index f4276934521f94..9739068b9179f0 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp @@ -58,6 +58,42 @@ const AP_Param::GroupInfo AP_BattMonitor_FuelLevel_Analog::var_info[] = { // @Values: -1:Not Used,11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6/Pixhawk2 ADC,103:Pixhawk SBUS AP_GROUPINFO("FL_PIN", 43, AP_BattMonitor_FuelLevel_Analog, _pin, -1), + // @Param: FL_VLT_MAX + // @DisplayName: Full fuel level voltage + // @Description: The voltage seen on the analog pin when the fuel tank is full. + // @Range: 0 10 + // @Units: V + // @User: Advanced + AP_GROUPINFO("FL_VLT_MAX", 44, AP_BattMonitor_FuelLevel_Analog, _fuel_level_max_voltage, -1), + + // @Param: FL_FF + // @DisplayName: First order term + // @Description: First order polynomial fit term + // @Range: 0 10 + // @User: Advanced + AP_GROUPINFO("FL_FF", 45, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_first_order_coeff, 1), + + // @Param: FL_FS + // @DisplayName: Second order term + // @Description: Second order polynomial fit term + // @Range: 0 10 + // @User: Advanced + AP_GROUPINFO("FL_FS", 46, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_second_order_coeff, 0), + + // @Param: FL_FT + // @DisplayName: Third order term + // @Description: Third order polynomial fit term + // @Range: 0 10 + // @User: Advanced + AP_GROUPINFO("FL_FT", 47, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_third_order_coeff, 0), + + // @Param: FL_OFF + // @DisplayName: Offset term + // @Description: Offset polynomial fit term + // @Range: 0 10 + // @User: Advanced + AP_GROUPINFO("FL_OFF", 48, AP_BattMonitor_FuelLevel_Analog, _fuel_fit_offset, 0), + // Param indexes must be between 40 and 49 to avoid conflict with other battery monitor param tables loaded by pointer AP_GROUPEND @@ -96,16 +132,24 @@ void AP_BattMonitor_FuelLevel_Analog::read() const uint32_t tnow = AP_HAL::micros(); const uint32_t dt_us = tnow - _state.last_time_micros; - // get voltage from an ADC pin and filter it - const float voltage = _analog_source->voltage_average(); + // get voltage from an ADC pin + const float raw_voltage = _analog_source->voltage_average(); + + // Converting sensor reading to actual volume in tank in Litres (quadratic fit) + const float voltage = + (_fuel_fit_third_order_coeff * raw_voltage * raw_voltage * raw_voltage) + + (_fuel_fit_second_order_coeff * raw_voltage * raw_voltage) + + (_fuel_fit_first_order_coeff * raw_voltage) + + _fuel_fit_offset; + const float filtered_voltage = _voltage_filter.apply(voltage, float(dt_us) * 1.0e-6f); - const float &voltage_used = (_fuel_level_filter_frequency >= 0) ? filtered_voltage : voltage; // output the ADC voltage to the voltage field for easier calibration of sensors // also output filtered voltage as a measure of tank slosh filtering // this could be useful for tuning the LPF - _state.voltage = voltage; - _state.current_amps = filtered_voltage; + const float &voltage_used = (_fuel_level_filter_frequency >= 0) ? filtered_voltage : voltage; + + _state.voltage = filtered_voltage; // this driver assumes that CAPACITY is set to tank volume in millilitres. // _fuel_level_voltage_mult is calculated by the user as 1 / (full_voltage - empty_voltage) @@ -115,6 +159,8 @@ void AP_BattMonitor_FuelLevel_Analog::read() // map consumed_mah to consumed millilitres _state.consumed_mah = fuel_level_used_ratio * _params._pack_capacity; + _state.current_amps = 0; + // map consumed_wh using fixed voltage of 1 _state.consumed_wh = _state.consumed_mah; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h index 78acb0b4c693fb..58b35002b2897e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h @@ -23,6 +23,7 @@ #include #include "AP_BattMonitor.h" +#include // Filter library class AP_BattMonitor_FuelLevel_Analog : public AP_BattMonitor_Backend { @@ -40,20 +41,25 @@ class AP_BattMonitor_FuelLevel_Analog : public AP_BattMonitor_Backend bool has_consumed_energy() const override { return true; } // returns true if battery monitor provides current info - bool has_current() const override { return true; } + bool has_current() const override { return false; } void init(void) override {} private: AP_Float _fuel_level_empty_voltage; + AP_Float _fuel_level_max_voltage; AP_Float _fuel_level_voltage_mult; AP_Float _fuel_level_filter_frequency; AP_Int8 _pin; - + AP_Float _fuel_fit_first_order_coeff; + AP_Float _fuel_fit_second_order_coeff; + AP_Float _fuel_fit_third_order_coeff; + AP_Float _fuel_fit_offset; AP_HAL::AnalogSource *_analog_source; LowPassFilterFloat _voltage_filter; + }; #endif // AP_BATTERY_FUELLEVEL_ANALOG_ENABLED From 6fe9090367b883d07327383254bcc5bd52872aea Mon Sep 17 00:00:00 2001 From: Lokesh Ramina Date: Thu, 20 Jan 2022 23:37:33 -0800 Subject: [PATCH 168/499] Tools : Decode_devid Add Compass QMC5883P, AK09915 --- Tools/scripts/decode_devid.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/scripts/decode_devid.py b/Tools/scripts/decode_devid.py index 4d79b9d063d362..9b8a192e11ed09 100755 --- a/Tools/scripts/decode_devid.py +++ b/Tools/scripts/decode_devid.py @@ -64,6 +64,8 @@ def num(s): 0x12 : "DEVTYPE_RM3100", 0x13 : "DEVTYPE_MMC5883", 0x14 : "DEVTYPE_AK09918", + 0x15 : "DEVTYPE_AK09915", + 0x16 : "DEVTYPE_QMC5883P", } imu_types = { From 8d64d5215e9b082f736f4f3fda8cee5ee9768c36 Mon Sep 17 00:00:00 2001 From: Jonathan Loong Date: Mon, 9 Oct 2023 23:52:17 -0700 Subject: [PATCH 169/499] AP_Periph: CarbonixL496 crystal hwdef changes --- .../hwdef/CarbonixL496/hwdef-bl.dat | 12 ++++++------ .../hwdef/CarbonixL496/hwdef.dat | 19 +++++++------------ 2 files changed, 13 insertions(+), 18 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat index 9600da15a6bfd6..7c8895bd3fb310 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat @@ -15,8 +15,8 @@ APJ_BOARD_ID 1053 # setup build for a peripheral firmware env AP_PERIPH 1 -# crystal frequency set to 0 to use internal clock -OSCILLATOR_HZ 0 +# crystal frequency +OSCILLATOR_HZ 12000000 # assume 256k flash part FLASH_SIZE_KB 256 @@ -28,7 +28,7 @@ STDOUT_BAUDRATE 57600 SERIAL_ORDER OTG1 USART2 # a fault LED -PA15 LED_BOOTLOADER OUTPUT HIGH # blue +PA13 LED_BOOTLOADER OUTPUT HIGH # blue define HAL_LED_ON 0 # USART1 @@ -60,9 +60,9 @@ define HAL_DISABLE_LOOP_DELAY PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 -# debugger support -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD +# debugger support, disabled as PA13 used for LED +# PA13 JTMS-SWDIO SWD +# PA14 JTCK-SWCLK SWD # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat index 34782ac10c937c..c621a9f58bd269 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat @@ -18,8 +18,8 @@ env AP_PERIPH 1 # enable watchdog -# crystal frequency set to 0 to use internal clock -OSCILLATOR_HZ 0 +# crystal frequency +OSCILLATOR_HZ 12000000 # assume the 256k flash part FLASH_SIZE_KB 256 @@ -55,7 +55,7 @@ PA11 OTG_FS_DM OTG1 PA12 OTG_FS_DP OTG1 # LED, active low -PA15 LED OUTPUT HIGH GPIO(1) +PA13 LED OUTPUT HIGH GPIO(1) # spi2 PB10 SPI2_SCK SPI2 @@ -78,9 +78,9 @@ I2C_ORDER I2C4 # allow for reboot command for faster development define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 -# debugger support -PA13 JTMS-SWDIO SWD -PA14 JTCK-SWCLK SWD +# debugger support (disabled as conflicts with LED) +#PA13 JTMS-SWDIO SWD +#PA14 JTCK-SWCLK SWD define HAL_NO_GPIO_IRQ define SERIAL_BUFFERS_SIZE 512 @@ -138,9 +138,4 @@ define HAL_PERIPH_ADSB_PORT_DEFAULT 3 define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600 BARO MS56XX I2C:0:0x76 -COMPASS MMC5XX3 I2C:0:0x30 false ROTATION_NONE - - - - - +COMPASS QMC5883P I2C:0:0x2C false ROTATION_YAW_180 From 16c55a3bc1fce844f6e6742795329cc055a5af05 Mon Sep 17 00:00:00 2001 From: Jonathan Loong Date: Fri, 10 Nov 2023 19:50:31 -0800 Subject: [PATCH 170/499] AP_HAL_ChibiOS: Add in CarbonixF405 QMC5883P compass enable --- libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat index 2849e1e3bb9a67..6bfaadd6db61ce 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixF405/hwdef.dat @@ -137,6 +137,8 @@ define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600 BARO MS56XX I2C:0:0x76 COMPASS MMC5XX3 I2C:0:0x30 false ROTATION_NONE +define AP_COMPASS_QMC5883P_ENABLED 1 +COMPASS QMC5883P I2C:0:0x2C false ROTATION_YAW_180 From 0db1719c8fb3f4505b1cadbe252157da14875871 Mon Sep 17 00:00:00 2001 From: Jonathan Loong Date: Fri, 10 Nov 2023 20:00:55 -0800 Subject: [PATCH 171/499] AP_Compass: Add in QMC5883P Driver --- libraries/AP_Compass/AP_Compass.cpp | 21 ++ libraries/AP_Compass/AP_Compass.h | 5 +- libraries/AP_Compass/AP_Compass_Backend.h | 1 + libraries/AP_Compass/AP_Compass_QMC5883P.cpp | 221 +++++++++++++++++++ libraries/AP_Compass/AP_Compass_QMC5883P.h | 73 ++++++ libraries/AP_Compass/AP_Compass_config.h | 4 + 6 files changed, 324 insertions(+), 1 deletion(-) create mode 100644 libraries/AP_Compass/AP_Compass_QMC5883P.cpp create mode 100644 libraries/AP_Compass/AP_Compass_QMC5883P.h diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 5a0ef79dbe45d8..18d2cc9136c76c 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -27,6 +27,7 @@ #if AP_COMPASS_DRONECAN_ENABLED #include "AP_Compass_DroneCAN.h" #endif +#include "AP_Compass_QMC5883P.h" #include "AP_Compass_MMC3416.h" #include "AP_Compass_MMC5xx3.h" #include "AP_Compass_MAG3110.h" @@ -1132,6 +1133,26 @@ void Compass::_probe_external_i2c_compasses(void) #endif #endif // AP_COMPASS_QMC5883L_ENABLED +#if AP_COMPASS_QMC5883P_ENABLED + //external i2c bus + FOREACH_I2C_EXTERNAL(i) { + ADD_BACKEND(DRIVER_QMC5883P, AP_Compass_QMC5883P::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883P_I2C_ADDR), + true, HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL)); + } + + // internal i2c bus +#if !defined(HAL_SKIP_AUTO_INTERNAL_I2C_PROBE) + if (all_external) { + // only probe QMC5883P on internal if we are treating internals as externals + FOREACH_I2C_INTERNAL(i) { + ADD_BACKEND(DRIVER_QMC5883P, AP_Compass_QMC5883P::probe(GET_I2C_DEVICE(i, HAL_COMPASS_QMC5883P_I2C_ADDR), + all_external, + all_external?HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL:HAL_COMPASS_QMC5883P_ORIENTATION_INTERNAL)); + } + } +#endif +#endif // AP_COMPASS_QMC5883P_ENABLED + #ifndef HAL_BUILD_AP_PERIPH // AK09916 on ICM20948 #if AP_COMPASS_AK09916_ENABLED && AP_COMPASS_ICM20948_ENABLED diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index b798f31661d0e9..2c7b1ac7418dfb 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -481,7 +481,10 @@ friend class AP_Compass_Backend; #if AP_COMPASS_MMC5XX3_ENABLED DRIVER_MMC5XX3 =19, #endif - }; +#if AP_COMPASS_QMC5883P_ENABLED + DRIVER_QMC5883P =20, +#endif +}; bool _driver_enabled(enum DriverType driver_type); diff --git a/libraries/AP_Compass/AP_Compass_Backend.h b/libraries/AP_Compass/AP_Compass_Backend.h index 779d63f385ec17..79bfe1f66fd7b8 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.h +++ b/libraries/AP_Compass/AP_Compass_Backend.h @@ -73,6 +73,7 @@ class AP_Compass_Backend DEVTYPE_MMC5983 = 0x13, DEVTYPE_AK09918 = 0x14, DEVTYPE_AK09915 = 0x15, + DEVTYPE_QMC5883P = 0x16, }; #if AP_COMPASS_MSP_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_QMC5883P.cpp b/libraries/AP_Compass/AP_Compass_QMC5883P.cpp new file mode 100644 index 00000000000000..80d6e46f1c6997 --- /dev/null +++ b/libraries/AP_Compass/AP_Compass_QMC5883P.cpp @@ -0,0 +1,221 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Driver by Lokesh Ramina, Jan 2022 + */ +#include "AP_Compass_QMC5883P.h" + +#include + +#include +#include + +#if AP_COMPASS_QMC5883P_ENABLED + +//Register Address +#define QMC5883P_REG_ID 0x00 +#define QMC5883P_REG_DATA_OUTPUT_X 0x01 +#define QMC5883P_REG_DATA_OUTPUT_Z_MSB 0x06 +#define QMC5883P_REG_STATUS 0x09 +#define QMC5883P_REG_CONF1 0x0A +#define QMC5883P_REG_CONF2 0x0B + +#define QMC5883P_ID_VAL 0x80 + +//Register values +// Sensor operation modes +#define QMC5883P_MODE_SUSPEND 0x00 +#define QMC5883P_MODE_NORMAL 0x01 +#define QMC5883P_MODE_SINGLE 0x02 +#define QMC5883P_MODE_CONTINUOUS 0x03 + +// ODR data output rates for 5883L +#define QMC5883P_ODR_10HZ (0x00 << 2) +#define QMC5883P_ODR_50HZ (0x01 << 2) +#define QMC5883P_ODR_100HZ (0x02 << 2) +#define QMC5883P_ODR_200HZ (0x03 << 2) + +// Over sampling Ratio OSR1 +#define QMC5883P_OSR1_8 (0x00 << 4) +#define QMC5883P_OSR1_4 (0x01 << 4) +#define QMC5883P_OSR1_2 (0x02 << 4) +#define QMC5883P_OSR1_1 (0x03 << 4) + +// Down sampling Rate OSR2 +#define QMC5883P_OSR2_8 0x08 + +//RNG +#define QMC5883P_RNG_30G (0x00 << 2) +#define QMC5883P_RNG_12G (0x01 << 2) +#define QMC5883P_RNG_8G (0x10 << 2) +#define QMC5883P_RNG_2G (0x11 << 2) + +#define QMC5883P_SET_XYZ_SIGN 0x29 + +//Reset +#define QMC5883P_RST 0x80 + +//Status Val +#define QMC5883P_STATUS_DATA_READY 0x01 + +#ifndef DEBUG +#define DEBUG 0 +#endif + +extern const AP_HAL::HAL &hal; + +AP_Compass_Backend *AP_Compass_QMC5883P::probe(AP_HAL::OwnPtr dev, + bool force_external, + enum Rotation rotation) +{ + if (!dev) { + return nullptr; + } + AP_Compass_QMC5883P *sensor = new AP_Compass_QMC5883P(std::move(dev),force_external,rotation); + if (!sensor || !sensor->init()) { + delete sensor; + return nullptr; + } + return sensor; +} + +AP_Compass_QMC5883P::AP_Compass_QMC5883P(AP_HAL::OwnPtr dev, + bool force_external, + enum Rotation rotation) + : _dev(std::move(dev)) + , _rotation(rotation) + , _force_external(force_external) +{ +} + +bool AP_Compass_QMC5883P::init() +{ + _dev->get_semaphore()->take_blocking(); + + _dev->set_retries(10); +#if DEBUG + _dump_registers(); +#endif + if (!_check_whoami()) { + goto fail; + } + //As mentioned in the Datasheet 7.2 to do continues mode 0x29 will set sign for X,Y,Z + if (!_dev->write_register(QMC5883P_REG_DATA_OUTPUT_Z_MSB, QMC5883P_SET_XYZ_SIGN)|| + !_dev->write_register(QMC5883P_REG_CONF1, + QMC5883P_MODE_CONTINUOUS| + QMC5883P_ODR_100HZ| + QMC5883P_OSR1_8| + QMC5883P_OSR2_8)|| + !_dev->write_register(QMC5883P_REG_CONF2,QMC5883P_OSR2_8)) { + goto fail; + } + + // lower retries for run + _dev->set_retries(3); + + _dev->get_semaphore()->give(); + + //register compass instance + _dev->set_device_type(DEVTYPE_QMC5883P); + if (!register_compass(_dev->get_bus_id(), _instance)) { + return false; + } + set_dev_id(_instance, _dev->get_bus_id()); + + printf("%s found on bus %u id %u address 0x%02x\n", name, + _dev->bus_num(), _dev->get_bus_id(), _dev->get_bus_address()); + + set_rotation(_instance, _rotation); + + if (_force_external) { + set_external(_instance, true); + } + + //Enable 100HZ + _dev->register_periodic_callback(10000, + FUNCTOR_BIND_MEMBER(&AP_Compass_QMC5883P::timer, void)); + + return true; + +fail: + _dev->get_semaphore()->give(); + return false; +} +bool AP_Compass_QMC5883P::_check_whoami() +{ + uint8_t whoami; + if (!_dev->read_registers(QMC5883P_REG_ID, &whoami,1)|| + whoami != QMC5883P_ID_VAL) { + return false; + } + return true; +} + +void AP_Compass_QMC5883P::timer() +{ + struct PACKED { + int16_t rx; + int16_t ry; + int16_t rz; + } buffer; + + const float range_scale = 1000.0f / 3000.0f; + + uint8_t status; + if (!_dev->read_registers(QMC5883P_REG_STATUS,&status,1)) { + return; + } + //new data is ready + if (!(status & QMC5883P_STATUS_DATA_READY)) { + return; + } + + if (!_dev->read_registers(QMC5883P_REG_DATA_OUTPUT_X, (uint8_t *) &buffer, sizeof(buffer))) { + return ; + } + + auto x = buffer.rx; + auto y = buffer.ry; + auto z = buffer.rz; + +#if DEBUG + printf("mag.x:%d\n",x); + printf("mag.y:%d\n",y); + printf("mag.z:%d\n",z); +#endif + + Vector3f field = Vector3f{x * range_scale, y * range_scale, z * range_scale }; + + accumulate_sample(field, _instance, 20); +} + +void AP_Compass_QMC5883P::read() +{ + drain_accumulated_samples(_instance); +} + +void AP_Compass_QMC5883P::_dump_registers() +{ + printf("QMC5883P registers dump\n"); + for (uint8_t reg = QMC5883P_REG_DATA_OUTPUT_X; reg <= 0x30; reg++) { + uint8_t v; + _dev->read_registers(reg,&v,1); + printf("%02x:%02x ", (unsigned)reg, (unsigned)v); + if ((reg - ( QMC5883P_REG_DATA_OUTPUT_X-1)) % 16 == 0) { + printf("\n"); + } + } +} + +#endif //AP_COMPASS_QMC5883P_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_QMC5883P.h b/libraries/AP_Compass/AP_Compass_QMC5883P.h new file mode 100644 index 00000000000000..4219640c7ba196 --- /dev/null +++ b/libraries/AP_Compass/AP_Compass_QMC5883P.h @@ -0,0 +1,73 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * Driver by Lokesh Ramina, Jan 2022 + */ +#pragma once + +#include +#include +#include + +#include "AP_Compass_config.h" + +#ifdef AP_COMPASS_QMC5883P_ENABLED + +#include "AP_Compass.h" +#include "AP_Compass_Backend.h" + +#ifndef HAL_COMPASS_QMC5883P_I2C_ADDR +#define HAL_COMPASS_QMC5883P_I2C_ADDR 0x2C +#endif + +/* + setup default orientations + */ +#ifndef HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL +#define HAL_COMPASS_QMC5883P_ORIENTATION_EXTERNAL ROTATION_ROLL_180 +#endif + +#ifndef HAL_COMPASS_QMC5883P_ORIENTATION_INTERNAL +#define HAL_COMPASS_QMC5883P_ORIENTATION_INTERNAL ROTATION_ROLL_180_YAW_270 +#endif + +class AP_Compass_QMC5883P : public AP_Compass_Backend +{ +public: + static AP_Compass_Backend *probe(AP_HAL::OwnPtr dev, + bool force_external, + enum Rotation rotation); + + void read() override; + + static constexpr const char *name = "QMC5883P"; + +private: + AP_Compass_QMC5883P(AP_HAL::OwnPtr dev, + bool force_external, + enum Rotation rotation); + + void _dump_registers(); + bool _check_whoami(); + void timer(); + bool init(); + + AP_HAL::OwnPtr _dev; + + enum Rotation _rotation; + uint8_t _instance; + bool _force_external:1; +}; + +#endif // AP_COMPASS_QMC5883P_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_config.h b/libraries/AP_Compass/AP_Compass_config.h index 6bb8153b58389a..ce8989f2be591f 100644 --- a/libraries/AP_Compass/AP_Compass_config.h +++ b/libraries/AP_Compass/AP_Compass_config.h @@ -112,6 +112,10 @@ #define AP_COMPASS_MMC5XX3_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED #endif +#ifndef AP_COMPASS_QMC5883P_ENABLED +#define AP_COMPASS_QMC5883P_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED && (BOARD_FLASH_SIZE > 1024) +#endif + #ifndef AP_COMPASS_QMC5883L_ENABLED #define AP_COMPASS_QMC5883L_ENABLED AP_COMPASS_I2C_BACKEND_DEFAULT_ENABLED #endif From 691b23db7dfe5d03e8ebef04f63820d329ddb765 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 12 Sep 2023 06:50:31 +1000 Subject: [PATCH 172/499] AP_Mount: added sending of attitude and velocity for SIYI will be used by SIYI for improved gimbal control --- libraries/AP_Mount/AP_Mount_Siyi.cpp | 33 ++++++++++++++++++++++++++++ libraries/AP_Mount/AP_Mount_Siyi.h | 5 +++++ 2 files changed, 38 insertions(+) diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index 1e4c54c8bf6949..c1fe0504d73101 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -82,6 +82,12 @@ void AP_Mount_Siyi::update() _last_rangefinder_req_ms = now_ms; } + // send attitude to gimbal at 10Hz + if (now_ms - _last_attitude_send_ms > 100) { + _last_attitude_send_ms = now_ms; + send_attitude(); + } + // run zoom control update_zoom_control(); @@ -1087,4 +1093,31 @@ void AP_Mount_Siyi::check_firmware_version() const } } +/* + send ArduPilot attitude to gimbal +*/ +void AP_Mount_Siyi::send_attitude(void) +{ + const auto &ahrs = AP::ahrs(); + struct { + uint32_t time_boot_ms; + float roll, pitch, yaw; + float rollspeed, pitchspeed, yawspeed; + } attitude; + + // get attitude as euler 321 + const auto &gyro = ahrs.get_gyro(); + const uint32_t now_ms = AP_HAL::millis(); + + attitude.time_boot_ms = now_ms; + attitude.roll = ahrs.roll; + attitude.pitch = ahrs.pitch; + attitude.yaw = ahrs.yaw; + attitude.rollspeed = gyro.x; + attitude.pitchspeed = gyro.y; + attitude.yawspeed = gyro.z; + + send_packet(SiyiCommandId::EXTERNAL_ATTITUDE, (const uint8_t *)&attitude, sizeof(attitude)); +} + #endif // HAL_MOUNT_SIYI_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index fd929558a7d3e8..c1bddd0699d3f4 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -111,6 +111,7 @@ class AP_Mount_Siyi : public AP_Mount_Backend ABSOLUTE_ZOOM = 0x0F, SET_CAMERA_IMAGE_TYPE = 0x11, READ_RANGEFINDER = 0x15, + EXTERNAL_ATTITUDE = 0x22, }; // Function Feedback Info packet info_type values @@ -324,6 +325,10 @@ class AP_Mount_Siyi : public AP_Mount_Backend uint32_t _last_rangefinder_dist_ms; // system time of last successful read of rangefinder distance float _rangefinder_dist_m; // distance received from rangefinder + // sending of attitude to gimbal + uint32_t _last_attitude_send_ms; + void send_attitude(void); + // hardware lookup table indexed by HardwareModel enum values (see above) struct HWInfo { uint8_t hwid[2]; From 901280902abab170925711a3b5ead89327a715b9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 2 Nov 2023 08:16:55 +1100 Subject: [PATCH 173/499] AP_Mount: allow for larger SIYI packets needed for attitude packet --- libraries/AP_Mount/AP_Mount_Siyi.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index c1bddd0699d3f4..60e40f4f2c164f 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -27,7 +27,7 @@ #include #include -#define AP_MOUNT_SIYI_PACKETLEN_MAX 22 // maximum number of bytes in a packet sent to or received from the gimbal +#define AP_MOUNT_SIYI_PACKETLEN_MAX 38 // maximum number of bytes in a packet sent to or received from the gimbal class AP_Mount_Siyi : public AP_Mount_Backend { From 265f19b396ad80fe62ab8f4895fb7976924f4607 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 13 Nov 2023 20:13:05 +0900 Subject: [PATCH 174/499] SRV_Channel: fix scaled passthrough of ranges --- libraries/SRV_Channel/SRV_Channel_aux.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/libraries/SRV_Channel/SRV_Channel_aux.cpp b/libraries/SRV_Channel/SRV_Channel_aux.cpp index 50557eed1b0b45..e6be2e6ef66ab1 100644 --- a/libraries/SRV_Channel/SRV_Channel_aux.cpp +++ b/libraries/SRV_Channel/SRV_Channel_aux.cpp @@ -60,7 +60,15 @@ void SRV_Channel::output_ch(void) int16_t radio_in = c->get_radio_in(); if (passthrough_mapped) { if (rc().has_valid_input()) { - radio_in = pwm_from_angle(c->norm_input_dz() * 4500); + switch (c->get_type()) { + case RC_Channel::ControlType::ANGLE: + radio_in = pwm_from_angle(c->norm_input_dz() * 4500); + break; + case RC_Channel::ControlType::RANGE: + // convert RC normalised input from -1 to +1 range to 0 to +1 and output as range + radio_in = pwm_from_range((c->norm_input_ignore_trim() + 1.0) * 0.5 * 4500); + break; + } } else { // no valid input. If we are in radio // failsafe then go to trim values (if From fef47303d2937e838eff4d81c426503de0860626 Mon Sep 17 00:00:00 2001 From: jfbblue0922 Date: Thu, 9 Nov 2023 09:45:22 +0900 Subject: [PATCH 175/499] AP_RangeFinder: add serial driver for JRE --- libraries/AP_RangeFinder/AP_RangeFinder.cpp | 7 ++ libraries/AP_RangeFinder/AP_RangeFinder.h | 3 + .../AP_RangeFinder_JRE_Serial.cpp | 107 ++++++++++++++++++ .../AP_RangeFinder_JRE_Serial.h | 105 +++++++++++++++++ .../AP_RangeFinder/AP_RangeFinder_Params.cpp | 2 +- .../AP_RangeFinder/AP_RangeFinder_config.h | 3 + 6 files changed, 226 insertions(+), 1 deletion(-) create mode 100644 libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp create mode 100644 libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 5636656604b352..1d21089df5acc9 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -58,6 +58,7 @@ #include "AP_RangeFinder_TOFSenseP_CAN.h" #include "AP_RangeFinder_NRA24_CAN.h" #include "AP_RangeFinder_TOFSenseF_I2C.h" +#include "AP_RangeFinder_JRE_Serial.h" #include #include @@ -575,6 +576,12 @@ void RangeFinder::detect_instance(uint8_t instance, uint8_t& serial_instance) break; } #endif +#if AP_RANGEFINDER_JRE_SERIAL_ENABLED + case Type::JRE_Serial: + serial_create_fn = AP_RangeFinder_JRE_Serial::create; + break; +#endif + case Type::NONE: break; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index 1f3353656708da..b00198644fa8e4 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -171,6 +171,9 @@ class RangeFinder #if AP_RANGEFINDER_TOFSENSEF_I2C_ENABLED TOFSenseF_I2C = 40, #endif +#if AP_RANGEFINDER_JRE_SERIAL_ENABLED + JRE_Serial = 41, +#endif #if AP_RANGEFINDER_SIM_ENABLED SIM = 100, #endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp new file mode 100644 index 00000000000000..e7f6311c8e3429 --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp @@ -0,0 +1,107 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_JRE_SERIAL_ENABLED + +#include "AP_RangeFinder_JRE_Serial.h" +#include + +#define FRAME_HEADER_1 'R' // 0x52 +#define FRAME_HEADER_2_A 'A' // 0x41 +#define FRAME_HEADER_2_B 'B' // 0x42 +#define FRAME_HEADER_2_C 'C' // 0x43 + +#define DIST_MAX_CM 5000 +#define OUT_OF_RANGE_ADD_CM 100 + +bool AP_RangeFinder_JRE_Serial::get_reading(float &reading_m) +{ + // uart instance check + if (uart == nullptr) { + return false; // not update + } + + uint16_t valid_count = 0; // number of valid readings + uint16_t invalid_count = 0; // number of invalid readings + float sum = 0; + // max distance the sensor can reliably measure - read from parameters + const int16_t distance_cm_max = max_distance_cm(); + + // buffer read + const ssize_t num_read = uart->read(read_buff, ARRAY_SIZE(read_buff)); + for (read_buff_idx = 0; read_buff_idx < num_read; read_buff_idx++) { + if (data_buff_idx == 0) { // header first byte check + // header data search + if (read_buff[read_buff_idx] == FRAME_HEADER_1) { + data_buff[0] = FRAME_HEADER_1; + data_buff_idx = 1; // next data_buff + } + } else if (data_buff_idx == 1) { // header second byte check + data_buff[1] = read_buff[read_buff_idx]; + data_buff_idx = 2; // next data_buff + switch (read_buff[read_buff_idx]) { + case FRAME_HEADER_2_A: + data_buff_len = 16; + break; + case FRAME_HEADER_2_B: + data_buff_len = 32; + break; + case FRAME_HEADER_2_C: + data_buff_len = 48; + break; + default: + data_buff_idx = 0; // data index clear + break; + } + } else { // data set + data_buff[data_buff_idx++] = read_buff[read_buff_idx]; + + if (data_buff_idx >= data_buff_len) { // 1 data set complete + // crc check + uint16_t crc = crc16_ccitt_r(data_buff, data_buff_len - 2, 0xffff, 0xffff); + if ((HIGHBYTE(crc) == data_buff[data_buff_len-1]) && (LOWBYTE(crc) == data_buff[data_buff_len-2])) { + // status check + if (data_buff[data_buff_len-3] & 0x02) { // NTRK + invalid_count++; + } else { // TRK + reading_m = (data_buff[4] * 256 + data_buff[5]) * 0.01f; + sum += reading_m; + valid_count++; + } + } + data_buff_idx = 0; // data index clear + } + } + } + + // return average of all valid readings + if (valid_count > 0) { + no_signal = false; + reading_m = sum / valid_count; + return true; + } + + // all readings were invalid so return out-of-range-high value + if (invalid_count > 0) { + no_signal = true; + reading_m = MIN(MAX(DIST_MAX_CM, distance_cm_max + OUT_OF_RANGE_ADD_CM), UINT16_MAX) * 0.01f; + return true; + } + + return false; +} +#endif // AP_RANGEFINDER_JRE_SERIAL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h new file mode 100644 index 00000000000000..0caa3124b6abf7 --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h @@ -0,0 +1,105 @@ +#pragma once + +#include "AP_RangeFinder_config.h" + +#if AP_RANGEFINDER_JRE_SERIAL_ENABLED + +#include "AP_RangeFinder.h" +#include "AP_RangeFinder_Backend_Serial.h" + +/* +The data received from the radio altimeter is as follows. +The format of the received data frame varies depending on the mode, and is stored in "read_buff" with a fixed value of 16 bytes, 32 bytes, or 48 bytes. + +[1] +Measurement mode: 1 data mode +Packet length: 16 bytes +Altitude data used: 4,5 bytes +|----------------------------------------------------------------------------------------------------------------------------------------------------| +| BYTE | 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | +|------|---------------------------------------------------------------------------------------------------------------------------------------------| +| NAME | header | header | version | frame | altitude | altitude | reserved | FFT value | FFT value | status | status | CRC | CRC | +| | (H) | (L) | | count | (H) | (L) | | (H) | (L) | (H) | (L) | (L) | (H) | +|------|---------------------------------------------------------------------------------------------------------------------------------------------| +| | | | | | | | | BIT 15to8: reserved | | +| | | | | unsigned | unsigned | | unsigned | BIT 7to4: GAIN detail | CRC result | +| DATA | 'R' | 'A' | 0 to 255 | 0 to 255 | LSB;0.01 m | N/A | LSB:1 | BIT 3-2: reserved | from BYTE | +| | | | | | 0 to 65535 | | 0 to 65535 | BIT 1: TRK / NTRK | 0 to 13 | +| | | | | | | | | BIT 0: GAIN LOW/HIGH | | +|----------------------------------------------------------------------------------------------------------------------------------------------------| + +[2] +Measurement mode: 3 data mode +Packet length: 32 bytes +Altitude data used: 4,5 bytes +|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| BYTE | 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14| 15| 16| 17| 18 | 19 | 20 | 21 | 22| 23| 24| 25| 26 | 27 | 28 | 29 | 30 | 31 | +|------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| NAME | header | header | version | frame | altitude | altitude | reserved | FFT value | FFT value | altitude | altitude | reserved | FFT value | FFT value | altitude | altitude | reserved | FFT value | FFT value | status | status | CRC | CRC | +| | (H) | (L) | | count | (H) | (L) | | (H) | (L) | (H) | (L) | | (H) | (L) | (H) | (L) | | (H) | (L) | (H) | (L) | (L) | (H) | +|------|-------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| | | | | | | | | | | | | | | BIT 15to8: reserved | | +| | | | | unsigned | unsigned | | unsigned | unsigned | | unsigned | unsigned | | unsigned | BIT 7to4: GAIN detail | CRC result | +| DATA | 'R' | 'B' | 0 to 255 | 0 to 255 | LSB;0.01 m | N/A | LSB:1 | LSB;0.01 m | N/A | LSB:1 | LSB;0.01 m | N/A | LSB:1 | BIT 3-2: reserved | from BYTE | +| | | | | | 0 to 65535 | | 0 to 65535 | 0 to 65535 | | 0 to 65535 | 0 to 65535 | | 0 to 65535 | BIT 1: TRK / NTRK | 0 to 13 | +| | | | | | | | | | | | | | | BIT 0: GAIN LOW/HIGH | | +|--------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| + +[3] +Measurement mode: 5 data mode +Packet length: 48 bytes +Altitude data used: 4,5 bytes +|------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| BYTE | 0 | 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14| 15| 16| 17| 18 | 19 | 20 | 21 | 22| 23| 24| 25| 26 | 27 | 28 | 29 | 30| 31| 32| 33| 34 | 35 | 36 | 37 | 38| 39| 40| 41| 42 | 43 | 44 | 45 | 46 | 47 | +|------|-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| NAME | header | header | version | frame | altitude | altitude | reserved | FFT value | FFT value | altitude | altitude | reserved | FFT value | FFT value | altitude | altitude | reserved | FFT value | FFT value | altitude | altitude | reserved | FFT value | FFT value | altitude | altitude | reserved | FFT value | FFT value | status | status | CRC | CRC | +| | (H) | (L) | | count | (H) | (L) | | (H) | (L) | (H) | (L) | | (H) | (L) | (H) | (L) | | (H) | (L) | (H) | (L) | | (H) | (L) | (H) | (L) | | (H) | (L) | (H) | (L) | (L) | (H) | +|------|-----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| | | | | | | | | | | | | | | | | | | | | BIT 15to8: reserved | | +| | | | | unsigned | unsigned | | unsigned | unsigned | | unsigned | unsigned | | unsigned | unsigned | | unsigned | unsigned | | unsigned | BIT 7to4: GAIN detail | CRC result | +| DATA | 'R' | 'C' | 0 to 255 | 0 to 255 | LSB;0.01 m | N/A | LSB:1 | LSB;0.01 m | N/A | LSB:1 | LSB;0.01 m | N/A | LSB:1 | LSB;0.01 m | N/A | LSB:1 | LSB;0.01 m | N/A | LSB:1 | BIT 3-2: reserved | from BYTE | +| | | | | | 0 to 65535 | | 0 to 65535 | 0 to 65535 | | 0 to 65535 | 0 to 65535 | | 0 to 65535 | 0 to 65535 | | 0 to 65535 | 0 to 65535 | | 0 to 65535 | BIT 1: TRK / NTRK | 0 to 13 | +| | | | | | | | | | | | | | | | | | | | | BIT 0: GAIN LOW/HIGH | | +|------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| +*/ +#define DATA_LENGTH 16 + +class AP_RangeFinder_JRE_Serial : public AP_RangeFinder_Backend_Serial +{ + +public: + static AP_RangeFinder_Backend_Serial *create( + RangeFinder::RangeFinder_State &_state, + AP_RangeFinder_Params &_params) + { + return new AP_RangeFinder_JRE_Serial(_state, _params); + } + +protected: + + using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial; + + MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override + { + return MAV_DISTANCE_SENSOR_RADAR; + } + + bool get_signal_quality_pct(int8_t &quality_pct) const override { + quality_pct = no_signal ? 0 : 100; + return true; + } + +private: + + // get a reading + bool get_reading(float &reading_m) override; + + uint8_t read_buff[DATA_LENGTH * 10]; + uint8_t read_buff_idx; + uint8_t data_buff[DATA_LENGTH * 3]; // maximum frame length + uint8_t data_buff_idx; + uint8_t data_buff_len; + + bool no_signal; // true if the latest read attempt found no valid distances +}; +#endif // AP_RANGEFINDER_JRE_SERIAL_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp index 16d30803f9bf05..a0873dec79b9e8 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Params.cpp @@ -10,7 +10,7 @@ const AP_Param::GroupInfo AP_RangeFinder_Params::var_info[] = { // @Param: TYPE // @DisplayName: Rangefinder type // @Description: Type of connected rangefinder - // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLite-I2C,5:PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:USD1_Serial,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X or VL53L1X,17:NMEA,18:WASP-LRF,19:BenewakeTF02,20:Benewake-Serial,21:LidarLightV3HP,22:PWM,23:BlueRoboticsPing,24:DroneCAN,25:BenewakeTFminiPlus-I2C,26:LanbaoPSK-CM8JL65-CC5,27:BenewakeTF03,28:VL53L1X-ShortRange,29:LeddarVu8-Serial,30:HC-SR04,31:GYUS42v2,32:MSP,33:USD1_CAN,34:Benewake_CAN,35:TeraRangerSerial,36:Lua_Scripting,37:NoopLoop_TOFSense,38:NoopLoop_TOFSense_CAN,39:NRA24_CAN,40:NoopLoop_TOFSenseF_I2C,100:SITL + // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:LidarLite-I2C,5:PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,11:USD1_Serial,12:LeddarOne,13:MaxbotixSerial,14:TeraRangerI2C,15:LidarLiteV3-I2C,16:VL53L0X or VL53L1X,17:NMEA,18:WASP-LRF,19:BenewakeTF02,20:Benewake-Serial,21:LidarLightV3HP,22:PWM,23:BlueRoboticsPing,24:DroneCAN,25:BenewakeTFminiPlus-I2C,26:LanbaoPSK-CM8JL65-CC5,27:BenewakeTF03,28:VL53L1X-ShortRange,29:LeddarVu8-Serial,30:HC-SR04,31:GYUS42v2,32:MSP,33:USD1_CAN,34:Benewake_CAN,35:TeraRangerSerial,36:Lua_Scripting,37:NoopLoop_TOFSense,38:NoopLoop_TOFSense_CAN,39:NRA24_CAN,40:NoopLoop_TOFSenseF_I2C,41:JRE_Serial,100:SITL // @User: Standard AP_GROUPINFO_FLAGS("TYPE", 1, AP_RangeFinder_Params, type, 0, AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_config.h b/libraries/AP_RangeFinder/AP_RangeFinder_config.h index 0800cadd3eae8a..a6c793c340517b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_config.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_config.h @@ -173,3 +173,6 @@ #define AP_RANGEFINDER_WASP_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED #endif +#ifndef AP_RANGEFINDER_JRE_SERIAL_ENABLED +#define AP_RANGEFINDER_JRE_SERIAL_ENABLED AP_RANGEFINDER_BACKEND_DEFAULT_ENABLED && BOARD_FLASH_SIZE > 1024 +#endif From 374573ae39f45034c4510caa12324639ff61c88c Mon Sep 17 00:00:00 2001 From: jfbblue0922 Date: Thu, 26 Oct 2023 16:55:55 +0900 Subject: [PATCH 176/499] Tools/scripts: add AP_RANGEFINDER_JRE_SERIAL_ENABLED --- Tools/scripts/build_options.py | 1 + Tools/scripts/extract_features.py | 1 + 2 files changed, 2 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 385c0c44d72da4..0548b646b6809d 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -213,6 +213,7 @@ def __init__(self, Feature('Rangefinder', 'RANGEFINDER_BLPING', 'AP_RANGEFINDER_BLPING_ENABLED', "Enable Rangefinder - BLPing", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_GYUS42V2', 'AP_RANGEFINDER_GYUS42V2_ENABLED', "Enable Rangefinder - GYUS42V2", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_HC_SR04', 'AP_RANGEFINDER_HC_SR04_ENABLED', "Enable Rangefinder - HC_SR04", 0, "RANGEFINDER"), # NOQA: E501 + Feature('Rangefinder', 'RANGEFINDER_JRE_SERIAL', 'AP_RANGEFINDER_JRE_SERIAL_ENABLED', "Enable Rangefinder - JRE_SERIAL", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_LANBAO', 'AP_RANGEFINDER_LANBAO_ENABLED', "Enable Rangefinder - Lanbao", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_LEDDARONE', 'AP_RANGEFINDER_LEDDARONE_ENABLED', "Enable Rangefinder - LeddarOne", 0, "RANGEFINDER"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_LEDDARVU8', 'AP_RANGEFINDER_LEDDARVU8_ENABLED', "Enable Rangefinder - LeddarVU8", 0, "RANGEFINDER"), # NOQA: E501 diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index d0b943dfe27752..be20757e008e57 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -82,6 +82,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_RANGEFINDER_LWI2C_ENABLED', r'AP_RangeFinder_LightWareI2C::update\b',), ('AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED', r'AP_RangeFinder_MaxsonarSerialLV::get_reading\b',), ('AP_RANGEFINDER_TRI2C_ENABLED', r'AP_RangeFinder_TeraRangerI2C::update\b',), + ('AP_RANGEFINDER_JRE_SERIAL_ENABLED', r'AP_RangeFinder_JRE_Serial::get_reading\b',), ('AP_GPS_{type}_ENABLED', r'AP_GPS_(?P.*)::read\b',), From 6bd702427420141701a132b9db94986b389e203c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 14 Nov 2023 12:46:50 +1100 Subject: [PATCH 177/499] AP_RangeFinder: change JRE parsing to reduce RAM overhead --- .../AP_RangeFinder_JRE_Serial.cpp | 126 ++++++++++++------ .../AP_RangeFinder_JRE_Serial.h | 9 +- 2 files changed, 85 insertions(+), 50 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp index e7f6311c8e3429..1fb9375fd7a23d 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp @@ -28,6 +28,21 @@ #define DIST_MAX_CM 5000 #define OUT_OF_RANGE_ADD_CM 100 +void AP_RangeFinder_JRE_Serial::move_preamble_in_buffer(uint8_t search_start_pos) +{ + uint8_t i; + for (i=search_start_pos; iread(read_buff, ARRAY_SIZE(read_buff)); - for (read_buff_idx = 0; read_buff_idx < num_read; read_buff_idx++) { - if (data_buff_idx == 0) { // header first byte check - // header data search - if (read_buff[read_buff_idx] == FRAME_HEADER_1) { - data_buff[0] = FRAME_HEADER_1; - data_buff_idx = 1; // next data_buff - } - } else if (data_buff_idx == 1) { // header second byte check - data_buff[1] = read_buff[read_buff_idx]; - data_buff_idx = 2; // next data_buff - switch (read_buff[read_buff_idx]) { - case FRAME_HEADER_2_A: - data_buff_len = 16; - break; - case FRAME_HEADER_2_B: - data_buff_len = 32; - break; - case FRAME_HEADER_2_C: - data_buff_len = 48; - break; - default: - data_buff_idx = 0; // data index clear - break; - } - } else { // data set - data_buff[data_buff_idx++] = read_buff[read_buff_idx]; - - if (data_buff_idx >= data_buff_len) { // 1 data set complete - // crc check - uint16_t crc = crc16_ccitt_r(data_buff, data_buff_len - 2, 0xffff, 0xffff); - if ((HIGHBYTE(crc) == data_buff[data_buff_len-1]) && (LOWBYTE(crc) == data_buff[data_buff_len-2])) { - // status check - if (data_buff[data_buff_len-3] & 0x02) { // NTRK - invalid_count++; - } else { // TRK - reading_m = (data_buff[4] * 256 + data_buff[5]) * 0.01f; - sum += reading_m; - valid_count++; - } - } - data_buff_idx = 0; // data index clear - } + // read a maximum of 8192 bytes per call to this function: + uint16_t bytes_available = MIN(uart->available(), 8192U); + + while (bytes_available > 0) { + // fill buffer + const auto num_bytes_to_read = MIN(bytes_available, ARRAY_SIZE(data_buff) - data_buff_idx); + const auto num_bytes_read = uart->read(&data_buff[data_buff_idx], num_bytes_to_read); + if (num_bytes_read == 0) { + break; + } + if (bytes_available < num_bytes_read) { + // this is a bug in the uart call. + break; + } + bytes_available -= num_bytes_read; + data_buff_idx += num_bytes_read; + + // move header frame header in buffer + move_preamble_in_buffer(0); + + // ensure we have a packet type: + if (data_buff_idx < 2) { + continue; + } + + // determine packet length for incoming packet: + uint8_t packet_length; + switch (data_buff[1]) { + case FRAME_HEADER_2_A: + packet_length = 16; + break; + case FRAME_HEADER_2_B: + packet_length = 32; + break; + case FRAME_HEADER_2_C: + packet_length = 48; + break; + default: + move_preamble_in_buffer(1); + continue; + } + + // check there are enough bytes for message type + if (data_buff_idx < packet_length) { + continue; } + + // check the checksum + const uint16_t crc = crc16_ccitt_r(data_buff, packet_length - 2, 0xffff, 0xffff); + if (crc != ((data_buff[packet_length-1] << 8) | data_buff[packet_length-2])) { + // CRC failure + move_preamble_in_buffer(1); + continue; + } + + // check random bit to for magic value: + if (data_buff[packet_length-3] & 0x02) { // NTRK + invalid_count++; + // discard entire packet: + move_preamble_in_buffer(packet_length); + continue; + } + + // good message, extract rangefinder reading: + reading_m = (data_buff[4] * 256 + data_buff[5]) * 0.01f; + sum += reading_m; + valid_count++; + move_preamble_in_buffer(packet_length); } // return average of all valid readings diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h index 0caa3124b6abf7..9415b50e198088 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h @@ -62,8 +62,6 @@ Altitude data used: 4,5 bytes | | | | | | | | | | | | | | | | | | | | | BIT 0: GAIN LOW/HIGH | | |------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------| */ -#define DATA_LENGTH 16 - class AP_RangeFinder_JRE_Serial : public AP_RangeFinder_Backend_Serial { @@ -94,11 +92,10 @@ class AP_RangeFinder_JRE_Serial : public AP_RangeFinder_Backend_Serial // get a reading bool get_reading(float &reading_m) override; - uint8_t read_buff[DATA_LENGTH * 10]; - uint8_t read_buff_idx; - uint8_t data_buff[DATA_LENGTH * 3]; // maximum frame length + void move_preamble_in_buffer(uint8_t search_start_pos); + + uint8_t data_buff[48 * 3]; // 48 is longest possible packet uint8_t data_buff_idx; - uint8_t data_buff_len; bool no_signal; // true if the latest read attempt found no valid distances }; From da6f31d5c7c2a892fc4a35fc1a7827a5869fa30b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 15 Nov 2023 09:30:11 +0900 Subject: [PATCH 178/499] AP_RangeFinder: JRE rename data_buff_ofs --- .../AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp | 16 ++++++++-------- .../AP_RangeFinder/AP_RangeFinder_JRE_Serial.h | 2 +- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp index 1fb9375fd7a23d..b360aa4d65f676 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp @@ -31,7 +31,7 @@ void AP_RangeFinder_JRE_Serial::move_preamble_in_buffer(uint8_t search_start_pos) { uint8_t i; - for (i=search_start_pos; i 0) { // fill buffer - const auto num_bytes_to_read = MIN(bytes_available, ARRAY_SIZE(data_buff) - data_buff_idx); - const auto num_bytes_read = uart->read(&data_buff[data_buff_idx], num_bytes_to_read); + const auto num_bytes_to_read = MIN(bytes_available, ARRAY_SIZE(data_buff) - data_buff_ofs); + const auto num_bytes_read = uart->read(&data_buff[data_buff_ofs], num_bytes_to_read); if (num_bytes_read == 0) { break; } @@ -71,13 +71,13 @@ bool AP_RangeFinder_JRE_Serial::get_reading(float &reading_m) break; } bytes_available -= num_bytes_read; - data_buff_idx += num_bytes_read; + data_buff_ofs += num_bytes_read; // move header frame header in buffer move_preamble_in_buffer(0); // ensure we have a packet type: - if (data_buff_idx < 2) { + if (data_buff_ofs < 2) { continue; } @@ -99,7 +99,7 @@ bool AP_RangeFinder_JRE_Serial::get_reading(float &reading_m) } // check there are enough bytes for message type - if (data_buff_idx < packet_length) { + if (data_buff_ofs < packet_length) { continue; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h index 9415b50e198088..df9fd1b00cc640 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h @@ -95,7 +95,7 @@ class AP_RangeFinder_JRE_Serial : public AP_RangeFinder_Backend_Serial void move_preamble_in_buffer(uint8_t search_start_pos); uint8_t data_buff[48 * 3]; // 48 is longest possible packet - uint8_t data_buff_idx; + uint8_t data_buff_ofs; // index where next item will be added in data_buff bool no_signal; // true if the latest read attempt found no valid distances }; From 4c7067044518dbf0b70ec4bd80d37b5462002176 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sun, 12 Nov 2023 14:10:17 -0800 Subject: [PATCH 179/499] AP_DDS: use AP_NETWORKING_BACKEND_ANY --- libraries/AP_DDS/AP_DDS_config.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_DDS/AP_DDS_config.h b/libraries/AP_DDS/AP_DDS_config.h index febd1a75423bec..244cb0d7ffd4a6 100644 --- a/libraries/AP_DDS/AP_DDS_config.h +++ b/libraries/AP_DDS/AP_DDS_config.h @@ -1,6 +1,7 @@ #pragma once #include +#include #ifndef AP_DDS_ENABLED #define AP_DDS_ENABLED 1 @@ -8,7 +9,7 @@ // UDP only on SITL for now #ifndef AP_DDS_UDP_ENABLED -#define AP_DDS_UDP_ENABLED AP_DDS_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#define AP_DDS_UDP_ENABLED AP_DDS_ENABLED && AP_NETWORKING_SOCKETS_ENABLED #endif #include From df600e5582ca32b6fc61ad28a1bc7bcf1f1c7c05 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sun, 12 Nov 2023 16:38:58 -0800 Subject: [PATCH 180/499] AP_HAL: Enable SocketAPM to use LwIP/ChibiOS --- libraries/AP_HAL/utility/Socket.cpp | 47 +++++++++++++++++++++++++++-- libraries/AP_HAL/utility/Socket.h | 9 +++++- 2 files changed, 53 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 83bdf78fb3866d..0cb09f63b44929 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -17,7 +17,8 @@ */ #include -#if HAL_OS_SOCKETS +#include +#if AP_NETWORKING_SOCKETS_ENABLED #include "Socket.h" #include @@ -34,7 +35,9 @@ SocketAPM::SocketAPM(bool _datagram, int _fd) : datagram(_datagram), fd(_fd) { +#ifdef FD_CLOEXEC fcntl(fd, F_SETFD, FD_CLOEXEC); +#endif if (!datagram) { int one = 1; setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); @@ -44,7 +47,11 @@ SocketAPM::SocketAPM(bool _datagram, int _fd) : SocketAPM::~SocketAPM() { if (fd != -1) { +#if AP_NETWORKING_BACKEND_CHIBIOS + ::lwip_close(fd); +#else ::close(fd); +#endif fd = -1; } } @@ -69,7 +76,11 @@ bool SocketAPM::connect(const char *address, uint16_t port) struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); +#if AP_NETWORKING_BACKEND_CHIBIOS + if (::lwip_connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { +#else if (::connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { +#endif return false; } return true; @@ -85,7 +96,11 @@ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t tim set_blocking(false); +#if AP_NETWORKING_BACKEND_CHIBIOS + int ret = ::lwip_connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); +#else int ret = ::connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); +#endif if (ret == 0) { // instant connect? return true; @@ -113,7 +128,11 @@ bool SocketAPM::bind(const char *address, uint16_t port) struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); +#if AP_NETWORKING_BACKEND_CHIBIOS + if (::lwip_bind(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { +#else if (::bind(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { +#endif return false; } return true; @@ -148,7 +167,11 @@ bool SocketAPM::set_blocking(bool blocking) const */ bool SocketAPM::set_cloexec() const { +#ifdef FD_CLOEXEC return (fcntl(fd, F_SETFD, FD_CLOEXEC) != -1); +#else + return false; +#endif } /* @@ -156,7 +179,11 @@ bool SocketAPM::set_cloexec() const */ ssize_t SocketAPM::send(const void *buf, size_t size) const { +#if AP_NETWORKING_BACKEND_CHIBIOS + return ::lwip_send(fd, buf, size, 0); +#else return ::send(fd, buf, size, 0); +#endif } /* @@ -166,7 +193,11 @@ ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uin { struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); +#if AP_NETWORKING_BACKEND_CHIBIOS + return ::lwip_sendto(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); +#else return ::sendto(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); +#endif } /* @@ -178,7 +209,11 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) return -1; } socklen_t len = sizeof(in_addr); +#if AP_NETWORKING_BACKEND_CHIBIOS + return ::lwip_recvfrom(fd, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); +#else return ::recvfrom(fd, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); +#endif } /* @@ -242,7 +277,11 @@ bool SocketAPM::pollout(uint32_t timeout_ms) */ bool SocketAPM::listen(uint16_t backlog) const { +#if AP_NETWORKING_BACKEND_CHIBIOS + return ::lwip_listen(fd, (int)backlog) == 0; +#else return ::listen(fd, (int)backlog) == 0; +#endif } /* @@ -255,7 +294,11 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) return nullptr; } +#if AP_NETWORKING_BACKEND_CHIBIOS + int newfd = ::lwip_accept(fd, nullptr, nullptr); +#else int newfd = ::accept(fd, nullptr, nullptr); +#endif if (newfd == -1) { return nullptr; } @@ -265,4 +308,4 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) return new SocketAPM(false, newfd); } -#endif // HAL_OS_SOCKETS +#endif // AP_NETWORKING_BACKEND_ANY diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index e159782ec3f7aa..a20cbbda0e9e45 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -18,6 +18,9 @@ #pragma once #include +#include +#if AP_NETWORKING_SOCKETS_ENABLED + #if HAL_OS_SOCKETS #include @@ -28,6 +31,10 @@ #include #include #include +#elif AP_NETWORKING_BACKEND_CHIBIOS +#include +#include +#endif class SocketAPM { public: @@ -72,4 +79,4 @@ class SocketAPM { void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr); }; -#endif // HAL_OS_SOCKETS +#endif // AP_NETWORKING_SOCKETS_ENABLED From c4cf3268cb4a77314c16b6531f3a7aba2108ba27 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Nov 2023 12:35:11 +1100 Subject: [PATCH 181/499] waf: added --enable-networking and --enable-networking-tests --- Tools/ardupilotwaf/boards.py | 6 ++++++ wscript | 9 +++++++-- 2 files changed, 13 insertions(+), 2 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 26e88c1b1621d0..2c5d221445dbef 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -148,6 +148,12 @@ def srcpath(path): ) cfg.msg("Enabled custom controller", 'no', color='YELLOW') + if cfg.options.enable_networking: + env.CXXFLAGS += ['-DAP_NETWORKING_ENABLED=1'] + + if cfg.options.enable_networking_tests: + env.CXXFLAGS += ['-DAP_NETWORKING_TESTS_ENABLED=1'] + d = env.get_merged_dict() # Always prepend so that arguments passed in the command line get # the priority. diff --git a/wscript b/wscript index 6f4d9d81b12f4b..393eab94c75fa1 100644 --- a/wscript +++ b/wscript @@ -267,9 +267,14 @@ submodules at specific revisions. help="Enables GPS logging") g.add_option('--enable-dds', action='store_true', - help="Enable the dds client to connect with ROS2/DDS" - ) + help="Enable the dds client to connect with ROS2/DDS") + + g.add_option('--enable-networking', action='store_true', + help="Enable the networking code") + g.add_option('--enable-networking-tests', action='store_true', + help="Enable the networking test code") + g.add_option('--enable-dronecan-tests', action='store_true', default=False, help="Enables DroneCAN tests in sitl") From bbe7ad484ee7059145a462d47182ca569de06137 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Nov 2023 12:36:21 +1100 Subject: [PATCH 182/499] Tools: added --enable-networking and --enable-networking-tests to sim_vehicle.py --- Tools/autotest/sim_vehicle.py | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 3e0fb79eb4c566..6f202f184eecd6 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -411,6 +411,12 @@ def do_build(opts, frame_options): if opts.enable_dds: cmd_configure.append("--enable-dds") + if opts.enable_networking: + cmd_configure.append("--enable-networking") + + if opts.enable_networking_tests: + cmd_configure.append("--enable-networking-tests") + pieces = [shlex.split(x) for x in opts.waf_configure_args] for piece in pieces: cmd_configure.extend(piece) @@ -1326,6 +1332,10 @@ def generate_frame_help(): help="IP address of the simulator. Defaults to localhost") group_sim.add_option("--enable-dds", action='store_true', help="Enable the dds client to connect with ROS2/DDS") +group_sim.add_option("--enable-networking", action='store_true', + help="Enable networking") +group_sim.add_option("--enable-networking-tests", action='store_true', + help="Enable networking tests") parser.add_option_group(group_sim) From 4afd0f746bcb7fb3519d2bce15520c0bf2107d40 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Nov 2023 12:37:10 +1100 Subject: [PATCH 183/499] AP_Networking: added networking test suite --- libraries/AP_Networking/AP_Networking.cpp | 14 +++ libraries/AP_Networking/AP_Networking.h | 13 +++ .../AP_Networking/AP_Networking_Config.h | 10 ++ .../AP_Networking/AP_Networking_tests.cpp | 103 ++++++++++++++++++ 4 files changed, 140 insertions(+) create mode 100644 libraries/AP_Networking/AP_Networking_tests.cpp diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index c6f51ad9297170..6e0161bfe258eb 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -56,6 +56,16 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @Path: AP_Networking_macaddr.cpp AP_SUBGROUPINFO(param.macaddr, "MACADDR", 6, AP_Networking, AP_Networking_MAC), +#if AP_NETWORKING_TESTS_ENABLED + // @Param: TESTS + // @DisplayName: Test enable flags + // @Description: Enable/Disable networking tests + // @Bitmask: 0:UDP echo test,1:TCP echo test + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("TESTS", 7, AP_Networking, param.tests, 0), +#endif + AP_GROUPEND }; @@ -116,6 +126,10 @@ void AP_Networking::init() announce_address_changes(); GCS_SEND_TEXT(MAV_SEVERITY_INFO,"NET: Initialized"); + +#if AP_NETWORKING_TESTS_ENABLED + start_tests(); +#endif } /* diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index a72f7cd3d5388b..10a120a4c94197 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -165,6 +165,9 @@ class AP_Networking AP_Networking_MAC macaddr{AP_NETWORKING_DEFAULT_MAC_ADDR}; AP_Int8 enabled; AP_Int32 options; +#if AP_NETWORKING_TESTS_ENABLED + AP_Int32 tests; +#endif } param; AP_Networking_Backend *backend; @@ -173,6 +176,16 @@ class AP_Networking private: uint32_t announce_ms; + +#if AP_NETWORKING_TESTS_ENABLED + enum { + TEST_UDP_CLIENT = (1U<<0), + TEST_TCP_CLIENT = (1U<<1), + }; + void start_tests(void); + void test_UDP_client(void); + void test_TCP_client(void); +#endif // AP_NETWORKING_TESTS_ENABLED }; namespace AP diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index b5f43eec42f6e5..992c44ab4b6856 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -60,3 +60,13 @@ #ifndef AP_NETWORKING_DEFAULT_MAC_ADDR #define AP_NETWORKING_DEFAULT_MAC_ADDR "C2:AF:51:03:CF:46" #endif + +#ifndef AP_NETWORKING_TESTS_ENABLED +#define AP_NETWORKING_TESTS_ENABLED 0 +#endif + +#if AP_NETWORKING_TESTS_ENABLED +#ifndef AP_NETWORKING_TEST_IP +#define AP_NETWORKING_TEST_IP "192.168.13.15" +#endif +#endif diff --git a/libraries/AP_Networking/AP_Networking_tests.cpp b/libraries/AP_Networking/AP_Networking_tests.cpp new file mode 100644 index 00000000000000..29372b2bd949a5 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_tests.cpp @@ -0,0 +1,103 @@ +/* + a set of tests for networking + */ + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_ENABLED && AP_NETWORKING_TESTS_ENABLED +#include "AP_Networking.h" + +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +/* + start tests + */ +void AP_Networking::start_tests(void) +{ + if (param.tests & TEST_UDP_CLIENT) { + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::test_UDP_client, void), + "UDP_client", + 8192, AP_HAL::Scheduler::PRIORITY_IO, -1); + } + if (param.tests & TEST_TCP_CLIENT) { + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::test_TCP_client, void), + "TCP_client", + 8192, AP_HAL::Scheduler::PRIORITY_IO, -1); + } +} + +/* + start UDP client test + */ +void AP_Networking::test_UDP_client(void) +{ + while (!hal.scheduler->is_system_initialized()) { + hal.scheduler->delay(100); + } + hal.scheduler->delay(1000); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP_client: starting"); + const char *dest = AP_NETWORKING_TEST_IP; + auto *sock = new SocketAPM(true); + if (sock == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP_client: failed to create socket"); + return; + } + // connect to the echo service, which is port 7 + if (!sock->connect(dest, 7)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP_client: connect failed"); + return; + } + while (true) { + hal.scheduler->delay(100); + char *s = nullptr; + asprintf(&s, "hello %u", unsigned(AP_HAL::millis())); + sock->send((const void*)s, strlen(s)); + free(s); + uint8_t buf[128] {}; + const ssize_t ret = sock->recv(buf, sizeof(buf), 10); + if (ret > 0) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP_client: reply '%s'", (const char *)buf); + } + } +} + +/* + start TCP client test + */ +void AP_Networking::test_TCP_client(void) +{ + while (!hal.scheduler->is_system_initialized()) { + hal.scheduler->delay(100); + } + hal.scheduler->delay(1000); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_client: starting"); + const char *dest = AP_NETWORKING_TEST_IP; + auto *sock = new SocketAPM(false); + if (sock == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_client: failed to create socket"); + return; + } + // connect to the echo service, which is port 7 + if (!sock->connect(dest, 7)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_client: connect failed"); + return; + } + while (true) { + hal.scheduler->delay(100); + char *s = nullptr; + asprintf(&s, "hello %u", unsigned(AP_HAL::millis())); + sock->send((const void*)s, strlen(s)); + free(s); + uint8_t buf[128] {}; + const ssize_t ret = sock->recv(buf, sizeof(buf), 10); + if (ret > 0) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_client: reply '%s'", (const char *)buf); + } + } +} + +#endif // AP_NETWORKING_ENABLED && AP_NETWORKING_TESTS_ENABLED From 74f9b74fe74dfd10162ad2cbb179304439711f44 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sun, 12 Nov 2023 17:41:10 -0800 Subject: [PATCH 184/499] AP_Networking: add get_str() accessor to IP address parms --- libraries/AP_Networking/AP_Networking_address.cpp | 5 +++++ libraries/AP_Networking/AP_Networking_address.h | 5 +++++ 2 files changed, 10 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking_address.cpp b/libraries/AP_Networking/AP_Networking_address.cpp index 622e6f919a6679..5cadbbe6f7a144 100644 --- a/libraries/AP_Networking/AP_Networking_address.cpp +++ b/libraries/AP_Networking/AP_Networking_address.cpp @@ -68,4 +68,9 @@ void AP_Networking_IPV4::set_default_uint32(uint32_t v) } } +const char* AP_Networking_IPV4::get_str() const +{ + return AP_Networking::convert_ip_to_str(get_uint32()); +} + #endif // AP_NETWORKING_ENABLED diff --git a/libraries/AP_Networking/AP_Networking_address.h b/libraries/AP_Networking/AP_Networking_address.h index f607d02facb482..a4a3b6f8b29a8f 100644 --- a/libraries/AP_Networking/AP_Networking_address.h +++ b/libraries/AP_Networking/AP_Networking_address.h @@ -1,5 +1,7 @@ #pragma once +#include + /* class for an IPV4 address as a parameter */ @@ -15,6 +17,9 @@ class AP_Networking_IPV4 // set address from a uint32_t void set_uint32(uint32_t addr); + // return address as a null-terminated string + const char* get_str() const; + // set default address from a uint32 void set_default_uint32(uint32_t addr); From 6cd24bb87b15953f393f61df49c5ffa90827a4a5 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sun, 12 Nov 2023 17:59:59 -0800 Subject: [PATCH 185/499] AP_DDS: Add user-selectable UDP IP --- libraries/AP_DDS/AP_DDS_Client.cpp | 4 ++++ libraries/AP_DDS/AP_DDS_Client.h | 3 ++- libraries/AP_DDS/AP_DDS_UDP.cpp | 2 +- libraries/AP_DDS/AP_DDS_config.h | 10 +++++++++- 4 files changed, 16 insertions(+), 3 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 29560fcc792080..100f51de2fe3cd 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -65,6 +65,10 @@ const AP_Param::GroupInfo AP_DDS_Client::var_info[] { // @User: Standard AP_GROUPINFO("_PORT", 2, AP_DDS_Client, udp.port, 2019), + // @Group: _IP + // @Path: ../AP_Networking/AP_Networking_address.cpp + AP_SUBGROUPINFO(udp.ip, "_IP", 3, AP_DDS_Client, AP_Networking_IPV4), + #endif AP_GROUPEND diff --git a/libraries/AP_DDS/AP_DDS_Client.h b/libraries/AP_DDS/AP_DDS_Client.h index acdf4c7ddcb162..19d20c3017d244 100644 --- a/libraries/AP_DDS/AP_DDS_Client.h +++ b/libraries/AP_DDS/AP_DDS_Client.h @@ -31,6 +31,7 @@ #if AP_DDS_UDP_ENABLED #include +#include #endif extern const AP_HAL::HAL& hal; @@ -138,7 +139,7 @@ class AP_DDS_Client struct { AP_Int32 port; // UDP endpoint - const char* ip = "127.0.0.1"; + AP_Networking_IPV4 ip{AP_DDS_DEFAULT_UDP_IP_ADDR}; // UDP Allocation uxrCustomTransport transport; SocketAPM *socket; diff --git a/libraries/AP_DDS/AP_DDS_UDP.cpp b/libraries/AP_DDS/AP_DDS_UDP.cpp index 2610291231dba2..6593100618bb50 100644 --- a/libraries/AP_DDS/AP_DDS_UDP.cpp +++ b/libraries/AP_DDS/AP_DDS_UDP.cpp @@ -14,7 +14,7 @@ bool AP_DDS_Client::udp_transport_open(uxrCustomTransport *t) if (sock == nullptr) { return false; } - if (!sock->connect(dds->udp.ip, dds->udp.port.get())) { + if (!sock->connect(dds->udp.ip.get_str(), dds->udp.port.get())) { return false; } dds->udp.socket = sock; diff --git a/libraries/AP_DDS/AP_DDS_config.h b/libraries/AP_DDS/AP_DDS_config.h index 244cb0d7ffd4a6..094d2d4efb96c3 100644 --- a/libraries/AP_DDS/AP_DDS_config.h +++ b/libraries/AP_DDS/AP_DDS_config.h @@ -9,10 +9,18 @@ // UDP only on SITL for now #ifndef AP_DDS_UDP_ENABLED -#define AP_DDS_UDP_ENABLED AP_DDS_ENABLED && AP_NETWORKING_SOCKETS_ENABLED +#define AP_DDS_UDP_ENABLED AP_DDS_ENABLED && AP_NETWORKING_ENABLED #endif #include #ifndef AP_DDS_VISUALODOM_ENABLED #define AP_DDS_VISUALODOM_ENABLED HAL_VISUALODOM_ENABLED && AP_DDS_ENABLED #endif + +#ifndef AP_DDS_DEFAULT_UDP_IP_ADDR +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + #define AP_DDS_DEFAULT_UDP_IP_ADDR "192.168.13.2" +#else + #define AP_DDS_DEFAULT_UDP_IP_ADDR "127.0.0.1" +#endif +#endif From fbe265184034eecc1dbbe67d5b9809a7021d3720 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 14 Nov 2023 08:56:07 +1100 Subject: [PATCH 186/499] AP_Networking: removed unuused send_udp in ChibiOS backend --- .../AP_Networking/AP_Networking_ChibiOS.cpp | 29 ------------------- .../AP_Networking/AP_Networking_ChibiOS.h | 1 - 2 files changed, 30 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp index b79413c2aab448..84e6f491ce2f13 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -143,34 +143,5 @@ void AP_Networking_ChibiOS::update() } } -/* - send a UDP packet - */ -int32_t AP_Networking_ChibiOS::send_udp(struct udp_pcb *pcb, const ip4_addr_t &ip4_addr, const uint16_t port, const uint8_t* data, uint16_t data_len) -{ - if (pcb == nullptr) { - return ERR_ARG; - } - - data_len = (data == nullptr) ? 0 : data_len; - - struct pbuf *p = pbuf_alloc(PBUF_TRANSPORT, data_len, PBUF_RAM); - if (p == nullptr) { - return ERR_MEM; - } - - ip_addr_t dst; - ip_addr_copy_from_ip4(dst, ip4_addr); - - if (data_len > 0) { - memcpy(p->payload, data, data_len); - } - - const err_t err = udp_sendto(pcb, p, &dst, port); - pbuf_free(p); - - return err == ERR_OK ? data_len : err; -} - #endif // AP_NETWORKING_BACKEND_CHIBIOS diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.h b/libraries/AP_Networking/AP_Networking_ChibiOS.h index 70c4f0b49d2f8a..71ebfb57a62504 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.h +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.h @@ -18,7 +18,6 @@ class AP_Networking_ChibiOS : public AP_Networking_Backend private: bool allocate_buffers(void); - int32_t send_udp(struct udp_pcb *pcb, const struct ip4_addr &ip4_addr, const uint16_t port, const uint8_t* data, uint16_t data_len); private: struct lwipthread_opts *lwip_options; From c54e6ce44b43f3aa41a448de79d79697c7d1be68 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 14 Nov 2023 09:07:25 +1100 Subject: [PATCH 187/499] AP_Networking: added NET_TEST_IP for test server IP address and default to same as default for DDS server --- libraries/AP_Networking/AP_Networking.cpp | 4 ++++ libraries/AP_Networking/AP_Networking.h | 1 + .../AP_Networking/AP_Networking_Config.h | 2 +- libraries/AP_Networking/AP_Networking_SITL.h | 22 +++++++++++++++++++ .../AP_Networking/AP_Networking_tests.cpp | 4 ++-- 5 files changed, 30 insertions(+), 3 deletions(-) create mode 100644 libraries/AP_Networking/AP_Networking_SITL.h diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 6e0161bfe258eb..1e3e1b47a07484 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -64,6 +64,10 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @RebootRequired: True // @User: Advanced AP_GROUPINFO("TESTS", 7, AP_Networking, param.tests, 0), + + // @Group: TEST_IP + // @Path: AP_Networking_address.cpp + AP_SUBGROUPINFO(param.test_ipaddr, "TEST_IP", 8, AP_Networking, AP_Networking_IPV4), #endif AP_GROUPEND diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 10a120a4c94197..d7e9bee1d59506 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -167,6 +167,7 @@ class AP_Networking AP_Int32 options; #if AP_NETWORKING_TESTS_ENABLED AP_Int32 tests; + AP_Networking_IPV4 test_ipaddr{AP_NETWORKING_TEST_IP}; #endif } param; diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index 992c44ab4b6856..16d105b230e5b6 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -67,6 +67,6 @@ #if AP_NETWORKING_TESTS_ENABLED #ifndef AP_NETWORKING_TEST_IP -#define AP_NETWORKING_TEST_IP "192.168.13.15" +#define AP_NETWORKING_TEST_IP "192.168.13.2" #endif #endif diff --git a/libraries/AP_Networking/AP_Networking_SITL.h b/libraries/AP_Networking/AP_Networking_SITL.h new file mode 100644 index 00000000000000..915e43f5f73413 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_SITL.h @@ -0,0 +1,22 @@ +#pragma once + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_BACKEND_SITL +#include "AP_Networking_Backend.h" + +class AP_Networking_SITL : public AP_Networking_Backend +{ +public: + using AP_Networking_Backend::AP_Networking_Backend; + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Networking_SITL); + + bool init() override { + return true; + } + void update() override {} +}; + +#endif // AP_NETWORKING_BACKEND_SITL diff --git a/libraries/AP_Networking/AP_Networking_tests.cpp b/libraries/AP_Networking/AP_Networking_tests.cpp index 29372b2bd949a5..b4b335f8727621 100644 --- a/libraries/AP_Networking/AP_Networking_tests.cpp +++ b/libraries/AP_Networking/AP_Networking_tests.cpp @@ -40,7 +40,7 @@ void AP_Networking::test_UDP_client(void) } hal.scheduler->delay(1000); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP_client: starting"); - const char *dest = AP_NETWORKING_TEST_IP; + const char *dest = param.test_ipaddr.get_str(); auto *sock = new SocketAPM(true); if (sock == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP_client: failed to create socket"); @@ -75,7 +75,7 @@ void AP_Networking::test_TCP_client(void) } hal.scheduler->delay(1000); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_client: starting"); - const char *dest = AP_NETWORKING_TEST_IP; + const char *dest = param.test_ipaddr.get_str(); auto *sock = new SocketAPM(false); if (sock == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_client: failed to create socket"); From 4a773eabb2e9270682909258d8ad193d1609842f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 14 Nov 2023 09:08:36 +1100 Subject: [PATCH 188/499] AP_Networking: added SITL backend this allows the net tests to run on SITL, and for DDS testing using the SocketAPM API --- libraries/AP_Networking/AP_Networking.cpp | 6 ++++++ libraries/AP_Networking/AP_Networking_Config.h | 4 ++++ 2 files changed, 10 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 1e3e1b47a07484..95f6a3920ee789 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -18,6 +18,9 @@ extern const AP_HAL::HAL& hal; #include #endif +#if AP_NETWORKING_BACKEND_SITL +#include "AP_Networking_SITL.h" +#endif const AP_Param::GroupInfo AP_Networking::var_info[] = { // @Param: ENABLED @@ -114,6 +117,9 @@ void AP_Networking::init() #if AP_NETWORKING_BACKEND_CHIBIOS backend = new AP_Networking_ChibiOS(*this); #endif +#if AP_NETWORKING_BACKEND_SITL + backend = new AP_Networking_SITL(*this); +#endif if (backend == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: backend failed"); diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index 16d105b230e5b6..70e45e0cf32c03 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -16,6 +16,10 @@ #define AP_NETWORKING_BACKEND_CHIBIOS AP_NETWORKING_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #endif +#ifndef AP_NETWORKING_BACKEND_SITL +#define AP_NETWORKING_BACKEND_SITL AP_NETWORKING_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL +#endif + #define AP_NETWORKING_SOCKETS_ENABLED (HAL_OS_SOCKETS || AP_NETWORKING_BACKEND_CHIBIOS) // --------------------------- From 8151ee36c7232f8169e0f0434a79b2052297190f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 14 Nov 2023 09:16:00 +1100 Subject: [PATCH 189/499] AP_Networking: fixed build with gcc 11.x --- libraries/AP_Networking/AP_Networking_tests.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_tests.cpp b/libraries/AP_Networking/AP_Networking_tests.cpp index b4b335f8727621..9370d93a23b407 100644 --- a/libraries/AP_Networking/AP_Networking_tests.cpp +++ b/libraries/AP_Networking/AP_Networking_tests.cpp @@ -54,7 +54,7 @@ void AP_Networking::test_UDP_client(void) while (true) { hal.scheduler->delay(100); char *s = nullptr; - asprintf(&s, "hello %u", unsigned(AP_HAL::millis())); + IGNORE_RETURN(asprintf(&s, "hello %u", unsigned(AP_HAL::millis()))); sock->send((const void*)s, strlen(s)); free(s); uint8_t buf[128] {}; @@ -89,7 +89,7 @@ void AP_Networking::test_TCP_client(void) while (true) { hal.scheduler->delay(100); char *s = nullptr; - asprintf(&s, "hello %u", unsigned(AP_HAL::millis())); + IGNORE_RETURN(asprintf(&s, "hello %u", unsigned(AP_HAL::millis()))); sock->send((const void*)s, strlen(s)); free(s); uint8_t buf[128] {}; From ba2cbbcebfae4fdddeff7d8cab65ea5aada14c5b Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 15 Nov 2023 01:45:16 -0800 Subject: [PATCH 190/499] Tools/autotest: fix whitespace in sim_vehicle.py --- Tools/autotest/sim_vehicle.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 6f202f184eecd6..42424488cf8f19 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -416,7 +416,7 @@ def do_build(opts, frame_options): if opts.enable_networking_tests: cmd_configure.append("--enable-networking-tests") - + pieces = [shlex.split(x) for x in opts.waf_configure_args] for piece in pieces: cmd_configure.extend(piece) From d189730b9fad16902fbf2a6667042cad8ef10131 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 15 Nov 2023 11:17:38 -0800 Subject: [PATCH 191/499] AP_DDS: fix defines to make astyle happy --- libraries/AP_DDS/AP_DDS_config.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_DDS/AP_DDS_config.h b/libraries/AP_DDS/AP_DDS_config.h index 094d2d4efb96c3..f1c71bbc871484 100644 --- a/libraries/AP_DDS/AP_DDS_config.h +++ b/libraries/AP_DDS/AP_DDS_config.h @@ -19,8 +19,8 @@ #ifndef AP_DDS_DEFAULT_UDP_IP_ADDR #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - #define AP_DDS_DEFAULT_UDP_IP_ADDR "192.168.13.2" +#define AP_DDS_DEFAULT_UDP_IP_ADDR "192.168.13.2" #else - #define AP_DDS_DEFAULT_UDP_IP_ADDR "127.0.0.1" +#define AP_DDS_DEFAULT_UDP_IP_ADDR "127.0.0.1" #endif #endif From b572fe80eca626ed8ffe09deb7193b2a00d664c3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 20:57:02 +1100 Subject: [PATCH 192/499] GCS_MAVLink: handle request autopilot capabilities as both long and int --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 14 ++++++-------- 2 files changed, 7 insertions(+), 9 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 897ef275e06ea1..8bce19b0c16b15 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -598,7 +598,7 @@ class GCS_MAVLINK void handle_send_autopilot_version(const mavlink_message_t &msg); #endif #if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED - MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet); + MAV_RESULT handle_command_request_autopilot_capabilities(const mavlink_command_int_t &packet); #endif virtual void send_banner(); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 19b33b06c56a8e..0fe426fd80ab55 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4519,7 +4519,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_int_t #endif #if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED -MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_request_autopilot_capabilities(const mavlink_command_int_t &packet) { if (!is_equal(packet.param1,1.0f)) { return MAV_RESULT_FAILED; @@ -4757,13 +4757,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t switch (packet.command) { -#if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED - case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: { - result = handle_command_request_autopilot_capabilities(packet); - break; - } -#endif - case MAV_CMD_DO_JUMP_TAG: result = handle_command_do_jump_tag(packet); break; @@ -5177,6 +5170,11 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p return handle_servorelay_message(packet); #endif +#if AP_MAVLINK_MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES_ENABLED + case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES: + return handle_command_request_autopilot_capabilities(packet); +#endif + case MAV_CMD_RUN_PREARM_CHECKS: return handle_command_run_prearm_checks(packet); From d7160aea2d2f3d3767cf01c318fb6176334b66c1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 14 Nov 2023 19:22:13 +1100 Subject: [PATCH 193/499] GCS_MAVLink: handle DO_SET_MISSION_CURRENT as both long and int --- libraries/GCS_MAVLink/GCS.h | 4 ++-- libraries/GCS_MAVLink/GCS_Common.cpp | 19 +++++++++---------- 2 files changed, 11 insertions(+), 12 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 8bce19b0c16b15..d0ea0232dec661 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -638,8 +638,8 @@ class GCS_MAVLINK virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg); virtual MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg); - virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet); - MAV_RESULT handle_command_do_jump_tag(const mavlink_command_long_t &packet); + virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_int_t &packet); + MAV_RESULT handle_command_do_jump_tag(const mavlink_command_int_t &packet); MAV_RESULT handle_command_battery_reset(const mavlink_command_int_t &packet); void handle_command_long(const mavlink_message_t &msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 0fe426fd80ab55..aa5716823e03f2 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4452,7 +4452,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_i // the current waypoint, rather than this DO command. It is hoped we // can move to this command in the future to avoid acknowledgement // issues with MISSION_SET_CURRENT -MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_command_int_t &packet) { AP_Mission *mission = AP::mission(); if (mission == nullptr) { @@ -4485,7 +4485,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_set_mission_current(const mavlink_comm return MAV_RESULT_ACCEPTED; } -MAV_RESULT GCS_MAVLINK::handle_command_do_jump_tag(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK::handle_command_do_jump_tag(const mavlink_command_int_t &packet) { AP_Mission *mission = AP::mission(); if (mission == nullptr) { @@ -4757,14 +4757,6 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t switch (packet.command) { - case MAV_CMD_DO_JUMP_TAG: - result = handle_command_do_jump_tag(packet); - break; - - case MAV_CMD_DO_SET_MISSION_CURRENT: - result = handle_command_do_set_mission_current(packet); - break; - default: result = try_command_long_as_command_int(packet, msg); break; @@ -5074,6 +5066,13 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p return handle_command_do_gripper(packet); #endif + case MAV_CMD_DO_JUMP_TAG: + result = handle_command_do_jump_tag(packet); + break; + + case MAV_CMD_DO_SET_MISSION_CURRENT: + return handle_command_do_set_mission_current(packet); + case MAV_CMD_DO_SET_MODE: return handle_command_do_set_mode(packet); From e0eacdc197d07b5a7c934f22e2a4e4b342c9121b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 14 Nov 2023 19:22:14 +1100 Subject: [PATCH 194/499] ArduPlane: handle DO_SET_MISSION_CURRENT as both long and int --- ArduPlane/GCS_Mavlink.cpp | 2 +- ArduPlane/GCS_Mavlink.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 3 +-- 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 71df773b681fda..2c199ba6446ee3 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1383,7 +1383,7 @@ void GCS_MAVLINK_Plane::handleMessage(const mavlink_message_t &msg) } // end switch } // end handle mavlink -MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_long_t &packet) +MAV_RESULT GCS_MAVLINK_Plane::handle_command_do_set_mission_current(const mavlink_command_int_t &packet) { const MAV_RESULT result = GCS_MAVLINK::handle_command_do_set_mission_current(packet); if (result != MAV_RESULT_ACCEPTED) { diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index b30ac872876695..b735540a01081e 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -26,7 +26,7 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK MAV_RESULT handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; - MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_long_t &packet) override; + MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_int_t &packet) override; void send_position_target_global_int() override; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index aa5716823e03f2..eda7797495e1af 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5067,8 +5067,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p #endif case MAV_CMD_DO_JUMP_TAG: - result = handle_command_do_jump_tag(packet); - break; + return handle_command_do_jump_tag(packet); case MAV_CMD_DO_SET_MISSION_CURRENT: return handle_command_do_set_mission_current(packet); From 485fa80f1caa7d006517d7923f68c80ccd331dd6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 21:23:54 +1100 Subject: [PATCH 195/499] GCS_MAVLink: collapse un-needed method --- libraries/GCS_MAVLink/GCS.h | 1 - libraries/GCS_MAVLink/GCS_Common.cpp | 16 +--------------- 2 files changed, 1 insertion(+), 16 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index d0ea0232dec661..5e2915174790ad 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -654,7 +654,6 @@ class GCS_MAVLINK virtual bool mav_frame_for_command_long(MAV_FRAME &fame, MAV_CMD packet_command) const; MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg); - MAV_RESULT handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg); MAV_RESULT handle_command_camera(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index eda7797495e1af..7c4032ca65287d 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4751,20 +4751,6 @@ MAV_RESULT GCS_MAVLINK::try_command_long_as_command_int(const mavlink_command_lo return handle_command_int_packet(command_int, msg); } -MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t &packet, const mavlink_message_t &msg) -{ - MAV_RESULT result = MAV_RESULT_FAILED; - - switch (packet.command) { - - default: - result = try_command_long_as_command_int(packet, msg); - break; - } - - return result; -} - bool GCS_MAVLINK::location_from_command_t(const mavlink_command_long_t &in, MAV_FRAME in_frame, Location &out) { mavlink_command_int_t command_int; @@ -4865,7 +4851,7 @@ void GCS_MAVLINK::handle_command_long(const mavlink_message_t &msg) hal.util->persistent_data.last_mavlink_cmd = packet.command; - const MAV_RESULT result = handle_command_long_packet(packet, msg); + const MAV_RESULT result = try_command_long_as_command_int(packet, msg); // send ACK or NAK mavlink_msg_command_ack_send(chan, packet.command, result, From 9ff9f8d216682cd2f1552bfb424cbe2b1ed06323 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 21:25:39 +1100 Subject: [PATCH 196/499] GCS_MAVLink: remove no-longer-required location_from_command_t(command_long) --- libraries/GCS_MAVLink/GCS.h | 3 +-- libraries/GCS_MAVLink/GCS_Common.cpp | 8 -------- 2 files changed, 1 insertion(+), 10 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 5e2915174790ad..e512ed7312e691 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -732,8 +732,7 @@ class GCS_MAVLINK // initialised. virtual void convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame = MAV_FRAME_GLOBAL_RELATIVE_ALT); - // methods to extract a Location object from a command_long or command_int - bool location_from_command_t(const mavlink_command_long_t &in, MAV_FRAME in_frame, Location &out); + // methods to extract a Location object from a command_int bool location_from_command_t(const mavlink_command_int_t &in, Location &out); private: diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 7c4032ca65287d..c04c2ba2cbb307 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4751,14 +4751,6 @@ MAV_RESULT GCS_MAVLINK::try_command_long_as_command_int(const mavlink_command_lo return handle_command_int_packet(command_int, msg); } -bool GCS_MAVLINK::location_from_command_t(const mavlink_command_long_t &in, MAV_FRAME in_frame, Location &out) -{ - mavlink_command_int_t command_int; - convert_COMMAND_LONG_to_COMMAND_INT(in, command_int, in_frame); - - return location_from_command_t(command_int, out); -} - bool GCS_MAVLINK::location_from_command_t(const mavlink_command_int_t &in, Location &out) { if (!command_long_stores_location((MAV_CMD)in.command)) { From 24f00ddaf7a1496f040d29df061f0ae706f7f782 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 21:31:03 +1100 Subject: [PATCH 197/499] GCS_MAVLink: add and use AP_MAVLINK_COMMAND_LONG_ENABLED --- libraries/GCS_MAVLink/GCS_Common.cpp | 2 ++ libraries/GCS_MAVLink/GCS_config.h | 7 +++++++ 2 files changed, 9 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index c04c2ba2cbb307..3a6de81ba52231 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4776,6 +4776,7 @@ bool GCS_MAVLINK::location_from_command_t(const mavlink_command_int_t &in, Locat return true; } +#if AP_MAVLINK_COMMAND_LONG_ENABLED bool GCS_MAVLINK::command_long_stores_location(const MAV_CMD command) { switch(command) { @@ -4858,6 +4859,7 @@ void GCS_MAVLINK::handle_command_long(const mavlink_message_t &msg) hal.util->persistent_data.last_mavlink_cmd = 0; } +#endif // AP_MAVLINK_COMMAND_LONG_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi(const Location &roi_loc) { diff --git a/libraries/GCS_MAVLink/GCS_config.h b/libraries/GCS_MAVLink/GCS_config.h index 2b981702f7ecda..ae978c1253cf39 100644 --- a/libraries/GCS_MAVLink/GCS_config.h +++ b/libraries/GCS_MAVLink/GCS_config.h @@ -86,3 +86,10 @@ #ifndef AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED #define AP_MAVLINK_MSG_MISSION_REQUEST_ENABLED 1 #endif + +// all commands can be executed by COMMAND_INT, so COMMAND_LONG isn't +// strictly required. This option created for 4.5, Nov 2023, and code +// left in place. +#ifndef AP_MAVLINK_COMMAND_LONG_ENABLED +#define AP_MAVLINK_COMMAND_LONG_ENABLED 1 +#endif From e7ff4a43ca53cc7e3db4c495be66c3337ecb1180 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 21:31:03 +1100 Subject: [PATCH 198/499] ArduCopter: add and use AP_MAVLINK_COMMAND_LONG_ENABLED --- ArduCopter/GCS_Mavlink.cpp | 2 ++ ArduCopter/GCS_Mavlink.h | 2 ++ 2 files changed, 4 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index ee174cc933f35f..4f5c8cd9f03e8f 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -877,6 +877,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_NAV_TAKEOFF(const mavlink_command_ return MAV_RESULT_ACCEPTED; } +#if AP_MAVLINK_COMMAND_LONG_ENABLED bool GCS_MAVLINK_Copter::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const { if (packet_command == MAV_CMD_NAV_TAKEOFF || @@ -886,6 +887,7 @@ bool GCS_MAVLINK_Copter::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD pa } return GCS_MAVLINK::mav_frame_for_command_long(frame, packet_command); } +#endif MAV_RESULT GCS_MAVLINK_Copter::handle_MAV_CMD_CONDITION_YAW(const mavlink_command_int_t &packet) diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 98de6b502f3866..7470434f4339da 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -108,7 +108,9 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK MAV_RESULT handle_MAV_CMD_SOLO_BTN_PAUSE_CLICK(const mavlink_command_int_t &packet); #endif +#if AP_MAVLINK_COMMAND_LONG_ENABLED bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override; +#endif MAV_RESULT handle_MAV_CMD_MISSION_START(const mavlink_command_int_t &packet); MAV_RESULT handle_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet); From 4b285fa579e8b6ad256f626c4adaeee765de0ac5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 21:31:03 +1100 Subject: [PATCH 199/499] ArduPlane: add and use AP_MAVLINK_COMMAND_LONG_ENABLED --- ArduPlane/GCS_Mavlink.cpp | 2 ++ ArduPlane/GCS_Mavlink.h | 2 ++ 2 files changed, 4 insertions(+) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 2c199ba6446ee3..196ce4e773b35b 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1105,6 +1105,7 @@ void GCS_MAVLINK_Plane::convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink out.z = -in.param7; // up -> down } +#if AP_MAVLINK_COMMAND_LONG_ENABLED void GCS_MAVLINK_Plane::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame) { switch (in.command) { @@ -1114,6 +1115,7 @@ void GCS_MAVLINK_Plane::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_comman } return GCS_MAVLINK::convert_COMMAND_LONG_to_COMMAND_INT(in, out, frame); } +#endif // AP_MAVLINK_COMMAND_LONG_ENABLED MAV_RESULT GCS_MAVLINK_Plane::handle_command_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet) { diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index b735540a01081e..41cb8e6b123f5f 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -62,8 +62,10 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK MAV_RESULT handle_command_DO_VTOL_TRANSITION(const mavlink_command_int_t &packet); #if HAL_QUADPLANE_ENABLED +#if AP_MAVLINK_COMMAND_LONG_ENABLED void convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out); void convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame = MAV_FRAME_GLOBAL_RELATIVE_ALT) override; +#endif MAV_RESULT handle_command_MAV_CMD_NAV_TAKEOFF(const mavlink_command_int_t &packet); #endif From 7a5ee38b9ff24f6e65c5375898715c84dce3595e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 21:31:04 +1100 Subject: [PATCH 200/499] Blimp: add and use AP_MAVLINK_COMMAND_LONG_ENABLED --- Blimp/GCS_Mavlink.cpp | 2 ++ Blimp/GCS_Mavlink.h | 2 ++ 2 files changed, 4 insertions(+) diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index c96624649184a1..a0bf1c4ba5fb97 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -488,6 +488,7 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_packet(const mavlink_command_in } } +#if AP_MAVLINK_COMMAND_LONG_ENABLED bool GCS_MAVLINK_Blimp::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const { if (packet_command == MAV_CMD_NAV_TAKEOFF) { @@ -496,6 +497,7 @@ bool GCS_MAVLINK_Blimp::mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD pac } return GCS_MAVLINK::mav_frame_for_command_long(frame, packet_command); } +#endif void GCS_MAVLINK_Blimp::handleMessage(const mavlink_message_t &msg) { diff --git a/Blimp/GCS_Mavlink.h b/Blimp/GCS_Mavlink.h index c248ae0886e2b1..756dddc3fcf24e 100644 --- a/Blimp/GCS_Mavlink.h +++ b/Blimp/GCS_Mavlink.h @@ -29,7 +29,9 @@ class GCS_MAVLINK_Blimp : public GCS_MAVLINK MAV_RESULT handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) override; MAV_RESULT handle_command_int_do_reposition(const mavlink_command_int_t &packet); +#if AP_MAVLINK_COMMAND_LONG_ENABLED bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override; +#endif bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED; bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED; From ec2b47ba5950ad106ccb693d00b588caa5ddd8c0 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Wed, 15 Nov 2023 17:41:01 -0700 Subject: [PATCH 201/499] Tools: ros2: Enable networking when needed * DDS was built without networking so UDP stopped working * Networking is automatically added when you want network tests * --enable-networking should only be on sitl Signed-off-by: Ryan Friedman --- Tools/autotest/sim_vehicle.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 42424488cf8f19..0c849f6405b6b8 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -410,12 +410,16 @@ def do_build(opts, frame_options): if opts.enable_dds: cmd_configure.append("--enable-dds") + if configure_target == 'sitl' and "--enable-networking" not in cmd_configure: + cmd_configure.append("--enable-networking") - if opts.enable_networking: + if opts.enable_networking and configure_target == 'sitl': cmd_configure.append("--enable-networking") if opts.enable_networking_tests: cmd_configure.append("--enable-networking-tests") + if "--enable-networking" not in cmd_configure: + cmd_configure.append("--enable-networking") pieces = [shlex.split(x) for x in opts.waf_configure_args] for piece in pieces: From c09352102ef45b372f14532fc09dec548bd8f97c Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Wed, 15 Nov 2023 18:19:19 -0700 Subject: [PATCH 202/499] waf: Improve help text for network tests Signed-off-by: Ryan Friedman --- wscript | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/wscript b/wscript index 393eab94c75fa1..7f0a2e14dfe356 100644 --- a/wscript +++ b/wscript @@ -267,13 +267,13 @@ submodules at specific revisions. help="Enables GPS logging") g.add_option('--enable-dds', action='store_true', - help="Enable the dds client to connect with ROS2/DDS") + help="Enable the dds client to connect with ROS2/DDS.") g.add_option('--enable-networking', action='store_true', help="Enable the networking code") g.add_option('--enable-networking-tests', action='store_true', - help="Enable the networking test code") + help="Enable the networking test code. Automatically enables networking.") g.add_option('--enable-dronecan-tests', action='store_true', default=False, From 7472f76336a4f887a06b9d089f90f12b6ac85837 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 15 Nov 2023 13:24:28 +1100 Subject: [PATCH 203/499] AP_Mount: set clock on SIYI this means photos on microSD have correct date --- libraries/AP_Mount/AP_Mount_Siyi.cpp | 12 ++++++++++++ libraries/AP_Mount/AP_Mount_Siyi.h | 4 ++++ 2 files changed, 16 insertions(+) diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index c1fe0504d73101..bbe829d47673b9 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -6,6 +6,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -68,6 +69,17 @@ void AP_Mount_Siyi::update() } else { request_configuration(); } + +#if AP_RTC_ENABLED + // send UTC time to the camera + if (sent_time_count < 5) { + uint64_t utc_usec; + if (AP::rtc().get_utc_usec(utc_usec) && + send_packet(SiyiCommandId::SET_TIME, (const uint8_t *)&utc_usec, sizeof(utc_usec))) { + sent_time_count++; + } + } +#endif } // request attitude at regular intervals diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index 60e40f4f2c164f..54f4d2b909b5c6 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -112,6 +112,7 @@ class AP_Mount_Siyi : public AP_Mount_Backend SET_CAMERA_IMAGE_TYPE = 0x11, READ_RANGEFINDER = 0x15, EXTERNAL_ATTITUDE = 0x22, + SET_TIME = 0x30, }; // Function Feedback Info packet info_type values @@ -335,6 +336,9 @@ class AP_Mount_Siyi : public AP_Mount_Backend const char* model_name; }; static const HWInfo hardware_lookup_table[]; + + // count of SET_TIME packets, we send 5 times to cope with packet loss + uint8_t sent_time_count; }; #endif // HAL_MOUNT_SIYISERIAL_ENABLED From 8ff2fa4fd9c3f0aaade18921120a4d0a6dd83366 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Nov 2023 09:36:30 +1100 Subject: [PATCH 204/499] AP_Mount: added gimbal rates for SIYI this helps diagnose issues with gyro bias versus control when camera is spinning --- libraries/AP_Mount/AP_Mount_Backend.cpp | 8 +++++--- libraries/AP_Mount/AP_Mount_Backend.h | 3 +++ libraries/AP_Mount/AP_Mount_Siyi.cpp | 8 ++++---- libraries/AP_Mount/AP_Mount_Siyi.h | 7 +++++++ 4 files changed, 19 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index d3cc0cb490ddc9..f05e7430eb95d6 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -142,6 +142,8 @@ void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan if (!get_attitude_quaternion(att_quat)) { return; } + Vector3f ang_velocity { nanf(""), nanf(""), nanf("") }; + IGNORE_RETURN(get_angular_velocity(ang_velocity)); // construct quaternion array const float quat_array[4] = {att_quat.q1, att_quat.q2, att_quat.q3, att_quat.q4}; @@ -152,9 +154,9 @@ void AP_Mount_Backend::send_gimbal_device_attitude_status(mavlink_channel_t chan AP_HAL::millis(), // autopilot system time get_gimbal_device_flags(), quat_array, // attitude expressed as quaternion - std::numeric_limits::quiet_NaN(), // roll axis angular velocity (NaN for unknown) - std::numeric_limits::quiet_NaN(), // pitch axis angular velocity (NaN for unknown) - std::numeric_limits::quiet_NaN(), // yaw axis angular velocity (NaN for unknown) + ang_velocity.x, // roll axis angular velocity (NaN for unknown) + ang_velocity.y, // pitch axis angular velocity (NaN for unknown) + ang_velocity.z, // yaw axis angular velocity (NaN for unknown) 0, // failure flags (not supported) std::numeric_limits::quiet_NaN(), // delta_yaw (NaN for unknonw) std::numeric_limits::quiet_NaN(), // delta_yaw_velocity (NaN for unknonw) diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 0503d02ae648ab..1c873e48e69473 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -67,6 +67,9 @@ class AP_Mount_Backend // yaw is in body-frame. virtual bool get_attitude_quaternion(Quaternion& att_quat) = 0; + // get angular velocity of mount. Only available on some backends + virtual bool get_angular_velocity(Vector3f& rates) { return false; } + // get mount's mode enum MAV_MOUNT_MODE get_mode() const { return _mode; } diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index bbe829d47673b9..0cdc907f9dee8d 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -99,7 +99,7 @@ void AP_Mount_Siyi::update() _last_attitude_send_ms = now_ms; send_attitude(); } - + // run zoom control update_zoom_control(); @@ -540,9 +540,9 @@ void AP_Mount_Siyi::process_packet() _current_angle_rad.z = -radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+1], _msg_buff[_msg_buff_data_start]) * 0.1); // yaw angle _current_angle_rad.y = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+3], _msg_buff[_msg_buff_data_start+2]) * 0.1); // pitch angle _current_angle_rad.x = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+5], _msg_buff[_msg_buff_data_start+4]) * 0.1); // roll angle - //const float yaw_rate_degs = -(int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+7], _msg_buff[_msg_buff_data_start+6]) * 0.1; // yaw rate - //const float pitch_rate_deg = (int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+9], _msg_buff[_msg_buff_data_start+8]) * 0.1; // pitch rate - //const float roll_rate_deg = (int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+11], _msg_buff[_msg_buff_data_start+10]) * 0.1; // roll rate + _current_rates_rads.z = -radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+7], _msg_buff[_msg_buff_data_start+6]) * 0.1); // yaw rate + _current_rates_rads.y = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+9], _msg_buff[_msg_buff_data_start+8]) * 0.1); // pitch rate + _current_rates_rads.x = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+11], _msg_buff[_msg_buff_data_start+10]) * 0.1); // roll rate break; } diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index 54f4d2b909b5c6..2245e4ca0dd346 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -93,6 +93,12 @@ class AP_Mount_Siyi : public AP_Mount_Backend // get attitude as a quaternion. returns true on success bool get_attitude_quaternion(Quaternion& att_quat) override; + // get angular velocity of mount. Only available on some backends + bool get_angular_velocity(Vector3f& rates) override { + rates = _current_rates_rads; + return true; + } + private: // serial protocol command ids @@ -309,6 +315,7 @@ class AP_Mount_Siyi : public AP_Mount_Backend // actual attitude received from gimbal Vector3f _current_angle_rad; // current angles in radians received from gimbal (x=roll, y=pitch, z=yaw) + Vector3f _current_rates_rads; // current angular rates in rad/s (x=roll, y=pitch, z=yaw) uint32_t _last_current_angle_rad_ms; // system time _current_angle_rad was updated uint32_t _last_req_current_angle_rad_ms; // system time that this driver last requested current angle From 4cb2562ee523932ec0cfb4e42769e41eb0124c78 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Nov 2023 16:35:56 +1100 Subject: [PATCH 205/499] AP_DroneCAN: cope with null stats (for SLCAN interface) this caused a crash on CubeOrange on boot if SLCAN is enabled --- libraries/AP_DroneCAN/AP_Canard_iface.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index 5fa96606f5be43..60980e510f8f9a 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.cpp +++ b/libraries/AP_DroneCAN/AP_Canard_iface.cpp @@ -217,7 +217,7 @@ void CanardInterface::processTx(bool raw_commands_only = false) { // volatile as the value can change at any time during can interrupt // we need to ensure that this is not optimized volatile const auto *stats = ifaces[iface]->get_statistics(); - uint64_t last_transmit_us = stats->last_transmit_us; + uint64_t last_transmit_us = stats==nullptr?0:stats->last_transmit_us; bool iface_down = true; if (stats == nullptr || (AP_HAL::micros64() - last_transmit_us) < 200000UL) { /* From 2c23ae970f97f559ff1157f889e86beae80f3504 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 15 Nov 2023 23:35:16 -0800 Subject: [PATCH 206/499] AP_Periph: allow showing SerialManager params without HAL_GCS --- Tools/AP_Periph/Parameters.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 80b3ae7d44a219..02da8a657a23be 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -443,7 +443,9 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Range: 1 255 // @User: Advanced GSCALAR(sysid_this_mav, "SYSID_THISMAV", MAV_SYSTEM_ID), +#endif +#if HAL_GCS_ENABLED || defined(HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS) // @Group: SERIAL // @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp GOBJECT(serial_manager, "SERIAL", AP_SerialManager), From ac16f10ecdd2848a25b8ae4574f42af51f43b0ea Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 15 Nov 2023 23:34:28 -0800 Subject: [PATCH 207/499] AP_HAL_ChibiOS: hwdef kha_eth to show SerialManager params --- libraries/AP_HAL_ChibiOS/hwdef/kha_eth/hwdef.dat | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/kha_eth/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/kha_eth/hwdef.dat index 4e94f0a10dada7..72def407252939 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/kha_eth/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/kha_eth/hwdef.dat @@ -135,11 +135,12 @@ define DISABLE_SERIAL_ESC_COMM TRUE define HAL_NO_RCIN_THREAD #define HAL_NO_GPIO_IRQ define HAL_DISABLE_LOOP_DELAY +define HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS define PERIPH_FW TRUE #define NO_DATAFLASH TRUE -define HAL_LOGGING_ENABLED TRUE +define HAL_LOGGING_ENABLED FALSE ################################# # AP_Periph - configurations specific to this App From 8c27d81c6a47bb16c413ed71032383628823b459 Mon Sep 17 00:00:00 2001 From: muramura Date: Wed, 15 Nov 2023 23:26:11 +0900 Subject: [PATCH 208/499] AP_RangeFinder: Move to a process that uses maximum value acquisition --- libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp index b360aa4d65f676..d54ef55d5f081c 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.cpp @@ -53,8 +53,6 @@ bool AP_RangeFinder_JRE_Serial::get_reading(float &reading_m) uint16_t valid_count = 0; // number of valid readings uint16_t invalid_count = 0; // number of invalid readings float sum = 0; - // max distance the sensor can reliably measure - read from parameters - const int16_t distance_cm_max = max_distance_cm(); // read a maximum of 8192 bytes per call to this function: uint16_t bytes_available = MIN(uart->available(), 8192U); @@ -136,7 +134,7 @@ bool AP_RangeFinder_JRE_Serial::get_reading(float &reading_m) // all readings were invalid so return out-of-range-high value if (invalid_count > 0) { no_signal = true; - reading_m = MIN(MAX(DIST_MAX_CM, distance_cm_max + OUT_OF_RANGE_ADD_CM), UINT16_MAX) * 0.01f; + reading_m = MIN(MAX(DIST_MAX_CM, max_distance_cm() + OUT_OF_RANGE_ADD_CM), UINT16_MAX) * 0.01f; return true; } From 4dcc64d82d97a7eb4d959eb6ffd0456404f1b3fe Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 12 Nov 2023 09:49:32 +1100 Subject: [PATCH 209/499] AP_Scripting: added more params to revert script --- libraries/AP_Scripting/applets/revert_param.lua | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/applets/revert_param.lua b/libraries/AP_Scripting/applets/revert_param.lua index b6cedcd227feb6..9eb8938596b857 100644 --- a/libraries/AP_Scripting/applets/revert_param.lua +++ b/libraries/AP_Scripting/applets/revert_param.lua @@ -54,7 +54,7 @@ local param_count = 0 local ATC_prefixes = { "ATC", "Q_A" } local PSC_prefixes = { "PSC", "Q_P" } local PID_prefixes = { "_RAT_RLL_", "_RAT_PIT_", "_RAT_YAW_" } -local PID_suffixes = { "FF", "P", "I", "D", "IMAX", "FLTD", "FLTE", "FLTT", "SMAX" } +local PID_suffixes = { "FF", "P", "I", "D", "D_FF", "PDMX", "NEF", "NTF", "IMAX", "FLTD", "FLTE", "FLTT", "SMAX" } local angle_axes = { "RLL", "PIT", "YAW" } local PSC_types = { "ACCZ", "VELZ", "POSZ", "VELXY", "POSXY" } local OTHER_PARAMS = { "INS_GYRO_FILTER", "INS_ACCEL_FILTER" } From bd05fad850c1ad2b3a857623919ff5adc7bc5c25 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 14 Nov 2023 14:06:05 +1100 Subject: [PATCH 210/499] SITL: add code to add, remove or corrupt bytes in SITL::SerialDevice xfrs --- libraries/SITL/SIM_SerialDevice.cpp | 61 +++++++++++++++++++++++------ libraries/SITL/SIM_SerialDevice.h | 2 + libraries/SITL/SIM_config.h | 4 ++ 3 files changed, 56 insertions(+), 11 deletions(-) diff --git a/libraries/SITL/SIM_SerialDevice.cpp b/libraries/SITL/SIM_SerialDevice.cpp index 64eb1edb875260..19065b7152de62 100644 --- a/libraries/SITL/SIM_SerialDevice.cpp +++ b/libraries/SITL/SIM_SerialDevice.cpp @@ -44,9 +44,45 @@ bool SerialDevice::init_sitl_pointer() return true; } +#if AP_SIM_SERIALDEVICE_CORRUPTION_ENABLED +ssize_t SerialDevice::corrupt_transfer(char *buffer, const ssize_t ret, const size_t size) const +{ + if (ret > 0 && (rand() % 100) < 2) { + // drop a random byte from returned data: + const size_t byte_ofs_to_drop = rand() % ret; + fprintf(stderr, "dropping byte at offset %u\n", unsigned(byte_ofs_to_drop)); + memmove(&buffer[byte_ofs_to_drop], &buffer[byte_ofs_to_drop+1], ret - byte_ofs_to_drop - 1); + return ret - 1; + } + + if (ret > 0 && size_t(ret) < size && (rand() % 100) < 2) { + // add a random byte to the stream: + const size_t byte_ofs_to_add = rand() % ret; + fprintf(stderr, "adding byte at offset %u\n", unsigned(byte_ofs_to_add)); + memmove(&buffer[byte_ofs_to_add+1], &buffer[byte_ofs_to_add], ret - byte_ofs_to_add); + buffer[byte_ofs_to_add] = rand()*256; + return ret + 1; + } + + if (ret > 0 && unsigned(ret) < size && (rand() % 100) < 2) { + // corrupt a random byte in the stream: + const size_t byte_ofs_to_corrupt = rand() % ret; + fprintf(stderr, "corrupting byte at offset=%u\n", unsigned(byte_ofs_to_corrupt)); + buffer[byte_ofs_to_corrupt] = rand()*256; + return ret; + } + + return ret; +} +#endif + ssize_t SerialDevice::read_from_autopilot(char *buffer, const size_t size) const { - const ssize_t ret = from_autopilot->read((uint8_t*)buffer, size); + ssize_t ret = from_autopilot->read((uint8_t*)buffer, size); +#if AP_SIM_SERIALDEVICE_CORRUPTION_ENABLED + ret = corrupt_transfer(buffer, ret, size); +#endif + // if (ret > 0) { // ::fprintf(stderr, "SIM_SerialDevice: read from autopilot (%u): (", (unsigned)ret); // for (ssize_t i=0; iwrite((uint8_t*)buffer, size); - // ::fprintf(stderr, "write to autopilot: ("); - // for (ssize_t i=0; iread((uint8_t*)buffer, size); + ssize_t ret = to_autopilot->read((uint8_t*)buffer, size); +#if AP_SIM_SERIALDEVICE_CORRUPTION_ENABLED + ret = corrupt_transfer(buffer, ret, size); +#endif + // ::fprintf(stderr, "read_from_device: ("); + // for (ssize_t i=0; i Date: Wed, 15 Nov 2023 10:02:53 +1100 Subject: [PATCH 211/499] AP_Mount: validate modes before setting them --- libraries/AP_Mount/AP_Mount_Backend.cpp | 20 ++++++++++++++++++++ libraries/AP_Mount/AP_Mount_Backend.h | 7 +++++-- 2 files changed, 25 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index f05e7430eb95d6..8545d75b90bf23 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -46,6 +46,26 @@ bool AP_Mount_Backend::has_pitch_control() const return (_params.pitch_angle_min < _params.pitch_angle_max); } +bool AP_Mount_Backend::valid_mode(MAV_MOUNT_MODE mode) const +{ + switch (mode) { + case MAV_MOUNT_MODE_RETRACT...MAV_MOUNT_MODE_HOME_LOCATION: + return true; + case MAV_MOUNT_MODE_ENUM_END: + return false; + } + return false; +} + +bool AP_Mount_Backend::set_mode(MAV_MOUNT_MODE mode) +{ + if (!valid_mode(mode)) { + return false; + } + _mode = mode; + return true; +} + // set angle target in degrees // yaw_is_earth_frame (aka yaw_lock) should be true if yaw angle is earth-frame, false if body-frame void AP_Mount_Backend::set_angle_target(float roll_deg, float pitch_deg, float yaw_deg, bool yaw_is_earth_frame) diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 1c873e48e69473..b88ddf42bf760c 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -69,12 +69,15 @@ class AP_Mount_Backend // get angular velocity of mount. Only available on some backends virtual bool get_angular_velocity(Vector3f& rates) { return false; } - + + // returns true if mode is a valid mode, false otherwise: + bool valid_mode(MAV_MOUNT_MODE mode) const; + // get mount's mode enum MAV_MOUNT_MODE get_mode() const { return _mode; } // set mount's mode - void set_mode(enum MAV_MOUNT_MODE mode) { _mode = mode; } + bool set_mode(enum MAV_MOUNT_MODE mode); // set yaw_lock. If true, the gimbal's yaw target is maintained in earth-frame meaning it will lock onto an earth-frame heading (e.g. North) // If false (aka "follow") the gimbal's yaw is maintained in body-frame meaning it will rotate with the vehicle From afd18cf13a90a3f65e7a3cb0ecc0966d6990874b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 10 Nov 2023 18:35:49 +1100 Subject: [PATCH 212/499] AP_Relay: make set() method public this neatens up some calling code --- libraries/AP_Relay/AP_Relay.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Relay/AP_Relay.h b/libraries/AP_Relay/AP_Relay.h index 1d049ce76493b5..c14e964c54ea47 100644 --- a/libraries/AP_Relay/AP_Relay.h +++ b/libraries/AP_Relay/AP_Relay.h @@ -29,6 +29,9 @@ class AP_Relay { // setup the relay pin void init(); + // set relay to state + void set(uint8_t instance, bool value); + // activate the relay void on(uint8_t instance) { set(instance, true); } @@ -63,8 +66,6 @@ class AP_Relay { uint8_t _pin_states; uint8_t _last_logged_pin_states; uint32_t _last_log_ms; - - void set(uint8_t instance, bool value); }; namespace AP { From 07d76a87fd5c77fc0505d46502e281eaefd6b163 Mon Sep 17 00:00:00 2001 From: Pradeep CK Date: Thu, 26 Oct 2023 16:17:19 +1100 Subject: [PATCH 213/499] AP_ICEngine: support relay for ignition and I2C for starter --- libraries/AP_ICEngine/AP_ICEngine.cpp | 65 +++++++++++-- libraries/AP_ICEngine/AP_ICEngine.h | 24 ++++- libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp | 97 +++++++++++++++++++ libraries/AP_ICEngine/AP_ICEngine_TCA9554.h | 30 ++++++ libraries/AP_ICEngine/AP_ICEngine_config.h | 8 ++ 5 files changed, 211 insertions(+), 13 deletions(-) create mode 100644 libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp create mode 100644 libraries/AP_ICEngine/AP_ICEngine_TCA9554.h diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index 852df82dbe535a..d7afd09e92fd8f 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -25,6 +25,8 @@ #include #include #include +#include +#include "AP_ICEngine.h" extern const AP_HAL::HAL& hal; @@ -163,10 +165,18 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { AP_GROUPINFO("REDLINE_RPM", 17, AP_ICEngine, redline_rpm, 0), #endif +#if AP_RELAY_ENABLED + // @Param: IGNITION_RLY + // @DisplayName: Ignition relay channel + // @Description: This is a a relay channel to use for ignition control + // @User: Standard + // @Values: 0:None,1:Relay1,2:Relay2,3:Relay3,4:Relay4,5:Relay5,6:Relay6 + AP_GROUPINFO("IGNITION_RLY", 18, AP_ICEngine, ignition_relay, 0), +#endif + AP_GROUPEND }; - // constructor AP_ICEngine::AP_ICEngine() { @@ -378,20 +388,21 @@ void AP_ICEngine::update(void) case ICE_DISABLED: return; case ICE_OFF: - SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_off); - SRV_Channels::set_output_pwm(SRV_Channel::k_starter, pwm_starter_off); + set_ignition(false); + set_starter(false); starter_start_time_ms = 0; break; case ICE_START_HEIGHT_DELAY: case ICE_START_DELAY: - SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_on); - SRV_Channels::set_output_pwm(SRV_Channel::k_starter, pwm_starter_off); + set_ignition(true); + set_starter(false); break; case ICE_STARTING: - SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_on); - SRV_Channels::set_output_pwm(SRV_Channel::k_starter, pwm_starter_on); + set_ignition(true); + set_starter(true); + if (starter_start_time_ms == 0) { starter_start_time_ms = now; } @@ -399,8 +410,8 @@ void AP_ICEngine::update(void) break; case ICE_RUNNING: - SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, pwm_ignition_on); - SRV_Channels::set_output_pwm(SRV_Channel::k_starter, pwm_starter_off); + set_ignition(true); + set_starter(false); starter_start_time_ms = 0; break; } @@ -591,6 +602,42 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle) #endif // AP_RPM_ENABLED } +/* + set ignition state + */ +void AP_ICEngine::set_ignition(bool on) +{ + SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, on? pwm_ignition_on : pwm_ignition_off); +#if AP_RELAY_ENABLED + // optionally use a relay as well + if (ignition_relay > 0) { + auto *relay = AP::relay(); + if (relay != nullptr) { + relay->set(ignition_relay-1, on); + } + } +#endif // AP_RELAY_ENABLED +} + +/* + set starter state + */ +void AP_ICEngine::set_starter(bool on) +{ + SRV_Channels::set_output_pwm(SRV_Channel::k_starter, on? pwm_starter_on : pwm_starter_off); + +#if AP_ICENGINE_TCA9554_STARTER_ENABLED + tca9554_starter.set_starter(on); +#endif +} + + +bool AP_ICEngine::allow_throttle_while_disarmed() const +{ + return option_set(Options::THROTTLE_WHILE_DISARMED) && + hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED; +} + // singleton instance. Should only ever be set in the constructor. AP_ICEngine *AP_ICEngine::_singleton; namespace AP { diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 743f8ccb9973a5..919e763b28201f 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -25,6 +25,12 @@ #include #include #include +#include +#include + +#if AP_ICENGINE_TCA9554_STARTER_ENABLED +#include "AP_ICEngine_TCA9554.h" +#endif class AP_ICEngine { public: @@ -58,15 +64,16 @@ class AP_ICEngine { void update_idle_governor(int8_t &min_throttle); // do we have throttle while disarmed enabled? - bool allow_throttle_while_disarmed(void) const { - return enable && option_set(Options::THROTTLE_WHILE_DISARMED); - } + bool allow_throttle_while_disarmed(void) const; static AP_ICEngine *get_singleton() { return _singleton; } private: static AP_ICEngine *_singleton; + void set_ignition(bool on); + void set_starter(bool on); + enum ICE_State state; #if AP_RPM_ENABLED @@ -128,7 +135,12 @@ class AP_ICEngine { // Idle Controller Slew Rate AP_Float idle_slew; #endif - + +#if AP_RELAY_ENABLED + // relay number for ignition + AP_Int8 ignition_relay; +#endif + // height when we enter ICE_START_HEIGHT_DELAY float initial_height; @@ -159,6 +171,10 @@ class AP_ICEngine { uint16_t start_chan_last_value = 1500; uint32_t start_chan_last_ms; +#if AP_ICENGINE_TCA9554_STARTER_ENABLED + AP_ICEngine_TCA9554 tca9554_starter; +#endif + #if AP_RPM_ENABLED // redline rpm AP_Int32 redline_rpm; diff --git a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp new file mode 100644 index 00000000000000..fddfa3363fc113 --- /dev/null +++ b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.cpp @@ -0,0 +1,97 @@ +#include "AP_ICEngine_config.h" + +/* + support for TCA9554 for starter control on I2C + */ + +#if AP_ICENGINE_TCA9554_STARTER_ENABLED +#include "AP_ICEngine.h" + +extern const AP_HAL::HAL& hal; + +/* + * TCA9554 output register mapping for PMB Rev E + * P0 = PMU_EN - PMU output ON/OFF (CN6 pin 2) + * P1 = ECU_EN - Unused (previously Engine Kill Switch) + * P2 = I2C_P2 - Unused + * P3 = LED (active low) + * P4 = PMU_START - Crank Direction (CN6 pin 5) + * P5 = PMU_ARM - Crank Signal (CN6 pin 6) + * P6 = PMU_STAT_IN - Unused + * P7 = PMU_STAT - Unused + */ +#define TCA9554_I2C_BUS 1 +#define TCA9554_I2C_ADDR 0x20 +#define TCA9554_OUTPUT 0x01 // Output Port register address. Outgoing logic levels +#define TCA9554_OUT_DEFAULT 0x30 // 0011 0000 +#define TCA9554_CONF 0x03 // Configuration Port register address [0 = Output] +#define TCA9554_PINS 0xC2 // Set all used ports to outputs = 1100 0010 + +/* + initialise TCA9554 + */ +bool AP_ICEngine_TCA9554::TCA9554_init() +{ + dev_TCA9554 = std::move(hal.i2c_mgr->get_device(TCA9554_I2C_BUS, TCA9554_I2C_ADDR)); + if (!dev_TCA9554) { + return false; + } + WITH_SEMAPHORE(dev_TCA9554->get_semaphore()); + + // setup 1 checked registers + dev_TCA9554->setup_checked_registers(1); + + dev_TCA9554->set_retries(10); + + // set outputs + bool ret = dev_TCA9554->write_register(TCA9554_OUTPUT, TCA9554_OUT_DEFAULT); + if (!ret) { + return false; + } + ret = dev_TCA9554->write_register(TCA9554_CONF, TCA9554_PINS, true); + if (!ret) { + return false; + } + + dev_TCA9554->set_retries(1); + return true; +} + +/* + set the state of the i2c controller + */ +void AP_ICEngine_TCA9554::TCA9554_set(TCA9554_state_t value) +{ + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - last_reg_check_ms > 100) { + /* + register checking at 10Hz allows us to cope with the i2c + device being power cycled after boot + */ + last_reg_check_ms = now_ms; + WITH_SEMAPHORE(dev_TCA9554->get_semaphore()); + dev_TCA9554->check_next_register(); + } + + if (value != last_state) { + WITH_SEMAPHORE(dev_TCA9554->get_semaphore()); + // set outputs and status leds + if (dev_TCA9554->write_register(TCA9554_OUTPUT, (~(value<<2) & 0x0C) | value)) { + last_state = value; + } + } +} + +void AP_ICEngine_TCA9554::set_starter(bool on) +{ + if (!initialised) { + initialised = TCA9554_init(); + if (!initialised) { + // waiting for power to PMU + return; + } + } + TCA9554_set(on? STARTER_ON : STARTER_OFF); +} + +#endif // AP_ICENGINE_TCA9554_STARTER_ENABLED diff --git a/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h new file mode 100644 index 00000000000000..005a5ece6cfdff --- /dev/null +++ b/libraries/AP_ICEngine/AP_ICEngine_TCA9554.h @@ -0,0 +1,30 @@ +/* + optional control of starter via a TCA9554 I2C + */ + +#include "AP_ICEngine_config.h" + +#if AP_ICENGINE_TCA9554_STARTER_ENABLED +#include "AP_ICEngine.h" + +class AP_ICEngine_TCA9554 { +public: + void set_starter(bool on); + +private: + AP_HAL::OwnPtr dev_TCA9554; + + enum TCA9554_state_t { + STARTER_OFF = 0x30, // output register - 0011 0000 + STARTER_ON = 0x11, // output register - 0001 0001 - Forward direction + }; + TCA9554_state_t last_state; + + bool initialised; + + bool TCA9554_init(); + void TCA9554_set(TCA9554_state_t value); + uint32_t last_reg_check_ms; +}; + +#endif // AP_ICENGINE_TCA9554_STARTER_ENABLED diff --git a/libraries/AP_ICEngine/AP_ICEngine_config.h b/libraries/AP_ICEngine/AP_ICEngine_config.h index c609d429f1257d..24e7fd4770c301 100644 --- a/libraries/AP_ICEngine/AP_ICEngine_config.h +++ b/libraries/AP_ICEngine/AP_ICEngine_config.h @@ -5,3 +5,11 @@ #ifndef AP_ICENGINE_ENABLED #define AP_ICENGINE_ENABLED 1 #endif + +/* + optional TCA9554 I2C for starter control + */ +#ifndef AP_ICENGINE_TCA9554_STARTER_ENABLED +// enable on SITL by default to ensure code is built +#define AP_ICENGINE_TCA9554_STARTER_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) +#endif From 32f6c1c53f23ab8e6d52e66a2bccd137eff6c03c Mon Sep 17 00:00:00 2001 From: Pradeep CK Date: Thu, 2 Nov 2023 14:51:34 +1100 Subject: [PATCH 214/499] waf: disable ICE in SITL periph --- Tools/ardupilotwaf/boards.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 2c5d221445dbef..6f53922836732a 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -837,6 +837,7 @@ def configure_env(self, cfg, env): HAL_PERIPH_ENABLE_RPM = 1, HAL_PERIPH_ENABLE_RC_OUT = 1, HAL_PERIPH_ENABLE_ADSB = 1, + AP_ICENGINE_ENABLED = 0, AP_AIRSPEED_ENABLED = 1, AP_AIRSPEED_AUTOCAL_ENABLE = 0, AP_AHRS_ENABLED = 1, From 3f730a8a94b4f759ae64fb96b183aa94947cd922 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 27 Jun 2023 00:02:15 +1000 Subject: [PATCH 215/499] AP_Math: add crc_sum_of_bytes sums the values of the bytes in a buffer and returns that sum modulus 256 --- libraries/AP_Math/crc.cpp | 11 +++++++++++ libraries/AP_Math/crc.h | 4 ++++ 2 files changed, 15 insertions(+) diff --git a/libraries/AP_Math/crc.cpp b/libraries/AP_Math/crc.cpp index ff320588ffa8bc..0b283b05153571 100644 --- a/libraries/AP_Math/crc.cpp +++ b/libraries/AP_Math/crc.cpp @@ -598,3 +598,14 @@ uint8_t parity(uint8_t byte) return p; } + +// sums the bytes in the supplied buffer, returns that sum mod 256 +// (i.e. shoved into a uint8_t) +uint8_t crc_sum_of_bytes(uint8_t *data, uint16_t count) +{ + uint8_t ret = 0; + for (uint32_t i=0; i Date: Tue, 27 Jun 2023 00:03:04 +1000 Subject: [PATCH 216/499] SITL: correct MegaSquirt simulation --- libraries/SITL/SIM_EFI_MegaSquirt.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.cpp b/libraries/SITL/SIM_EFI_MegaSquirt.cpp index 7aa29ff22911c3..7cdc183b429dfc 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.cpp +++ b/libraries/SITL/SIM_EFI_MegaSquirt.cpp @@ -20,6 +20,7 @@ #include #include #include +#include "SIM_EFI_MegaSquirt.h" using namespace SITL; @@ -37,7 +38,7 @@ static uint32_t CRC32_MS(const uint8_t *buf, uint32_t len) void EFI_MegaSquirt::update() { auto sitl = AP::sitl(); - if (!sitl || sitl->efi_type == SIM::EFI_TYPE_NONE) { + if (!sitl || sitl->efi_type != SIM::EFI_TYPE_MS) { return; } float rpm = sitl->state.rpm[0]; From 76d07f21f51c994744496b4abf1a40427f04e73b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 9 Nov 2023 14:56:36 +1100 Subject: [PATCH 217/499] AP_HAL: add simulator Hirth EFI --- libraries/AP_HAL/SIMState.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_HAL/SIMState.h b/libraries/AP_HAL/SIMState.h index b86c0282d45434..af62741110f2dc 100644 --- a/libraries/AP_HAL/SIMState.h +++ b/libraries/AP_HAL/SIMState.h @@ -33,6 +33,8 @@ #include #include +#include + #include #include #include @@ -206,6 +208,9 @@ class AP_HAL::SIMState { // simulated EFI MegaSquirt device: SITL::EFI_MegaSquirt *efi_ms; + // simulated EFI Hirth device: + SITL::EFI_Hirth *efi_hirth; + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // output socket for flightgear viewing SocketAPM fg_socket{true}; From f134a1df3495cca4523eb6b53ab6f2ead715b705 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 9 Nov 2023 14:56:36 +1100 Subject: [PATCH 218/499] AP_HAL_SITL: add simulator Hirth EFI --- libraries/AP_HAL_SITL/SITL_State_common.cpp | 9 +++++++++ libraries/AP_HAL_SITL/SITL_State_common.h | 4 ++++ 2 files changed, 13 insertions(+) diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index 10b2103fb0221c..260a9b28dac6f9 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -251,6 +251,12 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const } efi_ms = new SITL::EFI_MegaSquirt(); return efi_ms; + } else if (streq(name, "hirth")) { + if (efi_hirth != nullptr) { + AP_HAL::panic("Only one hirth at a time"); + } + efi_hirth = new SITL::EFI_Hirth(); + return efi_hirth; } else if (streq(name, "VectorNav")) { if (vectornav != nullptr) { AP_HAL::panic("Only one VectorNav at a time"); @@ -372,6 +378,9 @@ void SITL_State_Common::sim_update(void) if (efi_ms != nullptr) { efi_ms->update(); } + if (efi_hirth != nullptr) { + efi_hirth->update(); + } if (frsky_d != nullptr) { frsky_d->update(); diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index bed95fd9ceca50..e7b82c2c91d4aa 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -11,6 +11,7 @@ #include #include #include +#include #include #include #include @@ -212,6 +213,9 @@ class HALSITL::SITL_State_Common { // simulated EFI MegaSquirt device: SITL::EFI_MegaSquirt *efi_ms; + // simulated EFI MegaSquirt device: + SITL::EFI_Hirth *efi_hirth; + // output socket for flightgear viewing SocketAPM fg_socket{true}; From ca16e924db12698d67685f9b2a89f592f3c35179 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 9 Nov 2023 14:56:36 +1100 Subject: [PATCH 219/499] SITL: add simulator Hirth EFI --- libraries/SITL/SIM_EFI_Hirth.cpp | 248 +++++++++++++++++++++++++++++++ libraries/SITL/SIM_EFI_Hirth.h | 240 ++++++++++++++++++++++++++++++ libraries/SITL/SITL.h | 1 + 3 files changed, 489 insertions(+) create mode 100644 libraries/SITL/SIM_EFI_Hirth.cpp create mode 100644 libraries/SITL/SIM_EFI_Hirth.h diff --git a/libraries/SITL/SIM_EFI_Hirth.cpp b/libraries/SITL/SIM_EFI_Hirth.cpp new file mode 100644 index 00000000000000..ba6faece7ee29f --- /dev/null +++ b/libraries/SITL/SIM_EFI_Hirth.cpp @@ -0,0 +1,248 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + simulate Hirth EFI system +*/ + +#include "SIM_Aircraft.h" +#include +#include +#include +#include "SIM_EFI_Hirth.h" + +using namespace SITL; + +// assume SERVO3 is throttle +#define HIRTH_RPM_INDEX 2 + +void EFI_Hirth::update_receive() +{ + const ssize_t num_bytes_read = read_from_autopilot((char*)&receive_buf[receive_buf_ofs], ARRAY_SIZE(receive_buf) - receive_buf_ofs); + if (num_bytes_read < 0) { + return; + } + receive_buf_ofs += num_bytes_read; + + if (receive_buf_ofs < 1) { + return; + } + + const uint8_t expected_bytes_in_message = receive_buf[0]; + + if (expected_bytes_in_message == 0) { + AP_HAL::panic("zero bytes expected is unexpected"); + } + + if (expected_bytes_in_message > ARRAY_SIZE(receive_buf)) { + AP_HAL::panic("Unexpectedly large byte count"); + } + + if (receive_buf_ofs < expected_bytes_in_message) { + return; + } + + // checksum is sum of all bytes except the received checksum: + const uint8_t expected_checksum = 256U - crc_sum_of_bytes(receive_buf, expected_bytes_in_message-1); + const uint8_t received_checksum = receive_buf[expected_bytes_in_message-1]; + if (expected_checksum == received_checksum) { + PacketCode received_packet_code = PacketCode(receive_buf[1]); + if (received_packet_code == PacketCode::SetValues) { + // do this synchronously for now + handle_set_values(); + } else { + assert_receive_size(3); + if (requested_data_record.time_ms != 0) { + AP_HAL::panic("Requesting too fast?"); + } + requested_data_record.code = received_packet_code; + requested_data_record.time_ms = AP_HAL::millis(); + } + } else { + AP_HAL::panic("checksum failed"); + // simply throw these bytes away. What the actual device does in the + // face of weird data is unknown. + } + memmove(&receive_buf[0], &receive_buf[expected_bytes_in_message], receive_buf_ofs - expected_bytes_in_message); + receive_buf_ofs -= expected_bytes_in_message; +} + +void EFI_Hirth::assert_receive_size(uint8_t receive_size) +{ + if (receive_buf[0] != receive_size) { + AP_HAL::panic("Expected %u message size, got %u message size", receive_size, receive_buf[0]); + } +} + +void EFI_Hirth::handle_set_values() +{ + assert_receive_size(23); + static_assert(sizeof(settings) == 20, "correct number of bytes in settings"); + memcpy((void*)&settings, &receive_buf[2], sizeof(settings)); +} + +void EFI_Hirth::update_send() +{ + if (requested_data_record.time_ms == 0) { + // no outstanding request + return; + } + if (AP_HAL::millis() - requested_data_record.time_ms < 20) { + // 20ms to service a request + return; + } + requested_data_record.time_ms = 0; + + switch (requested_data_record.code) { + case PacketCode::DataRecord1: + send_record1(); + break; + case PacketCode::DataRecord2: + send_record2(); + break; + case PacketCode::DataRecord3: + send_record3(); + break; + default: + AP_HAL::panic("Unknown data record (%u) requested", (unsigned)requested_data_record.code); + } +} + +void EFI_Hirth::update_engine_model() +{ + auto sitl = AP::sitl(); + + // FIXME: this should come from simulation, not baro. baro gets + // warmed by the simulated electronics! + const float ambient = AP::baro().get_temperature(); + + const uint32_t now_ms = AP_HAL::millis(); + + const float delta_t = (now_ms - engine.last_update_ms) * 1e-6; + engine.last_update_ms = now_ms; + + // lose heat to environment (air-cooling due to airspeed and prop + // airflow could be taken into account here) + const float ENV_LOSS_FACTOR = 25; + engine.cht1_temperature -= (engine.cht1_temperature - ambient) * delta_t * ENV_LOSS_FACTOR; + engine.cht2_temperature -= (engine.cht2_temperature - ambient) * delta_t * ENV_LOSS_FACTOR; + + const float rpm = sitl->state.rpm[HIRTH_RPM_INDEX]; + const float RPM_GAIN_FACTOR_CHT1 = 10; + const float RPM_GAIN_FACTOR_CHT2 = 8; + engine.cht1_temperature += rpm * delta_t * RPM_GAIN_FACTOR_CHT1; + engine.cht2_temperature += rpm * delta_t * RPM_GAIN_FACTOR_CHT2; +} + +void EFI_Hirth::init() +{ + // auto sitl = AP::sitl(); + + if (is_zero(AP::baro().get_temperature())) { + // defer until the baro has had a chance to update.... + return; + } + + engine.cht1_temperature = AP::baro().get_temperature(); + engine.cht2_temperature = AP::baro().get_temperature(); + + init_done = true; +} + +void EFI_Hirth::update() +{ + const auto *sitl = AP::sitl(); + if (!sitl || sitl->efi_type != SIM::EFI_TYPE_HIRTH) { + return; + } + + if (!init_done) { + init(); + } + + // update throttle; interim thing to make life a little more interesting + throttle = 0.9 * throttle + 0.1 * settings.throttle/10; + + update_engine_model(); + + update_receive(); + update_send(); +} + +uint16_t EFI_Hirth::engine_status_field_value() const +{ + return ( + 0U << 0 | // engine temperature sensor + 1U << 1 | // air temperature sensor + 1U << 2 | // air pressure sensor + 1U << 3 // throttle sensor OK + ); +} + +void SITL::EFI_Hirth::send_record1() +{ + const auto *sitl = AP::sitl(); + + // notionally the field updates should happen in the update() + // method, but here to save CPU for now: + auto &r = packed_record1.record; + r.engine_status = engine_status_field_value(); + r.rpm = sitl->state.rpm[HIRTH_RPM_INDEX]; + r.air_temperature = AP::baro().get_temperature(); + r.throttle = settings.throttle / 10; // just echo this back + + packed_record1.update_checksum(); + + write_to_autopilot((char*)&packed_record1, sizeof(packed_record1)); + + assert_storage_size _assert_storage_size_Record1; + (void)_assert_storage_size_Record1; +} + +void SITL::EFI_Hirth::send_record2() +{ + const auto *sitl = AP::sitl(); + + // notionally the field updates should happen in the update() + // method, but here to save CPU for now: + auto &r = packed_record2.record; + r.throttle_percent_times_10 = throttle * 10.0; + r.fuel_consumption = ((MAX(sitl->state.rpm[HIRTH_RPM_INDEX] - 1500.0, 0)) /2200.0) * 10; // from log, very rough + + packed_record2.update_checksum(); + + write_to_autopilot((char*)&packed_record2, sizeof(packed_record2)); + + assert_storage_size _assert_storage_size_Record2; + (void)_assert_storage_size_Record2; +} + + +void SITL::EFI_Hirth::send_record3() +{ + // notionally the field updates should happen in the update() + // method, but here to save CPU for now: + auto &r = packed_record3.record; + r.excess_temperature_1 = engine.cht1_temperature; // cht1 + r.excess_temperature_2 = engine.cht2_temperature; // cht2 + r.excess_temperature_3 = 39; // egt1 + r.excess_temperature_4 = 41; // egt2 + + packed_record3.update_checksum(); + + write_to_autopilot((char*)&packed_record3, sizeof(packed_record3)); + + assert_storage_size _assert_storage_size_Record3; + (void)_assert_storage_size_Record3; +} diff --git a/libraries/SITL/SIM_EFI_Hirth.h b/libraries/SITL/SIM_EFI_Hirth.h new file mode 100644 index 00000000000000..cfc32517e6a76e --- /dev/null +++ b/libraries/SITL/SIM_EFI_Hirth.h @@ -0,0 +1,240 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + simulate Hirth EFI system + +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --uartF=sim:hirth --speedup=1 +param set SERIAL5_PROTOCOL 24 +param set SIM_EFI_TYPE 6 +param set EFI_TYPE 6 +reboot +status EFI_STATUS + +./Tools/autotest/autotest.py --gdb --debug build.Plane test.Plane.Hirth + +*/ + +#pragma once + +#include +#include +#include "SIM_SerialDevice.h" + +namespace SITL { + +class EFI_Hirth : public SerialDevice { +public: + + using SerialDevice::SerialDevice; + + void update(); + +private: + + void update_receive(); + void update_send(); + + void assert_receive_size(uint8_t receive_size); + + void handle_set_values(); + + // maps from an on-wire number to a record number: + enum class PacketCode : uint8_t { + DataRecord1 = 4, + DataRecord2 = 11, + DataRecord3 = 13, + SetValues = 201, + }; + + template + class PACKED PackedRecord { + public: + PackedRecord(PacketCode _code, T _record) : + code(uint8_t(_code)), + record(_record) + { } + const uint8_t length { sizeof(T) + 3 }; // 1 each of length, code and checksum + const uint8_t code; + T record; + uint8_t checksum; + + void update() { + record.update(); + update_checksum(); + } + + void update_checksum() { + checksum = 256U - crc_sum_of_bytes((uint8_t*)this, length-1); + } + }; + + void send_record1(); + void send_record2(); + void send_record3(); + + class PACKED Record1 { + public: + uint8_t reserved1[2]; + uint16_t save_in_flash; // "1 = data are saved in flash automatically" + uint8_t reserved2[4]; + uint16_t engine_status; + uint16_t rpm; + uint8_t reserved3[12]; + uint16_t number_of_interfering_pulses; + uint16_t reserved4[2]; + uint16_t number_of_speed_errors; + uint16_t injection_time; + uint16_t ignition_angle; + uint16_t reserved5; + uint16_t voltage_throttle; + uint16_t reserved6; + uint8_t reserved7[2]; + uint16_t voltage_engine_temperature; + uint16_t voltage_air_temperature; + uint8_t reserved8[2]; + uint16_t voltage_int_air_pressure; + uint8_t reserved9[20]; + int16_t throttle; + int16_t engine_temperature; + int16_t battery_voltage; + int16_t air_temperature; + int16_t reserved10; + uint16_t sensor_ok; + + void update(); + }; + + class PACKED Record2 { + public: + uint8_t reserved1[12]; + int16_t injection_rate_from_basic_graphic_map; + int16_t reserved2; + int16_t basic_injection_rate; + int16_t injection_rate_from_air_correction; + int16_t reserved3; + int16_t injection_rate_from_warming_up_characteristic_curve; + int16_t injection_rate_from_acceleration_enrichment; + int16_t turn_on_time_of_intake_valves; + int16_t injection_rate_from_race_switch; + int16_t reserved4; + int16_t injection_angle_from_ignition_angle_map; + int16_t injection_angle_from_air_temperature_characteristic_curve; + int16_t injection_angle_from_air_pressure_characteristic_curve; + int16_t ignition_angle_from_engine_temperature_characteristic_curve; + int16_t ignition_angle_from_acceleration; + int16_t ignition_angle_from_race_switch; + uint32_t total_time_in_26ms; + uint32_t total_number_of_rotations; + uint16_t fuel_consumption; + uint16_t number_of_errors_in_error_memory; + int16_t voltage_input1_throttle_target; + int16_t reserved5; + int16_t position_throttle_target; + uint16_t throttle_percent_times_10; // percent * 10 + int16_t reserved6[3]; + uint16_t time_of_injector_opening_percent_times_10; + uint8_t reserved7[10]; + uint32_t no_of_logged_data; + uint8_t reserved8[12]; + }; + + class PACKED Record3 { + public: + uint16_t voltage_excess_temperature_1; + uint16_t voltage_excess_temperature_2; + uint16_t voltage_excess_temperature_3; + uint16_t voltage_excess_temperature_4; + uint16_t voltage_excess_temperature_5; + uint8_t reserved1[6]; + uint16_t excess_temperature_1; // cht1 + uint16_t excess_temperature_2; // cht2 + uint16_t excess_temperature_3; // egt1 + uint16_t excess_temperature_4; // egt2 + uint16_t excess_temperature_5; + uint8_t reserved2[6]; + uint16_t enrichment_excess_temperature_cylinder_1; + uint16_t enrichment_excess_temperature_cylinder_2; + uint16_t enrichment_excess_temperature_cylinder_3; + uint16_t enrichment_excess_temperature_cylinder_4; + uint8_t reserved3[6]; + uint16_t enrichment_excess_temperature_bitfield; + uint16_t mixing_ratio_oil_pump1; + uint16_t mixing_ratio_oil_pump2; + uint16_t ouput_value_water_pump; + uint16_t ouput_value_fuel_pump; + uint16_t ouput_value_exhaust_valve; + uint16_t ouput_value_air_vane; + uint16_t ouput_value_e_throttle; + uint16_t number_of_injections_oil_pump_1; + uint32_t system_time_in_ms; + uint16_t number_of_injections_oil_pump_2; + uint16_t target_rpm; + uint16_t FPC; + // these appear to be duplicates of the above; one is probably + // voltage? + uint16_t xenrichment_excess_temperature_cylinder_1; + uint16_t xenrichment_excess_temperature_cylinder_2; + uint16_t xenrichment_excess_temperature_cylinder_3; + uint16_t xenrichment_excess_temperature_cylinder_4; + uint16_t voltage_input_temperature_crankshaft_housing; + uint16_t temperature_crankshaft_housing; + uint8_t reserved4[14]; + }; + + class PACKED SetValues { + public: + int16_t throttle; // percent * 10 + int16_t rpm;; + int8_t reserved1[16]; + }; + + // these records are just used for initial values of the fields; + // they aren't used past that. + Record1 record1; + Record2 record2; + Record3 record3; + + + SetValues settings; + + PackedRecord packed_record1{PacketCode::DataRecord1, record1}; + PackedRecord packed_record2{PacketCode::DataRecord2, record2}; + PackedRecord packed_record3{PacketCode::DataRecord3, record3}; + + struct { + PacketCode code; // code which was requested by driver + uint32_t time_ms; // time that code was requested by driver + } requested_data_record; + + uint8_t receive_buf[32]; + uint8_t receive_buf_ofs; + + float throttle; + + uint16_t engine_status_field_value() const; + + void init(); + bool init_done = false; + + // engine model: + void update_engine_model(); + struct { + float cht1_temperature; // engine reports in deg-C + float cht2_temperature; + uint32_t last_update_ms; + } engine; +}; + +} diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 4209fe06d14757..ade17ae2e854b1 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -296,6 +296,7 @@ class SIM { enum EFIType { EFI_TYPE_NONE = 0, EFI_TYPE_MS = 1, + EFI_TYPE_HIRTH = 8, }; AP_Int8 efi_type; From a018bed042734d43ffe264aee527fd6a1db22039 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 9 Nov 2023 16:39:27 +1100 Subject: [PATCH 220/499] SITL: improve MegaSquirt simulator fidelity --- libraries/SITL/SIM_EFI_MegaSquirt.cpp | 8 +++++--- libraries/SITL/SIM_EFI_MegaSquirt.h | 2 ++ 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.cpp b/libraries/SITL/SIM_EFI_MegaSquirt.cpp index 7cdc183b429dfc..2935024ce0b0aa 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.cpp +++ b/libraries/SITL/SIM_EFI_MegaSquirt.cpp @@ -41,16 +41,18 @@ void EFI_MegaSquirt::update() if (!sitl || sitl->efi_type != SIM::EFI_TYPE_MS) { return; } - float rpm = sitl->state.rpm[0]; + const float rpm = sitl->state.rpm[2]; + + tps = 0.9 * tps + 0.1 * (rpm / 7000) * 100; table7.rpm = rpm; table7.fuelload = 20; table7.dwell = 2.0; table7.baro_hPa = 1000; table7.map_hPa = 895; - table7.mat_cF = 3013; + table7.mat_cF = C_TO_F(AP::baro().get_temperature()) * 10; table7.fuelPressure = 6280; - table7.throttle_pos = 580; + table7.throttle_pos = tps * 10; table7.ct_cF = 3940; table7.afr_target1 = 148; diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.h b/libraries/SITL/SIM_EFI_MegaSquirt.h index f957a296c751f6..813e22e5e65d90 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.h +++ b/libraries/SITL/SIM_EFI_MegaSquirt.h @@ -96,6 +96,8 @@ class EFI_MegaSquirt : public SerialDevice { uint8_t pad[128-67]; uint16_t fuelPressure; } table7; + + float tps; }; } From 6c0d540afe78a39b60863bcf035c80ac5e479238 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 9 Nov 2023 14:56:36 +1100 Subject: [PATCH 221/499] autotest: add simulator Hirth EFI --- Tools/autotest/arduplane.py | 87 ++++++++++++++++++++++++++++++------- 1 file changed, 72 insertions(+), 15 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index a580e70d5e7af4..02c16a8482e703 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -8,7 +8,6 @@ import math import os import signal -import sys import time from pymavlink import quaternion @@ -4199,24 +4198,81 @@ def ForcedDCM(self): self.fly_home_land_and_disarm() - def MegaSquirt(self): - '''Test MegaSquirt EFI''' + def EFITest(self, efi_type, name, sim_name, check_fuel_flow=True): + '''method to be called by EFI tests''' + self.start_subtest("EFI Test for (%s)" % name) self.assert_not_receiving_message('EFI_STATUS') self.set_parameters({ - 'SIM_EFI_TYPE': 1, - 'EFI_TYPE': 1, + 'SIM_EFI_TYPE': efi_type, + 'EFI_TYPE': efi_type, 'SERIAL5_PROTOCOL': 24, + 'RPM1_TYPE': 10, }) - self.customise_SITL_commandline(["--uartF=sim:megasquirt"]) - self.delay_sim_time(5) - m = self.assert_receive_message('EFI_STATUS') - mavutil.dump_message_verbose(sys.stdout, m) - if m.throttle_out != 0: - raise NotAchievedException("Expected zero throttle") - if m.health != 1: - raise NotAchievedException("Not healthy") - if m.intake_manifold_temperature < 20: - raise NotAchievedException("Bad intake manifold temperature") + + self.customise_SITL_commandline( + ["--uartF=sim:%s" % sim_name, + ], + ) + self.wait_ready_to_arm() + + baro_m = self.assert_receive_message("SCALED_PRESSURE") + self.progress(self.dump_message_verbose(baro_m)) + baro_temperature = baro_m.temperature / 100.0 # cDeg->deg + m = self.assert_received_message_field_values("EFI_STATUS", { + "throttle_out": 0, + "health": 1, + }, very_verbose=1) + + if abs(baro_temperature - m.intake_manifold_temperature) > 1: + raise NotAchievedException( + "Bad intake manifold temperature (want=%f got=%f)" % + (baro_temperature, m.intake_manifold_temperature)) + + self.arm_vehicle() + + self.set_rc(3, 1300) + + tstart = self.get_sim_time() + while True: + now = self.get_sim_time_cached() + if now - tstart > 10: + raise NotAchievedException("RPM1 and EFI_STATUS.rpm did not match") + rpm_m = self.assert_receive_message("RPM", verbose=1) + want_rpm = 1000 + if rpm_m.rpm1 < want_rpm: + continue + + m = self.assert_receive_message("EFI_STATUS", verbose=1) + if abs(m.rpm - rpm_m.rpm1) > 100: + continue + + break + + self.progress("now we're started, check a few more values") + # note that megasquirt drver doesn't send throttle, so throttle_out is zero! + m = self.assert_received_message_field_values("EFI_STATUS", { + "health": 1, + }, very_verbose=1) + m = self.wait_message_field_values("EFI_STATUS", { + "throttle_position": 31, + "intake_manifold_temperature": 28, + }, very_verbose=1, epsilon=2) + if check_fuel_flow: + if abs(m.fuel_flow - 0.2) > 0.0001: + raise NotAchievedException("Expected fuel flow") + + self.disarm_vehicle() + + def MegaSquirt(self): + '''test MegaSquirt driver''' + self.EFITest( + 1, "MegaSquirt", "megasquirt", + check_fuel_flow=False, + ) + + def Hirth(self): + '''Test Hirth EFI''' + self.EFITest(8, "Hirth", "hirth") def GlideSlopeThresh(self): '''Test rebuild glide slope if above and climbing''' @@ -5313,6 +5369,7 @@ def tests(self): self.AUTOTUNE, self.AutotuneFiltering, self.MegaSquirt, + self.Hirth, self.MSP_DJI, self.SpeedToFly, self.GlideSlopeThresh, From c5eab29f5efeb16e6dab8c038e118ad2e8b168b1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 9 Nov 2023 16:38:28 +1100 Subject: [PATCH 222/499] AP_Math: add F_TO_KELVIN and C_TO_F --- libraries/AP_Math/definitions.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Math/definitions.h b/libraries/AP_Math/definitions.h index 88199349d51556..024838a1c62c94 100644 --- a/libraries/AP_Math/definitions.h +++ b/libraries/AP_Math/definitions.h @@ -74,7 +74,9 @@ static const double WGS84_E = (sqrt(2 * WGS84_F - WGS84_F * WGS84_F)); #define C_TO_KELVIN(temp) (temp + 273.15f) #define KELVIN_TO_C(temp) (temp - 273.15f) -#define F_TO_KELVIN(temp) C_TO_KELVIN(((temp - 32) * 5/9)) +#define F_TO_C(temp) ((temp - 32) * 5/9) +#define F_TO_KELVIN(temp) C_TO_KELVIN(F_TO_C(temp)) +#define C_TO_F(temp) ((temp * 9/5) + 32) #define M_PER_SEC_TO_KNOTS 1.94384449f #define KNOTS_TO_M_PER_SEC (1/M_PER_SEC_TO_KNOTS) From 3e0e32a40974a9d81027e5c896a84404723b3004 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 10 Nov 2023 13:48:58 +1100 Subject: [PATCH 223/499] AP_Scripting: support 2nd cylinder in EFI --- libraries/AP_Scripting/docs/docs.lua | 16 ++++++++++++++++ .../generator/description/bindings.desc | 2 ++ 2 files changed, 18 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index aa240b686de038..f3a6e8b638eaa8 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -287,6 +287,14 @@ function Cylinder_Status_ud:exhaust_gas_temperature() end ---@param value number function Cylinder_Status_ud:exhaust_gas_temperature(value) end +-- get field +---@return number +function Cylinder_Status_ud:exhaust_gas_temperature2() end + +-- set field +---@param value number +function Cylinder_Status_ud:exhaust_gas_temperature2(value) end + -- get field ---@return number function Cylinder_Status_ud:cylinder_head_temperature() end @@ -295,6 +303,14 @@ function Cylinder_Status_ud:cylinder_head_temperature() end ---@param value number function Cylinder_Status_ud:cylinder_head_temperature(value) end +-- get field +---@return number +function Cylinder_Status_ud:cylinder_head_temperature2() end + +-- set field +---@param value number +function Cylinder_Status_ud:cylinder_head_temperature2(value) end + -- get field ---@return number function Cylinder_Status_ud:injection_time_ms() end diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 2011ba9835361c..284633ce17986f 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -726,7 +726,9 @@ userdata Cylinder_Status depends (AP_EFI_SCRIPTING_ENABLED == 1) userdata Cylinder_Status field ignition_timing_deg float'skip_check read write userdata Cylinder_Status field injection_time_ms float'skip_check read write userdata Cylinder_Status field cylinder_head_temperature float'skip_check read write +userdata Cylinder_Status field cylinder_head_temperature2 float'skip_check read write userdata Cylinder_Status field exhaust_gas_temperature float'skip_check read write +userdata Cylinder_Status field exhaust_gas_temperature2 float'skip_check read write userdata Cylinder_Status field lambda_coefficient float'skip_check read write userdata EFI_State depends (AP_EFI_SCRIPTING_ENABLED == 1) From 6bf3debe73cdf785cbe80ad3dc66aac99f0fa997 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 10 Nov 2023 17:42:38 +1100 Subject: [PATCH 224/499] HAL_ChibiOS: default disable ICE in periph --- libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h index 476217512d5fba..306ce7bc32e548 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -385,3 +385,6 @@ #define AP_TERRAIN_AVAILABLE 0 #endif +#ifndef AP_ICENGINE_ENABLED +#define AP_ICENGINE_ENABLED 0 +#endif From 71141080a1865f61cb4b2fd69ec8723e1d6b328b Mon Sep 17 00:00:00 2001 From: Pradeep CK Date: Mon, 13 Nov 2023 11:33:43 +1100 Subject: [PATCH 225/499] AP_EFI : Hirth Driver Addition Implementation for Hirth. - Base class - AP_EFI - polynomial functional throttle linearization - AP_EFI_State parameter addition and changes for hirth logging - to fix autotest errors - updated comments - Hirth CI/CD autotest fail fixes - logging - fix CI issues --- libraries/AP_EFI/AP_EFI.cpp | 26 +- libraries/AP_EFI/AP_EFI.h | 9 +- libraries/AP_EFI/AP_EFI_Backend.cpp | 16 + libraries/AP_EFI/AP_EFI_Backend.h | 8 + libraries/AP_EFI/AP_EFI_DroneCAN.cpp | 3 +- libraries/AP_EFI/AP_EFI_DroneCAN.h | 5 +- libraries/AP_EFI/AP_EFI_Scripting.cpp | 5 +- libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp | 405 ++++++++++++++++++ libraries/AP_EFI/AP_EFI_Serial_Hirth.h | 195 +++++++++ libraries/AP_EFI/AP_EFI_State.h | 12 + .../AP_EFI/AP_EFI_ThrottleLinearisation.cpp | 74 ++++ .../AP_EFI/AP_EFI_ThrottleLinearisation.h | 28 ++ libraries/AP_EFI/AP_EFI_config.h | 9 + 13 files changed, 785 insertions(+), 10 deletions(-) create mode 100644 libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp create mode 100644 libraries/AP_EFI/AP_EFI_Serial_Hirth.h create mode 100644 libraries/AP_EFI/AP_EFI_ThrottleLinearisation.cpp create mode 100644 libraries/AP_EFI/AP_EFI_ThrottleLinearisation.h diff --git a/libraries/AP_EFI/AP_EFI.cpp b/libraries/AP_EFI/AP_EFI.cpp index b52756d09f18ea..3cc4d648ffd68d 100644 --- a/libraries/AP_EFI/AP_EFI.cpp +++ b/libraries/AP_EFI/AP_EFI.cpp @@ -22,6 +22,7 @@ #include "AP_EFI_NWPMU.h" #include "AP_EFI_DroneCAN.h" #include "AP_EFI_Currawong_ECU.h" +#include "AP_EFI_Serial_Hirth.h" #include "AP_EFI_Scripting.h" #include "AP_EFI_MAV.h" @@ -39,7 +40,7 @@ const AP_Param::GroupInfo AP_EFI::var_info[] = { // @Param: _TYPE // @DisplayName: EFI communication type // @Description: What method of communication is used for EFI #1 - // @Values: 0:None,1:Serial-MS,2:NWPMU,3:Serial-Lutan,5:DroneCAN,6:Currawong-ECU,7:Scripting,9:MAV + // @Values: 0:None,1:Serial-MS,2:NWPMU,3:Serial-Lutan,5:DroneCAN,6:Currawong-ECU,7:Scripting,8:Hirth,9:MAV // @User: Advanced // @RebootRequired: True AP_GROUPINFO_FLAGS("_TYPE", 1, AP_EFI, type, 0, AP_PARAM_FLAG_ENABLE), @@ -66,6 +67,12 @@ const AP_Param::GroupInfo AP_EFI::var_info[] = { // @User: Advanced AP_GROUPINFO("_FUEL_DENS", 4, AP_EFI, ecu_fuel_density, 0), +#if AP_EFI_THROTTLE_LINEARISATION_ENABLED + // @Group: _THRLIN + // @Path: AP_EFI_ThrottleLinearisation.cpp + AP_SUBGROUPINFO(throttle_linearisation, "_THRLIN", 5, AP_EFI, AP_EFI_ThrLin), +#endif + AP_GROUPEND }; @@ -117,6 +124,11 @@ void AP_EFI::init(void) case Type::SCRIPTING: backend = new AP_EFI_Scripting(*this); break; +#endif +#if AP_EFI_SERIAL_HIRTH_ENABLED + case Type::Hirth: + backend = new AP_EFI_Serial_Hirth(*this); + break; #endif #if AP_EFI_MAV_ENABLED case Type::MAV: @@ -232,12 +244,14 @@ void AP_EFI::log_status(void) // @Field: CHT: Cylinder head temperature // @Field: EGT: Exhaust gas temperature // @Field: Lambda: Estimated lambda coefficient (dimensionless ratio) +// @Field: CHT2: Cylinder2 head temperature +// @Field: EGT2: Cylinder2 Exhaust gas temperature // @Field: IDX: Index of the publishing ECU AP::logger().WriteStreaming("ECYL", - "TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,IDX", - "s#dsOO--", - "F-0C0000", - "QBfffffB", + "TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,CHT2,EGT2,IDX", + "s#dsOO-OO-", + "F-0C000000", + "QBfffffBff", AP_HAL::micros64(), 0, state.cylinder_status.ignition_timing_deg, @@ -245,6 +259,8 @@ void AP_EFI::log_status(void) state.cylinder_status.cylinder_head_temperature, state.cylinder_status.exhaust_gas_temperature, state.cylinder_status.lambda_coefficient, + state.cylinder_status.cylinder_head_temperature2, + state.cylinder_status.exhaust_gas_temperature2, state.ecu_index); } #endif // LOGGING_ENABLED diff --git a/libraries/AP_EFI/AP_EFI.h b/libraries/AP_EFI/AP_EFI.h index 36db32e07b5e83..e2cb728158ea26 100644 --- a/libraries/AP_EFI/AP_EFI.h +++ b/libraries/AP_EFI/AP_EFI.h @@ -22,6 +22,7 @@ #include #include #include +#include "AP_EFI_ThrottleLinearisation.h" #include "AP_EFI_Backend.h" #include "AP_EFI_State.h" @@ -96,7 +97,9 @@ class AP_EFI { #if AP_EFI_SCRIPTING_ENABLED SCRIPTING = 7, #endif - // Hirth = 8 /* Reserved for future implementation */ +#if AP_EFI_SERIAL_HIRTH_ENABLED + Hirth = 8, +#endif MAV = 9, }; @@ -123,6 +126,10 @@ class AP_EFI { EFI_State state; +#if AP_EFI_THROTTLE_LINEARISATION_ENABLED + AP_EFI_ThrLin throttle_linearisation; +#endif + private: // Front End Parameters AP_Enum type; diff --git a/libraries/AP_EFI/AP_EFI_Backend.cpp b/libraries/AP_EFI/AP_EFI_Backend.cpp index 8eff55e857aa05..c110dcf2054e97 100644 --- a/libraries/AP_EFI/AP_EFI_Backend.cpp +++ b/libraries/AP_EFI/AP_EFI_Backend.cpp @@ -42,6 +42,11 @@ float AP_EFI_Backend::get_coef2(void) const return frontend.coef2; } +void AP_EFI_Backend::set_default_coef1(float coef1) +{ + frontend.coef1.set_default(coef1); +} + HAL_Semaphore &AP_EFI_Backend::get_sem(void) { return frontend.sem; @@ -51,4 +56,15 @@ float AP_EFI_Backend::get_ecu_fuel_density(void) const { return frontend.ecu_fuel_density; } + +#if AP_EFI_THROTTLE_LINEARISATION_ENABLED +/* + linearise throttle if enabled +*/ +float AP_EFI_Backend::linearise_throttle(float throttle_percent) +{ + return frontend.throttle_linearisation.linearise_throttle(throttle_percent); +} +#endif // AP_EFI_THROTTLE_LINEARISATION_ENABLED + #endif // HAL_EFI_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_Backend.h b/libraries/AP_EFI/AP_EFI_Backend.h index dea30f8c44fce5..77a53888f702e6 100644 --- a/libraries/AP_EFI/AP_EFI_Backend.h +++ b/libraries/AP_EFI/AP_EFI_Backend.h @@ -49,8 +49,16 @@ class AP_EFI_Backend { int8_t get_dronecan_node_id(void) const; float get_coef1(void) const; float get_coef2(void) const; + + void set_default_coef1(float coef1); + float get_ecu_fuel_density(void) const; + /* + linearise throttle if enabled + */ + float linearise_throttle(float throttle_percent); + HAL_Semaphore &get_sem(void); private: diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp index c242598cf092a9..d917cb6599bc94 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.cpp +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.cpp @@ -1,8 +1,9 @@ #include -#include "AP_EFI_DroneCAN.h" +#include "AP_EFI_config.h" #if AP_EFI_DRONECAN_ENABLED +#include "AP_EFI_DroneCAN.h" #include #include diff --git a/libraries/AP_EFI/AP_EFI_DroneCAN.h b/libraries/AP_EFI/AP_EFI_DroneCAN.h index c4f9dde22c4724..0512d8ea1f7ca3 100644 --- a/libraries/AP_EFI/AP_EFI_DroneCAN.h +++ b/libraries/AP_EFI/AP_EFI_DroneCAN.h @@ -1,9 +1,10 @@ #pragma once -#include "AP_EFI.h" -#include "AP_EFI_Backend.h" +#include "AP_EFI_config.h" #if AP_EFI_DRONECAN_ENABLED +#include "AP_EFI.h" +#include "AP_EFI_Backend.h" #include class AP_EFI_DroneCAN : public AP_EFI_Backend { diff --git a/libraries/AP_EFI/AP_EFI_Scripting.cpp b/libraries/AP_EFI/AP_EFI_Scripting.cpp index 8a4b2f73a0b97b..710504710cf830 100644 --- a/libraries/AP_EFI/AP_EFI_Scripting.cpp +++ b/libraries/AP_EFI/AP_EFI_Scripting.cpp @@ -1,7 +1,10 @@ -#include "AP_EFI_Scripting.h" +#include "AP_EFI_config.h" #if AP_EFI_SCRIPTING_ENABLED +#include "AP_EFI_Scripting.h" + + // Called from frontend to update with the readings received by handler void AP_EFI_Scripting::update() { diff --git a/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp b/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp new file mode 100644 index 00000000000000..a7d3978a3e00fe --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_Serial_Hirth.cpp @@ -0,0 +1,405 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + + + +#include "AP_EFI_config.h" + +#if AP_EFI_SERIAL_HIRTH_ENABLED +#include +#include +#include +#include +#include +#include +#include + +#define HIRTH_MAX_PKT_SIZE 100 +#define HIRTH_MAX_RAW_PKT_SIZE 103 + +#define SERIAL_WAIT_TIMEOUT_MS 100 + +#define ENGINE_RUNNING 4 +#define THROTTLE_POSITION_FACTOR 10 +#define CRANK_SHAFT_SENSOR_OK 0x0F +#define INJECTION_TIME_RESOLUTION 0.8 +#define THROTTLE_POSITION_RESOLUTION 0.1 +#define VOLTAGE_RESOLUTION 0.0049 /* 5/1024 */ +#define ADC_CALIBRATION (5.0/1024.0) +#define MAP_HPA_PER_VOLT_FACTOR 248.2673 +#define HPA_TO_KPA 0.1 +#define TPS_SCALE 0.70 + +// request/response status constants +#define QUANTITY_REQUEST_STATUS 0x03 +#define QUANTITY_SET_VALUE 0x17 +#define CODE_REQUEST_STATUS_1 0x04 +#define CODE_REQUEST_STATUS_2 0x0B +#define CODE_REQUEST_STATUS_3 0x0D +#define CODE_SET_VALUE 0xC9 +#define CHECKSUM_REQUEST_STATUS_1 0xF9 +#define CHECKSUM_REQUEST_STATUS_2 0xF2 +#define CHECKSUM_REQUEST_STATUS_3 0xF0 +#define QUANTITY_RESPONSE_STATUS_1 0x57 +#define QUANTITY_RESPONSE_STATUS_2 0x65 +#define QUANTITY_RESPONSE_STATUS_3 0x67 +#define QUANTITY_ACK_SET_VALUES 0x03 + +extern const AP_HAL::HAL& hal; + +/** + * @brief Constructor with port initialization + * + * @param _frontend + */ +AP_EFI_Serial_Hirth::AP_EFI_Serial_Hirth(AP_EFI &_frontend) : + AP_EFI_Backend(_frontend) +{ + port = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_EFI, 0); + set_default_coef1(1.0); +} + +/** + * @brief checks for response from or makes requests to Hirth ECU periodically + * + */ +void AP_EFI_Serial_Hirth::update() +{ + if (port == nullptr) { + return; + } + + // parse response from Hirth + check_response(); + + // send request + send_request(); +} + +/** + * @brief Checks if required bytes are available and proceeds with parsing + * + */ +void AP_EFI_Serial_Hirth::check_response() +{ + const uint32_t now = AP_HAL::millis(); + + // waiting for response + if (!waiting_response) { + return; + } + + const uint32_t num_bytes = port->available(); + + // if already requested + if (num_bytes >= expected_bytes) { + // read data from buffer + uint8_t computed_checksum = 0; + computed_checksum += res_data.quantity = port->read(); + computed_checksum += res_data.code = port->read(); + + if (res_data.code == requested_code) { + for (int i = 0; i < (res_data.quantity - QUANTITY_REQUEST_STATUS); i++) { + computed_checksum += raw_data[i] = port->read(); + } + } + + res_data.checksum = port->read(); + if (res_data.checksum != (256 - computed_checksum)) { + crc_fail_cnt++; + port->discard_input(); + } else { + uptime = now - last_packet_ms; + last_packet_ms = now; + internal_state.last_updated_ms = now; + decode_data(); + copy_to_frontend(); + port->discard_input(); + } + + waiting_response = false; + +#if HAL_LOGGING_ENABLED + log_status(); +#endif + } + + // reset request if no response for SERIAL_WAIT_TIMEOUT_MS + if (waiting_response && + now - last_request_ms > SERIAL_WAIT_TIMEOUT_MS) { + waiting_response = false; + last_request_ms = now; + + port->discard_input(); + ack_fail_cnt++; + } +} + +/** + * @brief Send Throttle and Telemetry requests to Hirth + * + */ +void AP_EFI_Serial_Hirth::send_request() +{ + if (waiting_response) { + return; + } + + const uint32_t now = AP_HAL::millis(); + bool request_was_sent; + + // get new throttle value + const uint16_t new_throttle = (uint16_t)SRV_Channels::get_output_scaled(SRV_Channel::k_throttle); + + // check for change or timeout for throttle value + if ((new_throttle != last_throttle) || (now - last_req_send_throttle_ms > 500)) { + // send new throttle value, only when ARMED + bool allow_throttle = hal.util->get_soft_armed(); + if (!allow_throttle) { +#if AP_ICENGINE_ENABLED + const auto *ice = AP::ice(); + if (ice != nullptr) { + allow_throttle = ice->allow_throttle_while_disarmed(); + } +#endif // AP_ICENGINE_ENABLED + } + if (allow_throttle) { + request_was_sent = send_target_values(new_throttle); + } else { + request_was_sent = send_target_values(0); + } + + last_throttle = new_throttle; + last_req_send_throttle_ms = now; + } else { + // request Status request at the driver update rate if no throttle commands + request_was_sent = send_request_status(); + } + + if (request_was_sent) { + waiting_response = true; + last_request_ms = now; + } +} + + +/** + * @brief sends the new throttle command to Hirth ECU + * + * @param thr - new throttle value given by SRV_Channel::k_throttle + * @return true - if success + * @return false - currently not implemented + */ +bool AP_EFI_Serial_Hirth::send_target_values(uint16_t thr) +{ + uint8_t computed_checksum = 0; + + // clear buffer + memset(raw_data, 0, ARRAY_SIZE(raw_data)); + +#if AP_EFI_THROTTLE_LINEARISATION_ENABLED + // linearise throttle input + thr = linearise_throttle(thr); +#endif + + const uint16_t throttle = thr * THROTTLE_POSITION_FACTOR; + + uint8_t idx = 0; + + // set Quantity + Code + "20 bytes of records to set" + Checksum + computed_checksum += raw_data[idx++] = QUANTITY_SET_VALUE; + computed_checksum += raw_data[idx++] = requested_code = CODE_SET_VALUE; + computed_checksum += raw_data[idx++] = throttle & 0xFF; + computed_checksum += raw_data[idx++] = (throttle >> 8) & 0xFF; + + // checksum calculation + raw_data[QUANTITY_SET_VALUE - 1] = (256 - computed_checksum); + + expected_bytes = QUANTITY_ACK_SET_VALUES; + // write data + port->write(raw_data, QUANTITY_SET_VALUE); + + return true; +} + + +/** + * @brief cyclically sends different Status requests to Hirth ECU + * + * @return true - when successful + * @return false - not implemented + */ +bool AP_EFI_Serial_Hirth::send_request_status() { + + uint8_t requested_quantity; + uint8_t requested_checksum; + + switch (requested_code) + { + case CODE_REQUEST_STATUS_1: + requested_quantity = QUANTITY_REQUEST_STATUS; + requested_code = CODE_REQUEST_STATUS_2; + requested_checksum = CHECKSUM_REQUEST_STATUS_2; + expected_bytes = QUANTITY_RESPONSE_STATUS_2; + break; + case CODE_REQUEST_STATUS_2: + requested_quantity = QUANTITY_REQUEST_STATUS; + requested_code = CODE_REQUEST_STATUS_3; + requested_checksum = CHECKSUM_REQUEST_STATUS_3; + expected_bytes = QUANTITY_RESPONSE_STATUS_3; + break; + case CODE_REQUEST_STATUS_3: + requested_quantity = QUANTITY_REQUEST_STATUS; + requested_code = CODE_REQUEST_STATUS_1; + requested_checksum = CHECKSUM_REQUEST_STATUS_1; + expected_bytes = QUANTITY_RESPONSE_STATUS_1; + break; + default: + requested_quantity = QUANTITY_REQUEST_STATUS; + requested_code = CODE_REQUEST_STATUS_1; + requested_checksum = CHECKSUM_REQUEST_STATUS_1; + expected_bytes = QUANTITY_RESPONSE_STATUS_1; + break; + } + raw_data[0] = requested_quantity; + raw_data[1] = requested_code; + raw_data[2] = requested_checksum; + + port->write(raw_data, QUANTITY_REQUEST_STATUS); + + return true; +} + + +/** + * @brief parses the response from Hirth ECU and updates the internal state instance + * + */ +void AP_EFI_Serial_Hirth::decode_data() +{ + const uint32_t now = AP_HAL::millis(); + + switch (res_data.code) { + case CODE_REQUEST_STATUS_1: { + struct Record1 *record1 = (Record1*)raw_data; + + internal_state.engine_speed_rpm = record1->rpm; + internal_state.throttle_out = record1->throttle; + + // EFI2 log + internal_state.engine_state = (Engine_State)record1->engine_status; + internal_state.crankshaft_sensor_status = (record1->sensor_ok & CRANK_SHAFT_SENSOR_OK) ? Crankshaft_Sensor_Status::OK : Crankshaft_Sensor_Status::ERROR; + + // ECYL log + internal_state.cylinder_status.injection_time_ms = record1->injection_time * INJECTION_TIME_RESOLUTION; + internal_state.cylinder_status.ignition_timing_deg = record1->ignition_angle; + + // EFI3 log + internal_state.ignition_voltage = record1->battery_voltage * VOLTAGE_RESOLUTION; + + engine_temperature_sensor_status = (record1->sensor_ok & 0x01) != 0; + air_temperature_sensor_status = (record1->sensor_ok & 0x02) != 0; + air_pressure_sensor_status = (record1->sensor_ok & 0x04) != 0; + throttle_sensor_status = (record1->sensor_ok & 0x08) != 0; + + // resusing mavlink variables as required for Hirth + // add in ADC voltage of MAP sensor > convert to MAP in kPa + internal_state.intake_manifold_pressure_kpa = record1->voltage_int_air_pressure * (ADC_CALIBRATION * MAP_HPA_PER_VOLT_FACTOR * HPA_TO_KPA); + internal_state.intake_manifold_temperature = C_TO_KELVIN(record1->air_temperature); + break; + } + + case CODE_REQUEST_STATUS_2: { + struct Record2 *record2 = (Record2*)raw_data; + + // EFI log + const float fuel_consumption_rate_lph = record2->fuel_consumption * 0.1; + + internal_state.fuel_consumption_rate_cm3pm = (fuel_consumption_rate_lph * 1000.0 / 60.0) * get_coef1(); + + if (last_fuel_integration_ms != 0) { + // estimated_consumed_fuel_volume_cm3 is in cm3/pm + const float dt_minutes = (now - last_fuel_integration_ms)*(0.001/60); + internal_state.estimated_consumed_fuel_volume_cm3 += internal_state.fuel_consumption_rate_cm3pm * dt_minutes; + } + last_fuel_integration_ms = now; + + internal_state.throttle_position_percent = record2->throttle_percent_times_10 * 0.1; + break; + } + + case CODE_REQUEST_STATUS_3: { + struct Record3 *record3 = (Record3*)raw_data; + + // EFI3 Log + CHT_1_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x0007) != 0; + CHT_2_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x0038) != 0; + EGT_1_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x01C0) != 0; + EGT_2_error_excess_temperature_status = (record3->error_excess_temperature_bitfield & 0x0E00) != 0; + + // ECYL log + internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(record3->excess_temperature_1); + internal_state.cylinder_status.cylinder_head_temperature2 = C_TO_KELVIN(record3->excess_temperature_2); + internal_state.cylinder_status.exhaust_gas_temperature = C_TO_KELVIN(record3->excess_temperature_3); + internal_state.cylinder_status.exhaust_gas_temperature2 = C_TO_KELVIN(record3->excess_temperature_4); + break; + } + + // case CODE_SET_VALUE: + // // Do nothing for now + // break; + } +} + +#if HAL_LOGGING_ENABLED +void AP_EFI_Serial_Hirth::log_status(void) +{ + // @LoggerMessage: EFIS + // @Description: Electronic Fuel Injection data - Hirth specific Status information + // @Field: TimeUS: Time since system startup + // @Field: ETS1: Status of EGT1 excess temperature error + // @Field: ETS2: Status of EGT2 excess temperature error + // @Field: CTS1: Status of CHT1 excess temperature error + // @Field: CTS2: Status of CHT2 excess temperature error + // @Field: ETSS: Status of Engine temperature sensor + // @Field: ATSS: Status of Air temperature sensor + // @Field: APSS: Status of Air pressure sensor + // @Field: TSS: Status of Temperature sensor + // @Field: CRCF: CRC failure count + // @Field: AckF: ACK failure count + // @Field: Up: Uptime between 2 messages + // @Field: ThrO: Throttle output as received by the engine + AP::logger().WriteStreaming("EFIS", + "TimeUS,ETS1,ETS2,CTS1,CTS2,ETSS,ATSS,APSS,TSS,CRCF,AckF,Up,ThrO", + "s------------", + "F------------", + "QBBBBBBBBIIIf", + AP_HAL::micros64(), + uint8_t(EGT_1_error_excess_temperature_status), + uint8_t(EGT_2_error_excess_temperature_status), + uint8_t(CHT_1_error_excess_temperature_status), + uint8_t(CHT_2_error_excess_temperature_status), + uint8_t(engine_temperature_sensor_status), + uint8_t(air_temperature_sensor_status), + uint8_t(air_pressure_sensor_status), + uint8_t(throttle_sensor_status), + uint32_t(crc_fail_cnt), + uint32_t(ack_fail_cnt), + uint32_t(uptime), + float(internal_state.throttle_out)); +} +#endif // HAL_LOGGING_ENABLED + +#endif // AP_EFI_SERIAL_HIRTH_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_Serial_Hirth.h b/libraries/AP_EFI/AP_EFI_Serial_Hirth.h new file mode 100644 index 00000000000000..350a3477c41a1c --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_Serial_Hirth.h @@ -0,0 +1,195 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + + +#pragma once + +#include "AP_EFI_config.h" + +#if AP_EFI_SERIAL_HIRTH_ENABLED +#include "AP_EFI.h" +#include "AP_EFI_Backend.h" + +/*! + * class definition for Hirth 4103 ECU + */ +class AP_EFI_Serial_Hirth: public AP_EFI_Backend { +public: + AP_EFI_Serial_Hirth(AP_EFI &_frontend); + + void update() override; + +private: + // serial port instance + AP_HAL::UARTDriver *port; + + // periodic refresh + uint32_t last_request_ms; + uint32_t last_packet_ms; + uint32_t last_req_send_throttle_ms; + + // raw bytes - max size + uint8_t raw_data[256]; + + // request and response data + uint8_t requested_code; + + // meta-data for a response + struct { + uint8_t quantity; + uint8_t code; + uint8_t checksum; + } res_data; + + // TRUE - Request is sent; waiting for response + // FALSE - Response is already received + bool waiting_response; + + // Expected bytes from response + uint8_t expected_bytes; + + // Throttle values + uint16_t last_throttle; + + uint32_t last_fuel_integration_ms; + + // custom status for Hirth + bool engine_temperature_sensor_status; + bool air_temperature_sensor_status; + bool air_pressure_sensor_status; + bool throttle_sensor_status; + + bool CHT_1_error_excess_temperature_status; + bool CHT_2_error_excess_temperature_status; + bool EGT_1_error_excess_temperature_status; + bool EGT_2_error_excess_temperature_status; + uint32_t crc_fail_cnt; + uint32_t uptime; + uint32_t ack_fail_cnt; + + struct PACKED Record1 { + uint8_t reserved1[2]; + uint16_t save_in_flash; // "1 = data are saved in flash automatically" + uint8_t reserved2[4]; + uint16_t engine_status; + uint16_t rpm; + uint8_t reserved3[12]; + uint16_t number_of_interfering_pulses; + uint16_t reserved4[2]; + uint16_t number_of_speed_errors; + uint16_t injection_time; + uint16_t ignition_angle; + uint16_t reserved5; + uint16_t voltage_throttle; + uint16_t reserved6; + uint8_t reserved7[2]; + uint16_t voltage_engine_temperature; + uint16_t voltage_air_temperature; + uint8_t reserved8[2]; + uint16_t voltage_int_air_pressure; + uint8_t reserved9[20]; + int16_t throttle; + int16_t engine_temperature; + int16_t battery_voltage; + int16_t air_temperature; + int16_t reserved10; + uint16_t sensor_ok; + }; + static_assert(sizeof(Record1) == 84, "incorrect Record1 length"); + + struct PACKED Record2 { + uint8_t reserved1[12]; + int16_t injection_rate_from_basic_graphic_map; + int16_t reserved2; + int16_t basic_injection_rate; + int16_t injection_rate_from_air_correction; + int16_t reserved3; + int16_t injection_rate_from_warming_up_characteristic_curve; + int16_t injection_rate_from_acceleration_enrichment; + int16_t turn_on_time_of_intake_valves; + int16_t injection_rate_from_race_switch; + int16_t reserved4; + int16_t injection_angle_from_ignition_graphic_map; + int16_t injection_angle_from_air_temperature_characteristic_curve; + int16_t injection_angle_from_air_pressure_characteristic_curve; + int16_t ignition_angle_from_engine_temperature_characteristic_curve; + int16_t ignition_angle_from_acceleration; + int16_t ignition_angle_from_race_switch; + uint32_t total_time_in_26ms; + uint32_t total_number_of_rotations; + uint16_t fuel_consumption; + uint16_t number_of_errors_in_error_memory; + int16_t voltage_input1_throttle_target; + int16_t reserved5; + int16_t position_throttle_target; + int16_t throttle_percent_times_10; // percent * 0.1 + int16_t reserved6[3]; + uint16_t time_of_injector_opening_percent_times_10; + uint8_t reserved7[10]; + uint32_t no_of_logged_data; + uint8_t reserved8[12]; + }; + static_assert(sizeof(Record2) == 98, "incorrect Record2 length"); + + struct PACKED Record3 { + int16_t voltage_excess_temperature_1; + int16_t voltage_excess_temperature_2; + int16_t voltage_excess_temperature_3; + int16_t voltage_excess_temperature_4; + int16_t voltage_excess_temperature_5; + uint8_t reserved1[6]; + int16_t excess_temperature_1; // cht1 + int16_t excess_temperature_2; // cht2 + int16_t excess_temperature_3; // egt1 + int16_t excess_temperature_4; // egt2 + int16_t excess_temperature_5; + uint8_t reserved2[6]; + int16_t enrichment_excess_temperature_cylinder_1; + int16_t enrichment_excess_temperature_cylinder_2; + int16_t enrichment_excess_temperature_cylinder_3; + int16_t enrichment_excess_temperature_cylinder_4; + uint8_t reserved3[6]; + uint16_t error_excess_temperature_bitfield; + uint16_t mixing_ratio_oil_pump1; + uint16_t mixing_ratio_oil_pump2; + uint16_t ouput_value_water_pump; + uint16_t ouput_value_fuel_pump; + uint16_t ouput_value_exhaust_valve; + uint16_t ouput_value_air_vane; + uint16_t ouput_value_e_throttle; + uint16_t number_of_injections_oil_pump_1; + uint32_t system_time_in_ms; + int16_t number_of_injections_oil_pump_2; + uint16_t target_rpm; + uint16_t FPC; + uint16_t xenrichment_excess_temperature_cylinder_1; + uint16_t xenrichment_excess_temperature_cylinder_2; + uint16_t xenrichment_excess_temperature_cylinder_3; + uint16_t xenrichment_excess_temperature_cylinder_4; + uint16_t voltage_input_temperature_crankshaft_housing; + int16_t temperature_crankshaft_housing; + uint8_t reserved4[14]; + }; + static_assert(sizeof(Record3) == 100, "incorrect Record3 length"); + + void check_response(); + void send_request(); + void decode_data(); + bool send_request_status(); + bool send_target_values(uint16_t); + void log_status(); +}; + +#endif // AP_EFI_SERIAL_HIRTH_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_State.h b/libraries/AP_EFI/AP_EFI_State.h index c73416f5a377c6..522f88f87a6a5c 100644 --- a/libraries/AP_EFI/AP_EFI_State.h +++ b/libraries/AP_EFI/AP_EFI_State.h @@ -15,6 +15,10 @@ #pragma once +#include + +#if HAL_EFI_ENABLED + #include #include @@ -108,11 +112,17 @@ struct Cylinder_Status { // Cylinder head temperature (CHT) (kelvin) float cylinder_head_temperature; + // 2nd Cylinder head temperature (CHT) (kelvin), 0 if not applicable + float cylinder_head_temperature2; + // Exhaust gas temperature (EGT) (kelvin) // If this cylinder is not equipped with an EGT sensor - will be NaN // If there is a single shared EGT sensor, will be the same value for all cylinders float exhaust_gas_temperature; + // 2nd cylinder exhaust gas temperature, 0 if not applicable + float exhaust_gas_temperature2; + // Estimated lambda coefficient (dimensionless ratio) // Useful for monitoring and tuning purposes. float lambda_coefficient; @@ -204,3 +214,5 @@ struct EFI_State { // PT compensation float pt_compensation; }; + +#endif // HAL_EFI_ENABLED diff --git a/libraries/AP_EFI/AP_EFI_ThrottleLinearisation.cpp b/libraries/AP_EFI/AP_EFI_ThrottleLinearisation.cpp new file mode 100644 index 00000000000000..5b63474672fda8 --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_ThrottleLinearisation.cpp @@ -0,0 +1,74 @@ +#include "AP_EFI_config.h" + +#if AP_EFI_THROTTLE_LINEARISATION_ENABLED + +#include "AP_EFI.h" +#include + +// settings for throttle linearisation +const AP_Param::GroupInfo AP_EFI_ThrLin::var_info[] = { + + // @Param: _EN + // @DisplayName: Enable throttle linearisation + // @Description: Enable EFI throttle linearisation + // @Values: 0:Disabled, 1:Enabled + // @User: Advanced + AP_GROUPINFO_FLAGS("_EN", 1, AP_EFI_ThrLin, enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: _COEF1 + // @DisplayName: Throttle linearisation - First Order + // @Description: First Order Polynomial Coefficient. (=1, if throttle is first order polynomial trendline) + // @Range: -1 1 + // @User: Advanced + // @RebootRequired: True + AP_GROUPINFO("_COEF1", 2, AP_EFI_ThrLin, coefficient[0], 1), + + // @Param: _COEF2 + // @DisplayName: Throttle linearisation - Second Order + // @Description: Second Order Polynomial Coefficient (=0, if throttle is second order polynomial trendline) + // @Range: -1 1 + // @User: Advanced + // @RebootRequired: True + AP_GROUPINFO("_COEF2", 3, AP_EFI_ThrLin, coefficient[1], 0), + + // @Param: _COEF3 + // @DisplayName: Throttle linearisation - Third Order + // @Description: Third Order Polynomial Coefficient. (=0, if throttle is third order polynomial trendline) + // @Range: -1 1 + // @User: Advanced + // @RebootRequired: True + AP_GROUPINFO("_COEF3", 4, AP_EFI_ThrLin, coefficient[2], 0), + + // @Param: _OFS + // @DisplayName: throttle linearization offset + // @Description: Offset for throttle linearization + // @Range: 0 100 + // @User: Advanced + // @RebootRequired: True + AP_GROUPINFO("_OFS", 5, AP_EFI_ThrLin, offset, 0), + + AP_GROUPEND +}; + +AP_EFI_ThrLin::AP_EFI_ThrLin(void) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +/* + apply throttle linearisation + */ +float AP_EFI_ThrLin::linearise_throttle(float throttle_percent) +{ + if (!enable) { + return throttle_percent; + } + float ret = coefficient[0] * throttle_percent; + ret += coefficient[1] * throttle_percent * throttle_percent; + ret += coefficient[2] * throttle_percent * throttle_percent * throttle_percent; + ret += offset; + return ret; +} + +#endif // AP_EFI_THROTTLE_LINEARISATION_ENABLED + diff --git a/libraries/AP_EFI/AP_EFI_ThrottleLinearisation.h b/libraries/AP_EFI/AP_EFI_ThrottleLinearisation.h new file mode 100644 index 00000000000000..82b1e0fd6a44cf --- /dev/null +++ b/libraries/AP_EFI/AP_EFI_ThrottleLinearisation.h @@ -0,0 +1,28 @@ +#include "AP_EFI_config.h" + +#if AP_EFI_THROTTLE_LINEARISATION_ENABLED + +/* + throttle linearisation support + */ +class AP_EFI_ThrLin { +public: + + AP_EFI_ThrLin(); + + static const struct AP_Param::GroupInfo var_info[]; + + /* + apply throttle linearisation, returning value to pass to the + engine + */ + float linearise_throttle(float throttle_pct); + +private: + AP_Int8 enable; + AP_Float coefficient[3]; + AP_Float offset; +}; + +#endif // AP_EFI_THROTTLE_LINEARISATION_ENABLED + diff --git a/libraries/AP_EFI/AP_EFI_config.h b/libraries/AP_EFI/AP_EFI_config.h index 00653cc38c54a6..a89307c2bc232b 100644 --- a/libraries/AP_EFI/AP_EFI_config.h +++ b/libraries/AP_EFI/AP_EFI_config.h @@ -2,6 +2,7 @@ #include #include +#include #ifndef HAL_EFI_ENABLED #define HAL_EFI_ENABLED BOARD_FLASH_SIZE > 1024 @@ -38,3 +39,11 @@ #ifndef AP_EFI_SERIAL_LUTAN_ENABLED #define AP_EFI_SERIAL_LUTAN_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED #endif + +#ifndef AP_EFI_SERIAL_HIRTH_ENABLED +#define AP_EFI_SERIAL_HIRTH_ENABLED AP_EFI_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_EFI_THROTTLE_LINEARISATION_ENABLED +#define AP_EFI_THROTTLE_LINEARISATION_ENABLED AP_EFI_SERIAL_HIRTH_ENABLED +#endif From 6b2fe38ce87fde18f26ae176d9925d3d9ee4a658 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Nov 2023 16:16:07 +1100 Subject: [PATCH 226/499] Tools: fixed fuel flow EFI test --- Tools/autotest/arduplane.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 02c16a8482e703..c1078e9f4ebbef 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4257,8 +4257,9 @@ def EFITest(self, efi_type, name, sim_name, check_fuel_flow=True): "throttle_position": 31, "intake_manifold_temperature": 28, }, very_verbose=1, epsilon=2) + if check_fuel_flow: - if abs(m.fuel_flow - 0.2) > 0.0001: + if abs(m.fuel_flow - 0.2) < 0.0001: raise NotAchievedException("Expected fuel flow") self.disarm_vehicle() From f12166c2d4cbb965087f55cfff5cabda9b340b39 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Nov 2023 16:23:04 +1100 Subject: [PATCH 227/499] Tools: added EFI hirth to options and features --- Tools/scripts/build_options.py | 1 + Tools/scripts/extract_features.py | 1 + 2 files changed, 2 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 0548b646b6809d..8c8a4d38cfaee7 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -94,6 +94,7 @@ def __init__(self, Feature('ICE', 'EFI_Lutan', 'AP_EFI_SERIAL_LUTAN_ENABLED', 'Enable EFI Lutan', 0, 'EFI'), Feature('ICE', 'EFI_NMPWU', 'AP_EFI_NWPWU_ENABLED', 'Enable EFI NMPMU', 0, 'EFI'), Feature('ICE', 'EFI_CURRAWONGECU', 'AP_EFI_CURRAWONG_ECU_ENABLED', 'Enable EFI Currawong ECU', 0, 'EFI'), + Feature('ICE', 'EFI_HIRTH', 'AP_EFI_SERIAL_HIRTH_ENABLED', 'Enable EFI Hirth ECU', 0, 'EFI'), Feature('ICE', 'EFI_DRONECAN', 'AP_EFI_DRONECAN_ENABLED', 'Enable EFI DroneCAN', 0, 'EFI'), Feature('ICE', 'EFI_MAV', 'AP_EFI_MAV_ENABLED', 'Enable EFI MAV', 0, 'EFI'), diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index be20757e008e57..80fcbc79a81570 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -142,6 +142,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('HAL_EFI_ENABLED', 'AP_RPM_EFI::AP_RPM_EFI',), ('AP_EFI_NWPWU_ENABLED', r'AP_EFI_NWPMU::update\b',), ('AP_EFI_CURRAWONG_ECU_ENABLED', r'AP_EFI_Currawong_ECU::update\b',), + ('AP_EFI_SERIAL_HIRTH_ENABLED', r'AP_EFI_Serial_Hirth::update\b',), ('HAL_GENERATOR_ENABLED', 'AP_Generator::AP_Generator',), ('AP_GENERATOR_{type}_ENABLED', r'AP_Generator_(?P.*)::init',), From d625a1b13be5df78e8ef754147d89e8ecf6998fc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Nov 2023 15:43:12 +1100 Subject: [PATCH 228/499] Tools: fixed EFI test suite disarm --- Tools/autotest/arduplane.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index c1078e9f4ebbef..31a127f3e01170 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4262,7 +4262,10 @@ def EFITest(self, efi_type, name, sim_name, check_fuel_flow=True): if abs(m.fuel_flow - 0.2) < 0.0001: raise NotAchievedException("Expected fuel flow") - self.disarm_vehicle() + self.set_rc(3, 1000) + + # need to force disarm as the is_flying flag can trigger with the engine running + self.disarm_vehicle(force=True) def MegaSquirt(self): '''test MegaSquirt driver''' From 713745ed28d7a32c65b691c80f201ae9f413f075 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Nov 2023 06:49:24 +1100 Subject: [PATCH 229/499] AP_DroneCAN: don't update hobbywing ESC table while armed some hobbywing ESCs have a bug where requesting the ID table can cause the ESC to stutter --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index c980c413cc03e8..7853319cc8e7a9 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -427,6 +427,11 @@ void AP_DroneCAN::loop(void) #if AP_DRONECAN_HOBBYWING_ESC_SUPPORT void AP_DroneCAN::hobbywing_ESC_update(void) { + if (hal.util->get_soft_armed()) { + // don't update ID database while disarmed, as it can cause + // some hobbywing ESCs to stutter + return; + } uint32_t now = AP_HAL::millis(); if (now - hobbywing.last_GetId_send_ms >= 1000U) { hobbywing.last_GetId_send_ms = now; From f9f07912e6feece853e69dda19dd8e04cb80cfa3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Nov 2023 14:41:16 +1100 Subject: [PATCH 230/499] AP_SerialManager: added register_port() API allows another library to register a UART driver for exposing via AP_SerialManager APIs --- .../AP_SerialManager/AP_SerialManager.cpp | 48 ++++++++++++++++++- libraries/AP_SerialManager/AP_SerialManager.h | 30 +++++++++++- 2 files changed, 75 insertions(+), 3 deletions(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index bc717a99fb3cda..7e269789048f86 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -439,6 +439,8 @@ void AP_SerialManager::init() for (uint8_t i=1; inext) { + if (protocol_match(protocol, (enum SerialProtocol)p->state.protocol.get())) { + if (found_instance == instance) { + return &p->state; + } + found_instance++; + } + } +#endif + // if we got this far we did not find the uart return nullptr; } @@ -602,10 +615,23 @@ AP_HAL::UARTDriver *AP_SerialManager::find_serial(enum SerialProtocol protocol, if (_state == nullptr) { return nullptr; } - const uint8_t serial_idx = _state - &state[0]; + const uint8_t serial_idx = _state->idx; // set options before any user does begin() AP_HAL::UARTDriver *port = hal.serial(serial_idx); + +#if AP_SERIALMANAGER_REGISTER_ENABLED + if (port == nullptr) { + // look for a registered port + for (auto p = registered_ports; p; p = p->next) { + if (p->state.idx == serial_idx) { + port = p; + break; + } + } + } +#endif + if (port) { port->set_options(_state->options); } @@ -637,7 +663,7 @@ int8_t AP_SerialManager::find_portnum(enum SerialProtocol protocol, uint8_t inst if (_state == nullptr) { return -1; } - return int8_t(_state - &state[0]); + return int8_t(_state->idx); } // get_serial_by_id - gets serial by serial id @@ -646,6 +672,13 @@ AP_HAL::UARTDriver *AP_SerialManager::get_serial_by_id(uint8_t id) if (id < SERIALMANAGER_NUM_PORTS) { return hal.serial(id); } +#if AP_SERIALMANAGER_REGISTER_ENABLED + for (auto p = registered_ports; p; p = p->next) { + if (p->state.idx == id) { + return (AP_HAL::UARTDriver *)p; + } + } +#endif return nullptr; } @@ -755,6 +788,17 @@ void AP_SerialManager::set_protocol_and_baud(uint8_t sernum, enum SerialProtocol } } +#if AP_SERIALMANAGER_REGISTER_ENABLED +/* + register an external network port. It is up to the caller to use a unique id field + using AP_SERIALMANAGER_NET_PORT_1 as the base id for NET_P1_* + */ +void AP_SerialManager::register_port(RegisteredPort *port) +{ + port->next = registered_ports; + registered_ports = port; +} +#endif // AP_SERIALMANAGER_REGISTER_ENABLED namespace AP { diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index e3673c6183937b..4d8bfb66cbd954 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -23,6 +23,7 @@ #include #include +#include #ifdef HAL_UART_NUM_SERIAL_PORTS #if HAL_UART_NUM_SERIAL_PORTS >= 4 @@ -150,6 +151,13 @@ #define AP_SERIALMANAGER_MSP_BUFSIZE_TX 256 #define AP_SERIALMANAGER_MSP_BAUD 115200 +#ifndef AP_SERIALMANAGER_REGISTER_ENABLED +#define AP_SERIALMANAGER_REGISTER_ENABLED AP_NETWORKING_ENABLED +#endif + +// serial ports registered by AP_Networking will use IDs starting at 21 for the first port +#define AP_SERIALMANAGER_NET_PORT_1 21 // NET_P1_* + class AP_SerialManager { public: AP_SerialManager(); @@ -268,10 +276,12 @@ class AP_SerialManager { AP_SerialManager::SerialProtocol get_protocol() const { return AP_SerialManager::SerialProtocol(protocol.get()); } - private: AP_Int32 baud; AP_Int16 options; AP_Int8 protocol; + + // serial index number + uint8_t idx; }; // search through managed serial connections looking for the @@ -282,6 +292,24 @@ class AP_SerialManager { const UARTState *find_protocol_instance(enum SerialProtocol protocol, uint8_t instance) const; +#if AP_SERIALMANAGER_REGISTER_ENABLED + /* + a class for a externally registered port + used by AP_Networking + */ + class RegisteredPort : public AP_HAL::UARTDriver { + public: + RegisteredPort *next; + UARTState state; + }; + RegisteredPort *registered_ports; + + // register an externally managed port + void register_port(RegisteredPort *port); + +#endif // AP_SERIALMANAGER_REGISTER_ENABLED + + private: static AP_SerialManager *_singleton; From ba0598930e172505a7f5d1e33236e0623ab1f74d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Nov 2023 14:45:23 +1100 Subject: [PATCH 231/499] AP_Vehicle: added AP_Networking::Port NET_Pn_ parameters --- libraries/AP_Vehicle/AP_Vehicle.cpp | 29 +++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index dfe32815dd3dd5..9a4f702a2d15f6 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -210,7 +210,36 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = { // @Group: NET_ // @Path: ../AP_Networking/AP_Networking.cpp AP_SUBGROUPINFO(networking, "NET_", 21, AP_Vehicle, AP_Networking), + + /* + the NET_Pn_ parameters need to be in AP_Vehicle as otherwise we + are too deep in the parameter tree + */ + +#if AP_NETWORKING_NUM_PORTS > 0 + // @Group: NET_P1_ + // @Path: ../AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking.ports[0], "NET_P1_", 22, AP_Vehicle, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 1 + // @Group: NET_P2_ + // @Path: ../AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking.ports[1], "NET_P2_", 23, AP_Vehicle, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 2 + // @Group: NET_P3_ + // @Path: ../AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking.ports[2], "NET_P3_", 24, AP_Vehicle, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 3 + // @Group: NET_P4_ + // @Path: ../AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking.ports[3], "NET_P4_", 25, AP_Vehicle, AP_Networking::Port), #endif +#endif // AP_NETWORKING_ENABLED AP_GROUPEND }; From 84dd7eaaf1f8e19b96e9c7b62e81f44510dd3d87 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Nov 2023 14:46:08 +1100 Subject: [PATCH 232/499] AP_Networking: added support for mapping network ports only UDP_CLIENT so far --- libraries/AP_Networking/AP_Networking.cpp | 3 + libraries/AP_Networking/AP_Networking.h | 55 ++++++ .../AP_Networking/AP_Networking_Config.h | 4 + .../AP_Networking/AP_Networking_port.cpp | 181 ++++++++++++++++++ 4 files changed, 243 insertions(+) create mode 100644 libraries/AP_Networking/AP_Networking_port.cpp diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 95f6a3920ee789..7783adf77dac4e 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -140,6 +140,9 @@ void AP_Networking::init() #if AP_NETWORKING_TESTS_ENABLED start_tests(); #endif + + // init network mapped serialmanager ports + ports_init(); } /* diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index d7e9bee1d59506..e49f25a697ba44 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -8,6 +8,8 @@ #include "AP_Networking_address.h" #include "AP_Networking_Backend.h" +#include +#include /* Note! all uint32_t IPv4 addresses are in host byte order @@ -17,11 +19,14 @@ class AP_Networking_Backend; class AP_Networking_ChibiOS; +class SocketAPM; + class AP_Networking { public: friend class AP_Networking_Backend; friend class AP_Networking_ChibiOS; + friend class AP_Vehicle; AP_Networking(); @@ -175,6 +180,51 @@ class AP_Networking HAL_Semaphore sem; + enum class NetworkPortType { + NONE = 0, + UDP_CLIENT = 1, + }; + + // class for NET_Pn_* parameters + class Port : public AP_SerialManager::RegisteredPort { + public: + /* Do not allow copies */ + CLASS_NO_COPY(Port); + + Port() {} + + static const struct AP_Param::GroupInfo var_info[]; + AP_Enum type; + AP_Networking_IPV4 ip {"0.0.0.0"}; + AP_Int32 port; + SocketAPM *sock; + + bool is_initialized() override { + return true; + } + bool tx_pending() override { + return false; + } + + void udp_client_init(void); + void udp_client_loop(void); + + private: + bool init_buffers(uint32_t size); + + uint32_t txspace() override; + void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; + size_t _write(const uint8_t *buffer, size_t size) override; + ssize_t _read(uint8_t *buffer, uint16_t count) override; + uint32_t _available() override; + void _end() override {} + void _flush() override {} + bool _discard_input() override; + + ByteBuffer *readbuffer; + ByteBuffer *writebuffer; + }; + private: uint32_t announce_ms; @@ -187,6 +237,11 @@ class AP_Networking void test_UDP_client(void); void test_TCP_client(void); #endif // AP_NETWORKING_TESTS_ENABLED + + // ports for registration with serial manager + Port ports[AP_NETWORKING_NUM_PORTS]; + + void ports_init(void); }; namespace AP diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index 70e45e0cf32c03..bfc4af537f226d 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -74,3 +74,7 @@ #define AP_NETWORKING_TEST_IP "192.168.13.2" #endif #endif + +#ifndef AP_NETWORKING_NUM_PORTS +#define AP_NETWORKING_NUM_PORTS 4 +#endif diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp new file mode 100644 index 00000000000000..3a87db30cfba0b --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -0,0 +1,181 @@ +/* + class for networking mapped ports + */ + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_ENABLED + +#include "AP_Networking.h" +#include +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +const AP_Param::GroupInfo AP_Networking::Port::var_info[] = { + // @Param: TYPE + // @DisplayName: Port type + // @Description: Port type + // @Values: 0:Disabled, 1:UDP client + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO_FLAGS("TYPE", 1, AP_Networking::Port, type, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: PROTOCOL + // @DisplayName: protocol + // @Description: protocol + // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:Gimbal, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:EFI Serial, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency, 44:IRC Tramp + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("PROTOCOL", 2, AP_Networking::Port, state.protocol, 0), + + // @Group: IP + // @Path: AP_Networking_address.cpp + AP_SUBGROUPINFO(ip, "IP", 3, AP_Networking::Port, AP_Networking_IPV4), + + // @Param: PORT + // @DisplayName: Port number + // @Description: Port number + // @Range: 0 65535 + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("PORT", 4, AP_Networking::Port, port, 0), + + AP_GROUPEND +}; + +/* + initialise mapped network ports + */ +void AP_Networking::ports_init(void) +{ + // init in reverse order to keep the linked list in + // AP_SerialManager in the right order + for (int8_t i=ARRAY_SIZE(ports)-1; i>= 0; i--) { + auto &p = ports[i]; + NetworkPortType ptype = (NetworkPortType)p.type; + p.state.idx = AP_SERIALMANAGER_NET_PORT_1 + i; + switch (ptype) { + case NetworkPortType::NONE: + break; + case NetworkPortType::UDP_CLIENT: + p.udp_client_init(); + break; + } + if (p.sock != nullptr) { + AP::serialmanager().register_port(&p); + } + } +} + +/* + initialise a UDP client + */ +void AP_Networking::Port::udp_client_init(void) +{ + if (!init_buffers(4096)) { + return; + } + sock = new SocketAPM(true); + if (sock == nullptr) { + return; + } + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::Port::udp_client_loop, void), "NET", 2048, AP_HAL::Scheduler::PRIORITY_UART, 0)) { + AP_BoardConfig::allocation_error("Failed to allocate UDP client thread"); + } +} + +/* + update a UDP client + */ +void AP_Networking::Port::udp_client_loop(void) +{ + while (!hal.scheduler->is_system_initialized()) { + hal.scheduler->delay(100); + } + hal.scheduler->delay(1000); + + const char *dest = ip.get_str(); + if (!sock->connect(dest, port.get())) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP[%u]: Failed to connect to %s", (unsigned)state.idx, dest); + delete sock; + sock = nullptr; + return; + } + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP[%u]: connected to %s:%u", (unsigned)state.idx, dest, unsigned(port.get())); + + while (true) { + hal.scheduler->delay_microseconds(500); + + // handle outgoing packets + uint32_t available; + const auto *ptr = writebuffer->readptr(available); + if (ptr != nullptr) { + const auto ret = sock->send(ptr, available); + if (ret > 0) { + writebuffer->advance(ret); + } + } + + // handle incoming packets + const auto space = readbuffer->space(); + if (space > 0) { + const uint32_t n = MIN(350U, space); + uint8_t buf[n]; + const auto ret = sock->recv(buf, n, 0); + if (ret > 0) { + readbuffer->write(buf, ret); + } + } + } +} + +/* + available space in outgoing buffer + */ +uint32_t AP_Networking::Port::txspace(void) +{ + return writebuffer->space(); +} + +void AP_Networking::Port::_begin(uint32_t b, uint16_t rxS, uint16_t txS) +{ + // TODO: use buffer sizes +} + +size_t AP_Networking::Port::_write(const uint8_t *buffer, size_t size) +{ + return writebuffer->write(buffer, size); +} + +ssize_t AP_Networking::Port::_read(uint8_t *buffer, uint16_t count) +{ + return readbuffer->read(buffer, count); +} + +uint32_t AP_Networking::Port::_available() +{ + return readbuffer->available(); +} + + +bool AP_Networking::Port::_discard_input() +{ + readbuffer->clear(); + return true; +} + +/* + initialise read/write buffers + */ +bool AP_Networking::Port::init_buffers(uint32_t size) +{ + readbuffer = new ByteBuffer(size); + writebuffer = new ByteBuffer(size); + return readbuffer != nullptr && writebuffer != nullptr; +} + +#endif // AP_NETWORKING_ENABLED From 31fd43ba259a63e0b2b50fb87abec397ae87bea2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Nov 2023 17:44:30 +1100 Subject: [PATCH 233/499] AP_SerialManager: fixed passthru with network ports --- .../AP_SerialManager/AP_SerialManager.cpp | 40 +++++++++++++++---- libraries/AP_SerialManager/AP_SerialManager.h | 5 ++- 2 files changed, 36 insertions(+), 9 deletions(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 7e269789048f86..33205680ae7e65 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -682,6 +682,24 @@ AP_HAL::UARTDriver *AP_SerialManager::get_serial_by_id(uint8_t id) return nullptr; } +/* + get a UARTState by index +*/ +const AP_SerialManager::UARTState *AP_SerialManager::get_state_by_id(uint8_t id) const +{ + if (id < SERIALMANAGER_NUM_PORTS) { + return &state[id]; + } +#if AP_SERIALMANAGER_REGISTER_ENABLED + for (auto p = registered_ports; p; p = p->next) { + if (p->state.idx == id) { + return &p->state; + } + } +#endif + return nullptr; +} + /* * map from a 16 bit EEPROM baud rate to a real baud rate. For * stm32-based boards we can do 1.5MBit, although 921600 is more @@ -757,18 +775,24 @@ void AP_SerialManager::set_options(uint16_t i) // get the passthru ports if enabled bool AP_SerialManager::get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s, - uint32_t &baud1, uint32_t &baud2) const + uint32_t &baud1, uint32_t &baud2) { if (passthru_port2 < 0 || - passthru_port2 >= SERIALMANAGER_NUM_PORTS || - passthru_port1 < 0 || - passthru_port1 >= SERIALMANAGER_NUM_PORTS) { + passthru_port1 < 0) { + return false; + } + port1 = get_serial_by_id(passthru_port1); + port2 = get_serial_by_id(passthru_port2); + if (port1 == nullptr || port2 == nullptr) { + return false; + } + const auto *state1 = get_state_by_id(passthru_port1); + const auto *state2 = get_state_by_id(passthru_port2); + if (!state1 || !state2) { return false; } - port1 = hal.serial(passthru_port1); - port2 = hal.serial(passthru_port2); - baud1 = state[passthru_port1].baudrate(); - baud2 = state[passthru_port2].baudrate(); + baud1 = state1->baudrate(); + baud2 = state2->baudrate(); timeout_s = MAX(passthru_timeout, 0); return true; } diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index 4d8bfb66cbd954..880135a84da07b 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -246,7 +246,7 @@ class AP_SerialManager { // get the passthru ports if enabled bool get_passthru(AP_HAL::UARTDriver *&port1, AP_HAL::UARTDriver *&port2, uint8_t &timeout_s, - uint32_t &baud1, uint32_t &baud2) const; + uint32_t &baud1, uint32_t &baud2); // disable passthru by settings SERIAL_PASS2 to -1 void disable_passthru(void); @@ -284,6 +284,9 @@ class AP_SerialManager { uint8_t idx; }; + // get a state from serial index + const UARTState *get_state_by_id(uint8_t id) const; + // search through managed serial connections looking for the // instance-nth UART which is running protocol protocol. // protocol_match is used to determine equivalence of one protocol From aec605b020f33f19145438abda1fc02a7ccdbc40 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Nov 2023 06:09:56 +1100 Subject: [PATCH 234/499] waf: enable networking by default when supported, and disable with --disable-networking --- Tools/ardupilotwaf/boards.py | 7 +++++-- wscript | 4 ++-- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 6f53922836732a..776a1cd9223724 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -148,8 +148,8 @@ def srcpath(path): ) cfg.msg("Enabled custom controller", 'no', color='YELLOW') - if cfg.options.enable_networking: - env.CXXFLAGS += ['-DAP_NETWORKING_ENABLED=1'] + if cfg.options.disable_networking: + env.CXXFLAGS += ['-DAP_NETWORKING_ENABLED=0'] if cfg.options.enable_networking_tests: env.CXXFLAGS += ['-DAP_NETWORKING_TESTS_ENABLED=1'] @@ -674,6 +674,9 @@ def configure_env(self, cfg, env): '-Werror=missing-declarations', ] + if not cfg.options.disable_networking: + env.CXXFLAGS += ['-DAP_NETWORKING_ENABLED=1'] + if cfg.options.ubsan or cfg.options.ubsan_abort: env.CXXFLAGS += [ "-fsanitize=undefined", diff --git a/wscript b/wscript index 7f0a2e14dfe356..a2e8a7347808c6 100644 --- a/wscript +++ b/wscript @@ -269,8 +269,8 @@ submodules at specific revisions. g.add_option('--enable-dds', action='store_true', help="Enable the dds client to connect with ROS2/DDS.") - g.add_option('--enable-networking', action='store_true', - help="Enable the networking code") + g.add_option('--disable-networking', action='store_true', + help="Disable the networking API code") g.add_option('--enable-networking-tests', action='store_true', help="Enable the networking test code. Automatically enables networking.") From 7024f4d22a24e4c34b5b5cdbac2b8606a2f62225 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Nov 2023 06:14:46 +1100 Subject: [PATCH 235/499] Tools: change to --disable-networking for SITL --- Tools/autotest/sim_vehicle.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 0c849f6405b6b8..9540454e5231e3 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -413,8 +413,8 @@ def do_build(opts, frame_options): if configure_target == 'sitl' and "--enable-networking" not in cmd_configure: cmd_configure.append("--enable-networking") - if opts.enable_networking and configure_target == 'sitl': - cmd_configure.append("--enable-networking") + if opts.disable_networking or configure_target != "sitl": + cmd_configure.append("--disable-networking") if opts.enable_networking_tests: cmd_configure.append("--enable-networking-tests") @@ -1336,8 +1336,8 @@ def generate_frame_help(): help="IP address of the simulator. Defaults to localhost") group_sim.add_option("--enable-dds", action='store_true', help="Enable the dds client to connect with ROS2/DDS") -group_sim.add_option("--enable-networking", action='store_true', - help="Enable networking") +group_sim.add_option("--disable-networking", action='store_true', + help="Disable networking APIs") group_sim.add_option("--enable-networking-tests", action='store_true', help="Enable networking tests") From d5470ae466774087868cea36522b496dcff61103 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Nov 2023 06:16:51 +1100 Subject: [PATCH 236/499] Tools: disable networking in ccache test this allows for fair comparison between Durandal and Pixhawk6X --- Tools/scripts/build_tests/test_ccache.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/build_tests/test_ccache.py b/Tools/scripts/build_tests/test_ccache.py index 740390e0067668..884c3282e4c135 100755 --- a/Tools/scripts/build_tests/test_ccache.py +++ b/Tools/scripts/build_tests/test_ccache.py @@ -44,7 +44,7 @@ def ccache_stats(): def build_board(boardname): - subprocess.run(["./waf", "configure", "--board", boardname]) + subprocess.run(["./waf", "configure", "--board", boardname, '--disable-networking']) subprocess.run(["./waf", "clean", "copter"]) From 2ba4bf14789638d0cf299a519d061d199efbfe87 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Nov 2023 06:17:22 +1100 Subject: [PATCH 237/499] HAL_ChibiOS: allow for --disable-networking --- .../hwdef/scripts/chibios_hwdef.py | 23 ++++++++++--------- 1 file changed, 12 insertions(+), 11 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 5730f68585304c..6552630754f094 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -965,18 +965,19 @@ def write_mcu_config(self, f): f.write('#define STM32_USB_USE_OTG2 TRUE\n') if 'ETH1' in self.bytype: - f.write('// Configure for Ethernet support\n') - f.write('#define CH_CFG_USE_MAILBOXES TRUE\n') - f.write('#define HAL_USE_MAC TRUE\n') - f.write('#define MAC_USE_EVENTS TRUE\n') - f.write('#define STM32_ETH_BUFFERS_EXTERN\n') - f.write('#define AP_NETWORKING_ENABLED TRUE\n') self.build_flags.append('USE_LWIP=yes') - self.env_vars['WITH_NETWORKING'] = True - else: - f.write('#define AP_NETWORKING_ENABLED FALSE\n') - self.build_flags.append('USE_LWIP=no') - self.env_vars['WITH_NETWORKING'] = False + f.write(''' + +#ifndef AP_NETWORKING_ENABLED +// Configure for Ethernet support +#define AP_NETWORKING_ENABLED 1 +#define CH_CFG_USE_MAILBOXES TRUE +#define HAL_USE_MAC TRUE +#define MAC_USE_EVENTS TRUE +#define STM32_ETH_BUFFERS_EXTERN +#endif + +''') defines = self.get_mcu_config('DEFINES', False) if defines is not None: From f175cb19a1e09f19d83ea8677bc2302a36ec5021 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 17 Nov 2023 08:44:12 +1100 Subject: [PATCH 238/499] Tools: added autotest for networking over UDP downloads a log with mavlink over UDP from NET_P1 port --- Tools/autotest/ardusub.py | 1 + Tools/autotest/vehicle_test_suite.py | 36 ++++++++++++++++++++++++++-- 2 files changed, 35 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index d416d8efcaf75b..d1fc238c8263b9 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -530,6 +530,7 @@ def tests(self): self.MotorThrustHoverParameterIgnore, self.SET_POSITION_TARGET_GLOBAL_INT, self.TestLogDownloadMAVProxy, + self.TestLogDownloadMAVProxyNetwork, self.MAV_CMD_NAV_LOITER_UNLIM, self.MAV_CMD_NAV_LAND, self.MAV_CMD_MISSION_START, diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index d8eb3fb01548da..40e5190969e73e 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -4137,6 +4137,35 @@ def TestLogDownloadMAVProxy(self, upload_logs=False): self.mavproxy_unload_module(mavproxy, 'log') self.stop_mavproxy(mavproxy) + def TestLogDownloadMAVProxyNetwork(self, upload_logs=False): + """Download latest log over network port""" + self.context_push() + self.set_parameters({ + "NET_ENABLED": 1, + "NET_DHCP": 0, + "NET_P1_TYPE": 1, + "NET_P1_PROTOCOL": 2, + "NET_P1_PORT": 15004, + "NET_P1_IP0": 127, + "NET_P1_IP1": 0, + "NET_P1_IP2": 0, + "NET_P1_IP3": 1 + }) + self.reboot_sitl() + filename = "MAVProxy-downloaded-net-log.BIN" + mavproxy = self.start_mavproxy(master=':15004') + self.mavproxy_load_module(mavproxy, 'log') + mavproxy.send("log list\n") + mavproxy.expect("numLogs") + self.wait_heartbeat() + self.wait_heartbeat() + mavproxy.send("set shownoise 0\n") + mavproxy.send("log download latest %s\n" % filename) + mavproxy.expect("Finished downloading", timeout=120) + self.mavproxy_unload_module(mavproxy, 'log') + self.stop_mavproxy(mavproxy) + self.context_pop() + def show_gps_and_sim_positions(self, on_off): """Allow to display gps and actual position on map.""" if on_off is True: @@ -8123,7 +8152,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= def defaults_filepath(self): return None - def start_mavproxy(self, sitl_rcin_port=None): + def start_mavproxy(self, sitl_rcin_port=None, master=None): self.start_mavproxy_count += 1 if self.mavproxy is not None: return self.mavproxy @@ -8138,9 +8167,12 @@ def start_mavproxy(self, sitl_rcin_port=None): if sitl_rcin_port is None: sitl_rcin_port = self.sitl_rcin_port() + if master is None: + master = 'tcp:127.0.0.1:%u' % self.adjust_ardupilot_port(5762) + mavproxy = util.start_MAVProxy_SITL( self.vehicleinfo_key(), - master='tcp:127.0.0.1:%u' % self.adjust_ardupilot_port(5762), + master=master, logfile=self.mavproxy_logfile, options=self.mavproxy_options(), pexpect_timeout=pexpect_timeout, From f28ef5e5a7b3ad39c29eaaa57999b791b25aabc8 Mon Sep 17 00:00:00 2001 From: muramura Date: Sat, 11 Nov 2023 02:06:52 +0900 Subject: [PATCH 239/499] AP_Baro: Returns directly calculated values --- libraries/AP_Baro/AP_Baro.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index f7548894201572..874f4e054ad405 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -404,15 +404,12 @@ void AP_Baro::update_calibration() // given base_pressure in Pascal float AP_Baro::get_altitude_difference(float base_pressure, float pressure) const { - float ret; float temp = C_TO_KELVIN(get_ground_temperature()); float scaling = pressure / base_pressure; // This is an exact calculation that is within +-2.5m of the standard // atmosphere tables in the troposphere (up to 11,000 m amsl). - ret = 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling)))-_field_elevation_active; - - return ret; + return 153.8462f * temp * (1.0f - expf(0.190259f * logf(scaling)))-_field_elevation_active; } // return sea level pressure where in which the current measured pressure From d0bc7921f0921c1e091fa032c20b5432973c92c3 Mon Sep 17 00:00:00 2001 From: menrise Date: Sun, 13 Aug 2023 21:14:54 +0300 Subject: [PATCH 240/499] Docker: Added oportunity to set build flags (some envs) via docker build args --- Dockerfile | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/Dockerfile b/Dockerfile index 495c843488054b..fd24eaff53574c 100644 --- a/Dockerfile +++ b/Dockerfile @@ -7,6 +7,11 @@ ARG DEBIAN_FRONTEND=noninteractive ARG USER_NAME=ardupilot ARG USER_UID=1000 ARG USER_GID=1000 +ARG SKIP_AP_EXT_ENV=1 +ARG SKIP_AP_GRAPHIC_ENV=1 +ARG SKIP_AP_COV_ENV=1 +ARG SKIP_AP_GIT_CHECK=1 + RUN groupadd ${USER_NAME} --gid ${USER_GID}\ && useradd -l -m ${USER_NAME} -u ${USER_UID} -g ${USER_GID} -s /bin/bash @@ -29,7 +34,7 @@ RUN chown -R ${USER_NAME}:${USER_NAME} /${USER_NAME} USER ${USER_NAME} -ENV SKIP_AP_EXT_ENV=1 SKIP_AP_GRAPHIC_ENV=1 SKIP_AP_COV_ENV=1 SKIP_AP_GIT_CHECK=1 +ENV SKIP_AP_EXT_ENV=$SKIP_AP_EXT_ENV SKIP_AP_GRAPHIC_ENV=$SKIP_AP_GRAPHIC_ENV SKIP_AP_COV_ENV=$SKIP_AP_COV_ENV SKIP_AP_GIT_CHECK=$SKIP_AP_GIT_CHECK RUN Tools/environment_install/install-prereqs-ubuntu.sh -y # add waf alias to ardupilot waf to .ardupilot_env From 30bccf62663dab5786e912ff31e1f2f49598f1a1 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 17 Nov 2023 11:20:39 -0800 Subject: [PATCH 241/499] AP_Networking: adjustable PORT buf size --- libraries/AP_Networking/AP_Networking.h | 4 ++-- libraries/AP_Networking/AP_Networking_Config.h | 8 ++++++++ libraries/AP_Networking/AP_Networking_port.cpp | 12 ++++++------ 3 files changed, 16 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index e49f25a697ba44..58adaa3ac68c8e 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -206,11 +206,11 @@ class AP_Networking return false; } - void udp_client_init(void); + void udp_client_init(const uint32_t size_rx, const uint32_t size_tx); void udp_client_loop(void); private: - bool init_buffers(uint32_t size); + bool init_buffers(const uint32_t size_rx, const uint32_t size_tx); uint32_t txspace() override; void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index bfc4af537f226d..f7449065758efb 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -22,6 +22,14 @@ #define AP_NETWORKING_SOCKETS_ENABLED (HAL_OS_SOCKETS || AP_NETWORKING_BACKEND_CHIBIOS) +#ifndef AP_NETWORKING_PORT_UDP_CLIENT_RX_BUF_DEFAULT_SIZE +#define AP_NETWORKING_PORT_UDP_CLIENT_RX_BUF_DEFAULT_SIZE 4096 +#endif + +#ifndef AP_NETWORKING_PORT_UDP_CLIENT_TX_BUF_DEFAULT_SIZE +#define AP_NETWORKING_PORT_UDP_CLIENT_TX_BUF_DEFAULT_SIZE 4096 +#endif + // --------------------------- // IP Features // --------------------------- diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index 3a87db30cfba0b..a476218955c0a9 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -61,7 +61,7 @@ void AP_Networking::ports_init(void) case NetworkPortType::NONE: break; case NetworkPortType::UDP_CLIENT: - p.udp_client_init(); + p.udp_client_init(AP_NETWORKING_PORT_UDP_CLIENT_RX_BUF_DEFAULT_SIZE, AP_NETWORKING_PORT_UDP_CLIENT_TX_BUF_DEFAULT_SIZE); break; } if (p.sock != nullptr) { @@ -73,9 +73,9 @@ void AP_Networking::ports_init(void) /* initialise a UDP client */ -void AP_Networking::Port::udp_client_init(void) +void AP_Networking::Port::udp_client_init(const uint32_t size_rx, const uint32_t size_tx) { - if (!init_buffers(4096)) { + if (!init_buffers(size_rx, size_tx)) { return; } sock = new SocketAPM(true); @@ -171,10 +171,10 @@ bool AP_Networking::Port::_discard_input() /* initialise read/write buffers */ -bool AP_Networking::Port::init_buffers(uint32_t size) +bool AP_Networking::Port::init_buffers(const uint32_t size_rx, const uint32_t size_tx) { - readbuffer = new ByteBuffer(size); - writebuffer = new ByteBuffer(size); + readbuffer = new ByteBuffer(size_rx); + writebuffer = new ByteBuffer(size_tx); return readbuffer != nullptr && writebuffer != nullptr; } From fcf602cbe2388f438882ad51ecf6992701bcf403 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 17 Nov 2023 11:21:12 -0800 Subject: [PATCH 242/499] AP_Networking: init socket null check --- libraries/AP_Networking/AP_Networking_port.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index a476218955c0a9..17d2785a44fa3c 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -78,6 +78,9 @@ void AP_Networking::Port::udp_client_init(const uint32_t size_rx, const uint32_t if (!init_buffers(size_rx, size_tx)) { return; } + if (sock != nullptr) { + return false; + } sock = new SocketAPM(true); if (sock == nullptr) { return; From 3b35915774be2b936382194a7af36fb624cd85e8 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 17 Nov 2023 14:26:11 -0800 Subject: [PATCH 243/499] AP_Networking: return bug fix Co-authored-by: Ryan --- libraries/AP_Networking/AP_Networking_port.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index 17d2785a44fa3c..e4251c4a39085b 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -79,7 +79,7 @@ void AP_Networking::Port::udp_client_init(const uint32_t size_rx, const uint32_t return; } if (sock != nullptr) { - return false; + return; } sock = new SocketAPM(true); if (sock == nullptr) { From afa263c6915df5dcab48d68a24feb9da32a9b919 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 17 Nov 2023 12:57:33 +1100 Subject: [PATCH 244/499] SITL: set sitl point for GPS backends in constructor _sitl is guaranteed non-nullptr by the SITL::GPS::update() --- libraries/SITL/SIM_GPS.cpp | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 1b73e48899bcea..4416ed7187946a 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -39,6 +39,7 @@ GPS_Backend::GPS_Backend(GPS &_front, uint8_t _instance) : front{_front}, instance{_instance} { + _sitl = AP::sitl(); } ssize_t GPS_Backend::write_to_autopilot(const char *p, size_t size) const @@ -53,13 +54,6 @@ ssize_t GPS_Backend::read_from_autopilot(char *buffer, size_t size) const void GPS_Backend::update(const GPS_Data &d) { - if (_sitl == nullptr) { - _sitl = AP::sitl(); - if (_sitl == nullptr) { - return; - } - } - update_read(&d); update_write(&d); } From fffe3afb287512d314b85146291426b303a580b5 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 16 Nov 2023 16:04:20 -0600 Subject: [PATCH 245/499] AP_Arming: add arm/disarm controlled GPIO for module power control --- libraries/AP_Arming/AP_Arming.cpp | 17 +++++++++++++++-- libraries/AP_Arming/AP_Arming.h | 2 ++ 2 files changed, 17 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index fef0bff6abad9e..630340038c0e4f 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -1681,7 +1681,9 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) } } #endif - +#if defined(HAL_ARM_GPIO_PIN) + update_arm_gpio(); +#endif return armed; } @@ -1721,10 +1723,21 @@ bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks) } } #endif - +#if defined(HAL_ARM_GPIO_PIN) + update_arm_gpio(); +#endif return true; } +#if defined(HAL_ARM_GPIO_PIN) +void AP_Arming::update_arm_gpio() +{ + if (!AP_BoardConfig::arming_gpio_disabled()) { + hal.gpio->write(HAL_ARM_GPIO_PIN, HAL_ARM_GPIO_POL_INVERT ? !armed : armed); + } +} +#endif + void AP_Arming::send_arm_disarm_statustext(const char *str) const { if (option_enabled(AP_Arming::Option::DISABLE_STATUSTEXT_ON_STATE_CHANGE)) { diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index a755bc0bd04d46..a67a74bcd04503 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -303,6 +303,8 @@ class AP_Arming { uint32_t last_prearm_display_ms; // last time we send statustexts for prearm failures bool running_arming_checks; // true if the arming checks currently being performed are being done because the vehicle is trying to arm the vehicle + + void update_arm_gpio(); }; namespace AP { From 176a4aa51a3700a8c84d6fc9cba8b99c5a69825a Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 16 Nov 2023 16:04:20 -0600 Subject: [PATCH 246/499] AP_BoardConfig: add arm/disarm controlled GPIO for module power control --- libraries/AP_BoardConfig/AP_BoardConfig.cpp | 2 +- libraries/AP_BoardConfig/AP_BoardConfig.h | 12 +++++++++++- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.cpp b/libraries/AP_BoardConfig/AP_BoardConfig.cpp index cbd3292236c230..7367d34306e6bc 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig.cpp @@ -289,7 +289,7 @@ const AP_Param::GroupInfo AP_BoardConfig::var_info[] = { // @Param: OPTIONS // @DisplayName: Board options // @Description: Board specific option flags - // @Bitmask: 0:Enable hardware watchdog, 1:Disable MAVftp, 2:Enable set of internal parameters, 3:Enable Debug Pins, 4:Unlock flash on reboot, 5:Write protect firmware flash on reboot, 6:Write protect bootloader flash on reboot, 7:Skip board validation + // @Bitmask: 0:Enable hardware watchdog, 1:Disable MAVftp, 2:Enable set of internal parameters, 3:Enable Debug Pins, 4:Unlock flash on reboot, 5:Write protect firmware flash on reboot, 6:Write protect bootloader flash on reboot, 7:Skip board validation, 8:Disable board arming gpio output change on arm/disarm // @User: Advanced AP_GROUPINFO("OPTIONS", 19, AP_BoardConfig, _options, HAL_BRD_OPTIONS_DEFAULT), diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.h b/libraries/AP_BoardConfig/AP_BoardConfig.h index f1321c93ecf78c..18e6a007e94e1c 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.h +++ b/libraries/AP_BoardConfig/AP_BoardConfig.h @@ -155,9 +155,19 @@ class AP_BoardConfig { UNLOCK_FLASH = (1<<4), WRITE_PROTECT_FLASH = (1<<5), WRITE_PROTECT_BOOTLOADER = (1<<6), - SKIP_BOARD_VALIDATION = (1<<7) + SKIP_BOARD_VALIDATION = (1<<7), + DISABLE_ARMING_GPIO = (1<<8) }; + //return true if arming gpio output is disabled + static bool arming_gpio_disabled(void) { + return _singleton?(_singleton->_options & DISABLE_ARMING_GPIO)!=0:1; + } + +#ifndef HAL_ARM_GPIO_POL_INVERT +#define HAL_ARM_GPIO_POL_INVERT 0 +#endif + // return true if ftp is disabled static bool ftp_disabled(void) { return _singleton?(_singleton->_options & DISABLE_FTP)!=0:1; From 8e50584bd8863c4a90e8b5cd46229952bd5b394f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 19 Nov 2023 08:46:46 +1100 Subject: [PATCH 247/499] AP_Networking: fixed buffer size handling make begin() able to change buffer sizes --- libraries/AP_Networking/AP_Networking.h | 3 ++ .../AP_Networking/AP_Networking_Config.h | 8 ---- .../AP_Networking/AP_Networking_port.cpp | 43 ++++++++++++++++--- 3 files changed, 40 insertions(+), 14 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 58adaa3ac68c8e..2dffb34dff8557 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -223,6 +223,9 @@ class AP_Networking ByteBuffer *readbuffer; ByteBuffer *writebuffer; + uint32_t last_size_tx; + uint32_t last_size_rx; + HAL_Semaphore sem; }; private: diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index f7449065758efb..bfc4af537f226d 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -22,14 +22,6 @@ #define AP_NETWORKING_SOCKETS_ENABLED (HAL_OS_SOCKETS || AP_NETWORKING_BACKEND_CHIBIOS) -#ifndef AP_NETWORKING_PORT_UDP_CLIENT_RX_BUF_DEFAULT_SIZE -#define AP_NETWORKING_PORT_UDP_CLIENT_RX_BUF_DEFAULT_SIZE 4096 -#endif - -#ifndef AP_NETWORKING_PORT_UDP_CLIENT_TX_BUF_DEFAULT_SIZE -#define AP_NETWORKING_PORT_UDP_CLIENT_TX_BUF_DEFAULT_SIZE 4096 -#endif - // --------------------------- // IP Features // --------------------------- diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index e4251c4a39085b..f9f7248dba6656 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -14,6 +14,14 @@ extern const AP_HAL::HAL& hal; +#ifndef AP_NETWORKING_PORT_MIN_TXSIZE +#define AP_NETWORKING_PORT_MIN_TXSIZE 2048 +#endif + +#ifndef AP_NETWORKING_PORT_MIN_RXSIZE +#define AP_NETWORKING_PORT_MIN_RXSIZE 2048 +#endif + const AP_Param::GroupInfo AP_Networking::Port::var_info[] = { // @Param: TYPE // @DisplayName: Port type @@ -26,9 +34,8 @@ const AP_Param::GroupInfo AP_Networking::Port::var_info[] = { // @Param: PROTOCOL // @DisplayName: protocol // @Description: protocol - // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:Gimbal, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:EFI Serial, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency, 44:IRC Tramp - // @RebootRequired: True // @User: Advanced + // @CopyFieldsFrom: SERIAL0_PROTOCOL AP_GROUPINFO("PROTOCOL", 2, AP_Networking::Port, state.protocol, 0), // @Group: IP @@ -61,7 +68,7 @@ void AP_Networking::ports_init(void) case NetworkPortType::NONE: break; case NetworkPortType::UDP_CLIENT: - p.udp_client_init(AP_NETWORKING_PORT_UDP_CLIENT_RX_BUF_DEFAULT_SIZE, AP_NETWORKING_PORT_UDP_CLIENT_TX_BUF_DEFAULT_SIZE); + p.udp_client_init(AP_NETWORKING_PORT_MIN_RXSIZE, AP_NETWORKING_PORT_MIN_TXSIZE); break; } if (p.sock != nullptr) { @@ -75,6 +82,7 @@ void AP_Networking::ports_init(void) */ void AP_Networking::Port::udp_client_init(const uint32_t size_rx, const uint32_t size_tx) { + WITH_SEMAPHORE(sem); if (!init_buffers(size_rx, size_tx)) { return; } @@ -112,6 +120,7 @@ void AP_Networking::Port::udp_client_loop(void) while (true) { hal.scheduler->delay_microseconds(500); + WITH_SEMAPHORE(sem); // handle outgoing packets uint32_t available; @@ -141,32 +150,39 @@ void AP_Networking::Port::udp_client_loop(void) */ uint32_t AP_Networking::Port::txspace(void) { + WITH_SEMAPHORE(sem); return writebuffer->space(); } void AP_Networking::Port::_begin(uint32_t b, uint16_t rxS, uint16_t txS) { - // TODO: use buffer sizes + rxS = MAX(rxS, AP_NETWORKING_PORT_MIN_RXSIZE); + txS = MAX(txS, AP_NETWORKING_PORT_MIN_TXSIZE); + init_buffers(rxS, txS); } size_t AP_Networking::Port::_write(const uint8_t *buffer, size_t size) { + WITH_SEMAPHORE(sem); return writebuffer->write(buffer, size); } ssize_t AP_Networking::Port::_read(uint8_t *buffer, uint16_t count) { + WITH_SEMAPHORE(sem); return readbuffer->read(buffer, count); } uint32_t AP_Networking::Port::_available() { + WITH_SEMAPHORE(sem); return readbuffer->available(); } bool AP_Networking::Port::_discard_input() { + WITH_SEMAPHORE(sem); readbuffer->clear(); return true; } @@ -176,8 +192,23 @@ bool AP_Networking::Port::_discard_input() */ bool AP_Networking::Port::init_buffers(const uint32_t size_rx, const uint32_t size_tx) { - readbuffer = new ByteBuffer(size_rx); - writebuffer = new ByteBuffer(size_tx); + if (size_tx == last_size_tx && + size_rx == last_size_rx) { + return true; + } + WITH_SEMAPHORE(sem); + if (readbuffer == nullptr) { + readbuffer = new ByteBuffer(size_rx); + } else { + readbuffer->set_size_best(size_rx); + } + if (writebuffer == nullptr) { + writebuffer = new ByteBuffer(size_tx); + } else { + writebuffer->set_size_best(size_tx); + } + last_size_rx = size_rx; + last_size_tx = size_tx; return readbuffer != nullptr && writebuffer != nullptr; } From 213cba86af200aaad49e84769d22954bb839c964 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Fri, 17 Nov 2023 19:00:13 -0700 Subject: [PATCH 248/499] AP_SerialManager: Add missing option for XRCE DDS Signed-off-by: Ryan Friedman --- libraries/AP_SerialManager/AP_SerialManager.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 33205680ae7e65..838336d547fb54 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -178,7 +178,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Param: 1_PROTOCOL // @DisplayName: Telem1 protocol selection // @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details. - // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:Gimbal, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:EFI Serial, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency, 44:IRC Tramp + // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:Gimbal, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:EFI Serial, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency, 44:IRC Tramp, 45:DDS XRCE // @User: Standard // @RebootRequired: True AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, DEFAULT_SERIAL1_PROTOCOL), From 2d465a5b201115d31247a757095568a9bd4536b6 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Fri, 17 Nov 2023 19:20:28 -0700 Subject: [PATCH 249/499] AP_DDS: Fix typos and out of date info Signed-off-by: Ryan Friedman --- libraries/AP_DDS/README.md | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index 5b98ecbac774a2..b148fa23e079bc 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -149,8 +149,6 @@ Follow the steps to use the microROS Agent - Do "Creating the micro-ROS agent" - Source your ROS workspace -Until this [PR](https://github.com/micro-ROS/micro-ROS.github.io/pull/401) is merged, ignore the notes about `foxy`. It works on `humble`. - ## Using the ROS 2 CLI to Read Ardupilot Data After your setups are complete, do the following: @@ -252,7 +250,7 @@ In order to consume the transforms, it's highly recommended to [create and run a ## Using ROS 2 services -The `AP_DDS` libraary exposes services which are automatically mapped to ROS 2 +The `AP_DDS` library exposes services which are automatically mapped to ROS 2 services using appropriate naming conventions for topics and message and service types. An earlier version of `AP_DDS` required the use of the eProsima [Integration Service](https://github.com/eProsima/Integration-Service) to map @@ -338,7 +336,7 @@ Note that a service interface always requires a Request / Response pair. #### ROS 2 topic and service names The ROS 2 design article: [Topic and Service name mapping to DDS](https://design.ros2.org/articles/topic_and_service_names.html) describes the mapping of ROS 2 topic and service -names to DDS. Each ROS 2 subsytem is provided a prefix when mapped to DDS. +names to DDS. Each ROS 2 subsystem is provided a prefix when mapped to DDS. The request / response pair for services require an additional suffix. | ROS 2 subsystem | DDS Prefix | DDS Suffix | From b7fd04318a074b0c4c22ea3d673fbaf90e5f5c82 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 17 Nov 2023 17:31:21 +0000 Subject: [PATCH 250/499] AP_HAL_ChibiOS: fix race condition in sending serial LED data --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 223e5844d873f8..f90bb115cbf89e 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -2626,9 +2626,9 @@ void RCOutput::serial_led_send(const uint16_t chan) } if (grp->prepared_send) { - chEvtSignal(led_thread_ctx, EVT_LED_SEND); grp->serial_led_pending = true; serial_led_pending = true; + chEvtSignal(led_thread_ctx, EVT_LED_SEND); } } #endif // HAL_SERIALLED_ENABLED From 73610c8932d710acd770d748f9b4a669839257df Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 17 Nov 2023 17:32:01 +0000 Subject: [PATCH 251/499] AP_HAL_ChibiOS: return success status from serial_led_send and set_serial_led_rgb_data --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 34 +++++++++++++++------------ libraries/AP_HAL_ChibiOS/RCOutput.h | 4 ++-- 2 files changed, 21 insertions(+), 17 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index f90bb115cbf89e..e703d362991052 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -2506,29 +2506,29 @@ void RCOutput::_set_profiled_clock(pwm_group *grp, uint8_t idx, uint8_t led) setup serial LED output data for a given output channel and a LED number. LED -1 is all LEDs */ -void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) +bool RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) { if (!_initialised) { - return; + return false; } uint8_t i = 0; pwm_group *grp = find_chan(chan, i); if (!grp) { - return; + return false; } if (grp->serial_led_pending) { // dont allow setting new data if a send is pending // would result in a fight over the mutex - return; - }; + return false; + } WITH_SEMAPHORE(grp->serial_led_mutex); if (grp->serial_nleds == 0 || led >= grp->serial_nleds) { - return; + return false; } if ((grp->current_mode != grp->led_mode) && is_led_protocol(grp->led_mode)) { @@ -2545,7 +2545,7 @@ void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t } grp->led_mode = MODE_PWM_NONE; grp->serial_nleds = 0; - return; + return false; } } @@ -2556,11 +2556,11 @@ void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t // Failed to set output mode grp->led_mode = MODE_PWM_NONE; grp->serial_nleds = 0; - return; + return false; } } else if (!is_led_protocol(grp->current_mode)) { - return; + return false; } if (led == -1) { @@ -2568,7 +2568,7 @@ void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t for (uint8_t n=0; nserial_nleds; n++) { serial_led_set_single_rgb_data(*grp, i, n, red, green, blue); } - return; + return true; } // if not ouput clock and trailing frames, run through all LED's to do it now @@ -2579,6 +2579,8 @@ void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t } } serial_led_set_single_rgb_data(*grp, i, uint8_t(led), red, green, blue); + + return true; } /* @@ -2603,26 +2605,26 @@ void RCOutput::serial_led_set_single_rgb_data(pwm_group& group, uint8_t idx, uin /* trigger send of serial led data for one group */ -void RCOutput::serial_led_send(const uint16_t chan) +bool RCOutput::serial_led_send(const uint16_t chan) { if (!_initialised) { - return; + return false; } if (led_thread_ctx == nullptr) { - return; + return false; } uint8_t i; pwm_group *grp = find_chan(chan, i); if (!grp) { - return; + return false; } WITH_SEMAPHORE(grp->serial_led_mutex); if (grp->serial_nleds == 0 || !is_led_protocol(grp->current_mode)) { - return; + return false; } if (grp->prepared_send) { @@ -2630,6 +2632,8 @@ void RCOutput::serial_led_send(const uint16_t chan) serial_led_pending = true; chEvtSignal(led_thread_ctx, EVT_LED_SEND); } + + return true; } #endif // HAL_SERIALLED_ENABLED diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index b0984b3bfdd8f9..1fbd983944e5c0 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -254,12 +254,12 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput setup serial LED output data for a given output channel and LEDs number. LED -1 is all LEDs */ - void set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) override; + bool set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) override; /* trigger send of serial LED data */ - void serial_led_send(const uint16_t chan) override; + bool serial_led_send(const uint16_t chan) override; #endif /* rcout thread From d30e52ed3fff25d83d7e7d0801abb36a672ddb19 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 17 Nov 2023 17:33:04 +0000 Subject: [PATCH 252/499] AP_HAL: return success status from serial_led_send and set_serial_led_rgb_data --- libraries/AP_HAL/RCOutput.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index 0104817c2040fb..bc360932268ecd 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -352,12 +352,12 @@ class AP_HAL::RCOutput { setup serial led output data for a given output channel and led number. A led number of -1 means all LEDs. LED 0 is the first LED */ - virtual void set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) {} + virtual bool set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) { return false; } /* trigger send of serial led */ - virtual void serial_led_send(const uint16_t chan) {} + virtual bool serial_led_send(const uint16_t chan) { return false; } virtual void timer_info(ExpandingString &str) {} From 00ceca0fffa4621912ee1b03bbb2e52bfaf57c73 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 17 Nov 2023 17:33:16 +0000 Subject: [PATCH 253/499] AP_SerialLED: return success status from send and set_RGB --- libraries/AP_SerialLED/AP_SerialLED.cpp | 11 ++++++----- libraries/AP_SerialLED/AP_SerialLED.h | 4 ++-- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/libraries/AP_SerialLED/AP_SerialLED.cpp b/libraries/AP_SerialLED/AP_SerialLED.cpp index fafccd2af2fbe9..f5fc838abc5207 100644 --- a/libraries/AP_SerialLED/AP_SerialLED.cpp +++ b/libraries/AP_SerialLED/AP_SerialLED.cpp @@ -62,20 +62,21 @@ bool AP_SerialLED::set_num_profiled(uint8_t chan, uint8_t num_leds) } // set RGB value on LED number. LED number -1 is all LEDs. First LED is 0. chan is PWM output, 1..16 -void AP_SerialLED::set_RGB(uint8_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) +bool AP_SerialLED::set_RGB(uint8_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) { if (chan >= 1 && chan <= 16) { - hal.rcout->set_serial_led_rgb_data(chan-1, led, red, green, blue); + return hal.rcout->set_serial_led_rgb_data(chan-1, led, red, green, blue); } + return false; } // trigger sending of LED changes to LEDs -void AP_SerialLED::send(uint8_t chan) +bool AP_SerialLED::send(uint8_t chan) { if (chan >= 1 && chan <= 16) { - hal.rcout->serial_led_send(chan-1); + return hal.rcout->serial_led_send(chan-1); } - + return false; } #endif // AP_SERIALLED_ENABLED diff --git a/libraries/AP_SerialLED/AP_SerialLED.h b/libraries/AP_SerialLED/AP_SerialLED.h index 4ec45ab8d58091..b317cd1c0efbcf 100644 --- a/libraries/AP_SerialLED/AP_SerialLED.h +++ b/libraries/AP_SerialLED/AP_SerialLED.h @@ -42,10 +42,10 @@ class AP_SerialLED { void set_RGB_mask(uint8_t chan, uint32_t ledmask, uint8_t red, uint8_t green, uint8_t blue); // set RGB value on LED. LED -1 is all LEDs. LED 0 is first LED. chan is PWM output, 1..16 - void set_RGB(uint8_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue); + bool set_RGB(uint8_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue); // trigger sending of LED changes to LEDs - void send(uint8_t chan); + bool send(uint8_t chan); // singleton support static AP_SerialLED *get_singleton(void) { From b5ef11797b89acde41e2f3d9682ec71143e55e35 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 17 Nov 2023 17:36:10 +0000 Subject: [PATCH 254/499] AP_Scripting: add success status to serialLED:send and serialLED:set_RGB --- libraries/AP_Scripting/docs/docs.lua | 2 ++ libraries/AP_Scripting/generator/description/bindings.desc | 4 ++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index f3a6e8b638eaa8..40ddb7ac9c35fa 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -2000,6 +2000,7 @@ serialLED = {} -- desc ---@param chan integer +---@return boolean function serialLED:send(chan) end -- desc @@ -2008,6 +2009,7 @@ function serialLED:send(chan) end ---@param red integer ---@param green integer ---@param blue integer +---@return boolean function serialLED:set_RGB(chan, led_index, red, green, blue) end -- desc diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 284633ce17986f..a37476a5252d93 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -313,8 +313,8 @@ singleton AP_SerialLED depends AP_SERIALLED_ENABLED singleton AP_SerialLED method set_num_neopixel boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS singleton AP_SerialLED method set_num_neopixel_rgb boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS singleton AP_SerialLED method set_num_profiled boolean uint8_t 1 16 uint8_t 0 AP_SERIALLED_MAX_LEDS -singleton AP_SerialLED method set_RGB void uint8_t 1 16 int8_t -1 INT8_MAX uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check -singleton AP_SerialLED method send void uint8_t 1 16 +singleton AP_SerialLED method set_RGB boolean uint8_t 1 16 int8_t -1 INT8_MAX uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check +singleton AP_SerialLED method send boolean uint8_t 1 16 include SRV_Channel/SRV_Channel.h singleton SRV_Channels depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RC_OUT)) From 04fa8ed59360f432384da331ee73af0ad5bcbac0 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 17 Nov 2023 18:04:48 +0000 Subject: [PATCH 255/499] AP_HAL_SITL: return success status from serial_led_send and set_serial_led_rgb_data --- libraries/AP_HAL_SITL/RCOutput.cpp | 12 +++++++----- libraries/AP_HAL_SITL/RCOutput.h | 4 ++-- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/libraries/AP_HAL_SITL/RCOutput.cpp b/libraries/AP_HAL_SITL/RCOutput.cpp index 3a39d31c2b4b40..423c4ea57e4d77 100644 --- a/libraries/AP_HAL_SITL/RCOutput.cpp +++ b/libraries/AP_HAL_SITL/RCOutput.cpp @@ -125,34 +125,36 @@ bool RCOutput::set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, ou return false; } -void RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) +bool RCOutput::set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) { if (chan > 15) { - return; + return false; } SITL::SIM *sitl = AP::sitl(); if (led == -1) { for (uint8_t i=0; i < sitl->led.num_leds[chan]; i++) { set_serial_led_rgb_data(chan, i, red, green, blue); } - return; + return true; } if (led < -1 || led >= sitl->led.num_leds[chan]) { - return; + return false; } if (sitl) { sitl->led.rgb[chan][led].rgb[0] = red; sitl->led.rgb[chan][led].rgb[1] = green; sitl->led.rgb[chan][led].rgb[2] = blue; } + return true; } -void RCOutput::serial_led_send(const uint16_t chan) +bool RCOutput::serial_led_send(const uint16_t chan) { SITL::SIM *sitl = AP::sitl(); if (sitl) { sitl->led.send_counter++; } + return true; } #endif //CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/RCOutput.h b/libraries/AP_HAL_SITL/RCOutput.h index 34b124c241c157..fe6324d4ba2390 100644 --- a/libraries/AP_HAL_SITL/RCOutput.h +++ b/libraries/AP_HAL_SITL/RCOutput.h @@ -42,8 +42,8 @@ class HALSITL::RCOutput : public AP_HAL::RCOutput { Serial LED emulation */ bool set_serial_led_num_LEDs(const uint16_t chan, uint8_t num_leds, output_mode mode = MODE_PWM_NONE, uint32_t clock_mask = 0) override; - void set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) override; - void serial_led_send(const uint16_t chan) override; + bool set_serial_led_rgb_data(const uint16_t chan, int8_t led, uint8_t red, uint8_t green, uint8_t blue) override; + bool serial_led_send(const uint16_t chan) override; private: SITL_State *_sitlState; From 229916a48cb3e3de3d0e7512560b67171fc71fe0 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 17 Nov 2023 19:55:37 +0000 Subject: [PATCH 256/499] AP_HAL_ChibiOS: enable serial LEDs on ARK_CANNODE --- libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat index a4cf80cd7c99d8..5c6f22eee05d6b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat @@ -126,3 +126,4 @@ define CAN_APP_NODE_NAME "org.ardupilot.ARK_CANNODE" # enable ESC control define HAL_SUPPORT_RCOUT_SERIAL 1 define HAL_WITH_ESC_TELEM 1 +define AP_SERIALLED_ENABLED 1 From c017c8acf4b64601f3dfc32acf136c332141a89a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:10:36 +1100 Subject: [PATCH 257/499] GCS_MAVLink: tidy sending of queued mount messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 3a6de81ba52231..c212c5021714af 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5837,30 +5837,25 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_local_position(); break; - case MSG_GIMBAL_DEVICE_ATTITUDE_STATUS: #if HAL_MOUNT_ENABLED + case MSG_GIMBAL_DEVICE_ATTITUDE_STATUS: CHECK_PAYLOAD_SIZE(GIMBAL_DEVICE_ATTITUDE_STATUS); send_gimbal_device_attitude_status(); -#endif break; case MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE: -#if HAL_MOUNT_ENABLED CHECK_PAYLOAD_SIZE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE); send_autopilot_state_for_gimbal_device(); -#endif break; case MSG_GIMBAL_MANAGER_INFORMATION: -#if HAL_MOUNT_ENABLED CHECK_PAYLOAD_SIZE(GIMBAL_MANAGER_INFORMATION); send_gimbal_manager_information(); -#endif break; case MSG_GIMBAL_MANAGER_STATUS: -#if HAL_MOUNT_ENABLED CHECK_PAYLOAD_SIZE(GIMBAL_MANAGER_STATUS); send_gimbal_manager_status(); -#endif break; +#endif // HAL_MOUNT_ENABLED + case MSG_OPTICAL_FLOW: #if AP_OPTICALFLOW_ENABLED CHECK_PAYLOAD_SIZE(OPTICAL_FLOW); From dbc0f02649385ca91142fa67003018479e3f37eb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:10:36 +1100 Subject: [PATCH 258/499] ArduCopter: tidy sending of queued mount messages --- ArduCopter/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 4f5c8cd9f03e8f..2fe9b2f56103b3 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -548,7 +548,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if AP_BATTERY_ENABLED MSG_BATTERY_STATUS, #endif +#if HAL_MOUNT_ENABLED MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, +#endif MSG_OPTICAL_FLOW, #if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, From 4f76a6ec65e5c30fbe21afd764825a4467694f75 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:10:36 +1100 Subject: [PATCH 259/499] ArduPlane: tidy sending of queued mount messages --- ArduPlane/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 196ce4e773b35b..99e45f31cca209 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -678,7 +678,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if AP_BATTERY_ENABLED MSG_BATTERY_STATUS, #endif +#if HAL_MOUNT_ENABLED MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, +#endif MSG_OPTICAL_FLOW, #if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, From e407c3aacc286852980c7e090c7079bd728d81ce Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:10:36 +1100 Subject: [PATCH 260/499] ArduSub: tidy sending of queued mount messages --- ArduSub/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 9e8d7322852a3f..c89a54e9fa6224 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -390,7 +390,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if AP_BATTERY_ENABLED MSG_BATTERY_STATUS, #endif +#if HAL_MOUNT_ENABLED MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, +#endif MSG_OPTICAL_FLOW, #if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, From c22a75537372566cff15212140e3302bef77751a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:10:36 +1100 Subject: [PATCH 261/499] Blimp: tidy sending of queued mount messages --- Blimp/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index a0bf1c4ba5fb97..a58d3a45eef9bb 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -357,7 +357,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if AP_BATTERY_ENABLED MSG_BATTERY_STATUS, #endif +#if HAL_MOUNT_ENABLED MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, +#endif MSG_OPTICAL_FLOW, #if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, From 7229664ecddb6249215daaac27f473372d6bf380 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:10:37 +1100 Subject: [PATCH 262/499] Rover: tidy sending of queued mount messages --- Rover/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 7e7cc4f320f172..2339b528bfb730 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -570,7 +570,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if AP_BATTERY_ENABLED MSG_BATTERY_STATUS, #endif +#if HAL_MOUNT_ENABLED MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, +#endif MSG_OPTICAL_FLOW, #if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, From 0983bd2d0688db85106030b9da48eaf36b0cda78 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:13:07 +1100 Subject: [PATCH 263/499] GCS_MAVLink: tidy sending of queued opticalflow messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index c212c5021714af..7946e3fbf3d2ca 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5856,12 +5856,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; #endif // HAL_MOUNT_ENABLED - case MSG_OPTICAL_FLOW: #if AP_OPTICALFLOW_ENABLED + case MSG_OPTICAL_FLOW: CHECK_PAYLOAD_SIZE(OPTICAL_FLOW); send_opticalflow(); -#endif break; +#endif case MSG_ATTITUDE_TARGET: CHECK_PAYLOAD_SIZE(ATTITUDE_TARGET); From a97d51c877bd1a138f254e1233fed184901fa737 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:13:07 +1100 Subject: [PATCH 264/499] ArduCopter: tidy sending of queued opticalflow messages --- ArduCopter/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 2fe9b2f56103b3..1ec613c88a0899 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -551,7 +551,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if HAL_MOUNT_ENABLED MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, #endif +#if AP_OPTICALFLOW_ENABLED MSG_OPTICAL_FLOW, +#endif #if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, From 803a56a6b41d091e4de79aa76002f3054512eb4e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:13:07 +1100 Subject: [PATCH 265/499] ArduPlane: tidy sending of queued opticalflow messages --- ArduPlane/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 99e45f31cca209..360e956d50d9e4 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -681,7 +681,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if HAL_MOUNT_ENABLED MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, #endif +#if AP_OPTICALFLOW_ENABLED MSG_OPTICAL_FLOW, +#endif #if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, From 51481a82841a3fdf53814b160aab3809661830fc Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:13:07 +1100 Subject: [PATCH 266/499] ArduSub: tidy sending of queued opticalflow messages --- ArduSub/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index c89a54e9fa6224..4facb62f8015d9 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -393,7 +393,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if HAL_MOUNT_ENABLED MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, #endif +#if AP_OPTICALFLOW_ENABLED MSG_OPTICAL_FLOW, +#endif #if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, From e9700c170961e8c7aaad92fdcefe0e0b894741ef Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:13:08 +1100 Subject: [PATCH 267/499] Blimp: tidy sending of queued opticalflow messages --- Blimp/GCS_Mavlink.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index a58d3a45eef9bb..81fa2d806fed41 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -2,6 +2,7 @@ #include "GCS_Mavlink.h" #include +#include MAV_TYPE GCS_Blimp::frame_type() const { @@ -360,7 +361,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if HAL_MOUNT_ENABLED MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, #endif +#if AP_OPTICALFLOW_ENABLED MSG_OPTICAL_FLOW, +#endif #if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, From 71c1886c74759614a318eaa14efd5e69bda09927 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:13:08 +1100 Subject: [PATCH 268/499] Rover: tidy sending of queued opticalflow messages --- Rover/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 2339b528bfb730..e82b1f9fa12fda 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -573,7 +573,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if HAL_MOUNT_ENABLED MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, #endif +#if AP_OPTICALFLOW_ENABLED MSG_OPTICAL_FLOW, +#endif #if COMPASS_CAL_ENABLED MSG_MAG_CAL_REPORT, MSG_MAG_CAL_PROGRESS, From ec6986710255f444b3b48400eab0b36f6d5c2597 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:16:35 +1100 Subject: [PATCH 269/499] GCS_MAVLink: tidy sending of queued mcu status messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 7946e3fbf3d2ca..9e1c460952258e 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5883,12 +5883,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_power_status(); break; - case MSG_MCU_STATUS: #if HAL_WITH_MCU_MONITORING + case MSG_MCU_STATUS: CHECK_PAYLOAD_SIZE(MCU_STATUS); send_mcu_status(); -#endif break; +#endif case MSG_RC_CHANNELS: CHECK_PAYLOAD_SIZE(RC_CHANNELS); From 962584811d901674bdb7da4f9c50e9a3f1ec4e10 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:16:35 +1100 Subject: [PATCH 270/499] AntennaTracker: tidy sending of queued mcu status messages --- AntennaTracker/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 590b40e0acd931..06f97b797a1769 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -274,7 +274,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, MSG_POWER_STATUS, +#if HAL_WITH_MCU_MONITORING MSG_MCU_STATUS, +#endif MSG_MEMINFO, MSG_NAV_CONTROLLER_OUTPUT, MSG_GPS_RAW, From 88a862f1280a0fea3bb1f66cddde975c1ac38a40 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:16:35 +1100 Subject: [PATCH 271/499] ArduCopter: tidy sending of queued mcu status messages --- ArduCopter/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 1ec613c88a0899..3b7d2361967bf2 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -503,7 +503,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, MSG_POWER_STATUS, +#if HAL_WITH_MCU_MONITORING MSG_MCU_STATUS, +#endif MSG_MEMINFO, MSG_CURRENT_WAYPOINT, // MISSION_CURRENT MSG_GPS_RAW, From e1e1fae604112427613a89861df30fac08f134de Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:16:35 +1100 Subject: [PATCH 272/499] ArduPlane: tidy sending of queued mcu status messages --- ArduPlane/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 360e956d50d9e4..6f532a066b74df 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -618,7 +618,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, MSG_POWER_STATUS, +#if HAL_WITH_MCU_MONITORING MSG_MCU_STATUS, +#endif MSG_MEMINFO, MSG_CURRENT_WAYPOINT, MSG_GPS_RAW, From 964e0b91345ba2eb6310bb5471b33b7109e009f5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:16:35 +1100 Subject: [PATCH 273/499] ArduSub: tidy sending of queued mcu status messages --- ArduSub/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 4facb62f8015d9..0315d75ba2e9ea 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -346,7 +346,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, MSG_POWER_STATUS, +#if HAL_WITH_MCU_MONITORING MSG_MCU_STATUS, +#endif MSG_MEMINFO, MSG_CURRENT_WAYPOINT, MSG_GPS_RAW, From 294e04cffa4eabdee36c94241d134e2f47af387e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:16:35 +1100 Subject: [PATCH 274/499] Blimp: tidy sending of queued mcu status messages --- Blimp/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index 81fa2d806fed41..50f14bf90087a3 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -316,7 +316,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, MSG_POWER_STATUS, +#if HAL_WITH_MCU_MONITORING MSG_MCU_STATUS, +#endif MSG_MEMINFO, MSG_CURRENT_WAYPOINT, // MISSION_CURRENT MSG_GPS_RAW, From 0fe9030b4267d3e309298578877e77068796e00c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:16:35 +1100 Subject: [PATCH 275/499] Rover: tidy sending of queued mcu status messages --- Rover/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index e82b1f9fa12fda..a144042ea078cd 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -525,7 +525,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, MSG_POWER_STATUS, +#if HAL_WITH_MCU_MONITORING MSG_MCU_STATUS, +#endif MSG_MEMINFO, MSG_CURRENT_WAYPOINT, MSG_GPS_RAW, From d894281f2bb85f6fca135402847ae23a663139f0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:16:40 +1100 Subject: [PATCH 276/499] GCS_MAVLink: tidy sending of queued SIM messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 9e1c460952258e..eef2a3e4a20eb5 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5940,19 +5940,17 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_servo_output_raw(); break; - case MSG_SIMSTATE: #if AP_SIM_ENABLED + case MSG_SIMSTATE: CHECK_PAYLOAD_SIZE(SIMSTATE); send_simstate(); -#endif break; case MSG_SIM_STATE: -#if AP_SIM_ENABLED CHECK_PAYLOAD_SIZE(SIM_STATE); send_sim_state(); -#endif break; +#endif case MSG_SYS_STATUS: CHECK_PAYLOAD_SIZE(SYS_STATUS); From a95b2b2497e7a8b9ed57ad93fdd13c814fcf6a87 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:21:49 +1100 Subject: [PATCH 277/499] GCS_MAVLink: tidy sending of queued generator messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index eef2a3e4a20eb5..58f63441570629 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5992,12 +5992,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_vibration(); break; - case MSG_GENERATOR_STATUS: #if HAL_GENERATOR_ENABLED + case MSG_GENERATOR_STATUS: CHECK_PAYLOAD_SIZE(GENERATOR_STATUS); send_generator_status(); -#endif break; +#endif case MSG_AUTOPILOT_VERSION: CHECK_PAYLOAD_SIZE(AUTOPILOT_VERSION); From 256f373d7f490701113f5de1461cb3cc036dd13c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:21:49 +1100 Subject: [PATCH 278/499] ArduCopter: tidy sending of queued generator messages --- ArduCopter/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 3b7d2361967bf2..23c4a27fe86025 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -566,7 +566,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_RPM, #endif MSG_ESC_TELEMETRY, +#if HAL_GENERATOR_ENABLED MSG_GENERATOR_STATUS, +#endif MSG_WINCH_STATUS, #if HAL_EFI_ENABLED MSG_EFI_STATUS, From 3af77ea470c97f58c0d99fef71f04fe36369a82a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:21:49 +1100 Subject: [PATCH 279/499] Blimp: tidy sending of queued generator messages --- Blimp/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index 50f14bf90087a3..90feab831dfd7a 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -376,7 +376,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_RPM, #endif MSG_ESC_TELEMETRY, +#if HAL_GENERATOR_ENABLED MSG_GENERATOR_STATUS, +#endif }; static const ap_message STREAM_PARAMS_msgs[] = { MSG_NEXT_PARAM From 892bafe95182a531dc9a0d31e25c6bfc9b6bab79 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:24:38 +1100 Subject: [PATCH 280/499] GCS_MAVLink: tidy sending of esc telem generator messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 58f63441570629..40d1e19cd6db80 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -6004,11 +6004,11 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_autopilot_version(); break; - case MSG_ESC_TELEMETRY: #if HAL_WITH_ESC_TELEM + case MSG_ESC_TELEMETRY: AP::esc_telem().send_esc_telemetry_mavlink(uint8_t(chan)); -#endif break; +#endif case MSG_EFI_STATUS: { #if HAL_EFI_ENABLED From 621e245b103342d2e7ef38bf72e35c7e92da1a6c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:24:38 +1100 Subject: [PATCH 281/499] ArduCopter: tidy sending of esc telem generator messages --- ArduCopter/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 23c4a27fe86025..e3cd717a492ab1 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -565,7 +565,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if AP_RPM_ENABLED MSG_RPM, #endif +#if HAL_WITH_ESC_TELEM MSG_ESC_TELEMETRY, +#endif #if HAL_GENERATOR_ENABLED MSG_GENERATOR_STATUS, #endif From ec5fa8bd62d106c8b76a9522ba392db0355e56d0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:24:38 +1100 Subject: [PATCH 282/499] ArduPlane: tidy sending of esc telem generator messages --- ArduPlane/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 6f532a066b74df..84c00518cecc4c 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -657,7 +657,9 @@ static const ap_message STREAM_EXTRA1_msgs[] = { MSG_AOA_SSA, MSG_PID_TUNING, MSG_LANDING, +#if HAL_WITH_ESC_TELEM MSG_ESC_TELEMETRY, +#endif #if HAL_EFI_ENABLED MSG_EFI_STATUS, #endif From a0f4863dad118989dd5ebe6e04d61fc05be0462c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:24:38 +1100 Subject: [PATCH 283/499] ArduSub: tidy sending of esc telem generator messages --- ArduSub/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 0315d75ba2e9ea..149507e1beb76a 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -407,7 +407,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if AP_RPM_ENABLED MSG_RPM, #endif +#if HAL_WITH_ESC_TELEM MSG_ESC_TELEMETRY, +#endif }; static const ap_message STREAM_PARAMS_msgs[] = { MSG_NEXT_PARAM From c79e9eb039015c236d5bf1f360008e65a033179b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:24:38 +1100 Subject: [PATCH 284/499] Blimp: tidy sending of esc telem generator messages --- Blimp/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index 90feab831dfd7a..dd516e3e92163c 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -375,7 +375,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if AP_RPM_ENABLED MSG_RPM, #endif +#if HAL_WITH_ESC_TELEM MSG_ESC_TELEMETRY, +#endif #if HAL_GENERATOR_ENABLED MSG_GENERATOR_STATUS, #endif From cfb78a43ecc1adc251d10f8cddd17c2fb8cb30a4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:24:38 +1100 Subject: [PATCH 285/499] Rover: tidy sending of esc telem generator messages --- Rover/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index a144042ea078cd..f47cecfb283a25 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -588,7 +588,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_RPM, #endif MSG_WHEEL_DISTANCE, +#if HAL_WITH_ESC_TELEM MSG_ESC_TELEMETRY, +#endif #if HAL_EFI_ENABLED MSG_EFI_STATUS, #endif From 564e6ec77a362f3fa32fd680e31a83ebaaab7fc0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:24:43 +1100 Subject: [PATCH 286/499] GCS_MAVLink: tidy sending of efi messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 40d1e19cd6db80..06a3c0fdb9d4fa 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -6010,16 +6010,16 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; #endif - case MSG_EFI_STATUS: { #if HAL_EFI_ENABLED + case MSG_EFI_STATUS: { CHECK_PAYLOAD_SIZE(EFI_STATUS); AP_EFI *efi = AP::EFI(); if (efi) { efi->send_mavlink_status(chan); } -#endif break; } +#endif case MSG_WINCH_STATUS: CHECK_PAYLOAD_SIZE(WINCH_STATUS); From a8906ac491914a70987874b61cd3161a224675b3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:26:20 +1100 Subject: [PATCH 287/499] GCS_MAVLink: tidy sending of winch messages --- libraries/GCS_MAVLink/GCS.h | 3 +++ libraries/GCS_MAVLink/GCS_Common.cpp | 2 ++ 2 files changed, 5 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index e512ed7312e691..f12853064f8412 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -24,6 +24,7 @@ #include #include #include +#include #include "ap_message.h" @@ -385,7 +386,9 @@ class GCS_MAVLINK void send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc); void send_rpm() const; void send_generator_status() const; +#if AP_WINCH_ENABLED virtual void send_winch_status() const {}; +#endif void send_water_depth() const; int8_t battery_remaining_pct(const uint8_t instance) const; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 06a3c0fdb9d4fa..0d22beaa91fb26 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -6021,10 +6021,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) } #endif +#if AP_WINCH_ENABLED case MSG_WINCH_STATUS: CHECK_PAYLOAD_SIZE(WINCH_STATUS); send_winch_status(); break; +#endif case MSG_WATER_DEPTH: #if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover) From 10591837585871413b40303098ea84629aa226aa Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:26:20 +1100 Subject: [PATCH 288/499] ArduCopter: tidy sending of winch messages --- ArduCopter/GCS_Mavlink.cpp | 4 ++-- ArduCopter/GCS_Mavlink.h | 2 ++ 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index e3cd717a492ab1..62fd79b97e6701 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -311,17 +311,17 @@ void GCS_MAVLINK_Copter::send_pid_tuning() } } +#if AP_WINCH_ENABLED // send winch status message void GCS_MAVLINK_Copter::send_winch_status() const { -#if AP_WINCH_ENABLED AP_Winch *winch = AP::winch(); if (winch == nullptr) { return; } winch->send_status(*this); -#endif } +#endif uint8_t GCS_MAVLINK_Copter::sysid_my_gcs() const { diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 7470434f4339da..d042d3000ebe06 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -83,7 +83,9 @@ class GCS_MAVLINK_Copter : public GCS_MAVLINK void send_pid_tuning() override; +#if AP_WINCH_ENABLED void send_winch_status() const override; +#endif void send_wind() const; From 031e5b1dabdc2b6cd3ebaf598f9370fbb2a0b1c1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:28:08 +1100 Subject: [PATCH 289/499] GCS_MAVLink: tidy sending of WATER_DEPTH messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 0d22beaa91fb26..9956d533703a76 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1045,7 +1045,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c #if HAL_WITH_ESC_TELEM { MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, MSG_ESC_TELEMETRY}, #endif -#if APM_BUILD_TYPE(APM_BUILD_Rover) +#if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover) { MAVLINK_MSG_ID_WATER_DEPTH, MSG_WATER_DEPTH}, #endif #if HAL_HIGH_LATENCY2_ENABLED @@ -6028,12 +6028,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; #endif - case MSG_WATER_DEPTH: #if AP_RANGEFINDER_ENABLED && APM_BUILD_TYPE(APM_BUILD_Rover) + case MSG_WATER_DEPTH: CHECK_PAYLOAD_SIZE(WATER_DEPTH); send_water_depth(); -#endif break; +#endif case MSG_HIGH_LATENCY2: #if HAL_HIGH_LATENCY2_ENABLED From 84afe993d777182fe1df87e001a3de8cc1e6e308 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:28:08 +1100 Subject: [PATCH 290/499] Rover: tidy sending of WATER_DEPTH messages --- Rover/Log.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Rover/Log.cpp b/Rover/Log.cpp index c8c18d8ee9ec1e..36403f66d253ed 100644 --- a/Rover/Log.cpp +++ b/Rover/Log.cpp @@ -78,8 +78,10 @@ void Rover::Log_Write_Depth() (double)(s->distance()), temp_C); } +#if AP_RANGEFINDER_ENABLED // send water depth and temp to ground station gcs().send_message(MSG_WATER_DEPTH); +#endif } // guided mode logging From 6f5ff2f952baa67afe07677943f93f3e70202af7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:31:32 +1100 Subject: [PATCH 291/499] GCS_MAVLink: tidy sending of HIGH_LATENCY2 messages --- libraries/GCS_MAVLink/GCS.h | 2 ++ libraries/GCS_MAVLink/GCS_Common.cpp | 17 ++++++++++++++--- 2 files changed, 16 insertions(+), 3 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index f12853064f8412..d21668184cca8c 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -814,7 +814,9 @@ class GCS_MAVLINK } deferred_message[3] = { { MSG_HEARTBEAT, }, { MSG_NEXT_PARAM, }, +#if HAL_HIGH_LATENCY2_ENABLED { MSG_HIGH_LATENCY2, }, +#endif }; // returns index of id in deferred_message[] or -1 if not present int8_t get_deferred_message_index(const ap_message id) const; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 9956d533703a76..6f127a8c19782e 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1089,7 +1089,9 @@ bool GCS_MAVLINK::should_send_message_in_delay_callback(const ap_message id) con switch (id) { case MSG_NEXT_PARAM: case MSG_HEARTBEAT: +#if HAL_HIGH_LATENCY2_ENABLED case MSG_HIGH_LATENCY2: +#endif case MSG_AUTOPILOT_VERSION: return true; default: @@ -1676,7 +1678,11 @@ bool GCS_MAVLINK::set_ap_message_interval(enum ap_message id, uint16_t interval_ // mavlink work!) void GCS_MAVLINK::send_message(enum ap_message id) { - if (id == MSG_HEARTBEAT || id == MSG_HIGH_LATENCY2) { + switch (id) { + case MSG_HEARTBEAT: +#if HAL_HIGH_LATENCY2_ENABLED + case MSG_HIGH_LATENCY2: +#endif save_signing_timestamp(false); // update the mask of all streaming channels if (is_streaming()) { @@ -1684,6 +1690,9 @@ void GCS_MAVLINK::send_message(enum ap_message id) } else { GCS_MAVLINK::chan_is_streaming &= ~(1U<<(chan-MAVLINK_COMM_0)); } + break; + default: + break; } pushed_ap_message_ids.set(id); @@ -6035,12 +6044,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) break; #endif - case MSG_HIGH_LATENCY2: #if HAL_HIGH_LATENCY2_ENABLED + case MSG_HIGH_LATENCY2: CHECK_PAYLOAD_SIZE(HIGH_LATENCY2); send_high_latency2(); -#endif // HAL_HIGH_LATENCY2_ENABLED break; +#endif // HAL_HIGH_LATENCY2_ENABLED #if AP_AIS_ENABLED case MSG_AIS_VESSEL: { @@ -6311,11 +6320,13 @@ bool GCS_MAVLINK::get_default_interval_for_ap_message(const ap_message id, uint1 return true; } +#if HAL_HIGH_LATENCY2_ENABLED if (id == MSG_HIGH_LATENCY2) { // handle HL2 requests as a special case because HL2 is not "streamed" interval = 5000; return true; } +#endif #if HAL_MAVLINK_INTERVALS_FROM_FILES_ENABLED // a user can specify default rates in files, which are read close From 70160c58e82142754cbf023041e0a818107fb567 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:32:33 +1100 Subject: [PATCH 292/499] GCS_MAVLink: tidy sending of ADSB messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 6f127a8c19782e..37cc3c6a3f2bf1 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -6061,12 +6061,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) } #endif - case MSG_UAVIONIX_ADSB_OUT_STATUS: #if HAL_ADSB_ENABLED + case MSG_UAVIONIX_ADSB_OUT_STATUS: CHECK_PAYLOAD_SIZE(UAVIONIX_ADSB_OUT_STATUS); send_uavionix_adsb_out_status(); -#endif break; +#endif #if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED case MSG_RELAY_STATUS: From 170d96e8cc8af767aa6a509517f4846469be689a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Oct 2023 18:55:50 +1100 Subject: [PATCH 293/499] GCS_Common: remove mappings for non-supported messages --- libraries/GCS_MAVLink/GCS_Common.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 37cc3c6a3f2bf1..a94b569ebc9c86 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -967,11 +967,13 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_SCALED_PRESSURE, MSG_SCALED_PRESSURE}, { MAVLINK_MSG_ID_SCALED_PRESSURE2, MSG_SCALED_PRESSURE2}, { MAVLINK_MSG_ID_SCALED_PRESSURE3, MSG_SCALED_PRESSURE3}, +#if AP_GPS_ENABLED { MAVLINK_MSG_ID_GPS_RAW_INT, MSG_GPS_RAW}, { MAVLINK_MSG_ID_GPS_RTK, MSG_GPS_RTK}, #if GPS_MAX_RECEIVERS > 1 { MAVLINK_MSG_ID_GPS2_RAW, MSG_GPS2_RAW}, { MAVLINK_MSG_ID_GPS2_RTK, MSG_GPS2_RTK}, +#endif #endif { MAVLINK_MSG_ID_SYSTEM_TIME, MSG_SYSTEM_TIME}, { MAVLINK_MSG_ID_RC_CHANNELS_SCALED, MSG_SERVO_OUT}, @@ -987,7 +989,9 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_AHRS2, MSG_AHRS2}, { MAVLINK_MSG_ID_HWSTATUS, MSG_HWSTATUS}, { MAVLINK_MSG_ID_WIND, MSG_WIND}, +#if AP_RANGEFINDER_ENABLED { MAVLINK_MSG_ID_RANGEFINDER, MSG_RANGEFINDER}, +#endif { MAVLINK_MSG_ID_DISTANCE_SENSOR, MSG_DISTANCE_SENSOR}, // request also does report: { MAVLINK_MSG_ID_TERRAIN_REQUEST, MSG_TERRAIN}, @@ -1025,8 +1029,12 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c { MAVLINK_MSG_ID_ATTITUDE_TARGET, MSG_ATTITUDE_TARGET}, { MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, MSG_POSITION_TARGET_GLOBAL_INT}, { MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, MSG_POSITION_TARGET_LOCAL_NED}, +#if HAL_ADSB_ENABLED { MAVLINK_MSG_ID_ADSB_VEHICLE, MSG_ADSB_VEHICLE}, +#endif +#if AP_BATTERY_ENABLED { MAVLINK_MSG_ID_BATTERY_STATUS, MSG_BATTERY_STATUS}, +#endif { MAVLINK_MSG_ID_AOA_SSA, MSG_AOA_SSA}, #if HAL_LANDING_DEEPSTALL_ENABLED { MAVLINK_MSG_ID_DEEPSTALL, MSG_LANDING}, From 261bc4f884eeda9b62bf408b49c5368814ae24c8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 19 Nov 2023 11:38:46 +1100 Subject: [PATCH 294/499] AntennaTracker: stop streaming trying SIM_STATE messages outside sim --- AntennaTracker/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 06f97b797a1769..0fbe19edaa8ca8 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -303,7 +303,9 @@ static const ap_message STREAM_EXTRA1_msgs[] = { }; static const ap_message STREAM_EXTRA3_msgs[] = { MSG_AHRS, +#if AP_SIM_ENABLED MSG_SIMSTATE, +#endif MSG_SYSTEM_TIME, MSG_AHRS2, #if COMPASS_CAL_ENABLED From c531d81cb31b62959e8ceeb055be462a4565bf37 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 19 Nov 2023 11:38:46 +1100 Subject: [PATCH 295/499] ArduCopter: stop streaming trying SIM_STATE messages outside sim --- ArduCopter/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 62fd79b97e6701..139e6d64cd7660 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -531,7 +531,9 @@ static const ap_message STREAM_RC_CHANNELS_msgs[] = { }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, +#if AP_SIM_ENABLED MSG_SIMSTATE, +#endif MSG_AHRS2, MSG_PID_TUNING // Up to four PID_TUNING messages are sent, depending on GCS_PID_MASK parameter }; From ba8e770a818b3dd42d5e55f9119e6ca70035fdfc Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 19 Nov 2023 11:38:46 +1100 Subject: [PATCH 296/499] ArduPlane: stop streaming trying SIM_STATE messages outside sim --- ArduPlane/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 84c00518cecc4c..9427b99e0cdac9 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -649,7 +649,9 @@ static const ap_message STREAM_RC_CHANNELS_msgs[] = { }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, +#if AP_SIM_ENABLED MSG_SIMSTATE, +#endif MSG_AHRS2, #if AP_RPM_ENABLED MSG_RPM, From a966e4232bbb271463b5a0484b17478452d113fa Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 19 Nov 2023 11:38:47 +1100 Subject: [PATCH 297/499] ArduSub: stop streaming trying SIM_STATE messages outside sim --- ArduSub/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 149507e1beb76a..78a3e288b9466b 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -374,7 +374,9 @@ static const ap_message STREAM_RC_CHANNELS_msgs[] = { }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, +#if AP_SIM_ENABLED MSG_SIMSTATE, +#endif MSG_AHRS2, MSG_PID_TUNING }; From a13353f740b012ce609e28749312f5fff24de636 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 19 Nov 2023 11:38:47 +1100 Subject: [PATCH 298/499] Blimp: stop streaming trying SIM_STATE messages outside sim --- Blimp/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index dd516e3e92163c..8eaf6473dd9738 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -344,7 +344,9 @@ static const ap_message STREAM_RC_CHANNELS_msgs[] = { }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, +#if AP_SIM_ENABLED MSG_SIMSTATE, +#endif MSG_AHRS2, MSG_PID_TUNING // Up to four PID_TUNING messages are sent, depending on GCS_PID_MASK parameter }; From fc834caf384f84662b356c95a34cb71722f8d512 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 19 Nov 2023 11:38:47 +1100 Subject: [PATCH 299/499] Rover: stop streaming trying SIM_STATE messages outside sim --- Rover/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index f47cecfb283a25..e13e35bebc255c 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -556,7 +556,9 @@ static const ap_message STREAM_RC_CHANNELS_msgs[] = { }; static const ap_message STREAM_EXTRA1_msgs[] = { MSG_ATTITUDE, +#if AP_SIM_ENABLED MSG_SIMSTATE, +#endif MSG_AHRS2, MSG_PID_TUNING, }; From 36a66424e1d6a1d7aac69c90d1613bd109a0abbd Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Mon, 20 Nov 2023 11:39:53 -0600 Subject: [PATCH 300/499] AP_BattMonitor:remove unused param from analog fuel level --- .../AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp | 8 +------- .../AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h | 1 - 2 files changed, 1 insertion(+), 8 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp index 9739068b9179f0..f1dfead2bba7bf 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.cpp @@ -58,13 +58,7 @@ const AP_Param::GroupInfo AP_BattMonitor_FuelLevel_Analog::var_info[] = { // @Values: -1:Not Used,11:Pixracer,13:Pixhawk ADC4,14:Pixhawk ADC3,15:Pixhawk ADC6/Pixhawk2 ADC,103:Pixhawk SBUS AP_GROUPINFO("FL_PIN", 43, AP_BattMonitor_FuelLevel_Analog, _pin, -1), - // @Param: FL_VLT_MAX - // @DisplayName: Full fuel level voltage - // @Description: The voltage seen on the analog pin when the fuel tank is full. - // @Range: 0 10 - // @Units: V - // @User: Advanced - AP_GROUPINFO("FL_VLT_MAX", 44, AP_BattMonitor_FuelLevel_Analog, _fuel_level_max_voltage, -1), + // index 44 unused and available // @Param: FL_FF // @DisplayName: First order term diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h index 58b35002b2897e..5f3e0530c40cb8 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_FuelLevel_Analog.h @@ -48,7 +48,6 @@ class AP_BattMonitor_FuelLevel_Analog : public AP_BattMonitor_Backend private: AP_Float _fuel_level_empty_voltage; - AP_Float _fuel_level_max_voltage; AP_Float _fuel_level_voltage_mult; AP_Float _fuel_level_filter_frequency; AP_Int8 _pin; From f9c9a093277015f6e0010cc5a4e133ee2210b53d Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 19 Nov 2023 07:47:27 -0600 Subject: [PATCH 301/499] AP_MSP: update option metadata for clarity --- libraries/AP_MSP/AP_MSP.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_MSP/AP_MSP.cpp b/libraries/AP_MSP/AP_MSP.cpp index 971d446860fa11..9f41ed928afbbe 100644 --- a/libraries/AP_MSP/AP_MSP.cpp +++ b/libraries/AP_MSP/AP_MSP.cpp @@ -44,8 +44,8 @@ const AP_Param::GroupInfo AP_MSP::var_info[] = { // @Param: _OPTIONS // @DisplayName: MSP OSD Options - // @Description: A bitmask to set some MSP specific options - // @Bitmask: 0:EnableTelemetryMode, 1: DisableDJIWorkarounds, 2:EnableBTFLFonts + // @Description: A bitmask to set some MSP specific options: EnableTelemetryMode-allows "push" mode telemetry when only rx line of OSD ic connected to autopilot, EnableBTFLFonts-uses indexes corresponding to Betaflight fonts if OSD uses those instead of ArduPilot fonts. + // @Bitmask: 0:EnableTelemetryMode, 1: unused, 2:EnableBTFLFonts // @User: Standard AP_GROUPINFO("_OPTIONS", 2, AP_MSP, _options, 0), From 6d172a1b222e84ee6c21e253a27b4a001aac3133 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 16 Nov 2023 13:12:21 +1100 Subject: [PATCH 302/499] GCS_MAVLink: exclude deadlock-creation based on FAILURE_CREATION_ENABLED --- libraries/GCS_MAVLink/GCS.h | 2 ++ libraries/GCS_MAVLink/GCS_Common.cpp | 22 ++++++++++++---------- 2 files changed, 14 insertions(+), 10 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index d21668184cca8c..867ec889031087 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -581,11 +581,13 @@ class GCS_MAVLINK void handle_set_gps_global_origin(const mavlink_message_t &msg); void handle_setup_signing(const mavlink_message_t &msg) const; virtual MAV_RESULT handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg); +#if AP_MAVLINK_FAILURE_CREATION_ENABLED struct { HAL_Semaphore sem; bool taken; } _deadlock_sem; void deadlock_sem(void); +#endif // reset a message interval via mavlink: MAV_RESULT handle_command_set_message_interval(const mavlink_command_int_t &packet); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a94b569ebc9c86..f501f7d4657d50 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3203,6 +3203,16 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &pac INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); return MAV_RESULT_ACCEPTED; } + if (is_equal(packet.param4, 100.0f)) { + send_text(MAV_SEVERITY_WARNING,"Creating mutex deadlock"); + hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&GCS_MAVLINK::deadlock_sem, void)); + while (!_deadlock_sem.taken) { + hal.scheduler->delay(1); + } + WITH_SEMAPHORE(_deadlock_sem.sem); + send_text(MAV_SEVERITY_WARNING,"deadlock passed"); + return MAV_RESULT_ACCEPTED; + } #endif // AP_MAVLINK_FAILURE_CREATION_ENABLED #if HAL_ENABLE_DFU_BOOT @@ -3217,16 +3227,6 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &pac #endif } #endif - if (is_equal(packet.param4, 100.0f)) { - send_text(MAV_SEVERITY_WARNING,"Creating mutex deadlock"); - hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&GCS_MAVLINK::deadlock_sem, void)); - while (!_deadlock_sem.taken) { - hal.scheduler->delay(1); - } - WITH_SEMAPHORE(_deadlock_sem.sem); - send_text(MAV_SEVERITY_WARNING,"deadlock passed"); - return MAV_RESULT_ACCEPTED; - } } // refuse reboot when armed: @@ -3270,6 +3270,7 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &pac return MAV_RESULT_FAILED; } +#if AP_MAVLINK_FAILURE_CREATION_ENABLED /* take a semaphore and do not release it, triggering a deadlock */ @@ -3280,6 +3281,7 @@ void GCS_MAVLINK::deadlock_sem(void) _deadlock_sem.sem.take_blocking(); } } +#endif /* handle a flight termination request From 0d735ffb015cd4fcb3c1b0f3d645237b178379a6 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Mon, 20 Nov 2023 15:49:42 +0000 Subject: [PATCH 303/499] AP_DDS: increase the timeout when creating participants and entities Signed-off-by: Rhys Mainwaring --- libraries/AP_DDS/AP_DDS_Client.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 100f51de2fe3cd..43dd37f7887094 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -733,7 +733,7 @@ bool AP_DDS_Client::create() constexpr uint8_t nRequestsParticipant = 1; const uint16_t requestsParticipant[nRequestsParticipant] = {participant_req_id}; - constexpr uint8_t maxTimeMsPerRequestMs = 250; + constexpr uint16_t maxTimeMsPerRequestMs = 500; constexpr uint16_t requestTimeoutParticipantMs = (uint16_t) nRequestsParticipant * maxTimeMsPerRequestMs; uint8_t statusParticipant[nRequestsParticipant]; if (!uxr_run_session_until_all_status(&session, requestTimeoutParticipantMs, requestsParticipant, statusParticipant, nRequestsParticipant)) { From b8d50b112a66ef14e1b493baccd61e27f85104cf Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sat, 28 Oct 2023 12:58:32 -0500 Subject: [PATCH 304/499] AP_Compass: fix C++ One Definition Rule violations Two structs with the same name must have exactly the same definition, no matter where they occur in the program, otherwise the program is undefined. Move each sample register struct definition into the associated class definition so they are in a different namespace and no longer identically named, thus fixing this issue. --- libraries/AP_Compass/AP_Compass_AK09916.cpp | 9 +-------- libraries/AP_Compass/AP_Compass_AK09916.h | 8 ++++++++ libraries/AP_Compass/AP_Compass_AK8963.cpp | 7 +------ libraries/AP_Compass/AP_Compass_AK8963.h | 6 ++++++ libraries/AP_Compass/AP_Compass_LSM9DS1.cpp | 5 ----- libraries/AP_Compass/AP_Compass_LSM9DS1.h | 5 +++++ 6 files changed, 21 insertions(+), 19 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_AK09916.cpp b/libraries/AP_Compass/AP_Compass_AK09916.cpp index bb6732365a25db..8630da5e9747b2 100644 --- a/libraries/AP_Compass/AP_Compass_AK09916.cpp +++ b/libraries/AP_Compass/AP_Compass_AK09916.cpp @@ -58,13 +58,6 @@ extern const AP_HAL::HAL &hal; extern const AP_HAL::HAL &hal; -struct PACKED sample_regs { - uint8_t st1; - int16_t val[3]; - uint8_t tmps; - uint8_t st2; -}; - AP_Compass_AK09916::AP_Compass_AK09916(AP_AK09916_BusDriver *bus, bool force_external, enum Rotation rotation) @@ -477,7 +470,7 @@ bool AP_AK09916_BusDriver_Auxiliary::configure() bool AP_AK09916_BusDriver_Auxiliary::start_measurements() { - if (_bus->register_periodic_read(_slave, REG_ST1, sizeof(sample_regs)) < 0) { + if (_bus->register_periodic_read(_slave, REG_ST1, sizeof(AP_Compass_AK09916::sample_regs)) < 0) { return false; } diff --git a/libraries/AP_Compass/AP_Compass_AK09916.h b/libraries/AP_Compass/AP_Compass_AK09916.h index b4cca6e97346ea..5c80cff9ef6755 100644 --- a/libraries/AP_Compass/AP_Compass_AK09916.h +++ b/libraries/AP_Compass/AP_Compass_AK09916.h @@ -75,6 +75,14 @@ class AP_Compass_AK09916 : public AP_Compass_Backend void read() override; + /* Must be public so the BusDriver can access its definition */ + struct PACKED sample_regs { + uint8_t st1; + int16_t val[3]; + uint8_t tmps; + uint8_t st2; + }; + private: AP_Compass_AK09916(AP_AK09916_BusDriver *bus, bool force_external, enum Rotation rotation); diff --git a/libraries/AP_Compass/AP_Compass_AK8963.cpp b/libraries/AP_Compass/AP_Compass_AK8963.cpp index 4c4ced9e3f5c85..ad6a8c6d234efd 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.cpp +++ b/libraries/AP_Compass/AP_Compass_AK8963.cpp @@ -49,11 +49,6 @@ #define AK8963_MILLIGAUSS_SCALE 10.0f -struct PACKED sample_regs { - int16_t val[3]; - uint8_t st2; -}; - extern const AP_HAL::HAL &hal; AP_Compass_AK8963::AP_Compass_AK8963(AP_AK8963_BusDriver *bus, @@ -379,7 +374,7 @@ bool AP_AK8963_BusDriver_Auxiliary::configure() bool AP_AK8963_BusDriver_Auxiliary::start_measurements() { - if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(sample_regs)) < 0) { + if (_bus->register_periodic_read(_slave, AK8963_HXL, sizeof(AP_Compass_AK8963::sample_regs)) < 0) { return false; } diff --git a/libraries/AP_Compass/AP_Compass_AK8963.h b/libraries/AP_Compass/AP_Compass_AK8963.h index 7b61768d84225c..c0f020756571a3 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.h +++ b/libraries/AP_Compass/AP_Compass_AK8963.h @@ -39,6 +39,12 @@ class AP_Compass_AK8963 : public AP_Compass_Backend void read() override; + /* Must be public so the BusDriver can access its definition */ + struct PACKED sample_regs { + int16_t val[3]; + uint8_t st2; + }; + private: AP_Compass_AK8963(AP_AK8963_BusDriver *bus, enum Rotation rotation); diff --git a/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp b/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp index eeebe00fdca5c5..60db0f54de6226 100644 --- a/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp +++ b/libraries/AP_Compass/AP_Compass_LSM9DS1.cpp @@ -47,11 +47,6 @@ #define LSM9DS1M_INT_THS_L_M 0x32 #define LSM9DS1M_INT_THS_H_M 0x33 -struct PACKED sample_regs { - uint8_t status; - int16_t val[3]; -}; - extern const AP_HAL::HAL &hal; AP_Compass_LSM9DS1::AP_Compass_LSM9DS1(AP_HAL::OwnPtr dev, diff --git a/libraries/AP_Compass/AP_Compass_LSM9DS1.h b/libraries/AP_Compass/AP_Compass_LSM9DS1.h index 2cb91c74c6de4c..7017883bd62ad5 100644 --- a/libraries/AP_Compass/AP_Compass_LSM9DS1.h +++ b/libraries/AP_Compass/AP_Compass_LSM9DS1.h @@ -42,6 +42,11 @@ class AP_Compass_LSM9DS1 : public AP_Compass_Backend uint8_t _compass_instance; float _scaling; enum Rotation _rotation; + + struct PACKED sample_regs { + uint8_t status; + int16_t val[3]; + }; }; #endif From b83fc1575936b95363bcda4d0c4946a86a864c6c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 10:14:35 +1100 Subject: [PATCH 305/499] Tools: tidy MSG_MCU_STATUS defines --- Tools/AP_Periph/GCS_MAVLink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/AP_Periph/GCS_MAVLink.cpp b/Tools/AP_Periph/GCS_MAVLink.cpp index 55020876783077..cb454786ac8dde 100644 --- a/Tools/AP_Periph/GCS_MAVLink.cpp +++ b/Tools/AP_Periph/GCS_MAVLink.cpp @@ -28,7 +28,9 @@ static const ap_message STREAM_RAW_SENSORS_msgs[] = { static const ap_message STREAM_EXTENDED_STATUS_msgs[] = { MSG_SYS_STATUS, MSG_POWER_STATUS, +#if HAL_WITH_MCU_MONITORING MSG_MCU_STATUS, +#endif MSG_MEMINFO, MSG_GPS_RAW, MSG_GPS_RTK, From 232edac8d7870b2433afdbd5ba5d2ce877056009 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 10:36:58 +1100 Subject: [PATCH 306/499] AP_ADSB: create and use AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED narrower define we can use when not compiling in the backends which use this --- libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp b/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp index ad7bb48ca8c12a..e23ee23499d509 100644 --- a/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp +++ b/libraries/AP_ADSB/AP_ADSB_uAvionix_UCP.cpp @@ -253,7 +253,9 @@ void AP_ADSB_uAvionix_UCP::handle_msg(const GDL90_RX_MESSAGE &msg) _frontend.out_state.ctrl.x_bit = rx.decoded.transponder_status.x_bit; } run_state.last_packet_Transponder_Status_ms = AP_HAL::millis(); +#if AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED GCS_SEND_MESSAGE(MSG_UAVIONIX_ADSB_OUT_STATUS); +#endif break; #endif // AP_ADSB_UAVIONIX_UCP_CAPTURE_ALL_RX_PACKETS From bc03918ea49961cf35901e6e5a5e3241c6182290 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 8 Nov 2023 10:36:58 +1100 Subject: [PATCH 307/499] GCS_MAVLink: create and use AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED narrower define we can use when not compiling in the backends which use this --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- libraries/GCS_MAVLink/GCS_config.h | 4 ++++ 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index f501f7d4657d50..8d2776681ff418 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1062,7 +1062,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c #if AP_AIS_ENABLED { MAVLINK_MSG_ID_AIS_VESSEL, MSG_AIS_VESSEL}, #endif -#if HAL_ADSB_ENABLED +#if AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED { MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS, MSG_UAVIONIX_ADSB_OUT_STATUS}, #endif #if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED @@ -6071,7 +6071,7 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) } #endif -#if HAL_ADSB_ENABLED +#if AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED case MSG_UAVIONIX_ADSB_OUT_STATUS: CHECK_PAYLOAD_SIZE(UAVIONIX_ADSB_OUT_STATUS); send_uavionix_adsb_out_status(); diff --git a/libraries/GCS_MAVLink/GCS_config.h b/libraries/GCS_MAVLink/GCS_config.h index ae978c1253cf39..7a9e38b51922f6 100644 --- a/libraries/GCS_MAVLink/GCS_config.h +++ b/libraries/GCS_MAVLink/GCS_config.h @@ -79,6 +79,10 @@ #define AP_MAVLINK_MSG_SERIAL_CONTROL_ENABLED HAL_GCS_ENABLED #endif +#ifndef AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED +#define AP_MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_ENABLED HAL_ADSB_ENABLED +#endif + // GCS should be using MISSION_REQUEST_INT instead; this is a waste of // flash. MISSION_REQUEST was deprecated in June 2020. We started // sending warnings to the GCS in Sep 2022 if this command was used. From aad51b7066e50f22ac87cdb8fbc15234ba07628b Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 27 Jul 2023 15:59:43 +0200 Subject: [PATCH 308/499] Copter: update PID notch centers at 1Hz with average loop rate --- ArduCopter/Copter.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 7ddd0be1a87607..f5242feb0d95d1 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -671,6 +671,13 @@ void Copter::one_hz_loop() #endif AP_Notify::flags.flying = !ap.land_complete; + + // slowly update the PID notches with the average loop rate + attitude_control->set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); + pos_control->get_accel_z_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); +#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED + custom_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); +#endif } void Copter::init_simple_bearing() From 61e91dde35751b91f9fee88dddc9aa108b686580 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 27 Jul 2023 18:34:43 +0200 Subject: [PATCH 309/499] autotest: add PID notches test --- Tools/autotest/arducopter.py | 44 ++++++++++++++++++++++++++++++++++++ Tools/autotest/helicopter.py | 44 ++++++++++++++++++++++++++++++++++++ 2 files changed, 88 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index f77e3cb5b9dc5f..701c3d50ebd06b 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -5960,6 +5960,49 @@ def extract_median_FTN1_PkAvg_from_current_onboard_log(self, tstart, tend): freqs.append(m.PkAvg) return numpy.median(numpy.asarray(freqs)), len(freqs) + def PIDNotches(self): + """Use dynamic harmonic notch to control motor noise.""" + self.progress("Flying with PID notches") + self.context_push() + + ex = None + try: + self.set_parameters({ + "AHRS_EKF_TYPE": 10, + "INS_LOG_BAT_MASK": 3, + "INS_LOG_BAT_OPT": 0, + "INS_GYRO_FILTER": 100, # set the gyro filter high so we can observe behaviour + "LOG_BITMASK": 65535, + "LOG_DISARMED": 0, + "SIM_VIB_FREQ_X": 120, # roll + "SIM_VIB_FREQ_Y": 120, # pitch + "SIM_VIB_FREQ_Z": 180, # yaw + "ATC_RAT_RLL_ADV": 1, + "ATC_RAT_RLL_NEF": 120, + "ATC_RAT_RLL_NBW": 50, + "ATC_RAT_PIT_ADV": 1, + "ATC_RAT_PIT_NEF": 120, + "ATC_RAT_PIT_NBW": 50, + "ATC_RAT_YAW_ADV": 1, + "ATC_RAT_YAW_NEF": 180, + "ATC_RAT_YAW_NBW": 50, + "SIM_GYR1_RND": 5, + }) + self.reboot_sitl() + + self.takeoff(10, mode="ALT_HOLD") + + freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(5, 20, 350, reverse=True) + + except Exception as e: + self.print_exception_caught(e) + ex = e + + self.context_pop() + + if ex is not None: + raise ex + def ThrottleGainBoost(self): """Use PD and Angle P boost for anti-gravity.""" # basic gyro sample rate test @@ -10561,6 +10604,7 @@ def tests2b(self): # this block currently around 9.5mins here Test(self.DynamicNotches, attempts=4), self.PositionWhenGPSIsZero, Test(self.DynamicRpmNotches, attempts=4), + self.PIDNotches, self.RefindGPS, Test(self.GyroFFT, attempts=1, speedup=8), Test(self.GyroFFTHarmonic, attempts=4, speedup=8), diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index 0485556eb13efc..d3634ed4160f2a 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -801,6 +801,49 @@ def TurbineStart(self, timeout=200): self.set_rc(8, 1000) self.disarm_vehicle() + def PIDNotches(self): + """Use dynamic harmonic notch to control motor noise.""" + self.progress("Flying with PID notches") + self.context_push() + + ex = None + try: + self.set_parameters({ + "AHRS_EKF_TYPE": 10, + "INS_LOG_BAT_MASK": 3, + "INS_LOG_BAT_OPT": 0, + "INS_GYRO_FILTER": 100, # set the gyro filter high so we can observe behaviour + "LOG_BITMASK": 65535, + "LOG_DISARMED": 0, + "SIM_VIB_FREQ_X": 120, # roll + "SIM_VIB_FREQ_Y": 120, # pitch + "SIM_VIB_FREQ_Z": 180, # yaw + "ATC_RAT_RLL_ADV": 1, + "ATC_RAT_RLL_NEF": 120, + "ATC_RAT_RLL_NBW": 50, + "ATC_RAT_PIT_ADV": 1, + "ATC_RAT_PIT_NEF": 120, + "ATC_RAT_PIT_NBW": 50, + "ATC_RAT_YAW_ADV": 1, + "ATC_RAT_YAW_NEF": 180, + "ATC_RAT_YAW_NBW": 50, + "SIM_GYR1_RND": 5, + }) + self.reboot_sitl() + + self.takeoff(10, mode="ALT_HOLD") + + freq, hover_throttle, peakdb1 = self.hover_and_check_matched_frequency_with_fft(5, 20, 350, reverse=True) + + except Exception as e: + self.print_exception_caught(e) + ex = e + + self.context_pop() + + if ex is not None: + raise ex + def tests(self): '''return list of all tests''' ret = vehicle_test_suite.TestSuite.tests(self) @@ -817,6 +860,7 @@ def tests(self): self.AirspeedDrivers, self.TurbineStart, self.NastyMission, + self.PIDNotches, ]) return ret From b17b78e3299a03181f4109d824e8c5d03d4b1962 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 27 Jul 2023 15:58:50 +0200 Subject: [PATCH 310/499] AC_PID: add notch filters to target and error terms calculate D feed-forward and notch applications correctly only update notches when enabled add notches and D feedforward to heli PIDs add advanced flag an selectively compile advanced options --- libraries/AC_PID/AC_HELI_PID.cpp | 54 ++++++++++++- libraries/AC_PID/AC_HELI_PID.h | 2 +- libraries/AC_PID/AC_PID.cpp | 133 +++++++++++++++++++++++++++++-- libraries/AC_PID/AC_PID.h | 33 +++++++- 4 files changed, 209 insertions(+), 13 deletions(-) diff --git a/libraries/AC_PID/AC_HELI_PID.cpp b/libraries/AC_PID/AC_HELI_PID.cpp index 3525ae26c65627..14dbd97b60c3cd 100644 --- a/libraries/AC_PID/AC_HELI_PID.cpp +++ b/libraries/AC_PID/AC_HELI_PID.cpp @@ -69,12 +69,62 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] = { // @User: Advanced AP_GROUPINFO("SMAX", 12, AC_HELI_PID, _slew_rate_max, 0), +#if AC_PID_ADVANCED_ENABLED + // @Param: ADV + // @DisplayName: Advanced parameters enable + // @Description: Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + AP_GROUPINFO_FLAGS("ADV", 32, AC_HELI_PID, _adv_enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: D_FF + // @DisplayName: PID Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + AP_GROUPINFO("D_FF", 33, AC_HELI_PID, _kdff, 0), + + // @Param: NTF + // @DisplayName: PID Target notch Filter center frequency + // @Description: PID Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + AP_GROUPINFO("NTF", 34, AC_HELI_PID, _notch_T_center_freq_hz, 0), + + // @Param: NEF + // @DisplayName: PID Error notch Filter center frequency + // @Description: PID Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + AP_GROUPINFO("NEF", 35, AC_HELI_PID, _notch_E_center_freq_hz, 0), + + // @Param: NBW + // @DisplayName: PID notch Filter bandwidth + // @Description: PID notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + AP_GROUPINFO("NBW", 36, AC_HELI_PID, _notch_bandwidth_hz, 0), + + // @Param: NATT + // @DisplayName: PID notch Filter attenuation + // @Description: PID notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + AP_GROUPINFO("NATT", 37, AC_HELI_PID, _notch_attenuation_dB, 40), + +#endif + AP_GROUPEND }; /// Constructor for PID -AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz) : - AC_PID(initial_p, initial_i, initial_d, initial_ff, initial_imax, initial_filt_T_hz, initial_filt_E_hz, initial_filt_D_hz) +AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, float dff_val) : + AC_PID(initial_p, initial_i, initial_d, initial_ff, initial_imax, initial_filt_T_hz, initial_filt_E_hz, initial_filt_D_hz, dff_val) { _last_requested_rate = 0; } diff --git a/libraries/AC_PID/AC_HELI_PID.h b/libraries/AC_PID/AC_HELI_PID.h index 0ed7737f181e38..d9f323d34a7d28 100644 --- a/libraries/AC_PID/AC_HELI_PID.h +++ b/libraries/AC_PID/AC_HELI_PID.h @@ -17,7 +17,7 @@ class AC_HELI_PID : public AC_PID { public: /// Constructor for PID - AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz); + AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, float dff_val=0); CLASS_NO_COPY(AC_HELI_PID); diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index 8d3349252c4140..fcb2406cfe1ff3 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -4,6 +4,8 @@ #include #include "AC_PID.h" +#define AC_PID_DEFAULT_NOTCH_ATTENUATION 40 + const AP_Param::GroupInfo AC_PID::var_info[] = { // @Param: P // @DisplayName: PID Proportional Gain @@ -70,12 +72,62 @@ const AP_Param::GroupInfo AC_PID::var_info[] = { // @User: Advanced AP_GROUPINFO("PDMX", 13, AC_PID, _kpdmax, 0), +#if AC_PID_ADVANCED_ENABLED + // @Param: ADV + // @DisplayName: Advanced parameters enable + // @Description: Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + AP_GROUPINFO_FLAGS("ADV", 32, AC_PID, _adv_enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: D_FF + // @DisplayName: PID Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D_FF", 33, AC_PID, _kdff, default_kdff), + + // @Param: NTF + // @DisplayName: PID Target notch Filter center frequency + // @Description: PID Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + AP_GROUPINFO("NTF", 34, AC_PID, _notch_T_center_freq_hz, 0), + + // @Param: NEF + // @DisplayName: PID Error notch Filter center frequency + // @Description: PID Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + AP_GROUPINFO("NEF", 35, AC_PID, _notch_E_center_freq_hz, 0), + + // @Param: NBW + // @DisplayName: PID notch Filter bandwidth + // @Description: PID notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + AP_GROUPINFO("NBW", 36, AC_PID, _notch_bandwidth_hz, 0), + + // @Param: NATT + // @DisplayName: PID notch Filter attenuation + // @Description: PID notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + AP_GROUPINFO("NATT", 37, AC_PID, _notch_attenuation_dB, 40), + +#endif + AP_GROUPEND }; // Constructor AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, - float initial_srmax, float initial_srtau) : + float initial_srmax, float initial_srtau, float initial_dff) : default_kp(initial_p), default_ki(initial_i), default_kd(initial_d), @@ -84,7 +136,8 @@ AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_ default_filt_T_hz(initial_filt_T_hz), default_filt_E_hz(initial_filt_E_hz), default_filt_D_hz(initial_filt_D_hz), - default_slew_rate_max(initial_srmax) + default_slew_rate_max(initial_srmax), + default_kdff(initial_dff) { // load parameter values from eeprom AP_Param::setup_object_defaults(this, var_info); @@ -126,6 +179,26 @@ void AC_PID::slew_limit(float smax) _slew_rate_max.set(fabsf(smax)); } +void AC_PID::set_notch_sample_rate(float sample_rate) +{ +#if AC_PID_ADVANCED_ENABLED + if (!_adv_enable) { + return; + } + + if (!is_zero(_notch_T_center_freq_hz.get()) && + (!is_equal(sample_rate, _target_notch.sample_freq_hz()) + || !is_equal(_notch_T_center_freq_hz.get(), _target_notch.center_freq_hz()))) { + _target_notch.init(sample_rate, _notch_T_center_freq_hz, _notch_bandwidth_hz, _notch_attenuation_dB); + } + if (!is_zero(_notch_E_center_freq_hz.get()) && + (!is_equal(sample_rate, _error_notch.sample_freq_hz()) + || !is_equal(_notch_E_center_freq_hz.get(), _error_notch.center_freq_hz()))) { + _error_notch.init(sample_rate, _notch_E_center_freq_hz, _notch_bandwidth_hz, _notch_attenuation_dB); + } +#endif +} + // update_all - set target and measured inputs to PID controller and calculate outputs // target and error are filtered // the derivative is then calculated and filtered @@ -143,15 +216,42 @@ float AC_PID::update_all(float target, float measurement, float dt, bool limit, _target = target; _error = _target - measurement; _derivative = 0.0f; + _target_derivative = 0.0f; +#if AC_PID_ADVANCED_ENABLED + if (_adv_enable) { + if (!is_zero(_notch_T_center_freq_hz.get())) { + _target_notch.reset(); + _target = _target_notch.apply(_target); + } + if (!is_zero(_notch_E_center_freq_hz.get())) { + _error_notch.reset(); + _error = _error_notch.apply(_error); + } + } +#endif } else { float error_last = _error; + float target_last = _target; + float error = _target - measurement; +#if AC_PID_ADVANCED_ENABLED + if (_adv_enable) { + // apply notch filters before FTLD/FLTE to avoid shot noise + if (!is_zero(_notch_T_center_freq_hz.get())) { + target = _target_notch.apply(target); + } + if (!is_zero(_notch_E_center_freq_hz.get())) { + error = _error_notch.apply(error); + } + } +#endif _target += get_filt_T_alpha(dt) * (target - _target); - _error += get_filt_E_alpha(dt) * ((_target - measurement) - _error); + _error += get_filt_E_alpha(dt) * (error - _error); // calculate and filter derivative if (is_positive(dt)) { float derivative = (_error - error_last) / dt; _derivative += get_filt_D_alpha(dt) * (derivative - _derivative); + _target_derivative = (_target - target_last) / dt; } } @@ -253,8 +353,12 @@ float AC_PID::get_d() const float AC_PID::get_ff() { - _pid_info.FF = _target * _kff; - return _target * _kff; + _pid_info.FF = _target * _kff +#if AC_PID_ADVANCED_ENABLED + + _target_derivative * _kdff +#endif + ; + return _pid_info.FF; } void AC_PID::reset_I() @@ -275,6 +379,13 @@ void AC_PID::load_gains() _filt_T_hz.load(); _filt_E_hz.load(); _filt_D_hz.load(); +#if AC_PID_ADVANCED_ENABLED + _kdff.load(); + _notch_T_center_freq_hz.load(); + _notch_E_center_freq_hz.load(); + _notch_bandwidth_hz.load(); + _notch_attenuation_dB.load(); +#endif } // save_gains - save gains to eeprom @@ -288,10 +399,17 @@ void AC_PID::save_gains() _filt_T_hz.save(); _filt_E_hz.save(); _filt_D_hz.save(); +#if AC_PID_ADVANCED_ENABLED + _kdff.save(); + _notch_T_center_freq_hz.save(); + _notch_E_center_freq_hz.save(); + _notch_bandwidth_hz.save(); + _notch_attenuation_dB.save(); +#endif } /// Overload the function call operator to permit easy initialisation -void AC_PID::operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz) +void AC_PID::operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz, float dff_val) { _kp.set(p_val); _ki.set(i_val); @@ -301,6 +419,9 @@ void AC_PID::operator()(float p_val, float i_val, float d_val, float ff_val, flo _filt_T_hz.set(input_filt_T_hz); _filt_E_hz.set(input_filt_E_hz); _filt_D_hz.set(input_filt_D_hz); +#if AC_PID_ADVANCED_ENABLED + _kdff.set(dff_val); +#endif } // get_filt_T_alpha - get the target filter alpha diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index 7ae4592473109e..30300d071d5a4e 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -8,12 +8,17 @@ #include #include #include +#include #define AC_PID_TFILT_HZ_DEFAULT 0.0f // default input filter frequency #define AC_PID_EFILT_HZ_DEFAULT 0.0f // default input filter frequency #define AC_PID_DFILT_HZ_DEFAULT 20.0f // default input filter frequency #define AC_PID_RESET_TC 0.16f // Time constant for integrator reset decay to zero +#ifndef AC_PID_ADVANCED_ENABLED +#define AC_PID_ADVANCED_ENABLED 0 +#endif + #include "AP_PIDInfo.h" /// @class AC_PID @@ -32,11 +37,12 @@ class AC_PID { float filt_D_hz; float srmax; float srtau; + float dff; }; // Constructor for PID AC_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, - float initial_srmax=0, float initial_srtau=1.0); + float initial_srmax=0, float initial_srtau=1.0, float initial_dff=0); AC_PID(const AC_PID::Defaults &defaults) : AC_PID( defaults.p, @@ -48,7 +54,8 @@ class AC_PID { defaults.filt_E_hz, defaults.filt_D_hz, defaults.srmax, - defaults.srtau + defaults.srtau, + defaults.dff ) { } @@ -95,7 +102,7 @@ class AC_PID { void save_gains(); /// operator function call for easy initialisation - void operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz); + void operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz, float dff_val=0); // get accessors const AP_Float &kP() const { return _kp; } @@ -146,6 +153,11 @@ class AC_PID { const AP_PIDInfo& get_pid_info(void) const { return _pid_info; } +#if AC_PID_ADVANCED_ENABLED + AP_Float &kDff() { return _kdff; } + void kDff(const float v) { _kdff.set(v); } +#endif + void set_notch_sample_rate(float); // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -168,7 +180,14 @@ class AC_PID { AP_Float _filt_E_hz; // PID error filter frequency in Hz AP_Float _filt_D_hz; // PID derivative filter frequency in Hz AP_Float _slew_rate_max; - +#if AC_PID_ADVANCED_ENABLED + AP_Int8 _adv_enable; + AP_Float _kdff; + AP_Float _notch_T_center_freq_hz; + AP_Float _notch_E_center_freq_hz; + AP_Float _notch_bandwidth_hz; + AP_Float _notch_attenuation_dB; +#endif SlewLimiter _slew_limiter{_slew_rate_max, _slew_rate_tau}; // flags @@ -182,6 +201,11 @@ class AC_PID { float _error; // error value to enable filtering float _derivative; // derivative value to enable filtering int8_t _slew_limit_scale; + float _target_derivative; // target derivative value to enable dff +#if AC_PID_ADVANCED_ENABLED + NotchFilterFloat _target_notch; + NotchFilterFloat _error_notch; +#endif AP_PIDInfo _pid_info; @@ -190,6 +214,7 @@ class AC_PID { const float default_ki; const float default_kd; const float default_kff; + const float default_kdff; const float default_kimax; const float default_filt_T_hz; const float default_filt_E_hz; From 9211dba4841415aa2d89aa4c51103ee2825dec5e Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 30 Jul 2023 18:03:34 +0200 Subject: [PATCH 311/499] APM_Control: update docs for new AC_PID parameters add advanced flag to PIDs and selectively compile advanced PID options --- libraries/APM_Control/AP_PitchController.cpp | 40 +++++ libraries/APM_Control/AP_PitchController.h | 3 + libraries/APM_Control/AP_RollController.cpp | 40 +++++ libraries/APM_Control/AP_RollController.h | 3 + libraries/APM_Control/AP_YawController.cpp | 40 +++++ libraries/APM_Control/AP_YawController.h | 3 + libraries/APM_Control/AR_AttitudeControl.cpp | 169 +++++++++++++++++++ libraries/APM_Control/AR_AttitudeControl.h | 3 + 8 files changed, 301 insertions(+) diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 64e5a10478b633..c093d2d40e18f8 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -136,6 +136,46 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = { // @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0 1 // @Increment: 0.01 + + // @Param: _RATE_ADV + // @DisplayName: Pitch Advanced parameters enable + // @Description: Pitch Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: _RATE_D_FF + // @DisplayName: Pitch Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.001 0.03 + // @Increment: 0.001 + // @User: Advanced + + // @Param: _RATE_NTF + // @DisplayName: Pitch Target notch Filter center frequency + // @Description: Pitch Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NEF + // @DisplayName: Pitch Error notch Filter center frequency + // @Description: Pitch Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NBW + // @DisplayName: Pitch notch Filter bandwidth + // @Description: Pitch notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NATT + // @DisplayName: Pitch notch Filter attenuation + // @Description: Pitch notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(rate_pid, "_RATE_", 11, AP_PitchController, AC_PID), diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index 1cf1d76a32086c..e2900d15ad11a4 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -40,6 +40,9 @@ class AP_PitchController return _pid_info; } + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate) { rate_pid.set_notch_sample_rate(sample_rate); } + static const struct AP_Param::GroupInfo var_info[]; AP_Float &kP(void) { return rate_pid.kP(); } diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index f2cb86cf94d315..0cd9e7076a8135 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -119,6 +119,46 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = { // @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0 1 // @Increment: 0.01 + + // @Param: _RATE_ADV + // @DisplayName: Roll Advanced parameters enable + // @Description: Roll Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: _RATE_D_FF + // @DisplayName: Roll Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.001 0.03 + // @Increment: 0.001 + // @User: Advanced + + // @Param: _RATE_NTF + // @DisplayName: Roll Target notch Filter center frequency + // @Description: Roll Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NEF + // @DisplayName: Roll Error notch Filter center frequency + // @Description: Roll Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NBW + // @DisplayName: Roll notch Filter bandwidth + // @Description: Roll notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NATT + // @DisplayName: Roll notch Filter attenuation + // @Description: Roll notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_RollController, AC_PID), diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index 85633f1d5f987c..35a8a331cc8305 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -40,6 +40,9 @@ class AP_RollController return _pid_info; } + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate) { rate_pid.set_notch_sample_rate(sample_rate); } + static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index 47b04df4e0b460..04fc1890bef7d8 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -150,6 +150,46 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = { // @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0 1 // @Increment: 0.01 + + // @Param: _RATE_ADV + // @DisplayName: Yaw Advanced parameters enable + // @Description: Yaw Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: _RATE_D_FF + // @DisplayName: Yaw Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.001 0.03 + // @Increment: 0.001 + // @User: Advanced + + // @Param: _RATE_NTF + // @DisplayName: Yaw Target notch Filter center frequency + // @Description: Yaw Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NEF + // @DisplayName: Yaw Error notch Filter center frequency + // @Description: Yaw Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NBW + // @DisplayName: Yaw notch Filter bandwidth + // @Description: Yaw notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NATT + // @DisplayName: Yaw notch Filter attenuation + // @Description: Yaw notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_YawController, AC_PID), diff --git a/libraries/APM_Control/AP_YawController.h b/libraries/APM_Control/AP_YawController.h index 32129dd89c78ef..df33c9a1a6f75a 100644 --- a/libraries/APM_Control/AP_YawController.h +++ b/libraries/APM_Control/AP_YawController.h @@ -43,6 +43,9 @@ class AP_YawController return _pid_info; } + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate) { rate_pid.set_notch_sample_rate(sample_rate); } + // start/stop auto tuner void autotune_start(void); void autotune_restore(void); diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index 95d23fdc8f3dc1..140f8a832deff2 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -146,6 +146,46 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Description: Steering control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0.000 1.000 // @Increment: 0.01 + + // @Param: _STR_RAT_ADV + // @DisplayName: Steering control Advanced parameters enable + // @Description: Steering control Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: _STR_RAT_D_FF + // @DisplayName: Steering control Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.001 0.03 + // @Increment: 0.001 + // @User: Advanced + + // @Param: _STR_RAT_NTF + // @DisplayName: Steering control Target notch Filter center frequency + // @Description: Steering control Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _STR_RAT_NEF + // @DisplayName: Steering control Error notch Filter center frequency + // @Description: Steering control Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _STR_RAT_NBW + // @DisplayName: Steering control notch Filter bandwidth + // @Description: Steering control notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: _STR_RAT_NATT + // @DisplayName: Steering control notch Filter attenuation + // @Description: Steering control notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_steer_rate_pid, "_STR_RAT_", 1, AR_AttitudeControl, AC_PID), @@ -229,6 +269,46 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Description: Speed control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0.000 1.000 // @Increment: 0.01 + + // @Param: _SPEED_ADV + // @DisplayName: Speed control Advanced parameters enable + // @Description: Speed control Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: _SPEED_D_FF + // @DisplayName: Speed control Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.001 0.03 + // @Increment: 0.001 + // @User: Advanced + + // @Param: _SPEED_NTF + // @DisplayName: Speed control Target notch Filter center frequency + // @Description: Speed control Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _SPEED_NEF + // @DisplayName: Speed control Error notch Filter center frequency + // @Description: Speed control Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _SPEED_NBW + // @DisplayName: Speed control notch Filter bandwidth + // @Description: Speed control notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: _SPEED_NATT + // @DisplayName: Speed control notch Filter attenuation + // @Description: Speed control notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_throttle_speed_pid, "_SPEED_", 2, AR_AttitudeControl, AC_PID), @@ -372,6 +452,46 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Description: Pitch control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0.000 1.000 // @Increment: 0.01 + + // @Param: _BAL_ADV + // @DisplayName: Pitch control Advanced parameters enable + // @Description: Pitch control Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: _BAL_D_FF + // @DisplayName: Pitch control Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.001 0.03 + // @Increment: 0.001 + // @User: Advanced + + // @Param: _BAL_NTF + // @DisplayName: Pitch control Target notch Filter center frequency + // @Description: Pitch control Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _BAL_NEF + // @DisplayName: Pitch control Error notch Filter center frequency + // @Description: Pitch control Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _BAL_NBW + // @DisplayName: Pitch control notch Filter bandwidth + // @Description: Pitch control notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: _BAL_NATT + // @DisplayName: Pitch control notch Filter attenuation + // @Description: Pitch control notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_pitch_to_throttle_pid, "_BAL_", 10, AR_AttitudeControl, AC_PID), @@ -463,6 +583,46 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Description: Sail Heel control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0.000 1.000 // @Increment: 0.01 + + // @Param: _SAIL_ADV + // @DisplayName: Sail Heel Advanced parameters enable + // @Description: Sail Heel Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: _SAIL_D_FF + // @DisplayName: Sail Heel Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.001 0.03 + // @Increment: 0.001 + // @User: Advanced + + // @Param: _SAIL_NTF + // @DisplayName: Sail Heel Target notch Filter center frequency + // @Description: Sail Heel Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _SAIL_NEF + // @DisplayName: Sail Heel Error notch Filter center frequency + // @Description: Sail Heel Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _SAIL_NBW + // @DisplayName: Sail Heel notch Filter bandwidth + // @Description: Sail Heel notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: _SAIL_NATT + // @DisplayName: Sail Heel notch Filter attenuation + // @Description: Sail Heel notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_sailboat_heel_pid, "_SAIL_", 12, AR_AttitudeControl, AC_PID), @@ -1004,3 +1164,12 @@ void AR_AttitudeControl::relax_I() _throttle_speed_pid.reset_I(); _pitch_to_throttle_pid.reset_I(); } + +void AR_AttitudeControl::set_notch_sample_rate(float sample_rate) +{ +#if AC_PID_ADVANCED_ENABLED + _steer_rate_pid.set_notch_sample_rate(sample_rate); + _throttle_speed_pid.set_notch_sample_rate(sample_rate); + _pitch_to_throttle_pid.set_notch_sample_rate(sample_rate); +#endif +} diff --git a/libraries/APM_Control/AR_AttitudeControl.h b/libraries/APM_Control/AR_AttitudeControl.h index 2a6bc583afce34..54d956a657685e 100644 --- a/libraries/APM_Control/AR_AttitudeControl.h +++ b/libraries/APM_Control/AR_AttitudeControl.h @@ -100,6 +100,9 @@ class AR_AttitudeControl { AC_PID& get_sailboat_heel_pid() { return _sailboat_heel_pid; } const AP_PIDInfo& get_throttle_speed_pid_info() const { return _throttle_speed_pid_info; } + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate); + // get the slew rate value for speed and steering for oscillation detection in lua scripts void get_srate(float &steering_srate, float &speed_srate); From 25b66ef6caf9cf8475f5d81e2d03ee9bf29cc6a3 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 10 Aug 2023 12:08:38 +0100 Subject: [PATCH 312/499] Tracker: add documentation for PID notches and D feed-foward update PID notch centers at 1Hz with average loop rate --- AntennaTracker/Parameters.cpp | 82 +++++++++++++++++++++++++++++++++++ AntennaTracker/Tracker.cpp | 2 + 2 files changed, 84 insertions(+) diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index e1757fba32e4cf..b9c48d4e9a117b 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -387,6 +387,47 @@ const AP_Param::Info Tracker::var_info[] = { // @Units: d% // @User: Advanced + // @Param: PITCH2SRV_ADV + // @DisplayName: Advanced Pitch parameters enable + // @Description: Advanced Pitch parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: PITCH2SRV_D_FF + // @DisplayName: Pitch Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.001 0.1 + // @Increment: 0.001 + // @User: Advanced + + // @Param: PITCH2SRV_NTF + // @DisplayName: Pitch Target notch Filter center frequency + // @Description: Pitch Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: PITCH2SRV_NEF + // @DisplayName: Pitch Error notch Filter center frequency + // @Description: Pitch Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: PITCH2SRV_NBW + // @DisplayName: Pitch notch Filter bandwidth + // @Description: Pitch notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: PITCH2SRV_NATT + // @DisplayName: Pitch notch Filter attenuation + // @Description: Pitch notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID), // @Param: YAW2SRV_P @@ -464,6 +505,47 @@ const AP_Param::Info Tracker::var_info[] = { // @Units: d% // @User: Advanced + // @Param: YAW2SRV_ADV + // @DisplayName: Advanced Yaw parameters enable + // @Description: Advanced Yaw parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: YAW2SRV_D_FF + // @DisplayName: Yaw Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.001 0.1 + // @Increment: 0.001 + // @User: Advanced + + // @Param: YAW2SRV_NTF + // @DisplayName: Yaw Target notch Filter center frequency + // @Description: Yaw Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: YAW2SRV_NEF + // @DisplayName: Yaw Error notch Filter center frequency + // @Description: Yaw Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: YAW2SRV_NBW + // @DisplayName: Yaw notch Filter bandwidth + // @Description: Yaw notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: YAW2SRV_NATT + // @DisplayName: Yaw notch Filter attenuation + // @Description: Yaw notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID), #if AP_SCRIPTING_ENABLED diff --git a/AntennaTracker/Tracker.cpp b/AntennaTracker/Tracker.cpp index f3284e985ec353..fbf3427c501c55 100644 --- a/AntennaTracker/Tracker.cpp +++ b/AntennaTracker/Tracker.cpp @@ -103,6 +103,8 @@ void Tracker::one_second_loop() set_likely_flying(hal.util->get_soft_armed()); AP_Notify::flags.flying = hal.util->get_soft_armed(); + + g.pidYaw2Srv.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); } void Tracker::ten_hz_logging_loop() From c4dc6f647116df66de8186df79e4c2e06222507b Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 10 Aug 2023 12:09:12 +0100 Subject: [PATCH 313/499] Blimp: add documentation for PID notches and D feed-foward update PID notch centers at 1Hz with average loop rate --- Blimp/Blimp.cpp | 2 ++ Blimp/Parameters.cpp | 42 ++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 44 insertions(+) diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index ff5327006738d9..fc03cc4c8fb04b 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -209,6 +209,8 @@ void Blimp::one_hz_loop() SRV_Channels::enable_aux_servos(); AP_Notify::flags.flying = !ap.land_complete; + + blimp.pid_pos_yaw.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); } void Blimp::read_AHRS(void) diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index bb0ac2bb40d6af..aab8caeadccf95 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -729,6 +729,48 @@ const AP_Param::Info Blimp::var_info[] = { // @Increment: 10 // @Units: d% // @User: Advanced + + // @Param: POSYAW_ADV + // @DisplayName: Advanced Yaw parameters enable + // @Description: Advanced Yaw parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: POSYAW_D_FF + // @DisplayName: Position (yaw) Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.001 0.1 + // @Increment: 0.001 + // @User: Advanced + + // @Param: POSYAW_NTF + // @DisplayName: Position (yaw) Target notch Filter center frequency + // @Description: Position (yaw) Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: POSYAW_NEF + // @DisplayName: Position (yaw) Error notch Filter center frequency + // @Description: Position (yaw) Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: POSYAW_NBW + // @DisplayName: Position (yaw) notch Filter bandwidth + // @Description: Position (yaw) notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: POSYAW_NATT + // @DisplayName: Position (yaw) notch Filter attenuation + // @Description: Position (yaw) notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + GOBJECT(pid_pos_yaw, "POSYAW_", AC_PID), // @Group: From 952baf860ce473fbb65c219a91fc84c142aeac4f Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 10 Aug 2023 12:09:49 +0100 Subject: [PATCH 314/499] AC_CustomControl: add documentation for PID notches and D feed-foward add advanced flag to PIDs and selectively compile advanced PID options --- .../AC_CustomControl/AC_CustomControl.cpp | 9 ++ libraries/AC_CustomControl/AC_CustomControl.h | 3 + .../AC_CustomControl_Backend.h | 3 + .../AC_CustomControl/AC_CustomControl_PID.cpp | 136 ++++++++++++++++++ .../AC_CustomControl/AC_CustomControl_PID.h | 3 + 5 files changed, 154 insertions(+) diff --git a/libraries/AC_CustomControl/AC_CustomControl.cpp b/libraries/AC_CustomControl/AC_CustomControl.cpp index b8c7a58eaa3dff..26755cbb47f5ac 100644 --- a/libraries/AC_CustomControl/AC_CustomControl.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl.cpp @@ -184,4 +184,13 @@ void AC_CustomControl::log_switch(void) { _custom_controller_active); } +void AC_CustomControl::set_notch_sample_rate(float sample_rate) +{ +#if AC_PID_ADVANCED_ENABLED + if (_backend != nullptr) { + _backend->set_notch_sample_rate(sample_rate); + } +#endif +} + #endif diff --git a/libraries/AC_CustomControl/AC_CustomControl.h b/libraries/AC_CustomControl/AC_CustomControl.h index bf0628302b72ad..9cda1f21db6cba 100644 --- a/libraries/AC_CustomControl/AC_CustomControl.h +++ b/libraries/AC_CustomControl/AC_CustomControl.h @@ -32,6 +32,9 @@ class AC_CustomControl { bool is_safe_to_run(void); void log_switch(void); + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate); + // zero index controller type param, only use it to access _backend or _backend_var_info array uint8_t get_type() { return _controller_type > 0 ? (_controller_type - 1) : 0; }; diff --git a/libraries/AC_CustomControl/AC_CustomControl_Backend.h b/libraries/AC_CustomControl/AC_CustomControl_Backend.h index d9c537d34542eb..c4068a7b1b8f4e 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_Backend.h +++ b/libraries/AC_CustomControl/AC_CustomControl_Backend.h @@ -23,6 +23,9 @@ class AC_CustomControl_Backend // reset controller to avoid build up or abrupt response upon switch, ex: integrator, filter virtual void reset() = 0; + // set the PID notch sample rates + virtual void set_notch_sample_rate(float sample_rate) {}; + protected: // References to external libraries AP_AHRS_View*& _ahrs; diff --git a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp index e468e8f0be0f2a..61ae0fb2a76fcf 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp @@ -101,6 +101,48 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @Range: 0 1 // @Increment: 0.01 // @User: Advanced + + // @Param: RAT_RLL_ADV + // @DisplayName: Roll Advanced parameters enable + // @Description: Roll Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_RLL_D_FF + // @DisplayName: Roll Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_RLL_NTF + // @DisplayName: Roll Target notch Filter center frequency + // @Description: Roll Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NEF + // @DisplayName: Roll Error notch Filter center frequency + // @Description: Roll Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NBW + // @DisplayName: Roll notch Filter bandwidth + // @Description: Roll notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NATT + // @DisplayName: Roll notch Filter attenuation + // @Description: Roll notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + AP_SUBGROUPINFO(_pid_atti_rate_roll, "RAT_RLL_", 4, AC_CustomControl_PID, AC_PID), // @Param: RAT_PIT_P @@ -175,6 +217,48 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @Range: 0 1 // @Increment: 0.01 // @User: Advanced + + // @Param: RAT_PIT_ADV + // @DisplayName: Pitch Advanced parameters enable + // @Description: Pitch Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_PIT_D_FF + // @DisplayName: Pitch Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_PIT_NTF + // @DisplayName: Pitch Target notch Filter center frequency + // @Description: Pitch Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NEF + // @DisplayName: Pitch Error notch Filter center frequency + // @Description: Pitch Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NBW + // @DisplayName: Pitch notch Filter bandwidth + // @Description: Pitch notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NATT + // @DisplayName: Pitch notch Filter attenuation + // @Description: Pitch notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + AP_SUBGROUPINFO(_pid_atti_rate_pitch, "RAT_PIT_", 5, AC_CustomControl_PID, AC_PID), @@ -250,6 +334,48 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @Range: 0 1 // @Increment: 0.01 // @User: Advanced + + // @Param: RAT_YAW_ADV + // @DisplayName: Yaw Advanced parameters enable + // @Description: Yaw Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_YAW_D_FF + // @DisplayName: Yaw Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_YAW_NTF + // @DisplayName: Yaw Target notch Filter center frequency + // @Description: Yaw Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NEF + // @DisplayName: Yaw Error notch Filter center frequency + // @Description: Yaw Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NBW + // @DisplayName: Yaw notch Filter bandwidth + // @Description: Yaw notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NATT + // @DisplayName: Yaw notch Filter attenuation + // @Description: Yaw notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + AP_SUBGROUPINFO(_pid_atti_rate_yaw, "RAT_YAW_", 6, AC_CustomControl_PID, AC_PID), AP_GROUPEND @@ -332,4 +458,14 @@ void AC_CustomControl_PID::reset(void) _pid_atti_rate_yaw.reset_filter(); } + +void AC_CustomControl_PID::set_notch_sample_rate(float sample_rate) +{ +#if AC_PID_ADVANCED_ENABLED + _pid_atti_rate_roll.set_notch_sample_rate(sample_rate); + _pid_atti_rate_pitch.set_notch_sample_rate(sample_rate); + _pid_atti_rate_yaw.set_notch_sample_rate(sample_rate); +#endif +} + #endif diff --git a/libraries/AC_CustomControl/AC_CustomControl_PID.h b/libraries/AC_CustomControl/AC_CustomControl_PID.h index a48b5f9759536f..b3cdf68884475b 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_PID.h +++ b/libraries/AC_CustomControl/AC_CustomControl_PID.h @@ -21,6 +21,9 @@ class AC_CustomControl_PID : public AC_CustomControl_Backend { Vector3f update() override; void reset(void) override; + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate) override; + // user settable parameters static const struct AP_Param::GroupInfo var_info[]; From 370ee7d4d3e192d85e8966ab743dfa0ffcf9ea47 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 10 Aug 2023 12:10:17 +0100 Subject: [PATCH 315/499] AP_WheelEncoder: add documentation for PID notches and D feed-foward add advanced flag to PIDs and selectively compile advanced PID options --- .../AP_WheelEncoder/AP_WheelRateControl.cpp | 88 +++++++++++++++++++ .../AP_WheelEncoder/AP_WheelRateControl.h | 3 + 2 files changed, 91 insertions(+) diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp index e23a13b93ff9e8..0edf03fe9db835 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp @@ -90,6 +90,46 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = { // @DisplayName: Wheel rate control PD sum maximum // @Description: Wheel rate control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0.000 1.000 + + // @Param: _RATE_ADV + // @DisplayName: Wheel rate Advanced parameters enable + // @Description: Wheel rate Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: _RATE_D_FF + // @DisplayName: Wheel rate Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the error + // @Range: 0.000 0.400 + // @Increment: 0.001 + // @User: Advanced + + // @Param: _RATE_NTF + // @DisplayName: Wheel rate Target notch Filter center frequency + // @Description: Wheel rate Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NEF + // @DisplayName: Wheel rate Error notch Filter center frequency + // @Description: Wheel rate Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NBW + // @DisplayName: Wheel rate notch Filter bandwidth + // @Description: Wheel rate notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: _RATE_NATT + // @DisplayName: Wheel rate notch Filter attenuation + // @Description: Wheel rate notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_rate_pid0, "_RATE_", 3, AP_WheelRateControl, AC_PID), @@ -166,6 +206,46 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = { // @DisplayName: Wheel rate control PD sum maximum // @Description: Wheel rate control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0.000 1.000 + + // @Param: 2_RATE_ADV + // @DisplayName: Wheel rate Advanced parameters enable + // @Description: Wheel rate Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: 2_RATE_D_FF + // @DisplayName: Wheel rate Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0.000 0.400 + // @Increment: 0.001 + // @User: Advanced + + // @Param: 2_RATE_NTF + // @DisplayName: Wheel rate Target notch Filter center frequency + // @Description: Wheel rate Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: 2_RATE_NEF + // @DisplayName: Wheel rate Error notch Filter center frequency + // @Description: Wheel rate Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: 2_RATE_NBW + // @DisplayName: Wheel rate notch Filter bandwidth + // @Description: Wheel rate notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: 2_RATE_NATT + // @DisplayName: Wheel rate notch Filter attenuation + // @Description: Wheel rate notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_rate_pid1, "2_RATE_", 4, AP_WheelRateControl, AC_PID), @@ -237,3 +317,11 @@ AC_PID& AP_WheelRateControl::get_pid(uint8_t instance) return _rate_pid1; } } + +void AP_WheelRateControl::set_notch_sample_rate(float sample_rate) +{ +#if AC_PID_ADVANCED_ENABLED + _rate_pid0.set_notch_sample_rate(sample_rate); + _rate_pid1.set_notch_sample_rate(sample_rate); +#endif +} diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.h b/libraries/AP_WheelEncoder/AP_WheelRateControl.h index 1f72817845f2af..f62d981bfb6863 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.h +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.h @@ -51,6 +51,9 @@ class AP_WheelRateControl { // get pid objects for reporting AC_PID& get_pid(uint8_t instance); + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate); + static const struct AP_Param::GroupInfo var_info[]; private: From 6a40843a9ef15bba383e1638796efcfa7dcf9b95 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 27 Aug 2023 14:11:58 +0100 Subject: [PATCH 316/499] Filter: provide accessors for center and sample frequencies on NotchFilter --- libraries/Filter/NotchFilter.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/Filter/NotchFilter.h b/libraries/Filter/NotchFilter.h index dd6f319f784fff..476d06d79b3cc2 100644 --- a/libraries/Filter/NotchFilter.h +++ b/libraries/Filter/NotchFilter.h @@ -34,6 +34,8 @@ class NotchFilter { void init_with_A_and_Q(float sample_freq_hz, float center_freq_hz, float A, float Q); T apply(const T &sample); void reset(); + float center_freq_hz() const { return _center_freq_hz; } + float sample_freq_hz() const { return _sample_freq_hz; } // calculate attenuation and quality from provided center frequency and bandwidth static void calculate_A_and_Q(float center_freq_hz, float bandwidth_hz, float attenuation_dB, float& A, float& Q); From d6287e90f12e9e98a1f4d3f2527051dc52eb4a4e Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 27 Jul 2023 15:59:16 +0200 Subject: [PATCH 317/499] AC_AttitudeControl: update PID notch centres add documentation for PID notches and D feed-foward add notches and D feedforward to heli PIDs add advanced flag to PIDs and selectively compile advanced PID options --- .../AC_AttitudeControl/AC_AttitudeControl.h | 3 + .../AC_AttitudeControl_Heli.cpp | 150 ++++++++++++++++++ .../AC_AttitudeControl_Heli.h | 19 +-- .../AC_AttitudeControl_Multi.cpp | 134 ++++++++++++++++ .../AC_AttitudeControl_Multi.h | 3 + .../AC_AttitudeControl_Sub.cpp | 129 +++++++++++++++ .../AC_AttitudeControl_Sub.h | 3 + .../AC_AttitudeControl/AC_PosControl.cpp | 40 +++++ 8 files changed, 467 insertions(+), 14 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index a08dedda084c20..f75230980414d2 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -342,6 +342,9 @@ class AC_AttitudeControl { // sanity check parameters. should be called once before take-off virtual void parameter_sanity_check() {} + // set the PID notch sample rates + virtual void set_notch_sample_rate(float sample_rate) {} + // return true if the rpy mix is at lowest value virtual bool is_throttle_mix_min() const { return true; } diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index e05d6e4af73747..26004c3a13ba69 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -1,5 +1,6 @@ #include "AC_AttitudeControl_Heli.h" #include +#include // table of user settable parameters const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { @@ -87,6 +88,47 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: RAT_RLL_ADV + // @DisplayName: Roll Advanced parameters enable + // @Description: Roll Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_RLL_D_FF + // @DisplayName: Roll Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_RLL_NTF + // @DisplayName: Roll Target notch Filter center frequency + // @Description: Roll Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NEF + // @DisplayName: Roll Error notch Filter center frequency + // @Description: Roll Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NBW + // @DisplayName: Roll notch Filter bandwidth + // @Description: Roll notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NATT + // @DisplayName: Roll notch Filter attenuation + // @Description: Roll notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 2, AC_AttitudeControl_Heli, AC_HELI_PID), // @Param: RAT_PIT_P @@ -161,6 +203,47 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: RAT_PIT_ADV + // @DisplayName: Pitch Advanced parameters enable + // @Description: Pitch Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_PIT_D_FF + // @DisplayName: Pitch Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_PIT_NTF + // @DisplayName: Pitch Target notch Filter center frequency + // @Description: Pitch Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NEF + // @DisplayName: Pitch Error notch Filter center frequency + // @Description: Pitch Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NBW + // @DisplayName: Pitch notch Filter bandwidth + // @Description: Pitch notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NATT + // @DisplayName: Pitch notch Filter attenuation + // @Description: Pitch notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 3, AC_AttitudeControl_Heli, AC_HELI_PID), // @Param: RAT_YAW_P @@ -235,6 +318,47 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @Increment: 0.5 // @User: Advanced + // @Param: RAT_YAW_ADV + // @DisplayName: Yaw Advanced parameters enable + // @Description: Yaw Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_YAW_D_FF + // @DisplayName: Yaw Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_YAW_NTF + // @DisplayName: Yaw Target notch Filter center frequency + // @Description: Yaw Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NEF + // @DisplayName: Yaw Error notch Filter center frequency + // @Description: Yaw Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NBW + // @DisplayName: Yaw notch Filter bandwidth + // @Description: Yaw notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NATT + // @DisplayName: Yaw notch Filter attenuation + // @Description: Yaw notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 4, AC_AttitudeControl_Heli, AC_HELI_PID), // @Param: PIRO_COMP @@ -247,6 +371,23 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { AP_GROUPEND }; +AC_AttitudeControl_Heli::AC_AttitudeControl_Heli(AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, AP_MotorsHeli& motors) : + AC_AttitudeControl(ahrs, aparm, motors), + _pid_rate_roll(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f), + _pid_rate_pitch(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f), + _pid_rate_yaw(AC_ATC_HELI_RATE_YAW_P, AC_ATC_HELI_RATE_YAW_I, AC_ATC_HELI_RATE_YAW_D, AC_ATC_HELI_RATE_YAW_FF, AC_ATC_HELI_RATE_YAW_IMAX, AC_ATTITUDE_HELI_RATE_Y_FF_FILTER, AC_ATC_HELI_RATE_YAW_FILT_HZ, 0.0f) +{ + AP_Param::setup_object_defaults(this, var_info); + + // initialise flags + _flags_heli.leaky_i = true; + _flags_heli.flybar_passthrough = false; + _flags_heli.tail_passthrough = false; +#if AC_PID_ADVANCED_ENABLED + set_notch_sample_rate(AP::scheduler().get_loop_rate_hz()); +#endif +} + // passthrough_bf_roll_pitch_rate_yaw - passthrough the pilots roll and pitch inputs directly to swashplate for flybar acro mode void AC_AttitudeControl_Heli::passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) { @@ -485,3 +626,12 @@ void AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_yaw(float euler_roll_ } AC_AttitudeControl::input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_angle_cd, slew_yaw); } + +void AC_AttitudeControl_Heli::set_notch_sample_rate(float sample_rate) +{ +#if AC_PID_ADVANCED_ENABLED + _pid_rate_roll.set_notch_sample_rate(sample_rate); + _pid_rate_pitch.set_notch_sample_rate(sample_rate); + _pid_rate_yaw.set_notch_sample_rate(sample_rate); +#endif +} \ No newline at end of file diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index c20b2fe5a2aab6..0d519bf87d8f2e 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -33,19 +33,7 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { public: AC_AttitudeControl_Heli( AP_AHRS_View &ahrs, const AP_MultiCopter &aparm, - AP_MotorsHeli& motors) : - AC_AttitudeControl(ahrs, aparm, motors), - _pid_rate_roll(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f), - _pid_rate_pitch(AC_ATC_HELI_RATE_RP_P, AC_ATC_HELI_RATE_RP_I, AC_ATC_HELI_RATE_RP_D, AC_ATC_HELI_RATE_RP_FF, AC_ATC_HELI_RATE_RP_IMAX, AC_ATTITUDE_HELI_RATE_RP_FF_FILTER, AC_ATC_HELI_RATE_RP_FILT_HZ, 0.0f), - _pid_rate_yaw(AC_ATC_HELI_RATE_YAW_P, AC_ATC_HELI_RATE_YAW_I, AC_ATC_HELI_RATE_YAW_D, AC_ATC_HELI_RATE_YAW_FF, AC_ATC_HELI_RATE_YAW_IMAX, AC_ATTITUDE_HELI_RATE_Y_FF_FILTER, AC_ATC_HELI_RATE_YAW_FILT_HZ, 0.0f) - { - AP_Param::setup_object_defaults(this, var_info); - - // initialise flags - _flags_heli.leaky_i = true; - _flags_heli.flybar_passthrough = false; - _flags_heli.tail_passthrough = false; - } + AP_MotorsHeli& motors); // pid accessors AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; } @@ -97,7 +85,10 @@ class AC_AttitudeControl_Heli : public AC_AttitudeControl { void set_inverted_flight(bool inverted) override { _inverted_flight = inverted; } - + + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate) override; + // user settable parameters static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 2254ebd7b6f0a3..99ef248091ec4a 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -2,6 +2,7 @@ #include #include #include +#include // table of user settable parameters const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { @@ -79,6 +80,46 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0 1 // @Increment: 0.01 + + // @Param: RAT_RLL_ADV + // @DisplayName: Roll Advanced parameters enable + // @Description: Roll Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_RLL_D_FF + // @DisplayName: Roll Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_RLL_NTF + // @DisplayName: Roll Target notch Filter center frequency + // @Description: Roll Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NEF + // @DisplayName: Roll Error notch Filter center frequency + // @Description: Roll Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NBW + // @DisplayName: Roll notch Filter bandwidth + // @Description: Roll notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NATT + // @DisplayName: Roll notch Filter attenuation + // @Description: Roll notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Multi, AC_PID), @@ -154,6 +195,46 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0 1 // @Increment: 0.01 + + // @Param: RAT_PIT_ADV + // @DisplayName: Pitch Advanced parameters enable + // @Description: Pitch Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_PIT_D_FF + // @DisplayName: Pitch Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_PIT_NTF + // @DisplayName: Pitch Target notch Filter center frequency + // @Description: Pitch Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NEF + // @DisplayName: Pitch Error notch Filter center frequency + // @Description: Pitch Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NBW + // @DisplayName: Pitch notch Filter bandwidth + // @Description: Pitch notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NATT + // @DisplayName: Pitch notch Filter attenuation + // @Description: Pitch notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Multi, AC_PID), @@ -229,6 +310,46 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0 1 // @Increment: 0.01 + + // @Param: RAT_YAW_ADV + // @DisplayName: Yaw Advanced parameters enable + // @Description: Yaw Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_YAW_D_FF + // @DisplayName: Yaw Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_YAW_NTF + // @DisplayName: Yaw Target notch Filter center frequency + // @Description: Yaw Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NEF + // @DisplayName: Yaw Error notch Filter center frequency + // @Description: Yaw Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NBW + // @DisplayName: Yaw notch Filter bandwidth + // @Description: Yaw notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NATT + // @DisplayName: Yaw notch Filter attenuation + // @Description: Yaw notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Multi, AC_PID), @@ -269,6 +390,10 @@ AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_ _motors_multi(motors) { AP_Param::setup_object_defaults(this, var_info); + +#if AC_PID_ADVANCED_ENABLED + set_notch_sample_rate(AP::scheduler().get_loop_rate_hz()); +#endif } // Update Alt_Hold angle maximum @@ -431,3 +556,12 @@ void AC_AttitudeControl_Multi::parameter_sanity_check() _thr_mix_max.set_and_save(AC_ATTITUDE_CONTROL_MAX_DEFAULT); } } + +void AC_AttitudeControl_Multi::set_notch_sample_rate(float sample_rate) +{ +#if AC_PID_ADVANCED_ENABLED + _pid_rate_roll.set_notch_sample_rate(sample_rate); + _pid_rate_pitch.set_notch_sample_rate(sample_rate); + _pid_rate_yaw.set_notch_sample_rate(sample_rate); +#endif +} diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h index 8c85c666c20cca..c9966cbefd91a7 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h @@ -81,6 +81,9 @@ class AC_AttitudeControl_Multi : public AC_AttitudeControl { // sanity check parameters. should be called once before take-off void parameter_sanity_check() override; + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate) override; + // user settable parameters static const struct AP_Param::GroupInfo var_info[]; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp index cc7f7c566e66c4..71b28013de2493 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp @@ -78,6 +78,46 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Description: Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0 1 // @Increment: 0.01 + + // @Param: RAT_RLL_ADV + // @DisplayName: Roll Advanced parameters enable + // @Description: Roll Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_RLL_D_FF + // @DisplayName: Roll Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_RLL_NTF + // @DisplayName: Roll Target notch Filter center frequency + // @Description: Roll Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NEF + // @DisplayName: Roll Error notch Filter center frequency + // @Description: Roll Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NBW + // @DisplayName: Roll notch Filter bandwidth + // @Description: Roll notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_RLL_NATT + // @DisplayName: Roll notch Filter attenuation + // @Description: Roll notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Sub, AC_PID), @@ -153,6 +193,46 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Description: Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0 1 // @Increment: 0.01 + + // @Param: RAT_PIT_ADV + // @DisplayName: Pitch Advanced parameters enable + // @Description: Pitch Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_PIT_D_FF + // @DisplayName: Pitch Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_PIT_NTF + // @DisplayName: Pitch Target notch Filter center frequency + // @Description: Pitch Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NEF + // @DisplayName: Pitch Error notch Filter center frequency + // @Description: Pitch Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NBW + // @DisplayName: Pitch notch Filter bandwidth + // @Description: Pitch notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_PIT_NATT + // @DisplayName: Pitch notch Filter attenuation + // @Description: Pitch notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Sub, AC_PID), @@ -228,6 +308,46 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Description: Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0 1 // @Increment: 0.01 + + // @Param: RAT_YAW_ADV + // @DisplayName: Yaw Advanced parameters enable + // @Description: Yaw Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: RAT_YAW_D_FF + // @DisplayName: Yaw Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: RAT_YAW_NTF + // @DisplayName: Yaw Target notch Filter center frequency + // @Description: Yaw Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NEF + // @DisplayName: Yaw Error notch Filter center frequency + // @Description: Yaw Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NBW + // @DisplayName: Yaw notch Filter bandwidth + // @Description: Yaw notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: RAT_YAW_NATT + // @DisplayName: Yaw notch Filter attenuation + // @Description: Yaw notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Sub, AC_PID), @@ -429,3 +549,12 @@ void AC_AttitudeControl_Sub::input_euler_angle_roll_pitch_slew_yaw(float euler_r input_euler_angle_roll_pitch_yaw(euler_roll_angle_cd, euler_pitch_angle_cd, euler_yaw_angle_cd, true); } } + +void AC_AttitudeControl_Sub::set_notch_sample_rate(float sample_rate) +{ +#if AC_PID_ADVANCED_ENABLED + _pid_rate_roll.set_notch_sample_rate(sample_rate); + _pid_rate_pitch.set_notch_sample_rate(sample_rate); + _pid_rate_yaw.set_notch_sample_rate(sample_rate); +#endif +} \ No newline at end of file diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h index 18a627a3d7282e..fb69f7094f0d67 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.h @@ -65,6 +65,9 @@ class AC_AttitudeControl_Sub : public AC_AttitudeControl { // sanity check parameters. should be called once before take-off void parameter_sanity_check() override; + // set the PID notch sample rates + void set_notch_sample_rate(float sample_rate) override; + // This function ensures that the ROV reaches the target orientation with the desired yaw rate void input_euler_angle_roll_pitch_slew_yaw(float euler_roll_angle_cd, float euler_pitch_angle_cd, float euler_yaw_angle_cd, float slew_yaw); diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 06eed5ddba4612..c952cbd65ac413 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -209,6 +209,46 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = { // @Description: Acceleration (vertical) controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0 1000 // @Units: d% + + // @Param: _ACCZ_ADV + // @DisplayName: Accel (vertical) Advanced parameters enable + // @Description: Accel (vertical) Advanced parameters enable + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + + // @Param: _ACCZ_D_FF + // @DisplayName: Accel (vertical) Derivative FeedForward Gain + // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target + // @Range: 0 0.02 + // @Increment: 0.0001 + // @User: Advanced + + // @Param: _ACCZ_NTF + // @DisplayName: Accel (vertical) Target notch Filter center frequency + // @Description: Accel (vertical) Target notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _ACCZ_NEF + // @DisplayName: Accel (vertical) Error notch Filter center frequency + // @Description: Accel (vertical) Error notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + + // @Param: _ACCZ_NBW + // @DisplayName: Accel (vertical) notch Filter bandwidth + // @Description: Accel (vertical) notch Filter bandwidth in Hz. + // @Range: 5 250 + // @Units: Hz + // @User: Advanced + + // @Param: _ACCZ_NATT + // @DisplayName: Accel (vertical) notch Filter attenuation + // @Description: Accel (vertical) notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB // @User: Advanced AP_SUBGROUPINFO(_pid_accel_z, "_ACCZ_", 4, AC_PosControl, AC_PID), From e327691540398d2f20e85a01e9aacccd9eb1d63e Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 27 Aug 2023 20:01:23 +0100 Subject: [PATCH 318/499] Rover: update PID notch centers at 1Hz with average loop rate --- Rover/Rover.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index 4b6497382b48dd..82b7f46e371397 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -468,6 +468,7 @@ void Rover::one_second_loop(void) // send latest param values to wp_nav g2.wp_nav.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering()); g2.pos_control.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering()); + g2.wheel_rate_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); } void Rover::update_current_mode(void) From 0d10f74bf71146d863b0e08573b691cd51ab28b4 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 27 Aug 2023 20:01:05 +0100 Subject: [PATCH 319/499] Plane: update PID notch centers at 1Hz with average loop rate --- ArduPlane/ArduPlane.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 61d76425333278..36bc4f5b53e091 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -357,6 +357,16 @@ void Plane::one_second_loop() !is_equal(G_Dt, scheduler.get_loop_period_s())) { INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); } + + const float loop_rate = AP::scheduler().get_filtered_loop_rate_hz(); +#if HAL_QUADPLANE_ENABLED + if (quadplane.available()) { + quadplane.attitude_control->set_notch_sample_rate(loop_rate); + } +#endif + rollController.set_notch_sample_rate(loop_rate); + pitchController.set_notch_sample_rate(loop_rate); + yawController.set_notch_sample_rate(loop_rate); } void Plane::three_hz_loop() From 2442bca9787d8e952953e5add49cb6e3c488b8c5 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 27 Aug 2023 20:01:39 +0100 Subject: [PATCH 320/499] Sub: update PID notch centers at 1Hz with average loop rate --- ArduSub/ArduSub.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index b8ded91fddc343..e8012d2e91f612 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -291,6 +291,9 @@ void Sub::one_hz_loop() // need to set "likely flying" when armed to allow for compass // learning to run set_likely_flying(hal.util->get_soft_armed()); + + attitude_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); + pos_control.get_accel_z_pid().set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); } void Sub::read_AHRS() From 13ff23f39d129e093ba40a387d12a73d4b76d947 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Tue, 19 Sep 2023 17:41:04 +0100 Subject: [PATCH 321/499] AP_HAL: enable filters with AP_FILTER_ENABLED on sitl --- libraries/AP_HAL/board/sitl.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL/board/sitl.h b/libraries/AP_HAL/board/sitl.h index 6f0780a3d657dc..aa2799f09abc63 100644 --- a/libraries/AP_HAL/board/sitl.h +++ b/libraries/AP_HAL/board/sitl.h @@ -82,3 +82,7 @@ #ifndef AP_UART_MONITOR_ENABLED #define AP_UART_MONITOR_ENABLED 1 #endif + +#ifndef AP_FILTER_ENABLED +#define AP_FILTER_ENABLED 1 +#endif From b7a969d46211de506edf1985f949d5430a15c73f Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 1 Oct 2023 18:21:00 +0100 Subject: [PATCH 322/499] AC_AttitudeControl: update for new AC_PID settings enable filters with AP_FILTER_ENABLED --- .../AC_AttitudeControl_Heli.cpp | 105 ++++-------------- .../AC_AttitudeControl_Multi.cpp | 105 ++++-------------- .../AC_AttitudeControl_Sub.cpp | 104 ++++------------- .../AC_AttitudeControl/AC_PosControl.cpp | 34 +----- 4 files changed, 65 insertions(+), 283 deletions(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index 26004c3a13ba69..982ff2048ab881 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -88,12 +88,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @Increment: 0.5 // @User: Advanced - // @Param: RAT_RLL_ADV - // @DisplayName: Roll Advanced parameters enable - // @Description: Roll Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_RLL_D_FF // @DisplayName: Roll Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -102,31 +96,15 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @User: Advanced // @Param: RAT_RLL_NTF - // @DisplayName: Roll Target notch Filter center frequency - // @Description: Roll Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Roll Target notch filter index + // @Description: Roll Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: RAT_RLL_NEF - // @DisplayName: Roll Error notch Filter center frequency - // @Description: Roll Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_RLL_NBW - // @DisplayName: Roll notch Filter bandwidth - // @Description: Roll notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_RLL_NATT - // @DisplayName: Roll notch Filter attenuation - // @Description: Roll notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Roll Error notch filter index + // @Description: Roll Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 2, AC_AttitudeControl_Heli, AC_HELI_PID), @@ -203,12 +181,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @Increment: 0.5 // @User: Advanced - // @Param: RAT_PIT_ADV - // @DisplayName: Pitch Advanced parameters enable - // @Description: Pitch Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_PIT_D_FF // @DisplayName: Pitch Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -217,31 +189,15 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @User: Advanced // @Param: RAT_PIT_NTF - // @DisplayName: Pitch Target notch Filter center frequency - // @Description: Pitch Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Pitch Target notch filter index + // @Description: Pitch Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: RAT_PIT_NEF - // @DisplayName: Pitch Error notch Filter center frequency - // @Description: Pitch Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_PIT_NBW - // @DisplayName: Pitch notch Filter bandwidth - // @Description: Pitch notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_PIT_NATT - // @DisplayName: Pitch notch Filter attenuation - // @Description: Pitch notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Pitch Error notch filter index + // @Description: Pitch Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 3, AC_AttitudeControl_Heli, AC_HELI_PID), @@ -318,12 +274,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @Increment: 0.5 // @User: Advanced - // @Param: RAT_YAW_ADV - // @DisplayName: Yaw Advanced parameters enable - // @Description: Yaw Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_YAW_D_FF // @DisplayName: Yaw Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -332,31 +282,16 @@ const AP_Param::GroupInfo AC_AttitudeControl_Heli::var_info[] = { // @User: Advanced // @Param: RAT_YAW_NTF - // @DisplayName: Yaw Target notch Filter center frequency - // @Description: Yaw Target notch Filter center frequency in Hz. - // @Range: 10 495 + // @DisplayName: Yaw Target notch filter index + // @Description: Yaw Target notch filter index + // @Range: 1 8 // @Units: Hz // @User: Advanced // @Param: RAT_YAW_NEF - // @DisplayName: Yaw Error notch Filter center frequency - // @Description: Yaw Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_YAW_NBW - // @DisplayName: Yaw notch Filter bandwidth - // @Description: Yaw notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_YAW_NATT - // @DisplayName: Yaw notch Filter attenuation - // @Description: Yaw notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Yaw Error notch filter index + // @Description: Yaw Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 4, AC_AttitudeControl_Heli, AC_HELI_PID), @@ -383,7 +318,7 @@ AC_AttitudeControl_Heli::AC_AttitudeControl_Heli(AP_AHRS_View &ahrs, const AP_Mu _flags_heli.leaky_i = true; _flags_heli.flybar_passthrough = false; _flags_heli.tail_passthrough = false; -#if AC_PID_ADVANCED_ENABLED +#if AP_FILTER_ENABLED set_notch_sample_rate(AP::scheduler().get_loop_rate_hz()); #endif } @@ -629,7 +564,7 @@ void AC_AttitudeControl_Heli::input_euler_angle_roll_pitch_yaw(float euler_roll_ void AC_AttitudeControl_Heli::set_notch_sample_rate(float sample_rate) { -#if AC_PID_ADVANCED_ENABLED +#if AP_FILTER_ENABLED _pid_rate_roll.set_notch_sample_rate(sample_rate); _pid_rate_pitch.set_notch_sample_rate(sample_rate); _pid_rate_yaw.set_notch_sample_rate(sample_rate); diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 99ef248091ec4a..947975a0a16868 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -81,12 +81,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Range: 0 1 // @Increment: 0.01 - // @Param: RAT_RLL_ADV - // @DisplayName: Roll Advanced parameters enable - // @Description: Roll Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_RLL_D_FF // @DisplayName: Roll Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -95,31 +89,15 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @User: Advanced // @Param: RAT_RLL_NTF - // @DisplayName: Roll Target notch Filter center frequency - // @Description: Roll Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Roll Target notch filter index + // @Description: Roll Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: RAT_RLL_NEF - // @DisplayName: Roll Error notch Filter center frequency - // @Description: Roll Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_RLL_NBW - // @DisplayName: Roll notch Filter bandwidth - // @Description: Roll notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_RLL_NATT - // @DisplayName: Roll notch Filter attenuation - // @Description: Roll notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Roll Error notch filter index + // @Description: Roll Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Multi, AC_PID), @@ -196,12 +174,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Range: 0 1 // @Increment: 0.01 - // @Param: RAT_PIT_ADV - // @DisplayName: Pitch Advanced parameters enable - // @Description: Pitch Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_PIT_D_FF // @DisplayName: Pitch Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -210,31 +182,15 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @User: Advanced // @Param: RAT_PIT_NTF - // @DisplayName: Pitch Target notch Filter center frequency - // @Description: Pitch Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Pitch Target notch filter index + // @Description: Pitch Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: RAT_PIT_NEF - // @DisplayName: Pitch Error notch Filter center frequency - // @Description: Pitch Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_PIT_NBW - // @DisplayName: Pitch notch Filter bandwidth - // @Description: Pitch notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_PIT_NATT - // @DisplayName: Pitch notch Filter attenuation - // @Description: Pitch notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Pitch Error notch filter index + // @Description: Pitch Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Multi, AC_PID), @@ -311,12 +267,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @Range: 0 1 // @Increment: 0.01 - // @Param: RAT_YAW_ADV - // @DisplayName: Yaw Advanced parameters enable - // @Description: Yaw Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_YAW_D_FF // @DisplayName: Yaw Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -325,31 +275,16 @@ const AP_Param::GroupInfo AC_AttitudeControl_Multi::var_info[] = { // @User: Advanced // @Param: RAT_YAW_NTF - // @DisplayName: Yaw Target notch Filter center frequency - // @Description: Yaw Target notch Filter center frequency in Hz. - // @Range: 10 495 + // @DisplayName: Yaw Target notch filter index + // @Description: Yaw Target notch filter index + // @Range: 1 8 // @Units: Hz // @User: Advanced // @Param: RAT_YAW_NEF - // @DisplayName: Yaw Error notch Filter center frequency - // @Description: Yaw Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_YAW_NBW - // @DisplayName: Yaw notch Filter bandwidth - // @Description: Yaw notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_YAW_NATT - // @DisplayName: Yaw notch Filter attenuation - // @Description: Yaw notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Yaw Error notch filter index + // @Description: Yaw Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Multi, AC_PID), @@ -391,7 +326,7 @@ AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS_View &ahrs, const AP_ { AP_Param::setup_object_defaults(this, var_info); -#if AC_PID_ADVANCED_ENABLED +#if AP_FILTER_ENABLED set_notch_sample_rate(AP::scheduler().get_loop_rate_hz()); #endif } @@ -559,7 +494,7 @@ void AC_AttitudeControl_Multi::parameter_sanity_check() void AC_AttitudeControl_Multi::set_notch_sample_rate(float sample_rate) { -#if AC_PID_ADVANCED_ENABLED +#if AP_FILTER_ENABLED _pid_rate_roll.set_notch_sample_rate(sample_rate); _pid_rate_pitch.set_notch_sample_rate(sample_rate); _pid_rate_yaw.set_notch_sample_rate(sample_rate); diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp index 71b28013de2493..7f2791c241a36f 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Sub.cpp @@ -79,12 +79,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Range: 0 1 // @Increment: 0.01 - // @Param: RAT_RLL_ADV - // @DisplayName: Roll Advanced parameters enable - // @Description: Roll Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_RLL_D_FF // @DisplayName: Roll Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -93,31 +87,15 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @User: Advanced // @Param: RAT_RLL_NTF - // @DisplayName: Roll Target notch Filter center frequency - // @Description: Roll Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Roll Target notch filter index + // @Description: Roll Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: RAT_RLL_NEF - // @DisplayName: Roll Error notch Filter center frequency - // @Description: Roll Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_RLL_NBW - // @DisplayName: Roll notch Filter bandwidth - // @Description: Roll notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_RLL_NATT - // @DisplayName: Roll notch Filter attenuation - // @Description: Roll notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Roll Error notch filter index + // @Description: Roll Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_rate_roll, "RAT_RLL_", 1, AC_AttitudeControl_Sub, AC_PID), @@ -194,12 +172,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Range: 0 1 // @Increment: 0.01 - // @Param: RAT_PIT_ADV - // @DisplayName: Pitch Advanced parameters enable - // @Description: Pitch Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_PIT_D_FF // @DisplayName: Pitch Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -208,31 +180,15 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @User: Advanced // @Param: RAT_PIT_NTF - // @DisplayName: Pitch Target notch Filter center frequency - // @Description: Pitch Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Pitch Target notch filter index + // @Description: Pitch Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: RAT_PIT_NEF - // @DisplayName: Pitch Error notch Filter center frequency - // @Description: Pitch Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_PIT_NBW - // @DisplayName: Pitch notch Filter bandwidth - // @Description: Pitch notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_PIT_NATT - // @DisplayName: Pitch notch Filter attenuation - // @Description: Pitch notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Pitch Error notch filter index + // @Description: Pitch Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_rate_pitch, "RAT_PIT_", 2, AC_AttitudeControl_Sub, AC_PID), @@ -309,12 +265,6 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @Range: 0 1 // @Increment: 0.01 - // @Param: RAT_YAW_ADV - // @DisplayName: Yaw Advanced parameters enable - // @Description: Yaw Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_YAW_D_FF // @DisplayName: Yaw Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -323,31 +273,15 @@ const AP_Param::GroupInfo AC_AttitudeControl_Sub::var_info[] = { // @User: Advanced // @Param: RAT_YAW_NTF - // @DisplayName: Yaw Target notch Filter center frequency - // @Description: Yaw Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Yaw Target notch filter index + // @Description: Yaw Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: RAT_YAW_NEF - // @DisplayName: Yaw Error notch Filter center frequency - // @Description: Yaw Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_YAW_NBW - // @DisplayName: Yaw notch Filter bandwidth - // @Description: Yaw notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_YAW_NATT - // @DisplayName: Yaw notch Filter attenuation - // @Description: Yaw notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Yaw Error notch filter index + // @Description: Yaw Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_rate_yaw, "RAT_YAW_", 3, AC_AttitudeControl_Sub, AC_PID), @@ -552,7 +486,7 @@ void AC_AttitudeControl_Sub::input_euler_angle_roll_pitch_slew_yaw(float euler_r void AC_AttitudeControl_Sub::set_notch_sample_rate(float sample_rate) { -#if AC_PID_ADVANCED_ENABLED +#if AP_FILTER_ENABLED _pid_rate_roll.set_notch_sample_rate(sample_rate); _pid_rate_pitch.set_notch_sample_rate(sample_rate); _pid_rate_yaw.set_notch_sample_rate(sample_rate); diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index c952cbd65ac413..282237fb3a961d 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -210,12 +210,6 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = { // @Range: 0 1000 // @Units: d% - // @Param: _ACCZ_ADV - // @DisplayName: Accel (vertical) Advanced parameters enable - // @Description: Accel (vertical) Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: _ACCZ_D_FF // @DisplayName: Accel (vertical) Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -224,31 +218,15 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = { // @User: Advanced // @Param: _ACCZ_NTF - // @DisplayName: Accel (vertical) Target notch Filter center frequency - // @Description: Accel (vertical) Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Accel (vertical) Target notch filter index + // @Description: Accel (vertical) Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: _ACCZ_NEF - // @DisplayName: Accel (vertical) Error notch Filter center frequency - // @Description: Accel (vertical) Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: _ACCZ_NBW - // @DisplayName: Accel (vertical) notch Filter bandwidth - // @Description: Accel (vertical) notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: _ACCZ_NATT - // @DisplayName: Accel (vertical) notch Filter attenuation - // @Description: Accel (vertical) notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Accel (vertical) Error notch filter index + // @Description: Accel (vertical) Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_accel_z, "_ACCZ_", 4, AC_PosControl, AC_PID), From 560030c9ba18dbeb314ec1f933bedc2b4c563132 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 1 Oct 2023 18:21:00 +0100 Subject: [PATCH 323/499] AC_CustomControl: update for new AC_PID settings enable filters with AP_FILTER_ENABLED --- .../AC_CustomControl/AC_CustomControl.cpp | 2 +- .../AC_CustomControl/AC_CustomControl_PID.cpp | 104 ++++-------------- 2 files changed, 20 insertions(+), 86 deletions(-) diff --git a/libraries/AC_CustomControl/AC_CustomControl.cpp b/libraries/AC_CustomControl/AC_CustomControl.cpp index 26755cbb47f5ac..ada094b691e53a 100644 --- a/libraries/AC_CustomControl/AC_CustomControl.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl.cpp @@ -186,7 +186,7 @@ void AC_CustomControl::log_switch(void) { void AC_CustomControl::set_notch_sample_rate(float sample_rate) { -#if AC_PID_ADVANCED_ENABLED +#if AP_FILTER_ENABLED if (_backend != nullptr) { _backend->set_notch_sample_rate(sample_rate); } diff --git a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp index 61ae0fb2a76fcf..ddf6a40c6b4e0f 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp @@ -102,12 +102,6 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @Increment: 0.01 // @User: Advanced - // @Param: RAT_RLL_ADV - // @DisplayName: Roll Advanced parameters enable - // @Description: Roll Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_RLL_D_FF // @DisplayName: Roll Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -116,31 +110,15 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @User: Advanced // @Param: RAT_RLL_NTF - // @DisplayName: Roll Target notch Filter center frequency - // @Description: Roll Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Roll Target notch filter index + // @Description: Roll Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: RAT_RLL_NEF - // @DisplayName: Roll Error notch Filter center frequency - // @Description: Roll Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_RLL_NBW - // @DisplayName: Roll notch Filter bandwidth - // @Description: Roll notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_RLL_NATT - // @DisplayName: Roll notch Filter attenuation - // @Description: Roll notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Roll Error notch filter index + // @Description: Roll Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_atti_rate_roll, "RAT_RLL_", 4, AC_CustomControl_PID, AC_PID), @@ -218,12 +196,6 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @Increment: 0.01 // @User: Advanced - // @Param: RAT_PIT_ADV - // @DisplayName: Pitch Advanced parameters enable - // @Description: Pitch Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_PIT_D_FF // @DisplayName: Pitch Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -232,31 +204,15 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @User: Advanced // @Param: RAT_PIT_NTF - // @DisplayName: Pitch Target notch Filter center frequency - // @Description: Pitch Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Pitch Target notch filter index + // @Description: Pitch Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: RAT_PIT_NEF - // @DisplayName: Pitch Error notch Filter center frequency - // @Description: Pitch Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_PIT_NBW - // @DisplayName: Pitch notch Filter bandwidth - // @Description: Pitch notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_PIT_NATT - // @DisplayName: Pitch notch Filter attenuation - // @Description: Pitch notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Pitch Error notch filter index + // @Description: Pitch Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_atti_rate_pitch, "RAT_PIT_", 5, AC_CustomControl_PID, AC_PID), @@ -335,12 +291,6 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @Increment: 0.01 // @User: Advanced - // @Param: RAT_YAW_ADV - // @DisplayName: Yaw Advanced parameters enable - // @Description: Yaw Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: RAT_YAW_D_FF // @DisplayName: Yaw Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -349,31 +299,15 @@ const AP_Param::GroupInfo AC_CustomControl_PID::var_info[] = { // @User: Advanced // @Param: RAT_YAW_NTF - // @DisplayName: Yaw Target notch Filter center frequency - // @Description: Yaw Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Yaw Target notch filter index + // @Description: Yaw Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: RAT_YAW_NEF - // @DisplayName: Yaw Error notch Filter center frequency - // @Description: Yaw Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_YAW_NBW - // @DisplayName: Yaw notch Filter bandwidth - // @Description: Yaw notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: RAT_YAW_NATT - // @DisplayName: Yaw notch Filter attenuation - // @Description: Yaw notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Yaw Error notch filter index + // @Description: Yaw Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pid_atti_rate_yaw, "RAT_YAW_", 6, AC_CustomControl_PID, AC_PID), @@ -461,7 +395,7 @@ void AC_CustomControl_PID::reset(void) void AC_CustomControl_PID::set_notch_sample_rate(float sample_rate) { -#if AC_PID_ADVANCED_ENABLED +#if AP_FILTER_ENABLED _pid_atti_rate_roll.set_notch_sample_rate(sample_rate); _pid_atti_rate_pitch.set_notch_sample_rate(sample_rate); _pid_atti_rate_yaw.set_notch_sample_rate(sample_rate); From fc76312fc39e18322cf38d161a84cb51ab4d8e25 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 1 Oct 2023 18:21:00 +0100 Subject: [PATCH 324/499] AC_PID: use AP_Filter for notch configuration enable filters with AP_FILTER_ENABLED dynamically allocate notches remove load/save for notches, update docs move feedfoward update to update_all() restrict load_gains() and save_gains() to just what autotune needs add D_FF logging --- libraries/AC_PID/AC_HELI_PID.cpp | 48 +++------- libraries/AC_PID/AC_PID.cpp | 146 +++++++++++-------------------- libraries/AC_PID/AC_PID.h | 22 ++--- libraries/AC_PID/AP_PIDInfo.h | 1 + 4 files changed, 75 insertions(+), 142 deletions(-) diff --git a/libraries/AC_PID/AC_HELI_PID.cpp b/libraries/AC_PID/AC_HELI_PID.cpp index 14dbd97b60c3cd..0e599a160c5983 100644 --- a/libraries/AC_PID/AC_HELI_PID.cpp +++ b/libraries/AC_PID/AC_HELI_PID.cpp @@ -69,13 +69,11 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] = { // @User: Advanced AP_GROUPINFO("SMAX", 12, AC_HELI_PID, _slew_rate_max, 0), -#if AC_PID_ADVANCED_ENABLED - // @Param: ADV - // @DisplayName: Advanced parameters enable - // @Description: Advanced parameters enable - // @Values: 0:Disabled,1:Enabled + // @Param: PDMX + // @DisplayName: PD sum maximum + // @Description: The maximum/minimum value that the sum of the P and D term can output // @User: Advanced - AP_GROUPINFO_FLAGS("ADV", 32, AC_HELI_PID, _adv_enable, 0, AP_PARAM_FLAG_ENABLE), + AP_GROUPINFO("PDMX", 13, AC_HELI_PID, _kpdmax, 0), // @Param: D_FF // @DisplayName: PID Derivative FeedForward Gain @@ -83,40 +81,22 @@ const AP_Param::GroupInfo AC_HELI_PID::var_info[] = { // @Range: 0 0.02 // @Increment: 0.0001 // @User: Advanced - AP_GROUPINFO("D_FF", 33, AC_HELI_PID, _kdff, 0), + AP_GROUPINFO("D_FF", 14, AC_HELI_PID, _kdff, 0), +#if AP_FILTER_ENABLED // @Param: NTF - // @DisplayName: PID Target notch Filter center frequency - // @Description: PID Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: PID Target notch filter index + // @Description: PID Target notch filter index + // @Range: 1 8 // @User: Advanced - AP_GROUPINFO("NTF", 34, AC_HELI_PID, _notch_T_center_freq_hz, 0), + AP_GROUPINFO("NTF", 15, AC_HELI_PID, _notch_T_filter, 0), // @Param: NEF - // @DisplayName: PID Error notch Filter center frequency - // @Description: PID Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - AP_GROUPINFO("NEF", 35, AC_HELI_PID, _notch_E_center_freq_hz, 0), - - // @Param: NBW - // @DisplayName: PID notch Filter bandwidth - // @Description: PID notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - AP_GROUPINFO("NBW", 36, AC_HELI_PID, _notch_bandwidth_hz, 0), - - // @Param: NATT - // @DisplayName: PID notch Filter attenuation - // @Description: PID notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: PID Error notch filter index + // @Description: PID Error notch filter index + // @Range: 1 8 // @User: Advanced - AP_GROUPINFO("NATT", 37, AC_HELI_PID, _notch_attenuation_dB, 40), - + AP_GROUPINFO("NEF", 16, AC_HELI_PID, _notch_E_filter, 0), #endif AP_GROUPEND diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index fcb2406cfe1ff3..557b6b5bfbf146 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -72,54 +72,28 @@ const AP_Param::GroupInfo AC_PID::var_info[] = { // @User: Advanced AP_GROUPINFO("PDMX", 13, AC_PID, _kpdmax, 0), -#if AC_PID_ADVANCED_ENABLED - // @Param: ADV - // @DisplayName: Advanced parameters enable - // @Description: Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - AP_GROUPINFO_FLAGS("ADV", 32, AC_PID, _adv_enable, 0, AP_PARAM_FLAG_ENABLE), - // @Param: D_FF // @DisplayName: PID Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target // @Range: 0 0.02 // @Increment: 0.0001 // @User: Advanced - AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D_FF", 33, AC_PID, _kdff, default_kdff), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D_FF", 14, AC_PID, _kdff, default_kdff), +#if AP_FILTER_ENABLED // @Param: NTF - // @DisplayName: PID Target notch Filter center frequency - // @Description: PID Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: PID Target notch filter index + // @Description: PID Target notch filter index + // @Range: 1 8 // @User: Advanced - AP_GROUPINFO("NTF", 34, AC_PID, _notch_T_center_freq_hz, 0), + AP_GROUPINFO("NTF", 15, AC_PID, _notch_T_filter, 0), // @Param: NEF - // @DisplayName: PID Error notch Filter center frequency - // @Description: PID Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: PID Error notch filter index + // @Description: PID Error notch filter index + // @Range: 1 8 // @User: Advanced - AP_GROUPINFO("NEF", 35, AC_PID, _notch_E_center_freq_hz, 0), - - // @Param: NBW - // @DisplayName: PID notch Filter bandwidth - // @Description: PID notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - AP_GROUPINFO("NBW", 36, AC_PID, _notch_bandwidth_hz, 0), - - // @Param: NATT - // @DisplayName: PID notch Filter attenuation - // @Description: PID notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB - // @User: Advanced - AP_GROUPINFO("NATT", 37, AC_PID, _notch_attenuation_dB, 40), - + AP_GROUPINFO("NEF", 16, AC_PID, _notch_E_filter, 0), #endif AP_GROUPEND @@ -181,20 +155,33 @@ void AC_PID::slew_limit(float smax) void AC_PID::set_notch_sample_rate(float sample_rate) { -#if AC_PID_ADVANCED_ENABLED - if (!_adv_enable) { +#if AP_FILTER_ENABLED + if (_notch_T_filter == 0 && _notch_E_filter == 0) { return; } - if (!is_zero(_notch_T_center_freq_hz.get()) && - (!is_equal(sample_rate, _target_notch.sample_freq_hz()) - || !is_equal(_notch_T_center_freq_hz.get(), _target_notch.center_freq_hz()))) { - _target_notch.init(sample_rate, _notch_T_center_freq_hz, _notch_bandwidth_hz, _notch_attenuation_dB); + if (_notch_T_filter != 0) { + if (_target_notch == nullptr) { + _target_notch = new NotchFilterFloat(); + } + AP_Filter* filter = AP::filters().get_filter(_notch_T_filter); + if (filter != nullptr && !filter->setup_notch_filter(*_target_notch, sample_rate)) { + delete _target_notch; + _target_notch = nullptr; + _notch_T_filter.set(0); + } } - if (!is_zero(_notch_E_center_freq_hz.get()) && - (!is_equal(sample_rate, _error_notch.sample_freq_hz()) - || !is_equal(_notch_E_center_freq_hz.get(), _error_notch.center_freq_hz()))) { - _error_notch.init(sample_rate, _notch_E_center_freq_hz, _notch_bandwidth_hz, _notch_attenuation_dB); + + if (_notch_E_filter != 0) { + if (_error_notch == nullptr) { + _error_notch = new NotchFilterFloat(); + } + AP_Filter* filter = AP::filters().get_filter(_notch_E_filter); + if (filter != nullptr && !filter->setup_notch_filter(*_error_notch, sample_rate)) { + delete _error_notch; + _error_notch = nullptr; + _notch_E_filter.set(0); + } } #endif } @@ -217,31 +204,27 @@ float AC_PID::update_all(float target, float measurement, float dt, bool limit, _error = _target - measurement; _derivative = 0.0f; _target_derivative = 0.0f; -#if AC_PID_ADVANCED_ENABLED - if (_adv_enable) { - if (!is_zero(_notch_T_center_freq_hz.get())) { - _target_notch.reset(); - _target = _target_notch.apply(_target); - } - if (!is_zero(_notch_E_center_freq_hz.get())) { - _error_notch.reset(); - _error = _error_notch.apply(_error); - } +#if AP_FILTER_ENABLED + if (_target_notch != nullptr) { + _target_notch->reset(); + _target = _target_notch->apply(_target); + } + if (_error_notch != nullptr) { + _error_notch->reset(); + _error = _error_notch->apply(_error); } #endif } else { float error_last = _error; float target_last = _target; float error = _target - measurement; -#if AC_PID_ADVANCED_ENABLED - if (_adv_enable) { - // apply notch filters before FTLD/FLTE to avoid shot noise - if (!is_zero(_notch_T_center_freq_hz.get())) { - target = _target_notch.apply(target); - } - if (!is_zero(_notch_E_center_freq_hz.get())) { - error = _error_notch.apply(error); - } +#if AP_FILTER_ENABLED + // apply notch filters before FTLD/FLTE to avoid shot noise + if (_target_notch != nullptr) { + target = _target_notch->apply(target); + } + if (_error_notch != nullptr) { + error = _error_notch->apply(error); } #endif _target += get_filt_T_alpha(dt) * (target - _target); @@ -289,6 +272,8 @@ float AC_PID::update_all(float target, float measurement, float dt, bool limit, _pid_info.error = _error; _pid_info.P = P_out; _pid_info.D = D_out; + _pid_info.FF = _target * _kff; + _pid_info.DFF = _target_derivative * _kdff; return P_out + D_out + _integrator; } @@ -353,12 +338,7 @@ float AC_PID::get_d() const float AC_PID::get_ff() { - _pid_info.FF = _target * _kff -#if AC_PID_ADVANCED_ENABLED - + _target_derivative * _kdff -#endif - ; - return _pid_info.FF; + return _pid_info.FF + _pid_info.DFF; } void AC_PID::reset_I() @@ -366,46 +346,28 @@ void AC_PID::reset_I() _integrator = 0.0; } +// load original gains from eeprom, used by autotune to restore gains after tuning void AC_PID::load_gains() { _kp.load(); _ki.load(); _kd.load(); _kff.load(); - _kimax.load(); - _kimax.set(fabsf(_kimax)); - _kpdmax.load(); - _kpdmax.set(fabsf(_kpdmax)); _filt_T_hz.load(); _filt_E_hz.load(); _filt_D_hz.load(); -#if AC_PID_ADVANCED_ENABLED - _kdff.load(); - _notch_T_center_freq_hz.load(); - _notch_E_center_freq_hz.load(); - _notch_bandwidth_hz.load(); - _notch_attenuation_dB.load(); -#endif } -// save_gains - save gains to eeprom +// save original gains to eeprom, used by autotune to save gains before tuning void AC_PID::save_gains() { _kp.save(); _ki.save(); _kd.save(); _kff.save(); - _kimax.save(); _filt_T_hz.save(); _filt_E_hz.save(); _filt_D_hz.save(); -#if AC_PID_ADVANCED_ENABLED - _kdff.save(); - _notch_T_center_freq_hz.save(); - _notch_E_center_freq_hz.save(); - _notch_bandwidth_hz.save(); - _notch_attenuation_dB.save(); -#endif } /// Overload the function call operator to permit easy initialisation @@ -419,9 +381,7 @@ void AC_PID::operator()(float p_val, float i_val, float d_val, float ff_val, flo _filt_T_hz.set(input_filt_T_hz); _filt_E_hz.set(input_filt_E_hz); _filt_D_hz.set(input_filt_D_hz); -#if AC_PID_ADVANCED_ENABLED _kdff.set(dff_val); -#endif } // get_filt_T_alpha - get the target filter alpha diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index 30300d071d5a4e..0aa7e35e2c9508 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -9,16 +9,13 @@ #include #include #include +#include #define AC_PID_TFILT_HZ_DEFAULT 0.0f // default input filter frequency #define AC_PID_EFILT_HZ_DEFAULT 0.0f // default input filter frequency #define AC_PID_DFILT_HZ_DEFAULT 20.0f // default input filter frequency #define AC_PID_RESET_TC 0.16f // Time constant for integrator reset decay to zero -#ifndef AC_PID_ADVANCED_ENABLED -#define AC_PID_ADVANCED_ENABLED 0 -#endif - #include "AP_PIDInfo.h" /// @class AC_PID @@ -153,10 +150,8 @@ class AC_PID { const AP_PIDInfo& get_pid_info(void) const { return _pid_info; } -#if AC_PID_ADVANCED_ENABLED AP_Float &kDff() { return _kdff; } void kDff(const float v) { _kdff.set(v); } -#endif void set_notch_sample_rate(float); // parameter var table static const struct AP_Param::GroupInfo var_info[]; @@ -180,13 +175,10 @@ class AC_PID { AP_Float _filt_E_hz; // PID error filter frequency in Hz AP_Float _filt_D_hz; // PID derivative filter frequency in Hz AP_Float _slew_rate_max; -#if AC_PID_ADVANCED_ENABLED - AP_Int8 _adv_enable; AP_Float _kdff; - AP_Float _notch_T_center_freq_hz; - AP_Float _notch_E_center_freq_hz; - AP_Float _notch_bandwidth_hz; - AP_Float _notch_attenuation_dB; +#if AP_FILTER_ENABLED + AP_Int8 _notch_T_filter; + AP_Int8 _notch_E_filter; #endif SlewLimiter _slew_limiter{_slew_rate_max, _slew_rate_tau}; @@ -202,9 +194,9 @@ class AC_PID { float _derivative; // derivative value to enable filtering int8_t _slew_limit_scale; float _target_derivative; // target derivative value to enable dff -#if AC_PID_ADVANCED_ENABLED - NotchFilterFloat _target_notch; - NotchFilterFloat _error_notch; +#if AP_FILTER_ENABLED + NotchFilterFloat* _target_notch; + NotchFilterFloat* _error_notch; #endif AP_PIDInfo _pid_info; diff --git a/libraries/AC_PID/AP_PIDInfo.h b/libraries/AC_PID/AP_PIDInfo.h index 4ba52fe37d8546..70afb0974e01ce 100644 --- a/libraries/AC_PID/AP_PIDInfo.h +++ b/libraries/AC_PID/AP_PIDInfo.h @@ -14,6 +14,7 @@ struct AP_PIDInfo { float I; float D; float FF; + float DFF; float Dmod; float slew_rate; bool limit; From cfebae5857083a66e11f456bf5f28f0450a59755 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 1 Oct 2023 18:21:01 +0100 Subject: [PATCH 325/499] APM_Control: update for new AC_PID settings enable filters with AP_FILTER_ENABLED --- libraries/APM_Control/AP_PitchController.cpp | 36 +---- libraries/APM_Control/AP_RollController.cpp | 36 +---- libraries/APM_Control/AP_YawController.cpp | 36 +---- libraries/APM_Control/AR_AttitudeControl.cpp | 146 ++++--------------- 4 files changed, 50 insertions(+), 204 deletions(-) diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index c093d2d40e18f8..85689d1dce10d2 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -137,45 +137,23 @@ const AP_Param::GroupInfo AP_PitchController::var_info[] = { // @Range: 0 1 // @Increment: 0.01 - // @Param: _RATE_ADV - // @DisplayName: Pitch Advanced parameters enable - // @Description: Pitch Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: _RATE_D_FF // @DisplayName: Pitch Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target - // @Range: 0.001 0.03 + // @Range: 0 0.03 // @Increment: 0.001 // @User: Advanced // @Param: _RATE_NTF - // @DisplayName: Pitch Target notch Filter center frequency - // @Description: Pitch Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Pitch Target notch filter index + // @Description: Pitch Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: _RATE_NEF - // @DisplayName: Pitch Error notch Filter center frequency - // @Description: Pitch Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: _RATE_NBW - // @DisplayName: Pitch notch Filter bandwidth - // @Description: Pitch notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: _RATE_NATT - // @DisplayName: Pitch notch Filter attenuation - // @Description: Pitch notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Pitch Error notch filter index + // @Description: Pitch Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(rate_pid, "_RATE_", 11, AP_PitchController, AC_PID), diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index 0cd9e7076a8135..2ec7efd6c1ae25 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -120,45 +120,23 @@ const AP_Param::GroupInfo AP_RollController::var_info[] = { // @Range: 0 1 // @Increment: 0.01 - // @Param: _RATE_ADV - // @DisplayName: Roll Advanced parameters enable - // @Description: Roll Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: _RATE_D_FF // @DisplayName: Roll Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target - // @Range: 0.001 0.03 + // @Range: 0 0.03 // @Increment: 0.001 // @User: Advanced // @Param: _RATE_NTF - // @DisplayName: Roll Target notch Filter center frequency - // @Description: Roll Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Roll Target notch filter index + // @Description: Roll Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: _RATE_NEF - // @DisplayName: Roll Error notch Filter center frequency - // @Description: Roll Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: _RATE_NBW - // @DisplayName: Roll notch Filter bandwidth - // @Description: Roll notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: _RATE_NATT - // @DisplayName: Roll notch Filter attenuation - // @Description: Roll notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Roll Error notch filter index + // @Description: Roll Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_RollController, AC_PID), diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index 04fc1890bef7d8..af60641e062be6 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -151,45 +151,23 @@ const AP_Param::GroupInfo AP_YawController::var_info[] = { // @Range: 0 1 // @Increment: 0.01 - // @Param: _RATE_ADV - // @DisplayName: Yaw Advanced parameters enable - // @Description: Yaw Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: _RATE_D_FF // @DisplayName: Yaw Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target - // @Range: 0.001 0.03 + // @Range: 0 0.03 // @Increment: 0.001 // @User: Advanced // @Param: _RATE_NTF - // @DisplayName: Yaw Target notch Filter center frequency - // @Description: Yaw Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Yaw Target notch filter index + // @Description: Yaw Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: _RATE_NEF - // @DisplayName: Yaw Error notch Filter center frequency - // @Description: Yaw Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: _RATE_NBW - // @DisplayName: Yaw notch Filter bandwidth - // @Description: Yaw notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: _RATE_NATT - // @DisplayName: Yaw notch Filter attenuation - // @Description: Yaw notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Yaw Error notch filter index + // @Description: Yaw Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(rate_pid, "_RATE_", 9, AP_YawController, AC_PID), diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index 140f8a832deff2..67f12c20e946af 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -147,45 +147,23 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Range: 0.000 1.000 // @Increment: 0.01 - // @Param: _STR_RAT_ADV - // @DisplayName: Steering control Advanced parameters enable - // @Description: Steering control Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: _STR_RAT_D_FF // @DisplayName: Steering control Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target - // @Range: 0.001 0.03 + // @Range: 0 0.03 // @Increment: 0.001 // @User: Advanced // @Param: _STR_RAT_NTF - // @DisplayName: Steering control Target notch Filter center frequency - // @Description: Steering control Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Steering control Target notch filter index + // @Description: Steering control Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: _STR_RAT_NEF - // @DisplayName: Steering control Error notch Filter center frequency - // @Description: Steering control Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: _STR_RAT_NBW - // @DisplayName: Steering control notch Filter bandwidth - // @Description: Steering control notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: _STR_RAT_NATT - // @DisplayName: Steering control notch Filter attenuation - // @Description: Steering control notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Steering control Error notch filter index + // @Description: Steering control Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_steer_rate_pid, "_STR_RAT_", 1, AR_AttitudeControl, AC_PID), @@ -270,45 +248,23 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Range: 0.000 1.000 // @Increment: 0.01 - // @Param: _SPEED_ADV - // @DisplayName: Speed control Advanced parameters enable - // @Description: Speed control Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: _SPEED_D_FF // @DisplayName: Speed control Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target - // @Range: 0.001 0.03 + // @Range: 0 0.03 // @Increment: 0.001 // @User: Advanced // @Param: _SPEED_NTF - // @DisplayName: Speed control Target notch Filter center frequency - // @Description: Speed control Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Speed control Target notch filter index + // @Description: Speed control Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: _SPEED_NEF - // @DisplayName: Speed control Error notch Filter center frequency - // @Description: Speed control Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: _SPEED_NBW - // @DisplayName: Speed control notch Filter bandwidth - // @Description: Speed control notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: _SPEED_NATT - // @DisplayName: Speed control notch Filter attenuation - // @Description: Speed control notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Speed control Error notch filter index + // @Description: Speed control Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_throttle_speed_pid, "_SPEED_", 2, AR_AttitudeControl, AC_PID), @@ -453,45 +409,23 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Range: 0.000 1.000 // @Increment: 0.01 - // @Param: _BAL_ADV - // @DisplayName: Pitch control Advanced parameters enable - // @Description: Pitch control Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: _BAL_D_FF // @DisplayName: Pitch control Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target - // @Range: 0.001 0.03 + // @Range: 0 0.03 // @Increment: 0.001 // @User: Advanced // @Param: _BAL_NTF - // @DisplayName: Pitch control Target notch Filter center frequency - // @Description: Pitch control Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Pitch control Target notch filter index + // @Description: Pitch control Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: _BAL_NEF - // @DisplayName: Pitch control Error notch Filter center frequency - // @Description: Pitch control Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: _BAL_NBW - // @DisplayName: Pitch control notch Filter bandwidth - // @Description: Pitch control notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: _BAL_NATT - // @DisplayName: Pitch control notch Filter attenuation - // @Description: Pitch control notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Pitch control Error notch filter index + // @Description: Pitch control Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_pitch_to_throttle_pid, "_BAL_", 10, AR_AttitudeControl, AC_PID), @@ -584,45 +518,23 @@ const AP_Param::GroupInfo AR_AttitudeControl::var_info[] = { // @Range: 0.000 1.000 // @Increment: 0.01 - // @Param: _SAIL_ADV - // @DisplayName: Sail Heel Advanced parameters enable - // @Description: Sail Heel Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: _SAIL_D_FF // @DisplayName: Sail Heel Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target - // @Range: 0.001 0.03 + // @Range: 0 0.03 // @Increment: 0.001 // @User: Advanced // @Param: _SAIL_NTF - // @DisplayName: Sail Heel Target notch Filter center frequency - // @Description: Sail Heel Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Sail Heel Target notch filter index + // @Description: Sail Heel Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: _SAIL_NEF - // @DisplayName: Sail Heel Error notch Filter center frequency - // @Description: Sail Heel Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: _SAIL_NBW - // @DisplayName: Sail Heel notch Filter bandwidth - // @Description: Sail Heel notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: _SAIL_NATT - // @DisplayName: Sail Heel notch Filter attenuation - // @Description: Sail Heel notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Sail Heel Error notch filter index + // @Description: Sail Heel Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_sailboat_heel_pid, "_SAIL_", 12, AR_AttitudeControl, AC_PID), @@ -1167,7 +1079,7 @@ void AR_AttitudeControl::relax_I() void AR_AttitudeControl::set_notch_sample_rate(float sample_rate) { -#if AC_PID_ADVANCED_ENABLED +#if AP_FILTER_ENABLED _steer_rate_pid.set_notch_sample_rate(sample_rate); _throttle_speed_pid.set_notch_sample_rate(sample_rate); _pitch_to_throttle_pid.set_notch_sample_rate(sample_rate); From 5b0f30ad4487fb090ce1c3f6f2c196c9f4c91e6d Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 1 Oct 2023 18:21:01 +0100 Subject: [PATCH 326/499] AP_WheelEncoder: update for new AC_PID settings enable filters with AP_FILTER_ENABLED --- .../AP_WheelEncoder/AP_WheelRateControl.cpp | 70 ++++--------------- 1 file changed, 13 insertions(+), 57 deletions(-) diff --git a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp index 0edf03fe9db835..97c9a1e19c5e16 100644 --- a/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp +++ b/libraries/AP_WheelEncoder/AP_WheelRateControl.cpp @@ -91,12 +91,6 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = { // @Description: Wheel rate control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0.000 1.000 - // @Param: _RATE_ADV - // @DisplayName: Wheel rate Advanced parameters enable - // @Description: Wheel rate Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: _RATE_D_FF // @DisplayName: Wheel rate Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the error @@ -105,31 +99,15 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = { // @User: Advanced // @Param: _RATE_NTF - // @DisplayName: Wheel rate Target notch Filter center frequency - // @Description: Wheel rate Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Wheel rate Target notch filter index + // @Description: Wheel rate Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: _RATE_NEF - // @DisplayName: Wheel rate Error notch Filter center frequency - // @Description: Wheel rate Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: _RATE_NBW - // @DisplayName: Wheel rate notch Filter bandwidth - // @Description: Wheel rate notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: _RATE_NATT - // @DisplayName: Wheel rate notch Filter attenuation - // @Description: Wheel rate notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Wheel rate Error notch filter index + // @Description: Wheel rate Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_rate_pid0, "_RATE_", 3, AP_WheelRateControl, AC_PID), @@ -207,12 +185,6 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = { // @Description: Wheel rate control PD sum maximum. The maximum/minimum value that the sum of the P and D term can output // @Range: 0.000 1.000 - // @Param: 2_RATE_ADV - // @DisplayName: Wheel rate Advanced parameters enable - // @Description: Wheel rate Advanced parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: 2_RATE_D_FF // @DisplayName: Wheel rate Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target @@ -221,31 +193,15 @@ const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = { // @User: Advanced // @Param: 2_RATE_NTF - // @DisplayName: Wheel rate Target notch Filter center frequency - // @Description: Wheel rate Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Wheel rate Target notch filter index + // @Description: Wheel rate Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: 2_RATE_NEF - // @DisplayName: Wheel rate Error notch Filter center frequency - // @Description: Wheel rate Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: 2_RATE_NBW - // @DisplayName: Wheel rate notch Filter bandwidth - // @Description: Wheel rate notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: 2_RATE_NATT - // @DisplayName: Wheel rate notch Filter attenuation - // @Description: Wheel rate notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Wheel rate Error notch filter index + // @Description: Wheel rate Error notch filter index + // @Range: 1 8 // @User: Advanced AP_SUBGROUPINFO(_rate_pid1, "2_RATE_", 4, AP_WheelRateControl, AC_PID), @@ -320,7 +276,7 @@ AC_PID& AP_WheelRateControl::get_pid(uint8_t instance) void AP_WheelRateControl::set_notch_sample_rate(float sample_rate) { -#if AC_PID_ADVANCED_ENABLED +#if AP_FILTER_ENABLED _rate_pid0.set_notch_sample_rate(sample_rate); _rate_pid1.set_notch_sample_rate(sample_rate); #endif From 4c1c01f571575ca17b9153072ce729dc1f830d8f Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 1 Oct 2023 18:21:01 +0100 Subject: [PATCH 327/499] Tracker: update for new AC_PID settings --- AntennaTracker/Parameters.cpp | 72 +++++++---------------------------- 1 file changed, 14 insertions(+), 58 deletions(-) diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index b9c48d4e9a117b..79d1739ed21f0f 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -387,45 +387,23 @@ const AP_Param::Info Tracker::var_info[] = { // @Units: d% // @User: Advanced - // @Param: PITCH2SRV_ADV - // @DisplayName: Advanced Pitch parameters enable - // @Description: Advanced Pitch parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: PITCH2SRV_D_FF // @DisplayName: Pitch Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target - // @Range: 0.001 0.1 + // @Range: 0 0.1 // @Increment: 0.001 // @User: Advanced // @Param: PITCH2SRV_NTF - // @DisplayName: Pitch Target notch Filter center frequency - // @Description: Pitch Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Pitch Target notch filter index + // @Description: Pitch Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: PITCH2SRV_NEF - // @DisplayName: Pitch Error notch Filter center frequency - // @Description: Pitch Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: PITCH2SRV_NBW - // @DisplayName: Pitch notch Filter bandwidth - // @Description: Pitch notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: PITCH2SRV_NATT - // @DisplayName: Pitch notch Filter attenuation - // @Description: Pitch notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Pitch Error notch filter index + // @Description: Pitch Error notch filter index + // @Range: 1 8 // @User: Advanced GGROUP(pidPitch2Srv, "PITCH2SRV_", AC_PID), @@ -505,45 +483,23 @@ const AP_Param::Info Tracker::var_info[] = { // @Units: d% // @User: Advanced - // @Param: YAW2SRV_ADV - // @DisplayName: Advanced Yaw parameters enable - // @Description: Advanced Yaw parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: YAW2SRV_D_FF // @DisplayName: Yaw Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target - // @Range: 0.001 0.1 + // @Range: 0 0.1 // @Increment: 0.001 // @User: Advanced // @Param: YAW2SRV_NTF - // @DisplayName: Yaw Target notch Filter center frequency - // @Description: Yaw Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Yaw Target notch filter index + // @Description: Yaw Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: YAW2SRV_NEF - // @DisplayName: Yaw Error notch Filter center frequency - // @Description: Yaw Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: YAW2SRV_NBW - // @DisplayName: Yaw notch Filter bandwidth - // @Description: Yaw notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: YAW2SRV_NATT - // @DisplayName: Yaw notch Filter attenuation - // @Description: Yaw notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Yaw Error notch filter index + // @Description: Yaw Error notch filter index + // @Range: 1 8 // @User: Advanced GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID), From 97a4eed232cbce51107fa93e0edda31b7b2295eb Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 1 Oct 2023 18:21:01 +0100 Subject: [PATCH 328/499] Blimp: update for new AC_PID settings D_FF logging docs --- Blimp/Log.cpp | 1 + Blimp/Parameters.cpp | 36 +++++++----------------------------- 2 files changed, 8 insertions(+), 29 deletions(-) diff --git a/Blimp/Log.cpp b/Blimp/Log.cpp index 01a3e0f3e7b293..17c3161faba385 100644 --- a/Blimp/Log.cpp +++ b/Blimp/Log.cpp @@ -280,6 +280,7 @@ const struct LogStructure Blimp::log_structure[] = { // @Field: I: integral part of PID // @Field: D: derivative part of PID // @Field: FF: controller feed-forward portion of response + // @Field: DFF: controller derivative feed-forward portion of response // @Field: Dmod: scaler applied to D gain to reduce limit cycling // @Field: SRate: slew rate // @Field: Flags: bitmask of PID state flags diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index aab8caeadccf95..26971ef2e65392 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -730,45 +730,23 @@ const AP_Param::Info Blimp::var_info[] = { // @Units: d% // @User: Advanced - // @Param: POSYAW_ADV - // @DisplayName: Advanced Yaw parameters enable - // @Description: Advanced Yaw parameters enable - // @Values: 0:Disabled,1:Enabled - // @User: Advanced - // @Param: POSYAW_D_FF // @DisplayName: Position (yaw) Derivative FeedForward Gain // @Description: FF D Gain which produces an output that is proportional to the rate of change of the target - // @Range: 0.001 0.1 + // @Range: 0 0.1 // @Increment: 0.001 // @User: Advanced // @Param: POSYAW_NTF - // @DisplayName: Position (yaw) Target notch Filter center frequency - // @Description: Position (yaw) Target notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz + // @DisplayName: Position (yaw) Target notch filter index + // @Description: Position (yaw) Target notch filter index + // @Range: 1 8 // @User: Advanced // @Param: POSYAW_NEF - // @DisplayName: Position (yaw) Error notch Filter center frequency - // @Description: Position (yaw) Error notch Filter center frequency in Hz. - // @Range: 10 495 - // @Units: Hz - // @User: Advanced - - // @Param: POSYAW_NBW - // @DisplayName: Position (yaw) notch Filter bandwidth - // @Description: Position (yaw) notch Filter bandwidth in Hz. - // @Range: 5 250 - // @Units: Hz - // @User: Advanced - - // @Param: POSYAW_NATT - // @DisplayName: Position (yaw) notch Filter attenuation - // @Description: Position (yaw) notch Filter attenuation in dB. - // @Range: 5 50 - // @Units: dB + // @DisplayName: Position (yaw) Error notch filter index + // @Description: Position (yaw) Error notch filter index + // @Range: 1 8 // @User: Advanced GOBJECT(pid_pos_yaw, "POSYAW_", AC_PID), From e729c8ccfa28bcb2a610e8bddd5e25a231c853fd Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 20 Oct 2023 13:31:27 +0100 Subject: [PATCH 329/499] Filter: add AP_Filter support enable filters with AP_FILTER_ENABLED allow filters to be compiled out add dynamic updates, remove load/save and enable --- libraries/Filter/AP_Filter.cpp | 155 +++++++++++++++++++++ libraries/Filter/AP_Filter.h | 92 ++++++++++++ libraries/Filter/AP_Filter_config.h | 15 ++ libraries/Filter/AP_Filter_params.cpp | 25 ++++ libraries/Filter/AP_NotchFilter_params.cpp | 53 +++++++ 5 files changed, 340 insertions(+) create mode 100644 libraries/Filter/AP_Filter.cpp create mode 100644 libraries/Filter/AP_Filter.h create mode 100644 libraries/Filter/AP_Filter_config.h create mode 100644 libraries/Filter/AP_Filter_params.cpp create mode 100644 libraries/Filter/AP_NotchFilter_params.cpp diff --git a/libraries/Filter/AP_Filter.cpp b/libraries/Filter/AP_Filter.cpp new file mode 100644 index 00000000000000..ce65bd61ffe764 --- /dev/null +++ b/libraries/Filter/AP_Filter.cpp @@ -0,0 +1,155 @@ +#include "AP_Filter.h" +#include +#include +#include + +#if AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) + +extern const AP_HAL::HAL& hal; + +const AP_Param::GroupInfo AP_Filters::var_info[] = { + +#if AP_FILTER_NUM_FILTERS >= 1 + // @Group: 1_ + // @Path: AP_Filter_params.cpp + AP_SUBGROUPINFO(params[0], "1_", 2, AP_Filters, AP_Filter_params), + // @Group: 1_ + // @Path: AP_NotchFilter_params.cpp + AP_SUBGROUPVARPTR(filters[0], "1_", 3, AP_Filters, backend_var_info[0]), +#endif +#if AP_FILTER_NUM_FILTERS >= 2 + // @Group: 2_ + // @Path: AP_Filter_params.cpp + AP_SUBGROUPINFO(params[1], "2_", 4, AP_Filters, AP_Filter_params), + // @Group: 2_ + // @Path: AP_NotchFilter_params.cpp + AP_SUBGROUPVARPTR(filters[1], "2_", 5, AP_Filters, backend_var_info[1]), +#endif +#if AP_FILTER_NUM_FILTERS >= 3 + // @Group: 3_ + // @Path: AP_Filter_params.cpp + AP_SUBGROUPINFO(params[2], "3_", 6, AP_Filters, AP_Filter_params), + // @Group: 3_ + // @Path: AP_NotchFilter_params.cpp + AP_SUBGROUPVARPTR(filters[2], "3_", 7, AP_Filters, backend_var_info[2]), +#endif +#if AP_FILTER_NUM_FILTERS >= 4 + // @Group: 4_ + // @Path: AP_Filter_params.cpp + AP_SUBGROUPINFO(params[3], "4_", 8, AP_Filters, AP_Filter_params), + // @Group: 4_ + // @Path: AP_NotchFilter_params.cpp + AP_SUBGROUPVARPTR(filters[3], "4_", 9, AP_Filters, backend_var_info[3]), +#endif +#if AP_FILTER_NUM_FILTERS >= 5 + // @Group: 5_ + // @Path: AP_Filter_params.cpp + AP_SUBGROUPINFO(params[4], "5_", 10, AP_Filters, AP_Filter_params), + // @Group: 5_ + // @Path: AP_NotchFilter_params.cpp + AP_SUBGROUPVARPTR(filters[4], "5_", 11, AP_Filters, backend_var_info[4]), +#endif +#if AP_FILTER_NUM_FILTERS >= 6 + // @Group: 6_ + // @Path: AP_Filter_params.cpp + AP_SUBGROUPINFO(params[5], "6_", 12, AP_Filters, AP_Filter_params), + // @Group: 6_ + // @Path: AP_NotchFilter_params.cpp + AP_SUBGROUPVARPTR(filters[5], "6_", 13, AP_Filters, backend_var_info[5]), +#endif +#if AP_FILTER_NUM_FILTERS >= 7 + // @Group: 7_ + // @Path: AP_Filter_params.cpp + AP_SUBGROUPINFO(params[6], "7_", 14, AP_Filters, AP_Filter_params), + // @Group: 7_ + // @Path: AP_NotchFilter_params.cpp + AP_SUBGROUPVARPTR(filters[6], "7_", 15, AP_Filters, backend_var_info[6]), +#endif +#if AP_FILTER_NUM_FILTERS >= 8 + // @Group: 8_ + // @Path: AP_Filter_params.cpp + AP_SUBGROUPINFO(params[7], "8_", 16, AP_Filters, AP_Filter_params), + // @Group: 8_ + // @Path: AP_NotchFilter_params.cpp + AP_SUBGROUPVARPTR(filters[7], "8_", 17, AP_Filters, backend_var_info[7]), +#endif + AP_GROUPEND +}; + +const AP_Param::GroupInfo *AP_Filters::backend_var_info[AP_FILTER_NUM_FILTERS]; + +AP_Filter::AP_Filter(FilterType type): + _type(type) +{ +} + +AP_Filters::AP_Filters() +{ + AP_Param::setup_object_defaults(this, var_info); + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + if (singleton != nullptr) { + AP_HAL::panic("AP_Filters must be singleton"); + } +#endif + singleton = this; +} + +void AP_Filters::init() +{ + update(); +} + +// 1Hz update to process config changes +void AP_Filters::update() +{ + if (hal.util->get_soft_armed()) { + return; + } + + // make sure all filters are allocated + for (uint8_t i = 0; i < AP_FILTER_NUM_FILTERS; i++) { + bool update = false; + switch (AP_Filter::FilterType(params[i]._type)) { + case AP_Filter::FilterType::FILTER_NONE: + break; + case AP_Filter::FilterType::FILTER_NOTCH: + if (filters[i] == nullptr) { + filters[i] = new AP_NotchFilter_params(); + backend_var_info[i] = AP_NotchFilter_params::var_info; + update = true; + } + break; + default: + return; + } + + if (update) { + AP_Param::load_object_from_eeprom(filters[i], backend_var_info[i]); + AP_Param::invalidate_count(); + } + } +} + +AP_Filter* AP_Filters::get_filter(uint8_t index) +{ + if (index >= AP_FILTER_NUM_FILTERS) { + return nullptr; + } + + return filters[index-1]; +} + +// singleton instance +AP_Filters *AP_Filters::singleton; + +namespace AP { + +AP_Filters &filters() +{ + return *AP_Filters::get_singleton(); +} + +} + +#endif // AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) diff --git a/libraries/Filter/AP_Filter.h b/libraries/Filter/AP_Filter.h new file mode 100644 index 00000000000000..7c303a0842bcc0 --- /dev/null +++ b/libraries/Filter/AP_Filter.h @@ -0,0 +1,92 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + */ +#pragma once + +#include +#include +#include "AP_Filter_config.h" +#include "NotchFilter.h" + +#if AP_FILTER_ENABLED + +class AP_Filter { +public: + enum class FilterType : uint8_t { + FILTER_NONE = 0, + FILTER_NOTCH = 1, + }; + + AP_Filter(FilterType type); + + void init(); + + virtual bool setup_notch_filter(NotchFilterFloat& filter, float sample_rate) { return false; } + + FilterType _type; +}; + +struct AP_Filter_params { +public: + AP_Filter_params(); + + static const struct AP_Param::GroupInfo var_info[]; + + AP_Enum _type; +}; + +struct AP_NotchFilter_params : public AP_Filter { +public: + AP_NotchFilter_params(); + + bool setup_notch_filter(NotchFilterFloat& filter, float sample_rate) override; + + static const struct AP_Param::GroupInfo var_info[]; + + AP_Float _center_freq_hz; + AP_Float _quality; + AP_Float _attenuation_dB; +}; + +class AP_Filters { +public: + AP_Filters(); + + CLASS_NO_COPY(AP_Filters); + + static AP_Filters *get_singleton(void) { return singleton; } + + void init(); + // 1Hz update to process config changes + void update(); + + static const struct AP_Param::GroupInfo var_info[]; + + static const struct AP_Param::GroupInfo *backend_var_info[AP_FILTER_NUM_FILTERS]; + + AP_Filter* get_filter(uint8_t filt_num); + +private: + AP_Filter* filters[AP_FILTER_NUM_FILTERS]; + AP_Filter_params params[AP_FILTER_NUM_FILTERS]; + + static AP_Filters *singleton; +}; + +namespace AP { + AP_Filters &filters(); +}; + +#endif // AP_FILTER_ENABLED + diff --git a/libraries/Filter/AP_Filter_config.h b/libraries/Filter/AP_Filter_config.h new file mode 100644 index 00000000000000..d94dd9df1b720a --- /dev/null +++ b/libraries/Filter/AP_Filter_config.h @@ -0,0 +1,15 @@ +#pragma once + +#include + +#ifndef AP_FILTER_NUM_FILTERS +#if BOARD_FLASH_SIZE > 1024 +#define AP_FILTER_NUM_FILTERS 8 +#else +#define AP_FILTER_NUM_FILTERS 0 +#endif +#endif + +#ifndef AP_FILTER_ENABLED +#define AP_FILTER_ENABLED AP_FILTER_NUM_FILTERS > 0 +#endif diff --git a/libraries/Filter/AP_Filter_params.cpp b/libraries/Filter/AP_Filter_params.cpp new file mode 100644 index 00000000000000..d13cb2477faa69 --- /dev/null +++ b/libraries/Filter/AP_Filter_params.cpp @@ -0,0 +1,25 @@ +#include "AP_Filter.h" +#include +#include + +#if AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) + +const AP_Param::GroupInfo AP_Filter_params::var_info[] = { + + // @Param: TYPE + // @DisplayName: Filter Type + // @Values: 0:Disable, 1:Notch Filter + // @Description: Filter Type + // @User: Standard + // @RebootRequired: True + AP_GROUPINFO_FLAGS("TYPE", 1, AP_Filter_params, _type, int8_t(AP_Filter::FilterType::FILTER_NONE), AP_PARAM_FLAG_ENABLE), + + AP_GROUPEND +}; + +AP_Filter_params::AP_Filter_params() +{ + AP_Param::setup_object_defaults(this, var_info); +} + +#endif // AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) diff --git a/libraries/Filter/AP_NotchFilter_params.cpp b/libraries/Filter/AP_NotchFilter_params.cpp new file mode 100644 index 00000000000000..5927fef4459881 --- /dev/null +++ b/libraries/Filter/AP_NotchFilter_params.cpp @@ -0,0 +1,53 @@ +#include "AP_Filter.h" +#include +#include + +#if AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) + +const AP_Param::GroupInfo AP_NotchFilter_params::var_info[] = { + + // @Param: NOTCH_FREQ + // @DisplayName: Notch Filter center frequency + // @Description: Notch Filter center frequency in Hz. + // @Range: 10 495 + // @Units: Hz + // @User: Advanced + AP_GROUPINFO("NOTCH_FREQ", 1, AP_NotchFilter_params, _center_freq_hz, 0), + + // @Param: NOTCH_Q + // @DisplayName: Notch Filter quality factor + // @Description: Notch Filter quality factor given by the notch centre frequency divided by its bandwidth. + // @Range: 1 10 + // @User: Advanced + AP_GROUPINFO("NOTCH_Q", 2, AP_NotchFilter_params, _quality, 2), + + // @Param: NOTCH_ATT + // @DisplayName: Notch Filter attenuation + // @Description: Notch Filter attenuation in dB. + // @Range: 5 50 + // @Units: dB + // @User: Advanced + AP_GROUPINFO("NOTCH_ATT", 3, AP_NotchFilter_params, _attenuation_dB, 40), + + AP_GROUPEND +}; + +AP_NotchFilter_params::AP_NotchFilter_params() : AP_Filter(AP_Filter::FilterType::FILTER_NOTCH) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +bool AP_NotchFilter_params::setup_notch_filter(NotchFilterFloat& filter, float sample_rate) +{ + if (is_zero(_quality) || is_zero(_center_freq_hz) || is_zero(_attenuation_dB)) { + return false; + } + + if (!is_equal(sample_rate, filter.sample_freq_hz()) + || !is_equal(_center_freq_hz.get(), filter.center_freq_hz())) { + filter.init(sample_rate, _center_freq_hz, _center_freq_hz / _quality, _attenuation_dB); + } + return true; +} + +#endif // AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) From 6ecb18e02765a4a9ea86b86aeaadeef2e47f7cc2 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 20 Oct 2023 13:31:40 +0100 Subject: [PATCH 330/499] AP_Vehicle: link in AP_Filter support allow filters to be compiled out add filter updates at 1Hz --- libraries/AP_Vehicle/AP_Vehicle.cpp | 12 ++++++++++++ libraries/AP_Vehicle/AP_Vehicle.h | 4 ++++ 2 files changed, 16 insertions(+) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 9a4f702a2d15f6..b04cc282fc07c6 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -241,6 +241,11 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = { #endif #endif // AP_NETWORKING_ENABLED +#if AP_FILTER_ENABLED + // @Group: FILT + // @Path: ../Filter/AP_Filter.cpp + AP_SUBGROUPINFO(filters, "FILT", 26, AP_Vehicle, AP_Filters), +#endif AP_GROUPEND }; @@ -419,6 +424,10 @@ void AP_Vehicle::setup() custom_rotations.init(); +#if AP_FILTER_ENABLED + filters.init(); +#endif + #if HAL_WITH_ESC_TELEM && HAL_GYROFFT_ENABLED for (uint8_t i = 0; i #include #include +#include class AP_DDS_Client; @@ -469,6 +470,9 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { uint32_t _last_internal_errors; // backup of AP_InternalError::internal_errors bitmask AP_CustomRotations custom_rotations; +#if AP_FILTER_ENABLED + AP_Filters filters; +#endif // Bitmask of modes to disable from gcs AP_Int32 flight_mode_GCS_block; From 942be4f2f8556dedace0cf4b8a2ed24440c4e9fd Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 1 Oct 2023 18:21:01 +0100 Subject: [PATCH 331/499] autotest: update PIDNotches to use AP_Filter format --- Tools/autotest/arducopter.py | 14 +++++--------- Tools/autotest/helicopter.py | 16 +++++++--------- 2 files changed, 12 insertions(+), 18 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 701c3d50ebd06b..d137b57ebad56c 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -5968,6 +5968,7 @@ def PIDNotches(self): ex = None try: self.set_parameters({ + "FILT1_TYPE": 1, "AHRS_EKF_TYPE": 10, "INS_LOG_BAT_MASK": 3, "INS_LOG_BAT_OPT": 0, @@ -5977,15 +5978,10 @@ def PIDNotches(self): "SIM_VIB_FREQ_X": 120, # roll "SIM_VIB_FREQ_Y": 120, # pitch "SIM_VIB_FREQ_Z": 180, # yaw - "ATC_RAT_RLL_ADV": 1, - "ATC_RAT_RLL_NEF": 120, - "ATC_RAT_RLL_NBW": 50, - "ATC_RAT_PIT_ADV": 1, - "ATC_RAT_PIT_NEF": 120, - "ATC_RAT_PIT_NBW": 50, - "ATC_RAT_YAW_ADV": 1, - "ATC_RAT_YAW_NEF": 180, - "ATC_RAT_YAW_NBW": 50, + "FILT1_NOTCH_FREQ": 120, + "ATC_RAT_RLL_NEF": 1, + "ATC_RAT_PIT_NEF": 1, + "ATC_RAT_YAW_NEF": 1, "SIM_GYR1_RND": 5, }) self.reboot_sitl() diff --git a/Tools/autotest/helicopter.py b/Tools/autotest/helicopter.py index d3634ed4160f2a..0da15f1c91e4f1 100644 --- a/Tools/autotest/helicopter.py +++ b/Tools/autotest/helicopter.py @@ -809,6 +809,8 @@ def PIDNotches(self): ex = None try: self.set_parameters({ + "FILT1_TYPE": 1, + "FILT2_TYPE": 1, "AHRS_EKF_TYPE": 10, "INS_LOG_BAT_MASK": 3, "INS_LOG_BAT_OPT": 0, @@ -818,15 +820,11 @@ def PIDNotches(self): "SIM_VIB_FREQ_X": 120, # roll "SIM_VIB_FREQ_Y": 120, # pitch "SIM_VIB_FREQ_Z": 180, # yaw - "ATC_RAT_RLL_ADV": 1, - "ATC_RAT_RLL_NEF": 120, - "ATC_RAT_RLL_NBW": 50, - "ATC_RAT_PIT_ADV": 1, - "ATC_RAT_PIT_NEF": 120, - "ATC_RAT_PIT_NBW": 50, - "ATC_RAT_YAW_ADV": 1, - "ATC_RAT_YAW_NEF": 180, - "ATC_RAT_YAW_NBW": 50, + "FILT1_NOTCH_FREQ": 120, + "FILT2_NOTCH_FREQ": 180, + "ATC_RAT_RLL_NEF": 1, + "ATC_RAT_PIT_NEF": 1, + "ATC_RAT_YAW_NEF": 2, "SIM_GYR1_RND": 5, }) self.reboot_sitl() From 5d53485be09d52c96af27e4f21fe941c23a8c9a0 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 6 Nov 2023 11:25:23 +0000 Subject: [PATCH 332/499] AP_Logger: add PIDInfo.DFF logging --- libraries/AP_Logger/LogFile.cpp | 1 + libraries/AP_Logger/LogStructure.h | 10 ++++++---- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index 26717af38cf4b2..0666943e94b87e 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -496,6 +496,7 @@ void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info) I : info.I, D : info.D, FF : info.FF, + DFF : info.DFF, Dmod : info.Dmod, slew_rate : info.slew_rate, flags : flags diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index ad6632a24cbe79..1259c6417cd75f 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -405,6 +405,7 @@ struct PACKED log_PID { float I; float D; float FF; + float DFF; float Dmod; float slew_rate; uint8_t flags; @@ -679,10 +680,10 @@ struct PACKED log_VER { // UNIT messages define units which can be referenced by FMTU messages // FMTU messages associate types (e.g. centimeters/second/second) to FMT message fields -#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,Dmod,SRate,Flags" -#define PID_FMT "QfffffffffB" -#define PID_UNITS "s----------" -#define PID_MULTS "F----------" +#define PID_LABELS "TimeUS,Tar,Act,Err,P,I,D,FF,DFF,Dmod,SRate,Flags" +#define PID_FMT "QffffffffffB" +#define PID_UNITS "s-----------" +#define PID_MULTS "F-----------" #define PIDx_FMT "Qffffffff" #define PIDx_UNITS "smmnnnooo" @@ -910,6 +911,7 @@ struct PACKED log_VER { // @Field: I: integral part of PID // @Field: D: derivative part of PID // @Field: FF: controller feed-forward portion of response +// @Field: DFF: controller derivative feed-forward portion of response // @Field: Dmod: scaler applied to D gain to reduce limit cycling // @Field: SRate: slew rate used in slew limiter // @Field: Flags: bitmask of PID state flags From 60d5e65a1ddee7006d50e7689258b463c7446322 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 6 Nov 2023 19:22:05 +0000 Subject: [PATCH 333/499] Plane: DFF logging docs --- ArduPlane/Log.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 8f46404a85669f..55d5ab4c46b495 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -401,6 +401,7 @@ const struct LogStructure Plane::log_structure[] = { // @Field: I: integral part of PID // @Field: D: derivative part of PID // @Field: FF: controller feed-forward portion of response +// @Field: DFF: controller derivative feed-forward portion of response // @Field: Dmod: scaler applied to D gain to reduce limit cycling // @Field: SRate: slew rate // @Field: Flags: bitmask of PID state flags @@ -424,6 +425,7 @@ const struct LogStructure Plane::log_structure[] = { // @Field: I: integral part of PID // @Field: D: derivative part of PID // @Field: FF: controller feed-forward portion of response +// @Field: DFF: controller derivative feed-forward portion of response // @Field: Dmod: scaler applied to D gain to reduce limit cycling // @Field: SRate: slew rate // @Field: Flags: bitmask of PID state flags From 69bfe9b8375feb94e657cf99ba3f2809dbfd9f8e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 12 Nov 2023 17:34:27 +1100 Subject: [PATCH 334/499] APM_Control: added D_FF support for fixed wing --- libraries/APM_Control/AP_AutoTune.cpp | 2 +- libraries/APM_Control/AP_PitchController.cpp | 3 ++- libraries/APM_Control/AP_RollController.cpp | 3 ++- libraries/APM_Control/AP_YawController.cpp | 3 ++- 4 files changed, 7 insertions(+), 4 deletions(-) diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index 14b14b618fb27d..87c84ee94a1c34 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -179,7 +179,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg) // filter actuator without I term so we can take ratios without // accounting for trim offsets. We first need to include the I and // clip to 45 degrees to get the right value of the real surface - const float clipped_actuator = constrain_float(pinfo.FF + pinfo.P + pinfo.D + pinfo.I, -45, 45) - pinfo.I; + const float clipped_actuator = constrain_float(pinfo.FF + pinfo.P + pinfo.D + pinfo.DFF + pinfo.I, -45, 45) - pinfo.I; const float actuator = actuator_filter.apply(clipped_actuator); const float actual_rate = rate_filter.apply(pinfo.actual); diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 85689d1dce10d2..1c02fdb0a86bf9 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -218,13 +218,14 @@ float AP_PitchController::_get_rate_out(float desired_rate, float scaler, bool d pinfo.P *= deg_scale; pinfo.I *= deg_scale; pinfo.D *= deg_scale; + pinfo.DFF *= deg_scale; // fix the logged target and actual values to not have the scalers applied pinfo.target = desired_rate; pinfo.actual = degrees(rate_y); // sum components - float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D; + float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF; if (ground_mode) { // when on ground suppress D and half P term to prevent oscillations out -= pinfo.D + 0.5*pinfo.P; diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index 2ec7efd6c1ae25..8717828cda403b 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -206,13 +206,14 @@ float AP_RollController::_get_rate_out(float desired_rate, float scaler, bool di pinfo.P *= deg_scale; pinfo.I *= deg_scale; pinfo.D *= deg_scale; + pinfo.DFF *= deg_scale; // fix the logged target and actual values to not have the scalers applied pinfo.target = desired_rate; pinfo.actual = degrees(rate_x); // sum components - float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D; + float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF; if (ground_mode) { // when on ground suppress D term to prevent oscillations out -= pinfo.D + 0.5*pinfo.P; diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index af60641e062be6..f99333aca1e7e2 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -344,6 +344,7 @@ float AP_YawController::get_rate_out(float desired_rate, float scaler, bool disa pinfo.P *= deg_scale; pinfo.I *= deg_scale; pinfo.D *= deg_scale; + pinfo.DFF *= deg_scale; pinfo.limit = limit_I; // fix the logged target and actual values to not have the scalers applied @@ -351,7 +352,7 @@ float AP_YawController::get_rate_out(float desired_rate, float scaler, bool disa pinfo.actual = degrees(rate_z); // sum components - float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D; + float out = pinfo.FF + pinfo.P + pinfo.I + pinfo.D + pinfo.DFF; // remember the last output to trigger the I limit _last_out = out; From da0efa3323230e960d93f8cc2b78b0f1ad560cfa Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Thu, 16 Nov 2023 00:04:09 -0700 Subject: [PATCH 335/499] SITL: Bump up read rate on SITL * This is needed to do active configuration quickly * Read/Write split and exposed to ensure physics/write rate is still coupled to avoid impacting the jamming and delayed data * Created a utility to allocate the SITL instance Signed-off-by: Ryan Friedman --- libraries/SITL/SIM_GPS.cpp | 27 +++++++++++---------------- libraries/SITL/SIM_GPS.h | 30 +++++++++++++----------------- 2 files changed, 24 insertions(+), 33 deletions(-) diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 4416ed7187946a..ac45d68828cdd8 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -52,12 +52,6 @@ ssize_t GPS_Backend::read_from_autopilot(char *buffer, size_t size) const return front.read_from_autopilot(buffer, size); } -void GPS_Backend::update(const GPS_Data &d) -{ - update_read(&d); - update_write(&d); -} - GPS::GPS(uint8_t _instance) : SerialDevice(8192, 2048), instance{_instance} @@ -183,7 +177,7 @@ static GPS_TOW gps_time() /* send a new set of GPS UBLOX packets */ -void GPS_UBlox::update_write(const GPS_Data *d) +void GPS_UBlox::publish(const GPS_Data *d) { struct PACKED ubx_nav_posllh { uint32_t time; // GPS msToW @@ -486,7 +480,7 @@ void GPS_NMEA::nmea_printf(const char *fmt, ...) /* send a new GPS NMEA packet */ -void GPS_NMEA::update_write(const GPS_Data *d) +void GPS_NMEA::publish(const GPS_Data *d) { struct timeval tv; struct tm *tm; @@ -599,7 +593,7 @@ void GPS_SBP_Common::sbp_send_message(uint16_t msg_type, uint16_t sender_id, uin write_to_autopilot((char*)&crc, 2); } -void GPS_SBP::update_write(const GPS_Data *d) +void GPS_SBP::publish(const GPS_Data *d) { struct sbp_heartbeat_t { bool sys_error : 1; @@ -713,7 +707,7 @@ void GPS_SBP::update_write(const GPS_Data *d) } -void GPS_SBP2::update_write(const GPS_Data *d) +void GPS_SBP2::publish(const GPS_Data *d) { struct sbp_heartbeat_t { bool sys_error : 1; @@ -825,7 +819,7 @@ void GPS_SBP2::update_write(const GPS_Data *d) do_every_count++; } -void GPS_NOVA::update_write(const GPS_Data *d) +void GPS_NOVA::publish(const GPS_Data *d) { static struct PACKED nova_header { @@ -991,7 +985,7 @@ uint32_t GPS_NOVA::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_ return( crc ); } -void GPS_GSOF::update_write(const GPS_Data *d) +void GPS_GSOF::publish(const GPS_Data *d) { // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 constexpr uint8_t GSOF_POS_TIME_TYPE { 0x01 }; @@ -1286,7 +1280,7 @@ uint32_t GPS_GSOF::gsof_pack_float(const float& src) /* send MSP GPS data */ -void GPS_MSP::update_write(const GPS_Data *d) +void GPS_MSP::publish(const GPS_Data *d) { struct PACKED { // header @@ -1364,7 +1358,7 @@ void GPS_MSP::update_write(const GPS_Data *d) read file data logged from AP_GPS_DEBUG_LOGGING_ENABLED */ #if AP_SIM_GPS_FILE_ENABLED -void GPS_FILE::update_write(const GPS_Data *d) +void GPS_FILE::publish(const GPS_Data *d) { static int fd[2] = {-1,-1}; static uint32_t base_time[2]; @@ -1524,6 +1518,7 @@ void GPS::update() // run at configured GPS rate (default 5Hz) if ((now_ms - last_update) < (uint32_t)(1000/_sitl->gps_hertz[idx])) { + backend->update_read(); return; } @@ -1593,10 +1588,10 @@ void GPS::update() d.longitude += glitch_offsets.y; d.altitude += glitch_offsets.z; - backend->update(d); // i.e. reading configuration etc from autopilot + backend->publish(&d); } -void GPS_Backend::update_read(const GPS_Data *d) +void GPS_Backend::update_read() { // swallow any config bytes char c; diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index a4648c6123d9c3..235234fd6ad7a0 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -69,14 +69,17 @@ class GPS_Backend { GPS_Backend(class GPS &front, uint8_t _instance); virtual ~GPS_Backend() {} - void update(const GPS_Data &d); - // 0 baud means "unset" i.e. baud-rate checks should not apply virtual uint32_t device_baud() const { return 0; } ssize_t write_to_autopilot(const char *p, size_t size) const; ssize_t read_from_autopilot(char *buffer, size_t size) const; + // read and process config from autopilot (e.g.) + virtual void update_read(); + // writing fix information to autopilot (e.g.) + virtual void publish(const GPS_Data *d) = 0; + protected: uint8_t instance; @@ -84,13 +87,6 @@ class GPS_Backend { class SIM *_sitl; -private: - - // read and process config from autopilot (e.g.) - virtual void update_read(const GPS_Data *d); - // writing fix information to autopilot (e.g.) - virtual void update_write(const GPS_Data *d) = 0; - }; class GPS_FILE : public GPS_Backend { @@ -99,7 +95,7 @@ class GPS_FILE : public GPS_Backend { using GPS_Backend::GPS_Backend; - void update_write(const GPS_Data *d) override; + void publish(const GPS_Data *d) override; }; class GPS_GSOF : public GPS_Backend { @@ -108,7 +104,7 @@ class GPS_GSOF : public GPS_Backend { using GPS_Backend::GPS_Backend; - void update_write(const GPS_Data *d) override; + void publish(const GPS_Data *d) override; private: void send_gsof(const uint8_t *buf, const uint16_t size); @@ -125,7 +121,7 @@ class GPS_NMEA : public GPS_Backend { using GPS_Backend::GPS_Backend; - void update_write(const GPS_Data *d) override; + void publish(const GPS_Data *d) override; private: @@ -141,7 +137,7 @@ class GPS_NOVA : public GPS_Backend { using GPS_Backend::GPS_Backend; - void update_write(const GPS_Data *d) override; + void publish(const GPS_Data *d) override; uint32_t device_baud() const override { return 19200; } @@ -158,7 +154,7 @@ class GPS_MSP : public GPS_Backend { using GPS_Backend::GPS_Backend; - void update_write(const GPS_Data *d) override; + void publish(const GPS_Data *d) override; }; class GPS_SBP_Common : public GPS_Backend { @@ -179,7 +175,7 @@ class GPS_SBP : public GPS_SBP_Common { using GPS_SBP_Common::GPS_SBP_Common; - void update_write(const GPS_Data *d) override; + void publish(const GPS_Data *d) override; }; @@ -189,7 +185,7 @@ class GPS_SBP2 : public GPS_SBP_Common { using GPS_SBP_Common::GPS_SBP_Common; - void update_write(const GPS_Data *d) override; + void publish(const GPS_Data *d) override; }; @@ -199,7 +195,7 @@ class GPS_UBlox : public GPS_Backend { using GPS_Backend::GPS_Backend; - void update_write(const GPS_Data *d) override; + void publish(const GPS_Data *d) override; private: void send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size); From 15e0f689c21497c6686a87ef83a3804fb9637705 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 21 Nov 2023 14:15:44 +1100 Subject: [PATCH 336/499] AP_HAL_ChibiOS: correct AP_Filter defines - checking the build type is very rarely used and definitely not required here - fix boilerplate to conform to normal pattern of including the config header and #if'ing based on the _ENABLED directly after that --- libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h index 306ce7bc32e548..46e017f5830813 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -388,3 +388,7 @@ #ifndef AP_ICENGINE_ENABLED #define AP_ICENGINE_ENABLED 0 #endif + +#ifndef AP_FILTER_ENABLED +#define AP_FILTER_ENABLED 0 +#endif From e806adb009d759688d0c296dbaa23f3145fc46f0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 21 Nov 2023 14:15:44 +1100 Subject: [PATCH 337/499] AP_Vehicle: correct AP_Filter defines - checking the build type is very rarely used and definitely not required here - fix boilerplate to conform to normal pattern of including the config header and #if'ing based on the _ENABLED directly after that --- libraries/AP_Vehicle/AP_Vehicle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index b04cc282fc07c6..0635dc8368cf97 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -568,7 +568,7 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { #if HAL_WITH_ESC_TELEM && HAL_GYROFFT_ENABLED SCHED_TASK(check_motor_noise, 5, 50, 252), #endif -#if AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) +#if AP_FILTER_ENABLED SCHED_TASK_CLASS(AP_Filters, &vehicle.filters, update, 1, 100, 252), #endif SCHED_TASK(update_arming, 1, 50, 253), From 8eb5baa4ae060dcada5ee76b5024df9f83d213ff Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 21 Nov 2023 14:15:44 +1100 Subject: [PATCH 338/499] Filter: correct AP_Filter defines - checking the build type is very rarely used and definitely not required here - fix boilerplate to conform to normal pattern of including the config header and #if'ing based on the _ENABLED directly after that --- libraries/Filter/AP_Filter.cpp | 8 +++++--- libraries/Filter/AP_Filter_params.cpp | 8 +++++--- libraries/Filter/AP_NotchFilter_params.cpp | 8 +++++--- 3 files changed, 15 insertions(+), 9 deletions(-) diff --git a/libraries/Filter/AP_Filter.cpp b/libraries/Filter/AP_Filter.cpp index ce65bd61ffe764..3e2763141ac18c 100644 --- a/libraries/Filter/AP_Filter.cpp +++ b/libraries/Filter/AP_Filter.cpp @@ -1,10 +1,12 @@ +#include "AP_Filter_config.h" + +#if AP_FILTER_ENABLED + #include "AP_Filter.h" #include #include #include -#if AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) - extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_Filters::var_info[] = { @@ -152,4 +154,4 @@ AP_Filters &filters() } -#endif // AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) +#endif // AP_FILTER_ENABLED diff --git a/libraries/Filter/AP_Filter_params.cpp b/libraries/Filter/AP_Filter_params.cpp index d13cb2477faa69..40412bae8598e4 100644 --- a/libraries/Filter/AP_Filter_params.cpp +++ b/libraries/Filter/AP_Filter_params.cpp @@ -1,9 +1,11 @@ +#include "AP_Filter_config.h" + +#if AP_FILTER_ENABLED + #include "AP_Filter.h" #include #include -#if AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) - const AP_Param::GroupInfo AP_Filter_params::var_info[] = { // @Param: TYPE @@ -22,4 +24,4 @@ AP_Filter_params::AP_Filter_params() AP_Param::setup_object_defaults(this, var_info); } -#endif // AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) +#endif // AP_FILTER_ENABLED diff --git a/libraries/Filter/AP_NotchFilter_params.cpp b/libraries/Filter/AP_NotchFilter_params.cpp index 5927fef4459881..68769765dda719 100644 --- a/libraries/Filter/AP_NotchFilter_params.cpp +++ b/libraries/Filter/AP_NotchFilter_params.cpp @@ -1,9 +1,11 @@ +#include "AP_Filter_config.h" + +#if AP_FILTER_ENABLED + #include "AP_Filter.h" #include #include -#if AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) - const AP_Param::GroupInfo AP_NotchFilter_params::var_info[] = { // @Param: NOTCH_FREQ @@ -50,4 +52,4 @@ bool AP_NotchFilter_params::setup_notch_filter(NotchFilterFloat& filter, float s return true; } -#endif // AP_FILTER_ENABLED && !APM_BUILD_TYPE(APM_BUILD_AP_Periph) +#endif // AP_FILTER_ENABLED From adc0ebf9de90ac52eaa80fdce9a0cfc02581f6ef Mon Sep 17 00:00:00 2001 From: Peter Mullen Date: Tue, 14 Nov 2023 20:07:34 -0800 Subject: [PATCH 339/499] AP_RangeFinder: Add signal_quality_pct to range finder state --- libraries/AP_RangeFinder/AP_RangeFinder.cpp | 17 ++++++++++++----- libraries/AP_RangeFinder/AP_RangeFinder.h | 6 ++++++ .../AP_RangeFinder/AP_RangeFinder_BLPing.cpp | 7 +++---- .../AP_RangeFinder/AP_RangeFinder_BLPing.h | 2 +- .../AP_RangeFinder/AP_RangeFinder_Backend.h | 5 +---- .../AP_RangeFinder_Backend_Serial.cpp | 1 + .../AP_RangeFinder_Backend_Serial.h | 6 ++++++ .../AP_RangeFinder/AP_RangeFinder_JRE_Serial.h | 6 +++--- .../AP_RangeFinder_LightWareSerial.h | 5 ++--- .../AP_RangeFinder/AP_RangeFinder_MAVLink.cpp | 15 ++++----------- .../AP_RangeFinder/AP_RangeFinder_MAVLink.h | 4 ---- libraries/GCS_MAVLink/GCS_Common.cpp | 13 ++++++++----- 12 files changed, 47 insertions(+), 40 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index 1d21089df5acc9..b9ea6f90765edd 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -220,6 +220,8 @@ void RangeFinder::init(enum Rotation orientation_default) // initialise status state[i].status = Status::NotConnected; state[i].range_valid_count = 0; + // initialize signal_quality_pct for drivers that don't handle it. + state[i].signal_quality_pct = SIGNAL_QUALITY_UNKNOWN; } } @@ -693,6 +695,15 @@ uint16_t RangeFinder::distance_cm_orient(enum Rotation orientation) const return distance_orient(orientation) * 100.0; } +int8_t RangeFinder::signal_quality_pct_orient(enum Rotation orientation) const +{ + AP_RangeFinder_Backend *backend = find_instance(orientation); + if (backend == nullptr) { + return RangeFinder::SIGNAL_QUALITY_UNKNOWN; + } + return backend->signal_quality_pct(); +} + int16_t RangeFinder::max_distance_cm_orient(enum Rotation orientation) const { AP_RangeFinder_Backend *backend = find_instance(orientation); @@ -793,10 +804,6 @@ void RangeFinder::Log_RFND() const continue; } - int8_t signal_quality; - if (!s->get_signal_quality_pct(signal_quality)) { - signal_quality = -1; - } const struct log_RFND pkt = { LOG_PACKET_HEADER_INIT(LOG_RFND_MSG), time_us : AP_HAL::micros64(), @@ -804,7 +811,7 @@ void RangeFinder::Log_RFND() const dist : s->distance_cm(), status : (uint8_t)s->status(), orient : s->orientation(), - quality : signal_quality, + quality : s->signal_quality_pct(), }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index b00198644fa8e4..49230664c269b5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -193,9 +193,14 @@ class RangeFinder Good }; + static constexpr int8_t SIGNAL_QUALITY_MIN = 0; + static constexpr int8_t SIGNAL_QUALITY_MAX = 100; + static constexpr int8_t SIGNAL_QUALITY_UNKNOWN = -1; + // The RangeFinder_State structure is filled in by the backend driver struct RangeFinder_State { float distance_m; // distance in meters + int8_t signal_quality_pct; // measurement quality in percent 0-100, -1 -> quality is unknown uint16_t voltage_mv; // voltage in millivolts, if applicable, otherwise 0 enum RangeFinder::Status status; // sensor status uint8_t range_valid_count; // number of consecutive valid readings (maxes out at 10) @@ -260,6 +265,7 @@ class RangeFinder // any sensor which can current supply it float distance_orient(enum Rotation orientation) const; uint16_t distance_cm_orient(enum Rotation orientation) const; + int8_t signal_quality_pct_orient(enum Rotation orientation) const; int16_t max_distance_cm_orient(enum Rotation orientation) const; int16_t min_distance_cm_orient(enum Rotation orientation) const; int16_t ground_clearance_cm_orient(enum Rotation orientation) const; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp index 42e64add72e823..3cd40aa298e734 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp @@ -83,13 +83,12 @@ bool AP_RangeFinder_BLPing::get_reading(float &reading_m) return false; } -bool AP_RangeFinder_BLPing::get_signal_quality_pct(int8_t &quality_pct) const +int8_t AP_RangeFinder_BLPing::get_signal_quality_pct() const { if (status() != RangeFinder::Status::Good) { - return false; + return RangeFinder::SIGNAL_QUALITY_UNKNOWN; } - quality_pct = protocol.get_confidence(); - return true; + return protocol.get_confidence(); } uint8_t PingProtocol::get_confidence() const diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h index e61386bf4249e5..04fccaae4e35e2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.h @@ -138,7 +138,7 @@ class AP_RangeFinder_BLPing : public AP_RangeFinder_Backend_Serial * 100 is best quality, 0 is worst * */ - bool get_signal_quality_pct(int8_t &quality_pct) const override WARN_IF_UNUSED; + int8_t get_signal_quality_pct() const override WARN_IF_UNUSED; protected: /** diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h index 5ae14f0d5b96d6..86f487364ba342 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h @@ -48,6 +48,7 @@ class AP_RangeFinder_Backend enum Rotation orientation() const { return (Rotation)params.orientation.get(); } float distance() const { return state.distance_m; } uint16_t distance_cm() const { return state.distance_m*100.0f; } + int8_t signal_quality_pct() const WARN_IF_UNUSED { return state.signal_quality_pct; } uint16_t voltage_mv() const { return state.voltage_mv; } virtual int16_t max_distance_cm() const { return params.max_distance_cm; } virtual int16_t min_distance_cm() const { return params.min_distance_cm; } @@ -72,10 +73,6 @@ class AP_RangeFinder_Backend // get temperature reading in C. returns true on success and populates temp argument virtual bool get_temp(float &temp) const { return false; } - // 0 is no return value, 100 is perfect. false means signal - // quality is not available - virtual bool get_signal_quality_pct(int8_t &quality_pct) const { return false; } - // return the actual type of the rangefinder, as opposed to the // parameter value which may be changed at runtime. RangeFinder::Type allocated_type() const { return _backend_type; } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp index 186e4d1bd793a1..af27aaf5a7ad42 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.cpp @@ -53,6 +53,7 @@ uint32_t AP_RangeFinder_Backend_Serial::initial_baudrate(const uint8_t serial_in void AP_RangeFinder_Backend_Serial::update(void) { if (get_reading(state.distance_m)) { + state.signal_quality_pct = get_signal_quality_pct(); // update range_valid state based on distance measured state.last_reading_ms = AP_HAL::millis(); update_status(); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h index ecb7508d476cfc..e4349d75b8a8f2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend_Serial.h @@ -29,6 +29,12 @@ class AP_RangeFinder_Backend_Serial : public AP_RangeFinder_Backend // implement this: virtual bool get_reading(float &reading_m) = 0; + // returns 0-100 or -1. This virtual method is for + // serial drivers and is a companion to the previous method get_reading(). + // Like get_reading() this method is called in the base-class update() method. + virtual int8_t get_signal_quality_pct() const WARN_IF_UNUSED + { return RangeFinder::SIGNAL_QUALITY_UNKNOWN; } + // maximum time between readings before we change state to NoData: virtual uint16_t read_timeout_ms() const { return 200; } }; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h index df9fd1b00cc640..e37030a9713989 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_JRE_Serial.h @@ -82,9 +82,9 @@ class AP_RangeFinder_JRE_Serial : public AP_RangeFinder_Backend_Serial return MAV_DISTANCE_SENSOR_RADAR; } - bool get_signal_quality_pct(int8_t &quality_pct) const override { - quality_pct = no_signal ? 0 : 100; - return true; + int8_t get_signal_quality_pct() const override + { + return no_signal ? RangeFinder::SIGNAL_QUALITY_MIN : RangeFinder::SIGNAL_QUALITY_MAX; } private: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h index cbdfe5d6a52f2f..13f4e776cdd0e5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h @@ -26,9 +26,8 @@ class AP_RangeFinder_LightWareSerial : public AP_RangeFinder_Backend_Serial return MAV_DISTANCE_SENSOR_LASER; } - bool get_signal_quality_pct(int8_t &quality_pct) const override { - quality_pct = no_signal ? 0 : 100; - return true; + int8_t get_signal_quality_pct() const override { + return no_signal ? RangeFinder::SIGNAL_QUALITY_MIN : RangeFinder::SIGNAL_QUALITY_MAX; } private: diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp index 66ad7aebada8f7..b4fc5fb1ff5977 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp @@ -37,10 +37,10 @@ void AP_RangeFinder_MAVLink::handle_msg(const mavlink_message_t &msg) signal_quality = packet.signal_quality; if (signal_quality == 0) { // MAVLink's 0 means invalid/unset, so we map it to -1 - signal_quality = -1; + signal_quality = RangeFinder::SIGNAL_QUALITY_UNKNOWN; } else if (signal_quality == 1) { // Map 1 to 0 as that is what ardupilot uses as the worst signal quality - signal_quality = 0; + signal_quality = RangeFinder::SIGNAL_QUALITY_MIN; } } } @@ -79,19 +79,12 @@ void AP_RangeFinder_MAVLink::update(void) if (AP_HAL::millis() - state.last_reading_ms > AP_RANGEFINDER_MAVLINK_TIMEOUT_MS) { set_status(RangeFinder::Status::NoData); state.distance_m = 0.0f; + state.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN; } else { state.distance_m = distance_cm * 0.01f; + state.signal_quality_pct = signal_quality; update_status(); } } -bool AP_RangeFinder_MAVLink::get_signal_quality_pct(int8_t &quality_pct) const -{ - if (status() != RangeFinder::Status::Good) { - return false; - } - quality_pct = signal_quality; - return true; -} - #endif diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h index e2140260d19071..47cd080c13f9a1 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h @@ -31,10 +31,6 @@ class AP_RangeFinder_MAVLink : public AP_RangeFinder_Backend int16_t max_distance_cm() const override; int16_t min_distance_cm() const override; - // Get the reading confidence - // 100 is best quality, 0 is worst - WARN_IF_UNUSED bool get_signal_quality_pct(int8_t &quality_pct) const override; - protected: MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 8d2776681ff418..053e7294aaeeeb 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -385,13 +385,16 @@ void GCS_MAVLINK::send_distance_sensor(const AP_RangeFinder_Backend *sensor, con return; } - int8_t quality_pct; + int8_t quality_pct = sensor->signal_quality_pct(); + // ardupilot defines this field as -1 is unknown, 0 is poor, 100 is excellent + // mavlink defines this field as 0 is unknown, 1 is invalid, 100 is perfect uint8_t quality; - if (sensor->get_signal_quality_pct(quality_pct)) { - // mavlink defines this field as 0 is unknown, 1 is invalid, 100 is perfect - quality = MAX(quality_pct, 1); - } else { + if (quality_pct == RangeFinder::SIGNAL_QUALITY_UNKNOWN) { quality = 0; + } else if (quality_pct > 1 && quality_pct <= RangeFinder::SIGNAL_QUALITY_MAX) { + quality = quality_pct; + } else { + quality = 1; } mavlink_msg_distance_sensor_send( From 68f5c7b4dce1cc239601af979e7e0114377f9c34 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 19 Nov 2023 07:26:33 +1100 Subject: [PATCH 340/499] AP_Periph: fixed reply for serial tunnel add in serial index --- Tools/AP_Periph/serial_tunnel.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/AP_Periph/serial_tunnel.cpp b/Tools/AP_Periph/serial_tunnel.cpp index a1becc8aff65a3..cdba23b41c46d8 100644 --- a/Tools/AP_Periph/serial_tunnel.cpp +++ b/Tools/AP_Periph/serial_tunnel.cpp @@ -193,6 +193,7 @@ void AP_Periph_FW::send_serial_monitor_data() pkt.protocol.protocol = uart_monitor.protocol; pkt.buffer.len = n; pkt.baudrate = uart_monitor.baudrate; + pkt.serial_id = uart_monitor.uart_num; memcpy(pkt.buffer.data, buf, n); uint8_t buffer[UAVCAN_TUNNEL_TARGETTED_MAX_SIZE] {}; From a54503ae12be64da1937656dbfc39712a373eaa9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 19 Nov 2023 07:35:19 +1100 Subject: [PATCH 341/499] AP_SerialManager: define port ranges for CAN serial ports --- libraries/AP_SerialManager/AP_SerialManager.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index 880135a84da07b..3e5e5db97a81a0 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -158,6 +158,11 @@ // serial ports registered by AP_Networking will use IDs starting at 21 for the first port #define AP_SERIALMANAGER_NET_PORT_1 21 // NET_P1_* +// serial ports registered by AP_DroneCAN will use IDs starting at 41/51 for the first port +#define AP_SERIALMANAGER_CAN_D1_PORT_1 41 // CAN_D1_UC_S1_* +#define AP_SERIALMANAGER_CAN_D2_PORT_1 51 // CAN_D2_UC_S1_* + + class AP_SerialManager { public: AP_SerialManager(); From 0ae5c9116c74c2e238eefe9d9de69f81cbb02347 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 19 Nov 2023 08:29:54 +1100 Subject: [PATCH 342/499] AP_SerialManager: added AP_SerialManager_config.h --- .../AP_SerialManager/AP_SerialManager.cpp | 31 ++++ libraries/AP_SerialManager/AP_SerialManager.h | 141 +----------------- .../AP_SerialManager_config.h | 129 ++++++++++++++++ 3 files changed, 161 insertions(+), 140 deletions(-) create mode 100644 libraries/AP_SerialManager/AP_SerialManager_config.h diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 838336d547fb54..382162db78f483 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -27,6 +27,37 @@ #include "AP_SerialManager.h" #include +#ifndef HAL_HAVE_SERIAL0 +#define HAL_HAVE_SERIAL0 HAL_NUM_SERIAL_PORTS > 0 +#endif +#ifndef HAL_HAVE_SERIAL1 +#define HAL_HAVE_SERIAL1 HAL_NUM_SERIAL_PORTS > 1 +#endif +#ifndef HAL_HAVE_SERIAL2 +#define HAL_HAVE_SERIAL2 HAL_NUM_SERIAL_PORTS > 2 +#endif +#ifndef HAL_HAVE_SERIAL3 +#define HAL_HAVE_SERIAL3 HAL_NUM_SERIAL_PORTS > 3 +#endif +#ifndef HAL_HAVE_SERIAL4 +#define HAL_HAVE_SERIAL4 HAL_NUM_SERIAL_PORTS > 4 +#endif +#ifndef HAL_HAVE_SERIAL5 +#define HAL_HAVE_SERIAL5 HAL_NUM_SERIAL_PORTS > 5 +#endif +#ifndef HAL_HAVE_SERIAL6 +#define HAL_HAVE_SERIAL6 HAL_NUM_SERIAL_PORTS > 6 +#endif +#ifndef HAL_HAVE_SERIAL7 +#define HAL_HAVE_SERIAL7 HAL_NUM_SERIAL_PORTS > 7 +#endif +#ifndef HAL_HAVE_SERIAL8 +#define HAL_HAVE_SERIAL8 HAL_NUM_SERIAL_PORTS > 8 +#endif +#ifndef HAL_HAVE_SERIAL9 +#define HAL_HAVE_SERIAL9 HAL_NUM_SERIAL_PORTS > 9 +#endif + extern const AP_HAL::HAL& hal; #ifndef DEFAULT_SERIAL0_PROTOCOL diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index 3e5e5db97a81a0..f106e795494b16 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -21,147 +21,8 @@ */ #pragma once -#include +#include "AP_SerialManager_config.h" #include -#include - -#ifdef HAL_UART_NUM_SERIAL_PORTS -#if HAL_UART_NUM_SERIAL_PORTS >= 4 -#define SERIALMANAGER_NUM_PORTS HAL_UART_NUM_SERIAL_PORTS -#else -// we need a minimum of 4 to allow for a GPS due to the odd ordering -// of hal.uartB as SERIAL3 -#define SERIALMANAGER_NUM_PORTS 4 -#endif -#else -// assume max 8 ports -#define SERIALMANAGER_NUM_PORTS 8 -#endif - -#ifndef HAL_NUM_SERIAL_PORTS -#define HAL_NUM_SERIAL_PORTS SERIALMANAGER_NUM_PORTS -#endif - -#ifndef HAL_HAVE_SERIAL0 -#define HAL_HAVE_SERIAL0 HAL_NUM_SERIAL_PORTS > 0 -#endif -#ifndef HAL_HAVE_SERIAL1 -#define HAL_HAVE_SERIAL1 HAL_NUM_SERIAL_PORTS > 1 -#endif -#ifndef HAL_HAVE_SERIAL2 -#define HAL_HAVE_SERIAL2 HAL_NUM_SERIAL_PORTS > 2 -#endif -#ifndef HAL_HAVE_SERIAL3 -#define HAL_HAVE_SERIAL3 HAL_NUM_SERIAL_PORTS > 3 -#endif -#ifndef HAL_HAVE_SERIAL4 -#define HAL_HAVE_SERIAL4 HAL_NUM_SERIAL_PORTS > 4 -#endif -#ifndef HAL_HAVE_SERIAL5 -#define HAL_HAVE_SERIAL5 HAL_NUM_SERIAL_PORTS > 5 -#endif -#ifndef HAL_HAVE_SERIAL6 -#define HAL_HAVE_SERIAL6 HAL_NUM_SERIAL_PORTS > 6 -#endif -#ifndef HAL_HAVE_SERIAL7 -#define HAL_HAVE_SERIAL7 HAL_NUM_SERIAL_PORTS > 7 -#endif -#ifndef HAL_HAVE_SERIAL8 -#define HAL_HAVE_SERIAL8 HAL_NUM_SERIAL_PORTS > 8 -#endif -#ifndef HAL_HAVE_SERIAL9 -#define HAL_HAVE_SERIAL9 HAL_NUM_SERIAL_PORTS > 9 -#endif - -/* - array size for state[]. This needs to be at least - SERIALMANAGER_NUM_PORTS, but we want it to be the same length on - similar boards to get the ccache efficiency up. This wastes a small - amount of memory, but makes a huge difference to the build times - */ -#if SERIALMANAGER_NUM_PORTS > 10 || SERIALMANAGER_NUM_PORTS < 5 -#define SERIALMANAGER_MAX_PORTS SERIALMANAGER_NUM_PORTS -#else -#define SERIALMANAGER_MAX_PORTS 10 -#endif - - - // console default baud rates and buffer sizes -#ifdef DEFAULT_SERIAL0_BAUD -#define AP_SERIALMANAGER_CONSOLE_BAUD DEFAULT_SERIAL0_BAUD -#else -#define AP_SERIALMANAGER_CONSOLE_BAUD 115200 -#endif -#define AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX 128 -#define AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX 512 - -// mavlink default baud rates and buffer sizes -#define AP_SERIALMANAGER_MAVLINK_BAUD 57600 -#define AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX 128 -#define AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX 256 - -// LTM buffer sizes -#define AP_SERIALMANAGER_LTM_BUFSIZE_RX 0 -#define AP_SERIALMANAGER_LTM_BUFSIZE_TX 32 - -// FrSky default baud rates, use default buffer sizes -#define AP_SERIALMANAGER_FRSKY_D_BAUD 9600 -#define AP_SERIALMANAGER_FRSKY_SPORT_BAUD 57600 -#define AP_SERIALMANAGER_FRSKY_BUFSIZE_RX 0 -#define AP_SERIALMANAGER_FRSKY_BUFSIZE_TX 0 - -// GPS default baud rates and buffer sizes -// we need a 256 byte buffer for some GPS types (eg. UBLOX) -#define AP_SERIALMANAGER_GPS_BAUD 38400 -#define AP_SERIALMANAGER_GPS_BUFSIZE_RX 256 -#define AP_SERIALMANAGER_GPS_BUFSIZE_TX 16 - -// AlexMos Gimbal protocol default baud rates and buffer sizes -#define AP_SERIALMANAGER_ALEXMOS_BAUD 115200 -#define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX 128 -#define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX 128 - -#define AP_SERIALMANAGER_GIMBAL_BAUD 115200 -#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_RX 128 -#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_TX 128 - -#define AP_SERIALMANAGER_VOLZ_BAUD 115 -#define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128 -#define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128 - -#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128 -#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128 - -// MegaSquirt EFI protocol -#define AP_SERIALMANAGER_EFI_MS_BAUD 115 -#define AP_SERIALMANAGER_EFI_MS_BUFSIZE_RX 512 -#define AP_SERIALMANAGER_EFI_MS_BUFSIZE_TX 16 - -// SBUS servo outputs -#define AP_SERIALMANAGER_SBUS1_BAUD 100000 -#define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX 16 -#define AP_SERIALMANAGER_SBUS1_BUFSIZE_TX 32 - -#define AP_SERIALMANAGER_SLCAN_BAUD 115200 -#define AP_SERIALMANAGER_SLCAN_BUFSIZE_RX 128 -#define AP_SERIALMANAGER_SLCAN_BUFSIZE_TX 128 - -// MSP protocol default buffer sizes -#define AP_SERIALMANAGER_MSP_BUFSIZE_RX 128 -#define AP_SERIALMANAGER_MSP_BUFSIZE_TX 256 -#define AP_SERIALMANAGER_MSP_BAUD 115200 - -#ifndef AP_SERIALMANAGER_REGISTER_ENABLED -#define AP_SERIALMANAGER_REGISTER_ENABLED AP_NETWORKING_ENABLED -#endif - -// serial ports registered by AP_Networking will use IDs starting at 21 for the first port -#define AP_SERIALMANAGER_NET_PORT_1 21 // NET_P1_* - -// serial ports registered by AP_DroneCAN will use IDs starting at 41/51 for the first port -#define AP_SERIALMANAGER_CAN_D1_PORT_1 41 // CAN_D1_UC_S1_* -#define AP_SERIALMANAGER_CAN_D2_PORT_1 51 // CAN_D2_UC_S1_* - class AP_SerialManager { public: diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h new file mode 100644 index 00000000000000..a5a962b40c0918 --- /dev/null +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -0,0 +1,129 @@ +/* + Please contribute your ideas! See https://ardupilot.org/dev for details + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + SerialManager configuration defines + */ +#pragma once + +#include +#include + +#ifdef HAL_UART_NUM_SERIAL_PORTS +#if HAL_UART_NUM_SERIAL_PORTS >= 4 +#define SERIALMANAGER_NUM_PORTS HAL_UART_NUM_SERIAL_PORTS +#else +// we need a minimum of 4 to allow for a GPS due to the odd ordering +// of hal.uartB as SERIAL3 +#define SERIALMANAGER_NUM_PORTS 4 +#endif +#else +// assume max 8 ports +#define SERIALMANAGER_NUM_PORTS 8 +#endif + +#ifndef HAL_NUM_SERIAL_PORTS +#define HAL_NUM_SERIAL_PORTS SERIALMANAGER_NUM_PORTS +#endif + +/* + array size for state[]. This needs to be at least + SERIALMANAGER_NUM_PORTS, but we want it to be the same length on + similar boards to get the ccache efficiency up. This wastes a small + amount of memory, but makes a huge difference to the build times + */ +#if SERIALMANAGER_NUM_PORTS > 10 || SERIALMANAGER_NUM_PORTS < 5 +#define SERIALMANAGER_MAX_PORTS SERIALMANAGER_NUM_PORTS +#else +#define SERIALMANAGER_MAX_PORTS 10 +#endif + + +#ifndef AP_SERIALMANAGER_REGISTER_ENABLED +#define AP_SERIALMANAGER_REGISTER_ENABLED AP_NETWORKING_ENABLED +#endif + +// serial ports registered by AP_Networking will use IDs starting at 21 for the first port +#define AP_SERIALMANAGER_NET_PORT_1 21 // NET_P1_* + +// serial ports registered by AP_DroneCAN will use IDs starting at 41/51 for the first port +#define AP_SERIALMANAGER_CAN_D1_PORT_1 41 // CAN_D1_UC_S1_* +#define AP_SERIALMANAGER_CAN_D2_PORT_1 51 // CAN_D2_UC_S1_* + + // console default baud rates and buffer sizes +#ifdef DEFAULT_SERIAL0_BAUD +#define AP_SERIALMANAGER_CONSOLE_BAUD DEFAULT_SERIAL0_BAUD +#else +#define AP_SERIALMANAGER_CONSOLE_BAUD 115200 +#endif +#define AP_SERIALMANAGER_CONSOLE_BUFSIZE_RX 128 +#define AP_SERIALMANAGER_CONSOLE_BUFSIZE_TX 512 + +// mavlink default baud rates and buffer sizes +#define AP_SERIALMANAGER_MAVLINK_BAUD 57600 +#define AP_SERIALMANAGER_MAVLINK_BUFSIZE_RX 128 +#define AP_SERIALMANAGER_MAVLINK_BUFSIZE_TX 256 + +// LTM buffer sizes +#define AP_SERIALMANAGER_LTM_BUFSIZE_RX 0 +#define AP_SERIALMANAGER_LTM_BUFSIZE_TX 32 + +// FrSky default baud rates, use default buffer sizes +#define AP_SERIALMANAGER_FRSKY_D_BAUD 9600 +#define AP_SERIALMANAGER_FRSKY_SPORT_BAUD 57600 +#define AP_SERIALMANAGER_FRSKY_BUFSIZE_RX 0 +#define AP_SERIALMANAGER_FRSKY_BUFSIZE_TX 0 + +// GPS default baud rates and buffer sizes +// we need a 256 byte buffer for some GPS types (eg. UBLOX) +#define AP_SERIALMANAGER_GPS_BAUD 38400 +#define AP_SERIALMANAGER_GPS_BUFSIZE_RX 256 +#define AP_SERIALMANAGER_GPS_BUFSIZE_TX 16 + +// AlexMos Gimbal protocol default baud rates and buffer sizes +#define AP_SERIALMANAGER_ALEXMOS_BAUD 115200 +#define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_RX 128 +#define AP_SERIALMANAGER_ALEXMOS_BUFSIZE_TX 128 + +#define AP_SERIALMANAGER_GIMBAL_BAUD 115200 +#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_RX 128 +#define AP_SERIALMANAGER_GIMBAL_BUFSIZE_TX 128 + +#define AP_SERIALMANAGER_VOLZ_BAUD 115 +#define AP_SERIALMANAGER_VOLZ_BUFSIZE_RX 128 +#define AP_SERIALMANAGER_VOLZ_BUFSIZE_TX 128 + +#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_RX 128 +#define AP_SERIALMANAGER_ROBOTIS_BUFSIZE_TX 128 + +// MegaSquirt EFI protocol +#define AP_SERIALMANAGER_EFI_MS_BAUD 115 +#define AP_SERIALMANAGER_EFI_MS_BUFSIZE_RX 512 +#define AP_SERIALMANAGER_EFI_MS_BUFSIZE_TX 16 + +// SBUS servo outputs +#define AP_SERIALMANAGER_SBUS1_BAUD 100000 +#define AP_SERIALMANAGER_SBUS1_BUFSIZE_RX 16 +#define AP_SERIALMANAGER_SBUS1_BUFSIZE_TX 32 + +#define AP_SERIALMANAGER_SLCAN_BAUD 115200 +#define AP_SERIALMANAGER_SLCAN_BUFSIZE_RX 128 +#define AP_SERIALMANAGER_SLCAN_BUFSIZE_TX 128 + +// MSP protocol default buffer sizes +#define AP_SERIALMANAGER_MSP_BUFSIZE_RX 128 +#define AP_SERIALMANAGER_MSP_BUFSIZE_TX 256 +#define AP_SERIALMANAGER_MSP_BAUD 115200 From e63a2250cac1114376dd901f8acf3962cae6ca6d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 22 Nov 2023 11:33:33 +1100 Subject: [PATCH 343/499] AP_SerialManager: ensure registered ports are in sorted order this avoids ordering issues if using both CAN and network serial ports --- .../AP_SerialManager/AP_SerialManager.cpp | 20 +++++++++++++++++-- libraries/AP_SerialManager/AP_SerialManager.h | 1 + 2 files changed, 19 insertions(+), 2 deletions(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 382162db78f483..38b8124aaf6fb2 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -850,8 +850,24 @@ void AP_SerialManager::set_protocol_and_baud(uint8_t sernum, enum SerialProtocol */ void AP_SerialManager::register_port(RegisteredPort *port) { - port->next = registered_ports; - registered_ports = port; + const auto idx = port->state.idx; + WITH_SEMAPHORE(port_sem); + /* + maintain the list in ID order + */ + if (registered_ports == nullptr || + registered_ports->state.idx >= idx) { + port->next = registered_ports; + registered_ports = port; + return; + } + for (auto p = registered_ports; p; p = p->next) { + if (p->next == nullptr || p->next->state.idx >= idx) { + port->next = p->next; + p->next = port; + break; + } + } } #endif // AP_SERIALMANAGER_REGISTER_ENABLED diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index f106e795494b16..01d5d7bbd45640 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -172,6 +172,7 @@ class AP_SerialManager { UARTState state; }; RegisteredPort *registered_ports; + HAL_Semaphore port_sem; // register an externally managed port void register_port(RegisteredPort *port); From 65ffe713b41e62bd10407184b20c8d65da8ef7d8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 19 Nov 2023 11:05:00 +1100 Subject: [PATCH 344/499] AP_SerialManager: enable port registration for dronecan --- libraries/AP_SerialManager/AP_SerialManager_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index a5a962b40c0918..7dbf0c16a8a0cd 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -53,7 +53,7 @@ #ifndef AP_SERIALMANAGER_REGISTER_ENABLED -#define AP_SERIALMANAGER_REGISTER_ENABLED AP_NETWORKING_ENABLED +#define AP_SERIALMANAGER_REGISTER_ENABLED BOARD_FLASH_SIZE > 1024 && (AP_NETWORKING_ENABLED || HAL_ENABLE_DRONECAN_DRIVERS) #endif // serial ports registered by AP_Networking will use IDs starting at 21 for the first port From e06d65bd75e48c998d63f6a68e7ef3f7af976d04 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 22 Nov 2023 11:33:48 +1100 Subject: [PATCH 345/499] AP_Networking: simplify port registration --- libraries/AP_Networking/AP_Networking_port.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index f9f7248dba6656..e70224cf4b4b7b 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -58,9 +58,7 @@ const AP_Param::GroupInfo AP_Networking::Port::var_info[] = { */ void AP_Networking::ports_init(void) { - // init in reverse order to keep the linked list in - // AP_SerialManager in the right order - for (int8_t i=ARRAY_SIZE(ports)-1; i>= 0; i--) { + for (uint8_t i=0; i Date: Sun, 19 Nov 2023 07:36:20 +1100 Subject: [PATCH 346/499] AP_DroneCAN: support CAN serial ports this allows any serial protocol to be mapped to a remote DroneCAN node --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 113 +++++++++- libraries/AP_DroneCAN/AP_DroneCAN.h | 13 ++ libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp | 224 +++++++++++++++++++ libraries/AP_DroneCAN/AP_DroneCAN_serial.h | 75 +++++++ 4 files changed, 424 insertions(+), 1 deletion(-) create mode 100644 libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp create mode 100644 libraries/AP_DroneCAN/AP_DroneCAN_serial.h diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 7853319cc8e7a9..55d148bf1f90c0 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -51,6 +51,10 @@ #include #include +#if AP_DRONECAN_SERIAL_ENABLED +#include "AP_DroneCAN_serial.h" +#endif + extern const AP_HAL::HAL& hal; // setup default pool size @@ -148,7 +152,106 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { // @Bitmask: 0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16, 16: ESC 17, 17: ESC 18, 18: ESC 19, 19: ESC 20, 20: ESC 21, 21: ESC 22, 22: ESC 23, 23: ESC 24, 24: ESC 25, 25: ESC 26, 26: ESC 27, 27: ESC 28, 28: ESC 29, 29: ESC 30, 30: ESC 31, 31: ESC 32 // @User: Advanced AP_GROUPINFO("ESC_RV", 9, AP_DroneCAN, _esc_rv, 0), - + +#if AP_DRONECAN_SERIAL_ENABLED + /* + due to the parameter tree depth limitation we can't use a sub-table for the serial parameters + */ + + // @Param: SER_EN + // @DisplayName: DroneCAN Serial enable + // @Description: Enable DroneCAN virtual serial ports + // @Values: 0:Disabled, 1:Enabled + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO_FLAGS("SER_EN", 10, AP_DroneCAN, serial.enable, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: S1_NOD + // @DisplayName: Serial CAN remote node number + // @Description: CAN remote node number for serial port + // @Range: 0 127 + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("S1_NOD", 11, AP_DroneCAN, serial.ports[0].node, 0), + + // @Param: S1_IDX + // @DisplayName: DroneCAN Serial1 index + // @Description: Serial port number on remote CAN node + // @Range: 0 100 + // @Values: -1:Disabled,0:Serial0,1:Serial1,2:Serial2,3:Serial3,4:Serial4,5:Serial5,6:Serial6 + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("S1_IDX", 12, AP_DroneCAN, serial.ports[0].idx, -1), + + // @Param: S1_BD + // @DisplayName: DroneCAN Serial default baud rate + // @Description: Serial baud rate on remote CAN node + // @CopyFieldsFrom: SERIAL1_BAUD + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("S1_BD", 13, AP_DroneCAN, serial.ports[0].state.baud, 57600), + + // @Param: S1_PRO + // @DisplayName: Serial protocol of DroneCAN serial port + // @Description: Serial protocol of DroneCAN serial port + // @CopyFieldsFrom: SERIAL1_PROTOCOL + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("S1_PRO", 14, AP_DroneCAN, serial.ports[0].state.protocol, -1), + +#if AP_DRONECAN_SERIAL_NUM_PORTS > 1 + // @Param: S2_NOD + // @DisplayName: Serial CAN remote node number + // @Description: CAN remote node number for serial port + // @CopyFieldsFrom: CAN_D1_UC_S1_NOD + AP_GROUPINFO("S2_NOD", 15, AP_DroneCAN, serial.ports[1].node, 0), + + // @Param: S2_IDX + // @DisplayName: Serial port number on remote CAN node + // @Description: Serial port number on remote CAN node + // @CopyFieldsFrom: CAN_D1_UC_S1_IDX + AP_GROUPINFO("S2_IDX", 16, AP_DroneCAN, serial.ports[1].idx, -1), + + // @Param: S2_BD + // @DisplayName: DroneCAN Serial default baud rate + // @Description: Serial baud rate on remote CAN node + // @CopyFieldsFrom: CAN_D1_UC_S1_BD + AP_GROUPINFO("S2_BD", 17, AP_DroneCAN, serial.ports[1].state.baud, 57600), + + // @Param: S2_PRO + // @DisplayName: Serial protocol of DroneCAN serial port + // @Description: Serial protocol of DroneCAN serial port + // @CopyFieldsFrom: CAN_D1_UC_S1_PRO + AP_GROUPINFO("S2_PRO", 18, AP_DroneCAN, serial.ports[1].state.protocol, -1), +#endif + +#if AP_DRONECAN_SERIAL_NUM_PORTS > 2 + // @Param: S3_NOD + // @DisplayName: Serial CAN remote node number + // @Description: CAN node number for serial port + // @CopyFieldsFrom: CAN_D1_UC_S1_NOD + AP_GROUPINFO("S3_NOD", 19, AP_DroneCAN, serial.ports[2].node, 0), + + // @Param: S3_IDX + // @DisplayName: Serial port number on remote CAN node + // @Description: Serial port number on remote CAN node + // @CopyFieldsFrom: CAN_D1_UC_S1_IDX + AP_GROUPINFO("S3_IDX", 20, AP_DroneCAN, serial.ports[2].idx, 0), + + // @Param: S3_BD + // @DisplayName: Serial baud rate on remote CAN node + // @Description: Serial baud rate on remote CAN node + // @CopyFieldsFrom: CAN_D1_UC_S1_BD + AP_GROUPINFO("S3_BD", 21, AP_DroneCAN, serial.ports[2].state.baud, 57600), + + // @Param: S3_PRO + // @DisplayName: Serial protocol of DroneCAN serial port + // @Description: Serial protocol of DroneCAN serial port + // @CopyFieldsFrom: CAN_D1_UC_S1_PRO + AP_GROUPINFO("S3_PRO", 22, AP_DroneCAN, serial.ports[2].state.protocol, -1), +#endif +#endif // AP_DRONECAN_SERIAL_ENABLED + AP_GROUPEND }; @@ -369,6 +472,10 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) return; } +#if AP_DRONECAN_SERIAL_ENABLED + serial.init(this); +#endif + _initialized = true; debug_dronecan(AP_CANManager::LOG_INFO, "DroneCAN: init done\n\r"); } @@ -421,6 +528,10 @@ void AP_DroneCAN::loop(void) } } } + +#if AP_DRONECAN_SERIAL_ENABLED + serial.update(); +#endif } } diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h index 81abfbdda44303..f502e05a39f276 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -34,6 +34,7 @@ #include "AP_DroneCAN_DNA_Server.h" #include #include +#include #ifndef DRONECAN_SRV_NUMBER #define DRONECAN_SRV_NUMBER NUM_SERVO_CHANNELS @@ -58,6 +59,14 @@ #define AP_DRONECAN_HIMARK_SERVO_SUPPORT (BOARD_FLASH_SIZE>1024) #endif +#ifndef AP_DRONECAN_SERIAL_ENABLED +#define AP_DRONECAN_SERIAL_ENABLED AP_SERIALMANAGER_REGISTER_ENABLED && (BOARD_FLASH_SIZE>1024) +#endif + +#if AP_DRONECAN_SERIAL_ENABLED +#include "AP_DroneCAN_serial.h" +#endif + // fwd-declare callback classes class AP_DroneCAN_DNA_Server; @@ -258,6 +267,10 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { CanardInterface canard_iface; +#if AP_DRONECAN_SERIAL_ENABLED + AP_DroneCAN_Serial serial; +#endif + Canard::Publisher node_status{canard_iface}; Canard::Publisher can_stats{canard_iface}; Canard::Publisher protocol_stats{canard_iface}; diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp new file mode 100644 index 00000000000000..6856c539f2e9cf --- /dev/null +++ b/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp @@ -0,0 +1,224 @@ +/* + map local serial ports to remote DroneCAN serial ports using the + TUNNEL_TARGETTED message + */ + +#include "AP_DroneCAN.h" + +#if HAL_ENABLE_DRONECAN_DRIVERS && AP_DRONECAN_SERIAL_ENABLED + +#include +#include + +AP_DroneCAN_Serial *AP_DroneCAN_Serial::serial[HAL_MAX_CAN_PROTOCOL_DRIVERS]; + +#ifndef AP_DRONECAN_SERIAL_MIN_TXSIZE +#define AP_DRONECAN_SERIAL_MIN_TXSIZE 2048 +#endif + +#ifndef AP_DRONECAN_SERIAL_MIN_RXSIZE +#define AP_DRONECAN_SERIAL_MIN_RXSIZE 2048 +#endif + +/* + initialise DroneCAN serial aports +*/ +void AP_DroneCAN_Serial::init(AP_DroneCAN *_dronecan) +{ + if (enable == 0) { + return; + } + const uint8_t driver_index = _dronecan->get_driver_index(); + if (driver_index >= ARRAY_SIZE(serial)) { + return; + } + serial[driver_index] = this; + dronecan = _dronecan; + + const uint8_t base_port = driver_index == 0? AP_SERIALMANAGER_CAN_D1_PORT_1 : AP_SERIALMANAGER_CAN_D2_PORT_1; + bool need_subscriber = false; + + for (uint8_t i=0; i 0 && p.idx >= 0) { + p.init(); + AP::serialmanager().register_port(&p); + need_subscriber = true; + } + } + + if (need_subscriber) { + if (Canard::allocate_sub_arg_callback(dronecan, &handle_tunnel_targetted, dronecan->get_driver_index()) == nullptr) { + AP_BoardConfig::allocation_error("serial_tunnel_sub"); + } + targetted = new Canard::Publisher(dronecan->get_canard_iface()); + if (targetted == nullptr) { + AP_BoardConfig::allocation_error("serial_tunnel_pub"); + } + targetted->set_timeout_ms(20); + targetted->set_priority(CANARD_TRANSFER_PRIORITY_MEDIUM); + } +} + +/* + update DroneCAN serial ports +*/ +void AP_DroneCAN_Serial::update(void) +{ + const uint32_t now_ms = AP_HAL::millis(); + for (auto &p : ports) { + if (p.baudrate == 0) { + continue; + } + if (p.writebuffer == nullptr || p.node <= 0 || p.idx < 0) { + continue; + } + WITH_SEMAPHORE(p.sem); + uint32_t avail; + const bool send_keepalive = now_ms - p.last_send_ms > 500; + const auto *ptr = p.writebuffer->readptr(avail); + if (!send_keepalive && (ptr == nullptr || avail <= 0)) { + continue; + } + uavcan_tunnel_Targetted pkt {}; + auto n = MIN(avail, sizeof(pkt.buffer.data)); + pkt.target_node = p.node; + pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_UNDEFINED; + pkt.buffer.len = n; + pkt.baudrate = p.baudrate; + pkt.serial_id = p.idx; + pkt.options = UAVCAN_TUNNEL_TARGETTED_OPTION_LOCK_PORT; + if (ptr != nullptr) { + memcpy(pkt.buffer.data, ptr, n); + } + + if (targetted->broadcast(pkt)) { + p.writebuffer->advance(n); + p.last_send_ms = now_ms; + } + } +} + +/* + handle incoming tunnel serial packet + */ +void AP_DroneCAN_Serial::handle_tunnel_targetted(AP_DroneCAN *dronecan, + const CanardRxTransfer& transfer, + const uavcan_tunnel_Targetted &msg) +{ + uint8_t driver_index = dronecan->get_driver_index(); + if (driver_index >= ARRAY_SIZE(serial) || serial[driver_index] == nullptr) { + return; + } + auto &s = *serial[driver_index]; + for (auto &p : s.ports) { + if (p.idx == msg.serial_id && transfer.source_node_id == p.node) { + WITH_SEMAPHORE(p.sem); + if (p.readbuffer != nullptr) { + p.readbuffer->write(msg.buffer.data, msg.buffer.len); + p.last_recv_us = AP_HAL::micros64(); + } + break; + } + } +} + +/* + initialise port + */ +void AP_DroneCAN_Serial::Port::init(void) +{ + baudrate = state.baud; + begin(baudrate, 0, 0); +} + +/* + available space in outgoing buffer + */ +uint32_t AP_DroneCAN_Serial::Port::txspace(void) +{ + WITH_SEMAPHORE(sem); + return writebuffer != nullptr ? writebuffer->space() : 0; +} + +void AP_DroneCAN_Serial::Port::_begin(uint32_t b, uint16_t rxS, uint16_t txS) +{ + rxS = MAX(rxS, AP_DRONECAN_SERIAL_MIN_RXSIZE); + txS = MAX(txS, AP_DRONECAN_SERIAL_MIN_TXSIZE); + init_buffers(rxS, txS); + if (b != 0) { + baudrate = b; + } +} + +size_t AP_DroneCAN_Serial::Port::_write(const uint8_t *buffer, size_t size) +{ + WITH_SEMAPHORE(sem); + return writebuffer != nullptr ? writebuffer->write(buffer, size) : 0; +} + +ssize_t AP_DroneCAN_Serial::Port::_read(uint8_t *buffer, uint16_t count) +{ + WITH_SEMAPHORE(sem); + return readbuffer != nullptr ? readbuffer->read(buffer, count) : -1; +} + +uint32_t AP_DroneCAN_Serial::Port::_available() +{ + WITH_SEMAPHORE(sem); + return readbuffer != nullptr ? readbuffer->available() : 0; +} + + +bool AP_DroneCAN_Serial::Port::_discard_input() +{ + WITH_SEMAPHORE(sem); + if (readbuffer != nullptr) { + readbuffer->clear(); + } + return true; +} + +/* + initialise read/write buffers + */ +bool AP_DroneCAN_Serial::Port::init_buffers(const uint32_t size_rx, const uint32_t size_tx) +{ + if (size_tx == last_size_tx && + size_rx == last_size_rx) { + return true; + } + WITH_SEMAPHORE(sem); + if (readbuffer == nullptr) { + readbuffer = new ByteBuffer(size_rx); + } else { + readbuffer->set_size_best(size_rx); + } + if (writebuffer == nullptr) { + writebuffer = new ByteBuffer(size_tx); + } else { + writebuffer->set_size_best(size_tx); + } + last_size_rx = size_rx; + last_size_tx = size_tx; + return readbuffer != nullptr && writebuffer != nullptr; +} + +/* + return timestamp estimate in microseconds for when the start of + a nbytes packet arrived on the uart. +*/ +uint64_t AP_DroneCAN_Serial::Port::receive_time_constraint_us(uint16_t nbytes) +{ + WITH_SEMAPHORE(sem); + uint64_t last_receive_us = last_recv_us; + if (baudrate > 0) { + // assume 10 bits per byte. + uint32_t transport_time_us = (1000000UL * 10UL / baudrate) * (nbytes+available()); + last_receive_us -= transport_time_us; + } + return last_receive_us; +} + +#endif // HAL_ENABLE_DRONECAN_DRIVERS && AP_DRONECAN_SERIAL_ENABLED diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_serial.h b/libraries/AP_DroneCAN/AP_DroneCAN_serial.h new file mode 100644 index 00000000000000..9329ffdc917c68 --- /dev/null +++ b/libraries/AP_DroneCAN/AP_DroneCAN_serial.h @@ -0,0 +1,75 @@ +#pragma once + +#include + +#ifndef AP_DRONECAN_SERIAL_NUM_PORTS +#define AP_DRONECAN_SERIAL_NUM_PORTS 3 +#endif + +class AP_DroneCAN; + +class AP_DroneCAN_Serial +{ +public: + /* Do not allow copies */ + CLASS_NO_COPY(AP_DroneCAN_Serial); + + AP_DroneCAN_Serial() {} + + AP_Int8 enable; + + void init(AP_DroneCAN *dronecan); + void update(void); + +public: + class Port : public AP_SerialManager::RegisteredPort { + public: + friend class AP_DroneCAN_Serial; + void init(void); + + AP_Int8 node; + AP_Int8 idx; + + private: + bool is_initialized() override { + return true; + } + bool tx_pending() override { + return false; + } + + bool init_buffers(const uint32_t size_rx, const uint32_t size_tx); + + uint32_t txspace() override; + void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; + size_t _write(const uint8_t *buffer, size_t size) override; + ssize_t _read(uint8_t *buffer, uint16_t count) override; + uint32_t _available() override; + void _end() override {} + void _flush() override {} + bool _discard_input() override; + uint64_t receive_time_constraint_us(uint16_t nbytes) override; + + ByteBuffer *readbuffer; + ByteBuffer *writebuffer; + uint32_t baudrate; + uint32_t last_send_ms; + uint32_t last_size_tx; + uint32_t last_size_rx; + uint64_t last_recv_us; + + HAL_Semaphore sem; + }; + + Port ports[AP_DRONECAN_SERIAL_NUM_PORTS]; + +private: + AP_DroneCAN *dronecan; + + Canard::Publisher *targetted; + static void handle_tunnel_targetted(AP_DroneCAN *dronecan, + const CanardRxTransfer& transfer, + const uavcan_tunnel_Targetted &msg); + + static AP_DroneCAN_Serial *serial[HAL_MAX_CAN_PROTOCOL_DRIVERS]; +}; From d42e5d89fee431ddd9cc03f6402a7f5045592814 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 19 Nov 2023 08:34:59 +1100 Subject: [PATCH 347/499] Tools: added DroneCAN serial to options and extract features --- Tools/scripts/build_options.py | 1 + Tools/scripts/extract_features.py | 1 + 2 files changed, 2 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 8c8a4d38cfaee7..87e427e324fb90 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -305,6 +305,7 @@ def __init__(self, Feature('Other', 'SLCAN', 'AP_CAN_SLCAN_ENABLED', 'Enable SLCAN serial protocol', 0, None), Feature('Other', 'SDCARD_MISSION', 'AP_SDCARD_STORAGE_ENABLED', 'Enable storing mission on microSD cards', 0, None), Feature('Other', 'COMPASS_CAL', 'COMPASS_CAL_ENABLED', 'Enable "tumble" compass calibration', 0, None), + Feature('Other', 'DRONECAN_SERIAL', 'AP_DRONECAN_SERIAL_ENABLED', 'Enable DroneCAN virtual serial ports', 0, None), # MAVLink section for mavlink features and/or message handling, # rather than for e.g. mavlink-based sensor drivers diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 80fcbc79a81570..ca1f8ab5d77b24 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -234,6 +234,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_DRONECAN_HOBBYWING_ESC_SUPPORT', 'AP_DroneCAN::hobbywing_ESC_update'), ('COMPASS_CAL_ENABLED', 'CompassCalibrator::stop'), ('AP_TUNING_ENABLED', 'AP_Tuning::check_input'), + ('AP_DRONECAN_SERIAL_ENABLED', 'AP_DroneCAN_Serial::update'), ] def progress(self, msg): From f30ac4052cea655f6ef33cad668f1da8c4d6c066 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 21 Nov 2023 17:22:00 +1100 Subject: [PATCH 348/499] HAL_SITL: added SERIAL4 as UDP output for SITL periph --- libraries/AP_HAL_SITL/SITL_Periph_State.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.h b/libraries/AP_HAL_SITL/SITL_Periph_State.h index 0aca46d29b89fb..7a9d3ec757110a 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.h +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.h @@ -67,11 +67,11 @@ class HALSITL::SITL_State : public SITL_State_Common { "GPS1", "none:1", "sim:adsb", - "none:3", - "none:4", + "udpclient:127.0.0.1:15550", // for CAN UART test "none:5", "none:6", "none:7", + "none:8", }; uint8_t get_instance() const { return _instance; } From d23c633b2c802d799c4ca96059ad5cf824510bb4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 21 Nov 2023 17:22:45 +1100 Subject: [PATCH 349/499] Tools: added a test for serial over CAN download a log with mavproxy from a serial over CAN port which then comes out as UDP --- Tools/autotest/arducopter.py | 1 + Tools/autotest/vehicle_test_suite.py | 32 ++++++++++++++++++++++++++++ 2 files changed, 33 insertions(+) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index d137b57ebad56c..c7898e2b755353 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -10672,6 +10672,7 @@ def tests2b(self): # this block currently around 9.5mins here def testcan(self): ret = ([ self.CANGPSCopterMission, + self.TestLogDownloadMAVProxyCAN, ]) return ret diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 40e5190969e73e..effe660496eaae 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -4166,6 +4166,38 @@ def TestLogDownloadMAVProxyNetwork(self, upload_logs=False): self.stop_mavproxy(mavproxy) self.context_pop() + def TestLogDownloadMAVProxyCAN(self, upload_logs=False): + """Download latest log over CAN serial port""" + self.context_push() + self.set_parameters({ + "CAN_P1_DRIVER": 1, + "LOG_DISARMED": 1, + }) + self.reboot_sitl() + self.set_parameters({ + "CAN_D1_UC_SER_EN": 1, + "CAN_D1_UC_S1_NOD": 125, + "CAN_D1_UC_S1_IDX": 4, + "CAN_D1_UC_S1_BD": 57600, + "CAN_D1_UC_S1_PRO": 2, + }) + self.reboot_sitl() + filename = "MAVProxy-downloaded-can-log.BIN" + # port 15550 is in SITL_Periph_State.h as SERIAL4 udpclient:127.0.0.1:15550 + mavproxy = self.start_mavproxy(master=':15550') + mavproxy.expect("Detected vehicle") + self.mavproxy_load_module(mavproxy, 'log') + mavproxy.send("log list\n") + mavproxy.expect("numLogs") + self.wait_heartbeat() + self.wait_heartbeat() + mavproxy.send("set shownoise 0\n") + mavproxy.send("log download latest %s\n" % filename) + mavproxy.expect("Finished downloading", timeout=120) + self.mavproxy_unload_module(mavproxy, 'log') + self.stop_mavproxy(mavproxy) + self.context_pop() + def show_gps_and_sim_positions(self, on_off): """Allow to display gps and actual position on map.""" if on_off is True: From e9fc99b1bf9c26f04607d43773b455bb83cb09e2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 17 Nov 2023 11:18:06 +1100 Subject: [PATCH 350/499] AP_HAL_ChibiOS: base HAL_USE_SPI on devices not buses fixes compilation problem with gcc 10.3 ../../libraries/AP_HAL_ChibiOS/SPIDevice.cpp: In static member function 'static void ChibiOS::SPIDeviceManager::__static_initialization_and_destruction_0(int, int)': ../../libraries/AP_HAL_ChibiOS/SPIDevice.cpp:76:18: error: statement has no effect [-Werror=unused-value] 76 | ChibiOS::SPIDesc SPIDeviceManager::device_table[] = { HAL_SPI_DEVICE_LIST }; | ^~~~~~~~~~~~~~~~ compilation terminated due to -Wfatal-errors. cc1plus: some warnings being treated as errors --- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 6552630754f094..6b1275bf00a351 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -1524,7 +1524,9 @@ def write_SPI_config(self, f): if t.startswith('SPI'): self.spi_list.append(t) self.spi_list = sorted(self.spi_list) - if len(self.spi_list) == 0: + if len(self.spidev) != 0 and len(self.spi_list) == 0: + self.error("Have SPI devices but no SPI bus?!") + if len(self.spidev) == 0: f.write('#define HAL_USE_SPI FALSE\n') return devlist = [] From d5584fe70320db6fcf70131a72f906e729c72524 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Thu, 16 Nov 2023 11:49:58 +0100 Subject: [PATCH 351/499] Copter: fix USER_PARAMS_ENABLED includes --- ArduCopter/Copter.h | 11 +++++------ ArduCopter/Parameters.cpp | 4 ++-- ArduCopter/Parameters.h | 2 +- ArduCopter/UserParameters.cpp | 3 +++ ArduCopter/config.h | 5 +++++ ArduCopter/toy_mode.h | 4 ++++ 6 files changed, 20 insertions(+), 9 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 2d620deb8305c0..0827e2a09ca9e7 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -174,15 +174,14 @@ #error AP_OAPathPlanner relies on AP_FENCE_ENABLED which is disabled #endif -// Local modules -#ifdef USER_PARAMS_ENABLED -#include "UserParameters.h" -#endif -#include "Parameters.h" #if HAL_ADSB_ENABLED #include "avoidance_adsb.h" #endif - +// Local modules +#include "Parameters.h" +#if USER_PARAMS_ENABLED +#include "UserParameters.h" +#endif #include "mode.h" class Copter : public AP_Vehicle { diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 0f5b6ba6bbf029..7c09a42b07f7c4 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -894,7 +894,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { AP_SUBGROUPINFO(follow, "FOLL", 27, ParametersG2, AP_Follow), #endif -#ifdef USER_PARAMS_ENABLED +#if USER_PARAMS_ENABLED == ENABLED AP_SUBGROUPINFO(user_parameters, "USR", 28, ParametersG2, UserParameters), #endif @@ -1260,7 +1260,7 @@ ParametersG2::ParametersG2(void) #if MODE_FOLLOW_ENABLED == ENABLED ,follow() #endif -#ifdef USER_PARAMS_ENABLED +#if USER_PARAMS_ENABLED == ENABLED ,user_parameters() #endif #if AUTOTUNE_ENABLED == ENABLED diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index e1f207400f0825..e59bf2238788b6 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -591,7 +591,7 @@ class ParametersG2 { AP_Follow follow; #endif -#ifdef USER_PARAMS_ENABLED +#if USER_PARAMS_ENABLED == ENABLED // User custom parameters UserParameters user_parameters; #endif diff --git a/ArduCopter/UserParameters.cpp b/ArduCopter/UserParameters.cpp index 37e61f8ab5eb2a..61f1b7122b53e2 100644 --- a/ArduCopter/UserParameters.cpp +++ b/ArduCopter/UserParameters.cpp @@ -1,5 +1,7 @@ #include "UserParameters.h" +#include "config.h" +#if USER_PARAMS_ENABLED == ENABLED // "USR" + 13 chars remaining for param name const AP_Param::GroupInfo UserParameters::var_info[] = { @@ -16,3 +18,4 @@ UserParameters::UserParameters() { AP_Param::setup_object_defaults(this, var_info); } +#endif // USER_PARAMS_ENABLED diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 8b2010c0d242f8..329678e1b889ca 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -27,6 +27,7 @@ /// change in your local copy of APM_Config.h. /// #include "APM_Config.h" +#include #include @@ -642,3 +643,7 @@ #ifndef AC_PAYLOAD_PLACE_ENABLED #define AC_PAYLOAD_PLACE_ENABLED 1 #endif + +#ifndef USER_PARAMS_ENABLED + #define USER_PARAMS_ENABLED DISABLED +#endif diff --git a/ArduCopter/toy_mode.h b/ArduCopter/toy_mode.h index f955462b914786..13bb12454f9f68 100644 --- a/ArduCopter/toy_mode.h +++ b/ArduCopter/toy_mode.h @@ -1,5 +1,9 @@ #pragma once +#include +#include +#include "mode.h" + /* class to support "toy" mode for simplified user interaction for large volume consumer vehicles From 3d379c2b07d67df19f790a5e1e81235fa6aa90ec Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Tue, 10 Oct 2023 14:30:46 +0200 Subject: [PATCH 352/499] Tools: add junit output for autotest --- Tools/autotest/autotest.py | 9 +++-- Tools/autotest/vehicle_test_suite.py | 51 ++++++++++++++++++++++++++-- 2 files changed, 55 insertions(+), 5 deletions(-) diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 8a2d82e2c883d6..2ca2cf531e51f0 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -382,7 +382,7 @@ def run_specific_test(step, *args, **kwargs): a = Test(a) print("Got %s" % (a.name)) if a.name == test: - return (tester.autotest(tests=[a], allow_skips=False), tester) + return tester.autotest(tests=[a], allow_skips=False, step_name=step), tester print("Failed to find test %s on %s" % (test, testname)) sys.exit(1) @@ -506,6 +506,7 @@ def run_step(step): "sup_binaries": supplementary_binaries, "reset_after_every_test": opts.reset_after_every_test, "build_opts": copy.copy(build_opts), + "generate_junit": opts.junit, } if opts.speedup is not None: fly_opts["speedup"] = opts.speedup @@ -516,7 +517,7 @@ def run_step(step): global tester tester = tester_class_map[step](binary, **fly_opts) # run the test and return its result and the tester itself - return (tester.autotest(), tester) + return tester.autotest(None, step_name=step), tester # handle "test.Copter.CPUFailsafe" etc: specific_test_to_run = find_specific_test_to_run(step) @@ -884,6 +885,10 @@ def format_epilog(self, formatter): action='store_true', default=False, help='configure with --Werror') + parser.add_option("--junit", + default=False, + action='store_true', + help='Generate Junit XML tests report') group_build = optparse.OptionGroup(parser, "Build options") group_build.add_option("--no-configure", diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index effe660496eaae..fece6a02eaeb9a 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -18,6 +18,9 @@ import sys import time import traceback +from datetime import datetime +from typing import List + import pexpect import fnmatch import operator @@ -1466,6 +1469,7 @@ def __init__(self, test): self.reason = None self.exception = None self.debug_filename = None + self.time_elapsed = 0.0 # self.passed = False def __str__(self): @@ -1478,7 +1482,8 @@ def __str__(self): ret += " (" + str(self.exception) + ")" if self.debug_filename is not None: ret += " (see " + self.debug_filename + ")" - + if self.time_elapsed is not None: + ret += " (duration " + self.time_elapsed + "s)" return ret @@ -1512,6 +1517,7 @@ def __init__(self, ubsan_abort=False, num_aux_imus=0, dronecan_tests=False, + generate_junit=False, build_opts={}): self.start_time = time.time() @@ -1540,6 +1546,12 @@ def __init__(self, self.ubsan_abort = ubsan_abort self.build_opts = build_opts self.num_aux_imus = num_aux_imus + self.generate_junit = generate_junit + if generate_junit: + try: + import junitparser + except ImportError as e: + raise ImportError(f"Junit export need junitparser package.\n {e} \nTry: python -m pip install junitparser") self.mavproxy = None self._mavproxy = None # for auto-cleanup on failed tests @@ -8070,6 +8082,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= passed = False result = Result(test) + result.time_elapsed = self.test_timings[desc] ardupilot_alive = False try: @@ -11351,7 +11364,7 @@ def assert_current_onboard_log_contains_message(self, messagetype): if not self.current_onboard_log_contains_message(messagetype): raise NotAchievedException("Current onboard log does not contain message %s" % messagetype) - def run_tests(self, tests): + def run_tests(self, tests) -> List[Result]: """Autotest vehicle in SITL.""" if self.run_tests_called: raise ValueError("run_tests called twice") @@ -13577,7 +13590,7 @@ def post_tests_announcements(self): print("Had to force-reset SITL %u times" % (self.forced_post_test_sitl_reboots,)) - def autotest(self, tests=None, allow_skips=True): + def autotest(self, tests=None, allow_skips=True, step_name=None): """Autotest used by ArduPilot autotest CI.""" if tests is None: tests = self.tests() @@ -13618,9 +13631,41 @@ def autotest(self, tests=None, allow_skips=True): print(str(failure)) self.post_tests_announcements() + if self.generate_junit: + if step_name is None: + step_name = "Unknown_step_name" + step_name.replace(".", "_") + self.create_junit_report(step_name, results, skip_list) return len(self.fail_list) == 0 + def create_junit_report(self, test_name: str, results: List[Result], skip_list: list[tuple[Test, dict[str, str]]]) -> None: + """Generate Junit report from the autotest results""" + from junitparser import TestCase, TestSuite, JUnitXml, Skipped, Failure + frame = self.vehicleinfo_key() + xml_filename = f"autotest_result_{frame}_{test_name}_junit.xml" + self.progress(f"Writing test result in jUnit format to {xml_filename}\n") + + suites = TestSuite("ArduPilot Autotest") + suites.timestamp = datetime.now().replace(microsecond=0).isoformat() + suite = TestSuite(f"Autotest {frame} {test_name}") + for result in results: + case = TestCase(f"{result.test.name}", f"{frame}", result.time_elapsed) + # f"{result.test.description}" + # case.file ## TODO : add file properties to match test location + if not result.passed: + case.result = [Failure(f"see {result.debug_filename}", f"{result.exception}")] + suite.add_testcase(case) + for skipped in skip_list: + (test, reason) = skipped + case = TestCase(f"{test.name}", f"{test.function}") + case.result = [Skipped(f"Skipped : {reason}")] + # Add suite to JunitXml + xml = JUnitXml() + xml.add_testsuite(suites) + xml.add_testsuite(suite) + xml.write(xml_filename, pretty=True) + def mavfft_fttd(self, sensor_type, sensor_instance, since, until): '''display fft for raw ACC data in current logfile''' From aaa56699dd45adeee460fb6904a417569187c402 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Thu, 19 Oct 2023 22:38:53 +0200 Subject: [PATCH 353/499] Tools: add junitparser to default install skip-checks: true --- Tools/environment_install/install-prereqs-mac.sh | 2 +- Tools/environment_install/install-prereqs-ubuntu.sh | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/environment_install/install-prereqs-mac.sh b/Tools/environment_install/install-prereqs-mac.sh index 906ad0022a0bd6..5471e6f175e6ef 100755 --- a/Tools/environment_install/install-prereqs-mac.sh +++ b/Tools/environment_install/install-prereqs-mac.sh @@ -159,7 +159,7 @@ if [[ $DO_AP_STM_ENV -eq 1 ]]; then install_arm_none_eabi_toolchain fi -PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect geocoder flake8 empy dronecan" +PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect geocoder flake8 junitparser empy dronecan" # add some Python packages required for commonly-used MAVProxy modules and hex file generation: if [[ $SKIP_AP_EXT_ENV -ne 1 ]]; then PYTHON_PKGS="$PYTHON_PKGS intelhex gnureadline" diff --git a/Tools/environment_install/install-prereqs-ubuntu.sh b/Tools/environment_install/install-prereqs-ubuntu.sh index 65c84f229b850e..6fa833120a0ffe 100755 --- a/Tools/environment_install/install-prereqs-ubuntu.sh +++ b/Tools/environment_install/install-prereqs-ubuntu.sh @@ -153,7 +153,7 @@ fi # Lists of packages to install BASE_PKGS="build-essential ccache g++ gawk git make wget valgrind screen" PYTHON_PKGS="future lxml pymavlink pyserial MAVProxy pexpect geocoder empy ptyprocess dronecan" -PYTHON_PKGS="$PYTHON_PKGS flake8" +PYTHON_PKGS="$PYTHON_PKGS flake8 junitparser" # add some Python packages required for commonly-used MAVProxy modules and hex file generation: if [[ $SKIP_AP_EXT_ENV -ne 1 ]]; then From 507c27b5a4ebb00746a23894b6f028f451c1b8a1 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Thu, 19 Oct 2023 22:40:06 +0200 Subject: [PATCH 354/499] .ignore: remove junit xml files --- .dockerignore | 1 + .gitignore | 1 + 2 files changed, 2 insertions(+) diff --git a/.dockerignore b/.dockerignore index d7de4ddfc3cded..7b3ececc07c4ec 100644 --- a/.dockerignore +++ b/.dockerignore @@ -28,3 +28,4 @@ mav.* !Tools/environment_install/install-prereqs-ubuntu.sh !Tools/environment_install/install-prereqs-arch.sh !Tools/completion +autotest_result_*_junit.xml \ No newline at end of file diff --git a/.gitignore b/.gitignore index 506c527d8e1f1a..2769d317904195 100644 --- a/.gitignore +++ b/.gitignore @@ -165,3 +165,4 @@ venv/ ENV/ env.bak/ venv.bak/ +autotest_result_*_junit.xml From 1d7d6328bbeb67387bf5a234829e9a6a454661a3 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Thu, 19 Oct 2023 22:41:50 +0200 Subject: [PATCH 355/499] Tools: make CI output junit xml results --- Tools/scripts/build_ci.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index 4ae65daff8212a..3011ce83d2b550 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -89,7 +89,7 @@ function run_autotest() { if [ "$NAME" == "Examples" ]; then w="$w --speedup=5 --timeout=14400 --debug --no-clean" fi - Tools/autotest/autotest.py --show-test-timings --waf-configure-args="$w" "$BVEHICLE" "$RVEHICLE" + Tools/autotest/autotest.py --show-test-timings --junit --waf-configure-args="$w" "$BVEHICLE" "$RVEHICLE" ccache -s && ccache -z } From 63a836e013a6a26549c67ad92f23b9f50b2f4beb Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Thu, 19 Oct 2023 22:50:25 +0200 Subject: [PATCH 356/499] .github: move containers to v0.1.1 to include junitparser --- .github/workflows/test_ccache.yml | 2 +- .github/workflows/test_chibios.yml | 2 +- .github/workflows/test_coverage.yml | 2 +- .github/workflows/test_linux_sbc.yml | 2 +- .github/workflows/test_replay.yml | 2 +- .github/workflows/test_scripting.yml | 2 +- .github/workflows/test_scripts.yml | 2 +- .github/workflows/test_sitl_blimp.yml | 4 ++-- .github/workflows/test_sitl_copter.yml | 8 ++++---- .github/workflows/test_sitl_periph.yml | 4 ++-- .github/workflows/test_sitl_plane.yml | 4 ++-- .github/workflows/test_sitl_rover.yml | 4 ++-- .github/workflows/test_sitl_sub.yml | 4 ++-- .github/workflows/test_sitl_tracker.yml | 4 ++-- .github/workflows/test_size.yml | 2 +- .github/workflows/test_unit_tests.yml | 2 +- 16 files changed, 25 insertions(+), 25 deletions(-) diff --git a/.github/workflows/test_ccache.yml b/.github/workflows/test_ccache.yml index fabff75687c479..36ca816eaadf18 100644 --- a/.github/workflows/test_ccache.yml +++ b/.github/workflows/test_ccache.yml @@ -126,7 +126,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_chibios.yml b/.github/workflows/test_chibios.yml index 97a405eec79f04..09f6d5a10ee880 100644 --- a/.github/workflows/test_chibios.yml +++ b/.github/workflows/test_chibios.yml @@ -134,7 +134,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_coverage.yml b/.github/workflows/test_coverage.yml index 508e2cb99cf39f..2e07da61098eb0 100644 --- a/.github/workflows/test_coverage.yml +++ b/.github/workflows/test_coverage.yml @@ -15,7 +15,7 @@ jobs: build: runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-${{ matrix.type }}:v0.1.0 + image: ardupilot/ardupilot-dev-${{ matrix.type }}:v0.1.1 options: --privileged strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_linux_sbc.yml b/.github/workflows/test_linux_sbc.yml index 1c2259f3532a18..9c10af1e951871 100644 --- a/.github/workflows/test_linux_sbc.yml +++ b/.github/workflows/test_linux_sbc.yml @@ -135,7 +135,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_replay.yml b/.github/workflows/test_replay.yml index 1cd0b1c6afb60a..aace7b06c686b6 100644 --- a/.github/workflows/test_replay.yml +++ b/.github/workflows/test_replay.yml @@ -148,7 +148,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_scripting.yml b/.github/workflows/test_scripting.yml index c8d4b17c8255b3..8f6a4d0b91c88b 100644 --- a/.github/workflows/test_scripting.yml +++ b/.github/workflows/test_scripting.yml @@ -22,7 +22,7 @@ concurrency: jobs: test-scripting: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-base:v0.1.0 + container: ardupilot/ardupilot-dev-base:v0.1.1 steps: # git checkout the PR - uses: actions/checkout@v3 diff --git a/.github/workflows/test_scripts.yml b/.github/workflows/test_scripts.yml index 1728f5facd1dbd..c106c293f9bd11 100644 --- a/.github/workflows/test_scripts.yml +++ b/.github/workflows/test_scripts.yml @@ -9,7 +9,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-base:v0.1.0 + container: ardupilot/ardupilot-dev-base:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_sitl_blimp.yml b/.github/workflows/test_sitl_blimp.yml index 7343f4b81ebde6..b346efdcbe699b 100644 --- a/.github/workflows/test_sitl_blimp.yml +++ b/.github/workflows/test_sitl_blimp.yml @@ -207,9 +207,9 @@ jobs: autotest: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.0.29 + image: ardupilot/ardupilot-dev-base:v0.1.1 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_copter.yml b/.github/workflows/test_sitl_copter.yml index 9783a04c3d9acd..c2133a5a1d4990 100644 --- a/.github/workflows/test_sitl_copter.yml +++ b/.github/workflows/test_sitl_copter.yml @@ -161,7 +161,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -207,7 +207,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.0 + image: ardupilot/ardupilot-dev-base:v0.1.1 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails @@ -275,7 +275,7 @@ jobs: build-gcc-heli: runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.0 + image: ardupilot/ardupilot-dev-base:v0.1.1 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined steps: # git checkout the PR @@ -310,7 +310,7 @@ jobs: autotest-heli: needs: build-gcc-heli # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-base:v0.1.0 + container: ardupilot/ardupilot-dev-base:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_sitl_periph.yml b/.github/workflows/test_sitl_periph.yml index d3bd91ff2c4fdf..d53bbc54a2b9af 100644 --- a/.github/workflows/test_sitl_periph.yml +++ b/.github/workflows/test_sitl_periph.yml @@ -160,7 +160,7 @@ concurrency: jobs: build-gcc-ap_periph: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-periph:v0.1.0 + container: ardupilot/ardupilot-dev-periph:v0.1.1 steps: # git checkout the PR - uses: actions/checkout@v3 @@ -201,7 +201,7 @@ jobs: needs: build-gcc-ap_periph # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-periph:v0.1.0 + image: ardupilot/ardupilot-dev-periph:v0.1.1 options: --privileged strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_plane.yml b/.github/workflows/test_sitl_plane.yml index 24a48476c102a7..66bb9a7ebf3b18 100644 --- a/.github/workflows/test_sitl_plane.yml +++ b/.github/workflows/test_sitl_plane.yml @@ -162,7 +162,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -208,7 +208,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.0 + image: ardupilot/ardupilot-dev-base:v0.1.1 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_rover.yml b/.github/workflows/test_sitl_rover.yml index 5ca2fa60ace722..a6f3d669b32763 100644 --- a/.github/workflows/test_sitl_rover.yml +++ b/.github/workflows/test_sitl_rover.yml @@ -161,7 +161,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -207,7 +207,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.0 + image: ardupilot/ardupilot-dev-base:v0.1.1 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_sub.yml b/.github/workflows/test_sitl_sub.yml index 57d69d575d2f45..cbe5aaddf1b027 100644 --- a/.github/workflows/test_sitl_sub.yml +++ b/.github/workflows/test_sitl_sub.yml @@ -164,7 +164,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -210,7 +210,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.0 + image: ardupilot/ardupilot-dev-base:v0.1.1 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_tracker.yml b/.github/workflows/test_sitl_tracker.yml index c869fb2d66a6a1..8191e57483bf59 100644 --- a/.github/workflows/test_sitl_tracker.yml +++ b/.github/workflows/test_sitl_tracker.yml @@ -164,7 +164,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -210,7 +210,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.0 + image: ardupilot/ardupilot-dev-base:v0.1.1 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_size.yml b/.github/workflows/test_size.yml index 84bb5bb154ec81..03758fc24748bc 100644 --- a/.github/workflows/test_size.yml +++ b/.github/workflows/test_size.yml @@ -61,7 +61,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_unit_tests.yml b/.github/workflows/test_unit_tests.yml index f843f07960b87a..02b174336f945b 100644 --- a/.github/workflows/test_unit_tests.yml +++ b/.github/workflows/test_unit_tests.yml @@ -101,7 +101,7 @@ jobs: build: runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.0 + image: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 options: --user 1001 strategy: fail-fast: false # don't cancel if a job from the matrix fails From c1c730a9bb8473123e0baa05a8485d2edada8b4f Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Thu, 19 Oct 2023 23:11:17 +0200 Subject: [PATCH 357/499] Tools: fix flake8 issue --- Tools/autotest/vehicle_test_suite.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index fece6a02eaeb9a..3949ee25c6a0d7 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -20,6 +20,7 @@ import traceback from datetime import datetime from typing import List +import importlib.util import pexpect import fnmatch @@ -1549,7 +1550,9 @@ def __init__(self, self.generate_junit = generate_junit if generate_junit: try: - import junitparser + spec = importlib.util.find_spec("junitparser") + if spec is None: + raise ImportError except ImportError as e: raise ImportError(f"Junit export need junitparser package.\n {e} \nTry: python -m pip install junitparser") From 92c338f5d41624155b5c32f9c6f0fa9b107f0ba1 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Thu, 16 Nov 2023 15:09:45 +0100 Subject: [PATCH 358/499] Tools: fix junit report and add firmware version on report --- .dockerignore | 2 +- Tools/autotest/autotest.py | 6 +-- Tools/autotest/fakepos.py | 1 + Tools/autotest/pysim/util.py | 8 ++++ Tools/autotest/vehicle_test_suite.py | 71 ++++++++++++++++++++++++++-- 5 files changed, 77 insertions(+), 11 deletions(-) diff --git a/.dockerignore b/.dockerignore index 7b3ececc07c4ec..771ee99cc1411c 100644 --- a/.dockerignore +++ b/.dockerignore @@ -28,4 +28,4 @@ mav.* !Tools/environment_install/install-prereqs-ubuntu.sh !Tools/environment_install/install-prereqs-arch.sh !Tools/completion -autotest_result_*_junit.xml \ No newline at end of file +autotest_result_*_junit.xml diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 2ca2cf531e51f0..3e3fac36a55514 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -579,11 +579,7 @@ class TestResults(object): def __init__(self): """Init test results class.""" self.date = time.asctime() - self.githash = util.run_cmd('git rev-parse HEAD', - output=True, - directory=util.reltopdir('.')).strip() - if sys.version_info.major >= 3: - self.githash = self.githash.decode('utf-8') + self.githash = util.get_git_hash() self.tests = [] self.files = [] self.images = [] diff --git a/Tools/autotest/fakepos.py b/Tools/autotest/fakepos.py index 8e23a15e29c3fa..9793dc7822f9f3 100755 --- a/Tools/autotest/fakepos.py +++ b/Tools/autotest/fakepos.py @@ -51,6 +51,7 @@ def kt2mps(x): def mps2kt(x): return x / 0.514444444 + udp = udp_out("127.0.0.1:5501") latitude = -35 diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index 6b5729bf9894f2..beed41e777c75c 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -815,6 +815,14 @@ def load_local_module(fname): return ret +def get_git_hash(short=False): + short_v = "--short=8 " if short else "" + githash = run_cmd(f'git rev-parse {short_v}HEAD', output=True, directory=reltopdir('.')).strip() + if sys.version_info.major >= 3: + githash = githash.decode('utf-8') + return githash + + if __name__ == "__main__": import doctest doctest.testmod() diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 3949ee25c6a0d7..779a03434594b0 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -1554,7 +1554,7 @@ def __init__(self, if spec is None: raise ImportError except ImportError as e: - raise ImportError(f"Junit export need junitparser package.\n {e} \nTry: python -m pip install junitparser") + raise ImportError(f"Junit export need junitparser package.\n {e} \nTry: python3 -m pip install junitparser") self.mavproxy = None self._mavproxy = None # for auto-cleanup on failed tests @@ -6185,6 +6185,58 @@ def get_autopilot_capabilities(self): m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10) return m.capabilities + def decode_flight_sw_version(self, flight_sw_version: int): + """ Decode 32 bit flight_sw_version mavlink parameter + corresponds to encoding in ardupilot GCS_MAVLINK::send_autopilot_version.""" + fw_type_id = (flight_sw_version >> 0) % 256 + patch = (flight_sw_version >> 8) % 256 + minor = (flight_sw_version >> 16) % 256 + major = (flight_sw_version >> 24) % 256 + if fw_type_id == 0: + fw_type = "dev" + elif fw_type_id == 64: + fw_type = "alpha" + elif fw_type_id == 128: + fw_type = "beta" + elif fw_type_id == 192: + fw_type = "rc" + elif fw_type_id == 255: + fw_type = "official" + else: + fw_type = "undefined" + return major, minor, patch, fw_type + + def get_autopilot_firmware_version(self): + self.mav.mav.command_long_send(self.sysid_thismav(), + 1, + mavutil.mavlink.MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES, + 0, # confirmation + 1, # 1: Request autopilot version + 0, + 0, + 0, + 0, + 0, + 0) + m = self.assert_receive_message('AUTOPILOT_VERSION', timeout=10) + self.fcu_firmware_version = self.decode_flight_sw_version(m.flight_sw_version) + + def hex_values_to_int(hex_values): + # Convert ascii codes to characters + hex_chars = [chr(int(hex_value)) for hex_value in hex_values] + # Convert hex characters to integers, handle \x00 case + int_values = [0 if hex_char == '\x00' else int(hex_char, 16) for hex_char in hex_chars] + return int_values + + fcu_hash_to_hex = "" + for i in hex_values_to_int(m.flight_custom_version): + fcu_hash_to_hex += f"{i:x}" + self.fcu_firmware_hash = fcu_hash_to_hex + self.progress(f"Firmware Version {self.fcu_firmware_version}") + self.progress(f"Firmware hash {self.fcu_firmware_hash}") + self.githash = util.get_git_hash(short=True) + self.progress(f"Git hash {self.githash}") + def GetCapabilities(self): '''Get Capabilities''' self.assert_capability(mavutil.mavlink.MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT) @@ -8376,6 +8428,7 @@ def init(self): # recv_match and those will not be in self.mav.messages until # you do this! self.wait_heartbeat() + self.get_autopilot_firmware_version() self.progress("Sim time: %f" % (self.get_sim_time(),)) self.apply_default_parameters() @@ -13649,9 +13702,8 @@ def create_junit_report(self, test_name: str, results: List[Result], skip_list: xml_filename = f"autotest_result_{frame}_{test_name}_junit.xml" self.progress(f"Writing test result in jUnit format to {xml_filename}\n") - suites = TestSuite("ArduPilot Autotest") - suites.timestamp = datetime.now().replace(microsecond=0).isoformat() suite = TestSuite(f"Autotest {frame} {test_name}") + suite.timestamp = datetime.now().replace(microsecond=0).isoformat() for result in results: case = TestCase(f"{result.test.name}", f"{frame}", result.time_elapsed) # f"{result.test.description}" @@ -13663,9 +13715,18 @@ def create_junit_report(self, test_name: str, results: List[Result], skip_list: (test, reason) = skipped case = TestCase(f"{test.name}", f"{test.function}") case.result = [Skipped(f"Skipped : {reason}")] - # Add suite to JunitXml + + suite.add_property("Firmware Version Major", self.fcu_firmware_version[0]) + suite.add_property("Firmware Version Minor", self.fcu_firmware_version[1]) + suite.add_property("Firmware Version Rev", self.fcu_firmware_version[2]) + suite.add_property("Firmware hash", self.fcu_firmware_hash) + suite.add_property("Git hash", self.githash) + mavproxy_version = util.MAVProxy_version() + suite.add_property("Mavproxy Version Major", mavproxy_version[0]) + suite.add_property("Mavproxy Version Minor", mavproxy_version[1]) + suite.add_property("Mavproxy Version Rev", mavproxy_version[2]) + xml = JUnitXml() - xml.add_testsuite(suites) xml.add_testsuite(suite) xml.write(xml_filename, pretty=True) From aeed2c113c6ef917365e7f18dd937a46a220f448 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Tue, 21 Nov 2023 22:27:07 +0100 Subject: [PATCH 359/499] .github: move containers to v0.1.3 to include latest python stuff --- .github/workflows/test_ccache.yml | 2 +- .github/workflows/test_chibios.yml | 2 +- .github/workflows/test_coverage.yml | 2 +- .github/workflows/test_linux_sbc.yml | 2 +- .github/workflows/test_replay.yml | 2 +- .github/workflows/test_scripting.yml | 2 +- .github/workflows/test_scripts.yml | 2 +- .github/workflows/test_sitl_blimp.yml | 6 +++--- .github/workflows/test_sitl_copter.yml | 8 ++++---- .github/workflows/test_sitl_periph.yml | 4 ++-- .github/workflows/test_sitl_plane.yml | 4 ++-- .github/workflows/test_sitl_rover.yml | 4 ++-- .github/workflows/test_sitl_sub.yml | 4 ++-- .github/workflows/test_sitl_tracker.yml | 4 ++-- .github/workflows/test_size.yml | 2 +- .github/workflows/test_unit_tests.yml | 2 +- 16 files changed, 26 insertions(+), 26 deletions(-) diff --git a/.github/workflows/test_ccache.yml b/.github/workflows/test_ccache.yml index 36ca816eaadf18..c92011818eb956 100644 --- a/.github/workflows/test_ccache.yml +++ b/.github/workflows/test_ccache.yml @@ -126,7 +126,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_chibios.yml b/.github/workflows/test_chibios.yml index 09f6d5a10ee880..e86a6dd27b2dd4 100644 --- a/.github/workflows/test_chibios.yml +++ b/.github/workflows/test_chibios.yml @@ -134,7 +134,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_coverage.yml b/.github/workflows/test_coverage.yml index 2e07da61098eb0..553110fb3fb239 100644 --- a/.github/workflows/test_coverage.yml +++ b/.github/workflows/test_coverage.yml @@ -15,7 +15,7 @@ jobs: build: runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-${{ matrix.type }}:v0.1.1 + image: ardupilot/ardupilot-dev-${{ matrix.type }}:v0.1.3 options: --privileged strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_linux_sbc.yml b/.github/workflows/test_linux_sbc.yml index 9c10af1e951871..ef7e6db1ba2ebd 100644 --- a/.github/workflows/test_linux_sbc.yml +++ b/.github/workflows/test_linux_sbc.yml @@ -135,7 +135,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_replay.yml b/.github/workflows/test_replay.yml index aace7b06c686b6..7778c56c6c26f0 100644 --- a/.github/workflows/test_replay.yml +++ b/.github/workflows/test_replay.yml @@ -148,7 +148,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_scripting.yml b/.github/workflows/test_scripting.yml index 8f6a4d0b91c88b..972e7f42e9b64f 100644 --- a/.github/workflows/test_scripting.yml +++ b/.github/workflows/test_scripting.yml @@ -22,7 +22,7 @@ concurrency: jobs: test-scripting: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-base:v0.1.1 + container: ardupilot/ardupilot-dev-base:v0.1.3 steps: # git checkout the PR - uses: actions/checkout@v3 diff --git a/.github/workflows/test_scripts.yml b/.github/workflows/test_scripts.yml index c106c293f9bd11..458d2938715fb4 100644 --- a/.github/workflows/test_scripts.yml +++ b/.github/workflows/test_scripts.yml @@ -9,7 +9,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-base:v0.1.1 + container: ardupilot/ardupilot-dev-base:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_sitl_blimp.yml b/.github/workflows/test_sitl_blimp.yml index b346efdcbe699b..e5c5f9e05a3444 100644 --- a/.github/workflows/test_sitl_blimp.yml +++ b/.github/workflows/test_sitl_blimp.yml @@ -162,8 +162,8 @@ concurrency: jobs: build: - runs-on: ubuntu-20.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.0.29 + runs-on: ubuntu-22.04 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -209,7 +209,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.1 + image: ardupilot/ardupilot-dev-base:v0.1.3 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_copter.yml b/.github/workflows/test_sitl_copter.yml index c2133a5a1d4990..d586947019d50d 100644 --- a/.github/workflows/test_sitl_copter.yml +++ b/.github/workflows/test_sitl_copter.yml @@ -161,7 +161,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -207,7 +207,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.1 + image: ardupilot/ardupilot-dev-base:v0.1.3 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails @@ -275,7 +275,7 @@ jobs: build-gcc-heli: runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.1 + image: ardupilot/ardupilot-dev-base:v0.1.3 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined steps: # git checkout the PR @@ -310,7 +310,7 @@ jobs: autotest-heli: needs: build-gcc-heli # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-base:v0.1.1 + container: ardupilot/ardupilot-dev-base:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_sitl_periph.yml b/.github/workflows/test_sitl_periph.yml index d53bbc54a2b9af..669ae1b5baa70f 100644 --- a/.github/workflows/test_sitl_periph.yml +++ b/.github/workflows/test_sitl_periph.yml @@ -160,7 +160,7 @@ concurrency: jobs: build-gcc-ap_periph: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-periph:v0.1.1 + container: ardupilot/ardupilot-dev-periph:v0.1.3 steps: # git checkout the PR - uses: actions/checkout@v3 @@ -201,7 +201,7 @@ jobs: needs: build-gcc-ap_periph # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-periph:v0.1.1 + image: ardupilot/ardupilot-dev-periph:v0.1.3 options: --privileged strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_plane.yml b/.github/workflows/test_sitl_plane.yml index 66bb9a7ebf3b18..f87a2e6d45d4c7 100644 --- a/.github/workflows/test_sitl_plane.yml +++ b/.github/workflows/test_sitl_plane.yml @@ -162,7 +162,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -208,7 +208,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.1 + image: ardupilot/ardupilot-dev-base:v0.1.3 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_rover.yml b/.github/workflows/test_sitl_rover.yml index a6f3d669b32763..a12722f3ec5b6a 100644 --- a/.github/workflows/test_sitl_rover.yml +++ b/.github/workflows/test_sitl_rover.yml @@ -161,7 +161,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -207,7 +207,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.1 + image: ardupilot/ardupilot-dev-base:v0.1.3 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_sub.yml b/.github/workflows/test_sitl_sub.yml index cbe5aaddf1b027..22e0e41495aef2 100644 --- a/.github/workflows/test_sitl_sub.yml +++ b/.github/workflows/test_sitl_sub.yml @@ -164,7 +164,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -210,7 +210,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.1 + image: ardupilot/ardupilot-dev-base:v0.1.3 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_sitl_tracker.yml b/.github/workflows/test_sitl_tracker.yml index 8191e57483bf59..4fc48f178b7a0d 100644 --- a/.github/workflows/test_sitl_tracker.yml +++ b/.github/workflows/test_sitl_tracker.yml @@ -164,7 +164,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: @@ -210,7 +210,7 @@ jobs: needs: build # don't try to launch the tests matrix if it doesn't build first, profit from caching for fast build runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-base:v0.1.1 + image: ardupilot/ardupilot-dev-base:v0.1.3 options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined strategy: fail-fast: false # don't cancel if a job from the matrix fails diff --git a/.github/workflows/test_size.yml b/.github/workflows/test_size.yml index 03758fc24748bc..aa24582e051bac 100644 --- a/.github/workflows/test_size.yml +++ b/.github/workflows/test_size.yml @@ -61,7 +61,7 @@ concurrency: jobs: build: runs-on: ubuntu-22.04 - container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + container: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: diff --git a/.github/workflows/test_unit_tests.yml b/.github/workflows/test_unit_tests.yml index 02b174336f945b..95693485fed5fd 100644 --- a/.github/workflows/test_unit_tests.yml +++ b/.github/workflows/test_unit_tests.yml @@ -101,7 +101,7 @@ jobs: build: runs-on: ubuntu-22.04 container: - image: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.1 + image: ardupilot/ardupilot-dev-${{ matrix.toolchain }}:v0.1.3 options: --user 1001 strategy: fail-fast: false # don't cancel if a job from the matrix fails From 879937fffeb4952a4c3c2fb207dd6c7d0e98d5a5 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Tue, 21 Nov 2023 22:29:41 +0100 Subject: [PATCH 360/499] .github: update actions/checkout to v4 --- .github/workflows/cache_cleanup.yml | 2 +- .github/workflows/cygwin_build.yml | 2 +- .github/workflows/esp32_build.yml | 2 +- .github/workflows/macos_build.yml | 2 +- .github/workflows/test_ccache.yml | 2 +- .github/workflows/test_chibios.yml | 2 +- .github/workflows/test_coverage.yml | 2 +- .github/workflows/test_dds.yml | 2 +- .github/workflows/test_environment.yml | 2 +- .github/workflows/test_linux_sbc.yml | 2 +- .github/workflows/test_replay.yml | 2 +- .github/workflows/test_scripting.yml | 2 +- .github/workflows/test_scripts.yml | 2 +- .github/workflows/test_sitl_blimp.yml | 4 ++-- .github/workflows/test_sitl_copter.yml | 8 ++++---- .github/workflows/test_sitl_periph.yml | 4 ++-- .github/workflows/test_sitl_plane.yml | 4 ++-- .github/workflows/test_sitl_rover.yml | 4 ++-- .github/workflows/test_sitl_sub.yml | 4 ++-- .github/workflows/test_sitl_tracker.yml | 4 ++-- .github/workflows/test_size.yml | 4 ++-- .github/workflows/test_unit_tests.yml | 2 +- 22 files changed, 32 insertions(+), 32 deletions(-) diff --git a/.github/workflows/cache_cleanup.yml b/.github/workflows/cache_cleanup.yml index dfc73eebb223c2..6cb2403f2b622c 100644 --- a/.github/workflows/cache_cleanup.yml +++ b/.github/workflows/cache_cleanup.yml @@ -15,7 +15,7 @@ jobs: contents: read steps: - name: Check out code - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Cleanup run: | diff --git a/.github/workflows/cygwin_build.yml b/.github/workflows/cygwin_build.yml index 4b174721603596..9ae7ffba31fac7 100644 --- a/.github/workflows/cygwin_build.yml +++ b/.github/workflows/cygwin_build.yml @@ -144,7 +144,7 @@ jobs: runs-on: 'windows-latest' steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' - name: Prepare ccache timestamp diff --git a/.github/workflows/esp32_build.yml b/.github/workflows/esp32_build.yml index adad8f8e0c3e5a..c2a438891f7da7 100644 --- a/.github/workflows/esp32_build.yml +++ b/.github/workflows/esp32_build.yml @@ -155,7 +155,7 @@ jobs: gcc: [10] steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' - name: Install Prerequisites diff --git a/.github/workflows/macos_build.yml b/.github/workflows/macos_build.yml index 67e736006e902e..7dba405b0300e6 100644 --- a/.github/workflows/macos_build.yml +++ b/.github/workflows/macos_build.yml @@ -151,7 +151,7 @@ jobs: ] steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' - name: Install Prerequisites diff --git a/.github/workflows/test_ccache.yml b/.github/workflows/test_ccache.yml index c92011818eb956..c00521bc7b9dfb 100644 --- a/.github/workflows/test_ccache.yml +++ b/.github/workflows/test_ccache.yml @@ -136,7 +136,7 @@ jobs: gcc: [10] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' - name: ccache test diff --git a/.github/workflows/test_chibios.yml b/.github/workflows/test_chibios.yml index e86a6dd27b2dd4..3fe7c730eac021 100644 --- a/.github/workflows/test_chibios.yml +++ b/.github/workflows/test_chibios.yml @@ -168,7 +168,7 @@ jobs: steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_coverage.yml b/.github/workflows/test_coverage.yml index 553110fb3fb239..dda488770f7762 100644 --- a/.github/workflows/test_coverage.yml +++ b/.github/workflows/test_coverage.yml @@ -38,7 +38,7 @@ jobs: type: coverage steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_dds.yml b/.github/workflows/test_dds.yml index b4487d47315970..c8e63c33eda026 100644 --- a/.github/workflows/test_dds.yml +++ b/.github/workflows/test_dds.yml @@ -152,7 +152,7 @@ jobs: ] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_environment.yml b/.github/workflows/test_environment.yml index c7ee632a2d9e0b..f724c1db964d4c 100644 --- a/.github/workflows/test_environment.yml +++ b/.github/workflows/test_environment.yml @@ -73,7 +73,7 @@ jobs: esac # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' - name: test install environment ${{matrix.os}}.${{matrix.name}} diff --git a/.github/workflows/test_linux_sbc.yml b/.github/workflows/test_linux_sbc.yml index ef7e6db1ba2ebd..d55a75b3f42c19 100644 --- a/.github/workflows/test_linux_sbc.yml +++ b/.github/workflows/test_linux_sbc.yml @@ -167,7 +167,7 @@ jobs: steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_replay.yml b/.github/workflows/test_replay.yml index 7778c56c6c26f0..86cd8ba3b307b9 100644 --- a/.github/workflows/test_replay.yml +++ b/.github/workflows/test_replay.yml @@ -161,7 +161,7 @@ jobs: ] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_scripting.yml b/.github/workflows/test_scripting.yml index 972e7f42e9b64f..fab7a226deba19 100644 --- a/.github/workflows/test_scripting.yml +++ b/.github/workflows/test_scripting.yml @@ -25,7 +25,7 @@ jobs: container: ardupilot/ardupilot-dev-base:v0.1.3 steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' diff --git a/.github/workflows/test_scripts.yml b/.github/workflows/test_scripts.yml index 458d2938715fb4..b2e0c7bc6d1392 100644 --- a/.github/workflows/test_scripts.yml +++ b/.github/workflows/test_scripts.yml @@ -22,7 +22,7 @@ jobs: ] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' - name: test ${{matrix.config}} diff --git a/.github/workflows/test_sitl_blimp.yml b/.github/workflows/test_sitl_blimp.yml index e5c5f9e05a3444..c43546273c50cd 100644 --- a/.github/workflows/test_sitl_blimp.yml +++ b/.github/workflows/test_sitl_blimp.yml @@ -173,7 +173,7 @@ jobs: ] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build @@ -220,7 +220,7 @@ jobs: steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_sitl_copter.yml b/.github/workflows/test_sitl_copter.yml index d586947019d50d..0a379980978e6e 100644 --- a/.github/workflows/test_sitl_copter.yml +++ b/.github/workflows/test_sitl_copter.yml @@ -171,7 +171,7 @@ jobs: ] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build @@ -224,7 +224,7 @@ jobs: steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build @@ -279,7 +279,7 @@ jobs: options: --privileged --cap-add=SYS_PTRACE --security-opt apparmor=unconfined --security-opt seccomp=unconfined steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build @@ -320,7 +320,7 @@ jobs: steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_sitl_periph.yml b/.github/workflows/test_sitl_periph.yml index 669ae1b5baa70f..0f4b5453fbef42 100644 --- a/.github/workflows/test_sitl_periph.yml +++ b/.github/workflows/test_sitl_periph.yml @@ -163,7 +163,7 @@ jobs: container: ardupilot/ardupilot-dev-periph:v0.1.3 steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build @@ -212,7 +212,7 @@ jobs: steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_sitl_plane.yml b/.github/workflows/test_sitl_plane.yml index f87a2e6d45d4c7..18b1f0a8019015 100644 --- a/.github/workflows/test_sitl_plane.yml +++ b/.github/workflows/test_sitl_plane.yml @@ -172,7 +172,7 @@ jobs: ] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build @@ -220,7 +220,7 @@ jobs: steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_sitl_rover.yml b/.github/workflows/test_sitl_rover.yml index a12722f3ec5b6a..d17c0d154e16e2 100644 --- a/.github/workflows/test_sitl_rover.yml +++ b/.github/workflows/test_sitl_rover.yml @@ -171,7 +171,7 @@ jobs: ] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build @@ -220,7 +220,7 @@ jobs: steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_sitl_sub.yml b/.github/workflows/test_sitl_sub.yml index 22e0e41495aef2..65812b31b79e5a 100644 --- a/.github/workflows/test_sitl_sub.yml +++ b/.github/workflows/test_sitl_sub.yml @@ -174,7 +174,7 @@ jobs: ] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build @@ -221,7 +221,7 @@ jobs: steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_sitl_tracker.yml b/.github/workflows/test_sitl_tracker.yml index 4fc48f178b7a0d..e9e20eccfd8ae3 100644 --- a/.github/workflows/test_sitl_tracker.yml +++ b/.github/workflows/test_sitl_tracker.yml @@ -174,7 +174,7 @@ jobs: ] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build @@ -221,7 +221,7 @@ jobs: steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build diff --git a/.github/workflows/test_size.yml b/.github/workflows/test_size.yml index aa24582e051bac..f8015bc88a717a 100644 --- a/.github/workflows/test_size.yml +++ b/.github/workflows/test_size.yml @@ -86,7 +86,7 @@ jobs: - config: disco toolchain: chibios steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: ref: ${{ github.event.pull_request.base.ref }} path: base_branch @@ -175,7 +175,7 @@ jobs: echo [`date`] Built ${{ github.event.pull_request.base.ref }} with no versions - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: fetch-depth: 0 path: 'pr' diff --git a/.github/workflows/test_unit_tests.yml b/.github/workflows/test_unit_tests.yml index 95693485fed5fd..609e30386c1ca8 100644 --- a/.github/workflows/test_unit_tests.yml +++ b/.github/workflows/test_unit_tests.yml @@ -117,7 +117,7 @@ jobs: ] steps: # git checkout the PR - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 with: submodules: 'recursive' # Put ccache into github cache for faster build From 8cd91b4789286206ccaa759322a8b7574bc9052b Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Wed, 4 May 2022 13:46:43 +0200 Subject: [PATCH 361/499] Tools: add more tests for log downloads --- Tools/autotest/quadplane.py | 3 +- Tools/autotest/vehicle_test_suite.py | 160 ++++++++++++++++++++++----- 2 files changed, 136 insertions(+), 27 deletions(-) diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index 8715aa3e6a9969..d2e61b4f07ce0e 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -1524,7 +1524,8 @@ def tests(self): self.PilotYaw, self.ParameterChecks, self.QAUTOTUNE, - self.LogDownload, + self.TestLogDownload, + self.TestLogDownloadWrap, self.EXTENDED_SYS_STATE, self.Mission, self.Weathervane, diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 779a03434594b0..2c65dce31c4667 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -32,6 +32,7 @@ import tempfile import threading import enum +from pathlib import Path from MAVProxy.modules.lib import mp_util from MAVProxy.modules.lib import mp_elevation @@ -3454,34 +3455,13 @@ def HIGH_LATENCY2_links(self): if ex is not None: raise ex - def LogDownload(self): - '''Test Onboard Log Download''' - if self.is_tracker(): - # tracker starts armed, which is annoying - return - self.progress("Ensuring we have contents we care about") - self.set_parameter("LOG_FILE_DSRMROT", 1) - self.set_parameter("LOG_DISARMED", 0) - self.reboot_sitl() - original_log_list = self.log_list() - for i in range(0, 10): - self.wait_ready_to_arm() - self.arm_vehicle() - self.delay_sim_time(1) - self.disarm_vehicle() - new_log_list = self.log_list() - new_log_count = len(new_log_list) - len(original_log_list) - if new_log_count != 10: - raise NotAchievedException("Expected exactly 10 new logs got %u (%s) to (%s)" % - (new_log_count, original_log_list, new_log_list)) - self.progress("Directory contents: %s" % str(new_log_list)) - + def download_full_log_list(self, print_logs=True): tstart = self.get_sim_time() self.mav.mav.log_request_list_send(self.sysid_thismav(), 1, # target component 0, - 0xff) - logs = [] + 0xffff) + logs = {} last_id = None num_logs = None while True: @@ -3491,10 +3471,11 @@ def LogDownload(self): m = self.mav.recv_match(type='LOG_ENTRY', blocking=True, timeout=1) - self.progress("Received (%s)" % str(m)) + if print_logs: + self.progress("Received (%s)" % str(m)) if m is None: continue - logs.append(m) + logs[m.id] = m if last_id is None: if m.num_logs == 0: # caller to guarantee this works: @@ -3521,7 +3502,134 @@ def LogDownload(self): timeout=2) if m is not None: raise NotAchievedException("Received extra LOG_ENTRY?!") + return logs + + def TestLogDownloadWrap(self): + """Test log wrapping.""" + if self.is_tracker(): + # tracker starts armed, which is annoying + return + self.progress("Ensuring we have contents we care about") + self.set_parameter("LOG_FILE_DSRMROT", 1) + self.set_parameter("LOG_DISARMED", 0) + self.reboot_sitl() + logspath = Path("logs") + + def create_num_logs(num_logs, logsdir, clear_logsdir=True): + if clear_logsdir: + shutil.rmtree(logsdir, ignore_errors=True) + logsdir.mkdir() + lastlogfile_path = logsdir / Path("LASTLOG.TXT") + self.progress(f"Add LASTLOG.TXT file with counter at {num_logs}") + with open(lastlogfile_path, 'w') as lastlogfile: + lastlogfile.write(f"{num_logs}\n") + self.progress(f"Create fakelogs from 1 to {num_logs} on logs directory") + for ii in range(1, num_logs + 1): + new_log = logsdir / Path(f"{str(ii).zfill(8)}.BIN") + with open(new_log, 'w+') as logfile: + logfile.write(f"I AM LOG {ii}\n") + logfile.write('1' * ii) + + def verify_logs(test_log_num): + try: + wrap = False + offset = 0 + max_logs_num = int(self.get_parameter("LOG_MAX_FILES")) + if test_log_num > max_logs_num: + wrap = True + offset = test_log_num - max_logs_num + test_log_num = max_logs_num + logs_dict = self.download_full_log_list(print_logs=False) + if len(logs_dict) != test_log_num: + raise NotAchievedException( + f"Didn't get the full log list, expect {test_log_num} got {len(logs_dict)}") + self.progress("Checking logs size are matching") + start_log = offset if wrap else 1 + for ii in range(start_log, test_log_num + 1 - offset): + log_i = logspath / Path(f"{str(ii + offset).zfill(8)}.BIN") + if logs_dict[ii].size != log_i.stat().st_size: + logs_dict = self.download_full_log_list(print_logs=False) + # sometimes we don't have finish writing the log, so get it again prevent failure + if logs_dict[ii].size != log_i.stat().st_size: + raise NotAchievedException( + f"Log{ii} size mismatch : {logs_dict[ii].size} vs {log_i.stat().st_size}" + ) + if wrap: + self.progress("Checking wrapped logs size are matching") + for ii in range(1, offset): + log_i = logspath / Path(f"{str(ii).zfill(8)}.BIN") + if logs_dict[test_log_num + 1 - offset + ii].size != log_i.stat().st_size: + self.progress(f"{logs_dict[test_log_num + 1 - offset + ii]}") + raise NotAchievedException( + f"Log{test_log_num + 1 - offset + ii} size mismatch :" + f" {logs_dict[test_log_num + 1 - offset + ii].size} vs {log_i.stat().st_size}" + ) + except NotAchievedException as e: + shutil.rmtree(logspath, ignore_errors=True) + logspath.mkdir() + with open(logspath / Path("LASTLOG.TXT"), 'w') as lastlogfile: + lastlogfile.write("1\n") + raise e + + def add_and_verify_log(test_log_num): + self.wait_ready_to_arm() + self.arm_vehicle() + self.delay_sim_time(1) + self.disarm_vehicle() + self.delay_sim_time(10) + verify_logs(test_log_num + 1) + + def create_and_verify_logs(test_log_num, clear_logsdir=True): + self.progress(f"Test {test_log_num} logs") + create_num_logs(test_log_num, logspath, clear_logsdir) + self.reboot_sitl() + verify_logs(test_log_num) + self.start_subsubtest("Adding one more log") + add_and_verify_log(test_log_num) + + self.start_subtest("Checking log list match with filesystem info") + create_and_verify_logs(500) + create_and_verify_logs(10) + create_and_verify_logs(1) + + self.start_subtest("Change LOG_MAX_FILES and Checking log list match with filesystem info") + self.set_parameter("LOG_MAX_FILES", 250) + create_and_verify_logs(250) + self.set_parameter("LOG_MAX_FILES", 1) + create_and_verify_logs(1) + + self.start_subtest("Change LOG_MAX_FILES, don't clear old logs and Checking log list match with filesystem info") + self.set_parameter("LOG_MAX_FILES", 500) + create_and_verify_logs(500) + self.set_parameter("LOG_MAX_FILES", 250) + create_and_verify_logs(250, clear_logsdir=False) + + # cleanup + shutil.rmtree(logspath, ignore_errors=True) + + def TestLogDownload(self): + """Test Onboard Log Download.""" + if self.is_tracker(): + # tracker starts armed, which is annoying + return + self.progress("Ensuring we have contents we care about") + self.set_parameter("LOG_FILE_DSRMROT", 1) + self.set_parameter("LOG_DISARMED", 0) + self.reboot_sitl() + original_log_list = self.log_list() + for i in range(0, 10): + self.wait_ready_to_arm() + self.arm_vehicle() + self.delay_sim_time(1) + self.disarm_vehicle() + new_log_list = self.log_list() + new_log_count = len(new_log_list) - len(original_log_list) + if new_log_count != 10: + raise NotAchievedException("Expected exactly 10 new logs got %u (%s) to (%s)" % + (new_log_count, original_log_list, new_log_list)) + self.progress("Directory contents: %s" % str(new_log_list)) + self.download_full_log_list() log_id = 5 ofs = 6 count = 2 From d98a400d9ee4a798b3c4870427fc32b736afaae9 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Wed, 20 Sep 2023 17:35:17 +0200 Subject: [PATCH 362/499] AP_Logger: Prepare the maximum number of log files in the config parameter --- libraries/AP_Logger/AP_Logger.cpp | 21 ++++++++++++++++++++- libraries/AP_Logger/AP_Logger.h | 2 ++ libraries/AP_Logger/AP_Logger_Backend.cpp | 5 +++-- libraries/AP_Logger/AP_Logger_Backend.h | 2 -- libraries/AP_Logger/AP_Logger_File.cpp | 13 +++++++------ 5 files changed, 32 insertions(+), 11 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index d0b0f7b5a3ba52..6373b9d2d64c6d 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -77,6 +77,8 @@ extern const AP_HAL::HAL& hal; #define LOGGING_FIRST_DYNAMIC_MSGID 254 #endif +static constexpr uint16_t MAX_LOG_FILES = 500; +static constexpr uint16_t MIN_LOG_FILES = 2; const AP_Param::GroupInfo AP_Logger::var_info[] = { // @Param: _BACKEND_TYPE @@ -176,7 +178,16 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = { // @Increment: 0.1 // @User: Standard AP_GROUPINFO("_DARM_RATEMAX", 11, AP_Logger, _params.disarm_ratemax, 0), - + + // @Param: _MAX_FILES + // @DisplayName: Maximum number of log files + // @Description: This sets the maximum number of log file that will be written on dataflash or sd card before starting to rotate log number. Limit is capped at 500 logs. + // @Range: 2 500 + // @Increment: 1 + // @User: Advanced + // @RebootRequired: True + AP_GROUPINFO("_MAX_FILES", 12, AP_Logger, _params.max_log_files, MAX_LOG_FILES), + AP_GROUPEND }; @@ -822,6 +833,14 @@ uint16_t AP_Logger::get_num_logs(void) { return backends[0]->get_num_logs(); } +uint16_t AP_Logger::get_max_num_logs() { + const auto max_logs = constrain_uint16(_params.max_log_files.get(), MIN_LOG_FILES, MAX_LOG_FILES); + if (_params.max_log_files.get() != max_logs) { + _params.max_log_files.set_and_save_ifchanged(static_cast(max_logs)); + } + return static_cast(_params.max_log_files.get()); +} + /* we're started if any of the backends are started */ bool AP_Logger::logging_started(void) { for (uint8_t i=0; i< _next_backend; i++) { diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index d5b35cddfe1ba9..cf6d232f85c582 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -226,6 +226,7 @@ class AP_Logger uint16_t find_last_log() const; void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page); uint16_t get_num_logs(void); + uint16_t get_max_num_logs(); void setVehicle_Startup_Writer(vehicle_startup_message_Writer writer); @@ -336,6 +337,7 @@ class AP_Logger AP_Float mav_ratemax; AP_Float blk_ratemax; AP_Float disarm_ratemax; + AP_Int16 max_log_files; } _params; const struct LogStructure *structure(uint16_t num) const; diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index f938254a3a472a..8d45d8187e78cb 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -599,8 +599,9 @@ uint16_t AP_Logger_Backend::log_num_from_list_entry(const uint16_t list_entry) } uint32_t log_num = oldest_log + list_entry - 1; - if (log_num > MAX_LOG_FILES) { - log_num -= MAX_LOG_FILES; + const auto max_logs_num = _front.get_max_num_logs(); + if (log_num > (uint32_t)max_logs_num) { + log_num -= max_logs_num; } return (uint16_t)log_num; } diff --git a/libraries/AP_Logger/AP_Logger_Backend.h b/libraries/AP_Logger/AP_Logger_Backend.h index 4864f6802a215a..616ce36b667e1e 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.h +++ b/libraries/AP_Logger/AP_Logger_Backend.h @@ -12,8 +12,6 @@ class LoggerMessageWriter_DFLogStart; -#define MAX_LOG_FILES 500 - // class to handle rate limiting of log messages class AP_Logger_RateLimiter { diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 99e76bb97a2299..3208f8cf6e2549 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -234,7 +234,7 @@ bool AP_Logger_File::dirent_to_log_num(const dirent *de, uint16_t &log_num) cons } uint16_t thisnum = strtoul(de->d_name, nullptr, 10); - if (thisnum > MAX_LOG_FILES) { + if (thisnum > _front.get_max_num_logs()) { return false; } log_num = thisnum; @@ -330,7 +330,7 @@ void AP_Logger_File::Prep_MinSpace() if (avail >= target_free) { break; } - if (count++ > MAX_LOG_FILES+10) { + if (count++ > _front.get_max_num_logs() + 10) { // *way* too many deletions going on here. Possible internal error. INTERNAL_ERROR(AP_InternalError::error_t::logger_too_many_deletions); break; @@ -360,7 +360,7 @@ void AP_Logger_File::Prep_MinSpace() } } log_to_remove++; - if (log_to_remove > MAX_LOG_FILES) { + if (log_to_remove > _front.get_max_num_logs()) { log_to_remove = 1; } } while (log_to_remove != first_log_to_remove); @@ -719,6 +719,7 @@ uint16_t AP_Logger_File::get_num_logs() // not a log filename continue; } + if (thisnum > high && (smallest_above_last == 0 || thisnum < smallest_above_last)) { smallest_above_last = thisnum; } @@ -726,7 +727,7 @@ uint16_t AP_Logger_File::get_num_logs() AP::FS().closedir(d); if (smallest_above_last != 0) { // we have wrapped, add in the logs with high numbers - ret += (MAX_LOG_FILES - smallest_above_last) + 1; + ret += (_front.get_max_num_logs() - smallest_above_last) + 1; } return ret; @@ -826,7 +827,7 @@ void AP_Logger_File::start_new_log(void) if (_get_log_size(log_num) > 0 || log_num == 0) { log_num++; } - if (log_num > MAX_LOG_FILES) { + if (log_num > _front.get_max_num_logs()) { log_num = 1; } if (!write_fd_semaphore.take(1)) { @@ -1115,7 +1116,7 @@ void AP_Logger_File::erase_next(void) free(fname); erase.log_num++; - if (erase.log_num <= MAX_LOG_FILES) { + if (erase.log_num <= _front.get_max_num_logs()) { return; } From b5e2f9aa0a7337d9bb1d5cc4e57bb472b112a5c1 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 22 Sep 2023 17:29:05 -0700 Subject: [PATCH 363/499] AP_Scripting: change some _INFO msgs to _CRITICAL/ERROR --- libraries/AP_Scripting/AP_Scripting.cpp | 2 +- libraries/AP_Scripting/lua_scripts.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Scripting/AP_Scripting.cpp b/libraries/AP_Scripting/AP_Scripting.cpp index a31ba85f86450d..2c9dd332e7b056 100644 --- a/libraries/AP_Scripting/AP_Scripting.cpp +++ b/libraries/AP_Scripting/AP_Scripting.cpp @@ -317,7 +317,7 @@ void AP_Scripting::handle_mission_command(const AP_Mission::Mission_Command& cmd mission_data = nullptr; } if (mission_data == nullptr) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scripting: %s", "unable to receive mission command"); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Scripting: %s", "unable to receive mission command"); return; } } diff --git a/libraries/AP_Scripting/lua_scripts.cpp b/libraries/AP_Scripting/lua_scripts.cpp index e4a7568e4c6581..94850cb69d4dd7 100644 --- a/libraries/AP_Scripting/lua_scripts.cpp +++ b/libraries/AP_Scripting/lua_scripts.cpp @@ -240,7 +240,7 @@ void lua_scripts::load_all_scripts_in_dir(lua_State *L, const char *dirname) { auto *d = AP::FS().opendir(dirname); if (d == nullptr) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Lua: open directory (%s) failed", dirname); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Lua: open directory (%s) failed", dirname); return; } @@ -317,7 +317,7 @@ void lua_scripts::run_next_script(lua_State *L) { // script has consumed an excessive amount of CPU time set_and_print_new_error_message(MAV_SEVERITY_CRITICAL, "%s exceeded time limit", script->name); } else { - set_and_print_new_error_message(MAV_SEVERITY_INFO, "%s", lua_tostring(L, -1)); + set_and_print_new_error_message(MAV_SEVERITY_CRITICAL, "%s", lua_tostring(L, -1)); } remove_script(L, script); lua_pop(L, 1); @@ -452,7 +452,7 @@ void lua_scripts::run(void) { bool succeeded_initial_load = false; if (!_heap.available()) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Lua: Unable to allocate a heap"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Lua: Unable to allocate a heap"); return; } From 85172b56467668bee9fa0e68081027b13bc18c4a Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 21 Nov 2023 19:13:18 -0700 Subject: [PATCH 364/499] Tools: ros2: Run ament_black on all files * This commit is files changed automatically by the black linter Signed-off-by: Ryan Friedman --- .../ardupilot_dds_tests/time_listener.py | 4 +--- Tools/ros2/ardupilot_dds_tests/setup.py | 12 ++++------ .../test_navsat_msg_received.py | 12 +++------- .../test_time_msg_received.py | 12 +++------- .../ardupilot_dds_tests/test_virtual_ports.py | 4 +--- .../src/ardupilot_sitl/actions.py | 14 +++--------- .../src/ardupilot_sitl/launch.py | 22 +++++-------------- .../src/ardupilot_sitl/utilities.py | 4 +--- 8 files changed, 22 insertions(+), 62 deletions(-) diff --git a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py index e365eebaf91351..353ea76db7a219 100755 --- a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py +++ b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/time_listener.py @@ -40,9 +40,7 @@ def __init__(self): def cb(self, msg): """Process a Time message.""" if msg.sec: - self.get_logger().info( - "From AP : True [sec:{}, nsec: {}]".format(msg.sec, msg.nanosec) - ) + self.get_logger().info("From AP : True [sec:{}, nsec: {}]".format(msg.sec, msg.nanosec)) else: self.get_logger().info("From AP : False") diff --git a/Tools/ros2/ardupilot_dds_tests/setup.py b/Tools/ros2/ardupilot_dds_tests/setup.py index ce6e894687c5c5..3d2039beb5c0fd 100644 --- a/Tools/ros2/ardupilot_dds_tests/setup.py +++ b/Tools/ros2/ardupilot_dds_tests/setup.py @@ -9,15 +9,11 @@ version='0.0.0', packages=[package_name], data_files=[ - ('share/ament_index/resource_index/packages', - ['resource/' + package_name]), + ('share/ament_index/resource_index/packages', ['resource/' + package_name]), ('share/' + package_name, ['package.xml']), - (os.path.join("share", package_name, "launch"), - glob("launch/*.launch.py")), - (os.path.join("share", package_name, "config"), - glob("config/*.parm")), - (os.path.join("share", package_name, "config"), - glob("config/*.yaml")), + (os.path.join("share", package_name, "launch"), glob("launch/*.launch.py")), + (os.path.join("share", package_name, "config"), glob("config/*.parm")), + (os.path.join("share", package_name, "config"), glob("config/*.yaml")), ], install_requires=['setuptools'], zip_safe=True, diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py index d4f78f80ff6f06..05ff1343d271df 100644 --- a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_navsat_msg_received.py @@ -51,14 +51,10 @@ def start_subscriber(self): depth=1, ) - self.subscription = self.create_subscription( - NavSatFix, self.topic, self.subscriber_callback, qos_profile - ) + self.subscription = self.create_subscription(NavSatFix, self.topic, self.subscriber_callback, qos_profile) # Add a spin thread. - self.ros_spin_thread = threading.Thread( - target=lambda node: rclpy.spin(node), args=(self,) - ) + self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,)) self.ros_spin_thread.start() def subscriber_callback(self, msg): @@ -66,9 +62,7 @@ def subscriber_callback(self, msg): self.msg_event_object.set() if msg.latitude: - self.get_logger().info( - "From AP : True [lat:{}, lon: {}]".format(msg.latitude, msg.longitude) - ) + self.get_logger().info("From AP : True [lat:{}, lon: {}]".format(msg.latitude, msg.longitude)) else: self.get_logger().info("From AP : False") diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py index 65676dcc771fe5..5ffa1de6e0b11c 100644 --- a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_time_msg_received.py @@ -41,14 +41,10 @@ def __init__(self): def start_subscriber(self): """Start the subscriber.""" - self.subscription = self.create_subscription( - Time, self.topic, self.subscriber_callback, 1 - ) + self.subscription = self.create_subscription(Time, self.topic, self.subscriber_callback, 1) # Add a spin thread. - self.ros_spin_thread = threading.Thread( - target=lambda node: rclpy.spin(node), args=(self,) - ) + self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,)) self.ros_spin_thread.start() def subscriber_callback(self, msg): @@ -56,9 +52,7 @@ def subscriber_callback(self, msg): self.msg_event_object.set() if msg.sec: - self.get_logger().info( - "From AP : True [sec:{}, nsec: {}]".format(msg.sec, msg.nanosec) - ) + self.get_logger().info("From AP : True [sec:{}, nsec: {}]".format(msg.sec, msg.nanosec)) else: self.get_logger().info("From AP : False") diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_virtual_ports.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_virtual_ports.py index 25109a21e975a5..c1d0994ed5e0eb 100644 --- a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_virtual_ports.py +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/test_virtual_ports.py @@ -50,7 +50,5 @@ def test_virtual_ports(launch_context, launch_description): def validate_output(output): assert "N starting data transfer loop" in output, "Test process had no output." - process_tools.assert_stderr_sync( - launch_context, virtual_ports, validate_output, timeout=5 - ) + process_tools.assert_stderr_sync(launch_context, virtual_ports, validate_output, timeout=5) yield diff --git a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/actions.py b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/actions.py index 928a5117421231..05cfca12cea903 100644 --- a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/actions.py +++ b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/actions.py @@ -74,14 +74,8 @@ def __init__( """Create an ExecuteFunction action.""" super().__init__(**left_over_kwargs) if not callable(function): - raise TypeError( - "ExecuteFunction expected a callable for 'function', got '{}'".format( - type(function) - ) - ) - ensure_argument_type( - args, (collections.abc.Iterable, type(None)), "args", "ExecuteFunction" - ) + raise TypeError("ExecuteFunction expected a callable for 'function', got '{}'".format(type(function))) + ensure_argument_type(args, (collections.abc.Iterable, type(None)), "args", "ExecuteFunction") ensure_argument_type(kwargs, (dict, type(None)), "kwargs", "ExecuteFunction") self.__function = function self.__args = [] # type: Iterable @@ -98,9 +92,7 @@ def action(self) -> Action: """Return the Action obtained by executing the function.""" return self.__action - def execute( - self, context: LaunchContext - ) -> Optional[List[LaunchDescriptionEntity]]: + def execute(self, context: LaunchContext) -> Optional[List[LaunchDescriptionEntity]]: """Execute the function.""" action = self.__function(context, *self.__args, **self.__kwargs) self.__action = action diff --git a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py index 0d15ab4ac3c5f8..02c8230d5c7d9d 100644 --- a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py +++ b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py @@ -68,9 +68,7 @@ def generate_action(context: LaunchContext, *args, **kwargs) -> ExecuteProcess: return action @staticmethod - def generate_launch_description_with_actions() -> ( - Tuple[LaunchDescription, Dict[Text, ExecuteFunction]] - ): + def generate_launch_description_with_actions() -> Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]: """Generate a launch description with actions.""" launch_arguments = VirtualPortsLaunch.generate_launch_arguments() @@ -186,9 +184,7 @@ def generate_action(context: LaunchContext, *args, **kwargs) -> ExecuteProcess: return node @staticmethod - def generate_launch_description_with_actions() -> ( - Tuple[LaunchDescription, Dict[Text, ExecuteFunction]] - ): + def generate_launch_description_with_actions() -> Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]: """Generate a launch description with actions.""" launch_arguments = MicroRosAgentLaunch.generate_launch_arguments() @@ -315,9 +311,7 @@ def generate_action(context: LaunchContext, *args, **kwargs) -> ExecuteProcess: return mavproxy_process @staticmethod - def generate_launch_description_with_actions() -> ( - Tuple[LaunchDescription, Dict[Text, ExecuteFunction]] - ): + def generate_launch_description_with_actions() -> Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]: """Generate a launch description for MAVProxy.""" launch_arguments = MAVProxyLaunch.generate_launch_arguments() @@ -486,9 +480,7 @@ def generate_action(context: LaunchContext, *args, **kwargs) -> ExecuteProcess: return sitl_process @staticmethod - def generate_launch_description_with_actions() -> ( - Tuple[LaunchDescription, Dict[Text, ExecuteFunction]] - ): + def generate_launch_description_with_actions() -> Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]: """Generate a launch description for SITL.""" launch_arguments = SITLLaunch.generate_launch_arguments() @@ -553,8 +545,7 @@ def generate_launch_arguments() -> List[DeclareLaunchArgument]: DeclareLaunchArgument( "instance", default_value="0", - description="Set instance of SITL " - "(adds 10*instance to all port numbers).", + description="Set instance of SITL " "(adds 10*instance to all port numbers).", ), DeclareLaunchArgument( "defaults", @@ -599,8 +590,7 @@ def generate_launch_arguments() -> List[DeclareLaunchArgument]: DeclareLaunchArgument( "base_port", default_value="", - description="Set port num for base port(default 5670) " - "must be before -I option.", + description="Set port num for base port(default 5670) " "must be before -I option.", ), DeclareLaunchArgument( "rc_in_port", diff --git a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/utilities.py b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/utilities.py index 10a4396e9f6633..3df929793906bf 100644 --- a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/utilities.py +++ b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/utilities.py @@ -29,9 +29,7 @@ def listify(fn) -> List[LaunchDescriptionEntity]: """Wrap a functions's return value in a list.""" @wraps(fn) - def listify_helper( - context: LaunchContext, *args, **kwargs - ) -> List[LaunchDescriptionEntity]: + def listify_helper(context: LaunchContext, *args, **kwargs) -> List[LaunchDescriptionEntity]: return [fn(context, args, kwargs)] return listify_helper From d4c7601b1beca38366a012cbc564d13e6d7db466 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 21 Nov 2023 19:14:28 -0700 Subject: [PATCH 365/499] .pre-commit: Add Tools/ros2 to list of black formatted files Signed-off-by: Ryan Friedman --- .pre-commit-config.yaml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 44def5fb51b4fe..9c15396246364a 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -50,7 +50,11 @@ repos: rev: 23.7.0 hooks: - id: black - files: libraries\/AP_DDS\/(wscript|.*\.py)$ + files: | + (?x)^( + libraries\/AP_DDS\/(wscript|.*\.py)$ | + Tools/ros2/.*\.py + )$ # # Use to sort python imports by name and put system import first. # - repo: https://github.com/pycqa/isort From 61e2c5fda1cc08103eaa4f05ee557731ea9faeba Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 21 Nov 2023 19:15:13 -0700 Subject: [PATCH 366/499] Tools: ros2: Enforce black instead of flake8 * Removed dependency on ament_lint_common * Removed all flake8 artifacts * Ordered linters alphabetically Signed-off-by: Ryan Friedman --- Tools/ros2/ardupilot_dds_tests/.flake8 | 10 ------- Tools/ros2/ardupilot_dds_tests/package.xml | 5 +++- .../ardupilot_dds_tests/test/test_flake8.py | 27 ------------------- Tools/ros2/ardupilot_msgs/CMakeLists.txt | 5 ++++ Tools/ros2/ardupilot_msgs/package.xml | 3 ++- Tools/ros2/ardupilot_sitl/.flake8 | 10 ------- Tools/ros2/ardupilot_sitl/CMakeLists.txt | 3 --- Tools/ros2/ardupilot_sitl/package.xml | 10 +++++-- 8 files changed, 19 insertions(+), 54 deletions(-) delete mode 100644 Tools/ros2/ardupilot_dds_tests/.flake8 delete mode 100644 Tools/ros2/ardupilot_dds_tests/test/test_flake8.py delete mode 100644 Tools/ros2/ardupilot_sitl/.flake8 diff --git a/Tools/ros2/ardupilot_dds_tests/.flake8 b/Tools/ros2/ardupilot_dds_tests/.flake8 deleted file mode 100644 index b79f25fa411990..00000000000000 --- a/Tools/ros2/ardupilot_dds_tests/.flake8 +++ /dev/null @@ -1,10 +0,0 @@ -[flake8] -# Match black line length (default 88). -max-line-length = 88 -# Match black configuration where there are conflicts. -extend-ignore = - # Q000: Double quotes found but single quotes preferred - Q000, - # W503: Line break before binary operator - W503 - diff --git a/Tools/ros2/ardupilot_dds_tests/package.xml b/Tools/ros2/ardupilot_dds_tests/package.xml index 8e21f9ed4bd0ce..7b44fbffdcbf94 100644 --- a/Tools/ros2/ardupilot_dds_tests/package.xml +++ b/Tools/ros2/ardupilot_dds_tests/package.xml @@ -17,9 +17,12 @@ rclpy socat + ament_black ament_copyright - ament_flake8 ament_pep257 + ament_uncrustify + ament_xmllint + ament_lint_auto ardupilot_sitl launch launch_pytest diff --git a/Tools/ros2/ardupilot_dds_tests/test/test_flake8.py b/Tools/ros2/ardupilot_dds_tests/test/test_flake8.py deleted file mode 100644 index 17771247a54724..00000000000000 --- a/Tools/ros2/ardupilot_dds_tests/test/test_flake8.py +++ /dev/null @@ -1,27 +0,0 @@ -# Copyright 2017 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -"""Test Python files satisfy the flake8 linter requirements.""" -from ament_flake8.main import main_with_errors -import pytest - - -@pytest.mark.flake8 -@pytest.mark.linter -def test_flake8(): - """flake8 test case.""" - rc, errors = main_with_errors(argv=[]) - assert rc == 0, "Found %d code style errors / warnings:\n" % len( - errors - ) + "\n".join(errors) diff --git a/Tools/ros2/ardupilot_msgs/CMakeLists.txt b/Tools/ros2/ardupilot_msgs/CMakeLists.txt index 5a56bd31cc3572..8096431370687c 100644 --- a/Tools/ros2/ardupilot_msgs/CMakeLists.txt +++ b/Tools/ros2/ardupilot_msgs/CMakeLists.txt @@ -18,6 +18,11 @@ rosidl_generate_interfaces(${PROJECT_NAME} ament_export_dependencies(rosidl_default_runtime) +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + # --------------------------------------------------------------------------- # # Call last. diff --git a/Tools/ros2/ardupilot_msgs/package.xml b/Tools/ros2/ardupilot_msgs/package.xml index b2286616eb6987..08e92bf1df7d99 100644 --- a/Tools/ros2/ardupilot_msgs/package.xml +++ b/Tools/ros2/ardupilot_msgs/package.xml @@ -13,8 +13,9 @@ rosidl_default_runtime + ament_cmake_copyright + ament_cmake_xmllint ament_lint_auto - ament_lint_common rosidl_interface_packages diff --git a/Tools/ros2/ardupilot_sitl/.flake8 b/Tools/ros2/ardupilot_sitl/.flake8 deleted file mode 100644 index b79f25fa411990..00000000000000 --- a/Tools/ros2/ardupilot_sitl/.flake8 +++ /dev/null @@ -1,10 +0,0 @@ -[flake8] -# Match black line length (default 88). -max-line-length = 88 -# Match black configuration where there are conflicts. -extend-ignore = - # Q000: Double quotes found but single quotes preferred - Q000, - # W503: Line break before binary operator - W503 - diff --git a/Tools/ros2/ardupilot_sitl/CMakeLists.txt b/Tools/ros2/ardupilot_sitl/CMakeLists.txt index 9d40ea746d43b6..4b50d602da341b 100644 --- a/Tools/ros2/ardupilot_sitl/CMakeLists.txt +++ b/Tools/ros2/ardupilot_sitl/CMakeLists.txt @@ -88,9 +88,6 @@ ament_python_install_package(${PROJECT_NAME} # build tests if(BUILD_TESTING) - # Override default flake8 configuration. - set(ament_cmake_flake8_CONFIG_FILE ${CMAKE_SOURCE_DIR}/.flake8) - # Add linters. find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/Tools/ros2/ardupilot_sitl/package.xml b/Tools/ros2/ardupilot_sitl/package.xml index 2c3a375695013e..d0851a191e3a13 100644 --- a/Tools/ros2/ardupilot_sitl/package.xml +++ b/Tools/ros2/ardupilot_sitl/package.xml @@ -13,9 +13,15 @@ micro_ros_agent - ament_cmake_pytest ament_lint_auto - ament_lint_common + ament_cmake_black + ament_cmake_copyright + ament_cmake_lint_cmake + ament_cmake_pep257 + ament_cmake_pytest + ament_cmake_uncrustify + ament_cmake_xmllint + ament_cmake From 4fd54dccaf80cb28e087bc2858f15aae80a19f83 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 23 Nov 2023 09:52:09 +1100 Subject: [PATCH 367/499] autotest: correct python function typing bug around Dict vs dict --- Tools/autotest/vehicle_test_suite.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 2c65dce31c4667..caa4b0b711883b 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -20,6 +20,8 @@ import traceback from datetime import datetime from typing import List +from typing import Tuple +from typing import Dict import importlib.util import pexpect @@ -13803,7 +13805,7 @@ def autotest(self, tests=None, allow_skips=True, step_name=None): return len(self.fail_list) == 0 - def create_junit_report(self, test_name: str, results: List[Result], skip_list: list[tuple[Test, dict[str, str]]]) -> None: + def create_junit_report(self, test_name: str, results: List[Result], skip_list: List[Tuple[Test, Dict[str, str]]]) -> None: """Generate Junit report from the autotest results""" from junitparser import TestCase, TestSuite, JUnitXml, Skipped, Failure frame = self.vehicleinfo_key() From 4b61b3d64e42efab5b79de4f562febf954d208c9 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Thu, 23 Nov 2023 11:17:53 +1100 Subject: [PATCH 368/499] AP_Stats: initialise parameter defaults --- libraries/AP_Stats/AP_Stats.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Stats/AP_Stats.cpp b/libraries/AP_Stats/AP_Stats.cpp index 13992983a487da..2b5343a0876cb9 100644 --- a/libraries/AP_Stats/AP_Stats.cpp +++ b/libraries/AP_Stats/AP_Stats.cpp @@ -47,6 +47,7 @@ AP_Stats *AP_Stats::_singleton; // constructor AP_Stats::AP_Stats(void) { + AP_Param::setup_object_defaults(this, var_info); _singleton = this; } From 47a18596db24caa1e4a3062fe1ddbad3935ccbb3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 23 Nov 2023 10:07:41 +1100 Subject: [PATCH 369/499] AP_Periph: correct parameter documentation --- Tools/AP_Periph/rc_in.cpp | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/Tools/AP_Periph/rc_in.cpp b/Tools/AP_Periph/rc_in.cpp index 83f691bda2816b..63a584d684b828 100644 --- a/Tools/AP_Periph/rc_in.cpp +++ b/Tools/AP_Periph/rc_in.cpp @@ -33,7 +33,7 @@ extern const AP_HAL::HAL &hal; const AP_Param::GroupInfo Parameters_RCIN::var_info[] { // RC_PROTOCOLS copied from RC_Channel/RC_Channels_Varinfo.h - // @Param: RC_PROTOCOLS + // @Param: _PROTOCOLS // @DisplayName: RC protocols enabled // @Description: Bitmask of enabled RC protocols. Allows narrowing the protocol detection to only specific types of RC receivers which can avoid issues with incorrect detection. Set to 1 to enable all protocols. // @User: Advanced @@ -41,7 +41,7 @@ const AP_Param::GroupInfo Parameters_RCIN::var_info[] { AP_GROUPINFO("_PROTOCOLS", 1, Parameters_RCIN, rcin_protocols, 1), // RC_PROTOCOLS copied from RC_Channel/RC_Channels_Varinfo.h - // @Param: RC_MSGRATE + // @Param: _MSGRATE // @DisplayName: DroneCAN RC Message rate // @Description: Rate at which RC input is sent via DroneCAN // @User: Advanced @@ -50,7 +50,7 @@ const AP_Param::GroupInfo Parameters_RCIN::var_info[] { // @Units: Hz AP_GROUPINFO("_MSGRATE", 2, Parameters_RCIN, rcin_rate_hz, 50), - // @Param: RC1_PORT + // @Param: 1_PORT // @DisplayName: RC input port // @Description: This is the serial port number where SERIALx_PROTOCOL will be set to RC input. // @Range: 0 10 @@ -59,9 +59,8 @@ const AP_Param::GroupInfo Parameters_RCIN::var_info[] { // @RebootRequired: True AP_GROUPINFO("_PORT", 3, Parameters_RCIN, rcin1_port, AP_PERIPH_RC1_PORT_DEFAULT), - // @Param: RC1_PORT_OPTIONS + // @Param: 1_PORT_OPTIONS // @DisplayName: RC input port serial options - // @Description: This is the serial port number where SERIALx_PROTOCOL will be set to RC input. // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards. // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:SwapTXRX, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA, 10: Don't forward mavlink to/from, 11: DisableFIFO, 12: Ignore Streamrate AP_GROUPINFO("1_PORT_OPTIONS", 4, Parameters_RCIN, rcin1_port_options, AP_PERIPH_RC1_PORT_OPTIONS_DEFAULT), From 6809f243f10631946dad5d50952bd069cb61783e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 23 Nov 2023 10:07:56 +1100 Subject: [PATCH 370/499] Tools: CI: build AP_Periph parameters in CI --- Tools/scripts/build_ci.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index 3011ce83d2b550..6223c2c0b09cf3 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -451,7 +451,7 @@ for t in $CI_BUILD_TARGET; do fi if [ "$t" == "param_parse" ]; then - for v in Rover AntennaTracker ArduCopter ArduPlane ArduSub Blimp; do + for v in Rover AntennaTracker ArduCopter ArduPlane ArduSub Blimp AP_Periph; do python Tools/autotest/param_metadata/param_parse.py --vehicle $v done continue From 14aeb831fb98c4f8d5e2283b10ac95624476fb40 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 21 Nov 2023 17:46:30 -0700 Subject: [PATCH 371/499] AP_DDS: Add instructions for running HW test Signed-off-by: Ryan Friedman --- libraries/AP_DDS/README.md | 37 +++++++++++++++++++++++++++++++++++++ 1 file changed, 37 insertions(+) diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index b148fa23e079bc..1af0af6f6001a1 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -377,3 +377,40 @@ This will run the tools automatically when you commit. If there are changes, jus pre-commit install git commit ``` + +## Testing DDS on Hardware + +### With Serial + +The easiest way to test DDS is to make use of some boards providing two serial interfaces over USB such as the Pixhawk 6X. +The [Pixhawk6X/hwdef.dat](../AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat) file has this info. +``` +SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 +``` + +For example, build, flash, and set up OTG2 for DDS +```bash +./waf configure --board Pixhawk6X --enable-dds +./waf plane --upload +mavproxy.py --console +param set DDS_ENABLE 1 +# Check the hwdef file for which port is OTG2 +param set SERIAL8_PROTOCOL 45 +param set SERIAL8_BAUD 115 +reboot +``` + +Then run the Micro ROS agent +```bash +cd /path/to/ros2_ws +source install/setup.bash +cd src/ardupilot/libraries/AP_DDS +ros2 run micro_ros_agent micro_ros_agent serial -b 115200 -r dds_xrce_profile.xml -D /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02 +``` + +If connection fails, instead of running the Micro ROS agent, debug the stream +```bash +python3 -m serial.tools.miniterm /dev/serial/by-id/usb-ArduPilot_Pixhawk6X_210028000151323131373139-if02 115200 --echo --encoding hexlify +``` + +The same steps can be done for physical serial ports once the above works to isolate software and hardware issues. From a8e2908e8b998aef55018a7347ce80cf1e695aa8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 23 Nov 2023 10:16:39 +1100 Subject: [PATCH 372/499] autotest: build AP_Periph parameters in autotest --- Tools/autotest/autotest.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 3e3fac36a55514..616411b7165a8a 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -186,7 +186,9 @@ def all_vehicles(): 'Rover', 'AntennaTracker', 'ArduSub', - 'Blimp') + 'Blimp', + 'AP_Periph', + ) def build_parameters(): From 8718261f27db546c701ea467daf9b5daecd594de Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 22 Nov 2023 13:45:41 +0000 Subject: [PATCH 373/499] AP_Periph: add CAN_TERMINATE for software driven termination --- Tools/AP_Periph/Parameters.cpp | 22 ++++++++++++++++++++++ Tools/AP_Periph/Parameters.h | 6 ++++++ Tools/AP_Periph/can.cpp | 10 ++++++++++ 3 files changed, 38 insertions(+) diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 02da8a657a23be..7e17cb8daed180 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -107,6 +107,16 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GSCALAR(can_slcan_cport, "CAN_SLCAN_CPORT", 1), #endif +#ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM + // @Param: CAN_TERMINATE + // @DisplayName: Enable CAN software temination in this node + // @Description: Enable CAN software temination in this node + // @Values: 0:Disabled,1:Enabled + // @User: Advanced + // @RebootRequired: True + GARRAY(can_terminate, 0, "CAN_TERMINATE", 0), +#endif + #if HAL_NUM_CAN_IFACES >= 2 // @Param: CAN_PROTOCOL // @DisplayName: Enable use of specific protocol to be used on this port @@ -124,6 +134,12 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Param: CAN2_PROTOCOL // @CopyFieldsFrom: CAN_PROTOCOL GARRAY(can_protocol, 1, "CAN2_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)), + +#ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM + // @Param: CAN2_TERMINATE + // @CopyFieldsFrom: CAN_TERMINATE + GARRAY(can_terminate, 1, "CAN2_TERMINATE", 0), +#endif #endif #if HAL_NUM_CAN_IFACES >= 3 @@ -135,6 +151,12 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { // @Param: CAN3_PROTOCOL // @CopyFieldsFrom: CAN_PROTOCOL GARRAY(can_protocol, 2, "CAN3_PROTOCOL", float(AP_CAN::Protocol::DroneCAN)), + +#ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM + // @Param: CAN3_TERMINATE + // @CopyFieldsFrom: CAN_TERMINATE + GARRAY(can_terminate, 2, "CAN3_TERMINATE", 0), +#endif #endif #if HAL_CANFD_SUPPORTED diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index fb4a628b021099..a2a439b31fcb97 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -85,6 +85,9 @@ class Parameters { k_param_battery_hide_mask, k_param_can_mirror_ports, k_param_rtc, + k_param_can_terminate0, + k_param_can_terminate1, + k_param_can_terminate2, }; AP_Int16 format_version; @@ -205,6 +208,9 @@ class Parameters { #else static constexpr uint8_t can_fdmode = 0; #endif + + AP_Int8 can_terminate[HAL_NUM_CAN_IFACES]; + AP_Int8 node_stats; Parameters() {} }; diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 01adff69a5f60c..89611c5cac5477 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -1576,6 +1576,16 @@ void AP_Periph_FW::can_start() } #endif // HAL_PERIPH_ENFORCE_AT_LEAST_ONE_PORT_IS_UAVCAN_1MHz +#ifdef HAL_GPIO_PIN_GPIO_CAN1_TERM + palWriteLine(HAL_GPIO_PIN_GPIO_CAN1_TERM, g.can_terminate[0]); +#endif +#ifdef HAL_GPIO_PIN_GPIO_CAN2_TERM + palWriteLine(HAL_GPIO_PIN_GPIO_CAN2_TERM, g.can_terminate[1]); +#endif +#ifdef HAL_GPIO_PIN_GPIO_CAN3_TERM + palWriteLine(HAL_GPIO_PIN_GPIO_CAN3_TERM, g.can_terminate[2]); +#endif + for (uint8_t i=0; i Date: Thu, 23 Nov 2023 00:13:08 -0700 Subject: [PATCH 374/499] Tools: autotest: Fix junit printing for double str * Can't concetenate a double to a string without fstring or a type change Signed-off-by: Ryan Friedman --- Tools/autotest/vehicle_test_suite.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index caa4b0b711883b..c44aef485f5842 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -1479,15 +1479,15 @@ def __init__(self, test): def __str__(self): ret = " %s (%s)" % (self.test.name, self.test.description) if self.passed: - return ret + " OK" + return f"{ret} OK" if self.reason is not None: - ret += " (" + self.reason + ")" + ret += f" ({self.reason} )" if self.exception is not None: - ret += " (" + str(self.exception) + ")" + ret += f" ({str(self.exception)})" if self.debug_filename is not None: - ret += " (see " + self.debug_filename + ")" + ret += f" (see {self.debug_filename})" if self.time_elapsed is not None: - ret += " (duration " + self.time_elapsed + "s)" + ret += f" (duration {self.time_elapsed} s)" return ret From 58cf4f65a90f8bcb26f7cdb5c599c07a5779e12d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 23 Nov 2023 16:56:12 +1100 Subject: [PATCH 375/499] HAL_SITL: use SocketAPM for CAN multicast and SITL_Periph state --- libraries/AP_HAL_SITL/CAN_Multicast.cpp | 94 +-------------------- libraries/AP_HAL_SITL/CAN_Multicast.h | 5 +- libraries/AP_HAL_SITL/SITL_Periph_State.cpp | 89 +++---------------- libraries/AP_HAL_SITL/SITL_Periph_State.h | 5 +- 4 files changed, 21 insertions(+), 172 deletions(-) diff --git a/libraries/AP_HAL_SITL/CAN_Multicast.cpp b/libraries/AP_HAL_SITL/CAN_Multicast.cpp index b83642f7ef73c0..fe843473241a37 100644 --- a/libraries/AP_HAL_SITL/CAN_Multicast.cpp +++ b/libraries/AP_HAL_SITL/CAN_Multicast.cpp @@ -38,83 +38,9 @@ bool CAN_Multicast::init(uint8_t instance) { // setup incoming multicast socket char address[] = MCAST_ADDRESS_BASE; - struct sockaddr_in sockaddr {}; - struct ip_mreq mreq {}; - int one = 1; - int ret; -#ifdef HAVE_SOCK_SIN_LEN - sockaddr.sin_len = sizeof(sockaddr); -#endif address[strlen(address)-1] = '0' + instance; - - sockaddr.sin_port = htons(MCAST_PORT); - sockaddr.sin_family = AF_INET; - sockaddr.sin_addr.s_addr = inet_addr(address); - - fd_in = socket(AF_INET, SOCK_DGRAM, 0); - if (fd_in == -1) { - goto fail; - } - ret = fcntl(fd_in, F_SETFD, FD_CLOEXEC); - if (ret == -1) { - goto fail; - } - if (setsockopt(fd_in, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) { - goto fail; - } - - // close on exec, to allow reboot - fcntl(fd_in, F_SETFD, FD_CLOEXEC); - -#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD) - /* - on cygwin you need to bind to INADDR_ANY then use the multicast - IP_ADD_MEMBERSHIP to get on the right address - */ - sockaddr.sin_addr.s_addr = htonl(INADDR_ANY); -#endif - - ret = bind(fd_in, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); - if (ret == -1) { - goto fail; - } - - mreq.imr_multiaddr.s_addr = inet_addr(address); - mreq.imr_interface.s_addr = htonl(INADDR_ANY); - - ret = setsockopt(fd_in, IPPROTO_IP, IP_ADD_MEMBERSHIP, &mreq, sizeof(mreq)); - if (ret == -1) { - goto fail; - } - - // setup outgoing socket - fd_out = socket(AF_INET, SOCK_DGRAM, 0); - if (fd_out == -1) { - goto fail; - } - ret = fcntl(fd_out, F_SETFD, FD_CLOEXEC); - if (ret == -1) { - goto fail; - } - - ret = connect(fd_out, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); - if (ret == -1) { - goto fail; - } - - return true; - -fail: - if (fd_in != -1) { - (void)close(fd_in); - fd_in = -1; - } - if (fd_out != -1) { - (void)close(fd_out); - fd_out = -1; - } - return false; + return sock.connect(address, MCAST_PORT); } /* @@ -135,7 +61,7 @@ bool CAN_Multicast::send(const AP_HAL::CANFrame &frame) memcpy(pkt.data, frame.data, data_length); pkt.crc = crc16_ccitt((uint8_t*)&pkt.flags, data_length+6, 0xFFFFU); - return ::send(fd_out, (void*)&pkt, data_length+10, 0) == data_length+10; + return sock.send((void*)&pkt, data_length+10) == data_length+10; } /* @@ -144,9 +70,7 @@ bool CAN_Multicast::send(const AP_HAL::CANFrame &frame) bool CAN_Multicast::receive(AP_HAL::CANFrame &frame) { struct mcast_pkt pkt; - struct sockaddr_in src_addr; - socklen_t src_len = sizeof(src_addr); - ssize_t ret = ::recvfrom(fd_in, (void*)&pkt, sizeof(pkt), MSG_DONTWAIT, (struct sockaddr *)&src_addr, &src_len); + ssize_t ret = sock.recv((void*)&pkt, sizeof(pkt), 0); if (ret < 10) { return false; } @@ -157,18 +81,6 @@ bool CAN_Multicast::receive(AP_HAL::CANFrame &frame) return false; } - // ensure it isn't a packet we sent - struct sockaddr_in send_addr; - socklen_t send_len = sizeof(send_addr); - if (getsockname(fd_out, (struct sockaddr *)&send_addr, &send_len) != 0) { - return false; - } - if (src_addr.sin_port == send_addr.sin_port && - src_addr.sin_family == send_addr.sin_family && - src_addr.sin_addr.s_addr == send_addr.sin_addr.s_addr) { - return false; - } - // run constructor to initialise new(&frame) AP_HAL::CANFrame(pkt.message_id, pkt.data, ret-10, (pkt.flags & MCAST_FLAG_CANFD) != 0); diff --git a/libraries/AP_HAL_SITL/CAN_Multicast.h b/libraries/AP_HAL_SITL/CAN_Multicast.h index be8144cb65ec9f..d3725458e3d4fc 100644 --- a/libraries/AP_HAL_SITL/CAN_Multicast.h +++ b/libraries/AP_HAL_SITL/CAN_Multicast.h @@ -13,12 +13,11 @@ class CAN_Multicast : public CAN_Transport { bool send(const AP_HAL::CANFrame &frame) override; bool receive(AP_HAL::CANFrame &frame) override; int get_read_fd(void) const override { - return fd_in; + return sock.get_read_fd(); } private: - int fd_in = -1; - int fd_out = -1; + SocketAPM sock{true}; }; #endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index f72214aa46d697..27f1b063c86a42 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -138,59 +138,11 @@ void SITL_State::wait_clock(uint64_t wait_time_usec) */ void SimMCast::multicast_open(void) { - struct sockaddr_in sockaddr {}; - int ret; - -#ifdef HAVE_SOCK_SIN_LEN - sockaddr.sin_len = sizeof(sockaddr); -#endif - sockaddr.sin_port = htons(SITL_MCAST_PORT); - sockaddr.sin_family = AF_INET; - sockaddr.sin_addr.s_addr = inet_addr(SITL_MCAST_IP); - - mc_fd = socket(AF_INET, SOCK_DGRAM, 0); - if (mc_fd == -1) { - fprintf(stderr, "socket failed - %s\n", strerror(errno)); - exit(1); - } - ret = fcntl(mc_fd, F_SETFD, FD_CLOEXEC); - if (ret == -1) { - fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno)); - exit(1); - } - int one = 1; - if (setsockopt(mc_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) { - fprintf(stderr, "setsockopt failed: %s\n", strerror(errno)); - exit(1); - } - -#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD) - /* - on cygwin you need to bind to INADDR_ANY then use the multicast - IP_ADD_MEMBERSHIP to get on the right address - */ - sockaddr.sin_addr.s_addr = htonl(INADDR_ANY); -#endif - - ret = bind(mc_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); - if (ret == -1) { - fprintf(stderr, "multicast bind failed on port %u - %s\n", - (unsigned)ntohs(sockaddr.sin_port), - strerror(errno)); - exit(1); - } - - struct ip_mreq mreq {}; - mreq.imr_multiaddr.s_addr = inet_addr(SITL_MCAST_IP); - mreq.imr_interface.s_addr = htonl(INADDR_ANY); - - ret = setsockopt(mc_fd, IPPROTO_IP, IP_ADD_MEMBERSHIP, &mreq, sizeof(mreq)); - if (ret == -1) { - fprintf(stderr, "multicast membership add failed on port %u - %s\n", - (unsigned)ntohs(sockaddr.sin_port), - strerror(errno)); + if (!sock.connect(SITL_MCAST_IP, SITL_MCAST_PORT)) { + fprintf(stderr, "multicast socket failed - %s\n", strerror(errno)); exit(1); } + servo_sock.set_blocking(false); ::printf("multicast receiver initialised\n"); } @@ -199,29 +151,17 @@ void SimMCast::multicast_open(void) */ void SimMCast::servo_fd_open(void) { - servo_fd = socket(AF_INET, SOCK_DGRAM, 0); - if (servo_fd == -1) { - fprintf(stderr, "socket failed - %s\n", strerror(errno)); - exit(1); - } - int ret = fcntl(servo_fd, F_SETFD, FD_CLOEXEC); - if (ret == -1) { - fprintf(stderr, "fcntl failed on setting FD_CLOEXEC - %s\n", strerror(errno)); - exit(1); - } - int one = 1; - if (setsockopt(servo_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) { - fprintf(stderr, "setsockopt failed: %s\n", strerror(errno)); - exit(1); + const char *in_addr = nullptr; + uint16_t port; + sock.last_recv_address(in_addr, port); + if (in_addr == nullptr) { + return; } - - in_addr.sin_port = htons(SITL_SERVO_PORT); - - ret = connect(servo_fd, (struct sockaddr *)&in_addr, sizeof(in_addr)); - if (ret == -1) { - fprintf(stderr, "multicast servo connect failed\n"); + if (!servo_sock.connect(in_addr, SITL_SERVO_PORT)) { + fprintf(stderr, "servo socket failed - %s\n", strerror(errno)); exit(1); } + servo_sock.set_blocking(false); } /* @@ -241,7 +181,7 @@ void SimMCast::servo_send(void) for (uint8_t i=0; istate.timestamp_us == 0) { @@ -278,7 +217,7 @@ void SimMCast::multicast_read(void) } hal.scheduler->stop_clock(_sitl->state.timestamp_us + base_time_us); HALSITL::Scheduler::timer_event(); - if (servo_fd == -1) { + if (!servo_sock.is_connected()) { servo_fd_open(); } else { servo_send(); diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.h b/libraries/AP_HAL_SITL/SITL_Periph_State.h index 7a9d3ec757110a..b7e21d1491cc94 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.h +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.h @@ -30,9 +30,8 @@ class SimMCast : public SITL::Aircraft { void update(const struct sitl_input &input) override; private: - int mc_fd = -1; - int servo_fd = -1; - struct sockaddr_in in_addr; + SocketAPM sock{true}; + SocketAPM servo_sock{true}; // offset between multicast timestamp and local timestamp uint64_t base_time_us; From 68e2bb1f15b18dde2b72562e25a1cfaa14898f54 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 25 Nov 2023 12:53:00 +1100 Subject: [PATCH 376/499] AP_Networking: enable receive of multicast packets --- libraries/AP_Networking/AP_Networking_ChibiOS.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp index 84e6f491ce2f13..442efdc454a0ac 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -121,6 +121,13 @@ bool AP_Networking_ChibiOS::init() lwipInit(lwip_options); +#if LWIP_IGMP + if (ETH != nullptr) { + // enbale "permit multicast" so we can receive multicast packets + ETH->MACPFR |= ETH_MACPFR_PM; + } +#endif + return true; } From 3f76a552752903358a99bfc90fc7f6a135dda01c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 25 Nov 2023 12:53:55 +1100 Subject: [PATCH 377/499] ChibiOS: submodule update fixed multicast receive and update lwip to 2.2.0 --- modules/ChibiOS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/ChibiOS b/modules/ChibiOS index 3ef1657d53e643..3241db7d757922 160000 --- a/modules/ChibiOS +++ b/modules/ChibiOS @@ -1 +1 @@ -Subproject commit 3ef1657d53e643aa61f7268ab4b8596bf6826fdb +Subproject commit 3241db7d7579228656bb51435af78d8b7ceda0a4 From ee592476ce43414ba9f8dad164360c22bbf31299 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 26 Nov 2023 06:05:47 +1100 Subject: [PATCH 378/499] AP_HAL: implement multicast for UDP sockets --- libraries/AP_HAL/utility/Socket.cpp | 175 +++++++++++++++++++--------- libraries/AP_HAL/utility/Socket.h | 15 +++ 2 files changed, 133 insertions(+), 57 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 0cb09f63b44929..89215913c35e24 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -23,12 +23,18 @@ #include "Socket.h" #include +#if AP_NETWORKING_BACKEND_CHIBIOS +#define CALL_PREFIX(x) ::lwip_##x +#else +#define CALL_PREFIX(x) ::x +#endif + /* constructor */ SocketAPM::SocketAPM(bool _datagram) : SocketAPM(_datagram, - socket(AF_INET, _datagram?SOCK_DGRAM:SOCK_STREAM, 0)) + CALL_PREFIX(socket)(AF_INET, _datagram?SOCK_DGRAM:SOCK_STREAM, 0)) {} SocketAPM::SocketAPM(bool _datagram, int _fd) : @@ -36,24 +42,24 @@ SocketAPM::SocketAPM(bool _datagram, int _fd) : fd(_fd) { #ifdef FD_CLOEXEC - fcntl(fd, F_SETFD, FD_CLOEXEC); + CALL_PREFIX(fcntl)(fd, F_SETFD, FD_CLOEXEC); #endif if (!datagram) { int one = 1; - setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); + CALL_PREFIX(setsockopt)(fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); } } SocketAPM::~SocketAPM() { if (fd != -1) { -#if AP_NETWORKING_BACKEND_CHIBIOS - ::lwip_close(fd); -#else - ::close(fd); -#endif + CALL_PREFIX(close)(fd); fd = -1; } + if (fd_in != -1) { + CALL_PREFIX(close)(fd_in); + fd_in = -1; + } } void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr) @@ -74,16 +80,58 @@ void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockadd bool SocketAPM::connect(const char *address, uint16_t port) { struct sockaddr_in sockaddr; + int ret; make_sockaddr(address, port, sockaddr); -#if AP_NETWORKING_BACKEND_CHIBIOS - if (::lwip_connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { -#else - if (::connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { + if (datagram && is_multicast_address(sockaddr)) { + /* + connect fd_in as a multicast UDP socket + */ + fd_in = CALL_PREFIX(socket)(AF_INET, SOCK_DGRAM, 0); + if (fd_in == -1) { + return false; + } + struct sockaddr_in sockaddr_mc = sockaddr; + int one = 1; + struct ip_mreq mreq {}; +#ifdef FD_CLOEXEC + CALL_PREFIX(fcntl)(fd_in, F_SETFD, FD_CLOEXEC); #endif + IGNORE_RETURN(CALL_PREFIX(setsockopt)(fd_in, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one))); + +#if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD) + /* + on cygwin you need to bind to INADDR_ANY then use the multicast + IP_ADD_MEMBERSHIP to get on the right address + */ + sockaddr_mc.sin_addr.s_addr = htonl(INADDR_ANY); +#endif + + ret = CALL_PREFIX(bind)(fd_in, (struct sockaddr *)&sockaddr_mc, sizeof(sockaddr)); + if (ret == -1) { + goto fail_mc; + } + + mreq.imr_multiaddr.s_addr = sockaddr.sin_addr.s_addr; + mreq.imr_interface.s_addr = htonl(INADDR_ANY); + + ret = CALL_PREFIX(setsockopt)(fd_in, IPPROTO_IP, IP_ADD_MEMBERSHIP, &mreq, sizeof(mreq)); + if (ret == -1) { + goto fail_mc; + } + } + + ret = CALL_PREFIX(connect)(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); + if (ret != 0) { return false; } + connected = true; return true; + +fail_mc: + CALL_PREFIX(close)(fd_in); + fd_in = -1; + return false; } /* @@ -96,11 +144,7 @@ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t tim set_blocking(false); -#if AP_NETWORKING_BACKEND_CHIBIOS - int ret = ::lwip_connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); -#else - int ret = ::connect(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); -#endif + int ret = CALL_PREFIX(connect)(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); if (ret == 0) { // instant connect? return true; @@ -117,7 +161,8 @@ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t tim if (getsockopt(fd, SOL_SOCKET, SO_ERROR, (void*)&sock_error, &len) != 0) { return false; } - return sock_error == 0; + connected = sock_error == 0; + return connected; } /* @@ -128,11 +173,7 @@ bool SocketAPM::bind(const char *address, uint16_t port) struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); -#if AP_NETWORKING_BACKEND_CHIBIOS - if (::lwip_bind(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { -#else - if (::bind(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { -#endif + if (CALL_PREFIX(bind)(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { return false; } return true; @@ -145,7 +186,7 @@ bool SocketAPM::bind(const char *address, uint16_t port) bool SocketAPM::reuseaddress(void) const { int one = 1; - return (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1); + return (CALL_PREFIX(setsockopt)(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1); } /* @@ -155,9 +196,15 @@ bool SocketAPM::set_blocking(bool blocking) const { int fcntl_ret; if (blocking) { - fcntl_ret = fcntl(fd, F_SETFL, fcntl(fd, F_GETFL, 0) & ~O_NONBLOCK); + fcntl_ret = CALL_PREFIX(fcntl)(fd, F_SETFL, CALL_PREFIX(fcntl)(fd, F_GETFL, 0) & ~O_NONBLOCK); + if (fd_in != -1) { + fcntl_ret |= CALL_PREFIX(fcntl)(fd_in, F_SETFL, CALL_PREFIX(fcntl)(fd_in, F_GETFL, 0) & ~O_NONBLOCK); + } } else { - fcntl_ret = fcntl(fd, F_SETFL, fcntl(fd, F_GETFL, 0) | O_NONBLOCK); + fcntl_ret = CALL_PREFIX(fcntl)(fd, F_SETFL, CALL_PREFIX(fcntl)(fd, F_GETFL, 0) | O_NONBLOCK); + if (fd_in != -1) { + fcntl_ret |= CALL_PREFIX(fcntl)(fd_in, F_SETFL, CALL_PREFIX(fcntl)(fd_in, F_GETFL, 0) | O_NONBLOCK); + } } return fcntl_ret != -1; } @@ -168,7 +215,7 @@ bool SocketAPM::set_blocking(bool blocking) const bool SocketAPM::set_cloexec() const { #ifdef FD_CLOEXEC - return (fcntl(fd, F_SETFD, FD_CLOEXEC) != -1); + return (CALL_PREFIX(fcntl)(fd, F_SETFD, FD_CLOEXEC) != -1); #else return false; #endif @@ -179,11 +226,7 @@ bool SocketAPM::set_cloexec() const */ ssize_t SocketAPM::send(const void *buf, size_t size) const { -#if AP_NETWORKING_BACKEND_CHIBIOS - return ::lwip_send(fd, buf, size, 0); -#else - return ::send(fd, buf, size, 0); -#endif + return CALL_PREFIX(send)(fd, buf, size, 0); } /* @@ -193,11 +236,7 @@ ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uin { struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); -#if AP_NETWORKING_BACKEND_CHIBIOS - return ::lwip_sendto(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); -#else - return ::sendto(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); -#endif + return CALL_PREFIX(sendto)(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); } /* @@ -209,11 +248,29 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) return -1; } socklen_t len = sizeof(in_addr); -#if AP_NETWORKING_BACKEND_CHIBIOS - return ::lwip_recvfrom(fd, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); -#else - return ::recvfrom(fd, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); -#endif + int fin = get_read_fd(); + ssize_t ret; + ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); + if (ret <= 0) { + return ret; + } + if (fd_in != -1) { + /* + for multicast check we are not receiving from ourselves + */ + struct sockaddr_in send_addr; + socklen_t send_len = sizeof(send_addr); + if (CALL_PREFIX(getsockname)(fd, (struct sockaddr *)&send_addr, &send_len) != 0) { + return -1; + } + if (in_addr.sin_port == send_addr.sin_port && + in_addr.sin_family == send_addr.sin_family && + in_addr.sin_addr.s_addr == send_addr.sin_addr.s_addr) { + // discard packets from ourselves + return -1; + } + } + return ret; } /* @@ -228,7 +285,7 @@ void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const void SocketAPM::set_broadcast(void) const { int one = 1; - setsockopt(fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one)); + CALL_PREFIX(setsockopt)(fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one)); } /* @@ -240,12 +297,13 @@ bool SocketAPM::pollin(uint32_t timeout_ms) struct timeval tv; FD_ZERO(&fds); - FD_SET(fd, &fds); + int fin = get_read_fd(); + FD_SET(fin, &fds); tv.tv_sec = timeout_ms / 1000; tv.tv_usec = (timeout_ms % 1000) * 1000UL; - if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) { + if (CALL_PREFIX(select)(fin+1, &fds, nullptr, nullptr, &tv) != 1) { return false; } return true; @@ -266,7 +324,7 @@ bool SocketAPM::pollout(uint32_t timeout_ms) tv.tv_sec = timeout_ms / 1000; tv.tv_usec = (timeout_ms % 1000) * 1000UL; - if (select(fd+1, nullptr, &fds, nullptr, &tv) != 1) { + if (CALL_PREFIX(select)(fd+1, nullptr, &fds, nullptr, &tv) != 1) { return false; } return true; @@ -277,11 +335,7 @@ bool SocketAPM::pollout(uint32_t timeout_ms) */ bool SocketAPM::listen(uint16_t backlog) const { -#if AP_NETWORKING_BACKEND_CHIBIOS - return ::lwip_listen(fd, (int)backlog) == 0; -#else - return ::listen(fd, (int)backlog) == 0; -#endif + return CALL_PREFIX(listen)(fd, (int)backlog) == 0; } /* @@ -294,18 +348,25 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) return nullptr; } -#if AP_NETWORKING_BACKEND_CHIBIOS - int newfd = ::lwip_accept(fd, nullptr, nullptr); -#else - int newfd = ::accept(fd, nullptr, nullptr); -#endif + int newfd = CALL_PREFIX(accept)(fd, nullptr, nullptr); if (newfd == -1) { return nullptr; } // turn off nagle for lower latency int one = 1; - setsockopt(newfd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); + CALL_PREFIX(setsockopt)(newfd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); return new SocketAPM(false, newfd); } +/* + return true if an address is in the multicast range + */ +bool SocketAPM::is_multicast_address(struct sockaddr_in &addr) const +{ + const uint32_t mc_lower = 0xE0000000; // 224.0.0.0 + const uint32_t mc_upper = 0xEFFFFFFF; // 239.255.255.255 + const uint32_t haddr = ntohl(addr.sin_addr.s_addr); + return haddr >= mc_lower && haddr <= mc_upper; +} + #endif // AP_NETWORKING_BACKEND_ANY diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index a20cbbda0e9e45..76ac0974c508a7 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -70,12 +70,27 @@ class SocketAPM { // listen has been used. A new socket is returned SocketAPM *accept(uint32_t timeout_ms); + // get a FD suitable for read selection + int get_read_fd(void) const { + return fd_in != -1? fd_in : fd; + } + + bool is_connected(void) const { + return connected; + } + private: bool datagram; struct sockaddr_in in_addr {}; + bool is_multicast_address(struct sockaddr_in &addr) const; int fd = -1; + // fd_in is used for multicast UDP + int fd_in = -1; + + bool connected; + void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr); }; From ddba794420c4fe0c1bfb19cc893aee6d48a717da Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Wed, 22 Nov 2023 15:39:47 -0700 Subject: [PATCH 379/499] hwdef: ark_rtk_gps fix safety led --- libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat index 138ab20ea1f03e..05ed9e1d27ddb6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_RTK_GPS/hwdef.dat @@ -36,7 +36,7 @@ SERIAL_ORDER USART2 USART1 PA0 TIM2_CH1 TIM2 GPIO(77) LOW ALARM # safety LED, active low -PA1 SAFE_LED OUTPUT HIGH +PA1 SAFE_LED OUTPUT OPENDRAIN HIGH GPIO(3) define SAFE_LED_ON 0 # USART1 for GPS with DMA From 27f836b66e5af82ae40c113721307649d9dd977b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 22 Nov 2023 22:01:43 +1100 Subject: [PATCH 380/499] hwdef: correct ARK_CANNODE compilation this was turning SPI on when there aren't any devices... --- libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat index 5c6f22eee05d6b..8fa2061e0ab906 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat @@ -110,8 +110,6 @@ PB9 I2C1_SDA I2C1 #SPIDEV icm42688 SPI1 DEVID1 IMU1_CS MODE3 2*MHZ 8*MHZ #IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180 -define HAL_USE_SPI TRUE - define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_COMPASS_MAX_SENSORS 1 From 8d4611f22fb0d10eeb91d0e4755529613a1a7781 Mon Sep 17 00:00:00 2001 From: yjuav Date: Wed, 22 Nov 2023 17:11:24 +0800 Subject: [PATCH 381/499] AP_Bootloader: reserve board id for YJUAV_A6Ultra --- Tools/AP_Bootloader/board_types.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index c9c2cb0ec83c5f..27bfe00e6a5ad0 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -256,6 +256,7 @@ AP_HW_PixPilot-C3 1140 AP_HW_YJUAV_A6SE_H743 1141 AP_HW_FSO_POWER_STACK 1142 AP_HW_ATOMRCF405NAVI_DLX 1143 +AP_HW_YJUAV_A6Ultra 1144 AP_HW_ESP32_PERIPH 1205 From 4ffcc56cdb78b1cdab054edc7730f12127f389f7 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Wed, 22 Nov 2023 14:34:24 -0700 Subject: [PATCH 382/499] .git-blame-ignore-revs: Ignore black format change Signed-off-by: Ryan Friedman --- .git-blame-ignore-revs | 6 ++++++ 1 file changed, 6 insertions(+) create mode 100644 .git-blame-ignore-revs diff --git a/.git-blame-ignore-revs b/.git-blame-ignore-revs new file mode 100644 index 00000000000000..80c607e02ac4a6 --- /dev/null +++ b/.git-blame-ignore-revs @@ -0,0 +1,6 @@ +# This file allows ignoring commits in git blame view on Github. +# For more info, see here: +# https://docs.github.com/en/repositories/working-with-files/using-files/viewing-a-file#ignore-commits-in-the-blame-view + +# Tools: ros2: Run ament_black on all files +85172b56467668bee9fa0e68081027b13bc18c4a From 8f9df5a62e25a4c6555c858389e1bc196ef8439c Mon Sep 17 00:00:00 2001 From: olliw42 Date: Fri, 24 Nov 2023 09:54:25 +0100 Subject: [PATCH 383/499] AP_Arming: Reduce response time when checks go from true to false --- libraries/AP_Arming/AP_Arming.cpp | 13 +++++++++++-- libraries/AP_Arming/AP_Arming.h | 3 +++ 2 files changed, 14 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 630340038c0e4f..b617c6d134c491 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -183,7 +183,9 @@ void AP_Arming::update(void) const uint32_t now_ms = AP_HAL::millis(); // perform pre-arm checks & display failures every 30 seconds bool display_fail = false; - if (now_ms - last_prearm_display_ms > PREARM_DISPLAY_PERIOD*1000) { + if ((report_immediately && (now_ms - last_prearm_display_ms > 4000)) || + (now_ms - last_prearm_display_ms > PREARM_DISPLAY_PERIOD*1000)) { + report_immediately = false; display_fail = true; last_prearm_display_ms = now_ms; } @@ -1540,7 +1542,7 @@ bool AP_Arming::pre_arm_checks(bool report) } #endif - return hardware_safety_check(report) + bool checks_result = hardware_safety_check(report) #if HAL_HAVE_IMU_HEATER & heater_min_temperature_checks(report) #endif @@ -1575,6 +1577,13 @@ bool AP_Arming::pre_arm_checks(bool report) & opendroneid_checks(report) & serial_protocol_checks(report) & estop_checks(report); + + if (!checks_result && last_prearm_checks_result) { // check went from true to false + report_immediately = true; + } + last_prearm_checks_result = checks_result; + + return checks_result; } bool AP_Arming::arm_checks(AP_Arming::Method method) diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index a67a74bcd04503..603e1b6b85a7a5 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -304,6 +304,9 @@ class AP_Arming { uint32_t last_prearm_display_ms; // last time we send statustexts for prearm failures bool running_arming_checks; // true if the arming checks currently being performed are being done because the vehicle is trying to arm the vehicle + bool last_prearm_checks_result; // result of last prearm check + bool report_immediately; // set to true when check goes from true to false, to trigger immediate report + void update_arm_gpio(); }; From 07cfd14828c0a7ed6d5d26de6066c6193a710d91 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Wed, 15 Nov 2023 22:25:26 -0700 Subject: [PATCH 384/499] Tools: remove enable-networking * This flag was already removed, but the flags were left around Signed-off-by: Ryan Friedman --- Tools/autotest/sim_vehicle.py | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 9540454e5231e3..0768bd91bd0d75 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -410,16 +410,12 @@ def do_build(opts, frame_options): if opts.enable_dds: cmd_configure.append("--enable-dds") - if configure_target == 'sitl' and "--enable-networking" not in cmd_configure: - cmd_configure.append("--enable-networking") if opts.disable_networking or configure_target != "sitl": cmd_configure.append("--disable-networking") if opts.enable_networking_tests: cmd_configure.append("--enable-networking-tests") - if "--enable-networking" not in cmd_configure: - cmd_configure.append("--enable-networking") pieces = [shlex.split(x) for x in opts.waf_configure_args] for piece in pieces: From bf6bd3a023da746cf21319138cab7cb6be3b2cef Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Wed, 15 Nov 2023 22:26:14 -0700 Subject: [PATCH 385/499] .github: Enable colcon tests in DDS CI * Use checkout v4 to pull in ArduPilot into a subdir first * Enable console cohesion during test since JUnit reporting is out of scope * Install mavproxy separately as needed, alternative to --console * Hide wget progress * Install local pymavlink Co-authored-by: Pierre Kancir Signed-off-by: Ryan Friedman --- .github/workflows/colcon.yml | 206 +++++++++++++++++++++++++++++++++++ 1 file changed, 206 insertions(+) create mode 100644 .github/workflows/colcon.yml diff --git a/.github/workflows/colcon.yml b/.github/workflows/colcon.yml new file mode 100644 index 00000000000000..e39af18fc16949 --- /dev/null +++ b/.github/workflows/colcon.yml @@ -0,0 +1,206 @@ +name: colcon build/test + +on: + push: + paths-ignore: + # remove not tests vehicles + - 'AntennaTracker/**' + - 'ArduSub/**' + - 'Blimp/**' + - 'Rover/**' + # remove esp32 HAL + - 'libraries/AP_HAL_ESP32/**' + # remove non SITL directories + - 'Tools/AP_Bootloader/**' + - 'Tools/bootloaders/**' + - 'Tools/CHDK-Script/**' + - 'Tools/CodeStyle/**' + - 'Tools/completion/**' + - 'Tools/CPUInfo/**' + - 'Tools/debug/**' + - 'Tools/environment_install/**' + - 'Tools/FilterTestTool/**' + - 'Tools/Frame_params/**' + - 'Tools/geotag/**' + - 'Tools/GIT_Test/**' + - 'Tools/gittools/**' + - 'Tools/Hello/**' + - 'Tools/IO_Firmware/**' + - 'Tools/LogAnalyzer/**' + - 'Tools/mavproxy_modules/**' + - 'Tools/Pozyx/**' + - 'Tools/PrintVersion.py' + - 'Tools/Replay/**' + - 'Tools/simulink/**' + - 'Tools/UDP_Proxy/**' + - 'Tools/vagrant/**' + - 'Tools/Vicon/**' + # Discard python file from Tools/scripts as not used + - 'Tools/scripts/**.py' + - 'Tools/scripts/build_sizes/**' + - 'Tools/scripts/build_tests/**' + - 'Tools/scripts/CAN/**' + - 'Tools/scripts/signing/**' + # Remove autotests stuff + - 'Tools/autotest/**' + # Remove markdown files as irrelevant + - '**.md' + # Remove dotfile at root directory + - './.dir-locals.el' + - './.dockerignore' + - './.editorconfig' + - './.flake8' + - './.gitattributes' + - './.github' + - './.gitignore' + - './.pre-commit-config.yaml' + - './.pydevproject' + - './.valgrind-suppressions' + - './.valgrindrc' + - 'Dockerfile' + - 'Vagrantfile' + - 'Makefile' + # Remove some directories check + - '.vscode/**' + - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' + + pull_request: + paths-ignore: + # remove not tests vehicles + - 'AntennaTracker/**' + - 'ArduSub/**' + - 'Rover/**' + - 'Blimp/**' + # remove esp32 HAL + - 'libraries/AP_HAL_ESP32/**' + # remove non SITL directories + - 'Tools/AP_Bootloader/**' + - 'Tools/CHDK-Script/**' + - 'Tools/CPUInfo/**' + - 'Tools/CodeStyle/**' + - 'Tools/FilterTestTool/**' + - 'Tools/Frame_params/**' + - 'Tools/GIT_Test/**' + - 'Tools/Hello/**' + - 'Tools/IO_Firmware/**' + - 'Tools/LogAnalyzer/**' + - 'Tools/Pozyx/**' + - 'Tools/PrintVersion.py' + - 'Tools/Replay/**' + - 'Tools/UDP_Proxy/**' + - 'Tools/Vicon/**' + - 'Tools/bootloaders/**' + - 'Tools/completion/**' + - 'Tools/debug/**' + - 'Tools/environment_install/**' + - 'Tools/geotag/**' + - 'Tools/gittools/**' + - 'Tools/mavproxy_modules/**' + - 'Tools/simulink/**' + - 'Tools/vagrant/**' + # Discard python file from Tools/scripts as not used + - 'Tools/scripts/**.py' + - 'Tools/scripts/build_sizes/**' + - 'Tools/scripts/build_tests/**' + - 'Tools/scripts/CAN/**' + - 'Tools/scripts/signing/**' + # Remove autotests stuff + - 'Tools/autotest/**' + # Remove markdown files as irrelevant + - '**.md' + # Remove dotfile at root directory + - './.dir-locals.el' + - './.dockerignore' + - './.editorconfig' + - './.flake8' + - './.gitattributes' + - './.github' + - './.gitignore' + - './.pre-commit-config.yaml' + - './.pydevproject' + - './.valgrind-suppressions' + - './.valgrindrc' + - 'Dockerfile' + - 'Vagrantfile' + - 'Makefile' + # Remove some directories check + - '.vscode/**' + - '.github/ISSUE_TEMPLATE/**' + # Remove change on other workflows + - '.github/workflows/test_environment.yml' + + workflow_dispatch: + +concurrency: + group: ci-${{github.workflow}}-${{ github.ref }} + cancel-in-progress: true + +jobs: + build-test: + runs-on: ubuntu-22.04 + container: + image: ardupilot/ardupilot-dev-ros:latest + strategy: + fail-fast: false # don't cancel if a job from the matrix fails + steps: + # git checkout the PR + - uses: actions/checkout@v4 + with: + submodules: 'recursive' + path: src/ardupilot + # Put ccache into github cache for faster build + - name: Prepare ccache timestamp + id: ccache_cache_timestamp + run: | + NOW=$(date -u +"%F-%T") + echo "timestamp=${NOW}" >> $GITHUB_OUTPUT + - name: ccache cache files + uses: actions/cache@v3 + with: + path: ~/.ccache + key: ${{github.workflow}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} + restore-keys: ${{github.workflow}}-ccache- # restore ccache from either previous build on this branch or on master + - name: setup ccache + run: | + . src/ardupilot/.github/workflows/ccache.env + # https://ardupilot.org/dev/docs/ros2.html#installation-ubuntu + - name: Pull in repos with vcs + run: | + cd src + wget --progress=dot:giga https://raw.githubusercontent.com/ArduPilot/ardupilot/master/Tools/ros2/ros2.repos + vcs import --recursive --debug --shallow --skip-existing < ros2.repos + - name: Install rosdep dependencies + shell: 'bash' + run: | + apt update + rosdep update + # Workaround for flake8 attribute error + # https://github.com/ArduPilot/ardupilot/pull/24277#issuecomment-1632833433 + python -m pip install flake8==3.7.9 + source /opt/ros/humble/setup.bash + rosdep install --from-paths src --ignore-src --default-yes + - name: Install MAVProxy + run: | + # Install this specific version just to prevent rolling updates. + # These are the latest available + python3 -m pip install MAVProxy==1.8.67 + - name: Install local pymavlink + working-directory: ./src/ardupilot/modules/mavlink/pymavlink + run: | + pip install . -U --user + - name: Build with colcon + shell: 'bash' + run: | + source /opt/ros/humble/setup.bash + colcon build --packages-up-to ardupilot_dds_tests --cmake-args -DBUILD_TESTING=ON + - name: Test with colcon + shell: 'bash' + run: | + source install/setup.bash + colcon test --packages-select ardupilot_dds_tests --event-handlers=console_cohesion+ + - name: Report colcon test results + run: | + colcon test-result --all --verbose + From e8c852f0d4d689ef28eb62217b7b0d035b5be91e Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sat, 25 Nov 2023 13:41:26 -0800 Subject: [PATCH 386/499] AP_HAL: Allow APMSockets to autodetect Broadcast IPs --- libraries/AP_HAL/utility/Socket.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 89215913c35e24..0052778928aa46 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -119,6 +119,8 @@ bool SocketAPM::connect(const char *address, uint16_t port) if (ret == -1) { goto fail_mc; } + } else if (datagram && sockaddr.sin_addr.s_addr == INADDR_BROADCAST) { + set_broadcast(); } ret = CALL_PREFIX(connect)(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); From afc112295ce2bbd09b586436e95e0d3babc06520 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 18 Nov 2023 14:09:42 +1100 Subject: [PATCH 387/499] Tools: allow networking in SITL periph --- Tools/autotest/sim_vehicle.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 0768bd91bd0d75..89113e04108a34 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -411,7 +411,7 @@ def do_build(opts, frame_options): if opts.enable_dds: cmd_configure.append("--enable-dds") - if opts.disable_networking or configure_target != "sitl": + if opts.disable_networking: cmd_configure.append("--disable-networking") if opts.enable_networking_tests: From 8ab3ad2777b3a37f90789834616e3f3b65cb392b Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 16 Nov 2023 10:56:02 -0800 Subject: [PATCH 388/499] AP_Networking: add support for AP_Periph --- libraries/AP_Networking/AP_Networking.h | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 2dffb34dff8557..c931fc26982461 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -27,6 +27,7 @@ class AP_Networking friend class AP_Networking_Backend; friend class AP_Networking_ChibiOS; friend class AP_Vehicle; + friend class Networking_Periph; AP_Networking(); From 0b60777db607d00310007b299dd5f19439cf7e08 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 22 Nov 2023 16:10:55 -0800 Subject: [PATCH 389/499] AP_Periph: add Networking-UART passthrough --- Tools/AP_Periph/AP_Periph.cpp | 4 +- Tools/AP_Periph/AP_Periph.h | 3 +- Tools/AP_Periph/Parameters.cpp | 4 +- Tools/AP_Periph/Parameters.h | 2 +- Tools/AP_Periph/networking.cpp | 261 +++++++++++++++++++++++++++++++++ Tools/AP_Periph/networking.h | 53 +++++++ 6 files changed, 321 insertions(+), 6 deletions(-) create mode 100644 Tools/AP_Periph/networking.cpp create mode 100644 Tools/AP_Periph/networking.h diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index b4e707d0b2e65d..4d5cfdcbea1558 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -101,7 +101,7 @@ void AP_Periph_FW::init() can_start(); #ifdef HAL_PERIPH_ENABLE_NETWORKING - networking.init(); + networking_periph.init(); #endif #if HAL_GCS_ENABLED @@ -502,7 +502,7 @@ void AP_Periph_FW::update() can_update(); #ifdef HAL_PERIPH_ENABLE_NETWORKING - networking.update(); + networking_periph.update(); #endif #if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY) diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 8ed77e88fc1fbe..376e7245ba0e0d 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -36,6 +36,7 @@ #include #include "rc_in.h" #include "batt_balance.h" +#include "networking.h" #include #if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && defined(HAL_PERIPH_ENABLE_GPS)) @@ -356,7 +357,7 @@ class AP_Periph_FW { #endif #ifdef HAL_PERIPH_ENABLE_NETWORKING - AP_Networking networking; + Networking_Periph networking_periph; #endif #ifdef HAL_PERIPH_ENABLE_RTC diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 7e17cb8daed180..27c985a3bf6218 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -588,8 +588,8 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { #ifdef HAL_PERIPH_ENABLE_NETWORKING // @Group: NET_ - // @Path: ../libraries/AP_Networking/AP_Networking.cpp - GOBJECT(networking, "NET_", AP_Networking), + // @Path: networking.cpp + GOBJECT(networking_periph, "NET_", Networking_Periph), #endif #ifdef HAL_PERIPH_ENABLE_RPM diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index a2a439b31fcb97..ff64f16d1e9508 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -76,7 +76,7 @@ class Parameters { k_param_esc_number1, k_param_pole_count1, k_param_esc_serial_port1, - k_param_networking, + k_param_networking_periph, k_param_rpm_sensor, k_param_g_rcin, k_param_sitl, diff --git a/Tools/AP_Periph/networking.cpp b/Tools/AP_Periph/networking.cpp new file mode 100644 index 00000000000000..cfce8930632d1d --- /dev/null +++ b/Tools/AP_Periph/networking.cpp @@ -0,0 +1,261 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_NETWORKING + +#include + +extern const AP_HAL::HAL &hal; + +const AP_Param::GroupInfo Networking_Periph::var_info[] { + // @Group: + // @Path: ../../libraries/AP_Networking/AP_Networking.cpp + AP_SUBGROUPINFO(networking_lib, "", 1, Networking_Periph, AP_Networking), + + /* + the NET_Pn_ parameters need to be here as otherwise we + are too deep in the parameter tree + */ + +#if AP_NETWORKING_NUM_PORTS > 0 + // @Group: P1_ + // @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking_lib.ports[0], "P1_", 2, Networking_Periph, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 1 + // @Group: P2_ + // @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking_lib.ports[1], "P2_", 3, Networking_Periph, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 2 + // @Group: P3_ + // @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking_lib.ports[2], "P3_", 4, Networking_Periph, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 3 + // @Group: P4_ + // @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking_lib.ports[3], "P4_", 5, Networking_Periph, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 4 + // @Group: P5_ + // @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking_lib.ports[4], "P5_", 6, Networking_Periph, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 5 + // @Group: P6_ + // @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking_lib.ports[5], "P6_", 7, Networking_Periph, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 6 + // @Group: P7_ + // @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking_lib.ports[6], "P7_", 8, Networking_Periph, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 7 + // @Group: P8_ + // @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking_lib.ports[7], "P8_", 9, Networking_Periph, AP_Networking::Port), +#endif + +#if AP_NETWORKING_NUM_PORTS > 8 + // @Group: P9_ + // @Path: ../../libraries/AP_Networking/AP_Networking_port.cpp + AP_SUBGROUPINFO(networking_lib.ports[8], "P9_", 10, Networking_Periph, AP_Networking::Port), +#endif + + + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 + // @Group: PASS1_ + // @Path: networking_passthru.cpp + AP_SUBGROUPINFO(passthru[0], "PASS1_", 11, Networking_Periph, Passthru), +#endif + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 1 + // @Group: PASS2_ + // @Path: networking_passthru.cpp + AP_SUBGROUPINFO(passthru[1], "PASS2_", 12, Networking_Periph, Passthru), +#endif + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 2 + // @Group: PASS3_ + // @Path: networking_passthru.cpp + AP_SUBGROUPINFO(passthru[2], "PASS3_", 13, Networking_Periph, Passthru), +#endif + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 3 + // @Group: PASS4_ + // @Path: networking_passthru.cpp + AP_SUBGROUPINFO(passthru[3], "PASS4_", 14, Networking_Periph, Passthru), +#endif + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 4 + // @Group: PASS5_ + // @Path: networking_passthru.cpp + AP_SUBGROUPINFO(passthru[4], "PASS5_", 15, Networking_Periph, Passthru), +#endif + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 5 + // @Group: PASS6_ + // @Path: networking_passthru.cpp + AP_SUBGROUPINFO(passthru[5], "PASS6_", 16, Networking_Periph, Passthru), +#endif + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 6 + // @Group: PASS7_ + // @Path: networking_passthru.cpp + AP_SUBGROUPINFO(passthru[6], "PASS7_", 17, Networking_Periph, Passthru), +#endif + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 7 + // @Group: PASS8_ + // @Path: networking_passthru.cpp + AP_SUBGROUPINFO(passthru[7], "PASS8_", 18, Networking_Periph, Passthru), +#endif + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 8 + // @Group: PASS9_ + // @Path: networking_passthru.cpp + AP_SUBGROUPINFO(passthru[8], "PASS9_", 19, Networking_Periph, Passthru), +#endif + + AP_GROUPEND +}; + + +const AP_Param::GroupInfo Networking_Periph::Passthru::var_info[] = { + // @Param: ENABLE + // @DisplayName: Enable Passthrough + // @Description: Enable Passthrough of any UART, Network, or CAN ports to any UART, Network, or CAN ports. + // @Values: 0:Disabled, 1:Enabled + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO_FLAGS("ENABLE", 1, Networking_Periph::Passthru, enabled, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: EP1 + // @DisplayName: Endpoint 1 + // @Description: Passthrough Endpoint 1. This can be a serial port UART, a Network port, or a CAN port. The selected port will route to Endport 2. + // @Values: -1:Disabled, 0:Serial0(usually USB), 1:Serial1, 2:Serial2, 3:Serial3, 4:Serial4, 5:Serial5, 6:Serial6, 7:Serial7, 8:Serial8, 9:Serial9, 21:Network Port1, 22:Network Port2, 23:Network Port3, 24:Network Port4, 25:Network Port5, 26:Network Port6, 27:Network Port7, 28:Network Port8, 29:Network Port9, 41:CAN1 Port1, 42:CAN1 Port2, 43:CAN1 Port3, 44:CAN1 Port4, 45:CAN1 Port5, 46:CAN1 Port6, 47:CAN1 Port7, 48:CAN1 Port8, 49:CAN1 Port9, 51:CAN2 Port1, 52:CAN2 Port2, 53:CAN2 Port3, 54:CAN2 Port4, 55:CAN2 Port5, 56:CAN2 Port6, 57:CAN2 Port7, 58:CAN2 Port8, 59:CAN2 Port9 + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("EP1", 2, Networking_Periph::Passthru, ep1, -1), + + // @Param: EP2 + // @DisplayName: Endpoint 2 + // @Description: Passthrough Endpoint 2. This can be a serial port UART, a Network port, or a CAN port. The selected port will route to Endport 1. + // @CopyFieldsFrom: NET_PASS1_EP1 + AP_GROUPINFO("EP2", 3, Networking_Periph::Passthru, ep2, -1), + + // @Param: BAUD1 + // @DisplayName: Endpoint 1 Baud Rate + // @Description: The baud rate used for Endpoint 1. Only applies to serial ports. + // @CopyFieldsFrom: SERIAL1_BAUD + AP_GROUPINFO("BAUD1", 4, Networking_Periph::Passthru, baud1, 115200), + + // @Param: BAUD2 + // @DisplayName: Endpoint 2 Baud Rate + // @Description: The baud rate used for Endpoint 2. Only applies to serial ports. + // @CopyFieldsFrom: SERIAL1_BAUD + AP_GROUPINFO("BAUD2", 5, Networking_Periph::Passthru, baud2, 115200), + + // @Param: OPT1 + // @DisplayName: Serial Port Options EP1 + // @Description: Control over UART options for Endpoint 1. Only applies to serial ports. + // @CopyFieldsFrom: SERIAL1_OPTIONS + AP_GROUPINFO("OPT1", 6, Networking_Periph::Passthru, options1, 0), + + // @Param: OPT2 + // @DisplayName: Serial Port Options EP2 + // @Description: Control over UART options for Endpoint 2. Only applies to serial ports. + // @CopyFieldsFrom: SERIAL1_OPTIONS + AP_GROUPINFO("OPT2", 7, Networking_Periph::Passthru, options2, 0), + + AP_GROUPEND +}; + +void Networking_Periph::init(void) +{ + networking_lib.init(); + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 + auto &serial_manager = AP::serialmanager(); + + for (auto &p : passthru) { + if (p.enabled != 0 && p.port1 == nullptr && p.port2 == nullptr && + p.ep1 != -1 && p.ep2 != -1 && p.ep1 != p.ep2) { + + p.port1 = serial_manager.get_serial_by_id(p.ep1); + p.port2 = serial_manager.get_serial_by_id(p.ep2); + + if (p.port1 != nullptr && p.port2 != nullptr) { + p.port1->set_options(p.options1); + p.port1->begin(p.baud1); + + p.port2->set_options(p.options2); + p.port2->begin(p.baud2); + } + } + } +#endif // HAL_PERIPH_NETWORK_NUM_PASSTHRU +} + +void Networking_Periph::update(void) +{ + networking_lib.update(); + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 + for (auto &p : passthru) { + if (p.enabled == 0 || p.port1 == nullptr || p.port2 == nullptr) { + continue; + } + uint8_t buf[1024]; + + // read from port1, and write to port2 + auto avail = p.port1->available(); + if (avail > 0) { + auto space = p.port2->txspace(); + const uint32_t n = MIN(space, sizeof(buf)); + const auto nbytes = p.port1->read(buf, n); + if (nbytes > 0) { + p.port2->write(buf, nbytes); + } + } + + // read from port2, and write to port1 + avail = p.port2->available(); + if (avail > 0) { + auto space = p.port1->txspace(); + const uint32_t n = MIN(space, sizeof(buf)); + const auto nbytes = p.port2->read(buf, n); + if (nbytes > 0) { + p.port1->write(buf, nbytes); + } + } + } +#endif // HAL_PERIPH_NETWORK_NUM_PASSTHRU +} + +#endif // HAL_PERIPH_ENABLE_NETWORKING + diff --git a/Tools/AP_Periph/networking.h b/Tools/AP_Periph/networking.h new file mode 100644 index 00000000000000..0958977c2cbc67 --- /dev/null +++ b/Tools/AP_Periph/networking.h @@ -0,0 +1,53 @@ +#pragma once + +#ifdef HAL_PERIPH_ENABLE_NETWORKING + +#ifndef HAL_PERIPH_NETWORK_NUM_PASSTHRU +#define HAL_PERIPH_NETWORK_NUM_PASSTHRU 2 +#endif + +class Networking_Periph { +public: + Networking_Periph() { + AP_Param::setup_object_defaults(this, var_info); + } + + static const struct AP_Param::GroupInfo var_info[]; + + void init(); + void update(); + +private: + +#if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 + class Passthru { + public: + friend class Networking_Periph; + + CLASS_NO_COPY(Passthru); + + Passthru() { + AP_Param::setup_object_defaults(this, var_info); + } + + static const struct AP_Param::GroupInfo var_info[]; + + private: + AP_Int8 enabled; + AP_Int8 ep1; + AP_Int8 ep2; + AP_Int32 baud1; + AP_Int32 baud2; + AP_Int32 options1; + AP_Int32 options2; + + AP_HAL::UARTDriver *port1; + AP_HAL::UARTDriver *port2; + } passthru[HAL_PERIPH_NETWORK_NUM_PASSTHRU]; +#endif // HAL_PERIPH_NETWORK_NUM_PASSTHRU + + AP_Networking networking_lib; +}; + +#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE + From f870b63851f4389005623e5dbfc89e895d52b27a Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 22 Nov 2023 15:14:56 -0800 Subject: [PATCH 390/499] AP_Periph: move Network Passthrough to it's own file --- Tools/AP_Periph/networking.cpp | 102 +----------------- Tools/AP_Periph/networking.h | 5 + Tools/AP_Periph/networking_passthru.cpp | 135 ++++++++++++++++++++++++ 3 files changed, 144 insertions(+), 98 deletions(-) create mode 100644 Tools/AP_Periph/networking_passthru.cpp diff --git a/Tools/AP_Periph/networking.cpp b/Tools/AP_Periph/networking.cpp index cfce8930632d1d..8ac256850cd9b9 100644 --- a/Tools/AP_Periph/networking.cpp +++ b/Tools/AP_Periph/networking.cpp @@ -17,10 +17,6 @@ #ifdef HAL_PERIPH_ENABLE_NETWORKING -#include - -extern const AP_HAL::HAL &hal; - const AP_Param::GroupInfo Networking_Periph::var_info[] { // @Group: // @Path: ../../libraries/AP_Networking/AP_Networking.cpp @@ -145,80 +141,15 @@ const AP_Param::GroupInfo Networking_Periph::var_info[] { }; -const AP_Param::GroupInfo Networking_Periph::Passthru::var_info[] = { - // @Param: ENABLE - // @DisplayName: Enable Passthrough - // @Description: Enable Passthrough of any UART, Network, or CAN ports to any UART, Network, or CAN ports. - // @Values: 0:Disabled, 1:Enabled - // @RebootRequired: True - // @User: Advanced - AP_GROUPINFO_FLAGS("ENABLE", 1, Networking_Periph::Passthru, enabled, 0, AP_PARAM_FLAG_ENABLE), - - // @Param: EP1 - // @DisplayName: Endpoint 1 - // @Description: Passthrough Endpoint 1. This can be a serial port UART, a Network port, or a CAN port. The selected port will route to Endport 2. - // @Values: -1:Disabled, 0:Serial0(usually USB), 1:Serial1, 2:Serial2, 3:Serial3, 4:Serial4, 5:Serial5, 6:Serial6, 7:Serial7, 8:Serial8, 9:Serial9, 21:Network Port1, 22:Network Port2, 23:Network Port3, 24:Network Port4, 25:Network Port5, 26:Network Port6, 27:Network Port7, 28:Network Port8, 29:Network Port9, 41:CAN1 Port1, 42:CAN1 Port2, 43:CAN1 Port3, 44:CAN1 Port4, 45:CAN1 Port5, 46:CAN1 Port6, 47:CAN1 Port7, 48:CAN1 Port8, 49:CAN1 Port9, 51:CAN2 Port1, 52:CAN2 Port2, 53:CAN2 Port3, 54:CAN2 Port4, 55:CAN2 Port5, 56:CAN2 Port6, 57:CAN2 Port7, 58:CAN2 Port8, 59:CAN2 Port9 - // @RebootRequired: True - // @User: Advanced - AP_GROUPINFO("EP1", 2, Networking_Periph::Passthru, ep1, -1), - - // @Param: EP2 - // @DisplayName: Endpoint 2 - // @Description: Passthrough Endpoint 2. This can be a serial port UART, a Network port, or a CAN port. The selected port will route to Endport 1. - // @CopyFieldsFrom: NET_PASS1_EP1 - AP_GROUPINFO("EP2", 3, Networking_Periph::Passthru, ep2, -1), - - // @Param: BAUD1 - // @DisplayName: Endpoint 1 Baud Rate - // @Description: The baud rate used for Endpoint 1. Only applies to serial ports. - // @CopyFieldsFrom: SERIAL1_BAUD - AP_GROUPINFO("BAUD1", 4, Networking_Periph::Passthru, baud1, 115200), - - // @Param: BAUD2 - // @DisplayName: Endpoint 2 Baud Rate - // @Description: The baud rate used for Endpoint 2. Only applies to serial ports. - // @CopyFieldsFrom: SERIAL1_BAUD - AP_GROUPINFO("BAUD2", 5, Networking_Periph::Passthru, baud2, 115200), - - // @Param: OPT1 - // @DisplayName: Serial Port Options EP1 - // @Description: Control over UART options for Endpoint 1. Only applies to serial ports. - // @CopyFieldsFrom: SERIAL1_OPTIONS - AP_GROUPINFO("OPT1", 6, Networking_Periph::Passthru, options1, 0), - - // @Param: OPT2 - // @DisplayName: Serial Port Options EP2 - // @Description: Control over UART options for Endpoint 2. Only applies to serial ports. - // @CopyFieldsFrom: SERIAL1_OPTIONS - AP_GROUPINFO("OPT2", 7, Networking_Periph::Passthru, options2, 0), - - AP_GROUPEND -}; - void Networking_Periph::init(void) { networking_lib.init(); #if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 - auto &serial_manager = AP::serialmanager(); - for (auto &p : passthru) { - if (p.enabled != 0 && p.port1 == nullptr && p.port2 == nullptr && - p.ep1 != -1 && p.ep2 != -1 && p.ep1 != p.ep2) { - - p.port1 = serial_manager.get_serial_by_id(p.ep1); - p.port2 = serial_manager.get_serial_by_id(p.ep2); - - if (p.port1 != nullptr && p.port2 != nullptr) { - p.port1->set_options(p.options1); - p.port1->begin(p.baud1); - - p.port2->set_options(p.options2); - p.port2->begin(p.baud2); - } - } + p.init(); } -#endif // HAL_PERIPH_NETWORK_NUM_PASSTHRU +#endif } void Networking_Periph::update(void) @@ -227,34 +158,9 @@ void Networking_Periph::update(void) #if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 for (auto &p : passthru) { - if (p.enabled == 0 || p.port1 == nullptr || p.port2 == nullptr) { - continue; - } - uint8_t buf[1024]; - - // read from port1, and write to port2 - auto avail = p.port1->available(); - if (avail > 0) { - auto space = p.port2->txspace(); - const uint32_t n = MIN(space, sizeof(buf)); - const auto nbytes = p.port1->read(buf, n); - if (nbytes > 0) { - p.port2->write(buf, nbytes); - } - } - - // read from port2, and write to port1 - avail = p.port2->available(); - if (avail > 0) { - auto space = p.port1->txspace(); - const uint32_t n = MIN(space, sizeof(buf)); - const auto nbytes = p.port2->read(buf, n); - if (nbytes > 0) { - p.port1->write(buf, nbytes); - } - } + p.update(); } -#endif // HAL_PERIPH_NETWORK_NUM_PASSTHRU +#endif } #endif // HAL_PERIPH_ENABLE_NETWORKING diff --git a/Tools/AP_Periph/networking.h b/Tools/AP_Periph/networking.h index 0958977c2cbc67..d25dc5aa7aaa77 100644 --- a/Tools/AP_Periph/networking.h +++ b/Tools/AP_Periph/networking.h @@ -1,5 +1,7 @@ #pragma once +#include "AP_Periph.h" + #ifdef HAL_PERIPH_ENABLE_NETWORKING #ifndef HAL_PERIPH_NETWORK_NUM_PASSTHRU @@ -30,6 +32,9 @@ class Networking_Periph { AP_Param::setup_object_defaults(this, var_info); } + void init(); + void update(); + static const struct AP_Param::GroupInfo var_info[]; private: diff --git a/Tools/AP_Periph/networking_passthru.cpp b/Tools/AP_Periph/networking_passthru.cpp new file mode 100644 index 00000000000000..18ed58bf68bac5 --- /dev/null +++ b/Tools/AP_Periph/networking_passthru.cpp @@ -0,0 +1,135 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ + +#include "networking.h" + +#if defined(HAL_PERIPH_ENABLE_NETWORKING) && HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 + +#include + +const AP_Param::GroupInfo Networking_Periph::Passthru::var_info[] = { + // @Param: ENABLE + // @DisplayName: Enable Passthrough + // @Description: Enable Passthrough of any UART, Network, or CAN ports to any UART, Network, or CAN ports. + // @Values: 0:Disabled, 1:Enabled + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO_FLAGS("ENABLE", 1, Networking_Periph::Passthru, enabled, 0, AP_PARAM_FLAG_ENABLE), + + // @Param: EP1 + // @DisplayName: Endpoint 1 + // @Description: Passthrough Endpoint 1. This can be a serial port UART, a Network port, or a CAN port. The selected port will route to Endport 2. + // @Values: -1:Disabled, 0:Serial0(usually USB), 1:Serial1, 2:Serial2, 3:Serial3, 4:Serial4, 5:Serial5, 6:Serial6, 7:Serial7, 8:Serial8, 9:Serial9, 21:Network Port1, 22:Network Port2, 23:Network Port3, 24:Network Port4, 25:Network Port5, 26:Network Port6, 27:Network Port7, 28:Network Port8, 29:Network Port9, 41:CAN1 Port1, 42:CAN1 Port2, 43:CAN1 Port3, 44:CAN1 Port4, 45:CAN1 Port5, 46:CAN1 Port6, 47:CAN1 Port7, 48:CAN1 Port8, 49:CAN1 Port9, 51:CAN2 Port1, 52:CAN2 Port2, 53:CAN2 Port3, 54:CAN2 Port4, 55:CAN2 Port5, 56:CAN2 Port6, 57:CAN2 Port7, 58:CAN2 Port8, 59:CAN2 Port9 + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("EP1", 2, Networking_Periph::Passthru, ep1, -1), + + // @Param: EP2 + // @DisplayName: Endpoint 2 + // @Description: Passthrough Endpoint 2. This can be a serial port UART, a Network port, or a CAN port. The selected port will route to Endport 1. + // @CopyFieldsFrom: NET_PASS1_EP1 + AP_GROUPINFO("EP2", 3, Networking_Periph::Passthru, ep2, -1), + + // @Param: BAUD1 + // @DisplayName: Endpoint 1 Baud Rate + // @Description: The baud rate used for Endpoint 1. Only applies to serial ports. + // @CopyFieldsFrom: SERIAL1_BAUD + AP_GROUPINFO("BAUD1", 4, Networking_Periph::Passthru, baud1, 115200), + + // @Param: BAUD2 + // @DisplayName: Endpoint 2 Baud Rate + // @Description: The baud rate used for Endpoint 2. Only applies to serial ports. + // @CopyFieldsFrom: SERIAL1_BAUD + AP_GROUPINFO("BAUD2", 5, Networking_Periph::Passthru, baud2, 115200), + + // @Param: OPT1 + // @DisplayName: Serial Port Options EP1 + // @Description: Control over UART options for Endpoint 1. Only applies to serial ports. + // @CopyFieldsFrom: SERIAL1_OPTIONS + AP_GROUPINFO("OPT1", 6, Networking_Periph::Passthru, options1, 0), + + // @Param: OPT2 + // @DisplayName: Serial Port Options EP2 + // @Description: Control over UART options for Endpoint 2. Only applies to serial ports. + // @CopyFieldsFrom: SERIAL1_OPTIONS + AP_GROUPINFO("OPT2", 7, Networking_Periph::Passthru, options2, 0), + + AP_GROUPEND +}; + +void Networking_Periph::Passthru::init() +{ + if (enabled == 0) { + // Feature is disabled + return; + } + + if (port1 != nullptr || port2 != nullptr) { + // The ports have already been initialized, nothing to do. + return; + } + + if (ep1 <= -1 || ep2 <= -1 || ep1 == ep2) { + // end points are not set or are the same. Can't route to self + return; + } + + port1 = AP::serialmanager().get_serial_by_id(ep1); + port2 = AP::serialmanager().get_serial_by_id(ep2); + + if (port1 != nullptr && port2 != nullptr) { + port1->set_options(options1); + port1->begin(baud1); + + port2->set_options(options2); + port2->begin(baud2); + } +} + +void Networking_Periph::Passthru::update() +{ + if (enabled == 0 || port1 == nullptr || port2 == nullptr) { + return; + } + + // Fastest possible connection is 3Mbps serial port, which is roughly 300KB/s payload and we service this at <= 1kHz + // Raising this any higher just causes excess stack usage which never gets used. + uint8_t buf[300]; + + // read from port1, and write to port2 + auto avail = port1->available(); + if (avail > 0) { + auto space = port2->txspace(); + const uint32_t n = MIN(space, sizeof(buf)); + const auto nbytes = port1->read(buf, n); + if (nbytes > 0) { + port2->write(buf, nbytes); + } + } + + // read from port2, and write to port1 + avail = port2->available(); + if (avail > 0) { + auto space = port1->txspace(); + const uint32_t n = MIN(space, sizeof(buf)); + const auto nbytes = port2->read(buf, n); + if (nbytes > 0) { + port1->write(buf, nbytes); + } + } +} + +#endif // defined(HAL_PERIPH_ENABLE_NETWORKING) && HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 + From cd6a656acf558488042ff292178307c128bb177e Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 9 Nov 2023 14:41:47 -0800 Subject: [PATCH 391/499] AP_HAL_ChibiOS: set AP_BATTERY_WATT_MAX_ENABLED 0 for periph --- libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h index 46e017f5830813..3a0a8c372330d5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -122,6 +122,10 @@ #define AP_BATTERY_ESC_ENABLED 0 #endif +#ifndef AP_BATTERY_WATT_MAX_ENABLED +#define AP_BATTERY_WATT_MAX_ENABLED 0 +#endif + // disable compass calibrations on periphs; cal is done on the autopilot #ifndef COMPASS_CAL_ENABLED #define COMPASS_CAL_ENABLED 0 From 1f7b4d0938480def16a2817f593d43026b663c61 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 9 Nov 2023 14:43:08 -0800 Subject: [PATCH 392/499] AP_HAL_ChibiOS: set AP_BATTERY_WATT_MAX_ENABLED 0 for minimize --- libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc index 4461774aa45606..c7fc0f6e61700d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/include/minimize_common.inc @@ -62,6 +62,7 @@ define AP_BEACON_ENABLED 0 define AP_BATTERY_BACKEND_DEFAULT_ENABLED 0 define AP_BATTERY_ANALOG_ENABLED 1 define AP_BATTERY_ESC_ENABLED HAL_WITH_ESC_TELEM +define AP_BATTERY_WATT_MAX_ENABLED 0 define AP_BATTERY_UAVCAN_BATTERYINFO_ENABLED HAL_ENABLE_DRONECAN_DRIVERS define AP_BATTERY_SUM_ENABLED 1 define AP_BATTERY_SYNTHETIC_CURRENT_ENABLED 1 From 496125a8cb7504a1b37548852e92fc0923f59937 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 9 Nov 2023 14:43:56 -0800 Subject: [PATCH 393/499] Tools: add AP_BATTERY_WATT_MAX_ENABLED to docs --- Tools/scripts/build_options.py | 1 + Tools/scripts/extract_features.py | 1 + 2 files changed, 2 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 87e427e324fb90..6382ae512eb04e 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -51,6 +51,7 @@ def __init__(self, Feature('Battery', 'BATTERY_INA2XX', 'AP_BATTERY_INA2XX_ENABLED', 'Enable INA2XX BatteryMonitor', 0, None), Feature('Battery', 'BATTERY_SYNTHETIC_CURRENT', 'AP_BATTERY_SYNTHETIC_CURRENT_ENABLED', 'Enable Synthetic Current Monitor', 0, None), # noqa: E501 Feature('Battery', 'BATTERY_ESC_TELEM_OUTBOUND_ENABLED', 'AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED', 'Enable ability to put battery monitor data in ESC telem stream', 0, None), # noqa: E501 + Feature('Battery', 'BATTERY_WATT_MAX', 'AP_BATTERY_WATT_MAX_ENABLED', 'Enable param BATT_WATT_MAX', 0, None), # noqa: E501 Feature('Ident', 'ADSB', 'HAL_ADSB_ENABLED', 'Enable ADSB', 0, None), Feature('Ident', 'ADSB_SAGETECH', 'HAL_ADSB_SAGETECH_ENABLED', 'Enable Sagetech ADSB', 0, 'ADSB'), diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index ca1f8ab5d77b24..83a2f0583a18cb 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -101,6 +101,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_BATTERY_{type}_ENABLED', r'AP_BattMonitor_(?P.*)::init\b',), ('AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED', r'AP_BattMonitor_Backend::update_esc_telem_outbound\b',), + ('AP_BATTERY_WATT_MAX_ENABLED', 'AP_BattMonitor_Params::_watt_max',), ('HAL_MOUNT_ENABLED', 'AP_Mount::AP_Mount',), ('HAL_MOUNT_{type}_ENABLED', r'AP_Mount_(?P.*)::update\b',), From b468af81ac1930dec3ef6d31abdc16f5a920f6db Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 21 Nov 2023 11:14:26 -0800 Subject: [PATCH 394/499] Plane: wrap Watt Limiiter in #if AP_BATTERY_WATT_MAX_ENABLED --- ArduPlane/Plane.h | 2 ++ ArduPlane/servos.cpp | 4 ++++ 2 files changed, 6 insertions(+) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index d2fd912d4d293d..80e3cb8636ce1e 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -586,10 +586,12 @@ class Plane : public AP_Vehicle { // this controls throttle suppression in auto modes bool throttle_suppressed; +#if AP_BATTERY_WATT_MAX_ENABLED // reduce throttle to eliminate battery over-current int8_t throttle_watt_limit_max; int8_t throttle_watt_limit_min; // for reverse thrust uint32_t throttle_watt_limit_timer_ms; +#endif AP_FixedWing::FlightStage flight_stage = AP_FixedWing::FlightStage::NORMAL; diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 85fe2689f3765a..729e67089e528a 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -422,6 +422,7 @@ void Plane::throttle_voltage_comp(int8_t &min_throttle, int8_t &max_throttle) co /* calculate any throttle limits based on the watt limiter */ +#if AP_BATTERY_WATT_MAX_ENABLED void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle) { uint32_t now = millis(); @@ -466,6 +467,7 @@ void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle) min_throttle = constrain_int16(min_throttle, min_throttle + throttle_watt_limit_min, 0); } } +#endif // #if AP_BATTERY_WATT_MAX_ENABLED /* setup output channels all non-manual modes @@ -509,8 +511,10 @@ void Plane::set_servos_controlled(void) // compensate for battery voltage drop throttle_voltage_comp(min_throttle, max_throttle); +#if AP_BATTERY_WATT_MAX_ENABLED // apply watt limiter throttle_watt_limiter(min_throttle, max_throttle); +#endif SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle), min_throttle, max_throttle)); From 6dcaf94c3d89a844769bf2237db8fd1520dd4304 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 21 Nov 2023 11:21:18 -0800 Subject: [PATCH 395/499] AP_BattMon: add AP_BATTERY_WATT_MAX_ENABLED --- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 17 +++++++++-------- .../AP_BattMonitor/AP_BattMonitor_Params.cpp | 4 ++-- .../AP_BattMonitor/AP_BattMonitor_Params.h | 2 ++ .../AP_BattMonitor/AP_BattMonitor_config.h | 4 ++++ 4 files changed, 17 insertions(+), 10 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index f1d7710bc6551d..45f630ce3bb6f1 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -841,24 +841,25 @@ void AP_BattMonitor::check_failsafes(void) // return true if any battery is pushing too much power bool AP_BattMonitor::overpower_detected() const { - bool result = false; +#if AP_BATTERY_WATT_MAX_ENABLED && APM_BUILD_TYPE(APM_BUILD_ArduPlane) for (uint8_t instance = 0; instance < _num_instances; instance++) { - result |= overpower_detected(instance); + if (overpower_detected(instance)) { + return true; + } } - return result; +#endif + return false; } bool AP_BattMonitor::overpower_detected(uint8_t instance) const { -#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) +#if AP_BATTERY_WATT_MAX_ENABLED && APM_BUILD_TYPE(APM_BUILD_ArduPlane) if (instance < _num_instances && _params[instance]._watt_max > 0) { - float power = state[instance].current_amps * state[instance].voltage; + const float power = state[instance].current_amps * state[instance].voltage; return state[instance].healthy && (power > _params[instance]._watt_max); } - return false; -#else - return false; #endif + return false; } bool AP_BattMonitor::has_cell_voltages(const uint8_t instance) const diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index 12ca57ceed7c27..5302bf77306a66 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -40,7 +40,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @User: Standard AP_GROUPINFO("CAPACITY", 7, AP_BattMonitor_Params, _pack_capacity, AP_BATT_MONITOR_BATTERY_CAPACITY), -#ifndef HAL_BUILD_AP_PERIPH +#if AP_BATTERY_WATT_MAX_ENABLED // @Param{Plane}: WATT_MAX // @DisplayName: Maximum allowed power (Watts) // @Description: If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable. @@ -48,7 +48,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @Increment: 1 // @User: Advanced AP_GROUPINFO_FRAME("WATT_MAX", 8, AP_BattMonitor_Params, _watt_max, 0, AP_PARAM_FRAME_PLANE), -#endif // HAL_BUILD_AP_PERIPH +#endif // @Param: SERIAL_NUM // @DisplayName: Battery serial number diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h index fff2719f8f3cf1..2088845c39f62d 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.h @@ -39,7 +39,9 @@ class AP_BattMonitor_Params { AP_Int32 _arming_minimum_capacity; /// capacity level required to arm AP_Float _arming_minimum_voltage; /// voltage level required to arm AP_Int32 _options; /// Options +#if AP_BATTERY_WATT_MAX_ENABLED AP_Int16 _watt_max; /// max battery power allowed. Reduce max throttle to reduce current to satisfy t his limit +#endif AP_Int8 _type; /// 0=disabled, 3=voltage only, 4=voltage and current AP_Int8 _low_voltage_timeout; /// timeout in seconds before a low voltage event will be triggered AP_Int8 _failsafe_voltage_source; /// voltage type used for detection of low voltage event diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_config.h b/libraries/AP_BattMonitor/AP_BattMonitor_config.h index 4fab7ff189ee93..92d5ad074e937f 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_config.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_config.h @@ -34,6 +34,10 @@ #define AP_BATTERY_ESC_TELEM_OUTBOUND_ENABLED 0 #endif +#ifndef AP_BATTERY_WATT_MAX_ENABLED +#define AP_BATTERY_WATT_MAX_ENABLED AP_BATTERY_ENABLED +#endif + #ifndef AP_BATTERY_SMBUS_ENABLED #define AP_BATTERY_SMBUS_ENABLED AP_BATTERY_BACKEND_DEFAULT_ENABLED #endif From a84e9e8e6cf1faf945d17686ed9e95a3271f6d68 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 26 Nov 2023 21:14:25 +1100 Subject: [PATCH 396/499] Copter: don't send WINCH_STATUS message if winch not enabled --- ArduCopter/GCS_Mavlink.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 139e6d64cd7660..7f86eabc8ef5ea 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -573,7 +573,9 @@ static const ap_message STREAM_EXTRA3_msgs[] = { #if HAL_GENERATOR_ENABLED MSG_GENERATOR_STATUS, #endif +#if AP_WINCH_ENABLED MSG_WINCH_STATUS, +#endif #if HAL_EFI_ENABLED MSG_EFI_STATUS, #endif From f40250c0733c4fde36be32693126a547b4bbe87f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 17 Nov 2023 17:03:28 +1100 Subject: [PATCH 397/499] AP_AHRS: compile EKF2 out by default on all boards --- libraries/AP_AHRS/AP_AHRS_config.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_config.h b/libraries/AP_AHRS/AP_AHRS_config.h index 0be9f0cdd828bd..559d0403b0566e 100644 --- a/libraries/AP_AHRS/AP_AHRS_config.h +++ b/libraries/AP_AHRS/AP_AHRS_config.h @@ -16,8 +16,8 @@ #endif #ifndef HAL_NAVEKF2_AVAILABLE -// only default to EK2 enabled on boards with over 1M flash -#define HAL_NAVEKF2_AVAILABLE (BOARD_FLASH_SIZE>1024) +// EKF2 slated compiled out by default in 4.5, slated to be removed. +#define HAL_NAVEKF2_AVAILABLE 0 #endif #ifndef HAL_NAVEKF3_AVAILABLE From aa9bbd0fcbb6f26b3bfc393688504038ec522374 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 17 Nov 2023 17:07:30 +1100 Subject: [PATCH 398/499] waf: invert ekf2-disable command-line option --- Tools/ardupilotwaf/boards.py | 4 ++-- Tools/autotest/sim_vehicle.py | 6 +++--- wscript | 4 ++-- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 776a1cd9223724..017402f4d27c6c 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -462,8 +462,8 @@ def configure_env(self, cfg, env): # We always want to use PRI format macros cfg.define('__STDC_FORMAT_MACROS', 1) - if cfg.options.disable_ekf2: - env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=0'] + if cfg.options.enable_ekf2: + env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=1'] if cfg.options.disable_ekf3: env.CXXFLAGS += ['-DHAL_NAVEKF3_AVAILABLE=0'] diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 89113e04108a34..065b5265c1c53f 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -378,8 +378,8 @@ def do_build(opts, frame_options): if opts.math_check_indexes: cmd_configure.append("--enable-math-check-indexes") - if opts.disable_ekf2: - cmd_configure.append("--disable-ekf2") + if opts.enable_ekf2: + cmd_configure.append("--enable-ekf2") if opts.disable_ekf3: cmd_configure.append("--disable-ekf3") @@ -1295,7 +1295,7 @@ def generate_frame_help(): group_sim.add_option("--fram-storage", action='store_true', help="use fram storage emulation") -group_sim.add_option("--disable-ekf2", +group_sim.add_option("--enable-ekf2", action='store_true', help="disable EKF2 in build") group_sim.add_option("--disable-ekf3", diff --git a/wscript b/wscript index a2e8a7347808c6..19630462ecdd70 100644 --- a/wscript +++ b/wscript @@ -360,10 +360,10 @@ configuration in order to save typing. default=False, help='Use flash storage emulation.') - g.add_option('--disable-ekf2', + g.add_option('--enable-ekf2', action='store_true', default=False, - help='Configure without EKF2.') + help='Configure with EKF2.') g.add_option('--disable-ekf3', action='store_true', From 5f1f3e551951ae27957a02e1f853afabb2f37dcf Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 18 Nov 2023 13:58:37 +1100 Subject: [PATCH 399/499] waf: keep EKF2 enabled in SITL just because we don't compile this in doesn't mean we shouldn't continue to test it --- Tools/ardupilotwaf/boards.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 017402f4d27c6c..04a2e11e7d3011 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -654,6 +654,12 @@ def configure_env(self, cfg, env): cfg.define('AP_NOTIFY_LP5562_BUS', 2) cfg.define('AP_NOTIFY_LP5562_ADDR', 0x30) + try: + env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=0') + except ValueError: + pass + env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=1'] + if self.with_can: cfg.define('HAL_NUM_CAN_IFACES', 2) env.DEFINES.update(CANARD_MULTI_IFACE=1, From 73eb3b05909406857ab66c8288f6834f1d3ae710 Mon Sep 17 00:00:00 2001 From: Stephen Dade Date: Sun, 26 Nov 2023 14:48:42 +1100 Subject: [PATCH 400/499] AR_Motors: Add prearm check for no outputs --- libraries/AR_Motors/AP_MotorsUGV.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/libraries/AR_Motors/AP_MotorsUGV.cpp b/libraries/AR_Motors/AP_MotorsUGV.cpp index 5bb429ef0564f1..357815613e6ae2 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.cpp +++ b/libraries/AR_Motors/AP_MotorsUGV.cpp @@ -457,6 +457,18 @@ bool AP_MotorsUGV::output_test_pwm(motor_test_order motor_seq, float pwm) // returns true if checks pass, false if they fail. report should be true to send text messages to GCS bool AP_MotorsUGV::pre_arm_check(bool report) const { + // check that there's defined outputs, inc scripting and sail + if(!SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) && + !SRV_Channels::function_assigned(SRV_Channel::k_throttleRight) && + !SRV_Channels::function_assigned(SRV_Channel::k_throttle) && + !SRV_Channels::function_assigned(SRV_Channel::k_steering) && + !SRV_Channels::function_assigned(SRV_Channel::k_scripting1) && + !has_sail()) { + if (report) { + gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: no motor, sail or scripting outputs defined"); + } + return false; + } // check if only one of skid-steering output has been configured if (SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) != SRV_Channels::function_assigned(SRV_Channel::k_throttleRight)) { if (report) { From c48feefe232ec871435ef07aea270a2c6d540db8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 25 Nov 2023 08:24:39 +1100 Subject: [PATCH 401/499] AP_BattMonitor: fixed battery percentage with aux info when we have aux battery information we had assumed the CAN device would provide the battery remaining percentage. We should obey the "do not use CAN SoC" with or without an AUX message This fixes CAN battery monitors with a cell monitor --- libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index 281831f0d18390..123287c89a92ce 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -137,7 +137,8 @@ void AP_BattMonitor_DroneCAN::update_interim_state(const float voltage, const fl const uint32_t tnow = AP_HAL::micros(); - if (!_has_battery_info_aux || _mppt.is_detected) { + if (!_has_battery_info_aux || + !use_CAN_SoC()) { const uint32_t dt_us = tnow - _interim_state.last_time_micros; // update total current drawn since startup From dc76e03890f7457f6e044df1847cb62ce9e97fca Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 23 Nov 2023 19:54:35 -0600 Subject: [PATCH 402/499] AP_HAL: introduce get_HAL_mutable() to complement get_HAL() Returns a mutable reference to the same HAL for certain purposes where the HAL needs to be mutated to avoid UB problems with casting away const and to make the fact that mutation is happening obvious. --- libraries/AP_HAL/AP_HAL_Namespace.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL/AP_HAL_Namespace.h b/libraries/AP_HAL/AP_HAL_Namespace.h index b3e84314ed9ef0..aca8e02293763a 100644 --- a/libraries/AP_HAL/AP_HAL_Namespace.h +++ b/libraries/AP_HAL/AP_HAL_Namespace.h @@ -67,6 +67,7 @@ namespace AP_HAL { class SIMState; - // Must be implemented by the concrete HALs. + // Must be implemented by the concrete HALs and return the same reference. const HAL& get_HAL(); + HAL& get_HAL_mutable(); } From a9ddadee3ba81cd1be14b3485895b843f54d1b5a Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 23 Nov 2023 19:55:45 -0600 Subject: [PATCH 403/499] AP_HAL_ChibiOS: introduce get_HAL_mutable() to complement get_HAL() Returns a mutable reference to the same HAL for certain purposes where the HAL needs to be mutated to avoid UB problems with casting away const and to make the fact that mutation is happening obvious. --- libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index 6454f108e85ee3..46b352e5649f50 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -344,8 +344,13 @@ void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const main_loop(); } +static HAL_ChibiOS hal_chibios; + const AP_HAL::HAL& AP_HAL::get_HAL() { - static const HAL_ChibiOS hal_chibios; + return hal_chibios; +} + +AP_HAL::HAL& AP_HAL::get_HAL_mutable() { return hal_chibios; } From 2dbf5aefb39f10a1a67e15a6ad4d52a8b0506b5f Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 23 Nov 2023 19:56:04 -0600 Subject: [PATCH 404/499] AP_HAL_ESP32: introduce get_HAL_mutable() to complement get_HAL() Returns a mutable reference to the same HAL for certain purposes where the HAL needs to be mutated to avoid UB problems with casting away const and to make the fact that mutation is happening obvious. --- libraries/AP_HAL_ESP32/system.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ESP32/system.cpp b/libraries/AP_HAL_ESP32/system.cpp index 20f07a014758b2..4ee607c5617b72 100644 --- a/libraries/AP_HAL_ESP32/system.cpp +++ b/libraries/AP_HAL_ESP32/system.cpp @@ -56,8 +56,14 @@ uint64_t millis64() } // namespace AP_HAL +static HAL_ESP32 hal_esp32; + const AP_HAL::HAL& AP_HAL::get_HAL() { - static const HAL_ESP32 hal; - return hal; + return hal_esp32; +} + +AP_HAL::HAL& AP_HAL::get_HAL_mutable() +{ + return hal_esp32; } From db12f428c500673a25e525216bdf8c866b20e826 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 23 Nov 2023 19:56:23 -0600 Subject: [PATCH 405/499] AP_HAL_Empty: introduce get_HAL_mutable() to complement get_HAL() Returns a mutable reference to the same HAL for certain purposes where the HAL needs to be mutated to avoid UB problems with casting away const and to make the fact that mutation is happening obvious. --- libraries/AP_HAL_Empty/HAL_Empty_Class.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp index b2271a7df8eb89..2045e9c2893ee5 100644 --- a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp +++ b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp @@ -66,9 +66,14 @@ void HAL_Empty::run(int argc, char* const argv[], Callbacks* callbacks) const } } +static HAL_Empty hal_empty; + const AP_HAL::HAL& AP_HAL::get_HAL() { - static const HAL_Empty hal; - return hal; + return hal_empty; +} + +AP_HAL::HAL& AP_HAL::get_HAL_mutable() { + return hal_empty; } #endif From 8fe95dca816f52ddadf4fe78f5b7f52b6c4ffe76 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 23 Nov 2023 19:56:36 -0600 Subject: [PATCH 406/499] AP_HAL_Linux: introduce get_HAL_mutable() to complement get_HAL() Returns a mutable reference to the same HAL for certain purposes where the HAL needs to be mutated to avoid UB problems with casting away const and to make the fact that mutation is happening obvious. --- libraries/AP_HAL_Linux/HAL_Linux_Class.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp index ba68930e89a786..0fc691598b092c 100644 --- a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp +++ b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp @@ -491,3 +491,8 @@ const AP_HAL::HAL &AP_HAL::get_HAL() { return hal_linux; } + +AP_HAL::HAL &AP_HAL::get_HAL_mutable() +{ + return hal_linux; +} From 3c82ac6043539dd69a0c2d9fea7c970591d83b04 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 23 Nov 2023 19:56:54 -0600 Subject: [PATCH 407/499] AP_HAL_SITL: introduce get_HAL_mutable() to complement get_HAL() Returns a mutable reference to the same HAL for certain purposes where the HAL needs to be mutated to avoid UB problems with casting away const and to make the fact that mutation is happening obvious. --- libraries/AP_HAL_SITL/HAL_SITL_Class.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index 8a7537ab9730f7..bf8bc073510971 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -33,7 +33,7 @@ using namespace HALSITL; -HAL_SITL& hal_sitl = (HAL_SITL&)AP_HAL::get_HAL(); +HAL_SITL& hal_sitl = (HAL_SITL&)AP_HAL::get_HAL_mutable(); static Storage sitlStorage; static SITL_State sitlState; @@ -299,9 +299,14 @@ void HAL_SITL::actually_reboot() AP_HAL::panic("PANIC: REBOOT FAILED: %s", strerror(errno)); } +static HAL_SITL hal_sitl_inst; + const AP_HAL::HAL& AP_HAL::get_HAL() { - static const HAL_SITL hal; - return hal; + return hal_sitl_inst; +} + +AP_HAL::HAL& AP_HAL::get_HAL_mutable() { + return hal_sitl_inst; } #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL From de26095c582b1c49063fe16ad041eda0afb356b1 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 23 Nov 2023 21:00:39 -0600 Subject: [PATCH 408/499] AP_CANManager: use get_HAL_mutable() to install new CAN interfaces Avoids dubious const_casting. --- libraries/AP_CANManager/AP_CANManager.cpp | 30 ++++++++++++++--------- 1 file changed, 18 insertions(+), 12 deletions(-) diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index 78be64a97c66c9..9275ea2ba05edd 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -119,6 +119,9 @@ void AP_CANManager::init() { WITH_SEMAPHORE(_sem); + // we need to mutate the HAL to install new CAN interfaces + AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable(); + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL if (AP::sitl() == nullptr) { AP_HAL::panic("CANManager: SITL not initialised!"); @@ -146,17 +149,17 @@ void AP_CANManager::init() } drv_num--; - if (hal.can[i] == nullptr) { + if (hal_mutable.can[i] == nullptr) { // So if this interface is not allocated allocate it here, // also pass the index of the CANBus - const_cast (hal).can[i] = new HAL_CANIface(i); + hal_mutable.can[i] = new HAL_CANIface(i); } // Initialise the interface we just allocated - if (hal.can[i] == nullptr) { + if (hal_mutable.can[i] == nullptr) { continue; } - AP_HAL::CANIface* iface = hal.can[i]; + AP_HAL::CANIface* iface = hal_mutable.can[i]; // Find the driver type that we need to allocate and register this interface with drv_type[drv_num] = (AP_CAN::Protocol) _drv_param[drv_num]._driver_type.get(); @@ -166,13 +169,13 @@ void AP_CANManager::init() #if AP_CAN_SLCAN_ENABLED if (_slcan_interface.init_passthrough(i)) { // we have slcan bridge setup pass that on as can iface - can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode); + can_initialised = hal_mutable.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode); iface = &_slcan_interface; } else { #else if (true) { #endif - can_initialised = hal.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode); + can_initialised = hal_mutable.can[i]->init(_interfaces[i]._bitrate, _interfaces[i]._fdbitrate*1000000, AP_HAL::CANIface::NormalMode); } if (!can_initialised) { @@ -245,8 +248,8 @@ void AP_CANManager::init() bool enable_filter = false; for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) { if (_interfaces[i]._driver_number == (drv_num+1) && - hal.can[i] != nullptr && - hal.can[i]->get_operating_mode() == AP_HAL::CANIface::FilteredMode) { + hal_mutable.can[i] != nullptr && + hal_mutable.can[i]->get_operating_mode() == AP_HAL::CANIface::FilteredMode) { // Don't worry we don't enable Filters for Normal Ifaces under the driver // this is just to ensure we enable them for the ones we already decided on enable_filter = true; @@ -284,6 +287,9 @@ bool AP_CANManager::register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver { WITH_SEMAPHORE(_sem); + // we need to mutate the HAL to install new CAN interfaces + AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable(); + for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) { uint8_t drv_num = _interfaces[i]._driver_number; if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) { @@ -302,17 +308,17 @@ bool AP_CANManager::register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver continue; } - if (hal.can[i] == nullptr) { + if (hal_mutable.can[i] == nullptr) { // if this interface is not allocated allocate it here, // also pass the index of the CANBus - const_cast (hal).can[i] = new HAL_CANIface(i); + hal_mutable.can[i] = new HAL_CANIface(i); } // Initialise the interface we just allocated - if (hal.can[i] == nullptr) { + if (hal_mutable.can[i] == nullptr) { continue; } - AP_HAL::CANIface* iface = hal.can[i]; + AP_HAL::CANIface* iface = hal_mutable.can[i]; _drivers[drv_num] = driver; _drivers[drv_num]->add_interface(iface); From 008c0baf5fb81e131a414206b7f360d5c3f1859e Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 23 Nov 2023 21:03:48 -0600 Subject: [PATCH 409/499] AP_DroneCAN_sniffer: use get_HAL_mutable() to install new CAN interface Avoids dubious const_casting. --- .../examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp index 97a7850d41efdd..5745e94b761d04 100644 --- a/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp +++ b/libraries/AP_DroneCAN/examples/DroneCAN_sniffer/DroneCAN_sniffer.cpp @@ -117,15 +117,18 @@ static void cb_GetNodeInfoRequest(const CanardRxTransfer &transfer, const uavcan void DroneCAN_sniffer::init(void) { - const_cast (hal).can[driver_index] = new HAL_CANIface(driver_index); + // we need to mutate the HAL to install new CAN interfaces + AP_HAL::HAL& hal_mutable = AP_HAL::get_HAL_mutable(); + + hal_mutable.can[driver_index] = new HAL_CANIface(driver_index); - if (hal.can[driver_index] == nullptr) { + if (hal_mutable.can[driver_index] == nullptr) { AP_HAL::panic("Couldn't allocate CANManager, something is very wrong"); } - hal.can[driver_index]->init(1000000, AP_HAL::CANIface::NormalMode); + hal_mutable.can[driver_index]->init(1000000, AP_HAL::CANIface::NormalMode); - if (!hal.can[driver_index]->is_initialized()) { + if (!hal_mutable.can[driver_index]->is_initialized()) { debug_dronecan("Can not initialised\n"); return; } @@ -135,7 +138,7 @@ void DroneCAN_sniffer::init(void) return; } - if (!_uavcan_iface_mgr->add_interface(hal.can[driver_index])) { + if (!_uavcan_iface_mgr->add_interface(hal_mutable.can[driver_index])) { debug_dronecan("Failed to add iface"); return; } From 87fef1ae5d87f9330b3ef3094f00b43e75ca62a3 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Thu, 23 Nov 2023 21:07:03 -0600 Subject: [PATCH 410/499] AP_HAL_ChibiOS: use get_HAL_mutable() to install new CAN interfaces Avoids dubious extern redefinition. --- libraries/AP_HAL_ChibiOS/CANFDIface.cpp | 4 ++-- libraries/AP_HAL_ChibiOS/CanIface.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp index 2d261f7242084c..eaefd34324c69c 100644 --- a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp @@ -85,7 +85,7 @@ #error "Unsupported MCU for FDCAN" #endif -extern AP_HAL::HAL& hal; +extern const AP_HAL::HAL& hal; #define STR(x) #x #define XSTR(x) STR(x) @@ -568,7 +568,7 @@ bool CANIface::init(const uint32_t bitrate, const uint32_t fdbitrate, const Oper if (can_ifaces[self_index_] == nullptr) { can_ifaces[self_index_] = this; #if !defined(HAL_BOOTLOADER_BUILD) - hal.can[self_index_] = this; + AP_HAL::get_HAL_mutable().can[self_index_] = this; #endif } diff --git a/libraries/AP_HAL_ChibiOS/CanIface.cpp b/libraries/AP_HAL_ChibiOS/CanIface.cpp index 677f484804943e..97cd8acf2ad1be 100644 --- a/libraries/AP_HAL_ChibiOS/CanIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CanIface.cpp @@ -84,7 +84,7 @@ #endif -extern AP_HAL::HAL& hal; +extern const AP_HAL::HAL& hal; using namespace ChibiOS; @@ -846,7 +846,7 @@ bool CANIface::init(const uint32_t bitrate, const CANIface::OperatingMode mode) if (can_ifaces[self_index_] == nullptr) { can_ifaces[self_index_] = this; #if !defined(HAL_BOOTLOADER_BUILD) - hal.can[self_index_] = this; + AP_HAL::get_HAL_mutable().can[self_index_] = this; #endif } From fcb3d40ffd9e4aa61e0e5a7431355bd63e790d10 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 Nov 2023 13:14:15 +1100 Subject: [PATCH 411/499] Tools: sort serial ports for uploader this ensures that the first port on linux is used, the 2nd port may not have mavlink enabled --- Tools/scripts/uploader.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/uploader.py b/Tools/scripts/uploader.py index ee13ed62571091..a4872f2844ff70 100755 --- a/Tools/scripts/uploader.py +++ b/Tools/scripts/uploader.py @@ -1007,7 +1007,7 @@ def ports_to_try(args): if "linux" in _platform or "darwin" in _platform or "cygwin" in _platform: import glob for pattern in patterns: - portlist += glob.glob(pattern) + portlist += sorted(glob.glob(pattern)) else: portlist = patterns From 48825c9cc685aa33a7f620387de671f7588c75de Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 27 Nov 2023 16:20:37 +0900 Subject: [PATCH 412/499] Copter: minor format fixes --- ArduCopter/autoyaw.cpp | 4 ++-- ArduCopter/mode_auto.cpp | 2 -- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/ArduCopter/autoyaw.cpp b/ArduCopter/autoyaw.cpp index 40acda0f05c592..749a830f4dce65 100644 --- a/ArduCopter/autoyaw.cpp +++ b/ArduCopter/autoyaw.cpp @@ -114,9 +114,9 @@ void Mode::AutoYaw::set_fixed_yaw(float angle_deg, float turn_rate_ds, int8_t di } else { // absolute angle _fixed_yaw_offset_cd = wrap_180_cd(angle_deg * 100.0 - _yaw_angle_cd); - if ( direction < 0 && is_positive(_fixed_yaw_offset_cd) ) { + if (direction < 0 && is_positive(_fixed_yaw_offset_cd)) { _fixed_yaw_offset_cd -= 36000.0; - } else if ( direction > 0 && is_negative(_fixed_yaw_offset_cd) ) { + } else if (direction > 0 && is_negative(_fixed_yaw_offset_cd)) { _fixed_yaw_offset_cd += 36000.0; } } diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index b79b008c2e6b64..99449a2991daea 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1850,8 +1850,6 @@ void ModeAuto::do_yaw(const AP_Mission::Mission_Command& cmd) // Do (Now) commands /********************************************************************************/ - - void ModeAuto::do_change_speed(const AP_Mission::Mission_Command& cmd) { if (cmd.content.speed.target_ms > 0) { From 2d89f835e50e174f01da4749c297213cad18a55c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 25 Nov 2023 09:03:04 +0900 Subject: [PATCH 413/499] AR_PosControl: fix PSC_VEL_I param range --- libraries/APM_Control/AR_PosControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/APM_Control/AR_PosControl.cpp b/libraries/APM_Control/AR_PosControl.cpp index 9cf414831acf7e..12eee4b7ce4a47 100644 --- a/libraries/APM_Control/AR_PosControl.cpp +++ b/libraries/APM_Control/AR_PosControl.cpp @@ -56,7 +56,7 @@ const AP_Param::GroupInfo AR_PosControl::var_info[] = { // @Param: _VEL_I // @DisplayName: Velocity (horizontal) I gain // @Description: Velocity (horizontal) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration - // @Range: 0.02 1.00 + // @Range: 0.00 1.00 // @Increment: 0.01 // @User: Advanced From 46f4e6e33ab41bad1ac87b6bd6203f8a8bda6078 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 25 Nov 2023 10:43:59 +0900 Subject: [PATCH 414/499] RC_Channel: Rover circle mode aux function param desc --- libraries/RC_Channel/RC_Channel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index fac080b717a4e6..fb85273f26eccb 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -171,7 +171,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Copter}: 69:POSHOLD Mode // @Values{Copter}: 70:ALTHOLD Mode // @Values{Copter}: 71:FLOWHOLD Mode - // @Values{Copter,Plane}: 72:CIRCLE Mode + // @Values{Copter,Rover,Plane}: 72:CIRCLE Mode // @Values{Copter}: 73:DRIFT Mode // @Values{Rover}: 74:Sailboat motoring 3pos // @Values{Copter}: 75:SurfaceTrackingUpDown From cb1c912edf48b9370d3aa1710d311e2335333234 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 26 Nov 2023 12:05:04 +0900 Subject: [PATCH 415/499] Rover: circle mode aux function support --- Rover/RC_Channel.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Rover/RC_Channel.cpp b/Rover/RC_Channel.cpp index e799f38a70fd24..9a89b66d613764 100644 --- a/Rover/RC_Channel.cpp +++ b/Rover/RC_Channel.cpp @@ -33,6 +33,7 @@ void RC_Channel_Rover::init_aux_function(const aux_func_t ch_option, const AuxSw // the following functions do not need initialising: case AUX_FUNC::ACRO: case AUX_FUNC::AUTO: + case AUX_FUNC::CIRCLE: case AUX_FUNC::FOLLOW: case AUX_FUNC::GUIDED: case AUX_FUNC::HOLD: @@ -226,6 +227,10 @@ bool RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit do_aux_function_change_mode(rover.mode_simple, ch_flag); break; + case AUX_FUNC::CIRCLE: + do_aux_function_change_mode(rover.g2.mode_circle, ch_flag); + break; + // trigger sailboat tack case AUX_FUNC::SAILBOAT_TACK: // any switch movement interpreted as request to tack From fc2ba985bbbc7863db6f2a476323870b52914ea7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 26 Nov 2023 12:10:14 +0900 Subject: [PATCH 416/499] Rover: SYSID_MYGCS param increment --- Rover/Parameters.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 313cec0c21dc62..5d4a84fc9b08b6 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -42,6 +42,7 @@ const AP_Param::Info Rover::var_info[] = { // @DisplayName: MAVLink ground station ID // @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match. // @Range: 1 255 + // @Increment: 1 // @User: Advanced GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255), From f435632a35f7f25aa4beda4b1a421fe3f2296035 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 25 Nov 2023 13:53:34 +0900 Subject: [PATCH 417/499] Blimp: SYSID_MYGCS param increment --- Blimp/Parameters.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index 26971ef2e65392..593e9f26687f74 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -41,6 +41,7 @@ const AP_Param::Info Blimp::var_info[] = { // @DisplayName: My ground station number // @Description: Allows restricting radio overrides to only come from my ground station // @Range: 1 255 + // @Increment: 1 // @User: Advanced GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255), From 983965258879fe9603634e5bc45f169169ea8a18 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 25 Nov 2023 13:53:48 +0900 Subject: [PATCH 418/499] Sub: SYSID_MYGCS param increment Also add range --- ArduSub/Parameters.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 73ce3dbcb02f54..83ce1933c30289 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -47,6 +47,8 @@ const AP_Param::Info Sub::var_info[] = { // @Param: SYSID_MYGCS // @DisplayName: My ground station number // @Description: Allows restricting radio overrides to only come from my ground station + // @Range: 1 255 + // @Increment: 1 // @User: Advanced GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255), From 93a2e728da49f21031b41e688644a0e851fd3d30 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 25 Nov 2023 13:53:56 +0900 Subject: [PATCH 419/499] Plane: SYSID_MYGCS param increment --- ArduPlane/Parameters.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 720eed4c273694..fbecd0ee40b6c4 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -23,6 +23,7 @@ const AP_Param::Info Plane::var_info[] = { // @DisplayName: Ground station MAVLink system ID // @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match. // @Range: 1 255 + // @Increment: 1 // @User: Advanced GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255), From d673cddf265d234bc1396932abc229c8782b99df Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 25 Nov 2023 13:54:03 +0900 Subject: [PATCH 420/499] Copter: SYSID_MYGCS param increment --- ArduCopter/Parameters.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 7c09a42b07f7c4..b449b18e146fcc 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -46,6 +46,7 @@ const AP_Param::Info Copter::var_info[] = { // @DisplayName: My ground station number // @Description: Allows restricting radio overrides to only come from my ground station // @Range: 1 255 + // @Increment: 1 // @User: Advanced GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255), From befd601341247aa8a4e43d515d19062f2f985805 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 25 Nov 2023 13:54:14 +0900 Subject: [PATCH 421/499] Tracker: SYSID_MYGCS param increment --- AntennaTracker/Parameters.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 79d1739ed21f0f..2d20396ecfc694 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -23,6 +23,7 @@ const AP_Param::Info Tracker::var_info[] = { // @DisplayName: Ground station MAVLink system ID // @Description: The identifier of the ground station in the MAVLink protocol. Don't change this unless you also modify the ground station to match. // @Range: 1 255 + // @Increment: 1 // @User: Advanced GSCALAR(sysid_my_gcs, "SYSID_MYGCS", 255), From 0e9f9920bc12e00950d771fdd513e664b0542b16 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Thu, 26 Oct 2023 10:31:49 -0700 Subject: [PATCH 422/499] Plane: mode LoiterAltQLand to reuse loiter point if available --- ArduPlane/mode_LoiterAltQLand.cpp | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/ArduPlane/mode_LoiterAltQLand.cpp b/ArduPlane/mode_LoiterAltQLand.cpp index 0cc8b9457c11e7..8fbfd59735cd24 100644 --- a/ArduPlane/mode_LoiterAltQLand.cpp +++ b/ArduPlane/mode_LoiterAltQLand.cpp @@ -10,17 +10,13 @@ bool ModeLoiterAltQLand::_enter() return true; } + // If we were already in a loiter then use that waypoint. Else, use the current point + const bool already_in_a_loiter = plane.nav_controller->reached_loiter_target() && !plane.nav_controller->data_is_stale(); + const Location loiter_wp = already_in_a_loiter ? plane.next_WP_loc : plane.current_loc; + ModeLoiter::_enter(); -#if AP_TERRAIN_AVAILABLE - if (plane.terrain_enabled_in_mode(Mode::Number::QLAND)) { - plane.next_WP_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_TERRAIN); - } else { - plane.next_WP_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME); - } -#else - plane.next_WP_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME); -#endif + handle_guided_request(loiter_wp); switch_qland(); From d1b2c6e56466f4dc845ee57eb28fa591bf6b08a7 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 21 Nov 2023 11:52:03 -0800 Subject: [PATCH 423/499] Plane: set nav_controller stale on mode change --- ArduPlane/mode.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index ff124dc6ba3dd1..b6c3a2b44fc863 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -113,6 +113,9 @@ bool Mode::enter() plane.adsb.set_is_auto_mode(does_auto_navigation()); #endif + // set the nav controller stale AFTER _enter() so that we can check if we're currently in a loiter during the mode change + plane.nav_controller->set_data_is_stale(); + // reset steering integrator on mode change plane.steerController.reset_I(); From e6b7daa323ff466b41f83b50c173ca10514a322c Mon Sep 17 00:00:00 2001 From: "daniel.li" Date: Mon, 27 Nov 2023 10:49:45 -0600 Subject: [PATCH 424/499] AP_HAL_ChibiOS: Add Aocoda-RC-H743Dual target --- .../Aocoda-RC-H743Dual_Wiring_Diagram.jpg | Bin 0 -> 818276 bytes .../Aocoda-RC-H743Dual_bottom.jpg | Bin 0 -> 195952 bytes .../Aocoda-RC-H743Dual_top.jpg | Bin 0 -> 290142 bytes .../hwdef/Aocoda-RC-H743Dual/README.md | 113 +++++++++ .../hwdef/Aocoda-RC-H743Dual/defaults.parm | 2 + .../hwdef/Aocoda-RC-H743Dual/hwdef-bl.dat | 48 ++++ .../hwdef/Aocoda-RC-H743Dual/hwdef.dat | 224 ++++++++++++++++++ 7 files changed, 387 insertions(+) create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/Aocoda-RC-H743Dual_Wiring_Diagram.jpg create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/Aocoda-RC-H743Dual_bottom.jpg create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/Aocoda-RC-H743Dual_top.jpg create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/README.md create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/defaults.parm create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/hwdef-bl.dat create mode 100755 libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/Aocoda-RC-H743Dual_Wiring_Diagram.jpg b/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/Aocoda-RC-H743Dual_Wiring_Diagram.jpg new file mode 100755 index 0000000000000000000000000000000000000000..550efc89ac4af97d7ecd05f1691e825c44871ac4 GIT binary patch literal 818276 zcmcG$1yo#3)+pMzBoG>FTpD+mhL9lLxVyW%I|R4JU4y#>cSwS}y9Rd)kN~mA%zyuH zX6}9O-TT&?skKh8uC6|HcI~}ud!0Wkf7StE0EGYZhWL+$^jG^Iw<97TJdZwKe+~Sf ze)+QrKn9HbxddQ~nLC+U0L(uD004wPp8!B~lv-3#BmfYA07O6pBK#RZPy-+U04ONW zAAdC@WONKn1Vj{6v=<1^zoR|F^Vb*v0TBrq6%8E)0~6=@KBQ;pP+z>n#39E4fc`dw z0(c$-V&LLYbKw&Zim6; zrq-TbQRNk_?IVjTbo302d;${EY8skWHm>eIA(7F^DXB$`%`L-oM@&#DS#?V{kBGF& zrlI+T!($=I@T|UF^RUuEU5nz9GMHKDz}~^v=k*~y1A~bA0vGfW9R&dc0r1=fqM+iU zJp(4Df{qV1aY-T|1aYed7dFh!UlY;r@Ct})Xqviuq^6ZNf1X>wpyd~oP*c~kbn^@e z3r|idX>4lg-`V4XN}5?%xrY{&_1zHDF)+a*2KE`Hyowj;&C{i2A_s?dTmP&9ULrl? z8;A%5yai0}Mx{cF=zxsTP+71F?!T|2tRJXu3qHk+KPBBPVs!r>&rrd8OFia9_4vpL z&(eAH1u#i{aA>^=dgxAtQScUzF;L7t9K+N86Y%`+SI5o`4WT{6o;iCEW{gp3x=6vz z^uz(Ya=K6f;Wp-hBLv!@$`$_uO>K#u5U77MY<=CMNXa#-c=q3jxqm?V?$6ABjy`0+ zRo}TiuT5F-(hc3m8gB6y4;0a=K*p56&Vn2r^Chz+hT9UR$Du06|85TX$2$LCm@fu% z{{)XKpbC5{SH@IfnvgNQUc|`z7soCLOKf6-FD`s%s2;_m%B=q*Fn;_q`yV5N>g7i! z5up3c1*N++{2v&RvUdg#a7HFfSi{@sogn~;QK(+5Ya+5d6~*x^2xnIm@+tb!-^eqn z0}6!((Lh!HzVemA&)k>7es{12Ix$i5ZbMmc+`oBO{{zBjnkg?Tg%J44 z>7a<|ACuaW7hZ+~JrCcd;!O`wI!2XM{D%lS_a7su@_+9uB|&>Lv{qhN>t8ZecNWCF zC8|o5y6K1ZegVeXwMYnD@qCpY)ndM(p^UYQu>FqlS10&_4qG+I2QjMcSsdr3!um#p z0SNNN%Wdy}-veQ>Z%*QW75{LDjs0gt&NEq`$pInxgI zu%j7oP=Bz7XDRf_0?>(s1&SEE{|2?w+rX$+V)y7Z<05w8kLE?j#4hwl|6gO^oqye) za33VMRJ3uZK~I}1?RUl)k^c~77ye_E)x*acadNu}=mej#OIXC>!#MtD`5C35&R`M| zRrFnTTM4Q>Q5E@35?I8j4lQC2<6-#uhuBpW1JA(~Vn1jBXD>Yff8#i0NY`P)4D;6^g64nE`&-E>+gWhVXF?S)E zsX?wB`aAGJ8l|6F^%wU!%@%?8fjSinKk_4YKGEqyEgFs$GYUG z{1m~RfG4E0_4^O=%lC6Ccweo^I6jI7_yx8+`Tp*d1@}6=tfOxyjhRC2^1v$3kz?0s z)yTCY9QoO1!ccoj!Gv|&@?kb^XJM23-)AI?t+iZDxsiNL*9(C{o zD(_@oDNz^Ikoms@8q{j~3fA98L*FBlw$4*ggZx4|6j6Bm!2*IRniVsjte{b!x0yNE z?Xuu%ie910EG8yF&Ye=sHPVRnX)W$kXHk8Y1(wjkPrqzdv{S|q0Y#xsaGmvnA=s^~ z+daBCm$g~G+5(SD!}>U?L;7>Wh)NNMO%Vs~LYZ&VT}%1KY$aJRsjIy90|$vAMD-%3 zDQj@Vz?J_#3H58BMqc}nqv=+Z7xzvMURtN45s&C;6vC2xS0;LmMUfNqM?rv(Z6w|a z2hJ{=kzN)lm-GfOePT(v-g!VIdC<>ss{Mo2a9(mN&#xV!RRYu6w0UX0p-!$`a_&q_ zG43$%$Z1q6%;7zQzAEn@Kwl*GN=KIpf1qjig?wo8+HSk`Pd2AjErPza9WOimWm_fM zH6sWb*--II?RAaMFN+kH^+7_$=+V$&YEaU3%brnbAUp1A5vjsA)B^i*ZFZr7lrHtj zr8-FKOp*juN9S5!@&;dYTBB_Il6~p>eFLQACMHbxPA+A6XKI2k&!S!ZrkYK04~yvJ zBj;%f_Xp;5{=Qbbv!MegK&l=*-ngP>GghI+o-ZdODALb;Q!OETXo%|ImRBqAf_AFW z*hCPh^FhooIx_M*PLIMWiSi&Je>vBd%*cdeB)|WA>&6C=E-Sea-SoTgg>PGmniG?4 zKa1273c=*evpfyVELjLjrOXlXk>C->zbQgi&BhN!w>u3{+!4|P%k02qyt4$*c3XsS zz8_j#Jxiukil;(9je~4wr0XAm>TE(TtUZ9Ja6Qj*a!ClRA|#Uu4T7by{iTt51AoIM zAZHmeLKC07dJ&c+tDVc}rv%A0_ZwW^6u5p9Xwut%ZQv!{&{eYfN#}d)YYcK3J+FXX ziwVgC?XgtF!ni4es4AtIup6WW$C9J_(ojCW3bK}b`q~G7m2|F}GMh22_ez~R;HhsX zOa50S`6(1Dg`P<7Zqu?nV*uxNJAg0NK2Rn8F6 zE3mvScJT2~Zrkm{vx{~^n~yIhIS%QiE1siH*;Iz~CnEnWpfv(>WLFQO-Hmu${NVI> z@c=F2sQZo;C-!<#F{s(E0%BE~*#0%*{Y~n{;dNc?9pT5s*35x@tW9#O7tH2Y+D8Wh zvTm%Xj3Mv4Ujkrysjy(mqWxW-iV0BVB+JQ}yimr}3by28-*-plQH#$$USQKuecOW< zJ#kK3HJ(uT)+YQGbM&3ogUJW8CsAv><~)5f*^l3n@N zP%^CdmD}``9Vl{neCUNw1XHXepBA?iraBcC=|#J4YdjL7Ni11?(wt~jQ#vlfcIwu3 z2lE;(bC%N}ESbw3;TPsK3bgD-__K|O>@UTb&|%r7|HU+YA7_;?p_K zs!{5D8hBzy6B|oQCX0oWk7-->+*UaW`5L_2W%|$DJ~!#q<&V8|=Jzf4&kWorV0T{t zM;>bl*4rUz`3MM|2&iWvUQIPDy`iA_aN)9(ef zB*yV3cKEAFj-a=5A(v1S+WwOz2r`2+1`ANWsRAE7Z`l8Gq+qu>dw&4KXfdc64@I^{ za=tzbKjUfpyjxoF#TQyGa^0dfq)S?k%75x4U4o{sNJILwySF-gTn(`YN{IoEF@P*Q z`R+12pf;{utQ8UK&|__Dd{0Xx4HpZy4OH}LUsbGB#8!JP< zYqK;ICjuhCxTrz=!*C7~2a&1?`upm-7dARpEYgzY*&H>|Ua`R|WpFQQige5CD6$57 zY`ha?X_OAdLU~iSOl0Xgt}-Q9)1cG~=|O>sIqzbPrBE-4ZB1grzQ_g+DPV|dq^pGC zN>**bD10H-VB}Pi!q}6mQ=I7x8m7~AUA;G4Ou>wWVWp$AwG$vy4<{zR5ZcdTylJPT z+9c3SN*Vkvgkk|oEig+KJ<^|4wqc&db)VW>2b(WI2rjH+Hgk3EUHq)oA~mb{G~$dA z_eZoF`{J+ZVj4oZN5kj+w)m$YA)WN#V9PJRw;D_8_7BZd@KVc+KRcSN`+^_KZS-b= zF4}{gWewbu_f=$F`4={Nm+S1(eIO}6M;66jEe5h_%?BSWwMV#2URda>vQjc@4;tgf zLMTH61Czj*^x&u6zr3XXrsiLvj{grMu%S^<7WMbnKYvw$&+z{rX272pzhyPDo8DcE z>T(H)@(YIQ{)b2Cy)g{r}HxDy4XQp%B4UYbsch=A^Chp zt3!edjLK_rmH;z47x6$|)(i*J6{C7s;dSjIspGbc-lzt$;w(+gm4fIz2T?pJ$u=JE94vxzVEjx9*z_Qy-b8q0S!G97ndZ%!h$gSI?6=E5uC#btdF! zM$?kA_w;9e_S-TvRpn`GG|udIi{n)x?f(cLF#a>rOn}F&9&S~&+y`s~ob&0WZc`{` zUfRTI2Mhh!2VGaBJnfqU`kI(ribo`?xAn(kkObJ%J`6VIMh}xm!9l>GRC^T6-sORg>Bh$Kl|Rh(fGAP_I+9vYe&3=1M8P>j(wv(d-U7< z?tM3cuJ?)2nzHL1bvn|KF+*}x@UlZ8adRzbBx7(4fnh6AmZJVrv(R25x$RbnO};A0 z_x9G|VA?y5QW0fF1-SBs9tQz?v-7l}sFITOG{HjU;z>#Bl+wh{ zp>1eAtY?`hx7qMx^TuLT2td6~?xZJ+9+8&mx6cc2Y81{yd*?H50O=)p0TnKZZtzXK zT1=-1M*zj<+ppt1~g}CoYAY@9XUdX_yp{S`zy$w z5QP`YFmfj2ZwPp7sl4+1{7p3ClHRRk@o(CB?fEUuj_~IkwswaRvo*YKljB^ zQZ3n{oINbR;Bik%RxeSP&ko1U1c-_3a{Oj{M;cjp6|z%as<(Gk10%mrn|0#G#Eb%AUrV@l?7uU)_&+VOcfQ z^yVGHHxT(Fc7JE|W}zHl^#kpoS4j=6rvV0%CHxklcJpEySKW-UCM z5&6r-PQNZ6-2VV@b#wm!;yEpVT5SbgPn0A%PhTy6_i5Wk)kz)a^#%{My-WJ=#KB1b z^#9T>?!5F^P144n9v~z_-QnVJlH4tH*Ks$y{TVI&R`Kft*UpykdN29!!^`&%{%1w& zMQ`~Jz++Nhao+7eKZMKc4*(ViG_4-YkG!w$r_pwMg0*>|#}^;icTo(te}K2J+UjfD z*`D_7rFW3(u;^Kg=&+P)lxBYe%XJPui5FTRya~z!356MneH1qcVYpsK@A5ot2PRpU z6*q0^Ox>t_wO=sp5=5}E+R5}tgqbHBNT0N}+taSq7~{4(KE#xn(Yg;v*NF^mA4}h0 zJ}q;5{gi(e>{8AHvuKkP%M>`X31wa-+vN;pTHi{%K_`)4j!F-yKYsmiMY&@Uw;lh} z8*77dquB81vM&E9k5aslP~Rvq^bdgc=n?+$iPbtL-Gl3x>)t7zjhH1xeywm&HzhL$ zW@XvnxDM7s*tm^Lv^+55Y1w4+JRnur*u5M{mM)}Yz?~U{#9KjegRx-=it#O3HNCI0 z+x0DEJoL($;fsc}1;vWYcHGfBLv_OrFNWdzD z6cllI$Nn}cXQN?1Ff4V!1^HssKQ?a&f73P({{fI$34xywpEXT=*_|cHgzC_I@B2Gp zyRkbS$kvrt=2y7puxU|Y9GC8BW0OfKX`O~4)zJCK*I=qub1@#wrNR+rSB!ZGAyT&Y z#43{P>Jf^q_%Lml!)gpSL4JD8pknn(`Z7Q#Lz}gU;#}eF#=57&0!@3y7iA5UWDwf| zQ-6uPbnh0C5u1+B70~SEX1w`qR(<1UsLj5exB>yLdR^_=5LW7)PAa})A^LtCB|aQ4 z(0q|8${|(-0KOZ04vqGY>l@{0X;T_d6ucP+IRFFtt^Zr?z@mnW$>&$Ua$x_IdB3OA ztgELe6dFm}HTYS)-6EmsC4P85zosmGb^$Zwqgk!8kk#>s`Iy=5ExkA+4F0ZAeTr#k zit{0U(_$WRo&Ao0dpkBS^%#m{ z@^@_U42j|msl3XB$7=w1%r>g`?VBhs<>HD>a^Rz zfw6v#*_4=o^x~96WVSy&9?{FD{%B9C)Kc(t|ID&YO}5((QrUM7(-kQLpL@S9m1W%; zS(mF!^XTH%;jh@s%F%gVF(y9(H^A?kF_WU0QWaGZBf-^EG_RSO-whIuw6d`&>Mmo@ zpTkNChact062^}s95Ef70>+MEW$R6WWARuBHArO{R~%UKvxg!8S^ zE<3u_4X&kaNL77me4;5!n~X9PpNb?Z7t*d~{Ra@fnB=ymYt~YSH@R&Gt4-uihvnG0 z@2_vvN7bYXL!!%ogg<%Eqxyvm)H7kjQVl2@%oRnc7H%gaxEgXsQ0{u(ef& zkwia}>)(q&#lNgT_`cV(gpYsocL|SkO#rlfcMM(QlMC}>h;DVvY156Ls1$OCs?lUH zwY)IuNOA6v#jKIsggkL_M&aeIJG5WIQc9X%Lx1{ZX05cJRFsF|=MBkmInYp?a9t>j z3q-T7y1q&r#3^ERZO?xq!NNQX8Sh|^ePO)123=TVdoQD>)yv$LwYD;LosGOLNc%>8 zNEu6S-O=obmOOe>0oH8uI(Y+5ZWWDlz6^eh-SnI);^nHe@iVkWTyFpoBws*#$4GH-xav+7E=Z=~ypmMg#JA~`ddpLz5n zJl=J;h}kui(h|lUgO^^4_CXG6Y!jM1Gz>kimeQA$pffh zCINiDL==Q1Mhjt*r4Djx97b-faU*?K!`geS=8Wqf@%O5esa4#t*w9e7W+FNqK{!`I z@w(xo970e7aCU)V5_cwgBgJ3z{Qr}Mj?r0#%;DT_MRi8^o1y!;|5M`XU#trKTpLI# za6RB7s2^&O{m(fHd_D~sJQ%*3P&I4iShfsp7W9;{C=!Pnj~eitsRRHR;d`Wm zuhe7g-bN8tdr+htlu&V;cR2GmfV6)ezO=A(CuHYlV8joT{%oSBvg?Y^kAl2u3B<#e zL-woCok|ojOp95N>B*aO$2)cRg-_klRi4xmo#83^=7;eVlVV%Q86M}FPYi)?HI=*3 z$A7OgCJvC->4C+?g6{8;5-2ScSWUGziBB-K&ADV((Zv1$vVSPAw;|K5JAF3LT*#5B zc0G)UZKt9qV%At07ng4omt`aAN22Ix1-iMA|OfV&$5{Y)5BbrbWU7eZa=AQ(# z?3r#8pZqGd<`CaVtQ^u)8bSgf@)HKCi;6#?NuQQ&Hb>+yYCquMkap%F9VxDyv2LayZ`Jzcil@o+8H_K zsfgdtpEG{OxNlQZyUskD;6*gJe?B%+v%@d_IxBz_f2A+fEmN`cgdU)>@!4=acZs)W zg9H>b1i5@^+!fPVzV9tK@k>H$_$)N+BSwqUdh=GScS3!gpJeq6rP``y+tdRMn@t9r zp*M%ns#C+E_V5QCDMNnyl#wj7`UF~2nxo93rWFW=c8172ka^QJ3k@?-y29hC9i^XQ zm4u?-GtKdvkO1LpozDS60WW}}f)Eoi007T?Lc zR@3-Wct>UDP3L2T)vL?X@#g@D6xBPC`Ft7#D0K438az0jTu?-mbJT$#e@2?5 zz6%?gPg-X8Bz8!rY76;i#3{e;D|-@V1%~jwRG&cJF&}yfgfthiN(cHym-%MPdPLWk z_9^PFkz*I`riezlX0B&zzgo0gsk+Xw*QRDm4spwQkU_NfVaPES_*~LzM2rhE#KB(# zjbu(Rdw5+jBXF1Xl#fO1&U&;@N0a|~vw{9B|0j+6M($mKB0s;Vy4YKaxXbEOD-zK| zO1Z78p4x{9p2q9mj8)CyF$ce7X4p8tV%Pq+5rv}MQ&18Es-UB35C%c9pym_lxklf# z`rsl~O67TII^8gt!NZQ8>`6V_c%a~f<1$WsdXl0dy~ld$W}`0F8`T&o>M=LKxiC7= zJd}xn5`&nAhxLLGsPdA0bhOviQS!WaML=bK*e?G=65-?=*Tfresx^E!w7TZAj|sszbEooKv)^m^Z=?7~3n=*WQuLRRrb6HF>nwlFLx{fILPeHOH8 zC$G)EK98MSubJn7n99~o9bH3afZyPS*DE>JYG$mS=3E$+wdBXXleEcR7=xx^5$lF} zNCGZ;&;JJ?E)}J<)RFRW*K8Ivg*P+si!1>6j<)=c`e^OHqBy-Sy|LdF(k)*v8m94a zIP?odw|h{=x?&Z-Yqy%A&l`3&hL9388w~uy_5UUF0r{)Dzb!m}sbY$&5|gyV1()UX z6PA9y+h#80))SKJTYPMt zM08c45l^hvOzAGmeU9y`b35l*(8Tb})-RF^%;(Hshu#yV>mo3~|JfGN_V(pfD!eIE z`aq9&PM2jJ6B2+NdF3^r_mDhK`O_u$7=HZXIimRR)1`jlesUlmo^F>sbS%_GBa>Wk z_o2L9vdlDbQhcS!a`+l0(%A<^m%L7Fgni$Vl)3RFBi*>j846INCfFCj`vbr{QsGyoUB%=@y04rmHACZppA*Awa zeRJOmCg~5!(@Cc@i@^$StwW}k=vwRzXXd;lTr5}la^HyEcZQY_h=y@x$f)4}pz9c* z4YsZ@@`BK^>Y{_{R5j<-aS!xHY#i;NB9?+iQ}acb`UEOd3|I}{3%d&Z*y_t;AWrzS zOqknzI9#YHp!9%su><}RA9P0TbEH>tCI@4kD8+3>T?*uF+awSZ5bD{WqGghnsDOPs zqlBfTQx-yZ?vpc22<4JNs*WB=Ud&Oq1Dm-d}T$4VPQimO& zyhLZ11Ns>i)J-$3KP4_nX6MVaGjYdLHZ=Z3HXYVJ_dAHJTW)P$iyd>cyeKgoI{0>| zm63RyiD?_h!sKtEuf=&QkFt%l%?^ zop!d#d!vZ9~W zDZ)Jnn;dp^!@!s_W@^P6ZiZhh#y6xjL~<$e4e-n1)38pcB%E(JSP!*|@lWnu_z`Zz zwS3VLu#X>UgO#Z3$|QyZm@t(Ar$wwF5yG+$Emq}N$|t(p^FtLLc)`YwWEjp9`Z$?p z{N^M|EI?+)Z;Y=PmJNI@0UqcW=L6TZAI(8$BQoFI;jC0r7k$LiOw| zx~VdFi+5g%&$L<2qyop$t}X;~$&Z@UZN&@H09(<1F}0BtofMg7B4Rfdqm)&*xUPjE zC>o()J_T@1@}Kb*cHvmgn;bZj)I8K*=C5`|<$6ECN_|x=$6{;7v)TTnx|S4?X+!Uq zz14oz#>tIELt4c?f7!esMlhqGhW|++3_jOB{zUyt_Dqg_tG!wdB756MBHY4YD6U&l zPg_#sx5rCOxI-)X{o|!{d4)c0NQUpsC3pu{r&>LWG3k9#b^RuorQr#)ZQ6Y6=5=zi z_o=v~*ir)J+rY=Zx~*Q{3j?jXlf7ZNJlIC3YiEQ|4A~H5$^`h_ikK*2mDLwIC;jR| znr(MCRpihw+N6<)`aB?HdZNiJ77$cXt}yX{n1+Rm)NEtMet$p7GE0T|Eb%lA91Pef z03aKFKNj~;sGOAZpZTEfSj^M=?wVyG=ZjOhrQrxf>oW)XFV!ua2cDhHevvJTKLD@r z1kdjruuX%3NV&WzZ3XW;w3EZOgUkL**;H@}vh%>7+F^gR{MP~$qX z8oDPxO<|uj@9!M#YIM}5D}mFwvC%OF{EKW6<{%@ctOO5?HziZrM*1#oLtQPiRiw9y zH!Eh4&iAd{Q!Zl=&9(G)W0(DwP1_;Kbx_MP7q&p|LQAV8P9(Le^RB`g>%4N$f@vna z{7fnC1A!t7vEy+w?-JyQ(&VsAxJylOO)b8Mmc695j6+d!8C9<1rrGDJtIy!LU7`!K zXyj8-B_4~V4QU=sx@O#&rh1ZbUxVJUq=mX{qUH6A$!Zp7JO+~qIImV+_qux@HD;9{9%YI8&ps2*OIn@$Ckjd^UsmI#Wz!w?2htU8vUmxE(D~m1`OMN=)ms%M z7G^gQGD)@}(gubER7uH^nXV`)S6R}Fb01K4nfbv}MNt*iQK&uFN>~?s25Xtqu6D?@ z%p;;Yp605Pa-J4s(afu--!9)atqZB}E~lp`iu6Zf=D24{wz%Fn<+dqX!w-o+7>fLq zzW)R89Yv0??&kDl^q{Tck4K)rA9m4R8fRS8a*s75%{E2ZBdumoWL%s@Kk$J~Em~1e zEv9f|;K;+r?b+~e>IOYG;tRPV^4ep~qE4dKl*Wy|5#;3C|0q%wJ$#*X`G|k9PxC>b z7P}}y-%5^;V;vMDZO*&$_%JDPhMutw8fsPZ-+Fnw^^AQ{wJf`8o}k zU4~|s648JzWa+%irB!Xg(rQFgVIR)Q<}V@Ml-A;yv!uEmSi?8{dPt`sw@n?#jRJ;; zSfxIt%29Uzx0It1%}40Poy&dK&$xFpkwF!3-gn|0chtMTJIGeQ>Z-$1E`W^iBdg1ag}A%?cD;~g6f%zey&rnY2x zA0ckHBpE%h8&80s$1wN!eofefqM zO8f0LHGBH=Sf$}1>m6*5ei!@l`^fupgW27dCj@$(j+OJu5!7Ktu=~9tR`4%8O5979 zC*4I!y1BX}cCCji!ozblN>AdtLC<$C)da-+8;DHLa;0hSH3idaLPOId$_r z1>m`m;A#HnikedAZbM+QO#gZo;Sx;=q4#VicuFQ~!F>@KbG6SLJhm29%Qtuh*Cg2C zD0g>t_&O%3X_BK_l*s}Y)R$N(>e7<`>B!4t1wCS+!E(W#S4hAw`tH5SUt60~qb-QMCrU1y z(Q8sf+9JLcqk#<7y7~bndF?cz77~pSBwg2%6M!dK4;ZIdnBb4;1{?r3!@ zmjcV~dn)E_LE1uTQ%eL1r8^8PG0(}ZlG9=9bzoM&8EcJTjlztyA*II z7;ub}rXHqTB2)??wAVeLn<c*25E9JTD|n`F_po&^ zMlSGXVBR=qTTzBTdIHC zGeUde(zfenzqX0)1^1ltcaa`fqq+if;voTTgYr!q#t?SWvdS1^`aal6w~Yueu*{<& zO?L*D&0BTbb^64Mddt_%j+uxQz-Yx|1bU*QU>46W4 zb<6DogTXXV!6iHp%H(l<;9AEMrh${!d^sV13um%pHds#VMReA~PV8Dk7RL5wTe5ngnRD*J(lFXPLmFhRNFD|F+tT|KI^rMqEbgqIiZ zxdX<&vu}7uhe_&>E@?E;{+7Jv`3~Z@>~UD3SF6R%M2j;qCFkX?>_M5qO)?v-SXY7% z$wca@2vs&bgm0wB;L(pTSxk(Z+k!r!Lo|20!W^ZAvyUPrr&@8N70g1_8dMrzDnG6P zvSEn91e({M_wMW7P&}G0=^lL#Ju-#hKYOZcT zY3=ua-z_k3asZquJxM4?>7UUHrbCwkozkfVZM`&WV4 zKNacVMs*?U`r*q{KXkjpCjJVq|824sDN+Y@kW@D(pG`W^C?WrK=I|>nb|K{$Vu9b} zhjhuqF0Xcd2tkfr$bGH9&zmE4 zDEzLUt`^JqWLi$8QHdIf-$GA!BCDNdwH*9=wORi)T3gTDl!%40*pD33Df1`MsEQ(+ zD$7r5WTik(zpta6adRFh@e&l@G>4b8(vQyHx}4lX4q5TM3Yz@#vCYqph!uhEvC#`j zjqExs9{tJqgB(0wkqIZskO0$Yva)CVAX}P+u24XL9xQ9xU;8I;K?@8sQ>PCe&!Hgv z_1olN>O|fi7KU=t`f7GmUvD|FCJcQeDsy>oJ2#mfgp>jn*P-b~v}bZi{i&D0-LEr5 zioxYufJWksTz47hc5>(3H|E=FpQG+tUq|3xkbjN-#YcD}@&;=*G7MH+T2u?Mx|vQ= z7?W!gs-+MBhohjoqGv4QOE{BizGz1pJH0rZpml37VgTHU=9&Tc?>+W^e_-p1MGgcu zAWJr4&zIdHEoyH&F8cDEvc02yF(hz$Ho9FoVe~yx@$X~G7i%9R1E4<>If%BaKQIKA zbG_Rl7go%fd8HxjSv{MtV&&8~uf7(u5D8fSsL}!F*!0r$@rw4yJ$PM*8W+|@Q^H#L zvXsSJxL$~$>so$W>m)_{ApmM?c$ zH^>*+36g&R#5$tB_`gi-^whI=r)IOm7T*-!Mu;@=wg@xNt&I8De($~T{xPJ+ygP(5 zFFml4f-66hBT3A}tE?T)G!`=ss=-<`iIT#1!NRhp+eGTtDvlWEO%c}1)g_&K4pK&X zcexbohL`u!>Gt;%d1*sXhld2ev-N~Du@N1=_T33XhM1V-l~c^xu<)H70A;Kga0oP% z_de=``JUE_u)Yeea}#qRzZWm7D@^H$bHPIEt{r})GUWQGWvKW|(ew|XTj;}@`&N)| zRpj5v!muCgJ@m`KNBABB|9yS(_o2%57Q@&lINOzY&j6)P_F?)`r%=PRmZGf$>F^hr zy}6_GxJt0YU|l4{J_9p0!D0P6hMBu0*b)GscxNX$7T)|58|gfcb03or7D_i^dWc<5D4$uMG3Hx)9ET0sE+0iwcB9RB%Y~%cx1xn z-c~1weEPJL(7jfe|O>%1)QktqSDk4juHcSi13I^UQbb*H-wlzVH0PFfM7?zye{72YGglb{>cM zSwl;H3J=z!-`eN~tCPRlD@x90x_&-7G7cS{JXfd&F2X!_|CsTHr~}JxbfQ6=wNNDW zj#j(-+$h9uW0&{6`TNp4h7aU^HhelXUdqMAleemC5@$~h6 zGPsX@&ev$aYa{&wxMCq|&=GnhexfQ)Qsi1YQlZ1s;Mup69#A1bud+lkwf7g1k{_aq z@j=e|giP)n2XP`7g@uxx?{)b8r>*KUW?Z%Y8bEq08&j z(uBNFY3pU^Xu?-GEB9-{Xlr%Qi(y_(G^2Le&y@+F6KZ<&h5Z6@JRwnV~AYF zk-}2^__9I!aTU`UQsIh#U?MX7%mJ#|y61F9>m43omnHn0UIggBBl1#dc6b)_RrZ}Y zMZk06_uots#CMX9KhB-@XMd-jf~($&nLNg{xZTeV2SlHrf=A^3jhO+>>OH-h>lrUB zHpL_D4xS-%kfv^X+pCHVl8T=ldd!*jZxUCRnM?xnf7b{j7e1d~5Ds3NOC^|3XFNR2dEB+nQon7;ou z#A%R?N*yGeUO>R^`2;^QI5uu6a-efj8vGV^SHLyY*&OFl_M<)CD6JaxJ8b5nqz;^M zX`#lAU5Z8rZHR#OxyPs241?83U1Y>LYAl}dyK_*-FbnnM*Rvx!J zspqO(3accYuITY;1@Dq&*$b>L4JW}D8sW9R6~VqR`4Gu2Y6{m9v)tpz8m?H=sA$mG zIGj*2e_4v?m$s}9TZp6`!)bxDp^%sr@_we|KvKy3l(4#%bR?Kjepu%mpZ!x{R7{Yg z3HvVWE@`);xZ2bxIIx&E$NF<@t|9j99q?v>SDZcOe2TZ!X+2}`{SvU4O5^L5zOQys zh=Mela9u_L4kzPtq(?YGq9K2Aews*uY>IFTWgAdo{oda=)pCH*>0s+f|qn^bs50 zhP62%MB}X-E(u&x$845FP)?>?7hAzbjgUq6l(R-VxMyHZO*C^lmM)kV9iG6^0cobiM zwV68nK`*aD0DHpN-p+hSU4FNuLTItp|8wN2>}jLv-OAKa5l1wwc})q;KJ89P{(ubs ziEy?!*IvY{oV$^VO~>GM4O|2EG!%IW*Gx#13BoB50sQ2Ajrql>yoc>1hu~CBB{O1v zG`oF*f8vd_@I(p%fd~KRrHg3_8B*Qnb2NvfBC&0k18m<%D|r~zhm^YXS!dwDM&qog zMu(Wz+7Y_E_RyfP2t@f*TrSt zg-5V9eNb1~($ic`!?Xnh;@&AnEpJT!0}%g-*2oeI-C9m*NEg)9;cZs42uRsO4MiLvFqB$4-c3QCGWAH%TR<3uf_Es6kmS z>N9~{yTnBkqoGdKj$p}4@u?2STsp6=c!h~2$OKM(g28GVE#6!f=mO|QA7fvN12Yei zWa^KodIio21`X2>ch`}5`05g)&IWo{Hx6`Caj=-GaHk%{wL3&xrZ|5Xk?@@-&rQKk z1yB^?&Vn}VNDLJk*&+4ZFF2tjMw$xMK76Rd+;N{@_KA&C>z>Dt=%0ZdWk;x&14KG3DmO5zh{LwCnh~E_7h(hk;$#e z0Ih_n*S|o8V7v$2>4m?Wt1ie1_k7VxYEyuRbk~UFBsi{bHY``8UeBZ&r`L7gOrqvE z*o{N*m$cyGGK>LONO7+o1RIl0go_A)AMbs+*vZ?wh=u!d#Ty*j@T?RLYJ&DKtRiq+ z9QO7;kZw*^LwvObZcA2Uu*TiHLYgeIM%(dYYl2BzAX8}4yM+X`0T|P>iG$licCX(F zo~eKq1OHZBz>&0FLeLY=%{%>g`$slr@aVT^B^W7HENQ#( zgfw?MPpjg-t<6=dqUYvDzj+86x9yNd3N+M6HI0hj`B;P1?U!VFbgXw!M|8>Gsbqy| zg%bC^tp$YVg~+PnnRT)6zL|DJO0agyuYVKQcOC)9G2j8aF(XUm%2uX8Kr?Q$fB@8A z{?9H<*&o34U@_E)b&9|Uh8FRC`J(vhIDFV0_N}vs9XQ$I`1(D(Gw+kQP$$)jEKGbO z-Zb-r2oS_yjAB`AdPpET2Rx@+gxgw4mlWbTTaID|naJms=oe=wWC`f352N#1ukzIF z%%`P@b)qLi;;Y7)P3e=(86D|4g8(W7p}%m5-2*BV2|Mc>oz6?cX+Knhi1Z=F*j!pP zs}|jB=H2?Uej(&?B2jYhbv9z>*m5Q6Lfzx76wC=kCES8i;fK|IO57VnXwj`cJSU~?s5ujpA z*?s;Xhq4_5Z_~L|xm|>mf_D*TxwG~mmv^hm9qfXA6{%gLaeUKuWy^|3pv$V=k186yMJBrJ@1&N?nv&lG`~GJ2_0qp#=Mr$oX$M02KP%| z=e$}7Z4PI!<8+^V4s_$F#{ezbO;ZoJ7)ci@IKg`{FYad7L)M#nGDm7&Ak|R?Gg#;V} zl@+s+1-aI!(!87Tw!Rs?zJt9VYJA5{SoOR0{NNjB=d;e;2C*@rK4M7g zFx=oe_!=H2!M%4yZUeIjNNZ<=t)Cg-B&WuGa?JRUI;?mBj0n3&y?g7A-h5T+z`2_z zXDjhaS4UWDHGU;>RQC0#=TD8Lbrih}s0(ea9`|raru{ee?JniEeEO1wLRDhL3+E@IBOYj&X{c7tMP0vH@?Xd8_iPtxV^h{x{(<;y6)fC>M(+0g%we&iRfeB{f5yaE2 z=dLG_t!wU$9(Pr4Ak$PAVTF~bvyB`w#oW#U-E28EZTZUeHfvZTm-ej5F;3TM>dZB40tm7bWWD>kOAapDsedxX< zrj9Hih#}o;+f94R_BqHq$6AR|&+&6k`=sKooul?HI{?(=$~QMmx{vId$8P=ole_ywe4rI6Usy?E6m)ipX7)&m^Z|2d`{-FP8km&d-V1MH(7m9 zWtKD`|0iH3&csarjL{Nh`E5{6@>I>zyRhxk-p77MN14J{zy%g<3s9NO)If+wv$%P2 z2vMtP9+PEyG;2V*cevJp0-u`X7PHZ#TR5n0-ugDN;TR8GkoOUYXarRf!8j%DZxSU4)8c4W zc$oT{u$YPqkSRYY@fh>{n;+9MAP{YebmBv92Ro1`Mp@7(XbVE~n~dM^-)JF9I4EyX zooZBeCx zs;^vr{ubC+))%0se&73zdY;ryn|`uY?#LO-rr~zB;g|CpMwjEF4%%4%j;r%~@w!ul z^N%4(DTGQII0GSUP60HMItWO;x%f?4I`@6e@-QecbA2B1Q}4x*C~r`%)fYXZYw;-^ zVNh}Tsh?7#y(lT`=A5snTb=up|L7BrdE6`B5vPA&1!!>c$eAxhW1sQla;H_(*6x8M@SSO~Bh-ykxh%S1m1qD}mj^HxTzm0Zbggl9RjdHmNpr2wtrF2{ZxfK^ynf=vPgf3( zNTEgiu#xIiNO?UB6Ss<>P3K|c1JLqENe!6mnrAosj%M4~{|9(wt-qW-+Ipzc8{syc`kXm*>glv?l`n zt?U~PyPos72s@7J6XYRAjcDi@%)G$n^75MIu)%xIJ^+$~-<8rpmTzZ&h z*Lk(fmLbHbYuS=yW`t`l5f1|+5wB!7!B(Y5CwjC|`pVw@Jx@>)1fDTO&UQ-H#5^0Y zMtp&MV`WL6@qY07O#GGqFAQ8G8iaClqfj23^E~NG-GZZe`T%~74V#2MY>NGg_JME- zCnk~g{ztZ?}{NFV23Q0)AMjY03>2xSTXWgsG$j6#TL9*^Uel`V9 zSmB$#edpaEdSp?wVCUcnN%(i~0@Ro6FecNw$)^Hj=;)l^zgnH`tWx!&ZJBH#<2m$* z9!OU>h&xUe%!S6}-q0qEyIi@k=rZn_#k!*lozYpe+9Sj7J3M_ybveEc@&$-w|o@ zqUePEnq>CEq)}Rm`WTCQ%S`GX@v;&7G&6g0*dW;V0mEQP+@O1p!)Swb`>kMY`#aap zTYbDi-cEm($tgqnFAX9^N>{e0>G*0}EGJgyaV-T(;7_MKNBNvRLf^_zcjWUwCTeAj&aP{(IAN2?@lQKdozEjJd0{WC zPt*AkFN{x{9fpYM#wDU;bl8T(Gi(4u)lYk5i3>2#$>(Lh3bf=baRF++l(d!3%MbT0yYpk`^ljkap&yoo|I?oSe!1H6 zziSoz%l7=QIC%eA)%E=SJrsv|yRWn@`loJfyu+%Qy_T0_>mL=`Q@4<|ww2~qXKJHo z{5nyHZgoPL2xAXX%$`XECf(Xsmj)KxEci%A!EP@&P3KwmKQ`p>8B>1}bntAqWWW3c{s!DbS7O%=cPO!G3 zy>UaGU$(0%XJC5~0HCvzM!?YXq~0r9wA`!b*Y8FQ9Aa8wP)D}v(~UL3&+}hvB!?9^ zN{|S#>K0e#c;j%hS+~qbiuQhwbXWKydhs<(oJNndPy`$vT`GrcOe0+|#1~;dCAq%t zwWQoguF557v^Adbl-i{146Y#k?3)snO~PSH1UE!Y!-U7xAiPF%)0v9NP*w;o{cCu< z`ON>fs%|^Hr!3b5hI4>KTtiNpw2AGvA11OEO0;5Y{#0 zTI-?IkDGxae&k)-v&7n*_cb;B#cXX6&kL@*-fNFa(z7wXIsN|^3Tr0X>J^j+v z%0U&%bR6rw7XSCCDoQx&>t)$wuWDZQuRhgb8$b-7D37{r9UDm^We%Jk1>E*_3Ztsg zPk&;N+MU|R9CQ`qF7Jm=LB4InD`^cmf`;)|?LAa=Y^E%ML$sL9zun)ZMV>JBtf-?C zY)`3Y-YPj%%xR9jz0buHz{dxwgSzs|274H!4$beex z|EE!Mn#jFhhfVC4c;CS@r$325n=5){cYEwm(Y;cH*Lr(s%dKzorMFli^%8y)XX^&L zY!=W;It$R{w}5HbfpL|2s|z2Q=x)Ac1PvzGbnreQd6(RJFFLb+U`9@^vJ+jAGlcC4 z;{2?ufg`RJY3Mu|unYbrtEiAH8gHy}=w5}=E_dZWeMGgKuo>3Z$kR6Wv65j^9UIH%O17j79Vv+=JX=Yz+aBtmJWb2>RX64B{V>P)5U&znxlOr@*H5cE zFjTLWIKR&d|C3hTwi*n8gM(oQUI9Cd?Cn0D1fB#&f3R6=5u0OZ#S4;t+vfA+2n5ya zMu0948)ZL#Jy36vMvf>zSbXVaT0y`t&pYhD#r^cPa1Cx7@r!PYMf$}^zOvjbdANG{ zW|^)xsm+SaH}VG7)se!?H54amR%!J}=d;mVR-6f8g`Zd}%e=F5qk&e%WqkuCR{c{N z%|h7b*^PL*nei&P{qK+?hBA)pgFlnSAu{sBPK@S~p&*(8#^dH7SfJmn55p(MqknBiqY^uYJQ4G-IB1`@b==Jh zUiEyIHP7knk=1a;1~w<_1kRpu#i}Hj22D%^4>=A_NC=MkCtBW8y^$U2M_#PhKwHMl zA(N5*WAAY%H4RLS80|qWv6WlMDTLM;%ch}qK~eUALLYpsjR~TRNJU-M} zM((9|mmdDOTz`74^L<5cIuGwyPz8qGLu1YZ)R31556cNrjQPE;Vm>u2lbRw>GXYC; zIgzlyZm5zs?__-{?^L6@M2L{2#j!M1nXLBkJ6FPQj%qWu!0>sNZe81lU0vr|#n@Z& zl1yK|=zN`w%fTh0yLtG!FIb0JG)oDMQMdKrEwwP~biH2~FpCq=wK?>aEs|0Vu>{IE z@WRsn!cCz7C3`JVkR9RBP5y3*r7-vIShq;5@u}aVw%I}9b-QoU)R8l}1mEp6-(#>K z7fn%vY%`0u#D-mG$g*|;)#G8`IV)n{TKENDQ=qc!bLbRqHzAcirY8!eDdF25P<(;- z%6rW{_}Mkdtz=Mcb!K9}P)SYWKhPrms_9qO^EM)R@HT(*He-6kLa*o?*=z=wb#H-$sE>fwt?loNUVWh4^4woE8P%*dG@oW|uevnks&ObZ zdyt%JcjBGK$3z5YLrd&#&N-v)ZF(q7omVtJPbR5A9P`bk*T2rs(}$=NmzcQ~h`lrU zCK)J7IXcV`uL>xA={r>NNZO1R*gumnjS4EzEER>@{uZ5n{_L3}KXkp2lwBFcaI~_% zWn{+@+fBa`bFeD*n=Vr8pagRd$%Yb7GX4)tNvgagV&A;y%{#&J3u1;3I7z(9rHF}ry zgJe<(2SVr{g5ijU&j6sN2@i|&$)&c#aH66O=fi`CklbRx?9-gTCk+j6rmFcs?q7nY zccoowk}0*P%P8-pp!^(PTgEptP1U7T)6NIm;Mf9d z(&9_B^VVeKv{qe{Fq8!^X&AQ}G&G`xP3hg@7L&ldquFPhxtxkINa&GFX5vTU^=DLF z7FD|UiFJ-ddLUKBovA!?yRVCf>8S4feK{#_l*>MWAI^#=F6CNVBz7Fnl^5@;noTEdE5rGh}!s@chXc1PJmm%%%tHkJx?975u6%6%}tWa98 z5p3ilrIFDtFsZt&|MKq7`;*gVuiX&^cFU5hQ5?d{q#CxIG$z>yOUW>%3%k+@?DnQS zqO1a*VIX!)ysW(5K+;MWxVmb3NmPO5qM_y|H!ooSnz6IEgX%W1Ov=}wZfJljxIM9G zO+YJEpo#UH+KA=mi-N5#t4(!Bh{w_(3Mw3(R$#Y`P%pMtrzOOEQH+aO&E%r6n3~tL;a%POU945qub;~JD zsEkZAi;E8_cK-a~eW(SQDX(08|QH90rjtEvy) zRv$uV1xRO8emT8S4_TR)m4YfQbs3rF3MPXy_0igylfKC{14bY|>K3d#YAn}bP&^+( zh~2kog6)}YCz8r z&N7=Gq1}sUWT`;m!v5TxO^wMr<@6c-=$gquZ>$Mn?xO=3u!Im(S%;lN&Hx%E#)r3R zEK!^1M{vLA=;ecUOph|(aI>s8Fdrrq&giqKGhg1Fl_@_!UO(IUyn1*=KQrpNepk4B z?{j#Ynyqr#^XBt(Lcfld6TT9*9{k{XbRfe6K~r)7nX`&g;v71ens_VQ&$FfK>vUXb zRz)Po4WY;CqgSP38mg*V`o|AQ3cbVn;jF1TCC5G<-{O+#a^HqBRag;-M@V>UjeB_U zpw`5XVSrao<)m1DlaEp4(bh?HfjnW3Pu~WL&PK2S)Y_a264i$wnn9~i1rus=I!Y7r z$k^y)NSv6?h&c7w>`8meXZ@?~93m|xba7L}4+gmfO{5}fBobL#E8J{9Wv6&;MyHYD zLde0*v+iaY^085gqwD-0jJHFsF|Uzm!2R3gE0x_W;6Be&U(NVJ9KDt!^= zOM#ldFxKRak>3p#F4P#lj`MY6+iGk^U19_M!Ym^9lONP1j$h@Zdd-G@YUNKW$zY_= z*Zrtap|kag(ZavkPt9p#m&qS=n3s~4d|dbne;U=<8IsHCpdw*OUYJock8?2sTspiqzL5K_}iudoFvQoN-WfX zeLW527P2HsW$dr8!J7pIu6&VM!cB*YWo2eEqS}bno!DpkL51KEC$e#c@Wo-kfCO$e z4hRNLz59Y?3s9hfx=FqU7w+$h`clvIOwxq zDQATqla%)qd-asTh|ZNf=)EEAD!s5zAddx2XFmS>J++t0=;ubumoGUal$8>Yam-Q7|BJMc$%Q|q!PajBh|^Yx@WsrPMtDqUWrXu$~Bbb%{=5I)<4q?0jX7iI^@65;=rb$iBY#teyj0kwmx17mXe^&)bC>9ug8S!ngcB8w zu8*IhpXyQXeRYGb^ciccJ3pOU{*9(CCCy;=kGBP&CUhl}Fv zvUQy4@-Uee14p?35dBtMjM&RBwy!>=73m) zFR{jpW69V+uanZD1ua;<4xRS{|I0paM4}O?UR~sKA|IjHw z)KBXXe%Tx!)iet`osY2fG?srev_km!OGOf!|ItRFVNViOkwQ7Vn2Mz+9!Dahqvv3j zDbZEXe_Cmn-u&#Fd6qbMbbO5~oEa*s3|T;0If#E8mB>%28-9#Wk`lodg8c`%C)vT* z#!^o48I!NnW zQbUY1OwPiIYG4nME! zq8TW!vdagpq830rGm2_s+#mbYN6L^(!iy&{X)wf6_5ou|ZXl|~p!8KpG|2MJao&k=2>ok#Ooxl;>hjBva+qXhYTm2QGC#JKwOhUwAwKe zB9VjzI^owePh!5WxG^lgF@W2L8gZ@mvS}QK0i`a*qd_W6^z2}@_(#HZjt#}~m8avQ z`^$PUg~9c!il-3!jRg&b&X5v7k)6h6;I?qys&1&&98=19n?_`6i?MBW8*WQ={c>0N z0PnQYt|$-H9r2ONU>~PX7Vj=aqa%Y-N zy0bxq?Du11a{Gu!1BYRi>C+WuGP7NVjTtoR49b3$33vU8w9iCuBJ88hu=gb`v>>w} zlPDo^duduR+jlxsQxeO{*&4W05igBUdPg-04$nfHj6kfMI%IJHaCRAb|y^I*Kp+*Yw#e0*Nuh6Jb5?HsJ^LzcA21PQfdd z037GX9h7X-Nw}XVIb|<8IbfJa?$Quf|EpCM@h)qR(3ec{49ED0)2 zUX|jFtbRp>X`;x(pNB4W`*NI@e$()LfpIfSpmE>gk&q>VcPt)0do=rxby22a=|I#T zLct(Yx~zetzDh}bu~D%>pf^;i8usD<_**|q07&?`RyRzKz<~Sj!hFwv(01A1GKK-8 zt(xD{NmVy=QXHP~S8sq<*bwH{_J8Wd4u|7^VL19@I~wUzPt#e&)Cdo$zxx@zgyzm@ ziD{8JT|J>`U%!1Vhnjuf(%~KYx{Lx51E>y_os!?D-o;u*o?-mM5D`m!#K!xY?97 zgpAL*kZTR4Z%|VhM|cVevtgLs9*Vj~n(eI<%ikmw!N@={FDm9F6p~ofmHM^as z4^?pmnerQturpq{$oDrbqJA1*g5?Qnf!?oXv0|FiUhL(PnhbRth5Uegma%ok=09O2 ztT*q>l(k+yMHp%Fpb_*-j})kRnSZKCe@Qu_x#Ho`%OF3X4Qd{R0~&UUINzAEx?g2X zkdE`t0&fleS=|2_m==2od<*_&ut1S1AR`@K;|pO5OJWNZ=x#c{9^uiy2&{7I7iiqI z&m6vLE+Fjd`YjCnVYV*db2~Jc4ucFMHV8+@@C%%dY?4;^nK`BspNTx?A=74o&RQzr zGsYqmpfPF|WLOvnY|G*#tx=1+^qH2TBpQ@j{liwHG9J$}hf`6QB=nQ@Guaf5M^5lX z*y?)X4LM)&YNA69CY_DAHR?l*8QEm9jOb>oT;{$Z(F8@CPJ6Ak0l2Y3wJFF6sVG^4V2= zjo3COWoqU<%acl1&>3SMZgMIY*TZZEfWL}#%^LFXlQCwGh5YH zo;s1a5=CSo*QC82Mu8l8V!p6Jhz?e=dJW_aM03k@nAKlsZ^pX`l;SJf*%uq`(%I~4 zGK1yc*1f~GwU_6=F3@1cE1J2PcpUzM$Nmiav7{96o@Y|g68r>3Z|2-sX2ey2-WS$I z6lIzlWwr18l=V!i{1y|0t?Y=i8sp;~tzfSM0#p4Oop)gzRgX$vAu8a(8)nxiD@`?~ z{VuHWSm_#j+o(fo`rrkaFwqiBM^XE(;|6-h)58K@ZbF#bLohrmEIQ<(Snf22%&4Vp zJ)<2;cYlHP1SM^x7m{+}T!;buT-*a^L*x4PV?DmVBe$I0*4(l0U3C}wwwSIrTOH^F z%}-jW3sBWa$5u7464O1K-G{LXXxF8r+SJUTFgSUqW2h<^c@!ky)F_qq0qbbxqmGk$ z18<+YEq^%z>E|#pi7?YSfydR)DA~ZQq4Cw4P_5_t7;LSPffy_;HPpOOBS4WnGcNm= zpWUtDqlLd;5$93s6n;gTeLzK3rYcxF3b$Y3T{cv~lZJ!#%6O+rgqO{5Xx?v=!2z$| zPhRZLK{<>I5ul=z7EfQp)y$==IVnD^a8Qt9s5n@7}K{;qr^AE|f(j##O&hxRHjLFfH8p!*r)0ho9cW^!OY-=SogZVF_4*QF9GG zu4pMBcgM{74FkZ(wN;6Yb%o^ zlgjEy6fPD8=pEur-11i<)?04FmuK@`N%l3xH0Dpnqm_hdhgm~egM3yNOmou!<5;=~ zqNA)neGG^8&-X78MXxeP_X5T~)d6;GQ(#*> zqDJsVDalsn)n1>KwC=;rT|Qq80pngb2J<~+pS(= z&*63G4tHw6KL>f#BQvl)BGmak>!4;BO)|0US5Ko|C?>78QnRZCN(OO--&*_S$QqR; zmS9_;q}Rwsc^;fZ8__JQM2b^>2F-;?GHwld*V#H-y(2<&C;8B=G0wNI>?H8YH0I#f zm$h=AsJ~zig*7kI4}VZ{=kT(ia=WqG{aVprT$Ks?05B@$>{Dfw$`SdpZ? zoZdX*X0Oays%clG?MJA&Y8ZdTr|Nw~)%1SnFhO*N>ONBKW?VeW@9NE{zgwL#mt?f> zYS{lIpO?z-M&Z%0BYi<|?9z_iHq$IF`9MP#I6$?BzTt?DoHQe{NU*^3BVZnzu9(_Y zbakG)F2`T3+Ruy{^J4mR{{B>JtkaXjpn>eh?kYsIzC@7z`?*3@E?Z*6{gIoE_Z`Fj zMq7qkFG+LYZa`(F^8pvFRhG;=bnh3hxFaM78thD zy|NMvnW3dWPLC?UA*^EV$ZcTAdy&b5h9?OHPt7qo#m9B+0nMfx_k~=|oG_iJ=(pP* zDgwrq@=4p(aV$^Yji!`AQ$Lj=Az;fr@xyODZth%1Iy1p?n($ND1=jK+QsR?eI-;r< zQ3B~G0TU!)e_Ajcz*UA~iCl_NgTP_ytcdn|@85S`k7#GZ~-i@GecSqW!Pqeu~*2dqSkR$uN? zE%1rKSqeHo!aYoso{odR;+@n!;xRPx`O5{f%+CB6S0aYJ@uzKWrnZhp7!6Bv!D*?h z1?OwSrTvNTiMUE5UmyO;6o}0(g>|_>Z`hs)8yf*YglMm=`gs78xXqDBq&&Qbq0;`W z;F9h)UgKofRm6~Kh%5Qe6&Y-x9NC`V;~qm_^mgoLRRrULthshu`L#yqBEUz756Ae) z0y|6xiwq$5IDRs}N!&!x;zBEN?+@4_cOv+G!}TJ46KP>w>d%_ECJRkEikw?8TUfCT zj%fYb|0=SC=v?jTI|MZ8XEd2^#N4{=N5L?N$9y;uUlnKdZvIfM^z{#PJk+dN7}?#LvN8Y8;SzqN*LoPp zBfoeOoXw#QFLZ>pQxykK?J_%#0d3|Z*LI;ANHe# zFZ+CBSvV<&c#2+B1dO#3mOM&^n<}46+pZ$k_^(n>{1##pQ`l`_9n%=9l|EC_;id_F z@M_ER))M#`hY-tQ63%+@bNV;*<8sopzI57xrq;2Ygr@|=hFXZ{8U(8B7}gLNUG*C) za@hLHt#zDeSrg@~cveC|vnH6BBoWEXY^7x)?>7n0$=)5QPN4j7*1k)S(A3vsz--8i zaV8=_Q!-H2$ysW=(6QdCwI2+{{Z#7KC8NW|4iABM#piLDU~$6!iUF9Dn*nvp^Gt`A zrMJYS_kJk0>4pz-8Z)JYWAMbj)?E1TF51TmI`w1(!)T1$I+kl2Mg1v}NF~XsA7hB; z^Kwgd?}P-OS%o)bronVePnUK6CE?@Vl$^f#bonYJ8Bx0@yqaPM%K=YbuM;lOJO>Bm z)UalM^Vo*~m>d*t2T_^$dcP5IG?%=xcAn#}$ZIXe304>p=Vfc*AQJw_j?2Eug2)rU z)sW1#%^mcV%)aR{y@BGnuOFO+E3w3ejf;LHj#OZzyT|hs@MXs;+*TT(xwMwAmOC=; zIRXc68Q^O_pvY6PE!ofvLk+9>+QXx7k=~LlUNf@z*)tMRIl49W1TEHk?HQ%+jH_gM z@<2@1a8Njsn2?aff}I#_eyamhRh!1lEH25`%MwxO67_#=zrs3oM~3_GP)hsGL>x?UN(Uh?I*)J3+E^FF+$)6zPOd| zPf`6JE-Ca-*7;uyl>FZ-NYYVkOO;S9Gfujd+Sj34a;6d;-PJm52&Tb;qLudmro5rFAA#3OTeyYy+H>0m1+rMLHHqjN;^skZY(jk2 zbs6$k<6K{(G7~ToSOY{bJ5$QbuHw}VT%HS;eK!5G(fEB=bB#LSa;K~5TQ08SnC66!zyPivOWMV**)NwRm2>Y5xLcQ6`#`xyir#6S zC$V9d7+}1{?l||4H~%N3SDRauSC=H9lvnnR@{0}!y_w7+Lk%a#Oab=qb$J2T`OGpY z6y9TBOuD%pjvagh-0Zoy3qFH9;K8`QNN04S*#w-43%7D`;P>T+nuS9FPb_F zzR5*bO_9{8x1#P6g5n!W{v$1nBcz5hV-Q-?)r{L74VwF}U-{%BYm>D&2#but!3H{I z#35JnS(kSlU3duygeC;rI&ANIYqmafNizH>-$!D#WXeL4cCTRyAlI4+3X|L$4pV(j z+XeuSlYoD|-NxEPjovWS04mp=H(|bv-%HlPu ziR0B=q$ycZf!bwvNO;wPVh+eyze4Dp9G`B)bS0bIG^?8;N%T|HO}i(>?3d^IG6MZG z+R4kzk&3GqVyf*?+zx6TyuE0Z%WIT&sM=IS(LV->^$ymdQl3 zZ~WZb-OgrJz7429Z+&_W_u4Eekdkrg`{UYCgHJd21=)1)4o(bK*%>jy*APQpsu@hv$sEt+Ljl8gGq^?Qx>HH-@{qja(eaG)_YXcwJc z{L`H3XQ;N@o`E{m!7+)G$kLx!ts#B9+=nyZD9}VgnW3DTy~T1n`+DUqlg$4+wxYB` zZe=|DqcJ;BY~@Q0O_3s?t`p)vFXE-VrIf;mXvJ1D=v5PEQPisTxq!Zyvu|~2HO9cL zM#$w64{ETQZjV-MBk`p;oXCyUV;D^w%HM?A0i8s`N1fwsTC3T=8!DJB*vqk3a5EFLElq`4>AhFV;y_4$kjv(^C@@55T*iUdRhzYC`IeXw zF&VY412pBWhM$hPOF2;bGQ?{gqCi^WV=V>>zi8YJIgQL(y_P-YGF)Ul{1fM#b+! zzVL7LPa$v6c`kmkJ7Ba!v>&LV_s0gbfeH^W)Dd9#}H9fX0BlaR6i&3%Ywz;XQy^rqwi9N=MWb@51 zPf~@>R4)q?H8CN)gUv+TLYRVr?pvqcPD01_`>g+pa zt=o*G9bolU%yqg}%3tBvRVmuTxY7p&t{Ft z*KR>@Nx(R~ec}HqPYu-cRg8Mhcyf>N?w~t~7TtgCS#vBrYo=5a@ogY<}!`5%M5Q zw3?61*xcFXb_}7nw4s*P6=LH|!rp$Yq+L1lgm!$3qwGSeyVK>u#q}SVK0D*>6AsqBoJd6ep9zdLWBa(DnD zr*uTXIQgtH7>v~#tG*9&h7OG`LQ$Fj8K?WfDrY>{YV;;{9`NYipdB8U^z2Ai?r5#T+AWPwgT`G?Ddf$yzCJp9Vs z>Dc5%6!wVT#3rrC==kWy(4LT@KZ1n~Ugezt>c;HXU{% zi#KoxxX23{(E{JsaESKWcY8-U61@vAt(cw(*&K57#N^>qgKwzzUc|0wK{Zb1h zEush(vIw*e1_SLt|L{fsFzK)`ah2il@}kWSydKyxwAZK3;vTzcxtd1m_$0j31!1l` zJ*8CJu~pEnrN!^%7(t?Ukof^bps2)W>+(1_!cczN9WB+MhGB8_kAZp&Lfa@1+n+rP z>do#lJo;?HNGQl#E`^z(X3J8K)99$()h7Mk!G=GHfJBQc4F+;)Gav@b*Ep$>FP=p8 zdH@Wwfu4)0P#w)o`4n}^`Mca}d*G1f@M1*mHrqI^uSJ<|EC$>V_o5Zy{$iW?nej@a z5=90?;sUSLXB{}e7g%pKHW`48ZgUb@(b$e50IYX;2Wfl9W4L8y)xVHb4i28KO*Pw} z9#^dBejRUgaaK<`D~&q+Ne_9bwxZl>{vtiQHbwRqrhPCjlJFH@nl)%1HL0i&_gr%@ zT57Xd3YY)$h&vzNOP&p%Tc^kxM;85Lqgel*Y$#8|;tz@{Ct25lz2ubWQL6^G$Z6#jlOY_G`kA^=lg#cj*}xk-lWmAm!(JLQ?7 z4{jYwHV!-U59-3%7xDeVN(mv&l}ij&r(GY)5Zm3C<-5{;uo@YZ`jf{KiwH!#iP2V;iY`u`j#T~xwF0=2l@c!coRgBXC-2+A3WUk+zX+KA zEB&#v@dKHPqR|Y))#+2P=#ZH9e^A4r7Z56a=cEoLWWZUpGW;}+-8O_a1E7TUMQU6a z=Ijc(8rG!i18=xsp^6HjN9tnlQ)of19rNK|aQ`zYQlh}ouu~E(YwoeXUeq`xJxOh~OYaR~Y z57}77{o$uiq?ojgi$nc^7uj*xDwH9;br5Usqmh5Aa3pG^uaWQww;OPI@nz%nsx_-y zR3}pAeuhS0qijUL!^Sg%e>^BSBTRH0DPYtY4_r+H&b-wt@D(`u{&CFekIEgvBR$%x zauudZ3P>aS+4v_lh0Rbt2YmjoHU}4NT=GdHx+Q8D|8MYEYHUb@_R6O~$z_qv+8!?9 zW=H3Sq`J{irr~vzF|FWM>=DoPzc5NDpe=2Fs}wn-YkS4Ev%AQ4cI_{?QtT8plpkcl z$sDS*gB6L;Guid(T1a(Hz7vUPmsZO1o3I_{a2M|C^@vh0w*zFWkFW9PHB&5Z36V#Vs0Ib{1D``l?JJV33QSTTaac)sSzmFb=t4K4 ziaTa&|HIT-uI1XqTE};C{!r?Rj|`s`OjAFwp;4Z#I`KO!O*`c9uBkLR5tIh-#E>~+ z=B7n18c`MhV7L)dvoVHc8L*&u4M`{9M~7Yf=e##S4v&rlr|E zz@$4GN(TK37K2V{iN^5ez))mrcrdhd4_P*?RIb58U8;f5;< z=bHb-!<4TFcqpaUxHsjf?=BmuCuE(2QTrTonBvaEdE3T->JSwaE2$F^KadHo5Wm_&9KE?Me@|Di_NnHd8dVi;@-lHaGwk(3?bk;^xR zi_vS+8$N*LEg{-x4F(V2Pvo_4wkI&_^Z@iT*e}L*{MNV-j@)FuARIcx8#Wn7(4Wo! zW&I&*zn?MIU0Og*Kcoh+Q6@K;4c#9Bj;Z_+FXscP67C;q>pz#z(6mtRCHGT!XNHPK zZrC!wPn5i?ozeCpFoiwi5}D7>X(@qT7;y75`jzfV1R9uMO)lLEdG-OVa*=}E z_eDF?Ne)}jh0n*gWDZ0w6%`Wa(OYA7)dc@hYjO2j$skOb)?V{Xnm?&wK|NBx73aG%uk6HNZT4h_*I;G(AL zP4Ckb*MMnEh$LGND!8HcJ;k#sP@cDGGA8*JN^igHuVfXqZI8}#;4TZpaA0&ZNKu|@ zOk$9|!E#yQ3nJ3P@f{8v6kWYoNe8sSV@nMMh!Dn`rVVwWKTd<%HrIGa8&GZ#OFwUvSc$NmscWDYaNDpQNZis1&+@ zM?znIIFi8%fd!&H3=hADkro*qjv#r-hZcft#{s=sx-r)Vc3 zlJ+}vXLfPdm}t?DW{LurUl2;Kcb-8(n5`zyXV&@+yL*MsKzE&a;y;ZQ+yjb#lwQ~H z_OcQMPNO|apsfA`Jpp^uaTORm#Indo{0_uUC5bLbGWl*Tt}`fr;bq{Vu^D!6wb9t=#W%Ip_VYXpbT8rR z^IUK^bvRfeDqyIq@au)&&+yxUwTDv#$c5FAIZ~lB^-KLmQ=otqrF!;j?LOmk3YSHh zvY_PHj;pWv>MDecQoXG&CoDJU9D8W-fX#%F{DC8ZmGRNibk*1C>AQ8HMc4CsPZPy? z=6@sat)t@Fmc3CdK@uR1JE0*2cX#O~cyM=jmjHnP!5eocxI-Yg26uONry*#tB(Jmg z+4r1epZkq_#{0(m#(VEC#$xrFYtC7tm|~zl2kjOJ&#llp}RU{QX-z zDbTPHLD(fs63_#DB<%f}rxhP2iRvE&CUCFMp!N0|YTl&=i#GgIR+?PPq`5Y*y`9@4 zwAXfwFw8c-Z<3oDc$v{dG(y#+{)Db6y`_&g5@-lKbpgxrg-*!FxH`;oRuo(=1b#~H z^!G!ih;@Y4JIjj#3?+45K5`T`$h)MIZ^Clvw%P%fA<>XLg@Z#+YK#S7!rx!qh7c597ETvsygT1O`Kmg85aNqnYwWlI8yBXV()cvwZ-{j}qL zevfV?%Tf2aSV^D@-RA5&)6%qy4Z$*VR64n_$<3L&14%P6@`l7T}^jyApOJ+;8faTLWdMh%b#bVPm zH|yMBJRPfWQMPo%oM5jD2Hwnw&FJ@A6W2S z%uo}z*ZhFXC>O@4B2x%rZ1>jE{nluk`5gqfkOJ16US+V`>rA8x8pPa5*lU*_aqaHF ziUihF@LdWBkg@nE_7OtxEfG7yqeAVQ#i_UMqo#hqsVM8Nw;uER3mw!_-%mK~4pPOIGIR$)Q-{ zi_Ws$+)Fi3_jg4*Ju==vyrH%uU-{}e(Vv1RU#WfKF}4`|+8pDIv5GCgVvV|N=Zmo%f#Pr5 zD26oY?#R0OF!_!@+a$w;?sV=pLdu?A->v&c$GN$3qSo>!lnHZq5W zfGO=Yr%mmG9;?bV4nwL5*2R27{LtXQf%dtYBX#8?Md;5guURk5)%BkDG`^=^VT`8R zQ{zl@Y&fQ&w=L}>Y3)|0D-6)BK*3oVPo)Qd(NN2LlOfCANUM|?;DXkRuADHn;rHQ` zA?xzWIHC{7eCj(pZV5_G&eW`|7tuMQh&Db@p^YOE5QJ}NaH78YQMT*6y30FnDF5nG zdX3$iilet(ZEjZsc!xw*!p*rP)v=~4Rh6o*^X;l-3P*-h1|1OLaU*`fQDT4IIs|^V zl+*Jew+QX=Pbiwu`runqlM%p2U!kf2Z46h)%R{qQ7Y zscDYAM>EG9wZ<*Y-8TkpgHw{E25j;(`;fGgGhzO2(H=Hy$+k{ceZbgLqE2_>4~X@YV$aj;l>EWZaXuia&*ji-AKv@Vp`&~3 zd>(D8oYF6-P-QHCVj4Jg(3e$aTb|}&iT~`Zb*pzleym>DVK%`*klXRASO#?;uWvp= zjEYaV%gcN{vYR%qrj> zjL&82JUuG;#(8J8qqI0)r=cs9?s3<?PYDf)6HvG9FzO|8^iFjqD!Ntvf*njJ;_~mW?!;2p?e{0+M z@3DWsj5lwJqBr#jAd_} zNQn^{3#MQZq_{{_c9-TRC?tF0UpE*w#av)fo&yUCw80*v_I7KgJLh^M>O+EaCWVJ( zVLH=t2jr}d&d@`&vGD`dYD1#lRqK+B7`sbHXN-JRegeycI_c!FcF_S-sLKjrJ1cHj z4Rn8oW$MTyS66d?jd}@R+ipYjVKt*7P3^wE;JZuK+k7Ie1v+h#0j+z+k#QD*?%o}^ zy*CJyRrsZ*V-g8DMMGk$Z!z=b6j$p{9T}d*q&OsJ;V+V&v0|tlN{?zbzGRktPxX4x zIfmf7s|b>>$yY=_JPe|#*~k)}!o!SJvtfkq4}Y_)pCVWT zKg>vl1`<)7i;Bt#ncJ_mIOGh`R39dHf-i?I`P1o5-x%-bNhMM&^jSd^t79~odAXnW zHG7y=8$E24ytsjz?L28iudP?wC>Cg>wOkQ)T$GdHJ`&)G_)s*EtS;P z3~WLBUlrVNrxB{1EH*439222e@Em;~-gJyyIBZDafHyxNxD8SjI^!%M9EG~G;y)=S zmq;j7b0g^_5}!=8ZgjG)3*+{Uowh8K!Rz(+Eb)55NDqi$!;s8qBL1Y}j)y7`!tRUS zTu%BGfr0#FC`n!C^_3TeL!0@VLvoeHh}JafaFeHw>d^`D?#pLYj*2$V_JOw6d~;!< zIM}#P7um=d>-h$${9h{M>1#(mOBeXSW4y18Ynf3!q11@<;VXqXf87hJ!Nt?zxmcUo zrp$U5H5@-xI#gI&gyU5{m;)2Z;Aj70m!e2ukm&rPpD&_ zv<(WNY-hf1YFh!g!TgNB@jmRVd;t*C6p{4@J||THPcPHa6;ZaU0%U&wNa~~go#Dm% zK)U6r&tnatz8)}(l>4VN!r_#sVrF^MdIt=E1k9q>ADv^WZ{{%3i59F0Ja>EiO$FRJ zffo;6$PM1}^0@Vx0XVt*bGCoY24WehJjc3L^Rp4nX!fhlyf2_<5)#f0Vg;<_c^T8J#7Vn!(Fxz(@#Z z5_B2vZF^)$Bgf_-S^ulC9+;yxhgBBVJ!b+N!42d4JExGGf3ww0Tr%e$FJNeBjU3v# zB9}sVawBr9kVaG8g8B5&V<3FJ+S2WnB0fn>yxT`-6lmKIIP#>DkY+X$1RON@c^q)t zpJaEvrM}0MRJgdIfdu^&bHD6BSSqJ>PAh|TGZ8kX)ewd@uYaHIbIUho7cb+&(rXLC zXUxR8Ep+R)ZoDd{6WPJTF|!6|jfs+;oE}pEni%8!1nut%^nxlaCZ7 z+@^}dy`!NG+(3DixClZBHSkD_lNF9N)`RY#Bb<7nL;3{*z$2q{pYAebWFzXW^-IOC zPcUK{5^77Wjp;epfqH38{pOQr>WkEhb|!c1UwII83YJTpktuNRF9|zd2kT>KVy$?( zca-ax3hnZX?}lg5Yyo$0v`bdFPT~U6Qe>+V4aupKze*Ws^d$6?^r$?Q3qw-Z`rG0m z zRp+xYNtndvOT0yzkZ6me7gk-$++EbCgBx##w73b4FV|RKHx6rDtq9ds)=ME20)0!0 z3E5LP;ZP^iTPZ@SX~)N&$UXV88wg7kW5Bl8#7CO4+irAH848|@RB24T>}+=!T$^JL zCEPZ=Q$$2^<|OKk-$6ul;BiL9?I`+%O@6ru(;YNZ@P9@#tJKQyuziVD?QgLeV zf-0hU?Cm}MXHrk1NVK9fCyRC`%r8BM-99=;?WV7nX7nJ_WSw#Scdtbcn-`R_Vm_{y zUJ<^LSAa$HS*iI!jys?l!vt6Exu{{kXim?<{soy`-19Tw6}yO zsN{;TFJ2ukeYucdExFYDaE<+sRlV*XbCA3XdzUJ#wicY~cBP(kh5Rw|)ubn;>gu46 zgqQ!TY2}BBySfK~srr&u{35}CbD_9#&x&j1bM|E{p`5JUsG0hW-HcY%{Z`TAmob-_ z?`Pbrv;Lo7CB5h+Y(lR-fxX^Qxs|{AuJ_w6&=K4bj-uu+MHT*N!tML` zA+s9Axw+MEZ`mgHBql>eenyu{cXYQ^Yejy3j`J%IBn;z^k2}0#feQ+&hyPCSZ|F&{ z|Nj-5{r`hA{|~IPvR*Ch?3c6u-H*BdSlJ1ScAZFy&Yk4|&mn<2fs_pq0H>$gE`7Vt z4l%8VX&}|Gsvsiy7=ys+URrTylt%!^qkifvMG%ts78GWBMF^z&3yPkg18k}MHz}qm z=T1GmOMp9R{CuqvOsl6uJ4ZQ8V!tV?;6BNq1I!vS*oolk2@D5EiiOH-9m2xdD51fQ zq`k0CgVv6;BAcY`^JKFVQaSjzs~z$QcAu6#%nT7Z!~#;w;qc@c z-&YnmMVyu2RI6Xk%zwR*;ngXAwiKneYIr(f`?*58JYw$G_^w0Z*^eywvc#7s6P>1xQcen@7o_Byp>oefNO^ z>>aK+L`0B~-hQV8t|xhxbP5{5@8W>z#0bUVaF9SSQthPmI>QmZem_%+#(TFjxr`OQ#cw18wrSbua0f)~h*;W0Gi8KvJ)tR_n~GB9Op)kTSXo&J4}zM;H``X)&cS1c6K%xb`1# zH2#l?|B#=>G~8rY=WRi{g0F|rPbTm_A3h_0K7kKp?#4puCrx|&EgsyLyvuW92q3o$ zsn3f^V8O|TxmIFw*>V&B7_BfveEU~={)5ul40l?u_Qh+qghWX zwJ3KvzakYWNZ z7FY>B6|hi;PpAk@6s%W=IXog9%A0+N)^BwF{bfJjtT7Z;NfK_`Wlv)SWu0Gi8P*z} zRkNz|Kkd_U?V_cLf8X$Ehniw@d1R>f^XgYNW+vp>?PwNrY`c+Wg_xnD5{m-V3^Asi z&iXJP$4x{BGkSbQ0iIgSuA%3fMa^bAk@XiLD@SbYQ0;7Y8{+;Yd;4_ZK(p!Su($|~ zsAze{F0=iT84(xf1~$nU-C5DkMLr^AAIO@3TO!=gFllaz!orxJzV9|;*T1nR-C7ac zAUq+(e$(Wp&T)tUD@o7KFk-QTget(2_^s9ajr54R;wZj7k%(+Go9#02z%@S3$OUD= zi9UD&H-=}(k#;nlf0xJS)rPh*wl2zHy@r}zmJ>yFIPL~V8E1-PQz-Z{Bhgy^zFLaZ zIq%ipe&SnAyufG7?8Y|FsnnbQI$5&OU!M_AamBK)Cb$eG>{MLr+M29F8FVPEwXWk9 zg3g&$o1pYk549Z*6*aES_TpkqEzg|RRb7}yXC5_YJeoy{Q3-3_|H)eO*&S@5!FC_c zU`gI@_J^_z$hC+ka3X$_U7;Z5vZb&=xSRJoFynkK_2p(XQQKVbvk|~!w9DqJM>?~$ zjR$E5X&d$h^#QT!RPJtX2oJn$ZqS$YFfT5>uagh>Y#Sj%jUg@c5$Z&xkO1$V+#|8^ ziObo_iWPl1Q;6MMEwtt1J;}1-S3F+tVBp5{=M=y%ySlM$yOoU$O>u7J+IcfhOw+{$ z>c|doG58c+l@RI**U-Z-=VB(T#mI3ap=Ui3{jC43n*Yi3NkfyI$ks<2`@wNve8vw2AC z8G65t_*pMaRsN0LItgQuO~Vg3hDAkuXnC4_Ox3!<8D(`Falvkgi*><()N=ESDLc9Q zR@2m+>{$seIWa_KfI56yqf<|Hr6Rcbf=lFN+^#tN`TJZdMTf8_8C3Gsv?bIC>5`%> za47NoG!O`Ih)bAhYg!l`pp4PXzB5rUf@3wMn8@JT$n0%k%VQSaZr-y3rOH~YR_EgD zOM0|`(z|Vp&Ir$Njy@ePZQ>HAKD_Yvf-E$VPYvGbEiC{ zdC##&Ji9#oD1p;ir=gT!LBni#==LR9L*w!E$#BuhhCK~yT^yx=6I&8?K}ku;h{3kB zfmJA;WN|R-AhA8HLT6*6hZ2qLnJq|hKP-R)+HEhpSTKE3beRi7 zda2__rB58&8<^;A7;iK^RJEHLGHau2R|r*8YuU*l(UR+%hBN^6zlS4~m{I{oA<&QC zU=bVF{8+YESjk*DG^Q-^A|h_ja+tu}TN9x;%kJp)KV5w!hVU#Qu5b|m6n=tS=mfrl z4S$XnFzP=#LjGPy>=$YKw+k^1ZrRn{OYk%7_H3`A&m;?MgLSFXw@YV z210D->f;7Lx~eKYF!vEZO&IRqB!EsXzV|b~r-ItoQCYDe&4jX#;hw>?p_SkFV!WdP z#X~HlsdT%E6XbSC1dN5B7ZIHIr*SS!-C(7c1q?U>OU&n!=&iki)zT}yzV}X_03yUBx|`C$gNqH)VX7+YVcvl7@rl6JaK$A@+PNaQ#0>ari4~bX62J2 zcR*14OP=cely9M~LSYSBy~AK#ji4{}Hp9heS5gFtj&=qW&CmmFSZh)tqb4J@9$@R^ zmP=^#Rp5R~%|u~}P3fD16LqF9=i%>1+-E7haQc8^T4BZy(3kP$vd%1586(I5#y3c*a^!A%qWQ)1fw!U!u?OU6N2f0rh|C5S zSkoh`tMvi4bVg;yfoyW`Szr28MRj?)WOl?6Zkl6vwq5rxox_~l(#%$^&d&gvwdTId%veVY^uGyUPeiXL-OqGBa@e3Q9T=a zxDs9Hrd*fX_&RPNM{{?S2#E+M>YGD%pt%fg;Na|adpUn(*YpwUz1mi*9q&!ERj+^T zUPT(?oNv7u{rVW+8e2Q%DnbUS={8W-L-U4@9eaIIZP}9n3pmBu<`^6 zQ}K@_r-|l|w4Q82g?4!FVSqv_o!M`>{?G^1LV7W=&IHrY?Dd?AP$(;-&sUTC=}ItWLqa~<0*}sDrpaD1k zuDY(KJc2p$kt^%1fKb^be=3ZM)*=Wt6WZFVxCwMv6SrmEhjWuKU_PvZ^cZe@A*cH1 zAneD>(RFq<$Ez$v^; z*#pAfN{Yd093>SLvy$_KwoQ6~VqZ3SBjb{||E9a(lHe2TC56<`(Q0gU^d6dCEDQ>N zN=vjc(-(P3Hl2bwB0`N|6^bWYM8Nzp@znf?xCU7NhiRcCqj+(NIo&hjC#E_q6A+e< zc40mG>47|R~Mzs7uev^1MK5hnRt#;Gv;?o{C{aU&#W4RU^p1&r! zI=|W3m4dJgp4QRAo5|k@=n`0dcDl+E87Z$q05p}3QI-qJ@Ohic=E>u& zusRYeiTgxj3w>&1qJ+=xv$b7rxfC=}o-+v{Stxns+$){k5I)_0fM-2mh0Wqq5I)+2 zYUlaVKCA}pmO70oYLQtC%$e>Qm*tFR z>PhAo#UAV7#*tMpBwaDS9WECQEu4p2Oi5BxqQkq~6k`@Sf8T7Q~^7&E<}COU)O(79(1a znSv;n5#ku))lX_oHwB+-C~PeFgSz?}JeQ-YH<>Jm%{l{O#3Ap5iS}}of@N`8G z=Sye^au4kyI82%Sb=NS&HXxA(-k46F3Plq$m))3!6m_)2g3`GL4t$ z$^9jm=)arA(Rt|cbC>|!C<^lt;MNiP*}}P5^;Z?j;T)aUS6<-=z1uB^sg2@e2&RQ1 z-miu?EV3rz2J33NtI@i%z#bLNw-3pLhez+K4ypai^80HG9i15O#GK*WTqp3gVc}>9 znly6st1*}pZ(1CF@G&NV$1Tmjh2s46{GaQ`jcUlaBZodd(;QISwVEbAJ~A>bwVDa6 zLiOGd2u8JUO{%v2IwzZ_`iUMsnxQPo^u5}7y>lVLPM)z8c6xFA=p$g58Sq4lV!ga; zFZh~r@W%Y$km?)KfhZbhhxaWDDm+sU;n7w@RXLCNH%$uh3pI2aq3Gh{t% ze(qg1?*_ZauIxdIzW81cGy7XJ5%818{FK_%eFXkH{b$US`KQY===700)LJVnVo^tcko(rIp?+`!WNWBQ3Fj}s!1!3Ji_qi- z?*HU!-B~Xt$3cI=J>d62ZBn6=2f`U}@X%arEYp;zwyE{-WyHO&X&^>yPh(PQ1hAm@ z{3sra6+nwci(7eFxUX`fY$-0#Y4wcK5 zp1jCK^hcP4DlAk%$u#VIhPoIO^xkF9N^|p>< zf-5xWwZ7M<>WZUq%K~&(xDqaGq&k+#FxYToJn+^BNa6UMb3P>R0xQaS47})Nl98WU zwi7pGx*HgjnVN2<@vcnXmSqf{ELVNdSgK+w+}7ypuJU5pNkbqV4B@m1on;LOrPd8m zVzvOlq4yObgfzT5^-_L*{{zk%7Nd9y0=bh_5dkNE6CyC%&bexYYe76%e{l)sz-|Ke z(yL_#A_v=5yS_|um5TesRr8_xv19A@=}|RVSAQ}e+h|mBB9h;bwVTlTRK^6?BufU0 z6JYp#t$3v?ayNMC{0CgN>o}g(WM<^$JC~hrhAh3QRE|Z#JOxf`?O#4=@2)E=<6mM( zv~@in=s&ntLr{rfcRNP~x!18#DOfotd~Q;ZE|zSi4A#%?oxptBQkcMYf;{M1(rhQ& zT6n)D&rMI#=(Wka&&37)0q3ZR&(U2*Y|V|V@p?&DE^A)4f59C?=M#{Q0of`$T)Y4* z_EFFOD3AlR%~2DiKc_m`$)v^yzWT(U=m2>GYhUv+q|x~i+a|2*L8B7|E>oC<-TK-2 zQ*vC~r!+jG3cx_%fW368)Kpt2OHX~_Hx{Ftr-~3p2Su}Jme$#W<-F2ZpwyGdy{veL zJI}+$9j|o%LkZELU~70ZMPUjQr5I&q946SOy*csTrVPGlsEbw8%{DY)^Aipz6T5+- z)M?k*S$q*cKYk%RZs>??J0$-@d{|pXQH~TF_;Z6CHbM`Dd}@GB;7k`e!pehmRVB^< zeLYil5rbwB`TCI0n6aQ)elVGq62s}WjO6gr2?IX&CrC)KiFv1Lbc1#sB2^Hy8|?!f zxYIZj=gy(GMdFIKdy{W#2>Z5OmB95WdFHfk<2rmNrPqY( z^Eu3GsJD1wh=m_$oJvBtfwk|W#JoF|_-S_@;sCb0Hw7uug9BVPcb7M8QzJHfc}t72+X_G08g;=h!PY zS-D(>9oDQf@6Ny-$dj0tm9(WzS1l_NYt?;SblOUZgHB0HHB%CNK*n)yIV{L~l0v=! zy@Bp`e!cG-DunAR%3o=7kCY~q^MGtE80G>`ESC6RP*_p2V1w#RrW+WCMu(dyCfstP zZ8R;+2m4~~v(0jyE1W~|!*w%*l7gT+ABH`;&Q%r;1l+^URjzfas;6WjcKCdqYuuiW z5zLlY@_Zjjw+f#!6BGpy2^y4tbbBNlpxQ*kCxwq1;~s%`M-~BZfvI$prgG=tn8vtt zfo<4$%omR{vu81?`Sr{$u;N7pLrjdaI%$2g>A7sS9VL*yIw>;LZYE6vx-}t+P(Y}GdXRr9Zvw8Y{ZQ13V_=wiK=xc);2sg{dlK`@u{B)Nt@Y@GAFHqh=LRqS`6+G z%L$7wOjP3;LKK&~11m$SdZNM^>%Tq;lHXes(cl_3Eyg%;oVIx@>zoqIIzgK;7_nFf zIwI%<#nJeof%h+eQJ28z3h=U@g`|OpPm&UpgX=*G7BGLX%@lT-{tJLxCo-*wfFDS^ z=${^?|6Vow$DMzZoBYcg|9$}pjulUC>A@IntF#_EQN-8JVWbITLx9V6|4IX?&wEY_ zb4dXH{@6d})Np`w8w*%^Cmd%5Ji-C5CL z`iLEMkW@^Fsofq1iG-!k{Wddt~O1AG)iLXc)ob?sAG9D9CEF{H(QcVT2pB-r8KU2~=zv5&u zUg^d_OZ#qLkE&nNbqhMw{=zM1t8ABdconyM?~rg;CLAxH-;U@qJG~+`bM$iLdV~H- z;~hIx3! zD>a3FeTUq1hF*2Nd*4*R#uQd=$*Ljw8Du*9-J0R#KgMW)-x}%+2Z3BwXN9*&i^)HK z?k3Jm5$_Rk<(G@ zKL5B;II_I~zEXWhvm*H&`M>Bk&!7u-0P};<04<0$c+r$|Q9K=ue;+)j>UmIL3|KwC%-xhBkX&g92HPWoD zf7$#Y{r?**{J)vN|I;t50l&qw;dNOhn`h}RbJ8TclIZ!yI@#c#I}@MvZ|JQvMJCun z{fxPC<{izgAh4E37$peBIzVw-rb*8hzFm)^yxB ze;)*xh}(Izgt$MmOa<9B=LSNjv6xmwuxP~6kq`{*2P8#FFgf>e6ks?PydFWn)T$Fq2|1Std5kRcXmO z%?~(&R%y%@f&b!io%;XHLi+y@hyOeB{<|~e|Iqa6h)ASg)SNC#rj=pGM z$kRu#rHrB5Io7l9Db<#4UiC|i+yaMZ(BcFknaqE6?STLD>@0{;0Ajqf5K9hI2^1bI zO4@1>rM~iYKTJNP78ZDW`@R+6Rv?2A3g_zj2=Mw>_s>6lXA0`fd}d5b6ZncMEnx(( zY!iDsJ5_1^n|(+Y1}S0bZA!nZNG||( zv;nYsHy;B5&Sm<}aL=~Bz)(HAA|m1rq@5w~@B?oD4XilI?~h!!bNql?x)M;t^V=_}KOPTmKm7Bj zjPG73KLE)`L}88pPC-g`tvCld!Mj-7A$P3Wk?;V$|nE)G$NSzpiWctikw=WuBZzT5{hUF2s;f`snhs#B2PBXQj_BP3! zaM@=)N9x$%KMbigx62792&jHwS7nCAWR*s$ujLEm>+SzVJ=%R*8X-M4D({jh-^Ngc>?uk;-RFviv8u?KK z;yevx%VWTToUIc)^wcg6Md!R`j^+5gXZyEx@PQGRmpKdhf~p658VzUHDpPh6mT?Sk zh7!d_}v9-nSZ*H~ZyuN2XXc%I1pYmB`=>B!A`)(3#^{Se}Z_ zdvUY=rPkc5rO%143=-0mTfse>9_P`bnZ5y}G^f-rC-~M9F~u0JsZ~bA>AAekU#l0B z4DZpTCl}6cmsbnzkm&Ku%;PE9CzisWR^ys}>|<-9$Da6>5mru^WQb&EX(v4*%aJG6 z8kJ|#i%bJwx8;*1ZVriyDY7>+1>B|rMZd9VRcj}d1gpDZs9^L35#`K~P1rrW`J1#l zeyqOFLnfMPsvu4ucs{ieC^%X!o!nw!$I2t#ssDLQC?=mbW$k! znSFFc1)v^MT|$n(}Wsu?JU?8Fh$XiPlVm(7kv&rAPu+h)6E2Uto)c@(E8hAMA}#|7TM zLi#7JRtf*vyJ5`oA8_T!O6`V_*@CFCC={@y&f~T~j0ErHy>D2WL6N&cE}mU0#~1AU zW8`SfGt&9ez!V$bG6(cl`zRQsqZmm#6fS%Fj}{+vIy3S$E)zM{@=I-;ys_R4P_L#9 z&SJa4H>B@Yy}x8pSvNYfoG^G>tvE4qMH-c4(Cz0%mF?{9KBF0)ZR{P{_0@Gqb)Bn- zxzde1U9Nr4&LKD!;plZ`T#dfxAfoqX6l2;UKw7y1H_UZ=_`viPF%Z!w)z-d9uc@oZy3_XI9dWZ-$gBcIG>@Clbx%ZSnaIF?g42VjYrd zGGcqXlaO*X7#g20%E5p;5;y_(Dzf&7iX=ETsy%dIq#Szn6&)KMBaK_O?QVRxB8{cF zZ&}{5#@3m1uW|My&OW*awhQgfr$$9L1rtQ%yeAka2rDS_Z98>TeqKIxNinG^H=Wqp zKr>$wG(fc1nY_kfiH%y8Fy$d*txG?!O4!Q4Ve7H%zBmFd=cH4PGo(!B=v#GmU_vOyD4OCGTL;z1b2KNM*7wL(>d=4td{1&#uoH_ z{w(g4RY1@KDxf71> zi`SLAf(e!v+!h{`?cIbj&1=_f84hDitzIdWwxbz*kFN9;ri{(V2k3vmq1sQMTQtGN5b{uDZeYLNBl=Qtr zn5y#OMf(ULtamid*9c)y7OXwQ*W$k(##OecjKnWRROXqJZz~{|8Iu)$+Wsl3@O5D8 z-WTc5O_f=zUX!T{r@?Op2v77^w)vQ{@~<8;2)}sexv}47nKUi0ZLis07woMG7Bqw)Yq^UA}CqD!A4JJ0l!EaPsBBbR*hVR{oZlb!3JhUD>W- zm>d9dfGu9HUH^b9e)5esfw}Kax^P>+;$HfTZ8X~;ob5E?(&k}t0_WnSEcSC8L@VI` z+Q*jL1|%2%0jIO3xmwWHSzjx<9OWlFCL}#uHMPLwJ- zI+cIXJ=_2DWLsDcglsf^QW@XZ+jp=K?jWr6)=RRjTwxdh_!bttt@icxMR7w1SpNLL@xUy>Z*G8HZ0`!C%Qk5=GZ8z4hOunM4SSQyuU&o04d}A=5?c0mm91?c7R1m z4@>e)!e2aF8UQK$-TAnzj0!?RHbevN5elyv(eQf+WQB!P(O#+|AP`|bJN~|cdyUDKPvU_=#*Q;G( zHwmpT?Pj@h4wUvHT5opuYPZXii;^wQ8?}rCC!H|Da*prBm@%hM;?oS4A;uD)upyeQ&t}Z*$xbWW_19Jl?%f{`Or|~1f@Pzlyac!4;`jWN8;xK01y7!Dfva< zU97|1LkA!5Zv1lYny`95tda&2_HJZYPx0CD@gc1EWWM?VV$S?Z4)HBb$j5YytO~Nv zYxNZ&VQ3j_-p2LnQ9U5-gabaOW83%rWYWMyY#NNu>06r@OE46F?8WF2zc*hL72XVAHY z`kqY~OA|&3OWGN(&3U(b!NBSxe}>A>(?=nV4BD|kW9^c2F^P^A0#*w@&{5Ny^VJww zMPS-s%^6)&G$mixkO*WBjXsM_Sl_HoZ*(7hYf9%%4tK=B+CT$24oBb&zM^{hmYd1x zBWUnGO);)5H;+sm2Q)1iURCmng7#H1cg0V;LY6ivQ-`b2sl3O?L1LUKnQ@;XkUp;V zy}^cn)9hGp;$*#W(vI z(9hoJ>}inbcTXwIV<5vHvdbjDR+~Rr9BNR*Lud{$EoDLb)5X~ zmfSdc#b>zKd^TmU1U+0AueYIn_QtPecBV}2U*+v*ObE?wPbWs*t@ zwI)g~Yfvy~Tl-TR)w8-3n>%K-`+vcq=1ZpvQ$|XuGO8?-?3_rTsz#DS73*JuE|p=x z;${xQJaF*72;uIlkc*~xj~(?JZq&^Y(3iuh$G{OT=O;hlh;=+2CWqs{<s%d$Y6AZ4o1s47bh0AlJqDpWt$w$vam zsiYcDfe*%+#XG@g8^e#zL=0?O^e<~l5Pf@Jb+jT@-bL{(Egn7m1CN;rx(k23bEaGs zLvzs0j66%Ut;Z5}u8_vTeGoQj_xz-CmEtgVjM*!t5WkRhHX} zk${-B^eQ)35uZI&s&q69luCz}ZrCKVV!c*!h%noRvt`9-@p6bwaMMk0AxE53q4{cE|T+ukx7F@Z5%m{Jz#d_ci?a>=;4c$x<9epxc z?q9^SGiWxPs&_Qt}&!(J7rP<)h6ZTa6H@G{i1K zu2E5C+R5&HCfjnaD-D`2P0+;aLbi&8N(?-$vSH0iMx7?-X?@JzL_KRrOSRmHpc%_> zogH!H;4qs?fNB@V9jA_8G@8F0CdD|?`xv|Z&gvjtC0Yc;S`PRkoFhGSA1ij9`Lv*d zWM-Cu1u<<-#}_j)p|_#+DdE?bz5G4A1Sk3$H*shtFo3$%%x9a5G}kn4*6I>qt|Y8z zjJhE$n#nGF{u5R11 zAS6IYa1E}(-7OH@gHyP>yF(zjLvRc3?jGFTrEqumB3;RM@4Mf9w|n$>qeuURQ>W_e zvuv-u=A1^J`AfW+jj0Vx;Xi#9;pYG;d>@{|R#zD2{N~rI-}jmw^tONO8ofZu6SUn> z`xyyCSDM$D_rnnZ`KguKpeEOVO{#5{&%~HG5e+W5m{fRm_j#sd$j&P1kO7#I z)v7dy_M8^bYqF6avJVC}y2!9jsUSyANgmK5Xk>gAC7jkAq<$ce4-Vn!$hZy@$6(*J zK-&{Tk}DI-QZbVJQR!%8bM$7XXT@&oLf6dmQN^mXOmxhgxLr22rL6SwA)vu+a0PX; zQF}w1!~>;ELSi{4*LrYfOJrVBLS~Y(Xu=nS&z$bvLI@HtvMD^sc2vt%xW5UAyb=;%VBec{#N4e2 z>U!8M%{cI*paGVGJ|>;eoIck%GEb{M+JSwU^Gsg`k%HS< zp3sgDl_&7Se6TDLZf&l-)W`kWRVylg?+@fL((iwIKkhx>N1*-!3|UE@M!hW}?DsrS z4K9jj&8CBKhC+eBagSnYt}>%x3wcb#LbGXvAgIpRiHss8ObfGa~i>aoc|$rqfEdp%?EerJz%_DBj5WG~e)nhe|GJ*HeN8p0 zWckv`Mp$)u>iq$%y^Pu1L}m5v>xRm!71^|?;*S0 zT;Xc~VOQ2q#=L1`xP!=WHY3+A$CE2I;z6lbNk;^Kd6l-UL>%+9QhPwy75+JTOe4L9 zTz6{^yAn;T)KFPm#;)Ci@n%V)FsZmX&-x=%J&fYc0$l6Me?7U5f-Ip<(nnz(b%K
-Nsx<-n%{N zfE%ZhkRBTw8Kht0Ciy_ZRUL`XZJTY%A;^NaOC?Ey8Z7~^BMVUY6!|b!V#H6J0{t4D zP?aFc7Y4S}i7B9-kWls3>2g+UC9O8~{%wAC%_i;-RJ=_ud(-PSpNyG4Ou({t`|=EL zCI*Z>feb(C>QmMhz8>G|8OjB{;%@Ny%VX2E(-TEy#af+^&^VE&_G#6Y)W=bj4e*V_ z{?V#{F;FYkekC)~nH#p8!b?FzN!^V=Df(w>C6Xopp|3f|6 zR++ZG%x-?{e$GXqZ>n|GTdr(Q>B|0uam)%D9G2+t%|1N3K$!Sk3?HQVLGa=P+@#5L z@(Zw5VDjY|9W>y^df!UuxQ2a%1-TRHrV6OpHYjVi?Xo3p++md)DyBncn1PF;qBvzp z&s0jP1vnj4jixrnL(kIZfJoTnnqB^S<}-*pe@`)~m-5^CsKtAgbIJ>47dxXdq`Pvn z?&jd;8@U`e-Zo!-6Jkbi_hCnsng|eOp3GuDg+Ql`7v(}9jWdv&!szrgkD_lha++GJ3WBC%IUyRU zrBWm-9_Ecr2zU~;^F|gs!D?Yy{?|FE#3>^j-U~&^3Ng&_PMxA50(4Uz&)gNqgeZq! zwhriX^tD%8iM|YBF2kCTyE;LeIJA=qoU$DLxZPR-;F|onr zrfK4S&KIAjozgFU4J<;|aC*aSOoq$7m5AgbLBQG^zInGkbR{K}-LRB5B^{XZ1}D84 zds9r~JQjicHLg8-3#mSGJHc+=C5Bb8%2Eyf*TFzRz-16%GI;@ z0i--amv;u}u?K18H34p1-?_#}^u8Jfg~0awXzhSC$w2*JeLZ%aFq;rrIxZ`nZnrBP z18zBbyLlc(rqwpO@wy+Ja#?!j&a<&H__9%Xsse9yl?&f^hQ+S9_jR4Sx#Eugf*{BA zg8$4#?V>2$u8;tgGm6aEvn{etF+0_S^bpf{t&s&|YFU}HZL4KWWiHYI2WG=~%8mTk zk(*Y%UDF+ITb-!*sId7P_Yl4i0y*Cx;>PNoqyOd??X|xf`PuSPq4hTJE1755w&N)5 zBN6d>tL{$j&gn71sra(OHmvHOI1-}^myiA9brGiHq^!4hr1qLN@OGLwehR0-uItCK z%FU%Z_45AT#A^fv6~1raN{Ty0JQE=Y$f-J05wxNZpZ@FeSXANMxbw1l; z9D4(bFAhEo|ZH1ha)ziDJ5@`^h}1VB#QQib#iis?nyw463X`e7vXQgYtUK- zn^KuF&g7>AaJkbOUW6Z$Yd>ts%Dkm8ivS(!U=OgHKMxn~Tfb=_9f{pMw{gK=_Ag~2 zi-A|9EtEaw_F>RjfdpISE=5i*dGx#|;q8%Mv?>$+oxIAUSBB6b(#{5}k-XV8P zq6#;?t3dj#Lt0num@T^SSIezWUwiy=Et_Cnpbr(`K2h391zSBqB*;v5h7&^cN?9wFk)g zlcj5y9c+6W1J&*+%3{O2$c)R3Tvi@8y{YaVLDp(RC(;lUGvq#~7}6g~4cl91w+{8& zr8FeamTQ%ci&wg9IcnJ?B=6%3zPx!sk~<+pwbRCkqRV)Vo%41_hIeaaI{V26)p)lI zXe8xSUrnSnxN3!+?u5+|+eTKyvV1_6gtOE(_I^8NA4(D0^M@W(2%33|e;wjo(5YPT z4KBUgQ`?GIgbI0lnKfS0>1b^gIKA|QsC$W>t>%@9`Xqlbo*eONi~VA#1p+KS=rZwY zkpt9?JxJDULPHB779YavM`0XpiO%GeBzm`VnKJalQ|WO90A_oqL#RX zI3K7x$EXi~%fK5tHZS0|to&1qNU`uo@3~{x1Np@GPTc zS=(1U&hvBd;P1E^cJ0wNPr!C~m(b8?YAB`R-Pcj)pY?lmI0vt5rM_&kP!kCvUn|`9 zQS^{ookH^5w)cr`fWI*mxtAd81b`fPD&TokvCe-AiKj}W->OWquBS8f%rY7KR3>)f z;|)|(oRIADN*Ac=Z4v3A>Az>!gCL{dgQ@(>%n^9SAo}$vo0T#Q`DXkNu-pb*YmH{a zJ+6Owe~!cHolCrey1MTMss8RtN#U@ZGBZRc6nAkSLTj@Dt=grC2Hk9! zOKh5eNOIhpgZ$!fbvEU7qUa{(u26jm#{mIM_Wg}{8$;KAwJ%%Kr*~@ii4D(_1cYm< z{E;1os~AtWMJ_gb1~$+%s#+=9*PN=Wl1=s}YcbbawmS3i7c4QSA!hh)Eh_x>XN?7E zn$z|SWwtX+Rw6iqqkQtpYOjzZnb6Uj5x==}7rFhciwN@QUVVt$MK69 zpg1>6Z>`<)Zkb6425P!X8gSqg$T!q!MAC86>R{P+i)dWNRAB~Gd?!A^!QLU(`_Lc) z|Aqn8Tv+G_wLS$(qI9c3=za7@jl*>oz+`eJHvI zIz4j_t2Oz?iGOH3(yxMOJL*o_ZnYu-*SFX&s-fa+iP3MNQB?{Qt@k(aP=7E-y|Keu zsVamn zm`V~7KqXj3t)e9=@a@q~)L)4W z^gG5b{yjL_0u2*)Kq)r&!?-3)*x0w}EA8v`xyt+;04j z+j(_7-QEVRL)>eypvPnFU!|u~SlK)Ot_CgaW>{3CcA_QM2CHG`m#~4-jIA=&gE0~- zU}Kp3VZ8>MAX;8P8rwWbfiFU7p62wzr2 zh|GhP??O@>We}}Sn?fxSB{yR`7H;n8%c3(>T`4qPQ_^l}VCdUErMj8%h*%sPyh(s` zl{Dysu^SO9zF^w~z~3@6dGu%M^%&77@6; z$F;yHGxZAg>^jr+ZhF_jmIBNYjI@}Q)6wc<9aOz#mXrPl{;5~T2QqiV)Bn3}@8zL= zAWr(^lk?Qy&TDqX)rjT|5u!exm|R=s<2#DTf6?vy)xU z!EU`NcV*Au@D;utS>Lp3y#EG=+ZKbC-hrs-qQizvmhGYf{*}?|*Vd9{6TO;Jg;Byc z1gbE^5n}?(#=Q;|hO!>xP5K4Y`q!?Su1?xV8d;%P)$dmz&rE*9%&Il2%c0kzrKc~5 z6ZrX9dw_>~^n3E~>(V~*p8dOKT;AHT;4{4hSaVCq7~aKL&M>}uTbLE-_n?0TT?s8ab`cKkFJtSA?)Pi;b7NLl|oi$R|JZ~L3G9S2v! zsFO@-Ie3PWg4PD9HQ3`LpB9wU0}d|)igYS&WvLOZ9Y=dyU_sJ8-`Vegq>R(842HjR z59+DLE2K6PRi6f|75rS~Y6{mGMzz6jUYe1Af*E%43Ck3oW2Wp+D>v*|=4z1hx zJp(v$Y1pNEAM<>rc^YA*;l!J=94kJMxLVVdO0!YtT}zU4BANvc!(JLNg1!Lr>5c(d znf7_L^|TS_q_^4y_%H?kL}kDXh#O3 z$)_7Clb!Aj(*&l?lh&#h8rYe9`mGVR*%L$13< zu{o$udOvUp_!bJi`6+GDx_FcJphn1$C z8K$;WKK6c&W@30LE0ko|WzF|(9;-UCyzyYJ-=YHYl|tG@uRrPkO! z2Fe|T?Tg)N9Xy@;E1rJ5M!F!>Q#=Xv8OC|~(b9WR0fO7I*p$NFma#aX=o(}^Q|lYv zTAr4_x1Vb#$u(SNb^FjIIi1#;G|uEfH2V1VM{L=ElY$ltI!pm&IE+HV;d?t9t%&b^ zrYR?g4nmLR44aB>Qd-SKo%3mtoTKi85M_`7J2~p!>Yh}so|!=dJU6q)Mhn7c?}-Reo572nY(N40HN-l<=Px zKBO6!OIR=lITX);u({~{Q6kh_QO`^}yn4zK);#&&d}JfD`W2v1;P$cg*-_*toF&OC z2tQcfe_W`R;7)~f7XAxBHh6XYz9Ol##Bp9;(DgfzJYl;43~FN zfe*KFUjy+nCRhr47tVAbL9XB#KE#fw)#+yws(Xpi^4mT^)^C2bR$cpzgApIit(WU= zcs{&He^_wmAE>WuNCKwZHfk(ZC8iyZ?3BIYG3#{sU^h>?ut!O2gk?PwTbA4*^O=lH z?I*IxcCy_j>Y)Z2U3vW-GySF;{M6Xk;Arh98mF|oi*F;isI{@c#WCe{l7|PKbo#hG z;-MJvX1*va8(FO{ld4LKCkwD+=+-Yrtie@D@Tqhw#UbdZ(P%6`r3)Bu&;wBpmu*R= zuIgpXG?~Bj+PWMsmyKi5(t=p5*f0x&SrVgYa;M}??~Ev~&3*0hBzc@p0V1=`gybmZ zM8x$k{FM;E5k$cE|Jt(?!!Pp4v=0vTR?lqw{ox9Qo~x7hg`t{jEjxFGp@yHFy*41w zY&#zYj;1@)&_P~nOI#@$wO0NrCotOD5gOTr!jzN0d*_{JnyPmhO&>0;MgyLl=Z3bJ zbU$Q2A!6w69Eofn^@&>&d0i2voSo>d>rabXtCt>{mtw?7z%iHP^_tCz(@ce`sdu=y zWKro=ji=Cp!jTJ5{=+%a25Z&`>{N6Tz`dhxULkAiwg%hH6i-aZQ>bnAA?ENVwXUV~ zsp9ylly2bpXC!K-g6m8BW8yQUi!Krr>;Yc}GUC@2gV!nI_0jQ?deYe%JW-VAdw+rW z3*gc2C7Wg3;FRgq7UeX$#z^|@hmRMpdq@A8!Y@Fej(N&B4@VCV`1BW`xogz=i2v+? z9^($m8;vS82A|44>f&am@E4$cBrv~bW)1nwrDgT#_iri3*@N~*og4uTh?{+FdGk(# z{^n{g`AEJDSYtd(TE4SfK(os_VF{57W*T!y$|HVDLIS`S*!t@h-Lpp=7B0X$oy9vf zje@0T0#1C8+UT66U+==$dN-~9o(aKDl9rlr5wGDG<{a=6i?^laBG6TR&IZex0dqTQ z1%FY&*!j>epD5oJ4z%jr^#XNF(Qp$F(z_?KRco{iY+`=(N}VMMbPZKr4}>OEOn#Id zaI?st7$3K1YhEz~!S`D?ZAN6b3I zAUe+Vtt{P1HiSE=pV|?#J!$&fi^mc{b!#fGg~xMvo-9nv)Y|V^XukC-xogKTatZ&$ z>ui-uLqcY_%2_zeFR*XY=9~{Q$!hm-GR-PgYMJyqdZU4QCj1e-{ z%M(p^mD9F*hNM~wD%#6^>exHoFipThkQ3U8$JSD4Y=?z5bZx&SW@I_!FXG`Ty$iAGy zIVvu(3ws*FSiDf|TV!%vuX^(+7a~82pfH+!D!f>Iq-T<4=V3&o^4r*a;-0`)R+Xn8 zu{>>|e*u^w=J;^K9gvd2E!Vu--@N-$b_LBT=_RrC_;jdqKKy0Q#)G4W@7vsIbtc4~ z3uZDtRkY`UJ1!tBcm#j>%%7(#1DSw)Oh9@z?}u8c8UgDC7n5A|(_Pr^DtfSp*(8?< zHJ5YzG4Yl&UtsA;fm$j4!S)Ytb{(Vf4$yZ#ifi?7`MXAlMZ@0wUM-Ju>zS)5ReYcG zymhAV6AkC50d{)4{yDnUYO52Psk=D>-MTWKEGPA1Fd5x)sLv;+pj4m=-B^|6qLH+r zxIs`E6tdRXI^d5>cAQq$C_WCQ_wf?l6YdTq#x0m&8Avz5;_a6jQdC8j)X0EQdk;b> zXgFfo%bgR97bioLf+-xnZvsdgtnjohe!jZO=~z9>R4fD*ZRI|d9eb49%w{!e+rl?i zqg3H{*yuK`l#0>g5Mp;*@K6nIleC)pHakzuY0wE&*kcT<{Gg`Hba04a+(iZ)<$?A} zAqKG^BX>jt^46Vy%TT1`qr)fR;j`6!GV^L+-zM0lWsUi_{rwIi;7q50Oh$_UteN6Z z6&bl5?^tJ735btf;xw9vJUh$LbrcF;+SOy88K0D9y}xeazub8~rhon`uy`~UjC_FL z;i#jI_KFy~k?KBQy5s))B@jx$e_imNEhGOvs4@jKr?~qb0y&EpySbW4Yi?Dr z&rismwsGal5@`GLmB$Y5ihaYkJ5D3ZWvjdK&er8vD{P%()QLf4%p>~Eh9Bx2;C|CY ziAl#$2Wo?~39>L-ydZ%?8@1oozDn;_4V!%t=FP}R`Hp1M zoAf!WB)hwZFW|lP5lzg)S3Gk5+zYVR4FhCJ80tQ6{`DqC2_ZK1+iz?PKn^Y=a2r%N zAES=WihR21{=AH;H5uz8s(e&75mKA@wTXg4fEz)G8Z0)6S{4lS4SfhLuIptub)qk-Uxe$>?GF|^$p%#QjnI*) z1f+QsPTNY^Joj(W6dyFpH@t1t*Q3H{_qfnLZfKz48SHwUo(>;A&$7GJ((b0;+xt^S z9yFc4JHm$x@*?1cY zUW6^xVIE(KbsRn7kic*rTjCO8Nr$CN%g%xj9xw&lW5d7*e9kJ2#Qd}5XHKI_pgE=S zzpv%T-v*9^e0JCJa)iJJ$<+Zd_w=?R-3e27`C47K1hh3N<+C*oZZhh%M^VUUAcxL2o? zpEIytUAwUY76@b>^UfZqYO%X5beP?O zwnIV_@yjD5y8LlaRX2!p|A{(#i{}U%%-Om|j@cB1TPH zR2W*gR_NsQyXd5;Yx?Rh6Xu^bVV{;0=OF6dlljd^-9b6HA1ZldRRllBVxj9qk)J)4 zTND8n%dQa0WN4eZED$dawjC5aP`rovjRU&uU;Q3?ClhFC|p1WD;{`$XRuZ05V{-pa$d#_ zNQ5elbL?Go)<(c7NwH{YS;jrcEG;}eICFFuG|6m=U3?$z&iBp(L+N2NcXxY-eizku z=K-O5t?JIKsXUH!+taIVF}uO7F{qXa+v!x#^U~uoJCrgtA6xt7RP=C4pao>&njB@o zBRk~Ey6DfS*Ov)bFxeVcPo-1fMrvSVhkoYPvTfm!kgC1=Q&Z{VzXdu+>+&!p%T?Qd!s*v@-5o$eE9cD{mBvOFLQATDw(sM zJFS6K+?g!_Wi>rP-xv^|;SUk63#J#AGSYb^YMXrRO>Rr~sMg@^C`8YXx_RWDm<V!@RTePc=*h?x89iu>oxy z8d@E-Sj_V@E5z`y0dd!Xp1IS4@eD2?=5ea~6!dWVnCU`tluuX^FF0?Z}5wYw;s>%gpya!NEjU7EQ&d)m7(C53rM3Y@PvJs!9WIgQyF<-*yya z(q~vz7IbgPK64gk(62GCkUqS{ybY z5#CVo#v7NIa&w>c_ku0vTpulj;O!t{*`|j<00}9c%8D}KP2)r1m8ydtP`%eUT-y$= z{bHh{0%B&J$tRmZGQ%0nQ+yWt==`1HqdFkQ_t;nt5nzi?2HsM%%^LiZRa}Tdg0u^1M}eH)4>{pES|+`#@_CJGve3rPt^wq z$L5duHFc}F`FB`*HnpmmQX?E{`n z0{z@(Sy_WihfACKt%mPrGUw3`^X@yMB~L%R-P$Wv^S5S8tg&5lLK2Lsofx_pW(^W^ ztfU1teK;Q5*P`LGnm`8O{ zsw8D``|W$rG_x-esq$31;&m((?y0kL^a7#%MnN42aw<0Xd$f zp}Pds53~bE#7ud|DB^eV9lV)Xds_DwyD|*Nlvw*n;QJ*7N`Dka7bR07J&U`qc^h+8fTh*(r3)dH!f3A4 z?DekY6;uWvgOmHS&V9?9)FL|IzBW6lyjle(vs=(acu1X-NJ{zg?Y%>Z^Ssq;tPy#6 zi}y~u6=kpCL_c+3gP*PObRvqRK7~;6f}|4lR5iO8(}YNr!2X#>X@zN?XJv%0AGe&G z56CIzwK`4j|6^nIf2ytUr#HI3o$BNmfH+olb$L691q&gJ#Qebn2j>id*s0y&69cj# zql+j1l01M+b^d*ZF|f#OfcV6de-}n>T(jZ z_CJOmO^Mz>K^-G6n1)q!7?a;@BUTX1i1hp?fg`OHA9~PTpHHmCqmF49YV$w7o_csX zJ17l4wS$311x4Ecdp>Ke$ras}g{aWhh!M;sLEkCrfF_5$<&pb@ zm8)!Df)e6LtR$B$bx3cO$j|REVLjCbjZ$%l3yF9#?P^9_5%1p?awckPD_xW>j`XlI z?-PxdI!aR`h@iYNW|F)Zryt`QQz*>BV1ZRtLy9Vd^=@zPpa5$L%?kq!`!;z6izCq1 zO?l%nVBH}1LHQ{ll~(}OluqQEe7MLf>);Ue6XLO}mFUY3$!h;M@5rzFi(B~5 zrzkK?^me>S6X#f+dhSR|a2crbL&U1p9*ugVHt*5zI9J23KTH#o>pHj@X zS3w|3IkevnzC}#q0sF?a>9ei2UlZfNLN$F=4B7A7YJHV`_$s9kkG#MNuyu-yJ$5yb90p9zwbM*X?nRB90sENe+mMBXpFW=8-?N3b53gx#%?u2@GTXa^1NkJ6a1M`3RRL|oByg1(hO>0UhikVz?h$RxexreEl$@n*VCsSVwM3xgrS z%A+1C6uAm>ggY-NR5v{IUj5RgEN!4sM(VS7olFvN0!s9Bs8|EMr z3cSxyRHs|2pW6A6?G~Ymnf}$=(1Plgvu;7MOMR4qje$L(x`;VQKF+ugYg-pUg^p;T zF0{hXFUN{UUrZzO_-U|dUh%`+C?~8e4sKw1hJ$vPHHd5Bb`)$-*)=bmpxZQIKrl^G z5I`rkslgUeo2wt1-mNRV_xf!OTY!r-;&;4t0L-B+hsfR%E?aVzbbsC`;ZaMFHbc)t ztmMnNiEQ&$Ka)z&e7@Hms2un?!~Ib|D)95Aokh%dyD1ztfgymN8pnU<(uOH(ItfR&FkqHa>Kf~GA$(ua|GF|`&9C+7FC(s zC6{w^?w^fx-QwB}`|W|2YXq@F@o*fSm}#sK$<`Q}`}WVr6tH<5pCw6UA|9@(T;0tJ z%$3wOX!O)R3~Y55N^6y9*rO3IG;2%;L_f*6>Jay{r&Usfc!+EPm#;`(7qNz(b7=Hk zagdDS!AEP6+7qSxH0b|0snTRA(2#qfXpe`5VzcbL8p%0pq$!kpzu#&VYM+TTc)a}m zLMx77F_O2ox~_`Ok){4rt%V6D!dm@wO7AtgKG|aRd*K@D#B5|8J=|uRmh|Z?seJ>b z4?Ba+2yW$IsUsI8;H}<8pK_g5-~1|KP4>wgR_eQsbx>1EHQl)3Jtz1%oN8-zdGhuf znFjmRV0v~abBwf^2Jaxg(wFsYOZfK&4 zk2I|$6b8n@ot*o)Z+083T<&CobI`GtfRq$>SD|=Foj$moL2WsLP(8 zIg5pDC;M6@^XfiDmh(6djaXZTjU#mYOuER8G^$_SCNIm1Z(+DMUC2El&n9?lSDJIO z5Ip;C1o37VLTIWHYlU)#K%1lIL6f`Y9yIq-)EK^7_VIv&Pt9GYe@V2TGyA?Rul$(_ zHi`U7WG$8`i$R4wH;k%@vmf)s*ED&X6x1Bz+@)L`Tv|e?=}tsBb1 z_NI3qtmQQQX(Z(*ocu{CIY~ltVg^e5@XydUgIf&fy?2Xz0GL}Cq=6MdfDPGVg?TX zZTbCoA4j92XJ?|0w5QW{TW|Qa9yBeMd)hki+63#vEeO@|=G6Lka-vmL!6n+nn< zDZxj4G3V9!1xV;HXsK_$s^qztH_}=DwCgEoMn5nfJog8*WE36m9f39c?f3jj=-9LF zCohK=Ptg#c9rl00ta~7MqiD}{RB0jas>6G4Zj!@Y6vp5v)5z=JkQ))Rq?v}TV}LIB z>f!r~6@Vc&@BSA+Lg_i|X3b37J6~xkxZUU_Y;V5+_z8GR{zST4e0#p;OPI-Dsr`oP z{O3dGQM@TwTF*=9KtV^q%|z9ny}r1Vwk9u)A-U4&tDE8Tpp(Ws*43ltRdr58w*`fM1SS$4@>=&g=tzxr^11V)c$JEz5z>` zelhy@F^dI^(IFU$sAZHm*%IomjmQjJs!3rty=XyiqGj5M%1B-G_}mVqg7y#>EK-K1 zv{|Qi=`2bxQ@#v7FsQgIPDfm%ptiD9$1e7Fl-9u)Bk+svKr7sb}1Lpx~)_7cqd8RNatJz^0W$`%3XvQI>#)OIQq>FPpr=t=t&SQVEIh{_x?>%!YvXg|pP54nCPNJ-yp*HJG($n%Nu|<>v*gocugR z!`U&OCW3i^v(&-tDP0|-Oq&U7d(DSXD*Nu`sd*CmyuBYgn4+B9v{b>N<%(?)<&IB_ zwDbG*sVi4)kNiuOF(XzGjqs+_;lsLs6AQ>LPLVZ zd!>I2aaj@v?_pRbK}N9$+{_ZCtnHYZ5|G!vzlDUiaE{KJujGzkFJV zd+6$|du#J8Xe?8+sJNpUb}#kl_5Nxo$Nq>p;eFswLOmXete|IlUUDXeKp%C?_K?K= zaCINxYNAhCfl~Jiz}pp^hbOo3^$Jp}N=CXp?GLurAXh7A90 ziNOesk!lX9vJN%cJ%SPc98?DFD};0p^>B3?hjy>)xqdTLq$85}kXws;hWlc46;X&_Qi@A9 z>lna2KMWPzO5({V#I479LRb}wRG!}=P4$;zHQ6mQMRfB_9KnZEAWyPwYK@SP4oM+M z3KP2!qDX!LAR)j09JPK0`OLC?giY7E=iZX}D8j@!_>I?lALPYX$BS_m!zK56FBnHt zp0wlXZ?BcD%Q5gTkRhX2yN_cxY_}L~#faOUZ;jn9HsHHE_I>tEj(DaS7E}gv+>oF@ zjc39uhsZ1ZZIVgk*Z)*d>rd?!m<9D2UYJL~G_1HqK>mySZ<@Ti+vfey-xFe-qt+n; zEA9}v*Pq$+bH5c75If)gr?l0dR>B98BUHhwjZf2-gir$f5YGDCSPtp{h?--IJH@Va z&WSv_`kzg|h{WUi+#BWz=fvvvBIbU_=DLeC5?P$($>QwqqkB#x{8sR$z-Ye?X2a+v zdaRS>&_1eZ)34v{3mqv7iJ>j&!*+uTwYfBbY{Mzoq6@$~x=p5b2DoJ%3|$b7rYZ$1 zj3K>*qrR1e#J95OQ|9OPz3sI&kwzMlhpF;(s%nYsq!?5MdOLaLSLv2743Fmh^JV?1 zoGZeMI41ZSA>*s=vKpcFddageq;)uK-Wq~ZsH>R?^#rS%{xjc5HDpVxhHSs24Z=|} zaR;#+X4f%{@^1nk^_F(P3CUMyFL_Nz!Vd*2QlF%GG&`!N`MrJtruNFvb~Ej0!Hg&N zFT>Igkm+Elj9R%Aub!Ig?z-V8I+ndPFunUEzu6t?_%z}?!*T6+rq6ZLk;o}0O~g3* z^J~{W(7F5c7!ZS9HWql2m%-2y#kp8h_SO~)#aDN%Kw4c469q1-#H1l zZVcPQ*NUr`*|KRoZPbWe@vgNjb>9?}5tQh9Lz#>b#}%Ay@`|G99XXe@JaRU5R+G~& zK(SQG2d(=$@S3rRz&7Rqb4On32v_jM4alRffjjgghJzL+TfB`#dpHIng)(z8lOyR< zw2=S+5H@7Y?1(ppX`owJcD%V4>Gq~7ZB$%?-f9O|rU%Tsun!fA-?qABBR>}e1V&*!?hI#4^l17~|p zn|e8o^&Jc2+RoDZrK)9j8k3nx1d>y0?OAB>eFOVQRpHUR1|iIodVAn5e)eo7Ac8koMBui@}fVu_l(uJh@QAqDQ_s z3N&_*vB~z_H2w}o+2HnCK6bCb(q@v9A(AaZ=b&bFk_0>O-kCgRB#*)!MEMT=x$cuK zza+`5&M-t6c^ACK(Dt7gS+~uT2bXt*SL@gEm)p(pAOeg(aMuc$sGTs6KnUHkBDFaS z;V=^9-0ZefShEeql(Z5qN>?6BBgSD0PyE#keyvC!z?ukZiB)7_p@vG4Ao_^a>OdTrh)E=DYynZbI?(t(5PYKlbV4HSd5S?GSc`!+#~ z!$)1xcePW(@>7)90T%QtxcE>b2jd<$cx|}_xzc^sITgKz}SskXdcS$_I zb45RwHY|oYkTKWrYY%I~kGw~$7&Sb)>q)(XIE5t{`8lCBJME%N6@g(Kz+G)`>Ergd zR(lw$!a=bF;csloukcZ&ByJK3N#D^gc4(FQ@sSkM%f!)2foxBsQIDE5m!SF*^8>_! zz#DNaTBD)7@9U3IbzC={*gqYg#6NT1G1Zha>e63;dsyanpN;6qCB4A2^famkCUbdE zJ1;xCdjbLcT!?dce zIebO|$bi9Uyl?QeHjIW1fnrspw1*lcPa?EO32qSsof269B=2y8poRpHs?hFn*X~;& zWidD50$wFU%bv|DPnv*|5!v^e2I(w>#248gZ?_fLg_-3`MR7_3t))$%cTCFP5v2$# zvkzqZ*(ag`_TOS@zZCbYby1)!hzy#X<|P-SPIq%yDGZI%So)q4o6!Im0VDdria@PLb;H1WKC8 zAJtUfztOTaZ)X?+=^?`$3%1FkKOtIY1GOy{-p_S=bT|d<&ozxWyBCQt4#EB9#3tDI z921v?Keqd<5701_Frd@?-cZ7czmJ%~Xu80H_au#E-sKy0d&PYOtIUy4?C3@-Dx+)? z#3hS>BTXG8P&=CUc5JzBnZw&YKg1W$MUtv?_O+sPakkL6-OnPv02jZA*{MSa^&ey( z^iO655s5Sbjbs^Uix`<8ebYO|H@^TH0Tp`p^+j7(C+FXkx_{yUI3*7RJoUNO9?7rB z|K3rd&ik+G0)xi9M3OP3wEo0Z>>*X2lR$qg#fc3n8ltg_x2fs3F!e5wTb9Y}THiR< z4S{074a>5`A-W5oyTc`^KQeE|QOS?~X4rr7C5SOURQD{wwQcklz!~(Q;FUg|V85%? zn!fg+@o|M|bfsR8%1w)2qf&6GbO<~+Ez_bhfT3zpG&oi?Vvwda3g3JQ=Cu7eEt<$C zmg-~^p*%pd9lmYR(q5U!`b-udVnFV_`ktYrx1IBwfkm%GCozv5qwpS0!T2M(;{F%( zSTy8G28WanZm)6UIz8Iur>r@L-2Hi1Lygx#)67ZTHPN=o;-3XLeKjVO=!@O+L`?5leG16MWU|AU#v0M#BNy*sWVH`331vdzr6{I|B!z(z|Kvfxr?)OxrzsO zNKLdTI_-k^{3>suv~+XUC$1V(cJv}lcqd)JIBcg+Vk~i(wC}D8hJpboO36<09u>fa zVm%0hSOsS!ULcx;isP|YIPw=oBPk#0Jdht^WLa%iBX2GZrGC5U)^ zUmB@zq&rf710d|wst^>-W0gq7Zx#`m`d{q5Ra9NuvMxM>hT!h*?rtGi@Zj!l6KCQi z1b3e}fdqGVx8T9u-Q5HEXV%*5?Cf*zdARq!{;k0SjXuWcRlV2OrK-MSd2KHC{>Z%z zf~;F^v<2-r9?~$DgoYpDnhaI(c^Py)qCrSaO*Ix;4)JSxv%Sk@nzQ9eN6JYkYNF`hwk^3O+$dxdBf>K+J@eFnWI31>g(xMUMcna0ZOra&< zFTkQQQ8RA2Rd(P_3w;lS$YQnHt^*$ET|mFQ7{o;!;s|Qr>1-HT&h4*(8)#V|k)b=P zpQsB@cT1#oTXSm+v#SCp^ve$Qqfy7Nm5PPt>y zTsC_vb++Yq-HB?ahF1Hb<~znF8au_l4CG;)Vi`tUOt$s0kxgTAdP$1d_o}Z`U;xO2 zZ7D4XqbsrL965uj90kaEee_QAwt9yPG|`k;u1S^rWv*B^tQ@%0l^?YTzX^c@0Pef< zzzH^m)ZL*-Z<6q08~(}z`pyD7poe#UK`aJUGR?sh<|p#r<%TA*c;>k)?yKzkl3qxN z(e3$DZ$-N3wTb=NcKe4%Tl8Om3%TO9Bl`?Llm1@-&%CD#5sP-0UjS^6>|X$pRZ@?{ zUx2Te4*t}aAyZm0zX0J%UQ3pwDODY-)_y;gQY$ik0s0JRe*wlDLRP6o_j{Mt27Pj_ zXDNRHHWOCs7Y25j9PZK#J8&Bg1|;|m(JX9vDfAlPgnbblJj7SZjCRVUIl}K2XEHw9 zFBgi|ZV`~iEvH$C3T!X1v4yaId?Pql^|eyTHl1Jzh*+C39=bDlF2viwTQxbY(GGI& zgH>nbwFjdHa9YzEyBFzNz@ry+avimm+)8Yh-o!FqmZQssONXihxdg1%?M&TNk;bOA zRVjm(2tU@Ky1wPXg_JD6335vNebkY(^kXA!Z-NL-DbaD6{%_~jMx+tFM9=1%R8@WL z!_DFV!czd3Bqih~E7k5(@&^EPAq;OWqjGKv?ZEjPV#6EaJ5tb0!F}<+bH=t9%oXS& zb`AI2{leW6Zn8}bt3_-o9FTvXZI58rO|p?tGf0{=0%zK*IB?Ns1+aVE{m>Gl<0pY} z7v+iejLu`;>SX&1pGXQDdT#d8WcDA(qDNm zpQ5`2l|~W%sc1hc(42+ZfVv1z4-7Z~?kFDu`Rcz9@d%%5&XU zgrxbpxX8?x$xCdNy;b@f>k*S>`OliHx}t(ifa7$(fJwW>rA5g0jq;mOMoGeeN{ z1)1G>!bNTTCs;)F1W072P^v|w$|0Zo0VT1rde`E~M9@7_*jeTnfuX|(uLc7r4*7o7 zx&mF+!)%pdDj@f=;MHn|2a@ArFKx{ZD}NcSK4yZ>CpVKSmF>_<+(9%@*^bljU~4om zytmH2CEr}@CJ(m5`Bf8^x=BDFM>19o`-}sK?9_m*jo`b%A`Kg2vd--}VTq5i-RzlW zdq@bK<5Qpwz6 zl=cvDW=?p!#rKrT)uS};-u}GuHEJWAkb1_Cf^e;(%|jp4noYC)0t5{N=2M@KAH8b? z<+4tVMLKJIaa7o#t`M>;u$QCGD;@A}eILZ6EX3@4+#Optr+p1<1!NB>g^j7+)o0oe**59i2}z5^lppCJ1iH_G zT-e4G&4_3ROyPrucNf?)YSFL)HZ;zmc)0*F^2(WV!adTfp*!rWk#lT$J=YG-4oGIj zRlXzZPi0JXdJ#n4@h65PhfbqsCa*5_->i|iNvtd=dazf%dFFbWEPTC>@)`?+b3{~f zO>|G#GtW_6cjOjrO*j^5TiBR9x(vz`EqXU?$M z>5;6YZc;Jx|8{XTHNN>@^iTgSFy%j@RQ~f1tc3pcYSWpy21qf|@?wkko2nj#;lvPD zUHx$W0e*gkMG{D)>~b!P&j0@1dRRH4!h3sl=#HOe=C*TL#v%3F-V&b8>|H41{>E&` z$Ey6Ub)9g9z=$Q1+X%#I4A2_$Sq8V9CWUkbcFab*cr+og7+#aLghMuDd69ioH*OXEC|S=U@_@cM$+5-14n4;JoKY#x##$V{Kg~AB(AA2e-)*m{1#ph*ZLXCr!`t-NBmQ z!!m)RYCFtH8V1Nc5C_aAx!eKl6o^>cEhL;oBj!w=F|%$6Xl5oXyt3l2l9k7&y{%&}Y0(#YBR z47Gp9(co>kIB6qxQc_wyIV&iQj;tGpMAuar4U=l~PA{H;6Eh`zT~sI}!d>v+qCurZ z)O*RBq84vKy?ncodj@hzT&MJts`tY_%N&9qm#xAM*ds+sA`u@GW>{|;CvZh=4#vK> zv3LW=8g5KK>MQ9d{J5Q_RJSivs*@RMJ&y2boW^$EQVb(o;m&F%mpH`xMuxIU2B3gZ z>wQj(JIkun8qBm{$*55~aCu{?+}tlIPGgD{%wfR~BTJzY`tc_CIZ#D5ARx7i<->>f zj%3+>Z}}2E`EQSQ)*4RSKVe^1rRH<-mwXvaOAq{xlZ-WfOYwaZX*6>C)3RF*s?+$Q zC&760iDq0;2`R_quy(w{N>8yE8<+lDLGuJO^6y0vp+03b%vmR`5oV3n>_*FxGyWDr zVpU+tn-*f%Rwv?#DvxyW3cQD}-FzmJvRTJ^-{L;djcMHIKZ+{s%{9ty*t+WGtq?#0#Mp$pnsvs#dj(&{TcY-U0VtMwp015% zX%Bw^-uUaTh-O8k% zFYYL*6R(Z%8QPgQ$tg~@<-P$I%DS(+{>(j=k9mh<{gdCo7QE39`E`fem08r>Gw(+2 z!Ym>o@s8uCW>2N>_2)0oc-&!+9o<=L=WP%!guN{UJ?7O0xn{1r7bEY_b}Y0df6I3B zGr|G&Y~r(4cF9lLX9qXrqcY%~Zgbh}*V4OInFpLz(zUN}Ric{rs*5kU9qT@i^Hjako;zmh<4w(7G)wnj}Y(qKl|nf z>D!YlCLiGqMC-5x6}!I6Ow&r5p`hn%5aH3E-(G@z8~BCV5#R=C`RZ%Mu5=?Jcf!mj z@h^boO8@2IBQB8i{m0N~6{+Uo``Co@aLTMrYMg7-*A^E2tZ-4$Y=1e!80fJp|vL&x52Uc@)6+e_KGniqU>*Retvuf>7W6r<;vvGNS04MFT-hV&juSYo$z(y zjG+zQWh)YHch8C?0kfXx7ch_}0iu$l1}_zk9T8wi%)zIt!$lfP!n?D{(@aC|E6Zhl zM^9pdzh)ZK@Av%z{HygkRQjI5FM$0D=vt-_q7hL_#4j-uE}9)B%d9_f?>qfrA$B1D zFFWwF-Gy)Dl~X?R2=QOIb85L{Ykp1o^p`GzMFAu$Z)Mk+SC2p+h(T}fFHk|U ze@gj#R-@XE_i{8YyM3NKjop~LGC1XhkDJ*%|2?b!X!@4{psxG;ROaN1S5kP?|6feN zPYUxNb4f8gf2D9$;a`7R>5J>V(mg5-MnzNl-n~zGtv7Racn9G?hkaoq?ee@i#c0%7 z!8rg)LC%#UsE)won$_R=w>76*p#L0JY{;~Cs6Q=nyGzhM^9cA~diIwPYaNhTAA-`6 z2JvS%3Po4^ZJVj~`-WUtO-;VM+&-^nW^s3MZ#(*-ft`h^88X6DSzuQ%spOUPvch5v z1Wi^UcG3z`7lF7lB=C6UnqxNsNayrVxYgdRfZ$=HNsJz}O2&V{WBD zq_B7wq+Ka$4grOh`jSj&JWO@Y*F+Qx2#)Yc12RX%7Aqtb0i%{}5N1x1(`>knh)y}_ z#i<{==+pfwg9Hg5+b=cqHT_NO5Ib-s7Zrq1h8LhZBhTarBT!ac=v>cdYuq#sAXn?# zhj4FDC4s<;nfJ%a)-1?i{bhsymH-PP0lvO1sCi{t+R%Tc{{jNdWdDI-KT&@}C-mM- zt^D60F3|D|z~kFD7yK16jqa)-DXf18Eqdgg|1j6#Uj{KP{p)E@M~IpJ0j&^%9>lc< z2n=U1d6i9`22Aa@LwZ*8k8QPg#My5=KeE|k-uMRzS3PDuH-Aj(^wJ0JBNO{`2zP4# z3my8;{*X2Mx8{a6f7_rkF~rpiBCN~03-xXmUP1lc3iau)*9Ah7@&5(g5&13^e(Aqa zZqx^Y-TDv&fS??zTN%UAk7h{mA2D`z=a+5({O5uXs@ zA(6?j1zVmrP@1oPuQ4Bw&QRS-f3JwA2YT6msWRg6ulYlVI(>KIc^|BaCaopRa)3hY z&wc3e@3phwPqo|LL-6d=)rG{!9>#wl2PI^M`)zO8e`%KW2%=etD#}hF0QmgU;P!cL z_0I9P{sZPNnOj9WB%e+ED$WaH(tp1%;Oc0Z+Ofgww_IxvpH7h{A>Cw!SizQGNbEB* zWGsoK-^^|gJ?2jj{lyMGoYhUg(o2uW1lX7?GKCURl_ z0x6=``EX+&omptN4N32u#-k?R$37b_NpP zr8;MQW-kHX>hC|DE1mqXm$rQS`>E?^Q7ut0sBM|)N^>EE_3uX@_qPyp0x4P5@F6&w zexGA)jmb^iMxzva(2NOcduUE+uncid&e&wXte)Nc4Iv6L%sDcF!}(~AnY?pT ziUD%e`i)0obFDb6K38>zoZg*vR6PIb+uZ&{N>PVDA|Cb<&ZJTvt=Tn zKT)vz8*FM%1S-6pX=DFF!jW#VP8u;fRIM3q8Mioebaavl2$fER=WElHHy>6*TLfu3 z!vO9_Xs;kt>i$ar|H89pfj=rCU0`$M|8FSB!>4~r-g8))hCLNBCMe(PPhlt8>pI>B z)umRc|G@E+4zC-fsqJ=T!Scs<(!S#|#is>oSR{@}#IgwvP%P!(G9n!Hs4@}Zd1rkc zURl?;n(R^T7hBOy**iU7QC^MrMG{49quw6&X5slXl6rex!$Ox{J*fMk;TX9G+Gf0) zeg(Z^Y0=}fzaOWqli46K`gO*Vj6~=L1yLSdB2N*s>t%xs8CP_SlUnYVg0RJpERI4f zz7epoJ35ThfBP-fK)vGo{zvIYg41*J8n=alap&}@djo;AkZnT_X0y)xFYxg<3J zG!NtTQ%!OSgOBcA3cPO*gk=1`1;_mJngt4AXiVM3LlC-KIK{5X^!#$}?+mJdzi**D zlD}TxL~!eWb~ebY(QnsH$J_BXAFXkfOfuMYPm@-MuS!5ieH%_7u--tU-4Gk?3d^3> zZWI3nifZ0S@}A;h!)D+|z7tmO-EoaC8)tQ$YQ%DzzOI3O=AEg@@I$2btf&iD8}mrE zlTPv>$7uX~fd-5ElUt|2TNsJ%PxQ$oL4@UBX}fwRm_|+W*nWW6LV3bI&vf2fvF-eYTgWe9G|nLZ`WL$}43h@7|*UEx0XRYj2uv z>9u}-kZTEhJmUusW;FqQS}9|?9=SMB%h!O0T(Neh5^q9-lrw>q`@;zpW?Pl6X716? zd&eclT5ROT>J4Sq_OdOXgH(u$5(!eP5fB~eTzy*LCMK`f^F&NUb2+XTow9uyYcvaL zsv9UvXAW1oMA8-CPh#iQPe*fz7R&WuhcB)geTL~Ahj~2+^8-1a{5{&_i!WVU_|&y9 zk!ziU>tcOY15fGNb>NhOyIL zj?sWgkuXSR^4b05yJ>zue~HC6_Rx=bGl0tKfYO22*e0)EyPYg;UA+lsDcyi3b9#kR z_80=0+A7z7Ci+z|U8|6;;lIdK9Qfuk$?k_qsH28K=&D@QegXQgNbE=qPn`O%CB3al z2-9f5BlscM;?!VfnA(l(T642CkZ@1j7c6d4gd9q*_>(+KY zN_UPd8>K)+NpvL31*kWDkEg{%_u^#1SX40f(j&n%i^wEWkGx^p{4oq#_MKdKKWvL9 zXWf9eZRPFDkASE{u2vpuSK`BpRkJ6bR@hAEYGDDhoxEPuP>~y{+3T}Frg~+vTZUvYaVq|*Y5>iHP>PTUB{sCZ9HMm!!72*%{(hd0q zAd&O$Sysk{pV@lgz4NLkS)};>H7HU;V^BwP5a;-UnOM=7W^Q@3^-c<0l0UeOkc_6$ zR_Cb43zt=H?dhHa?Isz2WK(52^qNcCB(Za&`Y>^iqM^OQ;sWVZwI99lh{U4QGn6So zsK2saVSg}Odk8_0KeGdutlx(CI`D`?k8V6pQd!JAc?BJ&R~0!l69_jMmV)Fa5dn$OxhAgaGF!||?tN-tRGG+450q@#WCNob zIt7e|pqXt9i8{+(7Qw};WzCIUD|7`Hpk2Itu6O8@P;dVoABu{nj7#!V zD?B-YRTFb2>J?hwcq@ZiONthU>zxE0Cbo1vD8pRJ;(w>;?&aLS|u4!thJ8NJvBk6`twQ=n?J+ zSiPiQiC`&SuHJoO2wuT`OqV6~H_?ltcp?l848V#%x3WL_3TWB%j0z_{3TDwCyhAZJ zFR-^(s2+9!-^?&4q$%h$h?qOr$<;xsBJee*59x+V)>Fd6xWB2Pbp1q$hDinsdesiq zy^N)lrQg3hbE??W`nn3v)E;EO>;8@71-fs(fk3Ysb9}E_ayXrn(UsZCbJxX%Rd0B7 zmF;_*8%KONUGpI$@d%mGt0LFW^rVDtgiiVufhP|cRV;Qhd#J)H7D%7cILfi(s$4|) zzVk~RC$$2-8_>6hWml+btQHO)=;=NA2yu?F(D?hrsS=vR^8r~a2;|hEs8*E>@MWeQ z4mJ^FD?GcoaSeQ-7dW21##t3-jFfT&T2;=9s_j+6C&qa$i=pDIqV}Upm-U*?-0Ca6 z@nv(3A7pCY_ad=}Q;{}d*IqUPBb*o_soQCv{pD^4^-&OX_+vd|s=rq>~#xMt!65 z*7>_OBZrL~fxeDc$Ax}gV7aaUD(Ox{jw!+1xE+h2ueGP=Fg-T;mTbD5@g=ogV}lFL zr)IN9$yjGZE~!)iz@fKDv))jn>r9vCyhbG}t1hX9+4ISsF>5x_AHhX8d`waxO3{5a zHNv%DmH|k1D%PWkJS$_SDPKT7Wb_K*9g}TUaN89N?fPAbR%D+4Dj28ox+B3kI7Y4I z+pdM>r9{4bOZkoc6V!pFAjO8~pr@`qVxHfIYf#viETH z(Ufe{u+mSS^h5go7Pl+tLMHTrV+B-Kab1FMZSz|ZJ>&}8uLBGCCir7kFS=`OS zDaq!N={-!nseC(DYCkhQR^(hl@$OM48Et;#=OWQe7vcstnR$)8;6vFV$gzggLht+1 zD^?za)b}%r7gr8CxpufhW42lddwvG67);e+#c%#y;}gpjonrth#436goq$-D!Vx!4p_g@+9+Noa*2BB7}9WghMogs=KWPTc;5r6$e1YNb5oHB8gM!tlo=Bi!qP1rc6nIh2YeDh^mtwV$WGzMCjjfof3Mu6j@1sC&EyHKDbg)yww zo576Y#7!vV$vq4{R7Yi^p*Ht-quS8;mijzK!@5fRf;98m`bnpYH)9v^ifcOa3WNl( z>5beR(0db?5%1etGfI9?l`O!?mFLKt1#PZSnCAn?(l1ns3yPFYp9*~jv$>;s1=;pN zB!`e){-i}}ZCL1+ON%^bMMC{n5n#tIOS%`zuCc@XU1-0oymr-vBS=7e1u4DQSUn*} znU_X66|)#%3mw`LLrntEclBjFQj*6rgtGxB_*iH{(dZ_2yZNjJ$JXU5gxE~L$}}^h>Ej^t|QyX zotIf#<7F&FcRJClbY9bd&(YU>N_6169hgU`u;~61%3AlVbjf)l)g&cHR0IhlCFH{; zJ@@;t09r6;#Tsts-LhRiS6F`p-mbR%oXwsf+;kVN6mB;z+&43v0fDIA$GS=j$D3R; zU42&7?;hH!J$-BEfo)I1hfIKkYV=$RPWQ9ege&Dg_U4V^E=c`dpJjpog$!IcQ;$xX1e?W z`yKU!i>zRRK(zfW`Vn`CjT){uOFS@?8W_~sfq`XLF>170sm;(^UCmuuUCx~TGTFeY z>(+gcL_HVKoU<_2%Tz6)tU^^>bvDHw4$p=qZG?V8ARPkBa8fI2q9j565Xlan6E=Si zcTsm`#z{^3jV`B-)*MA+xlkn?wPipwgps03J%^q}JwZiu_3 zh3JK;k@vWx(njOy*yO%(J-bFU{V>^m=7!i8_?J7s^rRojQ?C1XRgrCxmh>Zs)xS3u zZVk3?icw?X$A8ygrI*kRS7!SN08&cm2St#{x9*`-A>Up?(gt@5!^a@e@13NFg1-QY zd2$yo@kI}~N9~iXlJZ4=qeValXb`SN6GZ}WGw zhLpsnD!kDRYI11KAMG{LH_N_6YL`X0!18yPRopgEN5x`Q9&02=od6fmY|GNk?QSvS zaZMj0H51nw70DTis}|AIUExzD#l-mV0#dQ-KL7Z!^#gUa`r`y5k z)6u8D^+aaec6OHLu^+zVwf;kdaY7>l*u)4YO(xL9@kZOLr#)5wuB^%X9gi;5p@U-m zF;h?;IdTNM?X^l8_2hx2gvW{#G&V)ScUZncNt3+Or>ep287J3eMYVJt_THh0(ZOO* z5L%n#@F1}?4d+d+1h0*G(@4l3zmJ4o)1{xR@|7ny2lk~WkCfKPwpt5q^g|B#ZB#O+ zrG+00+JR24+W3&k71~GWX#ha-u<1QpL1COn}!Jv>HeZ7kvVp|8lbiVE1LV;e!Wk%$^+mlPev1UD2gS9 z`7wN62sOGrZxL~Awd?>VY~Z&KI#h7mPz)c&`Hi1fu&nH!Lrrl;qfd^UFB)9x(%r^& zOIFcAr4kA=xZI$H5TO^AriI~d8MvdR$g(_Dw-NQo+#3FLsH9C-WXZKFz1YLVC zqG4y5&42v!g!FLyp{A>c`ui8bJ=s=_w-mWww|7w!MPyS|l~Z1{{6Qx{=n}DpU&#{T zOTF4p(B0Z=P!lDrBC?}xhd%IsF7?`vNXcapFrg2;mj6an4C{u^Np#B~SrpjEn2f=k zWOV_JmkUR)0jvtAfY|Q@4&Q_i>wUuJilAYu&;{JL+I$5xLnYS6`nl&D3$r_dtZJuO zsg(GXCcDN^I#t?8OAN1X0o(dL;37V)@fBiff{$eJZVi#N+VF;j`Hg#%ZFed{49k|3 z=T}oMgMtF4Zv~_qh`5Jw)NWRMy38}moW!+cb#Qe1KUs8g7{yzc&trS-(BB7zYlFJO z{RJgLKAY98TwyE+a-$=+oTnC#LWT2cBnx5ZeJ*gLmbFC3d}Xq= zA#X`8CmzhjT+ad)qeE9{P54ZawU1RCSmvVh{O(aT&%4^AM`eCV%A*8p-S#VL-ytdX zW`?LGN5UWzF!d*|AghsX@-g)|Hj5R{1a1*?dK6#7>n}IO%xet{-*j_#>2lc`S(>hj z-y~e8<~%F(+6w%fE3c~11L$=*8Q*|AHdy8WS zY1A^%ozY;vPC1h;Q02R%7l=F9u7yY4YcZ_#B)1olyO4a#uhEdNbU>na(YyUz#-Ux` z*N)yG#b3A3S-yG^(`GIQjlvOaZYdvL)+Md7M@N(UaRX+Cl8aivj(I#!Os!8gyazua zFk15avP|v`Il9-@t&VJqb27#>ja?rH$DIkJ0DL+dae>dM7UFSwWK* z^)-??4#OJzuGXMRHch5#1bR}qDoiY`Ms%&-S5S!(J8^;BT?6qScbidkx(Mnld&b75 zNYYMQW$gC)wWJA+`Afq*_2z1Y3+&l~s=hJ{9&T5EV_rg8Z_HL~R1{V-o_6dC5nCZU z-c(0pbfZ9YTUk!@Qm0zdqdh%gG8e|!8AZ|aI9+OFiwf1FFS;KIc-*YZt;3G^wi z`v0y+OhO9MBvEJ-d zFp!|p%39Crp>DxpSgJ{#*M3G4m!6M9_)Q);3N4dv{`1Vqsu(ayep!S|I>B|#*~V1( zP>@_(n^skzwe=*Tfq}o@(K%MDeI~Ldmx}Tvoo3jUj|!X|6RP2Pj}%dVLM#Nd*wH3e z$1JTKcjSQ{3&QY`jpZWjrlq!4)d6W(w4IGOxLB{@V+!z2WC_-fJJP#t(JU-p+p}_b zN7d$4;3A{d3TH^8!@j;d`+nAfrMU;Y!Z~sPoo>9>>`O%(;;XMox7b{gG|iKFDx{on zaZ{21WX}{x5H~P~+>D`_C8i=pp2l}=ci?y4p~Bf3zpbqaC4={cUZFY2M-__xJ=gqN z_PY>N1+^R5@Uchm50u>8x{qguk5I!N4a9pT)m>2o_%XP9DTwiMZ!A2t^1k5r4UP}b ze<|Anj!1NMaVuqhb(_(fhT8x&0nLTzjf`s7&n%R~SGAsnvO~%=crK3wg0mwcoSd~) zLy4bM(Wj^qIYE-@QvDdIP3xqVU=*nXKVE%JB_EDU`CXB5cd6nkQsfbdEUhlE25L~F zE5zeFuQ_aSmyV?~VgM$-0_mK`%XY}`$4PABlSRG@&lN9C?MdR=+=~d9+%la6AL@&W zXRzF$7TCpvP*jg`Z|FLj*b%Ic<{%OECSG&1)mpATIF=$h0eXB=tYzuqX`>*zu_FZUYQ@XRhNLw2H@;(Y2rW%RQp{Lqxnv_)@` zaF?4LiQN<@1b;@!c=9;^+&W^mWC*8u`fY1omQ2z0kvnO5IpADx>IdMR$BF^8;{2^G z`oRcqBP(3R@T?_&5;jw?h28j%) z`zou!WOm=2g~r;Iz8nO1&=f94j$*Q}_&o!hTC*yf*UeGJYj1+S88@=)KoLGs|0WsN zCiS9rVUkUYuO+IplFFsQY)oQQSM0lM3d@JQlU7+K1N!CBV|E>ysTrv~o2>Wqb`N-5 zA-Et-sLr@3hY{;dxf?!z=AX#-%H^DQ8Mniig!lRoZr|XxUFOE0fiL(W&)3=P1!1hy z8$TP)c{il8uCf;V#QhO-o_2))kD8P;1p6aB+aKKNdZ@CRAJeZ#3)cFw|0HkpWxt?; zRIGUV1qfpuHlck&sAnB48t|Rt=UPC`;L-eg;5j~&s_1+|9AT$xohoOY0yG-IbFkgO zdanA-?Q1sGnwP}`LLa+JZ#!{tp0Zt@hmu;F*XXV6Y)v z*nH0I@h?M4AqD=M-K7%3?y~$2U;LFUVJO5$H;>QG;7zpAcpLn}K(X_Y2jW=NhS1DG zKTG=`O#eZ)`&aR5CQ*-*M=}Mo^RC&bmI5L8D6V0UHpV@{zz~Z$$8&n(-f6BLF84z0 zx?zpjO={}#>wunblT&tPs+^cC>L_1QRk7ZycyT4hjpKU{f0_Z}91?G~4h=0>?;sgj z6FBrgTef4xU@A!vmagDg+Xew0`sT;wRp$&EYn!v|htcnDQj^S?kGu|rvqM;3#SGXp zA5YoJNGz=^#AbnW<3TKYxiWx*hwz+4F=?Xe_XD`v(Um)Edp)g5*wsB)N>=u(OX+Kc z&Rc7GFC}g0a9^A%UfUx%!F9RQWLt97=Ws}5(T?IIJ=knpGh$4)+RY2@Fis%8!+~d9 z(&Un5)Vp=klMW1Qjcb`aVR8Df3;PazqH2aUX#2pbv94kQ7@hl-*>*{GaGpSK%hY=* z|5?~rvmJM{C#^#9l`4_?S&1&H95eMP*H}WG~+-zZLG>cHN;z zYLNZ+v9tFz+mO1sWj{*iL&#OW-4iUfb+$)*THAywBNktgUV>Y^PFP)6Xam+oJV)*K zc?9yemF_OUBU)t!1#TWR#I~)yH5Izoo^=nX9z}3&3F26c21`_rZbVisAuI~eF{zw} ze>y_;Ip$%em2od|+~mIpXDq9jY!q@T+@A}z+Pu7kQbv)K-z%>+8<`jA`4@O^ejn#? zmrC+wOeqtJa&A@h>q@Rw(I)hL4g*(hQ4Ek!TwCM})qvnJiICJi6^3vUT_>jDZK=?K z`cHS^ZRN%BDGlxf;uT}hIA_sy>-?G%NQcS&>;CzElvQ|3iqUnXsW+0&>$+*<{?^-d zmB+3^h^@Q#)EmsV3!a&WlM>9!ZfL5heccD_?k6q*WT{gWnDtT7C9b#vfDXw=!Ic}v z5;J>38>W@5Oklc;@Y5x+O`9+30M@9glSZ#sFl4(_!zP*5LttjBL^5AinOPOf+~sxR zZ9X#yVs$~jNpR+C+n-1bV`SOE@g*I9R0OArL`Rt+6?mAk09glK#58gX*qDBzoA=M7knH1#U$g(WHx&}O^t?#l8&N+vNa*{z%jQxDz7A=UQ29uq zyetq1A&Ru6paL*_Uf8;vz#5vAfC@!>DOqSs-%bu zI8*)2+vR=$DI>uEn|wpCT$BaFkPZ?7vEbmLdGu@3+1vh6=b_!I<}Ao>2Dk92RTCMh zIAXVxo^!hpD@=Z2Y46TVE*_;1B;-YIC7*9`uSJevPoQ(5j78`b<o*5Ah7x?MJacf<1WgY)luaFKx1Ud$I24BjiMu$zZ zS@3la%iz}#b`|QBk}|q(1ZoyFEv<`$h2Fe{AJ;O*nPL&cEsq9AM z^I6~(&0@jOn9*aV_6hxA{8YvMLy*6|AmL-n|0J!FT5_hp^a$hQ!Tj3H|JZr2Z?#8{ zBF2Vuiv2I;|C2scXQ&GdC$8SSG`sWOxMu-%u^t?U*3_*;?v*&~i+xIWQHy4>CbNo| z1zuuOG;gM=I!bE)95T-Yd(|CFHebck+r^p z=du530Mub@pA2wzk*Ah3Ufz74-#i(dqwd2t*BySV&r`PARt|qZrsYY_f4$Wm=U3#8p@NQTCRjuWxag zz%6CV1DLQ@M6}_)Iat$=pItPnOw@G#%FTH8Gf8 z%Y~?I$n1@>d`Bj7$sU%s)wo*f9V^jPDkt=1#(aXVURT5>)`*+nPEd8@ppq)$LW}A0 zZE{=AH!s4^%L)s?55+?s!)!#Tus~yT#3;%!Vo7$pO@4X(kst5pY`k@dh~{kI%X{_R zEcg`%{XO0;^RqJP;ZhHll(52@@FZyWFm*~{EGlZ(UN2{So|pTiSuC-vvAnJ4b=p<4 zvjF{-ZaI@5gnXnfQ_Ga29B$mWE1Y`7-YRab#)pGUH2=b`glLU4F(XG6-=kv2t~RNJ z%v5t)Z1!oKHK=74%&bdzDP^4hrMI$`5Gt?RnuA+|J*=6D6bW(?GIeE_>X!o;#UpGK zX2v;?o3&I9>bLL+Y%UQBy*HN{bJp-|G`7dDvEb(;k|zirCLxsV)QJO^(0SUrs=5!o zd$$(el&j1kC+I$NG#iDbwU5sd3zz?PP}j0(QO#v@(cuXk^-fb&<9< z5r!(-eO_`FLFlH7S-e$#8s12?yNt+%AM+(<5VY+C&}S0V!GA-1}R+HdXGY zvv?U2xvaZJu<$AMm=jgJ4CAiGR1v)uPeO{7l}Yp)Jocgct!SQL4jztTjjBk~x3*fd zA7|^nzwYas`j%=lTCRueu>)MGUJJJvdEJ31)VNO+G`PkI z8Zq#|3Q%mxZu4nv;|up$9VibiZRy{;5@|kpIkvZTbN>bKyOSlELH|Ith7f6xpo!rT5mraxv}sH^v8+sPMDVgnBVz%EnSA%|RwrjY0Yha&xuD6UgRN4RepQ2b za2U8vLBA?d0?@A)h&4@7@Uy9VaXyI9WVsit{>uAh%Q!nMKMLhSD%#QQ6saQ7q zvxo}YuwJ=Axd15H$M7h>uOXGnRp>0!rcM&AKw8OaGJ_aM@jNIBNxP%$ySzsKi|vM= z!hPso!Rbu8jI@W)$fm6^jI{7Z2B`!y4XpH5>OXAR`j-=u?N+rt3Rp~cbQ|K}r1>av z7Mtj?&`83><^v?Xmo<$Rg+y^d-a|D()4Kszbr<%cRc;EQ)GNFrjZhb#twn+|S-yJA z?g~kcOk{p9(dLnsC|kor93mrge}k?XgTt6L))5uL8ez$z+qAHpuH7HcuLw6|YSGcS zNHdEt!YCj0ir{8S>Ola5-b`1fR4o;{5{eF47i`uU&e(!;JxZWj6&3yM)cba@rpon- zG5TnTaS305;74MOBhiailhMfyf%XL$Cp-6KxO&FZL6Txqdy_@Loh34LXupjdJ4KO# zhAk#iLVV-N&u;-|k>c^=K6@irY?0~%bm5}Jl+g`57+Kpylo?&!+Z-t^593tW*9c2; zw26L(90t0<{-@s!x|m-6!@QkfaHp_=07Y;|jnX3E4aIW7PSMk+OJ$tm7d<6WY;?Kw zJD>I&bor2fd=jT!Z9^1QA;gU%>AYdCtjIw?I&X0fxeI|QBn#>m7A$lZhs6i(=PK~x zJP2#c5>4|R3i$?0o({jWc>nv@eJUfIl8@oiA%NYr?jWwESVcoYK8Z zzP)xW@}QIBHF28T)~B}v-CHGJevZC~ww{*z;u7FmDqq}tucCrPgnfCvsB1F349ErE zv3-ou(soaQcZlT@c=Z8J(0OZJSbVqnZ0r0LVNK!v^Xi!fqdnUrbzdM77|oXqu4mDk zWoD^Y^uxwSZ=s*>Ot*lL?23mH9}vWUt6#bgH5TjRhkA79yc3ZxDlz>5fI>ka2tdXC zqyet`N%8XI;Z`E0qSNu5q`_xR*&(7J%n`?pl=O4k#+~zzMaydi3FOgUX=&qMfH)2C zO~enpie57pwm)=<@Ap}6C9Xu`X(pv>Ti+xIS&RVn2U}ZgRGJKFFB?zp3+EAvEN-la;)7*Dzc95 zT;3}x_^^|SKfUWsy#v?1eCX^kpORB5RCuFvBXBRGmLgl^)h|a1m}r^XX!E9c^(d;* zHS~@L>C%6pch~ex0+IvHq8m5Je_ZP?P^=ZO*rfnqu-@iPwU;7v%5L1<6YtV@VepT^ zh<_VggXdB9oD(68ivv8cwAMIud}fWPnJn79@=%Hy`uDl-_0AfB_a1V)*HDNPzh<(? zBL1$dymE%({dVV1hyQJ*e?0tNZ@fu) zqy2~L@Zh=YB8uj)-0?4va^vJbl;qXM3w62p9JadVkK{W!cjq+>2s80G-+v=av=z@Z zEN)#G3ocwfgn1HoZF~7GNiyiSX@k4YnO#Y=$DWU3?lO!&lpm$j&-rsY;ANg_I$l~+ z{o#*te^(Gt$`tM&;eJaf?bGhA_R_Swi5AW+uaZgI{aqejIJb7_Ms9xW2#aUjzXt+~vkHwz<04N77+fsJYAq0St6S~$NU=^<9X#jCWU#kK zC#@F^Ehogs40B~<*fumj25|84p%bg=jnn8@a&WE{FXDNfIB|oP9=s-?TgyrG*4nt( z{epEO>mx&zOfx}DD?~f7J9awS7tPH?jz648wR&FBKHPG7WaGr_Sl(z`WG$u-vs`|! z{L+W}0>moqh+v9i&H<)k-1Hx`w?AclR&HZ44C@8+9$DI@9DOKv zjrkj@kN|;TvTJZAotpD56Ed!tec<&1(zrEE%EN-|0k>Ivyu`V>Q$7Jw9R-KCE*{<1 z|6}m|rwNo#5L(RLzYqob2ciHW81I2)(^*{!-}(HBCMCY7tXI&}CJ!7~<;TkdFh z8yshQyqvo!6&{{2m_h(0?szAloBuS6_3?+egZAWxaJlP}Mz=b2z%YPsoTnA%qze6v zf2y$hF0++(K}Vf(bgA=>=-I*a|9~lVj3%WcRB>&jtH@dJ@aaCsWjE|DeNC_cDy5cI0n3o(g`{px590E82^v6~Ikim|dqq zhn;hm*`eR|cz`(3Jce-PSqGETO;A;H=?dn_;nobwr~0y$?zHoUCH!&q)tyz1M%VC1 zXS}-mr#E1nj2xc?1mRhra>F!(pmU+|{(h8Gb@-xBKDwpK?5A-hcSj z1>}qR@OmJf59Jq>?> za2K7zGuFgn>|uW=0y@0*oy-yD*X*IdW<>|TLoxgQ(>X%7r3PT07Pr!cpP7KrZ&!wM zd4(EB?ZB^_-(j`Zs+u=SS{65HrT+la{Y@~Zxql*n6j`p9P{+G6o7W@PUj3>pVfV=% z32#_KD2Y2gVSxZoP28;wZj(6JWj(s$Ts%}aO>jPw!hR_l;2D89w@;lY#3i_fh#1?4 z=aKdaf(&Huxl<1{NWrD)BQk^CTA^Ef4LfaI*2S$O%e%5Fvo<|M)@GHmF_W-I5;L_k z&ZzmS+ON2&7|@636O<}AOMccgz%9)BBwvcl#3hZC)F6pz;ccm`*!0B(H6S2~ zEZsOz{+pz2^?yaurXh>BlzzDF3>mr=-8ag4`_UcGD&^KvV#%BTG}WY_7q7s`R)Ys; zyUW6H@$MDcwIk~7ET1nS)wL`f?9-udUu2(%I70u6}=swVL;}(TpM(67?WI1tB5vvXa zI(;MQ7bGZg%SDbn8Zuh##PT4h=5E_m$FLhzIo(Z{2y$tL0~DL)f+Zg?xHzhx4ABc> zavE_v)YXwnkAOv*3vOjE5c4qydxRUm>)YHl^hDczD~N1uHckRfMYfzXygz$>UwJX{ zEpj%BHB5L2k_T5*VRt4RjFjU{Xq`1lK*mY)~I7PIF<$ z*oWZm8p?Hc<*)u@o0N4D=R$n>$wU}>44h)#1i5ljTq}b;>XQ`{B~BW8Q?;{7v>w}U z7xTfzUNx1*XCx~1)q!oF5e5SN9X5-F4Q{U;I&yYieR<;8LS{OT^a<1cH4mG@28B>3 zY=O;ETo>q+9uD=R=m*$?`|915V#MsH_EDZwv#RV9QINmA_jtT6nb|^!5AdI9EU7N$ zw6xV$^UsHWmKx^addKE;559kOZ{%ul3qQkT^=?`8`gDb|oRaci_c?%<6_8(3|KH!7 zkRY40!&^_cHX~aPt=-DRxwv|B-w>|65`69W{sp*JNZmM4NMqeBxy4cU^r{A_fN%@= z;NQ!aGkOh>G`Ph60-eC_XX;PUT$p&WxcA>`-|Y!Bz?NIB9(?v3e6T9i8s#t_D`~$^ zb5^cAqb`T!DONSLJ5rpaes9V8=>e_&1xgs2;8CrFn|M2Hsc8aDs=7(Yc-G2ho_?T* zO$@t;bRs{%`YDy-T76dv80+o+E(QMjinn!jk6?)!YwW+7GM07M9C(QU=jWx?kA34O`+gzF zJ$J(@p9$YB_ixLTl{ZZG;^U&anN(RCr*!$cFTcS{ zo7m;D-|mXfNqrCPPgQ4g`&o2uGF1%r=1Oe)ufr(k zrvg`}OP*}TNWMCkm(AknkVGZ@RwmK*EU?@TVQqZDpsmw6_^Vd+elDxJ%REPrkbTid zb4}Ksy6QG?P|s*uMbEd|JPvW1q}PHu(nJB+)6gd{r~aIdgpLBMCApTku^kyiv>8-o zlVKc8ktO9h-QwGIJ1~wHiu+O1EqF7bmJE6f&sE+^tU8<3K~0j_H0%RUu{?J&mKJ9arP0%6;j2H`s%fY=g(ipm#CYlUm1p?VQf#^_O#?kEM;Za& zf@(jhqtcefU=$mlWPG|O*FVKWCUtq01-JF$n}1bCw4CVziIuC_1?`2sHZemQ}3axvQOgtyr?JN{!n zf_0-a^J``N^U=T-8g;F0K^~QIin2;N^pc6!0UoasFU|EgbkrAVe~NDh2`LgK#@CUP ze25QaL8zT!M8~u5W>G}ca%@j4&dx5h{M4SlFrwIySA*F`>_!svT(KY9h(pjf#Yx)k zvn8*591F|)grr(OqsuV^*PVPyN{S%_^>-eMP!|pfo@nfqZl5Tsv#CBd*NSk51Cg%)w*jJWzDnCKk zhZk?VRlrKr?b9=O&P9W?15DAn-_I49QCevc)NUea=0+))u)(%fDh`%vY+K ztc;zcU`&u)T56Zo)WoQ&fKTo>Fg*?O^(%4xY*02*{6C8CG3jJ3%)fdv?e``>*DCDu zclYvGbsZH{^4B)f8Rmr*n5-LjMsWRZY`#y62Bwpkr<>NW+Y8)Gjd8BAru9681QKZO zqGUFA<2w(X9APRhZ4F0jC}NJySzmYAWyK}4JmV+9!$xi^)R`9~4-I4FF5|5sSrEqI zUn#4iuU&}64ldCR_S70{pU#-9d+YS{ygJle-P0mmW@gGpvR&=iW>lIpKWa#|9%>XC zCKE}5CU)2Ot&7|{d}QIfPF;%njHh~k-MD&^p)aU?CpTOkzcB$`?9=yzHM_V2IW(?$tk?(D=%&u3JDmVN~&FdKu{fyWwN1@FJ2&!XM!tEkcB>jlbSNd&n@R-aYq zvDjJ;N3~su$V9bcJ8vUNam#z&AYf93$TtsK(%Dj(ayQdd;S^n0jTR%)RutGHuycO; zPC)oM)NXw7V+#{Ph>^vW5ZJrIuhFzsbC9zTGB#N}7JG18!13G|UEzQ~JC}OnIzC94 zAV92exbC1F9Y^CAsF|i6xJE$&S%H!VI~3dWs$NnfPQ0=o`(A4hC)FLV&{v>2fw#i? z5?yF;PbNNu4;Jpj!88Hq3uJ8sG1o$`@O8_i?5seHn1vhpPHL zZC5p!YIVjVZ(h_4YQR&~GEjjU`0IaUp+C)1@GUL&+DbN{)1PIpX|JY+tBb$y$|Mi= zWHDqOm9cyxLU2r$Kfvo~!~Z&fPPpe8tR0q+be$ZgMHiOqlgo}6N0;94QVq?p;t*k5 z)v0fkai?UB)s?sEY*umoZzh@Q%t`5rCrU6bVN{ttXE(HHnco<%wGd_ZI3yAZn}N0O zcWQY$w_aaxt>V?edNzBz0e@Vyk*i8l>C+h|BbeT0cmS(H;dh1AZ3D1B`37E7%FW(#u7A(!jjrmS_< zK3CAw@3|sDH>WR;Iiymzh;&6KdgYtq@6eN%%+IXMoS{iHG*3Pk8tV`@WhmI$^oB;- zP%C<8er9oFtU3t_uPf>KhVBKUrMPf%wJ`)+={Y6OO9ku&RPq+<-bNwyn`-eRA=hx0uuu%lEHHpl@#Ik=-6y>s21w*WgA zMUNXn!x;=Sur!k}qi3V`N@r1ky+&`93^y17vdpfSmd z4~n#Eng!w>cd)+M;oqz~)+z$$Oio%Nw4c^?eM1`yBkh4FiGtQoV>NaJ8EAY7X>Nyi zu2qh*5Khm;A>|L;-Qd`wr>Nw2jH2sK9)DI(nLdIOmPx;vf>?lSzW0@mdF^)Z`C3xX zLe(T(7Zwi{oG_$Hq1mz%Utz9cp? zv+$1zrIU_jIt&%E`*+O9IxBbax%;AYma{gej-I?d2Z~-M!!iS1txOFm(%LoN3<>t5 z!nfno)OS6ZJ@N1#;t$N!fC7dW%FOMv1>LHRK&>|1?1!l}gi6U+nq<@UH&ih*FA~*0 ziCol9)~%scQ1sa@(e?{N2Mr}Z?r}xFmNqG2&?I>r{fdxmbZ;D>hSUP_7r2?Y?_(|iVxl&nq{Y2T;%7gVDUC|!s>u;G{_t@~C1XYz zOU-(Et36a<3q}uRM71$PqA$1!$~HMXM_Na|)c`fx!$~87i$aJrkfzYJ3oQciM5zZ| zAV>z~Bpf1gnj(A{Sgu5)sH%#4?$~p-i z$3ZNBR|;W#U;RxHS30R19^S2PaifxX>Z9RoQ5XXi~Xk zcaxdVDyvn7&1;~(4xPtsj18G7eM0w|L0qhWk_Eks6(o!F(ttkdszOIYFb<`Q9Rb<2 zX0}q4JQ0z5yeS1fS~rJnKS0%ljpvvu8h?PUi)j8KbUCX>HorAzB>EfCG&E=@Z_}sS(SJV@_LI(o^xNVY|a-mN# z@d(Jnss;IriajAe=H;2r5t9!JAu2eWxHD6sK!;E;>e^XEf8EL$Ypmu340|ws`@$rX z@GUxwnM9?1FlqYF7EO#^w7zOpht1Lc>Pe_Xs6SFRG$DHxJI;y*aT{-QRC;=GV7&A- z_AR`Mqx~$#eX1*B5Wwu4yy+r8=cJ)OSWDSA7;kDE+e~Ds)M0A?>cR1&*O>&Z6%P4< zp569szd=yMx?PK4?@+y01O)=}p9?U2v8=b;$me|0G@l;J zjSuz)I_!9u_Q}CTO<&5I?7_((d#shMXygV$F<4JNOwN*2A6%gssxzkq`PuM%6E*W8`wPG2E>cq7roKANubc0m>=vbUFz2cm<6=l6QPx$%bi}?k zwexqZvEuS@*NQlCvn&;ypiSbQNAQ@EINpd^9J51))|6jiCA`$bx*uCC=bWM=<~4N z3|xyeEbqrRP3n*Dt6`jt^mZ;0ntLN|%xg--p!Z!8TY(CO84;CYW**F0=)xfP6;g|F z_Gp-OiVfr_x*uRo>Jo4m18#iGJ^~&2TK!}#w|_)&fMnOtI#p!*!~yl%S8gt1xt;v8 z(u>R-`|}YpK|49X0X6dr!Ec=}UzC?`rZr|G%d->!G)h33MX<=)cD_mu1%1^y zN!lQ;smy}#^FG2j-WKcTM%YL+Row+LI(^&fbWVb_Xv>ey1X!%+UG+ZFx<5|M=DD@- zy0eN+2^V6Jdq=8nl039{5*lf17#PWi1zB6eQE*qp-?{B#D%Za$@}hT1s_3k5{4m*n z=`HsGiR4p@t~vi}a&IR-OOkoe9g{ zmYU#Lm%_;SSB4R-myH|HecZg0WvLaD^hh$>#Ngcxd(j!6{ba8o%W=zGOzPmtb$|T< zC``Ike29?3W>J>_nceJdpEI(}p52Opi0II+Vb`V_#_{v+sg15Z;;dkr0tkOkz7V#= zLW4bh2tT{`LO<$PW--NA1bUP!N@1UlLVCSHd>Of9&Bgxl z2%23|{x>PzU3kLjs1D`n0B~wlK;~Zp{cn%F6>~Mk>hG;>0|1IIk5b^0m9>H}(}Yau zhrKzQ4BF{(h14wZK3o|G^RvTNwF-UcwD&!2h58#Hn=Fvuv$-n> z=h|nUtpInnPKx3iU!e)VehOE{=afNX92CraUF?R+H)~U8w{U<2-E~wo?&oMNk83(q zFWdy)GV|ZoCAvXG4G0zygXnF*`gl!p=zh;%DWOGab_*=1ps8qYfrTYYZ{G~Ojk&-a z=}jCcWYLxQ)IMkxYw3$B;zX#k5|c(KulPZF=d<9MFhvJQ;-jNtwa~D?Ori~hS6qAK zW4C;vs`Z$q(hkI}senwz-JY$^Xn^PT!xSeH%B<=S{ica-j7^ORc4ngRgCak#ig4

2G<`WJ}ei?AOB^keYq6hcJX>);Ng}Tu}WR51a zqGk=~pb<)w*k=>kG^8YBD3^sTF8*EKI65|Lo^(EoGMLgDHQ_#tR>x+OkE-{3dQ`n{ zgbf~Hz5DTPX23&T2=m=B6~LaBa$ebXD06exWIngVsG(~3R;#NfX|`;8tv_tiPp8VR zUO0O~iT}+l;f|)0&W;@jD=3SP0Aw3*9*AavV%<76=|h{idf1MMp_~v6StdHD&#EBl zHkYpC4>A9o6~Sfufkm;T07+_j^*KWjr95gLJnWQ^()%^L>r~Cd8^S&H8#?>+iPeJ) zD#FtCFag5x-j@sPL;b!(Y>m=G4*ZTf`W9|A5|$|K(tZ%~MLf$BBBjYBgY_zp(N1Ba zASZa1oqC1W^g^KE+VuyNYk%|&voY+!C8f%`L?@|=+4!2nP2^FDxyvl>W)jmM^NxB9 zPyE$rcf9Lp21Crn1ww7Zo>zR_wY7S&xqBZh`-wHAx1=ehsZU_ zEfdiuPf0gHFM*Q_Ls-8^8=y8wB!cWBUc3@~WM^0xvu?dcp_(9>EODyG>$M=hcFkaD zR!375YqySmw(h>mD z86_?(n@gojw^hQghWOH8r>3BC=xNT)SWlbiLRYWLI4JNd3?!i8@cH=N?mNn#Df+DE zGn=LI^R2gbI#}mf0ct_iC)slzP4>b)S!v$hmQ2FcCwGAs(}b{FP&rIhfL<418UiZ7 z*jSvno4GB-;InnD+a>s07@j|&Rk9sW)>)Th`|KU$LyOqQiPSEnGB`7s?*!W{U9EAinonwQ>Q=Z{IB>>|$-3YzYnBFmlw?DDZVY z2bEo3w(WL*?U&=-ibOvsz@yQ`Zr3GKRcEj*Gi&2oHd+D-52|xO%$tM1uAnY#;JE6# zz|IRsoQQwPN=4*Q^WDw{b|R5_@vYp8a}u?rJ~-QgbP}^4v|inK`~vsfl%DM?Q>jcY z9l)Uu=F26H;0aH`{owr-nB!@@4vhK7xd*FUW9ppu>-P{EkTM_&X2+DvLGVuM4a<&O z3eR2ItO)ePlgO4Qi*0GS$}&r+1th1i5$F&P_Ct-t=J$j&x3x-&h;_1Ne$+>QQp~;) zO2|uq54ZP@&^IyDZ@x{;LwaU8*zlr1A@L{Ax3lh@X$uyOxVEXW)4QYza|esf9`yuu zbiJ!d(e5ekhUSfzrW%fS4re2c6VZwt-y}DPqA3H|#5&*emms=0l*E=RY-J9@+q~$& z5wDbS9=M68XCKh^7V z_`5IiDw{8pE-*lF_^K~4l-1f}Me<22@v_qGlo-p*?V&v$DYMSmLsKCs3FmI+K9hwe(?*$ ztEQ4h-&yZEP#1@GGQ?gt9kbdHip)yg3Vl9<7iA?i@>UDM|&Ar#pT{6WnJ{)LgEjY#O3%PT$hr_0bd=F_r+G7$UfND_1Jtxe4WN>a}S3#d`U&c?#*?F{wJJjYCo4Y5M1 zZkZRA$Cr7Ck( zag0i-tl8i>B9elpNp=A>!LTxBMG*j4sE7|p%xCd@QaXU zh6fy3%Q+cJsZysO3_ZtM;q4W?|T&?2BSi&)4%99?cf?^;phqT@HhD zsEbo_d#Ks&trZBimXSkGo-hTzg>|)5;6R`82Epp=g7VQYs)W-5;EcTiuB|sQQq4K= zgqbOXNGN#tH=E>GtSn*YOfb+e^k$#j@Zs7vWVtO+b~M>b3v#qB&}*E7I=6Y9Uor zhI_m8&HK^UMe3YM@jG3+HKQ`zKgye^&8t?%;9f%`Tm@<(jD5eLd3M_6=)HN*VU+x} z>#`z1i@ztYDBqO;LrY}-0fTiiT`Co1{Al6o|*d#bN&miK3+5EAW$D&&<Rzm1 z#iJG_ePRHICDMxvkW*#}c7}s+H4bf7X^lMHN*#egQ@ED#(lYP$D>sQuXgWq75^B~;T zmlNmP-C?^dLqvyB2?GhERLv}y?fW{zWA9qt*JYo%^lx_E29#u~fA0!bUJYdS8>)S?5J_ zR$;*H?!IGn9?d6BQ7&n{4BGLX&#=T%JGg?`&)IA2G%OrI&Z=@Hg>`cJy)+g^?w5@1 zyF;t^;mnlT#g2RgTPpGin)OU;&J2MDsP=;MRFw?`5j{%t37b0~Fw7T=5aUT-CZ}JI z*fHwASZ2-dSsNj=)62&(#2^n8+qvwC^5g20k9=J0dX21>AH)%;WR zVdvffO;qbhJ1W{>R&Y{L{oL!Mu6?37)v^Lweq_*m?T)?X zP7ZZOy{oQd(*7PGhmqaw0$MOAw?c(GV(FN^3o#C!u+C0(Zqwg0l~5b6|1@3mvL$&x z1TB*^AZT*G;^mVPjcReU8^!Mw2=%^pSRjrLkXWII!865Ix+mvyXm1Hag5XqsJVPp_ zL3Si95{rNd!L=7Q4toy*;n4DNc(b){$3DoL{+nU#-!zPskoz*Y8{k}REdS%3S5|?i z@XcXWDY87JiI7VFvHKYZFSC)tQ9|tbCs#qIM6jAl>W@Z_xj7mUDTh4nV|{A=`|a}v0hE}h%Prc>SpQ4E9% zT$)S!#}CiRhXqJOLnc18n$4xcjCfwE{|xW+zWOvHHb>K zznAj4{lH!!OV=ZbF@G-9>6hY6jLRIvpt(S?kT!s0mp=Ft#Zh_t`-$=C#mY-geLm!$pR>&$wUnUFANgQ3=C#5zf#mmuU7AbGFLaf8D5cO5WIl!8Nt?YUdDkqkPJ(B zp&%bFlYXEsJAYATrrliK5_3y$8UFPsG=Blcp}n+gzJzAdow9Q&BI6f`xbZsF>xOdo zu$MRP+$&%88ufwkK6OvEW~Imk^XvNuiuRvo-v?;Px+Yne{B4!|bd-@DNy;(Jx=WNu zG<#Lil_G`S6T_3gJnSE^sKuvFjB=eSdFBlpfiP+cPw}_Am%zE!|D7ImP?QI2h-VQEl(6@go1QKez=I{x~G7i#(BNKA{;&|dwKp4`vR)o`>cpZvtJlGrg z0VE^@x0FHqQ}8oD|BeeV_5c(hfIO-lyr*~uzd(21x8yU-{T>P0p{WcHQ@=nQKTEv# z)vp?Lv@5+5cPC7yKGJ%9grYo?M>)4Dy9W9d2H^SBNgKmzs?r5@sZVGWM z(^E0?ACqNPx$ib?mz|kna%Xk5=@O|Tn0Mk@SR#bjQ%*yN7jV8R^yWmqG{T|p(b@`5 zHY#?tQy50jGq{%W>$MIsKE$~7@m#@}280eMKVNr`(ET0!D-#rnc`lA|CX>?^U5LDv~}A(W|D3rBU(m0$h_}U@2x^L{sO=B`PpN2pw{4u6;4DM^F9b{r zk5*(Re1G2L&dB^}liYP%Hb&sv`<34hCSdyKlhypw`-J zE*;XYUNTX20QAWw)GDVliimN-eE+e=RGeh4qi7+2sNly;$NpEgp&SH!Y5Axeler9K z4ZC$Xd@*XQa}l4xn94+UVI?Sbp*=wZLXLe5zkc`=VL4S2P_DGXkQ^);-_xfoZ>vkL zmShj8?x;>=C-1AB%rR1ut1U9Za4v9KBt|)E9luyMtIl1gN^*3LyVpcnxOZCaJ_iaN ziDs^!_x6{cViW{lW+|BW@mEq9juKQc+U5z?@DhGYOg}C|nX9>cI+yC99MOw5`WoNp z>vWZAwZC%XbX{Sn^wIXH`E$|H7J?p?0&V{5u|P-L))_%uRTt}-cejXSTex7L8L={p zP)mICR;j<^#OEYkv~NbXxcwP97cb|O%;0;^^b1Q!pZpNnZ<)VA5XFC+-kA3-Pz&k0 zd>&gpz-FbtFx{q!U$5+WlR3AdULvf<4R%=+-5Z1{j)sO4r5u|O9QzV&^n)UH8Y4MnSnc|{BU+MKbSr=yODx%wL5xW*6%2fkGeIo(x^+Nj8rr!wO4R`1FY z$%W=4SxJb>cEp6)1JqUL@hR+Fygov*Lr3JR!%ycuK1$rU9}V1K&+|M~(2(DM-lshO zbcO0^@7j--cLmh_@*HZEnhxVPu!Zjhv}+HeRLjXJRF~pWs#x)1R)>FDZ*q&aqQE|x zbaE7FEdN-opg$PRZm^0pb2L0}UFaK4J1>R%21$nhV9ELk`OT}d&q&Y|+VMB*P4EL&y;8!Cv)LP7^_-uC*kNb9fcP46u} z)vhUz9(yqGLO z58QEu*EgRt=;;2ls|t`b$8*?U$w#yaM(}mg3-NWn#?wIwFel(z@H{|PEYvhKcoUaZ z>^_KTWQx=S&5_kqpWz{Cv)#1A860=REMmY-xR~rQCyrxqE-)rHA^Ay8PLKird;^72 z-n9Zri^F;%U!_L1ZI@MF_`9`|F|ObnjBM+=c!xe8foHHuLYts@*UJnFHNu;KZP?T2 z+tC2^ht;&@Kn7(A*~d0KKK!Tvf86gd068#2pig@L)S(<&Nn60lVI3l}m6#t&lH&=` zhqu0-kNpcrEpBrOB-)fP_1FRuTzfEr=Ii7A*$E)FV*J+h1s^}PUr32{t(GF1kRHj; zpsctV>|{uuLOQD#*-?|+)mJuN-9Kc`>1xv-IH%d@>{6Ib8k&@JV$(rL87H*^ zf>DTA$!}Nt;4$pe&>#Ypwot$8u4m6?7! zp4~UrKPLQ(E99oS>Mr{M@5AX;hiF%KI9@bR!@hXx?tvqz1IsZS+CoG#12*{1uDwvlHYk2 z9mwu2XJv6Kvb+nORX!1x6MWc%0R7h>`(+m$uYO~jtg%qRp-T(cJt_C zIUV+rQ*ciEhp+aif5<2M&l&U7IGqkAU0a+=7e+G;9a2$Tvps;aeD@uMb0bqX?e(-W#Za)J&pIP9kR~l!z+*Z#e8j`DqovJ;9hk$b*gnE9a;PH$_h|I z%Taui>&fsuNf9D&EqFsjW)ohye|-18}an=obR z=*TU_BjO1U=AnIRJf!RH@_ZJmnhXqmD0L$HOX!*h>ffr#to2+lD%^6t_mZLpjQLP? zE^$MmJ$en)w-1d!z+E|WFY!!A;$!2rJlbaH)V2OhV;eLS<*tSF3*--Q0elCD1G0~^ z=q8f$@7?j#)TmDX6a~7BVWoQPrQJC759N5Zw*q9_Wlxncx!CMeYL?bGp~v<|NdL1e zoHkp!qppcwp?eeej*VX!(^4`0AlnlQqlAaZjU?Mc$XlZ>Dsn1z39`U&l$+>dr~T3FpFLwY^r7S}Z z|6BO1*j923HsSpq)~~IQ`-gKoLx5Fsr30SpMIP{2IXo1-}0p!-C-#hL&YF2NFk-@(I~h==3)C>M{@O{rngA`r=sPUr5u>ovkiiVX(i z;-bMm+*|Ns)|Ui5n$@#%>NHuaHcRObnBZqA@IZaxcyvDU(`zHSfLHpCt9>2J^8@(^ z;+6%FdN8&?TQphTPCl;1?E&mWPC6l*q0M^O!sL#(v0>(}z898me9&=xl#+hR?R05F z#aQ%cgpV-Qg4?mubM1#>njVc>j-}OiTs(k)e-EZrwaP!y!CF*aE6{k(3K;!~hp*{C z*39eh2wb~0he8N}Z4VdUb7)~Kls(rPeDts1!FPwPkl=I1Kjx}GuFqrqb13G3nv>@9 z$(f~U!@+IMoE@*Zp6K+=s+q_9`_P}0BtIJioz*p!Wz=6sMv-y!euJr4 z<#1cu6!pro-Rj!|Fy*n3e`Cd+(as1*T~sJeX>kM^X212FX$N;FddJCgDV7_8>oAPa zRO{8!=(am}QDD=UKP9jIQHH?ji4c-60zE@Y=^68IG+1$^AFSbSxe`{ zU!dVfXD@v{9-E0^>18@`&9vZGK4)CB@xwP;EC%=bDCcbLI1#rDF0)r>(0M*3<_G^ z^8W%9_XEgefAq}o{LcuTf17tExiZtfB|7JYp;Qattmjs$J}9j1?&?3#=@H0kzZTr1 zTzTFuiDp6@fKLZYyYE^fy7a`hh0t3Jj_SAk40XRzJmqfh^sg$qqSJp4xZ$AmS z|07J(4eg`A!;k|oRmGV}5o9pm^gZjb`YQXOwsv9R1x8ryv z=R|o6C6(tM@Vx8*gwmjOw%*~kfOI)vIyX4OJ&ydH>-Z;>Gj#6hEO6bXk_&jWS2pl5 z76H5kFseQ4oCU}or;E9qn*IL*DW9DDdz2Gz5>{|1KInzTo)wh}rw2s&jc=K;kmJhG zf>GYxux67d%A@%n;d1T%<6@wSsLjf07EO2UE&FWh55P=tjet`Vt?5mTdYUf1S+okz z*!r!I-!`dBh&q#m$AXu^yAgPQ4IGVd`~oF@VR=k^n0wq_>=V#!$;Z5RZ+Ejd5J+`^DbAiAFfjxZ~gjy8wOzN;0A)R^sMpB3CQa}@&5LS%e9cGC0zKIbIwiI zAIE1lG>>^`8L0E;ejHl)x1qmHsLaCcK~_9@HJtoVI8(@4^rwR+PB3pL@=8Jgd#g*{ z+?W`b4g;=sx20UX{M*sai#`4}8^q@UFZ|Jd?sSVg0Mky$VPof*Zjm5>80`Qtk*vZL zz&1g9kNZ$;LASRJWOAFW6@XC4^$@!Hh?~GBC1=dkZiE?)l@*ML>+RysTy_5_i`CXF zAnBTjf-bhVRvOBhW(wtD~3hZo_04j~h32=r69}5{cnIOE%Y-j>tRG29t_|M(SRTK9w5L{!- zL^bbr%+!TDPnB|Fq)i4dLGZnU<6=#O3s=J``BgWN_5KPcx548xjh%mQ zUao~4h_>S+Ku@d>MwUJ}h8~!J19<(@xEvl4x9#4j=&oC_xvLe}6k+;8Rxa)S;X6Rs zf@M>Co=_cgagh~6=*MM)bG>aJp#|*K3fQx9&klyv_|br_SMWO z-GSF>G5j`CCnUJ$*)8jJOR-Y21L4+L1{L~|xT!Ks=b<%Xdl(OdkNXFX?4{`BS0^=3v+r!9_%bkwT92@7?APw!`0>0 z9YD+-q>^!Ub9WD^7m^d8Avo9rMgs-|bpny)?2JIDKsF}wn@ zyovdGAkX}+1uz;X5xabmf$wFJ#yp-fAny-??SDz;!Vyl$h`F=j!>neJ>6-?6mt^wG z?1u?G-2lw_WkdvANu$TBi=7A~rM(94>z~@#2=l~MjMGsLs-f1fJV&d{bxxMWLa~W( z5m%d!(@q-n6rm&RVsp`Vm*3~?@2P+A(qkLQ@Om#l>?>{RHB7p%-H=Oy!2kF-#V@|8 zwVxtMQe)A`6#=mm@s8;CNxQysu}R}tJkjolg=d+3*^~!ZQ#$@mN7B?&lVHN%6~v5V z)++|b29!a=w!R-M+ra;} z#bjgv2|RjEHo*!TbPK?c{=&sZAVyuOt8PrV`LjO84`992=3^qmrBjS`4 ztDtK&gxA}+dug7fLB3kbL?WKuzG=o0awKAo>W`T(_6zooJ2A!7& zXLz_COUW-;P#9P}JskuhZsv1mkkrZcnF+)#EJc{(lSJ@uSUig7?Cx7xDE19Kwp_eo z7K4h!aBZ1URaL}mZ!QZCEX{=k)(v3z!FyDr#zr)*XLO*ztn}Dz5|0n*eSpsAtr;;v z4Xu{iu;PLdnuAFSrH^myECpUnFvimm)Xk1~PNA*2J|l95m=1qRh8b%%={}@CAloaB z3Qd47GD#Gdge=leosnx8xzT2lt-La(Tj=R;tvA6Dlt<)TtTBDwc1!ms%DatAE^~Gp z9z_8$sspR2lWkWqD4%|!07_OjZHQ@vnK9n092BJdr0p#-3Oc?vG|iaAR_GDu6jzMc z;T5{A(l$&12G1Y1gv>+TstSvKTDK~!&K23GxjJq7RtLxWEYzlK~AtBi*wJ!FcFMIv#10bR$dL}-TN_A)+e38 zA)+5RGO=dce%-9>P6o4P2@xHbC4?&*!}FmKnom6O-PzBm{`*A3Q2})N)v`{}Z78~y zvtlSgdna-{Oem7PQ*8BX;jkuuV8#H0K5Us+?h5aZFCSVT5Ez6H)8*N0YrsdOzU9la z2t12*H;4LL!)e=%Bp0EB#yjx5C9UnQl#~X`6$Jx%FPEVKhW$}yG3v=tUhQlvJ#x&} zuh;cRuN-mUcl3rV8pMCB*#7WCsR3@kS5aWjvkvP|nDt$U2#cl=kC7UP_CdbLsLwT= z9S>x|(sFya(Fh%60k8@7^iOtoh5_-FvcPdL=`(YI;Pe@6s4F`oK-jM33O26ye=cMr ztUpeRKx&nxFjV)|y6fSBBc$NwKxnyJ zE?+vzBJX*LaJ=sdXn3H*`;G6uhBrjGRS;abK0QvYigMGqJ#AY3WHr^WpOAGPR4}R- zaSkHJCOKt52UafQ>hD5&q7wLIv46>~@I)(NxF|pAk89vxU3zLbEzuvQ=g~$G+JUxP zA!eLf#v=dWpLfY%R<$_7{xl|Xz@f844c&F`n@Cucaug);75XbmcEbB4HX2m3zTr0V z@)H zEEib68_@zrtZ%R9h~69{C!otI3q( zI;f>4+^>%DZTkCaPh@n2u=;9BN&yK_Zp2b7zlN!|&BlkQr_?4Mz3m&t#_F%*ce#NX z{Z3ZX8d+y97}hG*aC^(_OzLnQ!;7cOp+&o^r>t5H4!2xST0_=_t8g^YVL==las#>I z%QV>i(r`>TP4ea@<;pm`=Xq%=CbE)oagm>HzPOYo&u|fYb63d4%-3^13k`)c-R(N;(<4RF)>XE6twSt_2Fd?jO zDb3XIdRrVug+^kgnaD9VyY6vkoTGb2`nzmuSjDmugdci?E5T_Mc6<_B^{V{aC6ALM z*SS?8K@pPQgf)k$1Fil+--4(}y;^9vRlLHy zf-L+SfNZ$0(H-Ye2XAp<*HDqZ?wH(x*~nhB!eZ10-LTy@2Odt(@V6mtJ6=vjJsPN~ zcz(~gcm6EhCfvg!wmhbGI?eK4W9l~MW$ZBSYiC4h7Oqe4egr9DU37BYqS|D*wCQYd zoJgB#r-mZGMKLjMXUThv&nrHVJw^T^NH=>$i*P^GKC!79H-D{3(_xPnwZf!Vbu)qm zG@>+T(HNE#6rMrL)IC;S6lHA^Mi$59@cXVD;20|!-VZ+-noSgcHhY3}iscocfJ?E1 zKtQ$DE&k1>wpeh~zN8UQw~J7TNNbGT##s0pYz&pT*=_o)3&!-Rq?4QhxYG z=y|w0+E)u$0vMmN=pL{Q%)VLw!?$XZbu_R??;p}4IAnuai@2CvF%K7-$2>=Pa2h9vo;ai;DKbJ;pzfmq(mnqA*whaV^ zsIQxv7gKpt2FZ=QV*Bv9m_)pf%&E@Ep+>IR3Fc6p`>9MUt)xdZTcBKXI*bmZp~VuS{vck-^Q#S zYoU5BdF)eFylGTUQknh((yBtqn(N5jfB|uAlq~IORhz z(4XYhk?7=fP;1Er>|y2Fube?OSGC5|E&hI!R)Y=`rsGSQg}0m(9Z^363vEI$bjl!@ zC$w`bK=(ced4!AtZA-XEWp+wG;RelV<0LYF_*j;OHH{@g6K)m5$84MtrR#KfVW}hD z)lnz-=UpA>mTHMl6IvckK*2|Ra5-Vi>O)@6h<-l6Jg30Z*0RK%>+-nbBsoifX<$Gt zF0`KO0i9o-$%rGtPmgeyDX^^CciJ@R>?3T<5t+qT0Bi_*z(7W`EizdUfQFZwG`uRH z)U0=1ja7#y$*k%JI&OXC?x3|=V%KtCc*0IYa+EeK8F?`Lw^bVT8Z#61I#VyJ!2#t` zp(KBstgk^q9yvN+{7K4}=InZ{@YK99x`^_l@Ljabl_2ilteWOyO~X22iY;+2Dx@T$|8o3|#xSs) z*5reOp|yG#7%dl7hsTInC>GvD+AuY3!>6&MQ{;G>!rZ>1L3^4NTo*kte}P*K<|e%Y zmt!pmf^lvc{3xDzqyxoV?inuiXV&Sph;jTxi}JN1u1Cp7v}SZS$$hXET}AjC0J`Qm z3cA7lXDj(@<|SxzEbZFQ;d$8C?MC`;%6+1Aq59ID`-RiT{hm=3hwXm;C|{ASzkA7X z;1)VP({#l9(0e_Rop5$wvYyWzirx(5+;3lba;wm&Eq$0V+AVi(=Kk_1=HX zv_ty(08;q$>u117L$05`Spe25xltZQv76E+YQ+%jAF4IR8={{C|ZkD#MZ2 z`C+qxUs!KxB^2?VIzMhU4at(1rg#H3 zrm@{ro9Y4v$uEvF^=f)KgaW#_<^!?^=v-I*z2wK=dI~BV{L)`5-iyhkC(3+4{g@Ue zgju?qqp?DJ^4_bC!vEm61yeh=^EXY6Qu(dF>3CEM<@f@J-P!}qWyLhAAC3ciax<+Y zR4yfmF6yA2p5Vvq zzCq%s@SPzvBI!A6w*`WD4vi4PYC;2UoLK7kWKfzkegWzbzhFPtKmVflA3D>U4aRv! zKTzJU*Pr4KgOD2+IF#Tul=DDmNX@3Xv$Z>#c1u>dJ(7JOK-_mVFq+MeXgzgn6PDW<9}*n--!M2(Zzzy}D|SJh=J4P*B5sNG_bw$*z$TOVeRDFe(Y_=WzOh2+s zHEO=7aJ^huty*zM#};I!tBVuR=}@+jB$RT@$_q@$M+}Yu?B#PH{}E&$dhUBTOUN%BGFT1^x(=arjWWVt1N{UYCuj=VeeW<`=`8i_ zlNJxhdd8Vl8VK4rt?iQ;m+o&@Bm_8Oa*tv@sp@F&;)EIa8=4@m+ulk2c;CtIM6a0e zf~$O(lV4Yb@YuW-A!l@yUD$SloVRj1?e=h_$lGQE~qa&1z!hr|5zC%S!V&M-!(xak`b*shzSEef%4| z$mAX*Hda5zYl3fr$(4z%To6WWn*u1;j|ABMyUf?=|32o25>WH$9fE&VKyGId4tRbW5b?{zUgTz*nvzCUL8E{rGKzk#?|z<5&%420QvI%>u^BI#{V$ z#dan*eJY^D415N02TI@HF?o6wF8bf`zd^9UUnyx};i$MCwQbL#xdhuzvrQ$%xUlJu zlhWEFk`PTn<-fWjOXLxQF?z?r|r&UhD6nSn5Ft{t2 zm(uod`0vYdt{hLOo;ThA>n`>nn;Se!xffQX7rZ2^r~UlcXV7K$Ger7X^yq#?^_BM< z!1ZFib$Z6JSN3{```XE97?hT#c-20PbPng#;COIAP2ADj| zr)_g`)Es*QP;qyVzaDb@{}1(l^wc^U{pmLTKQr$7vON{-|Lr0BGUeEEi|%IO4r*h+ zYpPzyenGZG;|joATVz+It&P;u4v9C}5iQ0RIFv=(^slR7SHkXEu#N6=#upPFAFZqz zwz-y6f+L(Ip;d@b0~@ulT9(Xv>=m46O9yBRe##Bp?4uV)WpiLLXQYeAWv(!}Yz<@nG2(j~ z-L|w&phU7xUhbuB`e&eOz#8+%+`HfXJWDhf0>#dGMyDOghRv4tH0VHY8~t^PUwu+X zpL{5?2(>*v_{H~N635z9c8%_oMU8?Bgh$@BC2k&;S1ghgBV`UY=GCJY+u{52`LSNf zGv2`|n0v-Y9G2w}}diJHFSKosB*AfOVh!iLdTw_I|J7E$&l+2d%alkHeo zC&FhF7g8cH$fq>ZKW4_%ql%eB!t$vTv`Hb1+$6^uRGOmM%_2F77Fx734N9_;)n<*2 zMP&)OK>=xnK5Z%IohC*Oe??y7%a*9Csli~d09-O_hY=-OhzWkzMeN5qX-};pLH5w{ zM(i^=e*+L~>6x1W_q!-AKC*dEE1n%-9o3B)9ep$1Bg>0yTDzdnaKY9W)TUO`r~^_A z+x4N2I((M-GB>*QF81ui9@bRnM7tGyj@N0hqlOG`CGvG`vw;?#@mj`wVQhet^_%MT z$Dkx*u;Z#GLcSi9t2oE!YNUePg3#Eh#!wTY$<^;deBn0xbXBL3{Y~iR5aKk0qdEFm zB{z{(x4-+&*+#SUR>nQ%XLm}N;+m9?E8i*X^UCvv3`=6Ceq@NXm|?>#B=Es)4bUpFtP>mhc@X*zI$e0&CpI!JCi7 zK-!9Vb@w!s5AIo&NE&o2;KA>&!)&it>AzO>tVkuy#ruz1M3 zij~D=J5SXRgMpM4K7CAMj!47{pS3KUUu7zZD*KvZk&~VN(@|ZBhnxAH-ySp$a6RQF z(t<{$kC~!scC>DLEKZY%W@i}Ns>-)?5Z(Yh`LDvkTQItJ+p$adNBelMwnggM(*9;h z$bo4>Y{1bZ72j@u_2u3u<3$McZ93RFb?dw+ftAfUEkL=W;p{J`Q^^2 z?yX>g+>*oAD-8G6{wUg9n(U#nV#O1=21^BDi)6X1k4f5cE6k)UNMk+rbdiD+o(>+1 z^Jb6x8clf}tlE>#zVUsfV=l1HA~Gs?bUibccD_d{?rJ05NoV%f(9 zL8C1uskQF;0vhyItH*+v@G3=L53>$gOsjN?Psywbf_)@xV#StiVflIN?hb-x9PTt( z()z1UQV1uhV!9CtvYLxOt)3BOWkOiiWdl_k)3kM>HwpY~$@YC}znisx=?(EJ&bqD? zPSglMY9b*l{1QfcON{=r19xfdy2VWBW2n`xxWLW_Q}v*V+ReDK!x95aoderE(-FhN z82Q&F`jK^e@q1p9jXSolb|%-$szY0KrK--5 zgTgd3yBNc{!527Bl;0}9hE(;1@drnI)cX9Ths~cQQUT9sW{qklEvJT;NH1WO6?$#> z6TCi7Kc#0S@I%Y@+I~wtQBFhqJ2f}DsCYA5AwIrd&tJSp9gTBV6`qhOUD}l5D^K^r z7B{x`m#XHsk6_h(WD6Vqe;KGg23UaqbB&#)S&AW^`J8t$Ue7PDkpLsYwZHvf7%ae- zDDK_&j$b9>eoJ-@WaE~{XS{Sg+SPk04)dQd=s!^;~0Orw9YH9Ixqm!Z7H zSj8e-a36}!qWo#;_zB{?4f(>-b5bh20WzB6zwq_u&GBhi5vg^pQ@BLgpZ*lhNScbx zI{JOQbzNWArUU`I4QUj1_ziBqxmZi}tS;iEVoE$fYqa9@0H(!cO=2=C5?sJIh z>Lufig~U&DoR%g4DeHL5g-r))wv|-P6imzFvw{U-0bfu|;fodp#*!3agxxN;RyZht z7)^KTa)->a@xKr^jk<383><#;_4I+QhA!V$f8XUaC+cIe`LOOt{~J1qT7 zxray=90|#`FoZ*7Of$?857J@s zVf1VYhg3)G>o!*wlc`eBb>+@te0;CFE1D{WMl6XV)3~El7@==j%@A#E!%{;TE*W zR{O=ZFyeAI^LIt~FrXJ_!JVidDJ}m>ctExT#5_ZFL~EDDPT3nEr&V&?IDz(%`B8r6 zHOVZQXReurR3)bZQ+v7SIVPUEqqHLhDk^2=I*J~>h<=21y{LfjLij7803@?QVPlgM z?>QMBT-DHGle6i&_Bw2rEHnzQFt|^dl_Izr;OGI?b8V$%F2(D-0+*BrRc2*225|Ci zXOR{3MzD=xhu8C~d6`8?R%D(_qgntEJHX;YV9u6pkKlp3N%k?@%=&`D?Hz@~^OFnF z>hv+HoP7t;frt_JDtLcCNtu zMJYB&KP|=fqF9cySLxH7bQc#}2o-*a{471Whp$XTHJd5@u$fAeUdjSY+z(lNcEp1t zO3KwhtbgBD{X@TuC4Ke6T*=8O8Ru{wQBdeRbZ-5Lsg}O#cjd1H@As6Bf37&fPLb{t zJh0aWN8pY&eom6ufhO4O)Dd{cnJ?YtG*(N>C|npYsz_cEQfTqJ6=g|br%q;CK|j)f zRxdQ)R#)r?V^GtWM|MS9C>5uss$64Da&4iFD|fgQV6pxk#p*%CmNFKCvoNqnbLqn)Q1fxb9WScY3Xl!Poj0} za0migYK7jU$Xn4``aXNr@|)J1$B8cS`b3OrX1(GL8my%bq{vjJ!(ofj#DvmABQd&p z_&J9pChvyM^|9(byg_Z@DB+Th2Hk${P0pz9*s2&0^TEY@qe86|0boss4|zllU*Vm@oRPkddO-u#1 z(*4{9pHOT&xV=K}dw-0df^T~LMdT3+HA4yjSb%8rC?BAh`*Yk*$$sJSax?yLf%WYT z5VQ1eHRQjD$bS`+m4My=rte;}+pmx0+VKx5(j(oPPbquA8p+ZaBkhweFQ~_)$6P(_ zx-PRCYuM+ISNn7D9lcy%@L4#ms_-`&^UqMeWQ!$KOS1_!TKrrQ6!b5K&u1XeGY--u z-TeZ4$YEk2rpJ5-go+-vw}DDtVWldGc8ff%6YAq&#d`M%itV$qd|T!ib<|U;3yYG? za%fZR3yw{xi6(mLtEU??C&s25j`L6l8`Snqzd75ki>HBdJs*PBYUDjWx%xTFm~Eu zLj}2;*eDjy)n?&}4Yr1BTD8rmgK(DaJ$O;+2H+2T<)x8vQ;V0`_)6agqIbcT&L^@k z;q1P*zY-fy*`+_~80jXveV`9SEMlu1Md z5i{NGzNmAZg_CSB_vHu1Ro{3=(*tvDDG#HyRUgI2Sicj(PniRhR|lOJU*Q~Bnb+B2 z(3YlY*jLvX-vE}e7Iwkb&o@Mu@kYhu89`qUmURjc4cgabq-G@p?xPXRGmn-h1M zJo((^1U|W+6sGw;5=_>O%>oSyZep?E3ilGK6xExAci8%+l=_V{2B+PAZB3gfJ+?X< z_8aBx%#!ejk06;3zsyn9U@z&gI#6UqKfuNg8nV|a-8l&XnuwEsyz_ydays?9+50uM zMhRjFR?;laRI03Os;Dyo-mu*<9Um$qIDLKLIKQ24hg)UtwwU2!a`d28x076xss579 zGJXU-kuc!X8C{oh<##u8%QvWpE8Cs^UUK5$j?cM^U+C686QKqV@{cgnE+oA;jBSsQ*e-t3MSlnl;QKxCVrD|PUC z#G#>T#8ynynYOyB0t+%#nFXf5qtEqS8~zP+fn}plJ?mpKi$}eCLW@z?NbG`ZxOr|R zB@mIyxzF~iW9p+~y}o;#HQbAGf>kGP_U#vxI#QtB)GJ;iVq=^R{}hs)VS@KwYfIba zn6)4UL^U?hs9T|ziq9NtHq2=P>~6zLW805z0g6sa#A^3S#IdHx3{g!KB%GA+ry$Co^h30nOUpu3qgrA`wcklG;>PlW(h7Yv zMZ@3CxQ21w*exX%84*J-EwQ9kP9L6woJ9LxVAV5=8($1|gr8wzN<>K^RFLN=Pc@a9 zIh;xDxn!$|v2^{EZt=S9_HkCnbaH-|)BULb^;2VoemSg9y~AaPv`0*v4hPn8cWu|* z9!>HiN+PTl1icwwd1`5Qc}H7p?N+%h8CX&|z!mAm+SR}*=?QLa7RHJT>IcXDxzFbM zHTU(8o7BVj6H4957JpCt{c)e7o`OP||Ek&&A$*(ppEyDQrzJ9D5;#;5F1k-(jmnZ1 zW3n&&kaOXk{4%J2USlPHSdf#wYnKXd-9r^v`e4Dz)482RLA!WqO zvF?#>QR{W((TZ@RQedC#^716%4NwkL?xDdEK4`uud8$aKyBx8V%h`Vla=JbD+`W?) z<_%Dd;nkA5xSHPhyoxWc#eM{00M4I&XbHXitOz{AZC$&aZC0#v*#il-+oR7GucyRI zK48bXZh;L=IqJ6X)LUklxfD2J{A-*A2dLd79pTO10A}E%3uc3SV+7iB`%;$&mBEe1 z(@_du7`@z@Kb&EKWdUP?IG+ zjtKg6Sn#tT$(J6HFXkg(MCXt;PToo$c@X;tBq?9k0xuQ5B-71-A|Y<17Z|d`N6~J0WDUM(?;Y&__5ejDcHh@( zzh+Xas$dZ=)lnA&EW54Le^unzvf_vp6cUSPp@R zj0a3Dsx0U!(AF^%xQRilE6Yh@#oaU?4b_Flmg1@E;%-=pk7%ILx^?!C(fPnIa2@po5)js z)mMX;*6nde+MD3b!wYxQpnxU?kxkd|@6V?15r2&@R_)iFCL|}JqfFa}+3?Iw>i2=t zt7(G0pD6ndZc+V=ED~1-LsE~2i9A!O8{w9NDJ~QLubt88uuw{zE-WLPxe{l17RPUwClfZ zSG50AfX|PAZ4aa6xi*Wsk)U_fHtrK zYMw)(eYpi(|9rj!e@>6gn8-gUFE*c@!+VC5M$bGjxTfIbjjc5$dREt3?_flhBskEm zp~_dj>?;k@G=A!Ce(GZR@-rY$@<7)HRr87Z=tS_owObSBj#nD(-s1JUXIDZrhE}os zO7oK@icT>prmA@v%*RzpPS1+cf?);RmF0pxWa%@#mHu85dy22KRisLND8z~UA7p55 zHFAA8l5L;cKS`r+yJ=`T1?0W=Fl+o{ofpjlVepA$+3_hxpp{nJ+`^3~i~97j!*wEy ze2Fkpv!d-_5|zjq;>q*&bro4@J#0oN79yCeJ%qvF+O!&7csKXr zX{vWzrk8@P%=#f<{s&@qmK>4p3cIoA96hgqELq?%ys@?F+~)jknTz5-Ty0BER3?uP zoJ!tGoatLIaA)l9#JCD8O}9@H$Mu<@LYrhw{}3|GD4z*ZA(HE?Ie_0AU<(G`yu$pM zj=SUG-is95{&eCjl@pYVx3wz%-qxYtec{fs&i`5}={^13M}ZOqZ{RWvyhD2w%u)d` zwEQ-821(IlXFjAWcI!v4U4-3LpKZEP zoAW$Oh9tak% z&!A&~bq@RA0QdM@t^e6DnkOI?QE?ypYkzZS`hQ&g%ss>WYaV3FUi2cuhUDD$pWofK z|G5z@SLv3v#d~o1>MBt#$QdMd5)g*;{M60@tRT5zWD}N&fA@@cQ0Jk zb;7$V-h7vHwYiN8GFYAZ_hskp^{?Eov+rq0x)ba9nnVRNA2QDfPf1(1!HgiC)xM=y z;bWc`=PgbR|5siuck}z-kc0bM9svP@&)SWaz*4$WJqF#mPAf0ok(Z8!=z+pJYs z)ZcVW+nKr7oE6{LNArRlx`H(M?=lceFYqc_)Z-A*j&C{Lli>epQ0pV@#9631D1mF^ z^lO(>i%#pwQ-cP%>t_&B*Xc_RTNnPbM_2khjQDUlxVxLdEo#pE(;&FtZ9z!>lg<{m z70ui|(5UPE+c&%q@VxM;zuC+t&Y~s{+zg!qnuT#S=+|#KSIkg3Q3a8vKy|otNFm$~ zIOMzdn_fty=|K>r_!zQHe3FWz&JF4rm*AfIs{@w1Cj|}RdjlA~@OC|YT{7_HK0O#} zf7NWAIm>ct?tfLR=H2b?<6NaQ*vYo}zT zn7!f#57rWI&W%IA^WvRF3;ngU%6t5$PsfmE?LFvdNQa(SKy_!=eB0%TJn*dZ{kRrH z!~@=^^su$volsFP9=H2J{xyv-{$3y4Kdy9ERPFvu&^JKk*|wSJLFP5wyWGooaoT&atmoWfK=!$2}7alF~X8311xApWe5)24I`A6Id zHBO|FbbN=!oV&lrP1AlSr@`IL`>_XnHTSX4pLw`suY~8{mL$oAM^_8R36Ve(?n>ze zA4#7v&b!KbdznaDU?OXTLHU1pw5hN_wq4XP{&9UYwcztMq z)HCi{v`ikzY4F!GUMsn!zJUGUzeoc8Na63wC(b;!XRkF~DnsHn}CxMc-J!rVS?-Bj>#5ruy42jD8%11OeH_>X zOS5VMOXV-VrEPs111y(YHJfP?O(A1em*SbrLc=8XBFu(|R$pb|3=4ikU{QzEcJ@aQ zW!!{SzzFT1{CQe8d@Tpkj~bj!+>`qL7Ga5(am+I*FL$A?-}~%TI%?=`a&ti4RIL%T z_hZ-X4Oh6u-`jZ+Z0d#G61{N3gffN4e#Y|g*{N%@dF(hP&TxTecFUMiBL{~YK6tUt zp8iKyNIq^-U{{;mHKoqFaVLvg zuV7Yi4WXlF{|XUZk8UEO{&xp|_tk3yxKlA8fneHl)4(++=-*-S@INmDM>@aHOBudB z9{;uS+($eFa{d*-+rj<+26#j|{(SS!m$QA-=eFfp3i-3nJka09FReTYkLJFiBCPxi z=n3zP=|66a`r07!WdH*l6bsVIF2lexqx65D6Ohkz>79-@=AS?Nf+oR{-WcT4c?V_EJWT+yAxu@5Qp=?)Ukxka(cB{9kdy#dY7v zh!mVI*2bHCum7wb@OJ+1GKLRUjEy+Z}rKBJzsL< zdEpLy^YjKWytoTZ5!5HpD*_2z46_RBJ1|@z3m&o>*``tP%HU6 z#v7oRRr6`9K3nk~1m35ZO>dt|J+UL*TXALUo!vc9wx4af9v;I_Yy%g#yN>TduMd;^2wfydDJ<~P7j z+2u_OX3wz)Q}XxJ@}!Egz}i5)onhK`Hw3lTOOb7mxsSq0Z~l)LZ}p^sR1e41h|j>~ z*Bu7M>_f-Fp-dsG#|FH?OB(f_&Atj1+_7)yrATYD+!A$$_EryIWI{v`J*~2zmj!yJ znZudNZZeYc)~Kdsj-Dzy5a_I*Jg|b5?zl9IJj(|HG8(A^Bz(ITgSh)8=C(aBi-j=Pba!I z%+`bwMU`yK3uTQRq9IW2 zg`i~+7x8d@EVy0ql*YEURkliQ}ryKkFD?<096&uKEMUwa(@$4)y;+I zX7RWwBHzF-Lrhi`-W;o^20;hwz>{JnLW-;XN?1Id!la@>!}B$@yG zTq_-ho5j^4-xYp-^4&d-|yrX0>pa7L0Sh z8PGhf^8*{+ea(8hn_H>h2Ds!4MdjA;Nn}N!t(ab8-g0|e8RcSn^Yn_I<%i+Ah+A@7 z>dW@r%Y&nX;|5Z0xvhgiD5wzc795C6!4dneK6~e|dCM)?^#OKK!6piHwEC^o&cP}6 zMwdN^M8J9R`N6gb8GHyT4`zPmzw#I5zY;z6O1=T$U+kCFX(4io()^Ou{l$Nz6j*-l z6e-dE)JH*%kgA;pNAVQ`Hjk3(Cy*V6zJr|~pzq#&^3Z)d6ZrSQ!;Hn zxli04`$LcH9HX%RSa;g)vd2vi!dXY^x*s2{mOhK)f)D ztmY9pLp~xCqS24F#{rqaaB*-b(|7xk^Mu%h7KhD^Ia6UD5sa_J(T2ERfco7p!cr+> z1-mcqVanv4%+FlfJ|9DgJ(IZk^k*Tw(yQ=45$PQj%AY&9IlSbGgl`(X+PL@RHE_Cq zbmxb?Df->MpG_r4(T0RHj$aew4nKaCZZve@<~9FRS9|dctYE$xjyeh>9ZXAKl0Q$g za?&(2xYH21l?nLoYa7h|4}p~5ka^TmN_ffq)sZdq!toM#T>XQKZx4c`ryv4vmw(^4 z^abRS1*;J5>!bp4G5xE@!4xsUe^AOt&6ocvl+w{0j8bl5_7W6x8 z7O%Aa{vgPf5z(xkX3e$j23hQ#4~LCF0r*!BPv8on*Mv3qT7K0gvnL+T^Jg7?UN)U2 zsjEA$fOM8enP*MAfVx2J@O{WFu+>NYuk}N|mr-QkB80y*

    3Kny6*W31cP6Lg3llIp1uFguUWU3CP3)7IJuY^ zN}9-SYJU37{S6r?d)aXZe*gAG76X@3#0a3G;dP$e^PQcb3UsMWPuA7eTdbl8(KN#Y z5fvOSsRE+H(G3tgd%Sa!NH+BcQilSV=}2S?e!}_y#H3buf`Ts$K7ITaZ}Wq-2YR`- z${L6Ho%U{u*X3f0Z_TpqtX9R2?>x43oyo_p>!{jrk_TtbfeL~>p{N|TpG5(%VeeBa z{0}z4x+YcEWVpYz8bk4z<{@){s^%X{{nQN@lUL|3gx17L(JLs&L!1Kw8V8kf%M1`E z4n7&KKJKV5`3MCih(StC*%}=-`8(R0AslzZnLJ^wV*Wtv(xsGcjdf}3pO?>!{jFt| zyoF*LBgQ{v+#2ZBSXKuW8X2A_Habh$4Lg>ULoZ}ABE{+J*ZZL=qnG8u$g_|(@J_{K zUW6qZOE*wWF{1j|6ahG<1r^TmJp`|l=R_fhu z%9GMEXN^e(WHd4W6oI@x`Z)-n(vapH2oH4&I|Fn>=Q}htOsACzjL-3L*V2`j6ZE=M z)dFW6k?@hp5}d(JmeC}bXxrFb^Zq&?1$HzE4+@!o2}BM~#af{B^y`?^_rH!(JvIHkQgYT2KLl4jqmNNv>CJMC^{qqDx0i6@flz<%7m1ANZn*wVWWH(j zHiS9>Ka3&U_qn46qL#QrMZP`exEv`dRMy}V(e~)orGQf0NQdFWwu#pAW|6+$q>>qa z^lxd7W_wh%`C@3_BF|sRVuD#A4C7r`>mO5nc%4j8I2eI!J~AGsx16^`%ePlscRW>uk0#iGIKgpS*KEU`+4P`LA0V04Ut$vkm zVr}%U{k~<#N2A`2XH=4QMMZbi-sBXc%rs_&u^1uVPP95>ZnBVZRJid4#dW|6Toj&Q zY(xT#7J!upz|Krcpdqutznfnz%B_EV09Anh%eeAdLej}hUXUyG)A*5Nzf#xh_3%0P zED_^Tm!D7MF27?PD&d}c4fu5J%I&IgCnz{NnLApkPhHK|G-FyEmMitQT+eYp_{8hH z;GAt?J6Nqpw*UOsz2N`hZu$*O6dns#a&9mEhbzqZZ->*rw}yZ5@4&H>KZ^#Bcb*Iu zj#FoLc7{ubU)@E}tul+6EJ&{kqRIo?X&ua7F2?z40Rf{JZXOoU7u3_Sex-b^8~jb+BuBI&zlggLt9(!itCdeniKJtdghcfj6nh-kmVUm(FF#Ya6kK0zu+o7W^LE_ znr(0_hAwQY#;Yp50f@AP^wNGG*G=@q_1F=3%%Cl!PSMcp{4dttI;!raNf+Ko5<+kd z?gR-C2(H21-4i6ZyN3|m-GaLZg4@R3-8SwXY~#5<&N=VA=giD^*InPtUo19s@9ygA zs;=&*p3>uLHbW17Zl@Dm)cBHWL{w!eGIB-BC6R={aAm_7pVNXOc4eVXu(q}&0{SX` zX9r zX+$JqmN;=W*37C~_+8d|@YZ4P?C>PwL+i#-7lQ`MYUNqWF!f|>@edWAB1a{oz&E1_ zGVt(*n#%B%0X+w4AI|t5&lDy`k@6gnv`-m2TJSmTbJN$ccqiw=4*m92 z4@PM{ltz2WOumsY_lVHZgIE-0E7oZR?nLKV7xxb}ksi%?0Wn$esk0m_?!hg+vUgDR z;|m%0XVVpEx(sFj1@ay$=B>4!vz#~I5l|xCCHyVpl{Q?&@il4eNrYT;X?+2Bt~C3l zBg3p}Z^icR4Wi+*GNj5*TE~D+*+%zXrKXAi$#vu)-S*kteLnLM0cM+EpG}_!k=A_h z(WvLxZ;-saG?N_fvxjN#_*N8G<+Y6bj65jx{dxM@Nu8&Uz|wtsW69MJUsDUX^NA-_P7#{V!quu;)zJZhF9rg;*83mZW?bAt9rJo-K!?69LPbe+*wnY=t;$XL$w z+R_Qssvp`{FZ15LHubx{LwADA{wv1>b4X0NI@Wx&a580BdRYMOqJM>TI`3Pn(HK$8 zz1{RTpUd~Jz~U$zxLczW8lAeDq5fIbfvIl~W%H0_H1Qi-PUsns+@e?>oqjkyGn{wr z;a;n==4q)G>8=c8U9!;IN?;{RqNJ{Vqn8|WfC)y(Ui;kXji=aR=8$3l7w%u~dhO*S z>DGO*nE1T1L&+7x8dQJk-UXczzo)q%Dj@{#+5+i<;g*Dg^i}f|u$t8M& z`jiV-)#W%sayt>REjtW-ult@QRvSx=4??XZp!IS_ZhekOW#KZFAv2um$b=qCvsuzu z0lr6YjZQ}^t2oQVo|yIDKaLRV82tFGJSp(?Mqc%GhMe=v^O^^)>IaUsB}kyVk()(X zqW95K8Bh@ZVLvk6v_O*Om<#(>Pempx#P+R8k?*<4cH@y5$EpWp3(;J2T@QCkzVRi}H8+=%OeU-xU_G!3M03B5 z^b%Z^?{o+cd<8M;f8PKw%!lSTuW;FD;(r;ipEp5;l&>BV5KT|q5})-jtF<}@HfuM= z_|OrcKQxin*XU&Cz^l?WU^^(w6Lm(M+T-xC?{pp&DhjH~)1sI{h(B*+U)2%ZhVtN_ z&6Wctygfzu10Ne&f40ba0VTZs8c1N1(>+~P=@MiVOQSNCycP((>y`)g6q7pJQmUVZDJ#)bjPcX1v&ePH<^Ba z&I{mB1SaSw=%*=e!58yD0@rU)>BA22Y0B)%B}qyFbR|Kb9(X#v)2?Z9fI=Rjz>COs zqW*8tLPqneN7S2Ow;w)t`myP9Zo0R^edS{hiHkn#s-5&7%Ri_^u20?_uADEingDe~ zv3+;I_XN9_Z!SU`cwPXto58?c#nLozajkA!`pb6VUkK@cB1b|6kvq-FH)a?+!5MWx zEks1}Smz98H@|9{&=BBCN|tJ6%?H|f2jXfc7)$<}paT{i9hU(e$>osVi683{pU zFS<9|o~?Opp}fPV<7nSYgqr_5ZDlt&0S&np$XU_C;!<7guUp6_2PeE}0YuRsrWCME z^ff3C>GTT^$Ohm@H=31|YhQ$%U+sn#8Wp-gQMkZI*VQ4--?!qOgnP*i<5@}{r3RPk9@ZA37lx@)bqqA6xzg6%T5o_UO1e)eMtF9?#a#;t2|Eddw_3*)EZPQ;nu2qtvLisGw04 z%))d<%+1WUhbOSw$QVO&XuN2_*u01UAC;DL(e?l3oB4kJ_Y z<)cP-)*BcnjhEHmLMSiuzg0N?u!V4Z_WbFsocumpiW82+-X;%~$}E(nb4sg`Y$ih4 zIL`VYLj-3QeJN^G4PUJH2YYy)m!6uV`COIWT0a_I|1{W9w=6YEx4kC%3%&DrS9rMQ z{1R@OwPwF{Ccl6@Y|iA0CYqgCJ+sqv+a2T5Ye84&YkPTw)vZdq?2*c(ECWok^)9Ob zn)r#3<`3hQFDW4+>hJ0WMTSzEXp}*U5qIt0E=m#Rtrta39h%(8lg4Xyyi)ut)feG` z)|z|RVM?SO_%DzbV`3szxrT(|sY|sA9T0**Fz&tP(aWyaD%c3N79kDqb<@(W!;ESz zFewi#=$9~@t87BDzRxGYy_OQFv`c;7sh+$bK%OC7{U$YU4>vv;}J5aW4_D`R97knsTednoCn}wD5kuhl_rXjcO2GL<;K3fA*wzVDshnk{c_ZFPCwju2OYD@-zxmlGXCcV;_J-_$r+hwl1SnL|0bznR0O8 zGEm+E8{L{#qyq#~ACB()8QGT{<{NkK6%?O*lO2^*5vTe;(jfto-Rm~*+nxLCaE#xe z0jqx(@eL}9XZb^lRSN{W0g+pIWw zLgkwx6@t-}tdQ@d;`=Xgn_Nh+%28YBFfhp9XhLGVO&e&>>{!Pb zLHJlfcuaDd>|n$ciQME5!MQO;u+glOWFHWLL=Vs$ov7k}%rvK!oCM%q&{@%3&Ts9g zs}Wp^^pzRq=OyEGc|d(YdN6S}zC)a6wIN#-zd2u{tE8h-`E&Yz+);pk&;IY7z=B0& z>#`Yn4>7sF+JO#WZoGlg$17~RvO@}U)uO$M*rW%0ipXSJQ_%f)8u~c$RlP^*3|D5} z?4E;n`u7Jyjc}DV>qoxc!;dy4s{7C3aFe(@&G$t|_jMv99D+HJJAz7m0pP>`jR>UB z2dq9jOnK@u0XuQ=^AZ($FfF^M%DgrksF%Ulxd*eiGI1@inh3yZ=R@1|$(c$ysR%HJ?5ikuJCoA87sM6HBaZhswBY zPLM%QEG4|am$Qije$(t<3#bxsYkTPvlTyc%(UCCQt^VxuU=nuDb@k&N$2}Ao570u< zk8S||_xUZK&tIyih}F0W)S9M6BwsM_ z4WS}=t%&=)2tE)E+WBX!kz{#>E1lsOANVl@YwlIMTA+R(k*m>_+2)+I2s38t3d4FtcW%t zntO!a*qI_am7vgBMx9ka(ATI;YlF)#cMrhHOq{H3tscQ2`KP-#Zb`a|_ES^v%r zn$4GrzLj=htOpwX+1wr5{sCyp#Luj%mQK3?XchMNu%Sqgtc?WiOjC#py}dnU@(2~p zfM_4lujM~(yXc$mmme|7=8MNsNuVP8>Ze?)tiBAvQ>H|9HR<(?y}MXdDDE2T4Cq@7Jl z@-YDL2p{lqC2%1al3>^S(;vgH(n*aM-1A;Z@NDhq>LAOE2>74hAfIM0xk_iCGnf0R zy5X%g(Mwg-1H2+8i+hunMjZ5smDeZGyWXh-TvHcCsP;TmV^QhX&YGCw5}OLyV{}T) zJ*u+c0WfabJcy{hnce9c&j83v4FSO?OfT=n;AUse=GjB>^Vp|;Tpmr`Tf~M@_W2L) zhz~-qOJIW5Iqe z|I!VY`suQ>S**kX=Vt9NKk*WKe(SpLRHA_eyCT7wurqSoK0c!RUN=5wtGe>LQN^7Q zi)z!hz1>X9=E<`PyTwCFtwC-{#}qD6wpjZjIaox(XC@%g?q-VYhsR%++}%JKH~y2G zyHYEh;|=fZuU-N3 zDl5PJ`AoYovsOAuMEMQ9w10Q+ai9-)nSY&e;yCB{Hz;NONRH_{^4li8UsYDT8DUmD z^kjWHEYQm|D>Du@!G+nOvPHsgqO)&YwZ}E^s%3}C97Jj)OTUgP>8h7al1snrQ=nn3 zPd5Pg9C;v*zd?;X!%X{hAUoStsR%k{_}V_s=(prm;)0gk2~p=5u4O8y%xmc5{CtdX z47rYxwwO)dvL`>e5^-#$5+~SkmouGrwyc~)su#{@J%~em3?X*jOBMLbuSP6Y?fiy* znKktcF639L_gb@#X5dz;RiR=o!_5~jNUgzX?`s8oC0>91%ld71!H7G54L8=Eb+9uI`$> zS*}}FbTY26Pm6Z=IO&wp8$`g&hBA~(b+dLd@5&B=m7s;`Y4W2g;&XwhwYpW8HD!5Ig#J*^tm0Z%Tf6ntmjs|bUh?q7TWT`!%?t=m=rT+(}1W2Y2iKwn{7(FdX63N zJwhATj~Msq>jFtou$~=Fe@qex)62cj=y80}t$_5#e{q8dSR~KC)br$q38(eC*cNes z!w3Mf#FQ_+iDH^#!()2ozQWBqsBX20vd*T08==Lxkv4hpt@D}TjA`^3i*!^!9?MI3 z_`C&D?j?lEo2=y%Xm81s<;1Tsuaz^XZ3~SZ@49|xpq7@F&DUS-KMu9cH>~39!nb1w z&ymeL@E7DT`jg)8J(py#+*{c97B6N)qc>_#BBw?UbL=e79$DR|)Pfk6bY$bNx?!td znc%j*&=_#uZ?H>H>T!KsYt0~*yUM5pYA%)0mh?!fPC4fKPt!j8O0lAY8nM+r#Zo?{ zv7R;biKt5~Q@BxL?OYhVaud7n6xt~~D){Htu4q{=YBNyUYq4>Y2EXdlbEBJ&tvcgd zz7y9p+Zy-L{ArcKnp}ONd3lN$GpqWOas2B`?vFRd3*{*<<2K)+WxnEx?}gh9tV+?J zQa4IoUu%ol=&?)E+w5~qS?xR>&cPQkNNyq9mbA3On!pyB3A7+E0JlXjI5VuPisW00 zq{J1z&ckZUhWS9`@fA?fe8}VVrF(da9ye;^V{ha7xz#oJ^qpDQ(x=Z2Jh-);5gVfz z2be&SX)|%WhEPQzno^5UbY3KFP18$kiF_7nbK2k#Sh6XspOH>>KIu;@>@&O1Zsv7E zaM$9`U-vrwxlLk^b*_CatLM%utZ$tW#AY1qjry2a(T4`g)bBMdk(}PL#4xh`{D@F# z4uUjF-oXz%)9knx4|5sS_kh?r2VP=N?r>(h6Njb^UtDd*O+q@(X}Kf3Vs%GM{oV|6 z^;LXYj*%mSTs1xLaH<_U;gSp0TjqYL=YAE3B1r3J8~&YJ95v-h>s@ct433xp%jm&> zK;W)pf}j3Up$;+_m-W*s5;N9@bGP23lf1{whWAJ7aea`8qRlH@d&sb@mOA{Qqp)*- zbTP_zx>$Q^rFKNkx$#SbnXK5$vxu} zO(}2RoyOmmzPJpU0@pmg*Mq#0cyi2l4;#Q{s^+`^T8LM_3%9W zWrzSbQ}B=OpPc`3pa*ybsxc3E(kF5LwH$Xo8*E1ktmz5Yy&m9m;pu($Cr_+D2i4I% z_qvwyQiHqgGS@$4ljY-ha>H5wY^)D79;=Q38vB6H-~7#u&;PUWi}=M2;?XCaPISV$ zX}zc7FM)Y5U}L(*zbeZ7^Sf7wD-?m_L}b&WV5(TL_nG2{!->u^AuEVPs8~WV8DM@f}`J{u-Tdq6MxBh z7*%~N^=Y9i4n4{lpXBWQFJ;M(wRjrizuN!x`H@f9N}bRIH?U0qGIdXfz$a7pU+l)8 z2hQcXKV;kVX!c*#^bb1@F$504*jDM3gnIQZJ75LT2NwzJvUx)fu>#epob9e` z!OWw9dU%kG`9yqS=uR`_+Um}i1fpckE&rWEJ#MKgforCwAtHMDa|s^nYA*|4-xMvH#7u7>Kp8ULeFPAs_&k;WH@X9~2~DrjOkKL{nJ( z7c}JwJx$sspQ<eS}uh1B>_ZzfFHtzaYZ0yoe z?)?-Sqv%DJ|417KVq;6^`={8rpt|n(DK>tnSy+CGjkWLgr%zge*f{1XHja8!sr(~0 zK6(2n+WALp97*b#()w3y92o8H!jsYIGTZ*Y7#rgRpnO~is-Kn~FempHQ9{K$CXCXoyfzZ)vH<*o&1CQeL;4IIQTgpBbmGkOIoO~aSYtAA>&iLzo}jE;{_01? zC2yu)5v@98AO{eUJpHOLMAWMw6 znT{Vd*e|*u8PXQM3Rp=siOc!?affU(%7KUhm4R?g>{y#qRs>g67;TGLhLi=kb8@Kv z6A4m1+Bx_kI0&`SLwp@>dNx0d2^z2J65~#>L6?FXnEz#{V4GMhix*`%jN096*|!uO$am;~T=X&v{!&*)N5$SQj<=}Dv$?M0P^ zNBa#*@{u4V(zeR~{*L4hyDoG+zb-v?9n%5)XAg}wlo#T?t5+|A$W!z`@bay1q)AGd=7^Oh zRa!R9j%JvFU$UDHr>aCWC0au`e`1O@ecp}hRoG#c5&{JUfe^m2fip8m{N|pfuyYJ` z%D_MGBVx48YP2gUoweRu35>hKGsNTLJb&B1F3Ub($R1T&H5%2h1DA}I$JxMllb<;H~V(=oPhCDYGi!qg6%R>>E*ou4ZB5hlk zAcyDcH-hWBJ}>2TaAT^guW@t$P-N9l557^r_N2sk+4JK?@Ct)~5`Wa*|X zO?em~G3?8jRE#A>wFFPcolj_eqTX_dinfo)PM^_t9r*PMr@r5G+tRQT4nsGzhdotj zrhi5+?vN+g)TE@zdPJ8-x|p3>Qlr;elQBgOhD=g8J4@;l#%mB#t_#)7#ocn-FOJ?$Ex)&-0uWi0@7>r4r_qxbNflUo1!V7n zqZHwn@_Q7I^57Wf{W|NoROqCV00aaqkB5&*VisjRj?LI-wsvbI@LJ1q7^~5nR;=ZXo{lRLnkT;J$X*e zGNpWGT#CLXLep+}-4K*S-qA&b7dxgTUKSWdf zD!URfo1Q#dO*2-N3W3xhDVqun4Xx0^N0MIvwaU|2IAo~;l@BJF*kIQ~dOr}pY1nq(wPzVk|GIjz43Lrr^5Z%jW53D|J|-8 zF|krFvf9eUurv_Vvs29|cB|dZ+&?JPPff>eZ#rM@NT3tmIvqy7w8pOly<8u zB|3*l_g(z>&b$)Zhc@(S8kkx3(}L2L-fb7#$J+o_r#rlN6?MNsZv1mo|HUk3yl)DG zPBG_H%=PT{nTo-rT=y@;Xc)PsfoTuK$OBkQ~AuLJ#ggS5L@#lup zQo+#i+QTK1>A@AtCw+^@Gq23T6Jode>w5u5&;Ne*vYY8a*W>*ETvf+q2`GGwL(X|9(apm?2SEE+FMyJ?QHC>%g3cSZe=^HzXu}$J*;eLZdECJ)Y)HvLIU^i>E<4D~;&<=&(g* zPTdxIkGKS=>5SEyXm22@7d+wO^S}$g`p8gOPQ#KVP*qE2e%<9CWBqe9G;5trf}X32 zV^>kNBx~lKWYYi+#Z7No+>LBq$7byh-#x0u*cFJ<0z&)pd~7CChQ~QoW=>;;A&zxf zayK#(GQ}&A^N$??KxW=7k_2QmyKc%ywnHhpxc$>lT*9s=|GrquvTWee>xsR;E7`(t zP;-VUZP`xl^*w(-z%~ao3v!M9XESlPH+*7`n8$nktbZ3aU`ilQGW2_#X@S_u1a{ z|LJD_p^3}#b+ViP(544f^9VY8mhmgTo9}v{J#krQfk0l>3%`gH8@N+FrdrQ;y-<$) zH{TK%CYQA}6Tjg&wJ(`M9SvKPV_SpL=)|@dCz2_xs_P>ta-l6xQ&2G>QU?H|F2$Ze zahk9HFGyg+H@m5vapo?8&d(?5Td0g<40!Vrsc&1!jcIiW`qaw84Tr!c{FY0z#h9dGN6 zsKd~e{Pn&=%WUSemrqn>fHv{C#)6=}T zg_aJiUj$dJxlw(!R7UfYC)!pe>d*}*c#V`2`@afTac1x&u zf5zgi$sikPCUi~bd`zHbv9?~Qv#Uv3X{}3}5IainrnYUW3+5mXz@$u**M!r27lD(` z(BeO;@2{L)=orNK2y7Zw5(<0>gfe)&Y zs04)#m>Y$1#ylj?XjS49yb4B`66=@kddxxJja9KhOkV~E3Bp5hRK)1Yn#F9S^p5km zo|OKHeBrQOob|*2Vc=urpyL@FqTHBG^Rh{|<}Xc~1PfQ|)+%(LJ+J%N=>lMbp=gNQ zv;}KtuKcA#L0t-7lRnSN?6>C$7oSSP**-{Sh1+CrcqvP4E;%{w?GWhw z7$&Tf+iPX2e!XddUIRAk&!wPbOqQTrLinf(XGv99<6jlfH#wxE9l4<3(V5K{JiKXX z{gwy1(XSCJvJknhk7r=faXW>I`$(9wdjYT{*!ErLkBsMCeyQSvhO^}5plAYE67ZT1V@Mzd;D*6^gAXt}TRcF-%5fky3=HhG$Esn6>nr$@~w7Vfv;z6ieax zgo#9BP0Z`wPq`1&WfrHKg;F^!=B5jmIz3C~H<~_7GMCo=gXOD5Puu0CaO;vp z<%p9SO0jt}gkTKf=(Q!smw_6o#d*k-dvGC14VmVYW(OKoyKv+BhC~MDAzf{F9b!8F``f(T+3HiHs@Yi#nCV@ zbMD{h0kX9+nvj8J)bEaTcD9UnF!hjw*|o=sFD0)00v8<>biYC54^&_){h)j}5P~x@ zP@LID{s{4=WaUcpQs#bC;BNFH{jH|TD=2KperUGxCmN*n;V za$0AOtd}03J}tjN>PkvzknD|DU2{GZEX}g zcPgT!2EpRyn7CnWgq*XOhiiU(k2+c z?xT}gfQEU@h$moUdgCygb}E`qaC&hA7^NUYk;FMDnoCp+No9&(uqs<107Q5ci;5^+TpcR#BwKw)9mXakKgjZqB7G7=-czAiB%W z@gz?6p$Y#ty2@)yQ4qyD6V-1SfLW1R{s@fX2iU7r=TLN;q5D8_SN9@pg*gw;YEjC! zfp&B5&AM@-^#t)mVOC)_Xl}gvMCgu4%@B3YSX!)a+#$3PHjWdLEWsn$fwe{hLexTE zl6trTKZ2G-JotWWhY~ShOI8Vwjcj%l?lr(La2y1ObkN1_$dl;ak)e%D*VR_S4>I&^K~0D|e6Q1|S;tst_nfHhFn_r!-ZPFU)~Pd( zEY4c|*Xb@-lGF1=LRQ!5kLG^yBP^2Glq$>vu%^vjmsoo`70(_-%mOB6YRfKy^JD_T zFY|{2pP8D&J(IX*bDQ5FacEwrlv0ymOm*uiY@T$6!r2^e!hk$F{E?PA#A#Tzrryt3SWxY>t>F1%_ z(l8NdfsS)TyWgd|tUhNjTx>tzFl5y|jr6NcL84Yj-+Aar;*ao}j!+uNPaI;dez!oh z)n>d%1}{;a8SET}L|svBjv1ahHG?D0!zfd+mD$o8`z%1^L&f17}sk`4;nb%&zDz3 zHJOYY>e5qDoPV)hn+pkm%P-a1!Q(!1B%DR<-0tINUk@Wotgd_2SwN}B&0uV~k;Y~a ztc`Nq&6Ve0;lknOv1N9*LO4=}l6KXvF(M??5KiB^ZY?ei)@?^|F-iUDJH<3Ca;DzX zRqI@odCr)-^IlA<7wV1PP;S9Bl2kgVweor~hj8JrY%5hyhRICtmq=JnL-3lU5$HH? zNKX`t{u`!BSX8d#oOXs(;@8U|U>Y_W>dgJ;WchfohNYO*j%!>!iDzr@ePMXO{@erJ-aDVtE?5i1~i@&n&mP! zxPBf#7xJl#QmmS_*{LFAJg1*y0sls!$Zj2nz42Gv&Dtj9&W=8?RcGi zDZ1m@%CzZniB~yzBW6$>e*b>WW7u9Z8c!(Wz7_42jGnlg{%VaFf7O9#IDz5qjB0L;6#4UF$ad0WM?c~$olM9DLJAz-T;IuUk zBU9zNO^zk(>Bf@mmjop+O_3lL4Q&+?dc~ifpfx>fdXBKmaCnfXxRuQe)eSij_W=XmIYaY zUFU1Cl5f}v1N+=9ev^9puNeth0l`D8$A*=~{2C+sE?&cJ2HkfdY354O!OEa_l#TS= zVHN=~ZzXnos=vUN=*yCb8wQKd9OR?!hz%DJowDDWzlc)rDK>xkls$t@WQTrBvaowQ zQp0hD-O@6UF2KKn0Cl|W#wI#NxW!13hdO{Sq_?&FZX(l&e?UD5zv=Eo`s-2um6!_P z3~ANLGtoqu50S5cXNzfcDK^hH9AX8EO)u;KBOU+r_7*Bg^hLx|P(;^Su&>aLOuVG` z$RFL#QM3%*AsTo?<+nXJ|22-wJdSBg)Wic+dV9+0_)pM9HJ1&TyMv7LbyjI0O{Ipu zk@ruAK|S((m5D$3Wi?kG=ina1efFk`yagsy1;`&<7S#WM=rX0B38&yO-e$6v*Ze2iV| ze+J}pI6+TDRk|9X!`%a_x5=DgTaMx1@&r83pTEgAi znC+cf8=oq?Lopo~Y~v2!&N@8kz%@aVCK-B_ZaN3fmkv$e6tGtIp zQ?i|`sXcTqV_}PhJ2nnAxqB453*~z{J z5UFL~Kk_$*vwJ06M5`D*?uwrm%-EOVLfPdrh?~?U*0L^MxB?Yb$$ID6h2lw2MDp{l z#cW)Jj_*;u{YkP}Zl_NJ&wrMftKJinq~BR7je9Z)jCd8$yV)*H5VaKRvi*{+FaMqq zUs?!xzlUxmBs@QN>&!?u-LGB~aAmDF9X?PwVfz!#Zov-my{%(P=4We6=hX;=)c_F$ z_i2pRTM=y-JKB+=NBxTVL6S(hF>u-*D5-k0s&?%LYbo+Vo^A|6{jIN@X1=J^s|6g_ z5goBkzQ8rIFymj_^N4K<>XB4w)RT+N;b7umQkW=#^Ln{Ad(}}UB5yIm&FYoia3Y*> z2h~5%a{|bCH}U;}bWHyIP9Msf6=TZ_1{d=LRCJ_DFY*|RGUHtb#aVNSQsrc-xH{Y) z`3Nz2q`pHb0iQu1VPMdRiz6s{K>U{O-I4*e-!qc<>s1Up7v(nB2TNr|NL1YnY5SK^ zS&s_Kq-8fbH8tKt5~-ytKjBHXW7t^)z`FBZHO8O@sUvBTj&%c0l2tVeQ5Yll%(+w+ z0%PH8ESJK+n7p`dlbZ^?rjKyP)vgkz-;q@ZlFa%KB=y|orfTC@zHLi)MOaHG5Tg$d zTZ5}UDK!}2))}uG9qlzpYkitB+)+HJc0BsQzK2b`VF{n72d6ck+VNq{aKCuYYzo?T z%*>U)(Zy#_i2DU4`81-OGkf(rZJ{>(O8QXBFu(_f6&ykQb*Qmq?(yPFxV^38eSrFf4|Mn&~ z9p(0emR^E)*5iYFQ43u@FZb!eBzQ=dC#SNeWP+WcL{@c5+~W^4Jm z*pc^GXx|DMoAdG7BILwMyT-$0#QMSmYGBmaajVEJ|OYywn~lSBA0i;`~bN~f$_Irlm-gwojua^?Spbf*og{5@bk7w z1Hs4RSgf@y272QM*$hPhA;|C)zgL_ng66Ru`-5)QRX|WSR&f-U6p?N!P>ww)#XxbJ z!wTI>V=)MeySKNlUqm~8t|*QN-g*B{MYQ-+U&O}r&h*ixB2E`~SI<-VnQnAxE_qwH zKvNHIZz=MHm=2hMf{y^JZu8#JdDp{3b2^Y8T9;o)QewM}GIr-EiW8Klj2utm@C*35 z=?@SE&{gxpEqM|)q8y}UfIOb_q5z%ABoP4APh7n@2k4+tNx;BcyoZlAIMV8ojy&cM zYF;4sP$dmr+akmnw!fiCX567((3kpWLh5_schhP_b@GSSp({uOjovu>di4Q3H`>lh zg6w7i5S}$rG7R6Yt@w_OKsH{Z7j~PXiM3_~I=7xP#=&@w26qFrd8?@g9IZbt?)@~H z3&M^A7TLeo93SwlrOLADQ7eSh(Pw_p;@R!m{oZ{TM0%#+AT5urE_h>mSA$JQL&A#! zeh0cS4f!0DRhWs!S9zFCV=U8494$98hRQ!uOg`6`X^%(lE29jGYa@kKr1kp*1GA5Y z_REbXWH@FC=^~Pe%0awm(@K4wll!8Pa2Yotwp8Yh!P+ck_q+QhF^}DwPZTKC6Gn;? zvO_{O3D(H%+3>0hpJO-kW)FCNUGu^PfL+pHmpTLENM zwwqcQGpE`J%`vqz)#*Bj{C=V4ZKXUhnlTK+IJ1sJN`3 z=8bBbeF^DmlQg>F3{;lE7WVuoM}Ezz*%NvTeQ&qRByV1tlA4;Bk*B_}3yG^@6j5RJ zr=Ub3%WHWi_VB9zkQg_`qSCRmh>s?DMyQ3^y6{Z)A%SUQ`6o`(K?KGrILAs%inl7G zQ}c)7IPHQ>X)VUPj-%AeMG2}2y6nw)madkrK*ukMd%7JyALeGR#u`&#n_1M%8kp66 zXO05Wp!BwyQd<{Cp<-J>^+!Rc^-8^cS|QMA8l339G>P}$4Wnu0sI{GX@PnKyE%L4* z&ZXhmyf2fgE38a6XoN>}uM@_r?Y0Wwx26^YqPH6N8z?vWHTQ_UM53tESSi1i0ZaYbh>)PLUWv1P<|Z>W_er%N?b6y%Z) z2078_s#MtBu9Dz9cmoy()mRWauc8%c!ML7DdVQmJUR{mbsivy=td3Z(ySH+pQZaMZO~KpS?j`%`|VCzj0wt&`Ff(}z$msG1I@0grtvKIF*fG+ zp4UCcC(4loq`ay|dyD>$85ig2MCP(JI~hNzRm`kfs_YJXvRDplH5myiN$~oyelojH zzKu!<{U+*HqnT~?Ldgc*w74kR_65o_P3eAoSD0n#^7_$lBcPzB8XH?}JRT+Xyoxdc zVfsZ)7nF9Rxwz9w&C-E!oWuaB>O;3z?1I#8WaO|L#J7TO)Q3{PjAE^p)iy-ssZH=tSmK@dZK4<;1mbCe}k2C5IkM}-Kl&1${NovV4udO?Z zd{-WMAQ@XlE52ch>l>vl<>|({bh+Bpnqr?Qik(rBnG#q^oYtT+MMQ zB;&f?yEQCcZPppBt9lPXXrpDwePhfUZ41dJ8H)pO>+5*};TtcSVgnxu8mU;>7|855 zyL5J8nw+mK!?vxA#u_9RMr%srda1E3m^)&rUzbQ$`7P%Nzi=c{wuEQKq-0CyyJ*ZF zT>O$AdE(*lR^!+{z5Ek%t8!~E6?=D-TQ{oIy|H^^l9-nDS}zXPbSj%w4zq1E+UKpq zMYp=5N_5GpVd(bDZ{;{!wu$N}mDPUXmdG004~D{W`i%D0o>hm^IHzA@W4>s0g$MUm zjz>q8GZgmJ4$}L656%B28Jg1==Ndg?h-j7%3(}MhHnsVnpsK2r{p69J7z;q+0A)cN zoE;I-z9|TxeNDdJLg7Z!hH_M5r#2kPa;A%b8;v4*GTUQ!m zw6Xm8%+E89N&Awy@R`ttg;rRomPnKUDdHESMzZ3Ihtl0a((^RlTTeQFc`J6Y)|}OZ zwZWXW67_LOy`eLGv?b~2jggpAmgfN%D;~^>a4(}2(`IUJxaW40x@3AJcEL1pB6;Xc zK|FL3#0)Sb>|P&B3_hRxox{!2Q-ejQ`wHEOOKl;kb`%mN=jzd-dKje0d%)a8BWnLwMDTox8I;Ze> zPJD&ImKZ@KKrmLEAsSQ+&a&Qs6;V<&OjJp+*N})t%JQYYQJ1u+SCRUF4nHPHLAZSg zq!;o4D7cv4AV-QD06m3~&d6z*aAEj}EprPqnxs!+tG}TdbRv^xw8*7QMeufuTtlkYyQT{f{ID2fucax2ox^L30 zR*h4@W<6b`X#P~Xv*Xm!4@T)$I0^I2lgVViB$0PFb}$lSj15z{e#mg?7yIqCEkf7f zI2#W+Z>hi`^pyz(a{+D=hmxA1g3w(dqTy17_`LGL*FXK9+$XTIw4B%#95^D(b#El! z%XQz$q`4`u{FoIuJvaRBtq=@`#8IGYxgh18VgL$AqyL)hGe{27E7aTF^HQd%fVM;AD(nac)bXVhn3FM{^|S;^ zEgaBt;;*7ITS@Ro^+8x;-abQVhC0nva=YPm}DhT9G&r9~ylU{s8qe%wUQU88Z5IG+&Jsxj5L?fte8Xx4)}($izJ9<-Mm zX>nd|jj4EjpNO}vil=tJoB=EStW`?qhMObtCY6;rp+K$UnQ^RQh*I}MoEvY$%d+{Y zJkNAiuy0iaf%8PFZv7%hzNZd_ggugzM@8<7)&? z^)_#m)UUjJkAw8o-o>6}d{#Q~)q*GiUSIiLz!yWxLUgav{y+wysr!_|6fkVNv#?rD zD+Z~Z_xIDqC0I>XiYNli9fo=(ejn?^1U{I%`fNG<_I3%pux_7jGj7_s;T)FZFYI!C z@Lbh6uUfdx=pcID+*GgjzR?xjOICY`cn!HJ4E^qUtGM~y{Dy&O`ka`g;XCBs{KH!l zSURSHFJiW3?H#|f6TamOhfa4T!a)BM=l}LrC{6a)H)b9Kx8jo9&0E({2dZ!$ ztrCQk+#djs0GJOP>IAfLa=m})iVkgn4&(xwjFTi)%>O{gXE) z($o7F7_jYRvVV8t8ls<*Ftte*Og>9&KN+$D)`#gZwgCt|@|Tf?rhS)&*gbz$73&NI zWpdJlG#*|nVbqC1CU*0Gg`B^!zXTiSgd0=w6`fssX1tY=&5O2SC>Rh;U;8Y)C}Hi* zLq1QRFu8n0P63O=u!Ky7tN|W*!6f(3ytG{n7^1R2N10VpyHA>u#rz3|e6`!}NZVGFnBw_vy52B)8C*Ijv$ zu(;XCWTbbuQYDfK1%C6`8A4x3?7t111(2$`*PUPleenD76M&Z7aH|5_(GIayT9XOQ zB_DQANNYo=tC#JO0QMXS@vyL0&hVtxuV@s65J3Ow0GLVcdG)%ZzKD5Cbt?+Kqq>*x z(y~|iQ4N;|(^E(|&hK}8T&mEA$;MgAS?BURCi?i%AqV9^Ao009JKH1vQ&$So?_V1Q z8zYOS^ub$SdL0J$6{PjRK9<=9L%t!*HV}<}ztbZV>QNrW@2!!4oP728u$0lad^S8C ze=cL0=gqV|6UtpKOh`gn*GKT&c`j#VT=nl>{{WaI0vG4o&}QC^;M?Xf5r!b1;6@zbLUGeC+&lCoZBJQkx;#$lG{xk2dr>%Que*MpKIEV z|L2UGJo)ia`V{;D?4Os~_fh_H-bQXexJ$o*wZg|%l{bT>!TZkMal(vXyFW?FnzeL$2I&7Ea(@hC@XLZb@^!9@o#Hfp0&%T5#=zDfgZz5 z8DhC>jfWUQp;l@tG`LzLJD>!~&_ce8-z0RgUP5qM<-jslLgs>K{4sRG+DRD=EGg=C zLi5imTYcAC4eWFDAHZy>@~dw_nUC1>WkdBp+h9I3fbjqLQaLF&@OZX}#? zp~qdsa$23?)KguQD;LOO%^te@rS6CiQBVZDEwmrYzoQ$$TUv37RgX;4yINFC8VSgM_j; zT7!qhK|=vS9SSE^Z^Tz}(^b*V871DBt5r7#20b3x@yT(cN?LU%jeEt|bQ7hR7To3# zoKY1zMg@4bX(A;1<$<%T_c5agd0WAs4WyOlM(F%i4DN55?$*`AlWFpt$@ZfUeIA>{ zl3-S|19yWO>upS5yemLO`osGcgATQvnG0e=PHuX5;o@hZEd?1yxP8@UNv&7 zh;`%~f`ce;JB>&2X1eLml9LB*x@zIG7J*AwTBKPCxHc2wn(nR}O)qDMlpSB@3)f55 zJSd>bNT3u|@tWk=?2>ybT^{v2wojBWY=d!eKaFLtIyNaa37x7NZQUN(0ulOMOe5VZ zEe!`kqFChlYNiLU6R~u9n`hu zM$LFc9Mv>e8|N-Af-busTIVY%5gIy@=r80d`xyCub?77q= zuC8^_a*GG^w{z?OdYuc$$9z8e0H4#ZAE)0``-7_KnzEflV3V6 z2#!rP*kAgJe?1p3mx>^Q%*Nh3XVyMA>6M5>+2`h4C+@sc;gtZRY#%D zLYdQx3i!@f~{2BohNjsAInZy7M zUl$J-)CyQ7av8RPsVuge@%dH!%7zV>xGA@j%=cu&OB2cbfxcAd=2IiK;+xIdBvYai zpO1TjI1DLVqonHOW~Imy{hY?Xy0US$aGVnLz^}-1WJ_Q_e0`G$DT5#B$TwMLvzj2~ zj<;Bc8A%g{P#pQ0rc9D4t&Aa0Nn&3Eu-}2N)i^Qwx9sBojvng&%xM>kiYW9jY_foD z%G>CT(sJP@qaR++y`{=v_&dihFN;+$j>qb%jUK^js__DAUtW3KZUpR|z55V}DfQBs zRY#$P@o}H?Tbl)L1WMmw4E#^eT;x#6!-nO4Z0_8j(e$8rDVT#T9f0t&=@Q}6TP*MZ zA@rP=Z$>!0H3iM(6FbEja*=VqKW<^RW|sR2!Tnqv*YX!#0uQ2_A^z!BI?sl%!3aGM z%L$IGHk5CR@Yj_C!cFH1jo_v*66<;&WZ`X}2^$z#s@b%y zD$a1j)xV|>-}(?~YCq9n*=0O zsknpuiYJ@kfDkFL63rWyxookJ8f0uH%F2<;>~s` zch_PZ4NqGS4dxS#t&h(;?6n@W5!!#%R;CYq?ed26Y_z+B=_d#KWz`)O`OBcTDk*-! zCHlgr;o|Fda>{B{p`Cie@Nr;?nqosU?*k6*KGd2{m^+LJcLc;AvGUNL;As$maf?p^i&K>rB0a zcs%)Jj&6h#U^A~(hT6nkT4y~%-{6O@(IGWZ5C zmGUl%4)i;oW%y%i9FqyR(Nb;o-U%s2)#g~^8{%1>&U(r0t7gjyDaRX}?PiJI4rAK& zOs?fc5fW_xR_!oCx0YyY z1Q`NJsK$v|b68V+#1%V>@(CqVS-T>u6THDu&Ess7cv|wPnKf{(ejI2F{8!txKY$qZ z&ReR;t9y!C2hp^OmrF$_w_6Qv(mLBrnH7#?esfExQyEKY3x)uM=xrD8dNLMXT=h?@ zRWuL;S=gWM1y<`j856I{z7b%qrjI^IBlfPO4hOKq=s0+eN7X+yz*^Ra0$p7m|FD4N~R7(kG{oCtt=<0==oV0kZ_N!s>nA(u$mEEuBDZ)l^UvH6c8!~T$7V290 zltJc9o1(K)Y<7h7Knh^GFxdHhd!ot`5Utn?%FVe-e>~k8C@%sMdZSNJO!GN6P7fcl z`E%)L^=0TR0>lk<#2(}H-Km4+Dd&R;gKX{g2<62Mi?CR32FwMbS%9g`i6B)+rgE^G zGS5z2)A=K;93G~#XQF;t_$gT#ZB}cRb`Ho-*Z=G!g>{<_b#X_o7&XD%4qPWNIz=^4 zZY->92IUb50~+q$r(I)04Ln)$C)|0VG^1%&9C2N8n%Pl!oK8^-_oIx{SEG1B9W4P3 z+ojO`eWCOnt}N|Kr(cw!3sa@ywXj%Q^e$Q|*>&RVGEqH^bd;TvWdjXk=I9niEpjSQ=M; zxQND>UivWePex5Vr7(fk=S^ z{vcD&H*?xP_&Uu=ccapHp1;evUb~Y1j~1=}Y=MZoLHR0dhhKYs@S^oC%9`$7_GXOP zfAqnn-m+lt)Ojc33)*@@M4j<2yw6XwKo46$c76W-NtHx~1^0nRikcvHKU9@#9zI{B z>C;tIw2fgG3m*QoH3MsoCGLA(>3qB~S8UScoQM^LF{9^IShS6;{dl7vXxo}@l*`4D zva>!1F|)qxbqIcCXZV|G^tj_g@3ojYAX&~OlsQvg#g-|7O7>;lUUCiV^+i2;)SrJ8 zc}B}wNs2tK)!RJQ)lWC_?4X);XBMgYP$^X>BgZPBwv7b%r0nTSEp6$QU zmbEXM(K9_s(4Wg{#Z@C(8VRvN#yIx(t|Uj!nONf1*g;ETI%pv4Kzv`TY8~VW-se-W z#685Q^ma}yv|;$(8EO`fv%-V7Ab!vQ;L=$i%E;Vx`VNV?66`xrzE_=sRTVVl@>`fK zw!i1s!VrG?FTgg?jmQp|DaEaEMZ73(v|vX%mMrd=$iD7%{4CvTvq{z>SO47_G&?NE z@XO!QiE180$=6Z)qCz83UBamBsr3kc%Z);-FFJcE+HK(03{y=ciq~69=;%l4s>(8r zPwWfO6Va~isTu2}%@5exWw88!JITeb3&V4MXGio`E7iDBiWy?Vfiq^F%Y&S61wG$rfU2)teh zIJzlmXnApHQiAEcDyvjZD}^pPnjNa+qe;m1O!w{KO6U}5qRV+$rlOHREz)H5meqw2 zR*`RmtmhX~_r}Q_-coW@_zLK^i1cmcI={?WxP#((xIe8U5G->0bB&3g#h!~z0jnXv zS#fRL7&e^;5X{&jLDG9;i%Dgy?Uxys?zWcnp&=a<_1AHzy|N$XZtyZKt@vD4+auA( zL{TP_d0}a2q>KDv83q%}P3RTFEoFJ%?q{d*NT);k;but*juQwWWVko zkJYX@)Hvjx}-bj zin0o~7w4g!N{b0f9Aa*|hpbO0thDuo8pbJ@ z3P7yN7GX_09A}%mRg)e>cUT-9CPXI^3AA(nZXMv9lWB8^(&4Csn|q&|ZB@+4I_`vW z2vYB`eR+0Ta81evryGOFjhLfAS)#q-yIaj&KpDV#ox?uxw%c}MQRnPc1vLSkYpf_? zM1|ybbTF^^wOV+sFa=_I=E6r_ z?IyjEfQO{@>dOReQWvF&W>%~#eW6Y`yu%Tmm+3FEIjM0*oytR6pZ9wo8Yl23GPPwc zq*t13RvUx%HzW_v^K3AJUJK-lx}G1qY?oV9Jk zvYslWnk_gafM4%coPmu1iL36JC!>wNb@bSiY)6Z07jk&#M;)D8*=5sgSmE~Xz&&e| zV$WURh%zpB%^Pm{`=O=hsbSko9n46&h-mSp-~l_^l$gQ3 zmUKoyg>f2RKFq{P2>Wntuox!;7EG|!oU%=F%HS;#Wz+(ESoT35LGCpZ{>L%<+}?$U zT|4im!z#H@EXXsnL0%$|XKiNDD=b`Iap~ZftHtRZm-sZYZV7JHj35OZUZ1k+bY~<~o-s1lk;Wx$!Ew!CQodAO&vhCTaq*793jlW|J#|KP z35wisEjC%V1GRaK@xAb{I|E_ET9gzF#z}=#13OzR6HD4fJlsLJd!B86F%Vz&anD4~ z#>v{a5AS~X*lD&huhXpX|AtWihX(RL%8Js>jOuSb`hs3G5m9RLk!|N4s1_=iMvv`( znYtmHq7hZqJ%M3?iv_YhrxA-6_KTw5Y(k%WP>{nzoBT@?mV$RLyucvCC4RC_`Ur4U zNf<3pH=t>s*e(==;%|5;*a~rYcpq8>E`5GOHh2lR0gL()7J&t=xx-;Ug=`RmO$TWs z!$6!`5_|V05sotlPusk%*Y4dG;qcT%vEQFV4D)D;KP>>j5=M^kD1@_w9n}I=qhw3) zIGnUE9?yfJO_XP<4-$KMWJFB2*WN2+*?F{>F9;V=s5XN8Qqx%5s-l2`^P9IRFyaxF z9H*O_STLe46m$jv_3R;sl!fM28AATRuGkFaDG4XD^!1*!dzWa zrZ&&>=zGh|k#%%K)*iuVm=I7Jcn0Vev#5Qg# zp=~6g06YFfvF>5M160|7<<+K~CQ%)BR7+8?!62i-xu`I6NQEf4fEStIf`zgKYX~mu z9eQG{djA2~@8{8vJcy{ky!I+S@p@n9F*suSDgOWqcJco=n@G&u_r(DDju2c2Q!ac2 zS7}vWBkndW{{z?I?_mE!8T%g!;wd*giGgmb^V5G>~3LdemS(Uut((`1LQl)p%iM^<);|I-;>Bs?=e7vvW*W0dxs z9Nn@)8;waG(fq&*njc<7`K2SG^GgyC4}rDQxpNP9xHezU(0w+M>7+_l%+k~F{E;kR zQzNUf5m!0b%C*&LN%Lu|G@eR^JbgI(epqLn6X(rTm+RPnW{6XFGrV!##9SM+Vvlr3 z0JOKfR93fsQfI+tBW%Cht}5T?4sS5T?~k`2z`0!KB-;_Pi;LVhQ4uJw>SeN^CFaMX z#*{q+T&zNiz(MyEoOl`fFLpVLJt0v*-a%5@n%krv*yMKCgC-mi8~xM;)bXCK$6-q2 zIudW?2jQ)xM?RZ57ZCzP@W&un+CS#Uowvs1^S<35-Wd8yue;p24Lz}biJbUS0};q*!+;L>I3uITF=Gu8D@8O-n36A;dzTuWDx z5%b$Ru_^+A{G0mvgNe@c={KR?od&x{R}JVUo_>P0$~8!CcS|T8${Cc9Jw@(t$Y$u& z;NV^+KezXYddN=H2jO~i}q zMFZ18=J`uJ+!aX8b?1i6jNk0!w>dZWERo7b8*)!^1Y>%>zL*N^gfK21vzAWhLF6*E zh`Xkz`bOa0l=)O$<)S{LYtUookU*rmcLLcHWJ69kmEdoywzD)fBZru}>MyKe9I5E- z^k35F_}b`NDA8n+Vbnj)#Elx*WYTs;)8(t@-NpZK*jHmPLfWpmTkx*sV?^)cs1Jyg z&h`M3TV+n1*~h4O%I8P8KsXMiHftjrJgU$m!M8$V-QogdAOCYMK!f?Wx(F@iVyy1q-r;CsJM?;pT?)y$bNm}2j1;CrfJ zJxkwKi15A~)o`%}jJqHhPwj-Y%W!vnA4$3>)k3;W4co<9gq}uGuN~u%0unJDhnI%^ zc)?k9kTBkWSlZ6I`Hkzwy2Z6_H=DoM5f^|KAFjK1bMf(p5k&1*5!ydONXe>ITG-Q% zjrz>Ga{mQXQ5!K9wUt_hE)y#sMek-=SH;grDq6Ru1WGUD||&dUUZ7Ovwq&1ov`0hV&2@k!5$Exw)L z{xiAYvy}+5HZMDTspP9QNZ-V3?35X!JNF!02wnf<4VK2(32DQ&2zw~c^;^F=!}{+b z)=vxhyk`zZ=*CG)-7(D5O>*Ld3SUY1OT(?!J5xt6#c#T~K$fDOpt$1i>xNlJEk0pL z=+DEoUCX=5F01oh(8Rp=qx+Gp+rZny1q7_{dcE-H$?FpTj8-lyE4*cpVWHiZ_?@Kg zSoOCqXrc=}J6Ah>Wp^I|Dm*+Yer)8ueUr^*IhgZbvZr*lqhB!wnE;P%lHpQyrY1~{ zQ)w4|mDa+P{d1xKfFngV0Ewci^c87M2C1iwsVo^* z{sEw)gTJM^o@lTSHLmo#2&!P8gY(~A2GubZ#Ra--TtTa+GsA7?FdB*YU$TFFch*+n zc+oCfO|Y1Mwe7QQPBxjQ9p;8%jMaj*6;nUSt3^@?lUE{gNKYul zCwzJhxN-#xIL1aF2-=78cW!j~go03wA)e&%VGVpXTSQeTe>4VD*AKRLSbU>=Pmk zhYn4Ut*7?#=sPTJe17H82C5#5_!^5Um!%3TeYg*OZ4e`5`vF$aZ?Y#2g&Yu7OjK19 z6c;`@J9+iaY7iq%R3W(u-rc>ueF+quhrB~t>p8rh#wv%|yYH*MFA0sk(6`|O>l^$9 zRZdcJJlrF(BMi6%W3HMCQ8ohb-nV9`1kjum5{O>%WKfUj+QW$%Ff!+2~=B>X=gC4qnI4e4YCJ`$4Tz z=Qw^oOd!X2Z{KijFNxX-rqED(FyP4jNki-_ZNDFdnw-?7i)_Vz=9QBvDI$T;V2TUy;&!hPlZb&h9G9JDJ->$^{~G zP{kaJ3V!h2;FT*m9ME97;lOrPn?N_&WUfJHVif`}YV>^SvkXls`GBX*+VW;%MCoo0 zQem{-McS|4i7nu+HDnV77Y8Tvh4p?^-dA@t5yqo?@;L)l!lYlqsb8*af10(6AX3FJ z^@Q)t%m4JkNV-)QV2U*T=6!jFSRlVT+B|K-S1&O^I~a)dDg$jnnjA-q#!mZFE`g@mr>RaPc4yXY%_+-))qLYUfTmihZ4AFt zE~tRji`MF^LJvJ1q(II0pok5T9ASZy^5H|-MBo6qQPq-q6UvY|WVt5PL$lM-u|{x_ ztt`3t@j!m3{p6Yl?J56;AE?uS>!C; z^B9|~c5T6VZ|=E{FY#Fz#fn5~ysI`cwb6~QLt>6z)B*W?-5uokma-Pj+~sg!H*7s9 zy^gi5EJthO>8=e_W=^ok>Xm^s@>{jbmD3Rp+Qo3Ng=E^+oX50PM;sqMnWki;GFMTM z(_pqPFtBWA71t-odv1u{(uo&vGt^wi6qv53LXB2jR5ys6K&nDh`D*S$FGg>&Umedh zTLza8+)dQsmArr{kJH2ZHtCSYtIlH;4RUhLW#_h+J7MMCORd;Xx$f`CH{XR(PB)o~ zt7H-jV*dQDIYlT%`I1KB4`WEgzax2$TR6H^dX`z5Mq3-X8z?5G5w`O?!RRjOQ$mX6%@z(k6&xBNv6}!^wNR$484r;R)e= zv9&Y%-)$ze>rLd>n+wteStR-G%yp-J*%@fW&fmW<=m#*HhTZD&C2>1eRd3b?Z3VY9 zR9Ii)r(WTbr{3Ug>DuzSSaR~mDet#>jU|0%^=3=bGOg<8HH>6oI|f?fEN*bt-bYI? z@3C*S$!GI4WT37uE6Cn1bzWvQaGB*>hQR9#y_L zXvh&|X%7b>28&xhp35THWoImFi*GE5iu+DzK)0mV=*ZjjE;QahZ`H7fWA!TD`{?(A z>)JrV`BFi=pbYyuw)xONpnAve!0gY1x}DqWl)5ap)}QHf#nORv4bAshYYGgr^Jyd{ zg$2_pQV5jo$`I%f&K%a9ancM2o2?8G#VWtfi3nEHDf7oQRUBoT6f}=%Pb`l5U7Qu` zwEIXnLQ+A@5OT5^j{JTluVZTxx|6;sZmkE$!mSGi0hTBkh38S;j27FxJc z6vkIC!f>AIIco*snp(L^j|$#_nk1~r5U+I*b}7Q zZuAv)b2nMS^nc(+L56OwFCrC-aOK=ts=_;Wcaf)7qm!S}F5_lJ_-8vL8_Zj(&^S z#t+JOk!l0F30a=$Tcp9ngFuMnA9_Dq(yn61)wyN`gjs7d+QShI$wKP9@uZ%PE@X@H zS<;zXYV+k+RTcNty?;`XkR5K1NN5N}aPaV~wdtpTxoRyowYOvXx45}F~e898?c~Ch`!Z5tMQLU$c;3ZinqtXpm z1Z-&H*I=KGagQX6lEe7gar-m+!SccuI9EnGGuPt+2-2ZL08Q`uu6jPB!2TA^uS^p6 zw@aj*$JIUv;>Q^{e5uRhewB~E=;#0+##^c81fuh8GRQIZ&q)2xy^0~6F;_o*-H*UK z8&+>z=($_lF^J<#qerM(%BnFnO6&SUg)VB(i5D&x&pJ3lrG`m}UT?D+OVU?bBkPIW z_j7P36Khem`*=4NxA8c3@NpAzg)lchj?VUzb%6z7Gl#=ClfwlDU*^XF0ViVdkYVL?+zPnxWg1O>9SZXS0fogCs{%{T5|nd&Br!9b|~Jdd6RN8MVBp*=cpyVZF2 zxPW^_Ei}|%vALI}$TXJv(&L5rMgCP>s_toERFh)? zNh~QC{_!K78TPK-6O&XMT4Jjosr6bGJVP|?nBh5aPiBE zqJJ@oYoV7Gg`*wyQCwut$TY_A?W;fggf`J0nx^tvoQZmug|N((#h~pKB{R4;=qoK<#sox{7tib!y**ZwuSldZvNB)UP?)p5v-kI%M$)^7>mD z_ns%dRCpMolJWqq-w!)Kw9c@ZFn)F=!H1vT8=bbq>=X*?CU}9%zSfH>YqfA$R(nN!nDvC*4NH?kCAzN5Y{fr%H^X z&kpXI6UIJ2gw&;HVWPPlP9Vh}5_dEX$_pB+quGqhqm=hCY%OJ=i_&XFCy|=%e_yl5 zd;1bA3W@K$y@?Q`n?IkD>^nmR4I(`CM zI;!pX5spv?Dxr0bIB7v5qzR}DyClb9P)@Bel;pF6@a1I{RH8R{FeRE%7Ld@a)@%SMq8lA9Q;*W+R#1=l~jLUIS04Bl#Nr z(6;A$>?V&^MjC9|EyRWFB$|lCzz3fV-#~KzTU#nJ<)E%`R8R&x&sW=C8(>`4eqy`J)-oKL@C-4YCR5HB>Z0ts9pW z#6sr9{KpDbubQ!;&&}Pe>$<#=6YpAFEcKNh#InpehFqgYst9`ct&Q)Url`}FKzoBc zy)!7TK&cU^SYMWvrAUVaGG3iPtr10NBt_;xNY-V#nkheZIj|CS)?;RsH3S2qWi;9X zED^P2P0Nn0Q;W)#8q>Ho)T*6QPwmOWPV+g{#8tDEwLZR~i^;Xd&RKftubP%Po;>kZ z6?}qky>Ijs0J+xR=1%&_NEsEl)*(uG0}BhJ>ivyazJ&y&xy8@ng9}DTxwsJ(`kbk( zjm1FY(0)3W>Wzm;gULAZM6*0vAcQcaA-9KBnGG5Bm`13PDn4i<9gkHBp9|T$RcqyF zFos8j?>v-HqUwc&DY7x0qbXc*TT6q~=90e&y%Z6gopUgQ)mJ?jKj(_%(nD5J(0Nc_ z^~IRC{hlekOeD&bINHSOxX#Gi5%Rb=*XsNkN&L zre(FqDirlZ8gkoF@QoyTS9Q5IwLS*^gAM&J8`1xKnZ=;=RkKl5Z3TZbKl#rJp`0s5$k&B3b&_pN-Weaps zgRL=y3KCTA2LtvRMOA)_ zk#!k*gAK^dUn>I6y)wY2@M!=@6wXh57e4c-!pz;BwM?IeM)q%SZ{mbydDx*w?Yrz_ zypJM0LRi|)=M<3zDN(JKNf-`pF0ZCBR7xmNPVT^#9I`@8z~a@t8!+Rq6a(@?#09^; zdI(%L!i54mXxpY@X)+CmV{MeM)25vi~UUew1Pj4K`N9@ z-#50q5!!GBc^t9@PxecN6d*c?dINjz0%o33z$5JtHSpcvAB7tnLXFk9KK`HyM-x*V zJU~4`JvqNU&10}dIeF+*+6c}6&+Gc1G8R~U(fv$M0E>u{7D1jOVv=c$j(^p*8aM60 zq9CDSi6lS#LdsY37)&#RUr>d?JzGE_;{UjS{73EYzer^Kl?iI{DRZ~mwN*agH5W|b zJ!zBY_E{UW+TORX{9?vdOL0CH73JLAp}pe9I!|vM=T=L1;bzrNCYjcPsVQmdrz8d; zt-PA?yL9Dd+WG_UY0tYc*wdb7%}CH}@eNl+!K>s_z_gR%DF&?1l0Y21-Qk*W>~cCPsxu72Vm9F_^3hhdt2Y>B({f9 z`~Sb!{}VHig3jOLv(ZLURH@w-#)-8Gnr+E5v3<#&Z*hrUuv%-WJWjTjkkfvE;yu$V zr?rquUHlAkT{cRi{H55>1t&{F4_?YKFKaL9bDUYCmB$1EO`M`(vkI4#$chXNq7~HB z7Oj&rdQS$ppeDeCc{HLM(!4b~UKnDTKeeLFxFITPX^VsENK4B>TjRfWGkBje{tu0g zu_)WMofdd{3Cw>t#<8sV$GOjEN12>wOgyWfz0En3vV4AS8e(t_Ze%E@I^z1wsU^u^ zT(Bx&1ancqBc}9O+9L8rS1QC7DZH$GCDL%9nn&m2Kz=3i%6jQC`d|^3a|$6A;>CMO zFz!}wx(o7>$5b{7C5KZgC%>f7FdN?CxI|p5%D&6W@}zX2O*0F9b_8)@ZKN>fPZ!nDSM7hU2dL0Tq11XvG;Lcverfxgflnl5a>pt)yDIg zx$mg+eUwH*y50F$K51q9z%2Dd9zrSX*NjRghsDpJ*|5)|{#=__M>u6{YwMAgK$o^K zV5Z$pebs=M2qUL`D$Hbkw#5+X3K4p^acVmkL8_}>vcHZ5N`60n=m-}54<1{(wYfP} z7Cb)**;#xNf2<>a*1hb=%ZJsRk)XFPE}f^HoU<=7Tlbhx)Tcfx1IV=3gp0v;eax+% zV;;2=Pq3fFQT-`v?W}jyzjCOxOM@?uGsmtjU-fQGF}5k@tRm|}N;#A;qSK^Jl+nKN zSn8}ZIL>rn&2|r+S_^^wK91>*xc+kqR$t~S^=aX)aPRLVS5gGs;J2PBbx@f7In^~x z`p^nt1KVydCB5kv8)Cjg_>_`v~dTh64Gg0Wv{f zd^Q^ysTYHe?YQH^LsLWIoGoTSjzn8Turf1tMzH8IIai2nVY^F&-tydH`ukO_<(?rQ zc|owjEZnj)oGK!z4>)5ogpOr9+g^_u7APSuD(*9FKLdR4aR z4C7F3vh^B9+(wlaqj`trda+D)bT@>M%+uRc_#*ve;JyB2n{qEVZa)X{Anmm0oRb(%NO`{9v|BTde6M0!KV~tt0A~esipcj(A(W7dtK#c z^DK3bso3<$sGudM0o}+b_A=0kK8})-&@q@qD*hqXDuqayNugHoUJ>%ZL#%>&E zgkfT9x1^_f6CYw-6I+&KjH?~!u+v-cNg9&D9?WLCfHZd?rTx(BVTKq_1if|{Eyb)4$9&O7`Ubw}K)c^kr`Ql1oTqd>bdK10 zHBf{u-F|STVdb80zS_Lm-_v)ezD=bkj@h((GD{G9 zE>8fhj@yTxzTKqEfcw2<=e_kg)nS+Kcl_$}4zg65xx;wy>(Nm|p#?ml=1W`RYxfmDoG4dugNOt2D>Dg|lyy~H@3jSi6n+A!Iu%isbphf_JXp_>#NnH}*+z1dMD8Z88~s>fGwn$2q2 zC+IHqUA(ZYU@|o!Z)1X$cAfAG&cbPUEZ_z7^%uc0&TMfE6MYf0Zq@!c|6NN2$&A|c zVW!fwy?I*VWOQ7lwOgDLfJnv^C{aPG886JxCB4~VPT0rFF~SPs4HQ2rDH8)$9I$ZW z!XQX4XCE+68p|edNFk-5$W+f%JlR=I$t-|MAT@bfNlZDC4%ttU=oQ#`5)$Qi=iYNTimxWmVJocDCUtn=-0W7rqa0vBX^9iDCGL+pvOEo&rc zNQ%8ap$hZau6MS1xNt~d=?qTrROt{qoDSvEvc609T&>uw2HO+o96Qi3J<{gLPh;|3 zH@Uuwc(|}gVChcR%U8-fc=!25-+58jv%%!swGYMNjiPN0n|0%T4Vir4wr!wKs?r(m zHC72=r@AYbTq;s#%veR}XH`3)b(WW3OhvR?IrU_ zTSvZ3!xbNw;(k{mJFI{00go?&FNWj2gt^mLw`N_SwVQTaA#8qn&&4m1AK- zrpewa`_s-3veHPAR45+-18tF2yTKa<$S^~kF(j!WZ4GvIsN5t680GoS?A*H9x!%WI zn^};=x2)|+=oz#TLf|vS0E_F`eO$WZHysf~fp1JHvjglVrgO6?6LJL8SgI<+BPQ#; zk3(I&$xBSIY$yy``CqDz##)?+nRM>OxtmO@ZFJLcJ6dd9Z))pOGG2^cdq48&U4*)C zuX!NvdLE_bZI}K5I7uFDW4-9s717 zEAb&}u#T3Uy*fm3U5cQ3gG0j#@z+9?@L3R;IF=GeJ?zdw8a}UNxU_(AuQK1tOB*ER?t)X#;1P>D2-QC?KxVvj` zcXw$V0t9Uc-e}_*Am8h6@4HXkci-8k-rM!6D5|KQ3B8(C|5|g*IesHbEBiMiOLa;E z8(tpgL5--NUdIaEY8MYEMI-IhYLY)9|C|5uUS(MfX*CGMkXL<=reOo^3i6mE0#v(? z7c*6edv5B+SfDu~5Z_Pkz3|8RGiP3TWE5yIQ`jKIBw(T{o2=!sX19{lJDCz^?fag# zEw^2rQ-c_O#ZzT4w~>*^noJ=~W%nxC-EjckPj-4m)@9*hMSr6V2`x{9F6<32Xxf#O z$E~k|`8+4?CVz8XjsC_bDu8Vz8XiTAw8q=>USaC~DL;$MFbqK4+FP6`fQ8LWYh{C; zX|IwJ(mS>tS>P=p3Y;67zp72{h$|0_ILw6ij^l_x2=lFe@Ueain`4T!cAzAl(=gT0 zbjno#^fyTR)0+sojGFZ~hJrTi6(Jq6%ZS7@qWq1 zWQVFqI>zfn2m@UF>YBR*Zl(dH=9igGu8x)qQ#-`;&Lq6Hp=~V;7Cxu#K7&6W0`x)G z;S1Mzs?)6swbNb(lMP?KR0SROsHrWgn( zA#N_toVrffrlT`jx1)l+n(z^Jr&BCOt&wQEnpiuLZ2;Rnd-|erU6gTtbo*p_-#&By zKJDS3O&*+7Ce;i-)Z<7e`jV9w#nTm^*Vy*H#Hci}v9xIJZ3M3&Kg$Z1EJb}evD6u0 z-NACyRl{&_XRTLJex@_zJ5~nah!xZR41upL6QMELeqwyxO~)A&C6-t$=Wkaw6tq*={!M7ejp_V%B+v$<`GlT&!KhMHYG zNvYFvrSnuP9Gt*3Yi+FivkvZhaa0Y)M6})%S!QPQs5{$y=~jpjG%d+qb$%}xuPObe z{!v%v0s`r>spjiHYKAJc$W|{WKh{uVCmLTxbPh=48rn}0SY)nGtS`4%^G@Ambta+P zwC_IZlvVscNO%9GT0~>@js4=CkkIprA2M1M_@mz)AV8HSpo`8g5HSXmo?L9;U#*@g zp!csA`0AMAO5yU}6Ki|u^t;6jQB|rDiG%BJ4iAbMTK=JP#aJ&gg<+6}9uzZ@rH+ur z3Jm+V7c&%6h;6)m3%QDjnVVauid1olkSV-NFx1DigXh>4bjJ`1@NbbMcA;&2WB)AF z@A<2kRqY-Twz*9tND`ua22U;uOXScJFH}Qn5%j-^jx3w~%%lYL6?Y7D96Q{n3Rizy zNF&v8fQYk?7b22LWExlDZ_;t<=CbfN33zD~Q zzd0#p{Pgs@Pq+uBjb*FBMO{ZId0+GoOXx1%zk}_9E4q*`qZjnUu8^$rjkk;_{W|#X zYjDBYMxwZTg6-in$RnX9{4_cvx1HN5W)KF(3X{h)2fD%nas{%DK8Ft>P_K)KuEV6K ze|$jEMA2#Nr>CS{A(4fNWoq6DKgqsOMZ3eZBZPw=Lt(((_nEog3FkrR1?HFvaL*W5 zaIil?qV($1lhpsHG~qOVcPVjnf+3ww=t-xI??I7m^Z!eVl2G8R5X9jvX1v`~;{l(O z30Fjm`b12M!ol>ob)Y3$Q)EztVG8Wc0~CtXC|t-JgaSPx%m0Tv=HK5-|K=68zy7nR zXWUS}M5nFg^CDP_%pF*Q(jMw;24NX&d|Y7Cq#f6j>exHy)YA^OuH+k6WB()9hG*8= zm^>L{$xJ}n?t!FEMN=#T5NPK;K$(cKkO96R_*l_|WJ;lgt%tVCxgefMf#uWRULo$o zi7_A7n>daKGQ-iuqFtA^NqfzI;Y>U0>`b$PKaX%3{IednUgc}$?&Dya zV+mXNT-cx72i8}Ihp9#B1yh)93-JXBc?6&R( z4tx47x2=w==CtYR>{HU1_HCw)kY|}t`j%Q%!+L-3w@M*qstRM7eas+%$;rFFq z>J{}*r}o9~wUfD)(o@IkGd8&ifq?SIh^D5AZSmnyKBxW#fYgBY{mCe=|DNZG$oVv8 zlU9Jsc|luZTlrNwMblcN-}P-{<4dt?)THS{G*hzOk^^k5(xk>Tb6@c~pI%~UMdzU( zUDmrbrKwoy9s$n2?wkGJR2|pd{0dZrpeEj>Eh!2=b?3m)IaKoUr^2S9$)2sqaP$g4C*}}5sPsM>J zn>WL>Y1dqQA1&dwN!|px2JtphM{U1=S7!=);3Y2Z+~3oJGb80cbus3vIQHJU-)^%OA3u&%UBPUl3d9ts#8gcioZV?5SBM zgEn-n>(Nbo? z;c6p9awfROfTc(HMx^_dqL-o0&e*|6{kM&m_;CWa`-rDy1X%{@@da-vp8C!v>D;z& z{?YMsK}sG#F(vaQ>lc{EFab(EK1Tuh9@EloYVdl^^9%*$5qFgKwkt0A^K`U6f{mbC zW=}EJe4+Mmnh5r7xtd}OI z>x{l#%>=rf9i!`B)D}{SNlj(tnEwhtS8}aj8GpIVk8+MYte_9XzK69Ldrt)xd^~c6 z*>Ra=r0Y3j<417*)ky=nwAS^3QHQ3a~i^`mM!@ggA zp2!)(HtVHn1s@#j*u1-cA-hX~+xCxntpC4U#EtNc=yb~6yGMmsVHhEBlsurWU(Ruc z?Re^S+6#9_^a6O3a8CXZxE!E<^ZVBybC_=?Ga;+)cf!Qh6!%2OV_;j){i*k*$lYW**`O)~J!bKc>=b3w58A2QD_4Y!wsfaZRQP4+)E z*Y(>vEz&)M1^qlQNMYa4*Q3sxUrOurkPZBYlY*Y5-CO_REzaZTi1SLWa&NuWp|6yX z3&pK>boNozwa_f`;D6zF^$b5^P^pxuATdvZAN9zRPUrUuFsV@9tnqC4~ z?8XQu+;5coaYlR{Js!6xqq={~Y+JMo&4O8=E4$lg5sA%43Q%dwIxYEcaMYVAo6|QQSJq@e|prWk6Jy@vHWM;XtcZf_JEB zfF10t^sjuLcRlPWYWX_T!FI7E>Rmm0nZ0w7bxV2teBAA7ikz^hx==rOAs1C$XV~$A zbUSv@9^gmcRP*QXJOPE+Q}oj&$xHOjtzXIEuV?JF0MX_^nwQ+{c!N!-KXJtPse|Y5 z)(fiWm0#@&tp=d`oq*6)sfioBX`!_102{_`-_~~jx+g>XIXjz`o^WPEpG^UGgW291 zHlm>)eXik6T6=y4_SV(FwL}#xj`S4o>OI!=71R=lxmoTsS9q7bEn#XBr8yZDa@~v= zKT3Z+Jn9Hi>b0Xu{!&9v0p6!|GSZ}GDUI*h+E(9|9$QHjh|8V)&cf?5(6AzDlZvHB z{BF+WV(jMc+Bxo}>>&N@6FD6I2KEEazcaH)WusG2D?&;e5mxh9g(Y?OI6#X<$uStS zkg;G~;qn*cEZ`q)sl#sYPPHL{Zf4hhLk){}G!5XeQmnTV@GNzhnwZ!g7{;>~XB zHFUKbA6pfTiSagwf13EvEQev;L2X?Scs7QoIqc#8DM;P;F@X4+tlHIAT6J?$wMChe zY#EgL%tdUj(gy(MI&&78JK~~8O5zQVtOt5iSeU&<>C^~McU2`)p9#-QN<}$d1T|x zNQPlpSA?HCGiBuw4731?Yiu@%^hBqVnIrb|vHe)Iu5#DDbdS50?DqQg3fO2NpE5NcAjVQxM&_|m^HY_ z*!iALDc{0ru&NnRuVRQHkJ!dybG0XNzF0$OqqR;b+ukCdXP+Ih5$CV5rmn2*3aaYFH6B~Pkf5k0Ccxma2@ zdU?B?a6>!|!wUWgI5)I1w1F9b0?urnkn#gkhWcM7$IHJtM7s0^!&uJ7XTwgW;ABWA zr~5>5W*?|&g=PdxNfnQbyA{mk0Xb?pJAQkRlGvO_Dlxt!@d+0TLk$ERSLjXTmFIfjqzXqPp!hsywlKNugi){bS8(>)75Q(udkBd$1|y(U^a>j;r0urBUg zSWw~$sS*~~jxgy#+On%^!>J}ahV{&B?^?GT;8p}l9miKr3vM+QVC)q300dj5r#ML9 z)RCwsTMJuF!EL_>w_oU-sO*m6A9H=qZ;tObWsb;Ic`?=J%r%MP}V3ai~l2-lfXGQ{#;BbH)ZI0%NOVA#`%%Zrc=E}$;`?}$X-6@M>EI+ zl}&JFZS@r*)q5rlH3@Cy?JdH4GD3(}%)XORF(P$7_AS{TT-&?g{F{9O*u%agyfYkI z0c_sgaYg$3DCP@QkXzSN)K8HWSobkefp`a7iG)r2Z6XV+B7<(q!QcjEyr{Z>26hL^ z%e#3TBfUO$jK`xGCxFa35imXZ462rh01576_F-+nDA^3R}rxHxcgQsC&F>8KN0p1BN-D1L^d%o&WNb; z!PSnoHdIOf%>GzRR7`?{{hIe`a-D5kAW>FKdpHgVI;NkRWJ@WdItH7i<|H{PEbtLd zcIDv7D#l0r6d8*6Qxa8T;8#bEE0V)6(J_h745|@QW#EX6Iat()1WM33*?`XXfePEFT&(sk@}RzBz#tmbg%TTD|#m;pUD<1bDW$ zjbi3hM)3J*^d{Sh!-SKF!ay>jA8Gu@N>n24J4?e zjV$iN@16|gU`d+rycch8M9p)S;j*S%m`v<20)UI|z`s0?_>2MfB50EyDO`FO(CDWj zrkdQAGx1HW1Si_x zvS^b`1=G$?vlrDT@Qw%Z+h|AW8O_F}2wp$Wc-;|w5H>2GTGDey`_Vj&%UW&07D=cB z6%+6#o4VN}-Z+{HFl%WqUe=RDT;O~aR<)%DIa4$1S0Jg$+#5XXVQ(C5Y-PD3+Yc>o zH@7ZYbkQ`GqiDT)>o3Qc%!+Ntb|yO_E0RuRv1fI#Yi%j>es-DyNJmSI>8m`x4neV1 zyHFj9+gcs9q zrdP|RbqknwNE=DtNi0Y$8XYcN=)BU$Cs7yE7M?7Szyn%mQN2y012Kd;0~HMybZTeX zR2I=wUDg*z`Khiz8Z>X%`5s6lSj(*xMnOqAh}&wxniL18LG*%YD_Ubp8LH(%^{YeHpx5phb-=_h^Eb$y!{z3Lm$7C23_t6G*!D_2InnJ*n%w-*?N^+pWc#h zc-&ND?%*Y@R`omV!0Vyy$M88Xf-z?w`|O6QDxAw5s~Jc!u!(JaY0>`)n(4ZLZ0lB? zzneXQttxI<@@?O_5uC;@b@&z|nA)pIGo;A)2X(KSxNptu%q)2#@h?;CHjjF0J_OV? z^DvEeCQxn1>W8=}97I!40EM@>O<-vmTB-@Ga>=J%burpMC2mh{7M+nTIa~mxO-RCqYhV{Ff^<)Mg0RTmO+rK_0W69>Ke1LATGNAT7~yl^oUw7 zTXOZcaI6`+oSe)?;Rq>{AsDA|lLXNdY|$jdw$8D+%G&;;xLP$&jRe^%|0Mi+Nujyq zWiQ#`Y|HFmwR&x|nK!B2U=zPI&SS03?BKU&+y!ANxgN*z*)(a@aq;~521_qKk&js|px{F(!lpQPtpiS_4U^F@7 z=qK+&a>h98?R}S@x*eH0&|azA@ne}{9SCwfh|o@K<_YfOF%>Ln^gZbevl@wc=3sA3 zE~{jUKv<$hO)W0Ab6%)PmYl{u9U`>`HPyNN0ZROU=Gv-XRND#VKf*&X0#BB$-DA!pWty| zCTWZU?D`T&DJ_Z&_T;++m1PQb@oq#YVyuQe#30(HI?+EP9x9wj$3zN%CIS zW@YShEV1t6N)xo#KM5?X%dR6A5AAj68`_Ph#)H&DJx-(Hr0FGx{g>L#E@BRZn9?KO zc|e+a|7Nn4aZt>B${-=Tp|<;D55I1=OR@=V&wY;FKO;*HMQ{#p$8am0X077e#XLdj z*nY^;wY)L1ZCM+wbD(=H`1?4J4j9~;@2Z_?uljM3;sRNmT%)?0Xrp-s@_CxcFO_@F zOiJbD-0zx&X$-8LI*AIJ|IjK?>KP8Vrx)6Buc=GGsm+?^o#$FmAdZmJn;?NCN+ZYc zx!PviNi!JhD$PAA__<%1EG_cK_eDXHt?~tQj`sfx?`9iBeT08fV0uD+XXVAR*V|Y6 zRqZdhVBsrzcTekxAU2pK20&z&!n)RU3bJ)w}PH3`OM|M@1va^!hE? zj#)JzU`FeRNq&3l-P|OvJ!UNUOcLLCI=saey4^jQnNTMtvFb#Zy8-OH$g=FDomu(HcXCIY;5vlyTpSYRw$1;Lz}Sogs&O$zS12x?z{x>X&xCyY!>;yf2b2 znIKbuXm!t3=YJiOu2J+X@d#bd)7jI*Yc8X+*A_i&y&|%!tl9e!jBSoUPaW+KdFvPo z0JU|BX!LVI@1@Ag=;5>R!OHk&L2uOk z4Bfjca{Jv3@%jR$GQSK9Ro~yE@s4;SLdKjmHcO;!Vg>or&ejNcdCi9`LR5Pb1I$y^ z2WQ`>Ar8d2b&hdBzw+&^)}*!EExEawk4U3n_0ctEoQt=ccWpTeJ?N$QTH9yy$8bSi z1tBaZI=}5cH${Kzh%744x@=9_>O|Y@%ozjE39r!nTGuVD?MEtl-W9A6mi(1PFX#RH zJY#ZFhi_?Cv*DV1;mnLp=CLEDX{8lFtg@f4SDw_J=yCmE0gY*|Vz{gSyhB~nMDLJe zztk}OnqbOJgA#Aeo8;mhEe#b;$jy(Ht^kh|lyvWebb=))dgalmc5 zV$o0Uo#0NOHvr?OUAS-FyV2fC#{(YC2{te_UW8~DmWqK;5~}Q3nXXy+eohyjvHO`8 z`G1^ve6SPG?H?x|-#<>gpW%g3Xbu0CY&m&QBM79RULyzk54C0w)kdE-vz@O>C4Fq!?r(N)GrHnHzk zTBiAajm9ytbDG697?#*`zkyjTm*ZV0vVK18!#~myK0K&mqupLsMB{?&xyG2utKqQF z(zqummg0OrNYbv(2aeu%4dh}{3ET97Kr`^RrN0y&wA%upWK|=Jc+SEr%k+KQY~#He zhs1-^#6x^4E0f+F_Y-X_H=lUssLG+lARi6JMPBI0KX9qbFkEWY5kPH;63}eFMAt*x z@PM4<@3-#Z`l$or#6vlLA6CSEHn&#<&^s@UK(;OA+Uc@O&5CU)b0K!$EGuv&yhcUK zQVgm8^7-ZYyIW8GZWK3AQYQo1*`hzi*QH)rDFRe|R+5+}SPd>9?JTlSN z_}`1s@>v=4W_@4BvdH#^HS?xO=5tNuAW|FcHP5wSJHNDUiN}UT5`+7QsP6FornWjX zjhBTmC3Wd`)0=Yh{Xz%hrgHjc>j zIPMSDUqqN5DV<$sIL*_&Na2zW=91!)^UmYuXm@!V6I?fjsn6H6bq)^J_5zv6VJq=2 zYX82alVs{onD`5BV;(0C^R3t$=M%VM2K^t2=-Q#}HdL!dRDB&GB)`ONV8p12>i$|@ zrHF(n30*aLG4DvS)gZqX$xa|uo)jDeT^ObV6pLY=oL;-z!(nFcd@PJl+6fZaf5Chctg{Vo5@2+E~mRxgqFD$lwCj@|UTk3W%fat&=Gg zv%bkPhCgFKPpF>rp^9ucQ)2M?^A%P?XP^?~fu68g%s}_j(|3m{|K5QZT}v6KG14p| zvu`Be6D(xZ38Txk0mBrX<*&JJU zVc;<wry6NqG2E_zhTluNv0_)7zDC4*vJW>i+|4;CxMe zlLRwhw8Fx{HU7>K|9k3s@ICR6moGvy2KMou84>^2bpPK>WdD!<^1o3Z{%<~pfBeAq z*MFJ?-1z2J3=cZUTHXEGhUue)BGJ-9pGctVlr%`#m(T&2Jj3sU#ea5lKhCgBTJmk` zmWbkeXqluwAX^fXe^Pm;ZlX${^QH%vU6T5^aIla=xYpUucu8H}+Bc~AO|H0(p5%rY zi41bkGgC!16XzMOk|gu7^(7xly{(=ufxEdbk(tw5cK&_t(h-DRBECf2QWro9H+>Xv zvpt=dO5$?qE?m<(Jz)sx9E1^ zTY0_h;@BCNSx))UlzJ;Rqt`dT%w#svb^c3mi8XfVyHrKR&Qv)7=wK-e1LVk*tD7&Y zZL44u(gDB0!AaOQ3exQ*+r>!YC;-w{rzzk*&}91*!o7*2xrB43^%yhPb5Usi{odF% zkGXMNTnC;eMM2|V6rCC=X`+3j&k#4BcPFSdMU;;8Z)|2m@RCy51dLr-H%Lj|=k^+J zeoo)flX4QW;_=KDsKwbr6s%;$M}EFMKId~juN{uw9uC?IP8qkVdT{GU6wG2pM}EFN ze%L}2-t1s$zm2`_*3oLwWzfOzk;XvQhDL4WEUrJp@bfkv* zjG?+dzcZQv%GW%l2hkK1i+6P6vtx}7CIZIr;+CT?iKxcVS9Vx{f}#8z4z8IZjaEX_O~YM>a$S))A zk^Z!5->7BsvhDjj9$Ix%lWy{2Pd8V;D(G}<5Q3PbR=(X;r<87Pq7)T$o_ioCuUT^~ zS>uMOw3|ftoRWNF9O>faGtUjgUniqRBbDW!*&!5ze=&!w$*lNL-HD zh#|Hjfu=R%akkVbl5oU(n~eZpz6kj83|Wq<+%TBNWlI=CIrtKn5#%D_)@vUft^2u; zo1@XvYo`}Yx|+=Z@2AIraNEhtcQfz!$-*%vWA$rM-E^>S?x%}m$!HimWsz){R(F-u zO0ZLMc-J(ProF}O__zTkrS3vaO_kFES=40jXvGA~qUPd8%R_^lSv!8d8@-uH+@GFF z;aLh^u+Y&|mE&aEB3vSg^_3)*5uk~>_`5QjL=PM%W`ln<3j{7;k;u67c%YC8)7Y{| zQ&V}wX}V}&9&b-8ZAxFrM_VG+q&OW=5vpD%q7{9i?hHa20M}s8wfY$ijrB-PS_;b0 z%Sn>51Kc~gu;A&2_T9tc@5Kg%o{d1UEWRUlrLHX@ZY|0xA&0stpD3{G0Aj}<^IKdk z3@~(B=k-VVZS)$JU#BW_(ONqNncp#zqB>EftG9%y8`EsIN~Ts>2Zv^klZv7KJ|!6M zu%MOAb9uE_7rIiOiJ8yb_j9nNA#KDwClRyl@WIkxY<^+G{yyjJ&{mi2RZ$MIl6Mi| zZB0g7i-{otWDsyMg&nooXSd~&h026wF$z%_SIifFk-F9S;q4ndX& zxm1vKJHN`WT|s_KR++jw8^ndrKkHnKYO4d#JH!;)>#8WJ(N2cCAU(Zzq?H{Ikj zfmxqVT6{)NB^5)<;@9gWR_uCEmh`eeOiiDh<*6B&at5!z^$QL~swR zhM;47+Wxfrad*Nb{e%8ns4Kl`jNS?Y$;ulO*w=fi5i*KPW`Tk&;9qc+QLjvCx3;kK z#lR<+feSiy-2NBbaQh#*zu=xt208ki>NBh91H~g=UkdiUVY4Bo(?6r4FTVHqe`-B4 zOwb?2pJD7Mo!WN^T!E414d*Nq+9?|8b;uo@O&Q)-td+o+3*Dg)`}PH%A`N*{X2jRO z+@vy}QmWg4Zqcs5L@L(zXc|ClOoU?=dWvmsf_G@ZOyH{1daV4^`g~Wmww8oSrd(N8 zJnA<>czjkT)bk01`yU-5a~yY4`h}ooGEqc)_2{f_4f;g|W@O{k0ezt}Cp);w1%TG} zvZn)u9`dqN^nBWBslOCRZw*noX@yR0P#`J#3ll|+S*>x~)i0$5-D->57Dt(5-kN%5 zpFeTqaL}$}stpVUsxqhJU={iw#Mo=l0GS!*C6i<%jpdzI=mJ;(NP^4fa4vIzMx`OY z)*5QDs$GJF1V7)6v<9M1yzz7QYKe1q_rQ;Amt#3+jd5m5!Hx9pcdJG$S!WOpJwHlA6U(*0G_iYwyulW|D$%i!6Mx8 z48GDH@QaX>#d?85y{_zbjnZz9FScp+aN-GXxnO2l&y4lPOjqMfFUP%RO#=;;VRJvG zV_pYHUGbSvQ7vwFo0w~qqt1Ttv@!aOwz(a@(3KIaLar?2SQ8bSO|U-fmCHuqx-kV> zA=a}N!P8swU`=g~{}5@a6^=Fmj@>zr&r19JC2QB;j>YW92nfT(iB9aWGb6497AxVE zAm#ZC-P#}elh$<+eGzy2XW_SdSb*&Bt+ob-dSRc_+M z<#GrNZ_n`Ha^u?Ua^qu?5EULCl^{9%#IMbJj{T|I4O?J}#U(Ke7z-zY_G35MEwwoCOKj zFL{c3N}I&FvCj9`17c%g=Lnq4(Dna!OdZ32gQ*kxe}$>bUMZ@7879;{ZS3nCex&P? zGYyQ2f~8t*y`&=FR6nw9#cRHK6<3A@LhdnBGJ)j|zMLsr+~s&b8%C&NFqCZFFDU(Uo}Y) zL<)Q-j03nU*kd^kLQqA3@fkX7_0cA>6t$y@*yG86@C4nDA=+qfQW@jw9p+~RlgdsB z5ps4IM-F2mC^Ijg9lZ^^!Nhftieu8-@xKx#s<>%`(YcZG=3k>;Nb@8`g3=$ifCSb zdHpf_w$qPPNo2;nweSa5_x6XanDW6NT_Wg}L-!u6VpJGkA?2Mb*Ql6w0v0mf6a5T# zk=}QX61uN8gG)b+ZXOvTvtm_U2!#F|7IaDWN{Z!uS~k9def)&j*y#MP7owsal2y_6 zr?OzE_tQ&>4!jRl)XcJ=1KCRZUNL}G5~T=+X6yMRp>z~&-?Xa=FX0n0C81Y~sn`w= zy}5#|hUWaMwfJv(2>?K5-~$xql*ZTjXO(U=apoJ?%IkU-?R*KTt^>S;YRkXxQvc&u zV*cYy+8X%!XM@M=m732U zPWAB<9Tsf1kNHdr-{X{%KDAr5c%?}#l%{w}(rNNLFxZajOWO>0W!F`ET6d%?^dzW# zMTI?xcDo~VdRqU~%9Hw8nkp?$r^;_a;EbuQ!bq{Hpsis-e10^>b1kgY16*eLyS8E~ z635zp`coB2P*~w#aDk;x&|4+3m-{~Ml1kst5z799;lIS=(oJ1|C-2~Y=e(Tep^Q9-p>0-niep_*8G@d(LPEcp+zE1?r z6QbhR?8>^!t?|re0U`wfkbXmn6aDpw;HKPBuAXeEj)n7b!WsShn5>y%%r4+QX9WIR z@7&BNPdyXAF$$mS3;PNUHRCIzCAYs>^wWCJ=Tw7$ln4{}Ybi6z>>XpbnV(_+BYcvv z&rqAT?`WZKYfHoiQIx17>>lorExKV3_hQRa*j=yP&oAb&^Lg9VFXPI)4_jq-RH zjH&7@W{#}eU0!CmvEGp;(48v;WZ4Qu$&76IBTB@1y2`FYlP^Ax=P`G3?SLshROIXu zsH|w)5?4&G((;IYlg%U#F(%%jrn5s&A$*ukUX#h{9+UEa7z@~BC6OpTTP8FltDGUg z1sD(RPdg4Y*#EgoX+xTddp?x4Ys)K>mcHb8U*QnmHu429r?SBN1Fh>%8>#(Ya6;bK z)%$^14o2*Ed%|wJC^5+9 z`j0VOYlPBN22UPq-E{WVmFsQ${w;YqE*MoZ{W`!Q6a8Qn3{`Avd17|URrU=es)H)} zDHSWabRFw8l$KT}wHa0k72$f1^s#RLnEa!>0LVSnZ{oMpzT%-MQ)_RSfAs03M0{mw zX+;Uq`7+K_o?XUBHbGj{cwS)g&_!<;cBbpQaGBX!Qgb#@BcuJwEn#hOj4UeGgs&cI ztAAckOcdatyj--89#x>d`Ld5k9jvZmyFdMQvCoYEXQcRB6c{qoW1Nn>0?`fSKRoGGz%(v$OuU-D!fiE0xn)HRDRoTzP=2Q$<3wd(Yq4I?dt`ugTl&-_xj|8VM`m9=+;JYMkC|;Y{p(^r~yW7Sxj)v5i!i@iIQ$W7;_d zW0MtHduBF~)h$ zGL3BWRNU7WQr6Bk_enuo#W>(>Xg%78xA6eNPlO!%E)EU#ZGo^alBu91h%n>6KL>~+ zj#gPe)k@&cimM#<{QZrM^-=y<7K%#?3=Rv5K#agXtb_Bc(bo1 zbw{p>!(b~JpDLSkHPUo0KMFEhX%VkqvdPpbW8%yk# zmjS@On}?;@)9qQ;;P>LU(@b9jl3DF!mF=WY!O0dIQ#9(iBw^TzZ{^AU{5p9_m|5e+ z*i_&vA2ClI!*-v%BKgV28ka$ozr8>Nj>$oeH>Ep^ti9&sH;a`S<=V}`N>?ReU114f zY=X2A+?KoePPjr zUF;!mtKT%C+mv|VL$GP?d$;tras0{&5WBhfnUKTWa_t!40=|T=hK`6_2kXp9J?EC$zrC+C0Nq?YCe7P2RBN-Wbod>jWBZl+YNwBNNSq#Aa;v>1 znMDvi=gmkA`}zbab;Xn|`*QERfE0)RjI;|RqQ%)X_s5&)QdW5bULkr6|3ICqHKfnW zt+noa3o%pKt1CEm-wwJxdfP75bka{xnQ)OcjuYIjSB0vJ{Jwu%6cAotDaM3|0?@N< zPp$6@vKfjhr<9cyofc`lK;;~&q{MP4EGWKurT}Mer*n5{2a8oQhY{w=w)*TN9D= z^xRs_g(jl9M0sQ_SKdGsDb1IKzl0 zYoY|dk6ey}*HJwkdH7DP*FmbC^QbJQVrW)QRzbpry1~WMQZPO(d#J8v^X~}h=pE(e z@q58`Fp2xmnRo$90lH(@ZY_WCjI9y672dW#{ye-9F}CUo2yQ3^FP8Kv3$TfM#b7AQ z6Wg=i;ArX2=AcJ}*9l$r$R5cIllpvf+ZoY?PBi1LxVA95ug;k$!CY@?<&F9X1++(m zoJaF^@nnREi?3A=Zn|E$XhDuovBab(<4%=qXI@-tdSTZiY;kq9Aa^*m7!$!!keUGeMFwEEw`ItJIy!9)3#T1;g@=C* zU!>S;cuETsK&pp#b{%6a5WHod6_?eH5XTgM)F*+*sX?a(jJ7}7~ z4JeX!;po`KxKMbSd;B2Rj)odwO&;Km2(5s+*yac1P}}z3gh|X|<8PGmX96CThuY z?VT6nAa7d3N{M92m76Gwbi-O3Irf2rx^-MKHw{kd;0=Kor*QHV$|J7X&#TDFt*A*z z1J*VubBEQ)dDkrlIiGHYIZgDPD#~bsLfZieFs1@R##h_`z(iFZ zGIADn6^(5vuyM48ZDB#|?N)eO@>6_gWb>JWGUiD!VEEs0yc0LDEDfEPOBC2r7x8ElNy{saugno5|Hip($ zkHH#e8#y?1rXV;+wowUXluQOA_8gbTwi|GRRgC)E0l3ddN>3s%9DK>qBpq2ZY?8-_ zQg}n&Jc1*MvHLkA)#L00-4&Km6B&~8_{59e!6i9PKS_(G-}`r}k1|eYKLEA2iYm7J zz;tQ#&BZ)UBi0)nc~YrgFv+9bP%2={vHBMgRs1`Id&FO>$~b|uf58jrJ=T)r~#!_sr{$$F^by@?XPHqR6s}80(Qj zWyl%0F0$h_o(>c6lJf%F?JidZzU?V$@D_uS=NExUFr6ZRjX)Xiie5(leiiIjU=!IQ zKXxiVAZWi%dAM6lFF6_DL>k&6UcdbaGt^e&uO{-xEiIGN_e$uLBpl8yQy*Tw!?Y<5 z?WgiLU8N$YP{zAmJUAscxRt&(4Y$;}_go_RX!$g8@cQ~X(hL}V# z9&}Mx7z%&%e;8Iesg$2F_~r%LM0N=L1LrQu^&|HbhiA*U7_j;|_zN7F*uSi?|38i@ zVdKr1zy7nJU#!T+ls(L<<5wY@Lc10q57snKxYnWrMp7p3(sw zE&cVtDnt>Bd;d%gcXZ%=h=~$Ks>DWIyZn`A>P^=0Uh#1Ck!?e^IE}lrh=#$(>>EN` zZ5EU5$z6AweX!1k*J9Hfk!7=&OQ)kF_GxkS`oW4#7WYP2X?`^ZFugT-1b|XUuTiJa zS__(fy3kkg32oZc;l;~r$*>$p?KIcH=tLqn%~>X=)Y0e@6=KrZz^&)yOmV;i&es-E zBuC@K&!{}KN@CGdWR?TMronO*Gkng&CzpO`A9$4|CJM`wQbtK=y9lv21&4KrW;R=r zx&cZqaC#y0F7x08sP_b z@Zs$9jG^^|&qWQ>IhKjzcXIkRLJ7@7!IkmoB{gwpzFzwErW-5Bp(b{p8cDye;b%Id zRHrrc1R`(VLq&K=L&3H2wnwMmeaU{|o9_8$?l{@)nV?335XB8U?IBh}-eGZhQT7@> zo_1GtR3jStwXAl#%zRD$8!gop&;EIn-mNsHG+Umo5y%rP-y>v77jB9bzj=RDsN7qy zAmJr97e)c@D7aczn#9d7N|C+ywtXA+J6Ew-Zf0Y7121H8^crf*E}O+ZJxt0&{?m#7(UcDZ-Z3D8-;0yCQ|MI~yD_U$Spl;#f%P{%R)x{^NCX;EpH#V$b=CG}@n9 zqi_AcX#?pZXph00)Zg&N*jJmz+Bs_KaN6AFU2KS0?}m6=mJ4b{4y8EBO5vb4F&3o5 zM{P3fNhvl-B>iT=?_GiyB_*Enp4F#($I85Jeeg7;~@IidqeQi0H%vaF89wC&K;IRJ`Z1u(XiU1RY7R z4mfvg>JgV*KyyAr^e#auO+36hUS^I6r_o!=3r2_S}r z?tEb#Wwa!!0(jYx)cIA?3M8D~5FTkyMH0n2ija3Lh>q*|b_1MbqUo21s_%(oOq@qK zi;OGFC9^b!=n_h4^@jZNXN8e)g`tO% zxakw?wM~|krMJsquEc#=3!(h^;u3mjwlw)!7I7k*Pku?kh~RSk#{}XxF78Iy?l}FF2y?FLU*!FS8xy0 zxZ|5+uHVy?-KkgF6G^wJr_Qf~S7)*DPE^S@FENzTudn7%o^lu>-HO+8>#_-}==C5> zAg2I5Uq*YTev-Mb*NUvFds=;1#FlHRXJz%_8o(M>f$*e449NPqGa4HY=-T5aki^#t zov%jc1h`@O-q!B<|Dx`!g4>GLEG@^Fn3NW|o;_$84FIA%>WlL8ipaF@ww) zGuyEpC!>4&<=&dPHjoMbk5mz_W!T-Eji^0W6Adh!~}-kfRW2}shskE z4()lub6&DN+1K0<@p$;Xb!EETmg7WPv%kt}Nw(#FdD&x^biS%kS4<5ZNFo`dK<AQ;k6A< zhyHZwwlx-Juv0F}cGq1LibB}?1_>EeL}|U29OV!>2bPP-Tl#KRD44<12XSz2*P?XS%Tz>6(UU_qj&#^j+K{(Y|rAvZ? zt~AY&kWRUKquX8i1neU9mD@Bc_^7K0$%Nk7(M!e6b5LcbqEJX2R(ZVbQ#6|)(9nmq z&{w7EQ@Q!6>T00zawziQMS*HeJzAil>!!#GAL_eTu|6o;Qw#e=hq<`_8SyV54a)S~ z=+^oR*oFKB&_cKMO;%PJZ7wCxepA?_f?wl2HGEOi%1K46Ci5u9k651KO!&Lb^KIZ^ z-PWyKAXgTY`Sebctp<&vz?c;O4k5>CRUK5Q_r!ng;Qp5}uRe)in+YGP3|tyf_k`sd zRb<^Kqjm>}%}&g^qG+>l5THoNWQ^c}DBN_#itOv!@X`S6YGi%;HVKt|Yx)wbO>~Wvm{`!bEi-mtv~(46PkjqWO8db2(*a zA-A@5%X#n^ySp20HwY=UZf;%SPEbtEgHH@)0I&M+m#r{>q{tEu8a zxL?HHkWW#;%dMOa#i>^Cr^-A&n~m_WeS<)p5v#%KKnJM*A}3EpjmDeJiC}rea5X+b zc%Dolu+VrbV|odfaFo^g4tA7li#1UuO2-Fc>#U>2m6@x5YP>AFJY=|9z$~90ooekl znK$1+{hgf5Z0ZguII|XeKd~ZfJdvr_AL)OM~>=e+LPVLqx-)^|LF=}PVqSB<&iXDG2BD&6oR59t(N zUKB^nH4bunV8`(G7FFw`68XL{KUk{!RAEezs`I>F1^Pzgw|)`yi7#G_B(?JR?T^*M z7T>pF8M+$5qrp|^z-yWQR_%+8s2#E$6EVr!8jfBM!7l#w_>4*vwym?h>yKY2E zCNmb>)Au+OF?Q?_GIC!Ax-1?QbK@3c?9#jQ)oV=?Qd2NFTi*)=V-jEUAF`Vlw)e^0-d^%tPT9@W>(M)DVM6P3$Mye_wg z)^Ke8$CP#j+AJUa_1OG*cAtF8ucUQLX`h;$)qP+~|K03Vu3cwCukP?Ezt+Tn^;qEO z0ugUKe5vCvSc2y=a3U1^oj~QX@}UBeMXJ#R@(|w~hKQ!ZZ_tX+=d);`v8bWM>Q-5~ zKoNY6(9{isns^TLHA?h?cI3F`tX|_BuD1Albt7tp-VR~^`#}%oPCQd=btR>BF42JM z!p)S#+^(i2A%oQwT`d9SvE6uCNJn?S-n+@=#c_RMeL|waj>XnjEjwVT$Z^aw%D(Q+Fi+3WftmHItSYY_rYtmn zCR!t*%}Dg~Twm!Fy0mwvFx_jnd>*RE{*q!2?F{>rB<{dMI-%(A|Fomp&On_0>8$}8 z%IYv^g^H=jvQho;NPJkr_HjC$;R3P(&C&JBNqqe>{HsS>W-J5%06=rrpw0FL*k};q zkSLTV6rm%;c_7v!8vNNA)J#$7iQ_}=^bg#&iD+`^WZ$9;iE5=!^e{9stdgPV0Y+}` zHC_7ornez3=x3a}2HFDJ{=sXj430RQpbwO^q`{cN&lxa5y-aqs3DtX+%ex5xvKlU* z8De2xGGT53pVDOr)y!R?iD0GYA~#SDlrkD|bTitlD|EZRni~c?_SrA^#~jX+?$#2f zd}aOqn969wK2*$HF}VzE@qd1Pz{Gnb`vpaiU&5jLLYYkx&u*{%&d@IZ(L01A=muC@ zaE0GYL(~lNj~@>ydv_ZGwFV=Ng*>GDkc*{4(|VhPg$BnVSJ3PH!I zZ1? zn6?a{B<~v6MDnEjerrc9?M%M%{L{7(XQ!(ByLw403J6LSF~u|r_@O9sH_u-I2{n1dhb+|NUe{pLqN}CH$!1qGrQ_Uv^@p<6c@SSC?=xDH_o?js|IOs z?h5a}@^A`$S&4U0&Iwem6og@oG29ub(u06qNc@@6@Vg^HHY#0FAV(15*rE^Ffb z546^nd6p;cRK4+ojOM@M3K&*?wa=)kfEDE2*r-Scvnv@%-g103K{c#j@SS^wbNphr zGj-~!11sJP4R-f?}TgX@4)_5o>43!2g^OzY}8JRtw6vH>-81c3% zbbO~3JyJBwL%c0&nA=E-GKQdcK@8EHj zO*OQYR{A#0`2PangawX&m!hfO#>83vGO9L-aebAoF3Ack(gZ%0zb9;vt*}S$D^Oi< z%IJKQiQ3hVYa*xFsmSM$st6bnQ+di-s3kW2{&;NR?U2Y~_-hZ}!V%_xj(u6SofWD4 zNo6tY$FDn4yG~tJqf$%<(mY?x_TKqTgsK$14+S_glCRv^p^e#2)q(go#!e*Xz7qr^ zmQ~fYqmCRELjI@LsRoCBHC4bWoAhouu#zEc;htC2>MDHLF^I9sGm2V8c5J`QMjX`% z;6%jl%xCYC3qQUi1T3`(rVBXg@Y;FUJgeEXGuBhNsff#+49!eg^fCQ-SdmiBF2Jw; z^!miz0h*vXB4a|`H+S1mqI%zp2HM0->U+{}K2iG>a|26Vnx1>I%&CafOs0A2$(znE zj8MUGj^BxJBp4w#LEVcf6SGI%U~{;qp1G3QY>LH_XUSS#`dyArY3S#oXpU8HiL4 zFD>U8>?QPDTjsRp2C%$W)n^|Ce$Zalu~~g0Y9{(R6_Mn?aWUjJD%s^rnx4;xz;ScZ z&6Bb~Rn-GqZdscfiKT&$>wW{j{8M7GD`Ca7vD7+_f~v*4O)MK%{gmpfk*6d!ns>Ga;VK{U=x)*)Sbe^8QOb6nlHuSp zb?@42>~5+!%BxU4!H56;1M7@87G*pDAT!pq@~4ZK&pK_|(=k<2zOukJNvZmLc^&nD zs`;F_S7mNG?VGPJH}NNue#W7?iRAps^qR`-kQ5J^J@{J9Y>7T_n|?Qq-yDOD$?2#7 zoj)-q@X`0rUKY$)%m;pDhjdS9`I@Hk7Hy0?8Jyzp3`Gu#_~H`VU%wnL6Ui7tBowHy zwV#LQ2k8tLd6a7|b6+^~MBT<|v^6l^VTzg`G9WtOn?0BGNCemSS_hABtUX;xo7Tj1 z<~sRhUfMO6dxzE%LJCh)2j_KdX6`g|EGBf7O>)FM`}%W=Y9P}Jx{jvqT+v*7ZZ22sUM}NDsZ|ktck{jJbY6;G`9l{YW-b#!*{RWHjq|StRRMLpZbg1F zmbh{4iWfe4Lh85yxhg~DC;lO^EVJ0ttl$wRBRq6GGFGnjX~RWDGG;>6O@En8O7}vn zI7*red|z|i+>3KmSS+eCKnt>`lcj>jE)fD_($u9 zGU3#VUQtJOJwcl-5m$RvlQ@B8)CX7J(D#oE@s{f)feUm)MJKJzQyJP4U5SN$Wu49}eLjzw{0j)ikr5^x!Z%Gmt2|{lc*#+j829>6XvSuu z7fS^q!8ufjynQ)}cWe+qoK2D89TIUBqll4lD%milBzmN&s)(z7Q-B*E5Wj?O<8|R8mG>~Sgg3& zuE+}SzJ3uLgCVq$horn~B$U{+05a$E!ICIy!dN-c)4JE@m9+leBp4o9_j_p78 zE=pqpiNx5P5Lv)6<4?}08A+FU(5Ew96+s85_@5DhIe|nT0qf(sQy%v9AL?tyzRt^4 zQCI3DN)n~t$tkI^8n0{&Vjp;Sog^d%hFm4jBL>OTv3pv%7J7!uMdYEISkpRQ|49k! z*rR55@o^{WX`oY1Q9SIn;!Vh8MH-JuO@_J4uCW!;81$2$`I1dsyuebd2{=|i-f%jW zrCjrFoyc9I|6cUHs&Pdid(T_+VajeKTJbpS$!Jz+8t&Gf1aF~i%@qr&Zwcq035iMgxww`4qnvn-=he@WRAUqR!Y5L%Ui7Ol%YMRs!SDbk&zhUx(;b3?s*WMJ+G2 zcV8I=jJ7v0+i0APg0#g9_lfbt0)A zOeb49a>*1brrE3rxsMAGF9#!By|C=JMpib@t?O8WFNU%=jHgvm;r0m1u-#scwK&p9 z!z0INV1wb}-pM3kzz@gPun}eQweuRK-F;;H+LqMt+WFZ+l^de}5{A-@_W= z)X8Fy)o~aZv^K92WzPmp70x1rItly6a%LBxK|3Z zUsnyQVQno}sJG!#w##g*W&QY>`h@c$j_)=!@`X{%>#AFux;9AgREf}{SH)UcrP`Dt z`vT>?HRKtc{D67I!~mHFLb%5fPXZp#ELo;d7}*dw(w)?fDVlz%$5lB!X1KS^5@Um` zRapC&kKWNCh8=x~7j0HHtv2*O*(nX;X=Ps|R$};KR8na@&@~&+gU5pzq}#_CcL=I1 zu1v)+>H>tB)u_)Ocj9eiUc2O~)T@jFB>Ps-mFE+S?v=`oYq5d#gn}DNPBNRC^H@oA zWhQ2PfgCNaEy@#P46P9n-+;dmi%x82ymgGSk2oVX2G_!)(UKce#&uO>Wd2)*u>Y2c zOy=*>?B0J7Ae{c6Ze40=hnXYmi=eh^VligRyg@Xh$BX`G*53gSnUbCC`Z;B`B@M=r z9s*uVy&Xxw5&Ae`;-)4f&rYh6DjXQ)4{)5%HO_g&Q?F7}*H-#0_n4Z);$uh!w{0&F zmRl@1H+i0Q*$}1B&X25?{;n=ytm#07X|G?G@EXy>3V7rsaB4Ku{(-iIlH!T)jVhGu z09mkZmq*KVP##{&)w1u;ymIoTLY?2py5&#V+)qbSH46$6BDV6$22jf3yG>THu4!>{dF51%_yyxKBZ_pM2VrK!F!(?zc7Y zKnL*&OmLxR(%R9-X>HOO2FVF>cgr?5HO>+OMoH?Is&$i*#T$LS17R)L$DYoF?^PDi zPiL9_z}MvV{tF&)GWcKdh>);*&ouWWl$c)pS=H6V+xSe9MO6{W04miTck@&yHYMwo zM@X3snGp&b)o`=yy(4-ermPM(U4wM)fad!bJvQr)W=Lx&Iq%99?X1{~>O(~8{i98k zs!^;vM^;YW>7EIL@2z(zb*Ke?00?hub>#ujsYP@vCVRtp1Eq2u=7Qkloum8PYAGR@+Mj0U@ z7Q_#9ws3!O4AA){a^lYGJ^4f)@+bT4@oF~WQRmCX+uUwA@c5^2>6aAK;H32Y*KNx{ z_R&YzgD+`m8k3OThElg@QWt0=SGV^-!|-+aq`hW!YlHnqAkvyBG`AzQPiB^`=wPtOlE%KtFvJgS2buu?}CdUvm7T|3IJUAat^T0u71b5K3 z=Q02Yh?eS+vhS4UHxsMT5n_Ne{o zb=17>9xivIsA0(Uc=@LUbks6Wsc_?e(necAdqGL!#v~8?WiCdR&JW2AwbFG-e8!LNl5~u(t5Fbb;+34cP;NGzuoSQQ`@!Ie?+XMa zty`+6A{Xxjy*#0OCgtnqeivL^-n*46L=lzK3f(n35i7_U+@QhJc1Xd`gq}<1P*M-R zYcs;NcBenj+z})AIEErTW!>GNdo{cxpa;Q5G&V+ExidBY@y9Ep9JlU#J|UulnaoL= z>15!^Ud(zp zThFrbc~9~*=ZhAbUw`I5#^0hj3V@Z`d9SvqUHdj1=D@K=5U&fp1*bT(gbuvTN44zs zF9&+b*cwvnA}u`^(G!zbU^CT(4X!Onh2v8Bic5p1lhD84jfT`)=Cj**9G|xxgYS)> zuNYjg?|{g!4{BRZwCGx!$9G~uia~enA{=jWrWJj^pPU;)3khEo1B`uV`$P_}j>AcR zKVPYAU7lU4nQUy*&(zfR)T}&bKP#=ErxuDoW`e=qy%#DYb%wl`4>x@YhJHW$;aB^# zZ^*eC7}j@gjV7M#oxmN!mkSp`hOJJUXZt~0bsxRVy7X86{QIhr_phsl(Ep38#!dJy z)f>YFbES&#HoXXUh{7RK&y=>P`1skkabX3nlC&pvu1+CILIs*+20A?vL@!*9L)hB~ z-ImEf0*I*w7B`!fzBh|zURPbFFGrzat7yX15|F6%w6X2H%~XFCxanb@(q%_7$VipG zdG5S~W|dG^Ir2i!trOYiuw>!1rl%XmLtFcsvikK(GoX2z56v>j$3h|BG9sS#FxdEs z+YWf;gm4%SlEaV>#$)hdzMXRXC4A&N!h5 zf5gWn7Yd?P-sOxO#!FIR1lE^`U=MfYY87( z&S^&7{HP(UZX>+Tc7(;UzmXD192)Kd%}*9Qj(;}G<;bmN`zTuDUfiM}Y)#zlXW>&c z;XuUpb3>*uF!g;?Cz)Uc5W30_1%!U{H#~r@@`1p8lHvGfoI3`k4%)6l;q6Rga>IW*;!(B z<#&EKt4M^U!c$6ytF*M3nerMoRx3#nFD-S*o zwo@k>_2wG}I})kljo|~$OCftavF(fG%coyvC$k>g%U7Rzd4lLZl3%+He6mXkZ0USs zD}1u^_9d5_FP^*aneYlq&_XU>DBob8oi{m_(IMrlGcV9R1jap$8jix7Num#xQN<+W zwF*#>Q61DiQs0~uF+u(V&&~W7Ky&i)WshuP(uvJpnBA<0{2YzE@rjJzCC5cY=tK%r zeq&zqNl0MaDGjcBh}mQ|N4c$K%S2IPEOWqrYf0@xUSys-~c*UIt_FR|KB_^c>n1WH(vPi zJ1CEXjd6k=`x0UGBh;#_XgOIjUnM@CxuQ?F_84-LHA^hvZMjCaou8aSg2 z_?3JRD0ozA6YymJPx%=RJT7E8*_Y$DgtTtyUdB-K%nw}_L!wo0OfSbk3K<4t1M^Of zE*HSKFM|0M{kB5s^afuoAVrJYxhTbd4Njs2@E&tNGnxNDWa}~#HaN)_Tx?Fx%*-yr z%qZffB(J76Gd`v=t2)^wJnqod zPOZqSvCD-n?ege*Q~#8uHMCz{Gvlet9@^DXs~b+RE%w#dUo|~aiNa3aPBzVV)~t9s!XL7#LPep zmo89RT`ldQGc-O($-8ihfVFc67Bcd5cS=HB3>I#2-$tkkvRYGFbgAO|Ew#0S(1Mua z&q-#?gW;(uFIQn9;L-D;oH?q>L&28;EC>MLt$yp*ZU}YU_|3^hds05)?WsUff2aRBZT)AaCR8~Sm6|aS4BdhVB`QGK{?##BEPo~yBRiFtym7m*+ zs-is>a0jvyUBlEQJ_0egF{}x`jz%&g?C}pa% z<>TPFj-ygzXE}>LJZqfEkTi2ixUdbKdJQ43meZMWr3h8tmwHf@7OimyU6t)aU4f^i zdsd>dXZc2Wt~I^Bbn0f3MKWv5hM?`>W-TRUx~ve-+z&LA?NScXrue2s^>V=w@mNUn z2dX2Ln&rDHnmN3pG|)Ap5dCRRxHM8}q_(^G7^{f2;-cQG)Y1|f*-_sw zKp}~*AHpd6v+CH^sl4JlFfYr6K_Q^~@J^5q((kicsD{=wBl`;6F4cL5K8slUZPns= z#oix!G^fGr(n++h>G`C4bV5w1gkE*!&xPHeDc83pOzlLNR*G^?(dw&FPI-|pjmP)B zxXv3Sm;O5tYbP+Rw6O~Dy(4DvZ(7Os%~Z%3$Ik;^pGxR3sVY7(7rnWkT+zxLPQ8^D zDDRT!kbFP1qE6+iC+TI$BNI8CNOB+G_4ia6Zi|r^8hl6tE`~L5N2W7s!Mb*0xD!b*5D-ZQ)1NOGq2RH<#-^}7@F z3S3m@M;e+0kuaRf0GTBgzQl~twCa|moKGH|nHsjs8!vqMaV2Hslbfj?K*$9rE>7qS zg7uPxn^(L?jG!vDv|jx^l;^iV7SEMfOY=aVra8*WMOq9pT#HSp^EH;v)!p{>W#pd7 zC_@ye^*6+mLGAXS)4I>YkxLgx>LlYJiXRN9UBS7u9mooG?E$``??H5Whx8qOzN->* z5$c)c8K4I0kNKNl@*L)&%UgfQ8CC&Vd4NK3n|{V6J7IFYhyqO_SQaBh8V6{BRh7T| z>95=KB_h>XhS%8Us^{8!1S4TXgoA5*_89Y4UKX5X77;F52H-||&YRN#(#lSK5JvIh zWhy#C4gdpUA_z>n2J2=tjkdhs0c3Vq_~}))%F|^|$GYNyai!>P#Y?vAkcN+5Y!+sF z=^KM{k#)!~>*AE2+rW}WzB~q=u!>N-hn$p{= zzCO58CpXHncK*0bP)=Cz;FW!AqF(ND`2l1-9I8~IIEgz5XEmR{cbEyhO0@>n>O;~W}ou)7i_3#$qa^AlSc(R79}G#Q>v!Bhx>Nd+^xp! z0&_e2YOl+DyU+B#j$(-;ofXCb)Y$(?-qS>RUriIm8#8r z$$KR|MaEJD{cotSvuNh-Cr^I3HFv?BP4z~zF=m`0o1-Hv-rbX(75XA-H2vh z{P)<%EVZ&9=NBUCM_65y6W;9%q<1IG+m}@5c_M{I#CnlwjocWLFw=DBaoEJlJKR)P zNUxP7-0fa{N;$0@`W89^-6A3vqp`!3hT!c+t_Vdb#$H=i26q|_37iCFL$?p&$dQvO z;ei!=hufr%)8=Qsn5#L7N~%xGwA0iHwOQRdGntSL;sT{O?njQPb~57D)scOaqpvMS z?ZZ=1BW#qG1sVCr-puG9W75%*|BSYQ$$y?P@;R^Q^)}Cna>gjqnlGT72Pw5Kif^*E za&-#M8PpNMIs;(LvwzoSVS?d9BEvQ*ZumZ`5o4%f&*mIe3(Ex@CoIL)taB;za++7g zHkhzW?|-+-+q3)Vm_`T5LNM$-VvFf{^J4{u*QBBQxqBl!Mb>(G`WdN0+;SO^eSYV6 z?>C#F)nxV~4pD_8=YlN!hFpE9b|&n%ETY6M{XL1+FEFz-csg@v(VPtTzXkeh+VU0p zZI~ieR`|Lfw?+$K1!no;yI~Oni2S;GmZg~GBpLdMqym0a4*SNYSQX9&IihxOd|6}BrPyP>2OI6-W!m%#K#6!E2d08y7+raw= z^Y5ljD`VT^yGK{`fx)WyxH7xaZ}Pougmwb`|u^!-#U**smZlZrxDxX+)>#=W{BqS>Xsnh5mvYJxdBgd)MK1UA59HL z1dTS#I`{U7e0}!}Nv)jL$-^pe2sTMJu6UjcXfmZ#pM`>YzUs_3M;V~-CY#Z1i5v_L zy-X<~Tu?DY6s5T(`h}9=GL6hEanY)QvqTu_hVM3Vx9fRIonWd19h`~MD9`!DO~aetTp z2X%9q#3Z~vPJ;?r!i>H`w@kM7xq@r1ch|||&y4xCU!4}&aKGRpEbDZT-BN-do8B%o z5Yh9&>S5Qo;>79dCph#nODXvKkfCH0CSsP=3wbJGjLtkVT&hbdVH{)0+M;vV4uc3E zbT3&v`i%LZ+wLrOax@x53`TC!WKVQ;oX!d&0_jg7Fz={)<&>g@UwdihFJF@G{5#YC z#QA(alS>qRs>TzsTU74|5_RRr`Z5QceY3wA-FjdNn61pbs$>&*aA#J*Cg}pszyi`- zZtw)i7Sf>#)T%3r`O(^!7~soOuc3SM9t_Bvwi4yD!y&Pu(B!E9J4-zH)YbOysU9C|1}4Yj)NMChM7kbVg+*HG?;{1J9*c<0Q2i zO{-(D*~^(CbwVK&(LBN+3fN;SLPsz{gtoST5SPms>{8&nU2}Ov5Wia^)q($?H1Fx5 zV{OHK{S#8V-E%=tJEY%L!VxZlb=(|%H0-ZNNaM{B<15M$(_OBu?JPc=+-l&AI0Jn1 zM`d*b=`<$u?5cAYWT$Iux)l{Xe4Q8#3)eCmui8Q+Vl^mm?L|L#946D_kzYG8Au`3$ z$#`$iYi{sb!D&b@UH19mGVg0=kF4R!mjowq&stugqoGhIGl(~J!LRa@#pT29_8yL) zs|;w(k#Uh|Ns=#D)K%s@tZ2Ky(bN-LHyRt)H+hs}_KTHs>lxJoy6{o+__`ysb`ef$dv z$9MgCUvWaRXEJ2NW6mk9GEzs1DF_DZlZSp?3}H5ha8!Ft0@ z2BGcZ-A(6r9lsXH1zTNK@TB|+k;@OgX=awWJC^T|K!e>%#c~yHA84{MDg- zsd4}{8214zc@iPEKSumGmvH@Pm-BBq^Nz$G z^GiZ}x0C}G>sm~5aph9cVO^zm4^NzmcT6(MDFff;g!$Il5Lf zV2iwIYZeBZFHrLX(VcQ(+SUz8=F!+=c6IzzI-g{EUrEIiO9yV5PTMz| zM!bKcD4n&K82Ywe^2g_aGusVLnu(w~@`VU3{TswDGPO<)cFHL33N|UyAW})Bayqu} zLI~g%bcSyRGy=isG1_x&2V7b_oUQ=A6)=mtxi823p7`;wwcCNQuKrM>AKX1){-e!B zKghe9c15?=um7j!TC?k9l2)fDqrPw3SY5UO*bKo?_aLLg8_uXIQ`xq-+`=@&{v`Vm zO*m)47xB;lmafF+h%%v-Pov{wZ(HnXEnQSyv_PKZbE9&DJYrUoJF3-4Sp~&%WFHDjiSMP-d1Cuv^t*J(JqoVFx*|I zB^k?~+FC;CsnLyYSC6DrVFc$jbj<>}emA`fNsF z8yjDC;O!C=M2K2&p2|?_99cZVcjlD;MmeYjPO088UEvon)f#d))X>8owDe^Id{I5@ z870Htkt5zf`>eTALGbp`f+aL>&50S#dUeC%-O)vNoi34IN1b4Xi~fG;b`FEWdxmHE zW7iU*YBuuO!T zz^u_be2bZ1(%sXU4&0BW=i*r1cXJ5bf?AMAm7ptsOALkKpJ4P*oqg3nhkPQ!S?GNd zXx!@7**h!W_))%-CF9G8d^{N$qM4yjRvxoADlX1nfU-vN`N4Kb@IHq-i)^!Og33A= zyW-M2lnrP>83Ko>w(w|mXg4#WWA2ykH9V*_ERD|Usua${uhRw5a$Oc|02;@|$`OCv zYM;jEw|_U7!xxwYv-tjsS=ON@rXRmo-I0=%XWieI*if&9x8XBNS$(aFc>}yv(uC8YVt}h zpS2kHm|U^lg+ki_jRM1X#9C%X>zHo&Sg04~QmuuF{O+ivBtUt5s%u!=n@?wld-x%8 zmHz&%#dyTef+0AV0L+Vv^{)P{vB_-;PUOFUGKmW%rrYq?V0|%&TfLc;!1P z<<2?jXOU8u&KZ-1NVE;dfESSY<3n12+yQS3wO*sLFtp_4Wxt+fl?$RZr;QY9mwDw* zipme+BfCZDHU=a^&PfjWp|&`zPAzl&w3Dlit|biK8B(}b&Tn5I9KE||dDG=mI0Xr4 zu;K)a4eF>yv-n$Y_lID&K5P+PE|1~|!3&Jex}qxVp`_Vbx6xA<0l`M^4Sq0lbk>d3 zS<~#$712=^bV`rL`RK70&@_XpH7liH(4Z}hI^|fA8n=06BEDjASzZY1AB>W-{{r;d;{tAvSFXCty zoAxjq8~D|msM3+MxjbA(SrO-Rp6}wU_@N^5v%nwLcrPot`Ez+W8OJPT)_MIh^*0KF z$dzYEa~iYt`J6$Yxc9_5XiSJ9d0;e(TQBN7MK-6VSitT?5`xOn(v-`ybs_3#hAi`hl zz&G()*UOaYco2-{G>Nn~-nA}c_uNI+JWTJZ|GKvhHD<*|MS-j~+}&!w=HAcbvyn1Q z-a8}*aA%8b*0?~}&Py@NztuP}o!tcF2K@njA#sVNdg3g*3N-N*nGVWbzDDg5`SBqN zGmH7Aa;o)MSz^dI1Sk%7P21DPUy(4Yp;PRszhO=7a*{)=XS^N&2J&IfYz-M+w(ep& zm$~&ghQ(E&DLkx?w}U(>81Ln4s}ZHEvwMD*ZG5Y(6y~^1e@Kx4nXe}BVs8;WOaGX# za^Pd%jN<9x&#`yo>#cW2uVa%QE{*R>LUa2`S@H+FZuuG#EvmTm!o9~l9Bt$uxlGaM znaS2%AOYdZN;ve~5=b5MCU^Qaq|hAUmSVX_f%4+$usC_kC($jZ!iklCtp1h0ejBX3 z&WGB3-o7y!FDIhxF|%qBOG-K4d+rr->Nh`vz|%EDQ7F!nHc0aQy1Lf1XhHKj(8x2; z4IlMp<6#w`^2;4;(KL&XnlL#;4uf=?m-a<51>))aG5q->{ z6vT_z#*%-)qPal>_xmg;Xs;QexU-u&7lby1A4Zj$`)IG_l&xYb>8L-$x=_q;N;y=b3^%Yl*w!}~w zd3A+Nss+!aVOv?cUV4fnJYcMl={*G~^3i83$J|`*Nmq4gP4Ov)Lnf5f5|o7zTlHZ` zD-CyN{#+>_8w+j*UgF=&1dO+`F*Hr-7IIFt`xkW3K4%zsqE@UFT@q_jg13^l4(lkji5 zL0J$IRFN>4q~X6ipaE^tr$~>9kc<7hbx0bb=v>}K|d_$!%5d69*!{SM@ z-*^SRN>`7btX9n5qKiX)zkAE;r=%w2s-sjK=JNrBw`BfA=xR?l!|BF+ZLjb6=R7wf~O^RI&nKJ;x5N~^}GzjaeB zl;}E?pPTt$#I}p?&h) zq=i@W`znX3{cI0UD=YbaQHpn^IAu&lO;R>6q9D|j#cUrOEBcNR1x~bh5pbV$558Q!V!-vBKsb}86hcH^f|*BYUMI%FJbKi zeE%GI(Z7E3dAfu?gyYL@pzC9|*`0mN4hsD*Q^;F=*6(#HKiKzw@Z0|aoXY+J_&|mK zosYnWBa#0FpgW45S@$2!;X6lJ*3xLllQ>ndP#l@bC`^5CajVhKiD7`P_j~`|{s1k{ zfWA>tNPj9_Kbl*M#a&sEo+AcV^SoJ!am!)i*NcYVv1X>qgD;UIB-I=3 z`MrD=x<0bB%=fue7fm-%_TWUb4ZnVf2HuH_h2!aG;)W=@HsM@bx4S$YWXu`16tGMn zZ6Ik4TuJWwhaq1=|BJ^Pmj!2S!N;HS@R;O;xC;;A$>;Q2QKJe3HwACDg8fun_4MxC zmc`!Rs(eRUU9%dF=?oQDsBd!Y!=;U>s)n^cXlrq*0yQ5(@tBJ?s?WtbPv47!&zljk zK;BWW48l<2Z6F|XWfO5z`pfnLr-Kq$KHAsyWxIYkcx}TPQO5hL zX6+Jq$v?pI-o%_rCMi4t?hx0AE!LA@Aht5BiZ1vfot`OLSy9R}6J>;+F#^#I2IHcH zCGJ=BY4GTh_XX&R8G-LQE@7lweTaa~hIlCtPi@0Q|L!~Yj3`J^RMUW#b<}Y>c{)QV zrn>4yij)fJ92!GrM$6dNRjrv_#t~p&v1ks1zD4)r23;=^R7F!+B2`_CDPPS7$8^kO z4a=fEK3A@z(te5)^YR1MwJ8A1cvfR4IB9oK{ zJIl!N$vJF3WEo(>Ctp@PO)LaYS~F`}?hr9(gJJFmkb zHTBjXN%N<_0Lk*lGQDvYSOgVFij<}q|6Ezb#aq+$5Na~B6 zMLVzUII@da;f5v2u6)5SI|2W!!t>Jor&aiw|6>(i=Ko?9{`23J|49*Es{8B*ANEQg zr{dW7`AT%R%OQSH5|{M{7frBp7w!w&ne*nvPZqt$ja_vr56;t&uU(2VS~vw%o8L7R zdQjX!Jd^Dvo*#DBC@DI~}ra0$6?$P6eyf_Prc2nX!0GLHv|**wCb8Worc zf4YIW_cl$2dTsg*f5@rp!G2ilc^eXaO-rV{8~MZ!Ml4sju90_)4!IP{wc>Rle=1yzjqa$p_&?jdFl%Ki+iL!NJ)Ow-XA12J%sQrP>h(+1@?);5@ZfD8J zDe*_jBm94edykrC)Y=ZtUngL^F@rD}Lg%@vFs(}R;{(bW6(4!WK_WzDr#DD|2R(a> z>_XB6iyO;M<(tLbmPWx;*`1?KOm|BWjVUsOVGC!!;9@&IS%J1`xA{kCtlzp{*hgu1 zxH#RV*~^N*fLdBJ#wE2IwBIX+Lw^LbT<`h`^?1zCWL~U3$K#}aLfsY$viX7= z{r%IQKkZ)RGHHJ{Lab0PqdyR* zk3~HQrS6YBi=OCTfX8UWXGW~!PL7y`-T%edUkA1M#c#W4a9X6eYp~+(Qrz9$9fG^N zyL*efyHhNrIbb!6{ip#R>nAXrXq0dU4~nmWP|5ByC=_+My_M z6q;1&yd8WB{}VcmLfSJg;_mp48_I?;d8mKe*aSvO^=cBwsvfJ*o*dd&xbDe4HD5WYQ*uC?Ci zIBTd>yc%-NHugR?9FsDg$G?jn62m#(ZV;IJVp2`bC{(1Pg?Z)e3!0L*3CA|~TKiAf z;g?@SwG@6NPP3Z9SQ~U7A6G_doApEc@RYVc^L&8 z_~|FV#Ot$tj_{p=?{1^pK;+r?ac_wy&d={O@rnoJ@j3y22PdJ*hqDsMG}f))e}MdK z0F=pnZS!K)<#3*CZZcX*@J6HYg5#iamVCSV?ZV=ZOoe-M=X(uVrc{qc|7um6;r= zs+?7v)LV4!#q(IaQ3R(Y`u*X35B(Anj9c6P0RMMbVDxS0@!MZj?h{A%!}hFy3CqDG z44akjiM$tX!8E`YZ#dL!;pB&1*@%cy-!ES~r+Qkz+PEWv7L+(;(gfi=B!Nr~Dw7U! zLXNfm%=l=?^Il_W7A#drs*kwJW!DWu=MM?yaTSf2r9T1@jjO5>)3Yz@(mUZ0nAsd; zIWZL8O8^dj4F+MyQ@Qj+XQN197TfMx0<12VtX+w7id=H>yp9SIB*G(XhxEqng!! zfHBRzif`9ZO!>5T*Rg~J&9~f%!>zwwYp$DF{qt^C;1rV3`nwYwwm~a?+PmNK+6@U> zA5~br<}%cJJKif&Dw{GyYY6(76~g!13DsMPzhlRd1Qj(9l>A_qwXBL0J)*wJ@xKYf z0=Scoh7auy-F&L8IU3ECoj|FEEO}nqwzvItE)tq&(N_W!cM^!u?nzrf4^xknu>S*y zI9~O65x#CVe_3iCJpR0zvwqm~ZMo#1(e&4X!7Rfgg%O3;ybCvTe!#@ct(U>t(~0B;Dqn+Rt45`V)-UdnX57otyrOT25( z34?_%&vSzMuhrJ9rQ9Y{-PZih@5x^-T%oz$vEu+;k!aew!5C!cvzMj1^yZ_()$IQO zOJ(n5Ru+Zdx;S2u8gS`cKK~u(N4iSw|5mV#-tooiZj2}SoSJ-Ela-eu*lq7Epr}p$ z_j!=MiOb#{nql3YKx=it!Bf9ytO{U$HnocNh~D!fXaDN_yVcp~GSVA8{)RfUT*_e2 zGkMv60QuFd$begeK+}(LE=ivldrsFq+ZlV9!5BD#?QMWBfblZf!h2K)>Ca_ji={pt zH`HBP@n>Q%-Tpxs3hD61jeah--FqXe>)E*?)y!N2s%KQHUXsL?rAZ3J)zw77QpeHL zBC2U+LM=TR{~yN|oF9xQtSCMY042>AW=ZZGuB`UJHb3lCYHndMmrB(gt1D?Z4Zc8Z z^E%IcZ=I1dB&Wg9y`U`I_6Oiou!t#XCs}`YqkUkSuQO2V8{G5*FYb)u0nPV{BDizQ z6j;N5T}R!Z-jd~?{<8M7!W8K!L!#`(*_c8yRO(mQ3`@XQxYMj zyhT+VQ6lZ(QcxH3=>$h(s8nYNGFv)++taPPt13VjI7uBPFNlds5+;JZ>HPhwJtlD!xr-v=UQPk^9mnZSw0_-M!HO?m}DR5Lm$nj$g*+EFRL? zy)Q)=5S-Ac&K~Hv$t$jmZIrmMAL!TWmQpTTktF68hH9AX@kx0Gwwfd98KS(~PzH&3Ofj`7 zWkdyOSWH}g!H_!o!Hs{L6md#lUoVmk`1a*x5r<1( zl*EC42!MC{sN^d>H7EgT&lwlfp*xi~V~`a>1dK5cD~I&=dO@8U8&arZ$KPy?fcWQV)IlyQkBFteirDbaL zfi9kZM96z3Rlm$GefjF;M0RH~xh`qIi-Gy@CE;tF3w%G`-+?Y6qyAtFHJp@~oFFJ% z^JK4#<)e2IXX*zn%MfXx2`;7rj${4M3Hl6- z-1+<|q`&m&@*3(d*)!ei1WT%-SLOI3i!9vS{LPRO6O!fb{PZJ{OXZ~4jNIke_xB{U zRI-pJm^Fop!JaZO{!F+)}wFG)N_KKC5D4zyKSn zl=u&)VSl&YkDFWN{1T~awA=QB&}KZn^PB52xn_>I$KphS|9JBoE8hC76UI(!r3oeW z!wyXtSQ`|lq##kNaZU8TNDcEHVSlHLd>@$>8l#C_8<(|=b``kpWaWG39=GeFsaI58 zGM1ihVnGahdFtNZkts=&QIo#II(E|(knEo5EBULV(AD$1=b=Gjk;k>2b(_e{!0*0& z?@DqGilm95*qM4r)`=gTKgw`PLr-V#!Ofs>zZux4fHx9@(x)P@)U4XlbFrjw=4xuH z>$+hp(&RFfOQP8h>f^+5;3We@aing$6|gLrC~c1V!n3>FE-lFQ_>D@Ou8EWUb&zC7tY15blDGpSyQN*JP+ z|Dl12s$D(Xme;=|9Hc=us-$~*RqYxT^tZKf%LYBd@#AQGH+U|S35mOLaI>90m#hE; z+$-ml&6#QLwc=qS%RGtMNBq?tn+%oaX>2Bsf2?KrPe^O9<7?z&i47-~KGb$cf;{fL z>__PY;;qc^gOn5LWFRHfn$HLS;zh~~=ifQXg5fl!)Lxvv*VV;F(mfNK-yf_fEk`m( zG<0(6^jUYB{aLgzOMdZ5F|+3fGvCQ=T#1HQOt1{|Pl1-8C(e%gTS-lh0izR*5A9&ix)oeI*NQR)yO$enaaMfUZ=E!|28~#$PUC8LD)^>B1+lS! zVRcsFrr8RiO22J_J)(1GRo>bE0DkgVcq?t79n(Qic79q9d=E>aiVAYE9(o?jRULGE zBgy;@Xc18Jm=e_#SWCNw(``Jz`_hVz<5!;2#eR%7=wYaK&E45lXkj3Ty%ptYCM}0u z{>s;x>{)KXymUx?jKaVFfG|1o11AlF%|BHgCk8xYd#(=kgbUyu-!KsK{YA0c06ebD zj7?liQ>!1z~_v%mPISh68ii0 z)fm~H(+{#b?Ti=W%EucpCsttTUD9(g#ZO1jRrQR5BKj& zvvGV3eSRcK-=)=VB^U=I$(Z1JxQ3pN)jQa!^ETQgeO{~q+fv4`-88W!LHZ?}IJYYG zuNoN0UDH_Da(dyETN_to=Ykx&-Mm1B$X>hchqs@Uv`+k^l`t66_T-{0#d^1Z?!>Wg3-l*(21wmZqoqwxh7IZgv1PLt*_&0Y7UKjdkb~WJW z*$W05INe72l`)TxiZ##$;@Q!v5D>OZ|0oGDRmni7L92?_k*L7q;Vw@%I*%5lOm5sB z-v?)bHb6Eci=Ai>_G#=2aU0fYJ{gb5lTwvzE91Bea=0)ig#~{rPk^=E%q3b`)-Q)uTc~FFid?wbS)9}nw;Gg+bo}zv znt=hV<$tYwcL=V4=iaJ#O7E7_jWAwYyy#8jZMmV@PI(HXrK7RYSx(isjt4XgM!2|6 zCp~3axahf4X23(r1`rUE?vgdzS@QSU1=7hiW7G@UUg#OfPR;w?MY~%}jP?nWY!5Zp zyG1<>T|)|Iia6&CeF!2Nzx?Zzb;Qr1S9N?V^5D73(a39BwA=*@4N_~>g}J@FM>95Y zWeBad$Di&WV>?i6YB$Kor`Ie_ndgmCc8iW01vA;x$^H3Gx9972zl5mf?0KxWhui>9 z;TgzCjvRlVm>kRC>ZmoUoN2#OcZBs^p?XMn%Jbn5gYVk$APwwoDxa>p@)zxHzWvfh zeM(vRh*Iclz&5j((HR;u&z=xo*hIw=pE$}USG zei9>C7Y(B#m>Z=m8Z3Ki%^QQ#MQ#;KH45pCJHYA-`DO zwMMc3L0%Y{AGTAmP~%*r%F%sbrbAoZC1?CdRg;-NWj&Nnx(NEM&M1dUoFq~dY3o64 zfmv3d3N!0uq8OQ2_DWaHA^3&f67bQ{U{UOEi|#~LH2*+DM#6?++FkX&+j*Y7Zjo%p zXJQ{Qe8dqUy(dc2YDHcb!<0G;;i*5rRiwrpvMbz%RTMt; zw&h!PCHAP%RKI4xZ}@sk^cdSwp2P2xKY{FxmscbF$=ga^u+)CPpCT77L^DchWj1Sl zX&hV{^C8tgcB{=nYqD}F9h2g)d7ncr6` zPEq{8w!fxohK|dwulNRePP@-VlhSm};)-+>&w5OW&V;uJ*0>Y9;d!+bGPFCJ6tP>w7g)$pV~uj78}|SW@{f6oh`VR-~t@A18&2D_eTuiXgS!M@uTf* zy*m02Mv{vVI^7*n#7LY+BUS&(_@o$gEnU$Hgmk%sdR?1Gy*H_w2FpL<>B67c?QMDy zR`56`Bj?%IHRoO*m+;Xoa|JuamKt|D1T`=@Q`K1DT6f0_RwI=4^66dNOmt*~JQr7| zX{502DzIfI=p#T$I$B)Fu{mwhf(_JwKtl^2wY5PlPN+ko5hgMODVtZp>DCd|+ry*l zigXfB)8J>({e-?jQ|p><7u(HZfZf_*yQ=-;N%IMFbhqxbX>>WwySr|Vm%KI0>Es$h zQsg6a78{|%HdF;L1CAktGS6-zwK&>1=z`#LgZzA&{XU(#Bzfb>Fw&u}+QAu>U$ck7 zMP(ylR$;L2TNOA7q1)u<8DWq3B$>AH`NRa?viRsjoLK*Ss`nQ;?YC-Pt&eO+aob(c z4^3Nos>87=w+VA}R}|sWVVx42n5hl&ZeUqW2A}^nh)=YL;Pgb5MD0{`qjl1DHdkJY z5Ana(?ks!R^z509pw36<0i;hL6bybd)0a(bxg11kdhCSt`86nYh7wVpE>JH*0ux+kdr;zP>CqhUW<_6MgeY zd=%-X|6GwJ5?7n2VW_#U@u*ABH2YfpwRE@m7hHsLzd>)8E&RYoFzu+E`GpW50#Ug8 zh{@o!W%DOV5}pv#Nn!A8Q)nQ;g{38ScF+z$a)*xHXX1tS##Y)A2?_WgAaBQg9MVZN z2o(zP&3Eyq@GRSQVwc8m8hX31o;9JP+|(CBF~ zEj!71xPAgU0(pdgR>&ZBs(GdCC@--PyEk$ovO!ERK!(iBmY}9V6|XZ$Qj*tG?14XO zew`E5>%YfkCh4m3rhn!!;eqy*-m4o&NxqN48fF{m@OpVTCW+ zrR!IvV!ZFlJ=NDCFcA`|jQ*G}xd;Inua>V$(q!wTkff>rWq(#kw)A;YG$u%C?TUCK zb@a@|W`@13)Mrxi=*R=&`Db70X6m5Ncf)viKETB@{!0q%`r;+QG=-i{18-lwP-`lg z$;5V@G+%nx$MUrFR}JM^0ejq|#2|(0@ZERI~db0=|uDT!6kceHs)opp+6mvNpTyxAj~2E|pmj zcPW|nP?yKB3JB3s()cunWoBS{4Vv2=w8iaiWK@Zs6pNLmai_~%m_!Xtbl3=dc@d82 z)F7=QCZ#qsd?WPcSvbfsErk-C#?grkTyB%R;a%XO(!^GL!T={eu~!}I8qtuyJH4@w zeh+?i&G{BrRyQ*WJZJ&lq?tFXl{YBK%m#|ipYjLB^q*P@yE8g+`pl)QmL$D7NIlOS z!OiI+Rx|I>)=ZNkr0Dojt1_zIoC0>#9yS^l4&F+(D~=?OS8Rq4Jct$i1z*`wxmQ+Z zQ|4Z}h&zVt?W}Ht1NTu3Gy;*Ek7gbZ z{4ZD=3v`Gr?fpJzDt$XM7h9)`JM723h2~h>S|k-S3#30+F)>$e!i?lHI_2fr21l9il*g0EYwt9=$A_G+JkX(}`eQm-gbs=zG0-#n9rEzM z6WEmq%uaPysLZOWu+*vF5rcJg{_*zT*p|_)b~(uwdP&nD>h8-=xbrR*3W?{-bpLw=`DEYokzWVyNKQ zS62Uo-ybWIue%J~WT{%H z<~gOC+uWPw(n_0ho43qrB<<~(+MmkeP7*vFP>_>V9g2YP-jci;p-r%34h1qeH+`n& zsa#R*H!et#Pkn>Q*bZr;M^n2n=~n~5oW%;Y9+#)xuX8hxiJhS*p5Fw~oDDh>FKp$^ z2+paUY&uUxCV8H(`^(en*Av%qsI(F_FJ=2=ZzgheDAQSqr#Ir;b&D)2vk|ipduD?{ z{CRnNNOm3qd9p`kNhFO+t(O7MksP!#R5Z5)fLj(PglNXl1NiO1Nj;0$e`Z~LQA2i7 zbjn?M_d2ANq3%(g#f?`dJN=G~UgiqyE!u%krvj*HX^i5%t+0H`wY*okx}u`ENGY(4+yJAk(!%I` zukS|X%}uUdon+^_9^ZxJct~NvvBtf_S1}39BlJmZJ0tGadO9v!o~_Moh?sFrOzk#^UM4)#kdF5&^Ur5(esGH11?O9mU%vwxpt+X}7o{36fm0!{k(Nd#JzKh# zM!c5xK#zTQX?2=F%F-4+{WLiSh;t;KHtsgFfhcd;|4o<0uAX<7>=+T!`BwS+|WmADZX zN=jHG=jZMFrn~+ z%=pVB@k1Qh4F#c4Q~3of_5((}BRUTXtqu{v`nRJAdlLo5cMv zYG!|%EL(Vmh(cH6Ui5}Plx{mc=h^F`Bf1t~qoyUKc_)73sXgv@A*^&E)wZ#-ZO04b@& zMr_+fEmb_$cjWLd9B9Xh)gBENtULV89Tdh_ZlEE${E)*I{$IC5=0I9`lQLpEs-8hi zcQXe!&%5A6Mv_|$-;aOjYZmb8(`@)V~X3^nl|L}QoMCi!%ZcJND>d(b5N>mP#g zy7(KG3|#cDV3B{iow7mj`d2x*dgzJE*A8X8NL^T1Cz333gdD}DKHsg6Gqup+bXKqr zxcgJ^dw)70SOxj3FZ2Q%1lQH>ri>tQ);ATQM8AEMH)TohN&q*{EGHmoZ3vf?RYcW>(% zH;>+L6Fy#QRk`iB9?g9dFMDEXdgP3w-Y{E4M&;#0_;xFz{ZTDrwS8%$)b$-%U0g7` z4iZkj4?NJ=%8P+#;|D~Wd@Zvy_}s7MO3>J?n-1!Qm9nm#Q&IoJ!j;A&!dfU!N4|Z# z{gl`scmjO7Qs|=p=TS?537Y|pv5<_c2oiXmvP^<%S1c1g3)O}WN}G)VgQ{VU5O@py z!OD-~3RJ)?$1`^a=Ub~f%$$F;25Qd0Y6YXOLS?~4mNutEOn;C_^-Jv#%BMNsfn&B_ zlQYwq1#zr-C0@+F$h}&`b?RSr6u#(x?o?w@@02V*hL2EoWh;p7eBk-iL?Q?`LjNnt zvjW>%E+mV{S87{+c`V7F^sJ`v3}WK`iL$spwZZkpoy?}FLPyo?c2Ruyto!tKKv<>% z@-{);yTRCihXXxHVQ^oKDyvVV*;kA#yse_Ys?SVB^}Ycqm;s;=fK)9@eRk8hX!^w@ za~4R-+-{XdYN@F}h?FwCl)~o%4Ybm_ijm8+IEKqk{-*IWz=Z;V@dw(egg(n5Lgdz` z-n>s+xtImvJq~#&^*_sRQJqQ`P-4hhM&D&fths};U*pYTj}>;R%&yndfXxK z^*=uPLLWZ(BEDfkoB zkAM=g4c|YuF{1oDWJVv&?*luSQfE4y>9vRNZIWj?7f4W3fK+iLv^rfWX@JF0#&%2A zCLL3OF3RT%FNib`O>E1%(+X8wL)`!jv7sX_+rb!%c*BfSK#7|{Q#4GO5_$`Mto-Z@ z;rkNi9sYkQB45TN^`F2PSFB^NL$+~#)~kTAKr&$+CHIQycshF%ef@@u2|@zW!ahcuIQ`s| z)S#49)iem!6-9gJ1zeRd%jV#(f6?o+IR2;sZg|2UO(@UJ{(T30jRV?+!i{ykp2vUr zCRyvFGBB_21fC-${%K%?ZOGf^=!;%O>!0-4ySx3EhMsnMuBq3jm9k0;-Y(>5*yr68 z`wSc(i0Q9{zgXwCH@`)pL*7tdZyPqHOZ9;KSVKgEjXE>72Z0&!C{!^v!p!($LL7-B zefZP4tggRDkyvo9Nk~P7gWSl4jwb7Ddy9@%7F1Md5HHirl;Fsj4I)P!@qI}Hh8&zn zG~x~Rbo$4Pqi^q16C5b>+-E?o)XfG}huh8j@Au3a{PN!PMMhiYibm8xY5)KWIV9=B z%&=cb1+^YAc$7#F+<9J>6W2mCt?3 z`DSn-3prPR-2RjB#-jF+frdK%io?ESiDxCqwwmXI_v=#>5Di~;2m&uEug1%UxNm{J zPnodjWwmkz%}qW2wI;rYtfX9dKZ6}!qkT=3T4&S}R#o(fcUE2;W<`ZhV@(ddI3XPcuDeZFG3X>l zL&9OlDBV3l4w0)(Q>Hxc&MOu;V;Jnp5-F0Ezz8;+iz*2~Xq+h=j)WP2Xa|of^t8_Z zD6M7(bzEA`{ug3*j(J2`U^%UP3%xGwD2!K=Bdx%O|&oUYTF}Dg5mX%!aT)x?4-0vK}2Ey zF>*$F(j_p_ziVF6!h@;{RwI?O&B&+~Ah!C_h~W1pWJh|(t|q2V{&jP@LC zsAv5#_&5e>h8XE7zxBCEjn+7b<5Eh4vOeit)r` z_Ka10ZqlOhW0-P_dV-d(dMqC4@}dO2QU|3;jL6h9L6QiRaDIz$&(F?k4u(h8VJg1j z`|dh1hjQs{tts^ecl3wCvV4=>NLp`ok@Mx_YXd5|86C_4CfJb#n{`@q8|KQSb;|T} zd|O7{%mm?_DFJ;242Uj4iBzy(XL~YGvU+x5i>v$1^xn!e7zP$;{sSa6cPP$b>oJ^m z-h91Em(U*__qvW8?k1*U^|xfQ)-_O{H?58_Q`bIE`!ns~7uP&JJ@5{gSrh)}g1!G4 zK6F--1hd{iB{Cv!!LN9Tx5##yO}j8Y=n$ory@^)uCy@#`_mkk<(y}%B=vac^oBGWJ zq0wPB_kyd-WG~*QcuO&3bryE^iA8VjA)n9ocE{rF&$17a1cnIddDw zF1`A)cL=ber+to|u?%|1w9an+nyxZ3JRys)g>mlMvX}>!xof#452^o$3XskD3SL0k(|IQ}*l)NseM*?Fr5nHSc&nU6j!?bYy zdj)P6J}RuWPnxSg=uLA;oL-z zu6Rj9Co6ND_IhS1$W}?p;KRQxOI`M4ZQl-O9wG)zD_LA>b6J>F_J~v210?QQ9v6z= z3mCqPp0;t9DIG04>txek?e<98CkU*e6&cQ#mxf|m8m_UT`m0n~_KYFIEMpARGxF`< zyTu$*KlcF zv0_{9;v32B4M=T3LY4~3@567lV6!Cl7e(p)nHQQ7s8p*LWCRy%@npWt-2I81AGTH1 zb*C1Y!6U{T2aLfKftSyRp$YlJN_Vgmyy;VEoF_M_M|P3We2v1%oTq%#XT3{BisUpd z*nG#QX`&?Cg&`K9-{O|Ipl1b-oU08PRu9PmU^((-=vXE6dQ8$4vSm&pedlwxFl;RW z;h*>TD!$A`-+**aNty%so6a8UpZyGesZ?Nt*MxrF8l(a-_bXkxlc?OI87k!i zX9gm7f&cSBTFmmI*Y^s30~{Vl^^*?I&5R58gCxV4Q2@H7b)LcL3Ix|^ix#@)RQMrm6W4qZq4J*RcNzpTha4EihW5Z*1C~#bmyZefT#O?C;_+5pNT-R@I z0`Ioe$6jyEtJ6cKR#?bFVVT^Tu8wrhgr5wKn6Hhs&<0OgcrWC)4eZ+S2o7xmU)wcJBBQh)YUe}wl700 z08CNQjl1V5>@xoH;4VuB4^JkaP0(+Aw175`Nm~q|i+rxPg0h-fD5{Gs++Xnei7XlI zS##j8DNidO6dgx0Vkpv<5H2M9>DUv2ab<77mus|&zuVQ*T}*XUrqjl5u>^%rDUyYg zPTLbCkp5L+f&I^uaZ(sBg1HjJYuB)py0^8-}d&s3bQfBo-lR{FofQA0fI1($Q(N%v@-7&5U zCSnQ~F`l|QP1OrPk?$7uuS>=rT;{#~mj-UqtU(!Pw3IIZQH8kWCe5+s2>%VN{fyq+Oi5aIYFM?la`VQ0qIerqum zcLKQ?^$^e+_ktdZQ?KwAYTb{K8Y8(RAruYGP?99q(~Uy6NzgAA>Ss@L-7La5)3O46 z*eREw&m#@2D2d^vq`%vEPcvI&-3t1~NJm^@An+CRaX<}>F*cYOHv)K6H2}LL4+c#A zs8ko3{rsBY?4Tf{gCWn&D*TN$c2@luoX4<;=&6!+IuE3mexj0^A0AyzS}e>OQUbTS zLct~VYzFm;|L>j7|G8WG|1b&v|NXZA7XM$5$4NzEb0pmxvf>X>6@p{@EBeer_U>R~ zY6e4!7@%8Lt~&}x<}H3iCC`IU24R^$ZOvSN;_kh$7-8xjFHDrzO{F zZY4<1n@WuFD2!8?Wmx}IPJ<6UgO516g9mnrxni9}e$Gt-SUK{b2)aS{H#{GE{mnLt zOa}XhJSaTqUXK&t2p|m<>(q@&*2$1@#cVitkkBV$HDw0JJ`~X{>$3Cm>aVCle;;Gw z%%gOw^Y!68L}!Y{X_$Wc&N1zK0qQIn_jJbSl0 zt@zJ}i@BP(0ug+nH@b6}vt<|FyZV4jFSU7L)L^*Esw~>Qh2}GvcZ7~R#ku1B7E{u0K6{wnrDs(f5f4ur3dCqRY`X!i-pMNeg>R<4r-yxzuzk^+Nqo@{C*6 zr_fe-!_m144+nocRunUoJpps;I%hN#&jz;Q0_F+DZ$lN{2M+FX;5t1ImIo9(PimKXgTzxB__T1kud zil=B51dIGzV;Q(pzU|P=P7=ACt0c0MpcrXz$%BulpLE|8EhLT{W2_^x^)F)gtFd6> zfrn3l_Bu{Gs$)V|*V-;kSrU(DVh`>ypBI(tPbLic*TRYRvhe+@r_9>61G8fzVtd^3 z_Zo;;j>mK4<5*?YHR>4yq-)CY+7U4C#l7t?ygQr6cFI{^U)cgG5U@`Dd6;_YW{IsO z`3KE2^h_~7_biY_f2`^4t!lG=Cd|7326R)^KI(~&JB5KSTHeed&Th8u=ti64E2~*WcOb+gQhohI_M7@R=d5gW7ablGB@PyW zK$O&yqutF8V^*J=?VN%PYzA735pEa&&Wsp2{tF> zdiC&$%EACwp=e?_y;o}*5^FvBQ%v66B}W0Dn#81)e`x*B{E^zr1EK@J6f3+AOC29R zO}KcWb51n>mWCTm_45oH_crF9U~j%Q?CQ12--#FC{29-g(@wcv(Gq5+#X(Lz<{Cf; zQyfH}w5qXamWn~nbm!=3=h}oYM-?lS$8xm5M{FR0y2^oUw{bxul(!%!LL(|*yky+G}-6|uEd0d)w60M5I!Mvz7zMWCV z9-iUyAAq|slZ;G{&EP*kS-X)hZd{Oc{%;yXysbmrXeYs(1 zcA%ThIJORp4$o@B)P~xNT^u``9_}&vh5{$!ob#GBaebDvWJ)6sMp8~h@4?EOpzU3m zE&u-0UmD*2{Q{kNccs!rSH|@MKD$#B?LXgpN%wi$6Yu=>A$LJ|r}YknZ8|juBLb(> zgI{b-)bWyly&Pj7Zsu1;bDSxreWcOcu7iP2ZR*@I@?=!ymQ5_$Kr=jeUE*M0M*`No zxv55rTsDJbXcNM|pTL;bC(d`!O{daGL9gqV1nn7wuyWV=mJ?p1iX7K;gg+nNXb*kRjJTbM z&hTPQQ(M@&`?kH(ZBXLdHiwTQWBThBm6ShrBuFNi{rPma8-I>`_wTD{Z;aynSO1K7 zrz+q*#DB(WPCSiicgX^oc;H*R6z4fjYq_t_wcAnP5T01$&=y1Vrq;+1Y*ObypUcgV z(n@F7^q(sT33;SLXBbn>u7DIOT^fPJRbM9*I=v1?>8)8vOrhB~iHSE=>uL z&0#Qv@r`J}dH+~qFl((;)XRepIS5Lr;Ge!Q)$64{4QF(lqmzgc0HB5yX;0{qI4+$g zQI_4Kw>J*|Za<%w(@}(}j(rGo2 zWpzZc&$RmL@6TUsfZH6mRh{E2Hk>V`4}{r{nw4o;FbN|`YaYO!sXbB{l+{Pw^K>V^ zM-?+04dl@)^0SVXzu1%Aok3z{m&^VkhX5W5tctLtmh$qaML8;%W@bC!ht6>y6oJIY zs;=+U#ld`+U*CPhXh9zkklE@vdzr5Ao6KfOTQ|bpYp6SC)GwuzA~iKPq}`e-O)w@l zY9cJrT3tz`5TNO&;7Di74@cf;jUQ^^V`NQ7^CX3HR zjSc9JH?_E`akKXH_GYT(Cs1=*?Z(s+RS9+=0J{kFN*!mJ)s+{IJV)Kpr8YNpJ=(Ge zFDGk=QMd~6#bHWtOZ;|WpAT%bj?ede6}(KiXGwSlC;y@a_FJxZqyN$^f;Kfdhz35u)NG@>SX>klP@kDYdB$(3w*<6*9Mtbr3p#TOonB5g&;vg z+C}20Lq2kF0}V;|ap)e)LC3Y}cH#O&;>!a)50>S%iOsZ~GzY*E6DR}_s)Q{~wtE?ADN`A59`n|q>5I_1= zbc&z3Wa}$b;q@fHOd%aogKqGxNxvc4)sFaSH<|&*7}RkyQtqi#UsV-1 z=(pCUWM1XMwm)cUUd?oid2p6Z&g5SbS!{$kUFxTNi68?`b=g%Ymv~D{${7t4@3(j_ zV0NA&4qrN6-^;Y8k)~|V7T;4M?)Nn`+=HAX^2CL)*!|@Z zooHoNlBWI^>3=)|hD&0ULv2Z>@fdX{ak6CQh2?3yIlxhmN8uB92q$Gc(;S(+nF0PM zdlU*2RRNV%ukUPLs%9Y^4m|j@JkxHQKQ7w-&UaoM90(C`_ zPwWEyRgP0(HS$D|k?=7C>}fKvW~&CtviZ9H;r>1F?-vB089Ln5{BaFs3*c{5o=%hM zOC}$WRY!=vRxigI{hCyApk2-SYDIF(ZNZj_p2$=Wk-^J#;?(10S82ITN|@!NvHnn6 zYAY;WfVq?$qGQ>cdPbo<{?5=Z5xtoQIT5{4+h$}l7c3%Q1KKdDAs-S0e_|{E4-f5_ zfs&GjqG)yEL;AF8`_0^rmw|f+OxH7Uehb>!50J2p(D#a7Ulfkv4yPF8nRNec##y}% zOCj!+!c4alLSM#}*AK$+X*&3yzsgD35|n_2v_ITI?D2s{zoH^`{+ ztUJV)C$|tF3w|geU56}u)rTc@RZd+%|4n~GbP|C^hd22~E_#r)63(bm_P;VG$a<-x ze86-(-7jOIi99R)zvFq;!!PaK-n0S6Q)e`_9^IX8iYLo_K4EM@hqR=lmLdEI8D6O{ zUrjgfsH_?0sapPVMrj`+ln;Nku_&V~xuwiTSR;`IO_0cTViHz4RB!hc5$evR={pM1 zl`glOzbIR$ui&G_=gaHjBkZgfRVw7s+)(Ln+)m{6Sk?){iA<~KWw(QD)_p&-&DK|; z);%!VwR*GkHV<+0QYu1tzeteIbh|SywRCbG;^YL9BrkziWU0Qm;4_0>yFy1V5QpNo z4xbJxtEy<)uH7dN9r@9rt=B;rld`@uSpmm2uL5qts8-NbrQuCnogmghwho0QeIGGz z8fe;Sw9D~5ZMj#or_R7jsejr!o=tOgPfE@)2v-Ups1WyyM-&|QW5t`;$JqkwbC7ai+Y5M z%b!E8+Wq~0%n4enPKmR^-UrkV3WD{6(Moku%jzk&;xv#=J~A5eP+DNKwNriGeqs$ z_RG;-Hh$tUzb8M&OVYhRH_WLRdqPA@dhC#s>#)-6c!>V&#cBL0d(jd^9i7ZasTk$5 z<6*{F7`56-omMz8!}93Wd+I<(J%~D{GD1eHuIft?a#Boca=B|GxLLFgonRbaUwCdz z`yT-ZgW@V~Jbs|Qw^lXZMhnL8@>o|fA@hC73j+VhNqNhVkro-~*@IiG7Y4ug4bg$q zB-zeXzRq;_Qk)&pZ{%x~STr`pMcNb}?iMLd{g)*89dK;V1_3I&dAIuD=gdSQv@X}) zZAki>{^?HHBZVizua8Ad_WC)BJoU~m*YzJZrstyQ8rbGiXDCK_G{-#StiZ1sJY)kk zw;?YRi&R2aAymuw`iFTM!d&ix^CCRy2Nc+sjpg-HI{(+)INnIq2?qL3PgQ)B7I(-< z)3etfk#jY?IVo^ckO0t)^@KbsrtQS!VgUMrMdVvjOhJ5fvU9LK(5>-lj}((%`|+=b zlD@C)+Vam83LD!-E~Y zU#sF=lxfgKuh?GSZR3D)0KX&8FO$$Qo_*Y>2-)ugl#d9QPD&JXy3aZO(lPCt73{w9 zg3jBAC10tf)V)CKM|;O5%#hj-Ua+LDogejMPF~e=SJIG`#|P^YvR4(drJYj<`nMu@ zso{b_g*oT1i@13n>E-WxI^7*RBONC4lSuyZyE^RZ7sOlI@meu@gjNw=6fABr6|s`u z*h%}a6ac;=pE)0q`NvslTQKRXHsWR-;#{7_8PH}{=$;f{1POK-`TW9aoCCz-i}S!T7Z6fjI(J%$3hYE_Q~<{HUP z4ydA@9Az_PC<~o(*nR2%U^^RfW;|N^UT4gxTmQY#VCK<`lHtw^xRSctdP)!;+d{@# z;jc_)`)yResqBTDYKOo~EV%(G)!4mdp<9&o-7c=P1E54**d6Jsy{s7Oeb!FBi8BTK zd5mC~L!~^z&4jC76QRKPV&5ynQzsFK+iBPb3h7-0YY#{@_&0U#>f*qXXAI!j#~x>q^#a?CfE2EY+LsT0i3vi7U1u zr%KgQ7dnBUnYc~AazllKHn;KjgHov_(DV~|7Ek3yf5iHdT%zM@e`TV~&P%l~#*D%E zLjPzE&0xW8r{sqJIo3liv^!N?+3p&zB!7!A>Mcq}0-Eu@sr@dJpxQNjzZBg;b<(aE z!mL?>VeUz4Jx%lp7j@{Op(IIjB9$3s22Gwu6K2>Brz*@8apMPNn;>b&dd%UfjP>S= zPC*dRK#prfvGM<4?X801_@i&%!6Agf-Q6|F;O_2D@ZjzioWV6Xgy8OO!QI{6-7SQi z`Q20hhg0|ERNXsIJyShX-CZ@kcYpU<>$CaHT9~}3&;_0zNv}|~}e`IO*8;GGB zWkUIppEb?t5;nyRbi}mU@J(w8(YYhqI%wsd;sdfPmREY2g7J#$?_Z-#<91B5l)QE1 zj7jkjQ8hg~VVvB`ls zGE*h9O%-*2K+u$BO66f>rKahfIjic8OpD2-Y}u%ci{s)4;9S|G(36bG(7Kq&df+L9 zA9g(>o-HoQCyKx|nl4B~%h{kAt6#zi5TOJ+(+r^do)U@fI?p>N)s$Y#n6&~^IUj4U zTYc1YeSv?w3{O`8p4HU%a%()J@83>GKQ8TllQ~uBJEQ!TkG{fTH?ZTZ2zT2}uRWX% zy~LaFM$Ncn9DH0fTOY~DDIPm)DB4~9#cMxspVNs%Ls|4n+~hd2q9sy}7RH`}>G|FC zY32)y$GFZ9pjBy7eaYw2usUV(MaF`Rc`bEZx~YypXKO0>pz?bUT={UVh9-b5 zX(<}W*~+ZO#2D2>v=+LD(CA>96b_s7VE4R{A0zbO)mbWoxF-r zZOm(kKHI(lfhKCUGFKkNQT^CWm*Q<~EK-)A2pUdKy{o?($UNIJ8I*K7ck{DSIosror$u+jrcg%0} zO*V^V7-ZNiuJ`4x*&CA0{?(Vz4OXqygrZT}DmyR!c8xQl%3pTPbTJ!kJT4l$r4tN} zJCj{aECb<($9cb_c;FLD%+}q@3?&&XwZCO9`?(t0+SEe#^*D8nR?=@GpHyE)`8!No z%fm2YvjxW(#aQwN2Bj$CQekQ6al4>2`VB|~OMs$S2w9Rwi2#Fah;X)Yf|d6Cz%mPa z7URLt+Z=ICg(S|zp(*pQ316SJqtwKnVB8kXG^Y$>R|R&XWgK%eFtNQA_YIm4SU~Et z_c(Ur;9J5thyg=)JiUXKPie1}x1|U86_(COA|%}JK|w8K6dv6%=~RLI{xAs>(dX=~ zEv4?2{ryLTWqaw`T2v3m&PHT1p>X$osoK{B%U6rNseb;S;Np?vtxG2L;Q%znUVtR(N zpWC}z!Nq2GRAMx0DMH$2`sQl^#sf!#<#nA>v}1P?PRdklL+d&0!$c0YdPBeiS1RPz zBw7BSsN-IWf?xC~%vxPt@%FdcTxDr1AF^_ZB9x~)`5GNl>zJQyNR?O0hf=x9Tz)q@ zR(`kW*W+>j>0BG?cSqwxqlMH!z3_#nYQ#dHd5+s9jl%{_&ZI`3*1o`+*Ogsu4+giU zqGWq$)wne0UYygxSA6A3pw-!$45T|LpeG6_2X*WB9ThmCv)AlE+2YM1gYB=D8aIsg zW2-^IASP~3WpLG{gw0PSkkKE_6+K->vf+LsQH(>K;hMa3aRmdl*@>@Y6nmWWNPWl- zKiJ{a6wQ!6L;4k=^h2k<9wB05-YVbRk(Fc48;{td3KG~BFlEqu ztKH{{swkuY_&vu71FmZKR%hIK2OMrjo|Q?=lQ|sT7zLvg&X+Ylu69LTvSOB|ZH6Se z1Vp7D7a_RHIhACF5H~onBuZP12|9Ysk0wI3HA9W7(w}T*@Y=0Ok{Xk^f{L~wB4+>q z0-z-ZqB;y`#|x(boW^l{2Ui^q3X5eLq7YazHJI+&`Nwb=;kT@R_2`<7yF9{isY$S4 z#~QO-Ya<91S`OB^E;SkE#h)SWJ|PIoXGtm7MdN5xFR~@hp%S&EC!IIQ^p$`oU zP&H0RH_286Hn~zUcxr~k-!=^<6R#>Q=p^EXZun(0F~LH3RKTPf`y~g9xXXSc7wkE3 zp*RG|K@(7M0iFguiLP!Z;oFGAGwbRTv!&}BFu9Vv665pCQ-;70oMX%!*Oj`)iT!j} zYzO5D_a?k>BDQCZfzvJXBz($5NFe#9XR6F9e=+X>0#~(t>o(L>Iy1`W&s9ZM=HXI} zfdE(#e>wn2AX&*exJ(q0?Q% zy{G!Q`zQ+W7Y?nMS*r;{=*UL8au>|(9hZZgAHHIf-cnhJ{`p|g9M7^7O7QXEW(uzH)z(1>j;jwFFZLVWua*Q!ei z?Z2CAN^*Z~z|6&suON)K_;^$^{!jI8gH-Qnvf6@I*sooK&&YT{uC=fIKF(9=QI4PV z(7m2Wzv!fyKh9g|j}jM^4;?jD)2-AitS1T_*+Zu+_~pSA#|Fl>n}7O+s7|cpaDQPm zosq_OC?J*gWnolTJzP_qNL|KV?gY~I&QiXP{+hTVI&Yt1rV3oQ$=(c~H)*=W%HxV( zbOJd;g+JlIOs@yR1afzc)?9toW07B5Hw~5{yR%0n& zfUm1#j|{V_UO`pw{rQ1;KjWk~7fqNWxIRUbLY z;cWQgbv*Wjb_~D471Ny>zP0R3OE#L$3};AQS!VW?o_3n6dbey6dJ5KQHUNNO;2;A) z?q)0yBmv1KL7-gViN_T6T%-NoII9)XZ*Q`PcQ`mrQjR2q8_8~WR~+RpWulx0nut2q#o|8Mx$0L^P1Z5_8oQ_YLF3~g+LpVN-D0-nsYxEWs*hC6Di?!H zai+l#Oev&rvo@pD*hBxeO0Ocup*Iu{Q(0D2gvGiSqTvP^nZbg`-ADfN)R_UnfabJo?%{v;%l&s=tPCD=dCJa^{aH8BPm9V`}Zg>xEu3Nrik900Ev>eI5DulAY)vBub$!FQZXa86l! zxp`t?Tm*+SZ@l%XZKj?yG*g#NXIGf4!c)2_@u&bk-T~j*jQz4Hsw&YCGOr_UeXToY z5}O_8_~Rb4!aWaow;Fdq(c83-_PZA&F5OK&F=m+-dz?D^1R0#6d1xOYo>+IS#fFc; zR~nV0_VjcH8@6yQA?}SYUu~}qh91IsdxGYcvVfx2d}FH0k@6yaZuNOXNXPa*qJlR9 z7T-wCZvM_Hu{BdLfr&XxMzvH>&`qs7x<|q~s>_yT3MDot4REpUzs*6&leQ`23}!@# z>ZB=Q^Z8hY(GQ`K?C$l1?#;+RkeBm1$FwmP#t$X~-oX$~D?gjr13 z<{G(i&?Ns9vk&)rvL!n-Ox*7Jq6#j2Lp3Bm{LGxhJgt63UvG(Ce^r)c`doW45-oMn zSZ(DSASFfMz+nVe!6U_}Jqc#y)-H57Br#tg4_v%B$f>`ig_?NK%vCVO*0?H*OzKtT zKML2`rqp{9Ou_{+(@f#GDn`qYp*zMLPO#|F>d|oREis!Bh*BYMR$1@*#&J{W1hW8% zpD4yaGg|J3CS;Y(6>in}`56*rQ6+j?>><_X4wtgvo7B6BX>N)hA!gWW|fjE@Pup7uR6s{z@Nl2LL~u z3I0ETz|J4Ou}A!$_u}NvL{xq@zh4Sspaj(e4lV4G{@{%k981o z6Sq0mqk#n3dcDW3-%5%u>CF7_jr+|$^INwxRDwNZJvG3EEL5~#u~}m7lIy==Z7EI2 zw9{3ZA_az$MNZJ)Q)s?O(;jr*uhM4}PiFL0-CDd*&zutQr@DCB%t|>7r8c%0#33lI z9bXf&S`+BHE?9Zr zs^=uX*$}~)(b2$yqu@bc@DB`{bjJl1VEJWdMZICJ`I$$5h>6?!4rrWFVjlFEVGeY< z;gOdXhm05Xx+LzbAIK86(T;a{1T9?7q@*f;idFhjqZ5C)d6eP{8(wr77gL{; z+SH$2bOo9^W%|j5C*?yk=~J$Piq%C`m*d)o%i?|1?xB`yXBvXKdH;N4=%Yw> zUyv1J#cRd38imzhWvJ4S3~(FKjBZ6zY^T{ap#xkI^*3G(ea6Hp3HZ|R>mWc7e~Ap0 z0?A;DOlr?veLR54)v#mHSg%KZ$RhL@UwT)-3F#!4GYx$c;6?bxZf177bSe->zF`8g z?$@z9a@P&APYeay?PqcAzbwRPsa9(msBv8a$L&|pAzFQ}Aee;D5PpvYEbWEgItzWQ zmat{U>otCLdROC}9Oo!qbZCP7*nNLtRu=DN*VR$h%WD>dvMNjLLBN`JOqtjkHZ3^n z_>zHy(n7bTZ_D+j8yAR(2Y@Jv6#&$1z#U_fS~LF>Oh&-9#*DUl@uFkA+AX`-z}%NhFjFq(ImT zd|D|`gbtJhH~Otp_?ksLvxn@CcT_`Lep;isYdqP=5xc;nZq=TacXFnU%MpDwW-WB{Am!6c34t6lFHo zI@xvot~{k5_8NBIzh~ji{@Z=LOg@~;^1M;*QEXGuvRLABfva)0QgfUOxeYnu1R0w302_)tlhRJRCp#r=6|5CDNH-G}B>uNkQ}+#Us$4 zZE*2%`?Z-%{oU*6A7F39W~Dr;kXIb9E{TRdw3rbgoIZ*luNeLe5f5R2j9k+gFxBI2 zOVS?FMhg8#X6=ooXC18w0jOkYRo%c7D|T2O!X`MR@2~rdDq=;~sgsqu5*nkLn~)Ow zeOrUsWC<9iN=TD&jv7xM_}P!)%9!Vb!`><=lz`B!J9|&&(}N1oupZI~Rgd6yIYpG@ z?WZIWylo!pun@z=a1F2sS3Q-V}MYmdm7LX&IV`Bs*s7zBwf1N>79W z8j_|UH1`%TBYTaRp@JwNR`G*Pr`m_OP?g4Gp}tU-gJB(7=Te_R4ZyHj5tGykvJ2{8 zrrPY`mcb&I_~fLJbv;Jt4|Or+8mH6?MKd)-OWQ5URwrm~u<~H=n000VUdlEIh9V$5 zm+^N(E#ynp_8S7$vImM+!orG(h}Vih+A!PWoZyW$(OnaZ$iggm*az{ld@1HnfoG`{ zGAgi`CsHymvbaYHCr<}g{lau0Z0@7e{-3Mv%d>PeIh)}_V$Y5OLB5Uwe7;^Sif@h2 z+-JL^R?qCYdW|dkK@We7o^Nk&D(hck1WnBl<8{E0SG*PY2@GDIS_c+&!ieAibWO8P zqGlytzbi)LV@8R-cHIkR*<_$^1NRvT;yCLC59 z%tt~jCuf@}k|jIbFrka15Q|mlWmKS3V2rB~2eVJvZCXa;b8U{Ol3kP@H)I85uYWW- zH8-l%_vl@Huxq95*Nf5j-$_c!NCM}Dj2|K2zuFZzm^`PiQ+^(J*yiDsFCHLk~ zCG3udNWvyb7;NB&%_mB7(6A7b(r=vNj|Y(fDtAVy#E>T2LJR2}YvH$W&F8cKHtzj8 zNLVTDY3qux5$|yaW&v{<{!le_iw&J4r~W*&(5x%tpxIYki?Z9L%5HWJs((`=1Sv$f zI3?`=36!Ls(I}BM9}q!E=^<|gJO$cUxbSCBTnBfBHtpjS)Da;H){&w~qiMIq)>Zc% zwUWYkR!WzHNNQySkaYgO5#^_~JsRxDh&p-s;RIzz%CShcQu|bG?6pS7(S16?jO01Q ze7kHpuO7HqbPcJ0H_q9*g9JmfdV$t|T=w_WqU3TF%_l*T4LkhiWf<+E%q}lB%|2w; zAdfOlmor9VLqtThBO?=HtHvbLPtcc=;+kM~f<@D!(Ni`Z$o8+7qc)u=t(|zQ4(P>b zktwYUz=`e26S7K_gLSyT_Nwa@3&aDKO?Drl*W?q5rJAioh}}Kgdf)T=vNkeUq{ew4Bkuga4?AIAY4{N`h%2@8%G-p8miy zZR0N<$6x!yVXe1EjYn=~Qv8SjfX@2O@%8ilZDl(t-saK{4{=mp!mri~HQIAba`6EO zJ^?@+2-W0w9ODW7e$jl$C~aH&km$NAAbXQM@VprQ7mWdtu}FdDP(n?0UQm*gQJR)q zp+k*-xW&a`WK;F=6nz#^MFrpi!s59=Y2U8BlWq~-OXN%>to??;hlGu`w%;{V%bdra zQ$l#bb#1mkKc;CYz=|eXgNi~yv51vL;ir^5Ul;^MHT5KR&V{mk6vJ-g6c2ZQ<1zY1y1JkC%-5UsPln6IZKVsiPJ_b#Qs2MjXpV2hY zdW5m;%?xPWv6DrZqYNS@*PK+a?k#F1fdsvdcIlnZ+$0qBWmahvk}*`f)S;`Y(2HuK zN#k;8Vqs|juvD=$b&knlC5m__$N)6x#ILLA%Bcq3>p7Ij>FfDNWjk5!2>{wcs0HT8 ziw9^+D&#ZIThk}yn8zOp55|$^=|~bHzIC+@&}97hrdYj;d+ZV-etBF&9Pf~*YptPb zz^oi9dWUDF_7o3GVYJ_9W`aW$^ZKt$moph2heR}oV5*T8dUZ)yb$T^O(ii}aT;!8l zcn>6J|En#>e)fAqSl2<@F>(RqE~9KKIgmV%TkrK_S~Ks{YR?YO-FM>gDdLYa-hY5E zRsR4LT)v-HHLF`iq?vS$RWR|~A_}I|BCN6&t}X4LF2M^BlQ`gA;X)>iPf<+Ej` zTa|Yn#U*y#W=uME2A^5*F52D*8xp3l3fpx?iW3F-NTxI>g&Re{Oyofgg|Oh}E2N@{Ur`eCvNTal>U6G%P@iB(_`zU1?7o~- zP00MWpTz>~Tb{SfJ4qyitv-n9?Upm%>dR<)h`<*OTQd+3&%GpE)HEejkT#tqb1&-R zOg?Wv0FMd#)W-H+i#K?H2{ZBNzyN=+;q4vhx$e9I-;s+aDS$o?R2^D+Qv|?OT7_gu zqj~0THh*A136*`7`&3%3_TORtAChT$ZT=wdD8l%k5KpMHA>U6q;j7Zf`Lc%s2yLc0 zsvH#@fbtJOjBbNWM?y{-DkMj-T%vv|4MC_|A=9td#{X=Df;cwM{OSGy+Vh$DEChl{ zQ6YJ$|Fe_zJpBQwYt5D8|K91{O|qp(I6-=PBcE2TBzf;$L$XdBZ}-BdhcCi$P(pu( zBX^*8@$$V<5?vzjugOJ7!<8x)I*BpX0`NCl{0OIn>=zoC78Q@{)n}eRkl$))Deb-e zTXhm;2MmaASoVN$zKeLy@3N(LAZQ%@6ooM?fY0CV-!9;=RgNG`R0BaVAz@)*w%U_Re9`jnY1WU}fPTsK5zQ?7 zlRkRdXt%IGKK(WCN7jL!*Dlv16 zO(KRumoFHLZ_1H=f%}N8h0}Ny;4zoZQ5DIwoWmx^6(+;i=*+YAQgzc&anAQJs z2ybZq(Myti?(p7XQDC79vVk|=O^J{u=3bnZoW(l8#bC}(q>PuVkE%9ij}nFb`0k-> z(Z-?V+wbusEil}tB$7zKZ!x8)8bd#C65Yx@EV{roXHy`#&SfBRZ$(lGN#C=-Fxu_Z z)c{23#3#O9nu}}fNFB_LG-SIAF&=?(T=7L}jclT}t;)a}gH}f`sLZ*7Mxn*Ls!%q+ zOyItm+Vj@c3)dOAb=7a6znXRPp-=iTuKQjoZ)tb`=lFQ_U9DcZ znpR)XjQ9i$@ME5XY9>)_azz(ecSj0#m_}#$n-%DOX}G>(DV?|)<92=W4-m<*(DrAy zHNg8HU?5C;8OHI~rOhAjEFQ40$u7Uh_HLEt6mGD{UcJ~%y?;h!E+yQC||G&>mJ{l zr}lgEbre7BfBa?0KNHVgdwR1x>r$BQFMh>`=D3|j%@rqUk@R~OwhHB|%hwmN@7leagE{sC@6zLI4eYrPl0!1y5t{XB2JO1OMoILg{h>d@a*y^*zpK6tOXnZEm?_?xd^4}9nN2gqx=0ON%93b#9b{C=ga zykR^@I^P9^VE3k;^&!DNb(P0=s^mJDxZozS@=GpP)ij1cggE?BmU4#*L`_Pvh7Dw>+6SU z7UkMPY|!tft~%d9KT1R8m9SgoiZ>+TyILj$E7FajfZS<4$z7ocFX6^(?ft!ng@N7c zx35#~e%PrV5Qm`$$MzfC*VWHPmeWE=s#hnbBh{^S_Sn(C^NBw${!+%jtXb4V-8MbH zFm`pI2)FV^|K(18rBD4e{c{uXo%Mr?;ou!ZL_ETScY}MI`X~|APJmm7=S8gXy9MiD zX3O7C(XW7dyU4$z&jGp&9Vo72Q#e@fj^ZDs4mwY_@Yrb20-t@CzpDD;2vO>I&N6Ht zW;P1h@5U+K7cBdXGfG1>$3GOqte?5{Z%+vbuhrxdD!de0q84cW9Pe`YjPU0N!YTWA zszJ4?-yRSh`R?35z!FZar}zAhQT9Io)c2{My2fy2WN6DvwooXcTt6A0VHRuOoH@>F zYI(`xIX*Kzc$N$o!syd;6>pOe)DIftVeS7l$YBJ-fHd-d7H8)Kub1afBQM>^@7 z>F^L;U4ZM4%K#6xeY`lUH5SYU1A*0qW^6+_A=t6< zdJu@hpkQMOV(JIu?cs zKYp;5rA>DYyzoVk2p|9jw3&6GTOhhEYz`YtB2lB-FIw;O64^Zmcu2NNyLN6PZVQx8 zmbUZh5%f_OaMU83Ii-P5;8>?L^CbitnW5BaAKv_%|G!`F%8mT_r?au<-G+noej7$YqpFuy z%Nfs>!$61PPnsOV#Kg|3uf_SGLKfae;P?{RraJJHOt*M{bc(z+%YOjCn8i=i?5>%8 z=jL^Uik?Q?M|8^B=;@-~>ib$ym>M2Qumur|cZB_|Y>IAy9?DYXoflOj#0t$ltcJZZ z@?CZLA~YHE1ibhEF)m z@p9%;mz4UD)b*z`{=R}*BR2%rah0(9HA+&GQ%x~vMO$# zM76mcs@rMI$wX+XgR#QcLjiv8+SvV00(^G*xVe0G-0--gRBL$eT%xIgHxp%y>FMT6B<=)6gwgJ^Hxh1@%VMafLF*uqa3@f2};Z} z2;5n3t4$-0)_OX4Z#IE2AkL$zkJv{d+Bz?%6+9O1>|peupr)X8qid$|v# z8`STrkBYV!oHeyMI2>ax=OQ$=+C)#WF#_XtQlPsNxDtnk2GLL=t5B?nAdi~>J^&H) zlC#u`nVrJkQX_J%73zcf1(itQ1A6hj=qP=*;oZM%6a9`vYz*h=PFKRqqwU4m|oLVtQ?voPwx87+n9 zOT3OzTIDV}EGuTv+*E=M<+Oh9tj3x-A}K#8FU^nyuFOy%1GwBnypZpqYXRC5UQ#o4 znSNs7Wl6G;8gl*ZzL_tFKd$4Xc&nIQNgz{M+R~L^`1>AbJ(w`Dp;1o`?hxaBGm`~W zN+;i)H@A=>PX;p@y-y=gE*YQ3oISQ%l(?cBs?yJMakM=A7c9=P1(`h96XOj#aGcR* zD|lUY1{mmRM4)(h!RmGaLjqlK<4x^M3aSe&z{237dAXC^m3?5)ZG(FD49jy{m93+T zGL*5*-IrWSX&Q_dygy?*035QP0c;OJGs~n)xsUHzK_r?(Wv8DGhvHc~lxY4o-fR8? z@blPAZlJ5wpY&|T?)+T8uhJXixB7O=IAKnp9$Cec7j0OR;pXlzm}7PSmRR>mhVCnDb>pw&ut%3gGJSv&)umgh%%3%MA|EvCa_fiCsd$Zxm$Fj@G?c?f5K zS4IqyG*03+zN*h*rgKO`7&fD&sL!k*T7@^mI#5v_g9a>+R+mHsu{_BJtp~r z+Mn8aMT+z@x}s~Fgvf-jBlZQ}qA@kJB9s9M5s365+9_Li3dNpU*O?o}l~s6yx!swM zjKxUgb@}hu0D-!|o^V!z-4#zKIorOy%5Z+QH16ckJUlb|p3bXnD9xw5h8y!1t&?Yn zRp1l(e9#~|%<|kPzoPW6Lz9#aE%glIz}6^#T3=T+8(1Ia3g7mt7LUb%y|q?mwzG7B z2FFK~5hsU=Xan(%V_*HRDB3NGmxC5}Ij3gj5{q(wY8Mqv(Iryko|`l%%1TxEY^Yr1 zBQ+?(&@jM=fq{?Olg}nP4F-B=a(O#;{`aiNt}lyi;q+p=PIscOX@AECk!Jzswm7el z?2z@kt91S`ThiT%s-~T_%B+uAdXbglGG(OShfyV${-Sj<({&Q zz-cuA=>&_y*-fxw{^Desryj=a0YziT>_HKMcPCu9$%1T1_*S(EvZPdB7OP&Z<-Vrn zT0y{+f2)w41{4+e!W(ks6b#hm8=}1~wN%k3y%AZkp=m4@6*<7^J=iljk*nW{9Oe#& z4hu`;k&63mGN@`|Cyf0jZ7Gde0JyDL;n6wd!wHPo(_9Nbus(;=ZYhd~frY%|4(#kL zvl4p zys>T?OMczsuGe~M(YEJ0sN85Fvh@g0%u8lzQElJEh4RytV!vhl!LQUb8+W~gz273W zbZY5gptR~g?6m@BSigFmW4JSIV)!zBn&nt*9W6Ua44*lj_BVmiiOKEHN5aNYHH92B0>*>C;QCu?96J;nq+;iQ z?gqS0mA#PFH!!prULOE}-KV;VbP^q`QYhQ; zm1ZZ4owp{Cq%IwI>*0Joi`Eb&H+U49J znprwxd9Hy+sBN0K{FS<)9i_MB3S4_m&IW88PPttUinE4*Y0Y6uHo8ot@Y!XDJWw4 z{ca{9=O;zs!c43t>{G*v-`8-N64T?}_KB*<3z~9MDpTVgb5MEXUFixm!?PT@zEqRSSilv6mcE`7CJmY2I zH(ug$k(o=0+9GR8Wjdy&$3RCrP1Tl)N5+=>*S=PhRAxU5rBRj@u#y$c<45wK=2Z$c zDFagu=>tWCJeCeS2SXP}!%a1?6PA1SM)6L}I}GMcQ8J~ap;-|3kdSRu_Zm@)O>D0? zzOXC9B|vVMuypowWkTQ2;~D8E}49@ z3H`|oms-2gb1P06==Xzhw+#1DDn%Rgsb7P})%|#IPMaKVO2${3_hy8$clKSdQ*|%= z&2vY)jLlin=|($j4#Bw@SKwEjQG`h&9t1=N2>T7gO+K$oNgNNMLd!$cqOw=IX~L%7 zhA(%%vV2>V($qJD$uTz7m1rr!&S4pO1B50*?#nBWQDBKer2PH29)Jv5rWR%2*nYr; zo4f8nRInt{QfF}KD6~mnNuOfn6cXgB@R(&Y*xbHDMP1EbysKJ(2$s=l=3pTm>2hiB zNH3!?mZiv%ge^-LLPiNc+z4o}1!1K;Xi5>-iSZUWM_!scOM41lJO77-J(6i_klYaA zYLKFqxS-HNc(#ZGpovn|O#%#%bCjU_j$>b;C2Ivyrxb@%|HhYPJ34JGb#?g4A5^fs zgtuJbuawdzYt?I!Ge4`<_A=b&$zcc?37qm$2pl_3WyAqKVM+Tvne6CHI?x8~YiKk~ zhYd?|q9$?k?j~hS1jWw*a}>OoY1S&wz31(|k}s*N^I1;ZET=(kwrA*TJqABP=UF;V zUDd1!=apG8RjFee+CceXwiy+R>%z{)*k|h|Gh&hv-(T}BO4w=in37oP?4h0)pZ4jT zh&;NrW>sgFWHssMhMJM&vmtgc7#3MZ<0VrKsU)fMIwq$*BDfJUg9N}$67=iZfo}SF zGK~deD!#KPvdbY;vU49q00w~f$!P=N3HZYsJU1yG zWb(j8si=YH&*|tW$Qp;Z^0Zx54NLN(hf#EyTCS@*#3Ofys>4D>s^Dx$zI|2j^PX?} ztwFo6w7hHS_p`IkcRj7xe}G?SSA;@# zQJDuJqNCFjp0n4V1uV_X+*)&R7VG~Q%md>1N*bp7sg!|5rMsh5 zg1w$Y36lmWLncXe1Xi?JP}OAWnn^EL{5c+-F*h5IdZ^H!b3;RZSR}i(q>6IOG5tEw zZxT7n(U?~tO+n1G6|kR$QYDe59H|$9<$yq=Q!q4P%4V|2*K%ArvVS}fNJ%)_$K(3m{M(svI0odI zzG;oEHFr|Fi?{DHV~@C57B915ZB8x1Tf3Qa_gE;=pj{H|b;a+tF0FF+syEp=P)xvw zn;t+ zz%9Mt>y)051*W#T86-+bl$|vwnM1K%nLr<|gLoh-)cg*V`vli!1DnPrIm`1L|F78u zHM$jfD}>1HbR{WJhCRCQ(W{F(c2JH^6SDY2Le6v@;!JLFrM$QRM;tBcQc(W)AU=NJIMlgBKYCJ27d z=-0(lX|z(xhv@xtX%s=eE94_plHPpg1I#-+hi$aWx4 zJL>*fKD|&aaY*GB`{f$A1)PmYrh0z+A6YIQ(!Pqx^W>-)ngz+tgE4Aj>N-(tv0IUD5+a(zsx)mc4j58SkwMD{6HCdr< zDTI}K^qI3QsFkQA!^s_1!tlXhlk7(w7N4mxT}pl{0E`p`Gm?|8HqS%7t119o^PrPg zp5V?^xjk*0{V6|~eZY1bDR;icya+zucM=ryrw(ILb|<)xl~OYzlVOUAbG8!*PK?~F zYW$s?oQM%c&ESjN!}gbZe~CiSz0-q>Sc0Ese0I@~jcw(6hld#w|KI2%k5WaxQsf$u z!`0x`U%7wU3aa7W`JMR49MAH8%pAOHH=ahK`(~9m;r&ENUc*joA0x#PF?G#6H5BlQduzm*S;HO_;~%2VLsaleWI#~*5u11ZlT*ij71JFzO_zjGx6xkG3km* zWOsx!+td6AKDuP)v7|#rQxA#!@Fz)2O9_d|S@L9<2Zsp{lR&!)sARZa^VIzOd{t&i ziCzdVJu zmRcBoUQJ$Us^$ou)akQ1^z;zbi>KLITQ+R+m`ZHW)q3h&=jO1IscqkaG;M=xr2O7( zvl?CGV<3;ECxpODee?(tce@o2VJwueIc|1NSE)V)pM4e++kMzZ!Ro6_5m%)I%@3sX zvm2>)x}jDgN83O@i)x(T=zTkB&UL$fIaat=9+EXvxm82=2^VR-n)bXt;PeD1QRqK2pE+lEo$N`*5POH1?(C)XZyvm zAz^Pw*(>XX!Tg)Z8)?E?iP!0N_7hzt@gZ(?CJS1ABYcGu%gyd%5n#f;XDvbM0%HQY zq0N>&6Fh2cN4*(EZQcI7sIXWG#7`{w(XAR|Ous_UfSdZs9C4@#^^+_RMo|b#5s-Wi z?UX99>9gvE_onH_Nb<;uK>IyWfsjE z!=5r~#xuYt-3Q)29LHe87rW@nuN(8sCeA>%c!7yAJwCcFaZd7Nun?WsP;<(nfYMM@ zr7PuQwepYQbrd-AiJ2D%FPQxJ5znDaXktFgr+!>yu}zo`2~KNFib?_JT#CK^0d)OZ}}4&^7%Pv9nZ)R!68_%M^=7GU05 zBP&^S-9gmyw=A`Y89sp>181}H31!~35uB>o8PX)zra(nOVZrvs(r*XP*SZbfe@s>h z@vKX!8#)H2Mr0Tf258TmyVhyXA9srB#MptMC0jeu9dcD0@6N~`vB8GZ&Ko>MlP*Rr z3iG43LsxCoj)YMMuj|^^)n#Rp#RoLA3~;cztlOG{8ZzlFxwK;VS)M zGZHH|YgYK5on38B&0q-n16T;)vXyb2X(M$sl4LpKGSw8Oot*_Doq1@xhSSu>#v_ig z&udgtJ>*;NL$cK^w)FxAFxo6nI}Ca)WPfl7(GR0DBaoX1-03F9QJ;!#i{S( z4KZti=jY`{^#Q>ke9DzeMGOI1%4ilSW-GX*<~$^g^ZQ~-eWf#xTJ~xjs#g9U$@D48 z^nKe~9wH#m$}pLsj@o-|eJ)=D6W4Jx3tm?9Ou#N6!67soy+slUJ}Ntioak?9>FS&m zyQJkgQD+YYG_iQR2`Ip_kCBbZI^2Mx8+Y)F=$!o5iKcCWqb%O=VfjFA?)rhe9}jc& zR$emw&HvFu4xVv?%fh>|TsYd})&&L|?KOp>Shw0*b0N zs`O1CgMJrYyy|oO$!$L1b3eG$QbuNzIIA^j0ebX3g65NOA6{VCK*J z?i=hlQ{pX-vY$P<_zEgW=93~u>~%A@t=(CHthw0GrLPoU7%ko~Dv4?OR^!ba^jD`$ zwnop8d1fmc2Ep8=78SHW=T|Om(}%yMPvIiow?KjG zp72KGn|)J}R#*fyyP_h0#RGqG%W+2@Gqgx=R)X2TEl&E&&<=|&)g26b{2JAGye`8z zyjXI8MOyo1JHeUg)By~rz#;PHBma>Vn%Vk^RejPe?j-4EDOuu{gh}EDxk+v7TGz~@ zj*!ef78LL;9pf3>TB5ds)Qua7gaIKb6d>*e7uJBN{`!hmi#pod`qPq}WpAg>ImT-9 zbu@*`O07F=Whhr#Koz;;zHC!v!@2|Qk-6hWG!Yw;1eJLqWr_-M8}NuO-P;vXvSfun z3QAkvFa^6T#f7!jV*~>HyXPt`hDfzDzOo#z7s#g(EUC-GC@lXOqLu3ryL9Ng9ywc2 zJRKdM%Dk7X%p6+<%Y&lrBrxDevHJe_)8<(F&mID`(HFgExijNRqGFAhobPd5pX75lC1>}l{&-7qB*xDwcKpcB z59&|g#YB5(uBvB(u?4wvasSs7rZvRQ`6&huUt*!R?;W|lC&T1rT#Xf!@LumvpEJx) zUhD8ndOgGPErCp4*)}j9nFa(u$}7Q^7Ci13FnRv_0$&c}N>1rMUUY@i&c^)^xBqJh zMmkOA7kuAmV_7DZ$M(`~%Z*6s^}T+7HcgvLPJA-LtaG8L)!H)icaf!Ike9ZRljSNl z6*VQhrD2N7EJIVpNGs(2)}Vl3k>US>gFrRk?fpDI&5}q}gEBW;)HRMz=zuq)jLSQa zbcGj38>MNwDA=HBFQNlA-t7a*g6e@XhHEu=i2dxWI>AR$Pvb10^`*JNk~^)=cTG+8&)tp1>|C6a9&F%)3Gti`d(oYs9wK-KIu+P}Yaw*Cx` z&<|p@#=UWnuC6ngZtEwrF=P9x+t1KpeE0Bso5%2vRdMk*7$i)BLA+8zt!>NlXqFi4 z-xwQU%DEiLMKr$h>@hl%>Y6cKeS}ebmo!F;C*E{JN<@c(vTN6DL#lfIKn|HZgLA-a zZxvJ(z(iB?i`D{Pao(2p{S6S{BVKq*8@VSp@;fxHz6s9#w18%%i8h8n|6sJrTXyx8PLe-JiMsTyKq#$cIEU z9B@@2Xo}Hi7RQDh7FWU--yhrNQe(3qm(yt|Odp6a3O*`k@uv{^MigOsx~KQ7H8O^e0lnbv zbwH@}H2%V)s2%n*t_i;s3twvO-ov8Wz?<14@AQ8$_Lf0$MGd!R;}G1PK;!NX!5ViB z(zv_31PSi$1PkuajS~p&!QI`O0D(Y=+YTG{@4fa~&kC@9 z2g{G_^sNOSIx4$l~vd}%wEg$N5h!m zv->w!j|NN!U|}e_{pvYsI)ks}=MHVALy6kz1PC%{x(jBxUW#x+ad{>>9~eBltv-3% z00MBJG3IHa=eBbBFjmoz#^ce;3Tnt(Q&p=qSF|D7d#mOhEQ6AU=(GH{GMmFncL##c zGB=BJIx-F=9CzXlPIAwk*T>`!Ge+$<0?7H~df9iq*67_#LpYsjs#C2>- zlzm?yDLT3TEeA5Q%*K(4Nm4^QtIBs{O-%wc79)%|k9H@5%Qiwe#r*>1h;sOQNi5w> z3pKUt7Z10dW#{0J?|Id({$Av~I-lu}*dBZT@p6)%QAQA=p>B$_L3+6E^+8v( zdrK~+NHums(-t0^#U6Ow#un%293gMuuER4S_!bj^hH0IH&0gWxW#{mBQiElZXW^z- zf4H4O+o$sW_b0#hQQ$WNmcT!==ZPA51Hpf$fJ;@lBzte+ZbdP7kI;j1X3d)r^OQK~ zPwBu9yKr5>=Kx+_77WrTlK67#5Wn>L;lF;Zzmvpu`utrRh0}4&@+3aE!?58dN7DHZ z-Jt)z?9O85^gUd;SSDimv$t8!8JKud&gqZK5+Weq_E;9DM?=ix4%QS&^Yosd;M9phnt46eGhUPOp( z@q@|U9B&8vW5>0Ys>^HZlVYzK)#pr?pVU`P6{B%d3v1PN`fS)diLsZ~!s!jZ;jw+R zN{2*LtNou-0j-0PxIkP)+<+8krm(ktP6q{JCeO|9Gp0-)cqZBtArB@(SN=#(H@fl_ zs6T_$0n_|p7^K!>fD@kBBs8nLx#d?XPt?P436}&#og*t<_6rlH%S8h4g`;iPj@Vfe zD26g)ahLW)gv7ZJGj;+FY^)nnb)k0kQrM-QNp9ui!J)fB`Gf16>epsIz8U|qf4^YP zIG3|J%>o=D(>L2MFgv9GSn4KErAAQ34Qw>wqBcr zP-pNi$4V63-w?w6ayrHpm|-A8Vm3|o8f=eH*RIL4$bc;=--+XRE3)m2vPW&JXsZTF zn-rv3th>9LOC$BbHPd#R0Du(T?K{og6Z(x|Gw~;h{!#mC#31jCnhAuLi395*DX=6% zDxLJ!Kv3_P=!FGMQ?OR3|e>t1+H3^7X+4d#ugDk}46NrjwLhW&^J+Teue^*m z-YsVE0&38fK>BDP8ZkBBMX%;PiMGHOYwNsep_yrNId#%Gnf6mJ znP#Jq;$)W@U+;9`PYs#@WltpzZs6|uK>VR!U@da2pN<&zlfQQyIxA))a0C%)(-+O#4Kli%Jy-bcY z6?1~k8yv9g>l^+7+zu1V?>_bUvZit-G1mJ9)bYWf+y?CnPgtv{BRTJVhE+R#arhoC z@tV^_e7@52mRMn`7FQGOTt;-4z{)uH=_X3`tKUbGq|O8+AoY`=@=)r zRXwpz?c-1WO;Q}skR8vVb-T?TihWc6{rK$6Ns?8EF&)0@o>P73&gTOL3OknsTS9ac zYh6)cZqIkbTrrO*j_S6Daodb_YU3#u4Z)gJCffI_D?^T(LfAvhKI@H*s=K3*Tgot} zxq@P+sRO}YKgC%R{a#U`*B+K;@d)cWyB*ex{@b+6K*pU1UpxQ_Rkr5PVJPQuGR1Ju zD4D|G7rsBqj@I>=2806y$Gsnny6X13`GeVm{DqA~eo($^Y2VFYYIwvzUVVqq8J73X zFXO8(xXPh8giKHvBc=yO}AyeHGF^04$0fOU^(wJl8 zK>$&*+w^_N^*|wO}3-MkPZutI0wGOMaH?z7hzq znpBfN!nx>hX-|4JMVg!R+i#6`J%XXt>_}`@&PW35Mkd@x+p3-$-P9P6gZ%Mhld(5j z{{FHBh-Tzh&QqIqH~RGY+VYe{msG?``?QSN8SnV(_+%hmzPPr=t_lZjW zB31c?=@_Hx(uXwrA&hdWL6KFBG)4hKRc}`fDjt}G+8!1f0cCsh^(~T79RV$@}$*DMyk$4VaxZbsmh0Xg9y_ZUHwa6E3mDm zqvR%cyEd6DbEFqYYL=Jbbu6?yMw0sLWC$EbF1rM5;{(b{lX)Iprou8jFgI@*JU!`S zR*j(IR>|viBl_MGLe;h$UV6@ zXk+WUTh8efzS5`PO;`E}YuKfD!PrVGm10$=alUhIR&Qb$QZtk}`#fpAx{u2NRFRzq zv3E?|(>)oMZ*yHWaX3^d3GBf;o`$YFJ&FFA@lkiSqhWCNwJp68U(Fa;R}ByCqZ@5o z1A!?JLtevcv|VNF!nufY#oL`A!dbZ+@$$W4*AzX?i8Jv7r#Rmddr@pSFOA-Z53~(tO|kE4s(-iFlH2F%Vo!%8aZz_u zJi#!FVq1~G>3%(*2v>eQj^-%F zRP~{zxs3iTE%(Lw0hZ|3#pUNF+8?7QnI(x4T+DvH!Ark>ZLrZ2mn(f4&L-5B`Sf33 zO*S^?<(r|TH`hr<>A(8L4s?STOd~;PZxB?MwZwYk0Dk(!d>c$PaP`uYZu#6u zRJTH{+?R-;+>^}_uarrwj?yZt6p@K19Q9B@-iYE{MyX$+x4qbf;JFv`qJj`S8KGu& z+Uuf*l$y7FcShImjV&Gx{p8R3=P77TK;pSd_>>KUHT%`;HFNX_HMtCB;P?FFDil5x+;2KA_iZ98EzsXMafLtNKj2SUQOH=aQiiXuk}p)7|XM}(^^+=TIuT{FdM36fIMCzyFZu=r`d;6msJ3>Z zC7E8j*i=tu7QiXeF-y%ii#R<6AkT+-%9B@0ssBW`5tV4r3AtZIp>*2jSYnv3fu(YX zjuOd__tAW|Q!J}?`#aFShg4iZA>{+!mr$82SU!9S=i#uaXDRHDahR_4nK^J_mml|& zRggIUD6{>e-L%4Jyu6xKbHbZi4vnR-#(DZH)CkJidBk&6s9q2v#o6KH5a0se7;o$9 zq~Md{cujq~0%)|`I_ej+xKN;Jov>_38VUJSy+YGxddw%$&uujP#Z8NphC8LsuJdaf zK1=1cjSQ-o5>^3~1)NY-C=fXbvXbe_$m4#v=9lJU&RDRj)kfvX)d0jZIc*zASuA{B zyt%*9eyuIE6V7MI0H2B6c^4^jd3G~Aw=k14WIqz)^65|AXa??sT>$$cf{g&dMk)%F zuENXkw{sv< zk{G>Wd5Xq&0x~=v!~gx|d3e>6@ASkq(-^wJbv`QRJjJKZVs`M0od%hJzFMBq{@TC9 z`zanQSqEIo0|idK>k^kcg6~&73MZJQ~@YHAaGz`+3ouQU} zw~mbuLh_EKi?zJN{ggPr4P5fXE&f#RRti7gPjuS>SN)6~dD|f%FM^_5ezF(VRCaUu ze4e1&zM9*h*b$N?-)!DO`TvjZ{(RvG(99TQrj4KPz3knZ;6%TfR_sStm zXugG?<}Z-+-lMT9dgD60y!>h7?2Qj~44RX2hd+bY1j`njGhuf)e0Ls(@7Ps+w0*P% zFJzZ;NYrQxI(Ta)JAo7& znEcm)6JKw>?Bokq?;4@awRE3a4<6aqduy-ZUFKvj9!KnNXhtT1eYJ_(D#}n2i&|rZ zXdS|{NS!JR{L`Ig7kiRES|HUR6UG6RuPm$#Ld4=vs@L+Gs(t0#xUNhsrpU}aJi zmvsfIt1Gn}Ru%*c*W!Hjpf|lq5&#eOKRS0(a+G!A(Rkw;KD}4w2z4_3d7=0AzU<^a zcp3iQMIQ3}0N1Y(Ad_&c>L#9R*+0#saV!ZL5QLn@-~P_#qCyuzv(b$yoExI>N`Ygn zh>bA_8pcCmIkW7km94{MU+Hl0Dw@eGnBOWV~wbGSF{>)hAyXkG($E}cyUA5B5bJ(aI1eXZW z&?+;Hgd+$c-y2;vsOKGtfxiF1SNap1TI&bdH6yJh}LqD{b3g ze2d>RmgK?pT#t6N1);N8OQqV~qdNDw>aVLNj6Xz1{{a?^Zl-tc3zOkg>s^e{S`+UC zK2<9@s~v`pR$mnNp-oXFekWViC7s;gsCqrOs!<}nNr{|alDWHBgFh~=f1;54ifkbg z^1ZE%d$8#(ZNVU#uJ7^8ZH`bxRG?(mWw2Gal;8JLF;QT~+5(5$;TryEC8^+WBG|<> zbyZtmOTDY!ECf@I)a^M{?%+Em_LU?ZAn`=!+X5XRsx^g zcIR@bFQC_i5(AlE7a{@KG?r!rAFRKlOW0m$yNj|q3N|17c18&XZw{t$kDAw;{FZ$9 zTXC1hKNg^fv6b%*v?rHTwWI8TP52qvG}N~_O**>m7~12Qw?NtaKkp@Rvwv%9vMmC` zbomK65{dAU3oBWj<6b$06n@5tPx?i=dMj<={Q0?2H6FQ!L*?1MpHuK& zMqJg_o%etg**6lM_MSGf+32gLX3s_Yjl@=M<2z%&n~n#zLkDqYM6+(x>m=x*Jr}zs zzY*z7LsAxI+>4R_bK6l2^sQXeBZFwM&m}Qpyq{su7x9}byDh0P)7;jcg#6aL@ZE8B zoS$A`E^_+m^##TTRRm85di_*{%Y&B>gd>N0OD*WGgT>$w3ge^k@~5st5yMY@%dyzh zx~kTpp3;YEwn$vV+P?f242H8q>4)rII%eUetWuuB#y z9~^-r$38Fb$!k-C$W{?W#ZCVKHmswE_T^#dw0EdG?7AT$ki?`P#MM`fr^1k?ksr+g zP9IoL$X&ccdAp0dq3u+onG913JCIazQb`_F4Y4(&z;sp=kPf~!utDcj#w~}Rl1sgy zHP5~PL@*1o!i_)TRJsFtp*}OT#SO473C_t4Up%A$W4tMLGa5a&yoooYCOfOvABPoe zl@#JIjcvPNXO`|)HM0h&8Z5-8b;C>sRK#{6rKMXGvN{KaMIM=CaT8Uw=$O^qJ0f&S z09q}CQ=Y6+ChQ#}ebrc((~XEp1SVCy(i zr9%KxJi|TG*S7QCADMN1vsDcyRY~J;;p48aI`=++u1lcz)y3ZkB|_lxAz1ux|t2<^=fGQtwe;(Il8Oi<-eIpm=#5$ z+sc2-&PrG0rOa)Y_WsoYF+13t+VCp752dd*`YR9x!O$cjp6I0sw3RXkO^gr3%)NA? zA4{Y@`PpAyxpYxqn{ytT+$3+ zMEM(!MvPdGQ}tyWtS>57Rk8lIF_Q?iSQg=dPZa?vU!r^((z}Hz ze7h7du68}Xzru!0bQA5!=lm2t&u4m>iDW={XU`muwr%5Jo&Ftes%bq3ElpA}ZH3~K z!bz$I>cd>yymw65VLKowzwa9ijxJzXl;bgVtxaQL7y2-FJxdjYlHa>gVI-89XgYn-}eKR5qe+(UF%whJEq_w92qc>dO+~e1bis>w+poq7G3wKzl`ZJ*g zMhkNqTZ3yDp7Cd<)CN-)^Ypw!^-OB_kxN|QHp!`pUH)lH>m9NIXK$m4&3#UfQ$@zf zqRhq?+j*r$9-CaTh6S&jM#?m2hEFHi+g6kRp6B-!4|6yFn5iTLbj?mppJ9be(_IY6 zsdpF5w>ODXFT3c^;`$#J{sX8BJsttonP%1>TIXp*{rxxm=wn-QmGX4m_%H~|;Sdczt6Z~ERHLDYkJ7-64aDZ73sEC?-uX+ z0lk~1jD&VQC4K5gXO$`0C9ZDb7+56kd2!8doK9i$$#pBY`MD4W2R7}&sWV`_zDkc4 z-&Z*CoHUY)Y84k%@8?{C8Lw(J=A>un}Swf=~Ah|=WJ&&oGPM;5w= z;7#cdF!w-bFuR7iA<*l0AqHYLIJno7d><43_*d%7ev!%h=$0FyOnfd9rwcAcb*;3d z?1U_<_Poh0uQ0|<+zK0GwtB^DFhh?bFAk+U6*I}O=QSUdHClfA0R+331_3SNKXFsQ z`El~W!ZhVzh`V#aKDrszw`ooG(mcoPzVX;N`UX51WDnXMbN7#SDfbei?c}whzg=@H zDsGY*?aw%n7@eFDnphz1l_kQK{P>iXwi4bfiVeF*C|t2S_wK%!%(yu+%vf4##!WzI z-CS?zMwRTCd2VY#LTzha9KpCc>JM3^fp{9Tu`58bnxm)d^%b7wI~Qktk})xuGO`<~&AUha&sxBdX)Q2C zu}ioih7w2Uy{;{X6WL4;*}fPgRkO!hn)+V))o`MREeYq592I80qtF#Jr<}PuEfh-i zOVHPNf+uKJ7AfX7uh-2dTS;|JUx{%m=)7jy7Tbr*`6$@ ztrgoD)E+XeXnFK`^bKA{KnGodGn2Jgp<17%KL1n)8`7r3;fjJ7{-LN4Szu7wxB@OfDUE zK+%P{SvMx&BJ8-Qf%0A0>cUeoVa!Zb3wMk#ywlZ&D1WPkw8}gc8c+6BV?Wm3dVPWR zWGE?+Xn{WSjpQ3?dfV(*dg%K?-WrcLDhX3y*(w<-raJ6p&GcPA$^GDAs)y}%Lu~Iv zlNthUitYBqZ?g8;5epIC)$b90opvU7Z52lxOi)T~G6M@p=BJpvYVsc)KM$uJ^N_{T zwc3?_tfq_d;8oM!Mi!UttVO02F^t~lhzP*AB;Y$45r*Y6lgcX>xwHMc4NuY2raR_f zZ?BhjEbg#6vD|#S4<>)@y zhv0DA;gi;`mTb7YUN>0B*;C{8B!17ezd^a`vcG0hDe=fr!#=7yAI@l*wIfq#=+n@pHzSpfT5 zu{wfoh5=i9Nvb;E@>i6Cv90t8WRnq%3JP zPMPpf=OG0!#(pwZD=&0z4~hUXV=Q6VlRcU)c}`5p`V?rjMano44S6%_$ZGW28VHtB z?*Iqut@_geeJO|t-O`ElLr3D%rZAM;Lbt{yJzZ;LqF+dL$XG6;Y@@fy&h33%a}0V* z?wN!Rsv{izGN=Gy@{x9^7J4ggyrfgl%8pdZ-ZGrFJtc4&ZIoN+TLJN@vy!Q9w#z=7 zbZzHC#=X=NJ*T{4-4cWI0%RirO)rFB%N`jPX67dAa37EfEF%N!T?&<0mT^uAiNetG zs(|1?>Dkh(HJ-wGnKOgfXGEB!8@xNO>QKpC`|iW>&C^R=PaV|X6Q0yq>P>pboe|eT zTD?_+vt%98%P~{fE#!(5_ldR3C^iP)5n(~-6^Gf zm0N?0SLppBPiW?y5Pa(o=ZPJ+Qel=HnzfX!kj(<=>={k&yw?a+V0#ga2V^27N?kNo?Qz3Awdy zVBZifUUOgr>S8obzOb};|`sHmlQM>_Dob1ysL&Z(E#66 zFbYb{t*}#=uQ|UZYkhnlkiX1T$|V#E`!r`{W+hb$v$Xp4RG{5jc&&wul@BI7lSaml z3TupV8{GT~w-U0H*jAL5$LP4%rYS6i^~OY&UOF&9zmsm|RErLeoZ(+`(+ZvG!HC7` zyL9i@xb*d>Kg)%=W_#^la+Ly7wJ<&+_FEmooZ5|7h2;QP)BwYPSd>N?d6tA)TE02% zNwTNuk)B+~U|tgv5O(!PLDHl=(DwT|@$up%dbTa>6ApjAd+H|3Vd(Gc4A{*>M|w)P ztB2o7y}oIyUa~fD6U1LGkB>wU6gC%e4jf;9=i=Jc`h1&ca*)Lrup+kHBQ}K72Jq;^axw0oc z)`dz!K3)0Oa#fQolX_Uvc)-MB_tk;|*-_Wx=L*9O6e@R`o8+4JVrugq<7hgZz;)Ff zVG8JVRJlDc2O4_blwaXOe3r-TZMTEs7QUBe|V;L_?~s+-!XJ9_a9l5!=8h4 z6-3+VHvQiiR98%`is0*Cun0Pz9 zX>ZPDy5F2hL-Bw0n=Gw}<#?Wu&fo9jJ zQl^Bu%^jcFiEaUdRCk&947)Bd<;}%Bl{#a^iab_qNooo{4j7fX^%^cYAABxsg!ewtIm!56t{CDrW(-bLTqS|@pW-BFA+ zbAS~d7?qCdEvqsgu?Z<%C+sMDha1vf_!Nv?HC}ecy%C5nsL17n+%jC#k7fAM&_8?r zl^QhM{L$LxT0D|VW3qNC(bISZTgafMaWb|QVTZ0{y9y%Fa_)}Mi0KRQsV!>h7!d+n z&{!uJ@ezR67h{JYm*1lnbfW|l?)I0cKRfw^Y@^*P)Rlp%m)|>@l((j~KhS+CM%BAu9`&rM#3S1}Juem8d(vpU%e%I!P)iz{euRv2Z& z^SJWu`LNWi8R0x1N2MNAIVrL4gm%)?#4knp1NzJw5kH!1g)P2|UP>y6S?w4cR_1Nn zUT5!Dl;U~F8EtpsQY+FOfKhKA)1)}wUf&&Qm*qoml3=%#l={JYNUqHdw58B1x(?J@ zuXRB|OxGB@#9mf|8kD3S_LC%)cuok@yq|2sEpwT<5d9tNZ%wYo?Xf*$B5Kv{>^uD1 zh^vx^X|M*EX;X;t2F)csL4J|%^Mixk`fD3Ao2NunFFm)*SXHST6Xv5JjxGdfuGTKv<2~{nFUpB*F?Gzfu?gS3Ao@)K%P0miB&)FsD$!SLtkp@DWczE z_mPit&FA+iVVvL=pUfOhJ#T7GLUyu8ztp@QWrJo4u5y*MQJ!dgFVT?oOvydWW0%&E zgv~Bk#a9{Q>)=?qm&?sg*LsCj2RotJd^=-<3;M<_mHAE+7O(bHn@9%+TRo8nYPme6 z?%%jRM>~8wx}-V8huZdAnWR+soQ2s%uqb~0M`!T2IHfXvs=56Rcalszf&`g40p;I8 zeJ$9 zK?|G05((1{b}?=^1R}yB{-P>*_=y&8=;AbW?GT=@7 zrR56eElO~wP(42gDRRQvXnG01Htxq+60Ay5-oYhVIF*~cJ{4$J4_!)Q_WKGNV333s z{=oBkZkFM3v0~H8%*-yz$|?Djo$;xQ3&T-0a{p7lkN*vRsSD?2CtA(`hINQ~qdrbUwi?N7`GxH~;N*0-qC#2sR=N0V!Ja)N{P_QI=Q`NCeMy)8JqMmJ{NH>@E%gg^ytG53>0o}AlkP8B4 z@*RE2o!@-}+_XyfibMDP-60RO(MbPTN|_cc@jFW%YtRNH9U9+f#tBbkG2#myA+A=aS2QKiqs?aZ0R2WL~|P#x+mq5=lm~~o7=LYWf^|L};X`(GaTEcqk z2Jiw;0V|z6!eK=4+D$0BPguvmOt9ko{7t&+lcdb5=gm`1{56`zllA619yoM$a_f5h zaIY<{W6K@v){bkR+7t)DJ6RvU!oP;chxJICacB(X;)v_5WlqM|Y&(UMt1FqVd#A?3 zhO&M;@i*dGdP{e!7>gP6$-W7#S2)vW)FP}pDfG=0Rm+Q*s8dATmw;=%CeDXgGA@FU zhD7~RhJ|tyj=$Q!qM1XuFe5>u?D2&$mR>$h#cV)0JPnQYjVuYk{0A*ZU${-5h<}IT#N9zz}RsO6Ehog7VA;1CgI3oanMxY5GnsqMPUyTH- zhf__O%8Q@w>QBwC`c;HQ%T=M7_LL^{lZAVy%MweoVo4VLu2?bVifYrefj}OsCXzye`mVJGz}8e>gLdtmw&Oz%zeAE8c#C`0DqX?SR}q^B_* zW8!E`F@*}r#4oW(ie}t)Mqe$!x%{i;5s{5y_t$-ur{50P3<|>| z;Qm2sPFv)2xd#L5+e2Zkx8JU^uPSoWng!3@2PL^6I^t+Na~5CYp*WVTE?a4%w1pi? zx?~`v7GzL}@7F*1UvN)a7d9cErbeI|^Jo;AOO2mK*%{v)`nIp~n#F|*e0^AaGnkKH z+5SKP>}2tYO#RUCD26ZPF25Knv{SU>yR#GH=ARyz+$k1pm9$m-8>07p7Lw<-9{^|Y&9Y>6ljj!E zex_xNwn_hO#bodX+G`H%Gtw<_T?#9>rvIP1sHpwRiTN{@@=g_Hx|iM{-R_=|37&1iTs6xr2(x@a=7 z<_PC;;C#{hFxje4fk@j1L~4nwjYIbfj~KSZbwP!^_Fa7E_Rx=`SMR@-e{IgpJuY8jl$CR@F(yRIpkoz``{peNV+~mG+ANxC3zh_kebacI-HeGMI zgKK12T{dD#n|~|AR+~R9C`le2oIR^EArls-RXG(uvyU-{tII3 z(IQVQ5`MlSh_4Kq%*qla6a|dXZLRwkG|tIB5zVfsRnh+S8AZ5zzpCEfJ-dNw>%k!M z4cDL?5Mq%Q!Y;cX9>|P-4*Lhl2%0AtP-=?RV;{K_SUEVWKdj3qVy=96z|h07dSDhu zF1Ooi&lgle#ia{Jg{}^5n?TjNjFsLg3+INWqAl;Yy6htio_s0uzoTmXvrnRv(%!~8 z@{xCGDf=5n(I`tXt-*Z=e_`0nf&{hV=1opQ(urs|d2xN-7(8)ef}?nV2E&KFdV2n=;x` z#;*P8L9ul`6|Lz10Gqz{-<1CWaw04!rQbeUOKI3Q0>7uq^~eU9Um=*u`c!1z0fEi% zQ4ql)`lu9FdmT-{R+faamxX0Xvp{`6FtZqvJMG%Nv?*w}L%P>uK5T*VEAqiF@ViPX z?xuZPh<&4t3D^*tFuJyYLsU{=tRzK;ATuWF5Lrr8TADd54&EXA1b7gH! zLP0fld5Qs_BBX7+$GX!?unFOMd9_zA!mTRGIl?`dVM%w{(#2=SIS~W6Pf6{Kd3Q@7 z;zJ-x&{T3uaTI&GH$5=EDz|dqXRV}G(_3#$?0av+j-Fjg1~R{5nVB+eO|mGenI$rR zGg-BMs#c0ZT`#Sea^wL`PFvOI%?pW9(P9iBS`6339kM-gFI@i@opH6#_J(dGx+Fcuv5AQrY+TSnz9)lJa9TVr2h&~aQ z*Nb6?pWZrCNGw3Xmuj^kpsf~;qRud-wf+Y1R{fQ%&WYVmQQpXi{-i#as5yA|9(>ln z6e~LCc?douI3t|N&?GQOo5iv*97$IISQ`R5apZT9V&iSwE4+vVf-CQdO7jVqs;G~F z=HhhHP&LsP>BYPr@~weny0*}V8M`~A!ziwclB@(K&A%p_&H-f$*VVP zR;~U~>?0{iTCPS~M)sOkvXoXZN^0&C;v+L@#Qy!aP}^{l3IZ3g*O~LCSaJR<6}=`( z+JX;~GA=VS;K~9x9weoU#jT7bYfRV>=jh8iRn~>X1W%{H>(8lP4rPf^!Up&GSX_c{ zhG{g0_9U?2fbahRh9qv!cwT&UXTqXvA2d4&e~Lv-lwfr)UAaY&y>ix86qvMhM|kSn zzO~C6W68=G*OCEEu%-otL++y{-BMv*eP|H;A zf`Bj?(SRu1bpl~ACy#@)x~_-#dxJ9~sKf;=Dni7 zSg%6Am#3GcB}MCv>EQOPZb!;_6ZsLu`x6$P6}u63?2b{*UF+idyV|nl#^iIT3(6sQ z+V}!IW6F{T;!(PbxxA^K=cdX>d6Lf1hwo@v?@oCNeeZuByFEYAygwCHT21@f#Pjtv z$qR-3Ks#~^ooehTL;dN5}xrHpH)V zBMXN3)Xj-BrrFRf(rw_4EwjZ>rF+I_#}<9870Vqry8WN#qW^Rkh4hBoiV`{mnmerP zwz{o9avb{x(LG{B@X;OZbD5B!4d-J0ziKA_FY+@<@6E;v$T(t# zI)(zci^)PAQ_fO)p@rSK3s>8h!hK`S`$5_=KkZ&`Z~w9ZQ{Go@BYo(E3)P~gX~EbV zH@_p+K-vk%5(>Ef?ZgH4)TU9;8J>Q`BUjW zi$0U*s2`Uzm3=m@n^NJ@klb{F1P#3k&SliH=;F(gsnF62$bZx%h7m3W3FHSCv=ox7 zCaUV*%cH5!_!D@G@R=#EDJ<@G6|*k(q>bN#IY2-r65edLvbf2YQA@XrYsuYP|Hnb! z;QrlP>`W&%R*(v?en;Hm3YX=gJ$}rn7r(?9wn&q7;=M~P06JXIR5yoT{TZ>{Q)i1Yt3K5r0om_e+dJ*Y1p~m-x9UG0n!dU8%pxc_5;JrIYBAKO zTPU+C^$6j2rcJB}7O7iIJm77-afWD^EKO?${zSCq@VHRc*K5OrdfBXUTY5dq+mXLJ z?6N`V-+ab1l~?k?Du<)q-kQlfQd3_NGT2L6IP#+&qZusKqX}Nxqa3Q9KziNE+_y0| zHb|LF{EBCiu-1? zH_0-O(HD%WfI&~FyQIpYpfrhajccvCu7u;j$zXQ0G{j0b!dsy7CR|-&g;(KkM`F9pqCa^9IAkh+Rl$ zWzXJrUeC>o)%hMDR(`NUBjg`IKpgfy;!a`lly%{>p3*XjXYeeRT zSm|ydY6NdakQG}z(7o7s8!eoYZDwJmzg+m2G~|d7{GuVfXv_oUg$T&bfJ)& zR1W=&Lc5Pm!h6_HvMw}_{w9T0!+p3(NKdOxR0hAY|8G@FK9Gx)KhNtejUB-W zHoHYKXo5YnQ~~JDV{*fE!WlO%1P*eRmZ^aOwHnJc9^-d0FejKiPGp1*raK9r-aqLb z6{l=uq71eav1Q^#5q+(y_dX3t_NJy*E!_$KN@4Q3Y%|pde1;=!ZfC=hs91Pj=Tuk6 z82wF8h=*)7O)kIg^pAw=ibbP;jpE%Kd$sLfIGZ2aXsJ$|@0JB~U4aJB*cKr%Uqo*RDl2=JLo69W;KD-$VVW8)8t7&|-H}a=y zdN-a&u+`Ubbk-!_Sji2<0_ z*1CqVVREIc_0z4DOTV4dO3X%bF{a^#Jx!iy=lu20;QH=e4U zUWA*7I6U9{55mqmD31Q?@`F1BcXxM}AcMQRySqz}1RLDl-JQYRCAdRyf=vP>NFY2r z&u?q1-raq-_Mfhqo|*2hn(DfJzvrIw(N(fpv`+O=K$DO5-m{M7Kxx!bxweR!ymb_(l8Q}1AelGgFOiR zJJ|FM{S!bWLroTY)l9{8r|P9 zLBG@BIxeygrk&l#HnC%&g>?~KFf;4%w?)-^Qd_S6ml^2fagi5k;SsmJ((~mnNx}sx#d_vg`)>`566k&5U;ZZlC806({@biDn;XpP1s7;7s;x zN}|`wQ<3I|xz$PrUCTvi5s*kkcsPpWDVC$~U*)!Y_ffE2dg zZAK2f#xS_mSQHMpEUAUF~8wZqH@jAIxCGg$pyH6?i$Hv%xoD`jUBWH^EbM9 zLZgee0Pvf1MF32?riXE;F-E%$3t`NOyTG2uq)^`=$uG%wkCk-Y6wH)s^Z2#YN5pfIx&n@DlpT(_Rz_>0cCK0dqvs;V*wL#OTAyXDIdM!hO$4^K z$*EpyT{;@cO$QFDFK6Awl!aW@d%kgA6KB-}W>N-*%aupe@#h7`B%e%!Yrn(@C3brc zvEho#3xh4UdGkza$~vOt;s&>-oLCvO3%YzswMQHsshVmknqAoy0%I?udeQx|$!W?p zVD?}<2%mRB4PQCm5hb?T^_-`8N_RY2gu_*VG_kb$zD|(8l5#mojh|q4J@27BC~a#zyexS zS+JBN;$b8QvN%-|wTA$G^f8eDtpqkmhFySJnfEARG6w39%xR6`uOha zyFtyf;-4rrmT@m+z_CF;IB$P1<8g!+fn~O_>^p(RQZ?D$F-=^LngqixC2p42g66l& z1WRtEl4>5%9vRMwW_y`QwBS%;$@K!-cV^NiU2ypVFh_1*zF@=9WAx0!&BCma2L9Lv z8f4vlJ=V{;?H{2p+Y@H~2s&b$2C-bt5cX@wcx;+puuJScp^NvSp7uvek0e>{Rr}P! z?>~mH3TVKz+oE1&w2WzzmeyF?RC_C%Y@&4z|D+yh$75*=@R%ePK`BI&TQED8;oD zI(P&g*~bM=ni48l*VA$`gvd%roA<6+m|_ctCE7ih@PcAIP$!xCa30OosY7+Zl``%Z zra~5Q^IQM>#~eA8=H)%$c_KuoF&GKHF& ztV-jLl>r?i&IPhJm`xOm=*xQ7Xa`> zu#IPF@}YjI=YF~)t-<>4Gy6-{@1sn4nu~(Q*R4Fe@3FDd`m1b)L56y#`Qt>QeN>GG zC;|C78_zu=jx*CzLaA=$(Y3Knde^X(%&|x~clLGyNFZIUL&L}{6uMDnV@>!KK0@S* z%;iDxvnHd>XfXd&&)Uk06wS-KOk-7bo>O3mTHe8NwR z3Pt|_e)Ktic0anq@APl@@f<%PxC}V$qq&^_6F8-}KSnI-bE1s%`YDVrHf&Lr)lzxV z58ZVuPB*uqheUPI5xpNgJJPKud<9?XPEr+GJO?ij|D1f-;Z%A$Y*`nq8 zTb+p`_?J=1Uhj%2J&p7>B$Yx31b3n2!mfMB@=QK^;4f)TrK|scbW@EzKdJLvp8J&YYSP!OkGj7X#x&4Pm#6&_K z3O^wfv8nTVF1h*{kRDus*XG$)C%Szro=8lz1SU%U0Z<7?e(8J=UhXtdmop;}>u@P( z&jSCwnGXln-Q8pCl^pd>eOHlWN*2>S!sC;{NL~N+8(Uv`+ZOLwent+xDREhCiaUI9 zLokSFO1QGgVFN{Ab~|2?)}Ds3bGdg+H@qtgcU<`V?{epkQ0JIBS^?v8xvka(hM9?f z{IoGPH0?_?#>FKQ$=1~ITbFHhmTSJ_KY*An*VZtqN&bOLT&G!O?BWnDDIT_7CqfHu zbeP|y7B8XO+V&bp;q!ms;`CHiUdr}V+3C{wv=`_QzH;^2@tWO$Q&v{Jkd3S?Qiij zJKb3&n28jx!wxNUgQ1Ze?NyOp_*!`QQqn9rxx9E|4`Z%d1gzn=>ZHkd(Fzl4)cimW zC}}m?K6{GJt+QYSBMyFhxMO=bqKl`|mv0NGlDO$@Ff1=h(Ap^2O@mCc_b2d!s^dT? zDf068_)UWf9-oz6Fe5KN(GkOX1%-TF2cJy!6jHilkp3ZAoSj>Q?1 z9Iu6rq*zd5_pExdJGBp{q{u1OTO%o0DalXf`c3TS0yC&?d%BuiUnt?5M+E{upY=-$ zi0Ppdhy;>`p=S&m8L4v|Ev`Vyu(Xzl3W2&r6~9wSNB_i#QMA_Q{M?QC%vr);7`*)= zw;4GtbbtQ2pKY#-J7W)F1c7e(6=|NbTXmFng{t;TUq$#Eh^hqJMwj_t)D9ITCASJK z-Y_>xONbqcaAA0Zh~u9FYdL_cXDT|Bg6JHOsteyP^agW1`GvmjcIfV41H0h zGk|{0^2~=qUH0=C1{^5x>BqS1K$4A)d?j?TF&Q~nU&HS4MX9~-6Y{N{DyB>G@K*A6 zZcnzlwReLeL>O+Dxf3kNyZ85#axmEwZoQEkN}}a8HFW$YfO%@M<<^uFkW;h*86x4H zMF2wFg~*PbC04}Z)Ab0zlMu{Ka4jhKk%ufu=;UDpi*XCQY0Qyl?oTIMm!&wiX$o?h z`TEfnALsrDN`6p~$Tuy;`&e#QYJo-m5yMPfWVEInIw^ciY0{Qg<`yzz@@;RMQOmT_ zHK7dc*$uv)V{#n1OE}p*qbc#;X(VN}a=S=5gbY@yvI)f+>c$WY*gzBUq>nd|@`{~b zW&r2rOSNxE=616cR1#arl$NM3*`Kgt8#fpdM-P9BA2;Amy)qbL@IA!+oM|GOxYwP? zrQz(_D3@<6RGQk}NbK|EO9$H-QPqKDr-agS-Ii-NV9_$?EmY7^YUr=u$KKHJ!#u}% z1S7duzb`G2`7v+|%#=btWN$P=1fvG15xjar~LmyfvsXvp!%x)h;BRf?Gs6V#TB-K&#b?f zMYCp5vS`p!)igP|vRQAYhFhI#eu~Yg!lzlRwXA6`&`QxT)1{`#_jeaM?;txT!=7gy zJPsA6)HBy!*+tvKu-;a9_P`6q{(#-3XjJ{)L(KP!#m~j`t&k@8AHd)NSnr(@+t@g0 zaY&;<4g78s%yP4a2;a({AI%eVGD$S~fcDa$e7=HWjMYq9#eO@4#?U9Lr`W%n^Xywt zvo(3CDLF%Q#;K(G9{osd5zs`M-s)mBNH`{IZi?ib-O(|-WfhQmi#XmQeCyy(b9jid z;#%$9X@W15ZU`3z^2I#>CzeqBr-l-U#WI{0px(=7dw#EM;zpUM)(QM=Tc8SXzax zS^?SnUcNs=QNrGsPM0zXsBbWCYn;eDn;a)=E_@J9GC467dgiYD%J$6vW9KK+Bz(qebwgvKz? z*_^oR6S;|Iw(StU%gMZ7#T#$M!DxTa&906$MDMPRDK3ASKR(lk9kWeNM9vf+P{l)Y_y z(?ljEAn4d00q1&F_s1xKgJJwSYl27&3wCQ~_1J@U<%%kAG?Wq7t=&`HQ$=QXi5rDP z+RV#K_p=I6Cs^`wUm_(n?5s~N(U?kx>_T`JpwZ~AuB>ay>+szw%c%!5i#x%)=!pWR z(OHTveHeiH`9!@!@j`G1_+SrpNw-sT0i&AOZyIr#p^ptjq+*{@X1zAs9Fms%;|r)4O)v?)r=DU#BI3U>1{LTgso zM}`MRQ^#OkQKnpS+25;U2xC+Zw4YsiR_8ysp%`}~x{;G%7A17_>i0lAC;}I|sy$%; zG+;cZk6x6xtf{HBcno6A=Atp0ViROmV_EFa^rWT-?c)juQ@c;gPXZ@8FA>%%#v4Et z`CU-5C|g|}9$--6v;m25e!DITdH67`Y)}cT;B2Itw@qSlL2B6GEahF`LV_^UR!q`V zSyd8z;o)!?@N+N?eI)S}G>IOeh zE3fUZuj~2@j9R<*K1XHyrej6{UIWkdJ>Gs!*_kTbXjsB1jDP>_)$kdOO!R&GoG)1Y z#Xin8L5NvH?G<`jPq7gVu7Y+_b>U`>()C{XwNwqJ6a}aidQ{|9GgSpq$Uqgja|2$3 zO0&5f$sIfc=y)C!wuzAaZ@~)(?|s5k18(pEoV@DXwe?wsbqZb8;C!@$1&4N$-8(3Q zNbtCQari~I%V#vFn3p#^tCQqRCD7s9^e*ogoH@xfsG*GaAbS$eIP#i{FqBeB>jMa{ zq*Muk3t;o!8xYv6|KDZ_{kKZ4^Wc7=jw~3{G?feDlaoa6?KiifRZ z%W%)@$~4zoUOn80YvMhrxPRO!W2*E#yLxzhLZwO4jh6_sgbKcrTv$o5-T&7qWdGUx zKULzcxNwOxY#ID;QGu6FPO&A#pWHun|8&8V1?X_SKvxr7u(5B;*rA%Q*3m|H&tpsw zO+uR;w{VE{_Qj87Lc%?#jVdngL~kAtK7>6>T-ayr8lVx2au^T3Thw&ZXFE`$#IP?iN*2?B(Z@|#Gu(J7Y7;Q=_o;fDKFn*epsxTt8Pag?~{isn*dQJ-;Lu3HWUZU;>BTtv*Rh|HkGO395sj z=UJ|4#q}tWLrpeq|4uoukNP6ecH?LB@~db!4bL?=Y_j0GCE9zId0O1sd@h~#)fS$n z$JE4#vSN}|g`bzjc3JM7$*H3`s+U_Z>DGzrbr$g2rz;RJr3DbhGguWw1EA1TKm^{j zNQib_otM`o$02-EAuT5ZsC$B9ML|??nQS`cfTzh95aJ6ST&bQonK_lI@R_ zjael!Z79v~ZCZ1R9!gZ>b*FY0_R7y7%tEa6TI=s?*dCSRcpEVne7xJTEcR>cHfpRr z1Xp3Hf7Vft5pPwyO68R$)4A&xZe1Pt3?4n+=kauOom0K-;b~goNUhkLo;xh5e0ijSAdYDajHVow z#x>Mm%RSosdav=BiJ>?7dYZ;+Y5SIo@9<4?=JRUopFI)iC0OQIe( zUWzydgjQCMe$%Rf&Y{FN{9>(oW;eU~ignq0-rK}VgT^S_pFh;wDB#IMh%O&R^nTU9 zlP6wr?eEEge=-*+aGh(D@qM?>JEP1ig9)^4=-{{FUm5JL$uO;-=k*Yx7FUAr8Yyoa zg?=zEARlTIWJ^`j`XeuUi`xNHG-FY8bDsh44~Ha78OzX6fTT4@;`Lb9j(b7a%Y=_M zg4@ijHG_S?s*yUw4Lv>4i~h%9<4ztnJ87H6fzh1POl`T+_Q|{(UG}|xiX)G4({aev4Pf! zA>`EYeY(P3FdT2D+uB>zagVa+Y^3BRlgvM-fA(`YNzYJ+GzC}G`n(RG50vmBAv(4S zItsP|TngffF7HFhRoQ-hE%+*GgV2lt;LmflTJ;`%((y*BB2Kh)c4l?FMzh%q`u>p3 z;nUkF*2v~)ebU#o+@ki!XA@qr6gxAG*SL%cwILv*?n7Wy!P|iKS}q*>OxisrQaVFs z`@&~Sybia_k`4vOBNyAFinOI$K|q?k(TJzh%hEW4yY#eGcb;!vX_@XSA#I;tXHqg3$Ugd5tnntxe6%9^Mu=DF& zfbS?U8G$f;e}L;|UHH(LkgXs|jn4RiJY1oPwdS3}&+pUR!?xyN@sB=JW^iAS5Vg5^ zR{19T0s@J_1DibtE#}_1_beh4AT}m>no^>VN)+jCzuT3g*#S?u7-NjNt}G%FrRK^m z*q=)th5l}Oqfn0L$bt%ZbC1rBEq(Z{1X#w zk@{5=MyywFyaPSonY>QN&k&-wtn;g`v+`1@-`O?EzBnFU#c&PG1LErX-mO>hT(q$S`d`G-@}D(#3>`C58zn%Kw9@gfqU(^U#6xkOHQE=hzz2M0GjYDo;^$FpOD!A1uV>T10v zjy@4K4$}IsXy#uo%VRH4(A4DvG{s)xcm^(lce%Q4yPeGiCV{r@II8)=QG6guF#IsOBi{1MF+8@W zEams=rmnl@e}+Kgm*0HfznIkyt;qbL^~A6UR(%8N{R60drJ>&|j_7{=b#H$=^gzJS zVzP9Tr5?3jh1SD0$m^WbR#+KS9=J`kf8ECI>b+>#`UCP=Q#8Hbf}Sr(6DdGC(~8Nv z8#diLr$lTao6?vLp|?$&a#lR!125O;*_bGy;I z`S#=$OAkxTiI7+ue*UJkqC8}p;tpzlozXg>+#$L??I>l{TA_x8_UJYK!YVK`%qM4u zF$AknULI3ITf>aRO$TF#h0{yOxujGcP8%`iNs8OeDK%zk?gw-LJTuDYi$GEeb_y)w zej#5zo#Q=F&hBhblZ|)8Pk*rAH%kF>P4l*X8Rwh=X*OpE;%uCGEJsJIq`az1>g>naw z79wbqXA87SZHJ|-yhtwfN%mF`?}!u~=Umvd6L%wx^;5Eo`&mnqmD!2cDl}!a%*Th< zvevR2eJ>JwmZUkav>D^s+edE8nyVFC(%`1`0wt#slF@=8e9)0xWexxX6;`n+wgVmB zBX_V^QK*hAmrO*I$1PNi9y@!0`V{>YBqWADJwl-<=^k4$^#{;Y5imXgqbF$K>l9E@ z2kw&*dDtd221NRMTx_-lR8tpiDcv$1fMQqtvS+#npvaPC`MIBg(1s9yTDF-2Y=6|53?I^(_LZAz~H$2?6`RZk?e&fihkGv)>6VMf6|D>j7pw1^2Tkw83?Q zjJ^my4W6&bHv17?hEbPMiBb=^jXW{Mb1IR#&XNWfC&d;rxpp(TLc&C7s`?))FgTn( zfiu2>X-Ur*mm5Y!M7++s^J=~2C!ky8B+kHwlb~{9DJe!EP|X@S+ndyjMOZ&l z9~}YH`cHO#1p_vPT+b&7Udb|A@V$Uz#*$l(@4HXw`Ypgkqb=qE8*K4crFgDfqxehw zmwpMJEMq7wAQ}eFbCq-8a=Au)>cvItfRb3533!-1hW9tD%1!IlFkeIF{w&CN?1b5N zw*m7*h-ho$&gf&C&$EMa5q-g1FpBiq{Q2`VZ!i0{vsxhLY5GjF0gEA8nCq%1ZiV#+ z{0pi~>5K{E!4O-v8dBpt>cg3_6Ko^HV0K3=I<=kq9!xCa5&nr>Yo3|C<<)zEfn6{8 zA+EjNxV98$iUW>$pWIEw%e_on9DvFM_o7NL&$$zNZA{k?w#|z691}cfRJH2U(o|&T7jS-8;>s(;32!!Ub@zT?vZEm3} z@+%?GUJYWlWeQA^hoF~RGg!xAGN|M;!cEq;6X0WV%F(&9m5wxqMul7N%^5a%OZKUT z3v~97Mm)T_?o!V8A?$=PwuKytW2jk=_8EuLlcg)FKz1r3+r)P-qKov6Sfcs=l-gEc zVyrDuT!|dpCxh`liaetZ>~D$fcQYZr%Jijn62mVt%nF0?GQ=b!{F7hCAFtNUczh;M z;B4e*))Liz*2OFTD#>OEWh~{JPt5O;0~feggrD#ET>4Ht{}kxm(D{{IOE)RW-mOUX zMuFhWd#Cn`-zjB=wbYEdp3W-{Pu3;Xk1hT)rA=Nf^Z19En%sU{E@TX2lgHTE9y<+88Gi}p_AhlXBz`U0w%O5K%c^C|zE%lHPp&0fez$A;G;9Ms)31?YegD@?8-L?6$k#8eZ-6N<(j8 zQ(;>t47nW>w2tIF_r#9}Bw}kp*|JHEgZ--ouGwD4dZ13ooEqvchyK9AtCh8Y-Xl^^ z8hIq$cm_yh0YFWId7+XwY2V9Db6%I&o1~(t7`qZXM!aQpdXy5E-od%Du(<`Q9I*pF zNP=5MScM*?PUjPIS-iTKRpSQ-v;7;F+Hi>v#%J;?daDE}&LuInL`z&ft%4{7G7cH@ z+T8diu=BXqVV@A?hHhRlx4i>xRf--Fc@F!VkYBwRq@`q>VLev~*ozezd^cRyeWz1Z z=v2-DOfO(c8#UR9yLb~q%(C&)`o@}g#6C}z$*auU#NK&dgdL7UQ@g$xhV$8oL+|61z`^N@N?qn7bL8ChabA-obk<|Zn8Oy z<{X|G_H?CfefTfk43&ejzKNJMGHieNWx8-XoV@9*;?h(`=`dgtA7xJ2D2eMwS--QM zHdfYV5tA`rnvgvgecwC0SVI!RS&{ODrq?qI>}`|R8OWLhusX>AG3E*FRJmiqCO%JBJw+o!_*fvM4nlOxAcjptalcpsF7xQ)!=u98^ zO&+q1`C|v8rFx0Aj{NuxVV&5fW!ewYPD$_Lu8i|L6^#_3<+9IC`(fFTL--^H3dm{` z&JvD_(>0RKA;q`HSiye@%v2E+_B-H=9}7R?H#n2~xw^cnEIKCC-^L&e!9ZAm{$*6K z=aH&$u%~Wh?)X*19!B$Ctfh&jciA1K!{%m$wx|Z}3bJPOAH>guM>2c0S>CkvD-l5f`Ue(?fhe`C+jEC@1nEsV zWQ70~JoWO6^N$Sk+mEY1G0MB@#1Kiqw59t_F7xpMudjjClJSN}r)ujS2dq5&SiX}g%>UY0$1PMeH``|*l&CN8jV~%o%ePs+XYdYaC2lR)NGB*l^&Xo z+0HCCHM$0Ezs7)<&Fs8*_8j^Z_s^$wQcM}O;c*MdX}rpi&Tug&_!n0nL6I)SG@BQD zQ}{a1^vIu;$wjTx^y98*sx6!uvY7VZ)43P1QcL)RKw!kezbS2MtQ{uXis>GTR3O}j zgYO}bU@OuZo5Gz!Qo4XXS`W7@5eOA2tU?*5vKktBX=S2f_&)$jl~cH(>`%I}Nx!Gf ze?_~no^n|Ikw^araF13IdfZqak~$og+xR-8%K&?nJu0fP;nR3)C1@1@p*@Or3TFAiyCHi1F-gapY&VK61dL1Sm;qhmoCPr zY6>OI*PAX+41%M#gbto&*8)lV%a1}dPybRO)g^U8779& zL;$0%NUzAi1LGc&G;`L!K_!#rMauJ>dIOd z{2gofD%=FRawHcDl(o$W;fOtJe%HETF*ARVoTZp`8*LA%Q*G}JF;w3UApky(heIl(XOzTs2@r`DpLeNoh?kQVl_gmKx!9`pNxkHKU*cx#GmKh4UbeikMNsuwMX9W=t#vNg$wSpcj$)=m z7?l?jYeD>Aa=t%Pj4VNceiQiSvZ^kxHrwkqXZ2F}8NIt;Q4y_f9t5U#t+kfWW*||7 zlbtl>T!BwBh-KY}wMF*E=jQOdEG9P5c1OLo9AS-ih(4-vKbxze9BpJjy31&bC&LEY zBO^U-zkZs^*7*3v=|9ax-#LxP;-5U_KlfKiKO2<;p#4GA2yV3h+6u*^-5S!70kb<+ zLS=S^H3Zj0yftBr_*!2Hymh}^m+7a@abjYKH_ef|qDvpa_C?&M1iIiwQ^-qH#p8s; z4MeAb<^+3K$>;K5^NsMWs#H=VOTwmnX7bAT%3^M470P#LiEXUzV;AK!*hKRJNR{@Y{7HhVIk zVZ}hxdk&8Ecb;XS6V%|$$H5QK5$fju99Z=KcNMbL|DM78Un%n6%V8Hy)VL4cg?5am zsnqcroCy+2G?Aa?WcIMqVyhhDfJWi5e$c2OjggCUJXxapN8i8A6F|+`7A*HYXrqjW z4)??a^8K%HP|kmr{x>Cc$2uY;ENmYdQW=i<_2Wmc*vh1uWQ)g_*I%;8K>4oNj{l_r zXNlNfTySPj>^^suvCCIc61|ReLm{L?67Q(7-QkVhpl_H%u}mOI{HHf_hLHhmw{w$V zzh@+fCc*yZ1E>AO0Jg*@DEHL+AHW`TcKqG^>Eqvp|FVk^&Ua@?aG}*>+dqNMcFu9X zCCzVt!Cj?Y^_R*i`YL^SWtmNGgACnSMie2Eq85<=H#)V(`jG^2rNhH9qqd$>LkWrOD_DH8f zzA3vzBBQbWSY&@Fi-_AE=_{!+vvbh(1>TgR-}eZVO_aQOfGXN731dF<7T=m}rYY93 zt@9^I6^M+1LG_(n?+DR7M{IEk#7?J#u8_GluZOU!KwNMeCza;Uehw1pZId7RUy9Z z)kL{*wAlfXu7QI3UbV-Otd&X)2ik`c?fdvplS!Ip)^8E2uQuQBy$v|{dF`g9rJ;km ztIr!G0d<}Y={0w)T7!yC)t-ruXT9nfvKkKh(N@gAip6+jp<1bq^H_4sm#J~P-?NXp zomo_OtO?pqhMU^8D7zxk4{E+>qejPZiuro2PxxKj7m4EijG8ia%?fB4s2XQn%Y@0! z`HJ^{$ks9-`4`PO^XZI8P6mQn**@ZfkPV9?)~7-7#bIi*IW@4NLrXHYNa2cC9V+6m zCJZV~4`%x_iMa^Z%7N}W`&cbV`X4~lgvOG#`Yln2rm*|8N_Ro81-n<(qV3rWN4iX> z*o*$}TdWm)YK941Z@l;|y`)^Tp*6hd!uxl(;UKfjm~gh!4Xs808y5yrkjLYGXVYBJ zj?pjPn&*c-eHHS(y_@Ar#rZZ&oZnOGmNZwyPuRxKA89B?y7=KDJB9I-{b+($_0y{HoEr+I{T>Z#y?sUsNhW=*_RpWz5g~8$&dCL&*X;9 zdNR_ZXWlwUNe;yt*&$3%&C8|kWsC=xi^T?{l+}27rJQZS`(4r0hjKbPW0;em9lvI^ zo%2|{N;vY8*PP%j%nxKG7fn3Z#d3s*5)^a&R!6ZOWxxK|P$=2H{h;bp`$`AENx z&*PS(vdD3Apqwwv;W!>Su@Ki9(6|?QpWg|y^Ulfu`z4y(TZ?{Xe6K5O1l~$!7lf&6 zVCk5`vCnr?R#5e2nguVupuY+uaTBP2wjjpl^O8)bg__t5( z#r8l^TOVcRd<_U6r5P#v!?>zOZYBeFZ-BE4(Ud1b(uqGs zk>0Pjd&tp16#FgCHLVu%&>XY*PDu3By#TG?6DtVV)fN#beA*U=sQR&w_Ok4_2&z^*4>0c z*YWaDlgBEDc4LX|Z-uwL6$Px5b-+D{Rfb{wnZg9quXB~%3>CPYIU`m*xwD(1`*~1T z>U1tfVMgW6E+1c;UauW)q-B12;7puDw>>Q?xf$fk;Iwj3Hafs-xsSiF|ciLP?Y zQuHQnReP7tw1rCqqJgyJ&DzRf*nK)rFty!_GR-mZU|vuib4gr^($;iXecJgIcx82T za^D|q?$>_uoz4(8+BeGa%b@GEcM6bqP1d7cfliNWn;9lM$hSPTqq2%4c;jbhsf`UA zfkLW3h?RxIgb1j~a^(Uycpqj{xo9YZy2!^p$U2GB+||WXCNRA*q{zOubSWaI+kg-YF$ng zWo9TQ<5RMh7`oP#tVl}tIYhx;KB%`U2zLJ=GQuPrC488k1K1cusE`1eXzdUUJ7$?r z1(&ZGsV@YTv^c*h-o4x$UAFwJDH^y_t@q= z$vy3Ra%fEgpDfs$`ww%;9f-CIaGRsitJojXQ%`H7Aoq{{T~cel`?B;nH{?;!IOHSW zWp#U_2>}rRrv=hwdJXFLJq3BsQQERN~=?2v?(?{JZaus+z{2HZTgoJmb*WUF_W{C&cN)P0J8EaFayM} zFqK!hB+~fFlkSsp+b1qT6;z&hdL4Wd$rYTk7q0s3`DWg^=@d_O=vFz4B1M|=p+99V z#+~fO@!<-kf8XZbJU9u%ITHc59vANjtO9`e3`L5@c*}_ML^EjYVxB@NGqk>A%E3+k z@K}O`!*?dIr5!or45-;HVthSKeTwWzJ>D@mDqE(vJ}kJMV045LR`@u zAc+S;(FccH7hrN#F=4aPHnnFH`jq|bHN>2SXZ~^HoOVU<_hVVdi@;qH?xxRj{=!Zo zOU~l?cP^nRPekL31IFSiVpGlfkzM>W{k|=C0V%gp!&^68)U zvQgyQ3_Yp+amrGYM4{%9Tt8M>x;~qV5Q{ANn2nyPrH)}^e_srsU^0*7xpeDScZ<=y zebeR6=C6mTzk+~&d(nxbnSnt!3HqF3|?Fo~go|-1G60JeY36lL-D;PBn*n zv!6{PkbkC5Q)&AEzBd)5REl;2zp2JhFjntFel*I7{M~p8symnW@R>J_fwFCqs z4O?Kmg@q180X3ny@=PEjXkZM#)BDyc!dbOR%)j+&vb$rO_At8&IH@?pV#Uf_?DWcYeNJZ+wumd6UtAx{C8GZUywYiX+!QtVlshQ%HvR3}#pC)0<*y_^*AVc>D+wg% zK;G)w%y)}Va-kSdD4;^crzXE5yBDkn+E1T~ceUSB7Z;kdk^agL{{wh43d$8n$NK)Y zbm)BsFZuW4>iqwp>@9=h>biB&CIk!GxVyVM1b26Lcb6a`Xam7r6Wrb1-GW==?rs5+ z+wc4Bd+w>dZ`G;OzgotcYxbX2bBxEf$o^P3U){aheVyZ5ZMxn53n+btj2ohj>cTkj zj(wcKDYkN^8uuY-Zl7*#+nXF$x{St-sGks@rzU=35KLGzEP*@boWbER`YgB?z~iZD z(G~l-!qHWwG|`emr_`(T!eRb*2$_jYGR)SefV2+Edx8 zLRQ?vqJm%@1AG8#*iEP2&hl=}b)qb3qD_9LO@5SxEM+2@x-4Z9EfCTh2f>hAKt`mH z7mVdk03#o>rr!od^rn37o|`hd?4j%ll|*ToRnQBI3-a_P>b-%J$CL3Zd5TK?@6LSIlKY1 zZyFLO11HkE`LvO=>e-*jn*SINNf^{p8z~vKhtftz>l`S6JCK2*|0$wTB9Z%y1>|@6 zt@>OVIUg|>Hzc8yEu3r-adl*JuAw+mR6eT^!+RhLga-0*^S^Y)Ya;asqUuQ576@&t8#i2Ca>tAy>XfY&sg)}l= z1@#eW@r5{K5mlFjUHD~i-lyM-L$nMPTkKA5rgvThrid*Sdrpb75@l z(ydt156e#DMTSkIudWZnxj1Vo9g60abjpK_axFc z$zvLxsc~Xp%S9!@*^E*9D~U`0Z~RWdKXqNy0YT@V9(SKH0zJM=;FLZ?j5>s`3@Tt; zr-#~jnC%OQ^?gbRw|x0`Eep@&9M4gN8l4d5YzrA2`qFTD(>!q;N5+Jmu{Z9MER?oS zf+aNjEij;BMTlw6qx}0o zXFG5#8v}o&IZIaho9d$0V#|lfgLp~G86+%EMHZ%*Y8M;#OhiyEvrX4%SGuzh)2TDz zx|?>Y*nF{99pkgp-c{GK?=Isv`*l~t>%b+t2>%kRi$gXCzjoDIE+#YEhz8Uy}Knh5( zauG8LQPTt$_2X@|B#4N-8vC{gdKXgi*`1~ z`mX)Rvf^=e$YQ}W6oLC5{fNb0OoSfja6u8^zJhvQVW&mXur>4ucW)MVp1y?B;2cE_ zb#E7Oo}M-<)?HjvH38kFdV-_w%c6omIoS%yIN28%z#Fprp)y5e$o&Q#Nqt5?z-UM} zn#&dv=xbYCSDr3&;N`e1S~u!e?iOYJ;ca{B1(DC3FO7H-SBpqp7;Vz3)fsmk+*~Yj zf!y5^o{Pe0A4D1~Y72cx?74dBHGHRJI_aZ?r>z>oL0AJT#i2Q2SA_DbZ(|hShi}q8 zbB+)Jrg-ycKw5dVM43>zvBSw~($T}*H*z$)i4SECl5>5K6s`Ty@&jTxbAqaulftU% z@v=hsr>c~PsN{&#%4myKbv8@IT9bvgs6;*4155c8VwmjB`O>cJIX#*E9lyqeQpD)} z4x(|sG+M`skA;(s?y3v&MC$*R&6VvgbEYPu!Xcj8lJb5K8}HD!i+}*v0Ae9F>)PA6 zC(RAhOBgSwUp;8NN58(z)D;?zH2#R({Ctnyac-+U(2vI9?eg$=@5rH^Ok7Sb(^U+p_ zGV$&k@2xT2dXV`v=T4)h#bR`yjm6V-bHxz&^;$n>HIUGkF(v?I7o{L=$z2*kUAoD9 zhN)G6*i!~9r6y$e0uT0J9xr^F?5Q6vD{ z>y<<4hIj4o88h8vI$H|Kp}I0QwqP{IncLq*;ZX{}JJ*> z@QhsgCB?>u;EL+W#Bgf+mN?f-M3^LwxK9~8-@kZKK>Ku~HEkH1(BSY2WtEYjv98yQ zaZgo6%_f|@lKjh=oGPn3fwIn;Okv~q^!L*8gMlJUm9kQEYNLsBoxI8c7r|L^{V>y3 z#yYDO*x8+1Zav=JTM{_1FrMBKf~15%d&IcI3uVexLPFQHxvzFTeR*aJVQ+bv{aGFF zR@ygDNpmDmmZUL3W&c%kcU%aeq#ApepqN`~iM8z~-%9Ckc9tzSh?o7*eXX{f_CJr( z)WrTC%6I2=9ZBunF3(5gopk6sp4NZ|)I;*Qxac?2bNc`JI7M)6?$yZ>I?Keye_NE| zm^Zut7AmMTbDF1ZI~AS_M(sQrFT^WzrHygF>Pqn*_3bs7j(b;Ths^b`76O=J;bsXG z`j1@&r$UeYy#_9Yeti0_SgVVA|zC@o;tx|qR_Bk0(mkIu-1V- zo<5By=L*-%S38_=b!=f#cSDNU7McoTeWWfjsDpNW@qL)R0;^@NliW@*BNPD;ad8wb{iKT`00G;`Q4arf+OOfBC}E+ zeP@2Sp>Zr=Up{If@~el5f0}zu$$1%c0DqLttzCap!Wa>9QM?$o%(OnXB7&6TCa_Ig zkyTOj`1$b%gD7ZTk{Ju6DzEkU;n>1!SE@5eo}jaVvaWT37^B|#yg@e!9QSHTsA=cMN#k5Me8n(jvBRnb6mjaaw>Ed3$Q0Al{EP;J$ zk%kB2%8={OfiUReup>lGgOOLt>kfvl8Y;FCaUqQtC5;Z2>^n6OeWv!)T0LCpKxZ{r zZBWqqf!&MONU!HTf##>+J`!p++~2^R37=m~;DcpHQN0>nsMY$DqshyvMP05_;{LM}Oka(O*CtWKI3GzX1JJ$Z6EGtLC96 z3Y1lK@wEza9^G)Zf46xbCwFRT`qLPA0JI@*+5PbTE1&x80}Xd#P= zJkv%iS-$;1gRC;L_7rl74CFDM__P1{a27kO=Hf4)iUkb0@b&ANJOrUJvh2+A+iH=} zyZo=EZSVd9SYChpIRyRqd<)stU%=)6wpGYN|JkZ(~b0YxNpP2TTe*LJ?7$np+VRkATMN~BzZnj!4u@@tdQbD zy!E-|MitX6yZ9WReCr=G(0|XxEPrSJ7h)7`8msmg1C-DCO4D~#JBtYsh4{SvfvEfb zL5V=*Di>&{cMx#QT27f3^#>%z%mHg2`S3J>A>TfBlm7Do0*1MP8ZR5)9`l*}>OR}Q&-`0+ z@wM$WS<-QnA#QOVm4~JCXkGn0!$i8hIqV#}08_jNKFLj&a1f)XqQB-Cnj*^{g;xn&D{;g2pBt=>Z#`>f*hm_-%6 zrqzgxRCIz#&EizTfI1UK&(TI0z}C?1Be}0N@&^o^X$&Vv25m8oRx^ zwywMI+DN4Hkns$gnS7=GHYLMtT28hk!NK=ij5!Vl>&fXYH7LgAys9^cw^>xumk-|b z10!|o9wbW3y~gtsDQIKOise$8MuPf2Zo~@x?QRL7BRdK{Vh*ZPgi})b3k8R|iN?3| z7R<Pi*sOD4U|RkMOG4%7TLI&432Z-Dy;6SJfrqnCj50 zj)&FjV)**anZ3ul8EZ`={xfItb>&r24uy?TlJ+f(ZWFpzwjfpc+CeSzZZMZ$JUhYh zYn0hpj9)@M^z(YVeX%`{zm!m?)rPcD8V9Ltq`Zp}QYvNAee4Et%zBahEKLiUOnVDm zGulaxXYAX?$}uM3w^-S{N2u~M0F9+dLOXS*E~(ZtF4Fn9vt+PCE0ZGKGihUVc(3ZS z9?B(y+GUj5Y-48XTZY#<+<{x3JHOAY%_2Gu(?@)%79I&FCs*=j*pd>H%_G8BcYQqc zlc~q~iqoUCZxg=Ac?C5Nb=Xp+rJL7XxO6a%rQ=T4`RL3U1-Kxzu=f#~x_pM}gH7B^ zwuL~T*PfPd{Q+U#w{xW0MD$R%e636zKg%VhnJ_FC7+;f}c4CcBDhfYgi9mWgDC5lI zqmMYbrMDHgUeM`&)(BA*%?vV|4Th2$`l*|l&H*j1mEPj*3Gbta7exuTWK*~rO?$xd z!dVsbS)3ehbE48G$Gr{xG*aGslo)rHD_7(~A{{#>Aw|noOwPXm46`2B?>Q;`Ua8X8 z)xNaJS%y@IdHvE-lt(8CM-Dx71EtW797aRJqgsx)Sp>O)4WX8O;r#J>q0!3gL=D68 zqNu$sL?gM+6rESfSwGk#$K#4jt4b@kB2jw+IYdn^{Yu;yN7BfqG^?{Y*PX!a6vI#R zu^(|;ggz(sBqSNxVNr2C7KQc<%BlucoA)0MQHw5MoqY-b zil1Gzx!f0~n~rrn4v#2Yh$`JTto^pab|x)Nrf6CTNr-|ii}OgQ91{CIM-0lpk*!0F zbH9i{GDPh^h9@?Ibqh?o*1m{L&@g3nLFc6av=NMW zAy?#<8R4ni5#(aW8E(rrbFu+>CRn228AY~KpIw(sxt2+Q{U}vO3+EXQeiKiY&&5Ti zH4-YList<8RYLug+DMB$VxP@-PH?Q$JMj;>B0>7itziSX`bKX3al9l%)<&8KHU}^s zw8BsuO}&NVXm4CbQ+Nwb-FbEx=kMj5B=MgKF5l&1UXuZ*^xuR6ymBY53B~Ch2AB>E zbhuiZ@xH05P2-DaQU$|GT`!}c;Ac8We`u=a(?s^-(KS?(Ey*m`u1zr0J3?QN4KW|n zyVFriJ)bUlKxMEs=HsARk8_IFm8rO6FW}yy1(&9xuu&Oq(t=YD@_4iE3DJ(JHrT#T zGpWgl6tmDxW!G@zdB9esxqshV!)nYdZ%q|tZ-<@9lqMgVyhXsGo(uib=yz1XdjMd+ z=y7>OFH~jC?pHCCdy#HqW)qpo?oO}?;l8!-B zgoff&HQI%86z_=4=OokZbt4ATCHzsxGINtzUy1pk!JJ!howERso5KPCnEGzU49*uk zDXfj}m)w3K@z-TvmD=^y(^DYYk- zs}^IJB{=K5d1o?9r#E&RoHQ?4H0}s45-P`FmyvT{zEg7(Y~k*iGdNFCj){L3KueT~ z`WeSxmK9$@{>1n&)O|anD`rhQzRkc54&WkyBdiox2y>PD`OPF9`eQ2GxW22E$}|Qo zeA-V^oCbGK&<*T*2fPbW^95{$4Q{wq&48UCcQ9@BkrcB#EFCf9RK(HAVxG zRwxH>Q{!4?Q^-iDq$K7fL{zxJu%-kN6(UoFT}-+2Zh^w4(z8z1Wu4iu8XWr#1VtJ% z(o?z%uJAJGtm?6gErtU=A}~G0gV;3-<_3fCMmy-{VHE47&}hRC&iz)niB?{c?QT;E zqBP8YE$%W`uunnLftUH=$u`2JDXW-10Je8UJ4VTSjR~jP${p50(jY}>x(z~dNI;Me zw|h?cK^4zsm6L(M=^~zQ2o{Ht)fX>ClpDeMwBJ0|PLbIq@1@JKLT0<78o9OoL}EnZ z`X^@Ph4<>Qp39yaY4#Ve1u45FyA-<3qd3_7Z3T>HzSz!-9=r7P*C}mV?2S}~#I%}A zHnU>}9klM{V)6MjM3#-`<`%6^M9L^jg0TUZajwDq={cNX{e4$q30(7B1#PH)9<|r@ zk>msO{X0WeDFdIDD0kclmtrA?srC3WyV5dOh6a9f#^4I?t<5YF+8d zKf=-YagZ@|@7ICZK};GC8HS^R0dO)q#L~FgspB4~6SJrSpC{k!W%=E~7>x_)keBX( zh2nVNzn^`Gr>C3{Id86U0gbub-h*-yYeT)ahZ4VM z2J@VS#zzo1NH8 z4L>uy?UI?NWq3XQkg;~XhR^TQ4lmh2c>3n7*Q{q|yIo^N__ThxhXIdE%ouGx!_Rsv z`bfsaFlfvnG&ThQslalL{59~G zyE_pCMHpKrZRImTNsc?I!}SxJOQ`ZKqFNaC2Gq1k==05eR-G89SiFFL?yCDl9&Ys- zeiFy(3n9=kl9DZuH34lQtyJvRZErqvKhZZxFtm%(UjXB?O_UnMOtut~Zwvuj*roQ? ze%?m(L9Am*@yI1=5>2@b!K>fQ0oy8a??) z-)^6u=TJ+4&+ZK-`E*>%SVA^_Xs4)7pk|)8TIiVyh}JGi-YGud>T@uta&Nc^W@AT@ zz231z($lIkygF|$LbcCg6>RjT5Kq=c?GrPF}Iis{?z=gR4a#8Xpz4rMGkM z!G_3A_7KEuNNN~nb#?YSZK|ZSF?&p!zTOIsmdFilm`BWGoJw7HCaKnHU_C`S3sBLt zwrU-2m3s$mG#;I>gm49%IgUkK4QT#UX|UhfAsc$JN82v8dN{zUpp96DjB;tH@nUo8 z!oISP$d%aK(jYL z{k4f?QpYTB^E16ELp0e*1EQ6E38wkcTH+iWFq-pR>kW^RP=sBAq;ti>_H)ewhZ zr7U;_xiC{#4Q&i8A)y(er%{m%$r748nlr$6U|xm_>_&{Tc?eHyM8|(bhZFGD){+jD zSLY|$=}KXxZU~UosZneej`MU4cMX+nNc6bKV!y2RBrA>1zs?=dj>)Y8#q1?rlul|= z#bXPEeURfSS52@qoHwOm2mQJ%2yK>!4Nq8h^JSt^@ye8#D3Akk7xWqLU z*N*tH#8Ws^OY}`U!5^WAU&!)s!JqXn;D>j$X6JJR1&o>944EDC-9#G;mX6PzByS54 zTsVjgMjrTTShB#Zw_qXY;GlY`3;&#MCYCv_r&9BAUlXo!oi;Iy4^ZyjJSWMFmvhG9 zL}sWh89ryZ_Qh5}k6YMQ;7fU13^L25?$4o4lx^{~enLj^Hg`L*q)#&`Z6oM|3^p$9 zf=!C@Gq^}gHfu&k0E-~6n~AvW}eP+4O*6OMEh6ReS-N$nZ3Ba*RapBmg+2p zuYT0&_^LM2EYLp@Z6c3bI$L7VQ>_n)Prs7B)^6yOfkTwqo&)lhX33JMy zZe0Hb%#|$m6<@)<(cgDmc^Bh^e_l}*-;R5v+UQ1pT8AL0gxRmZFXfipUK)JOCpK+5 z{sPDZ>r`x(*Os=f{C)&IX>VNlJ_%k8PiV;>?i^$>y%ar;#2e|>zHfFfHva|qf#0Az zy083Z+L|CWtVZLPl3VuJZz*<`712DaI7A(#l|rGni$5x2+}UTFB3z`m;)*#KA`R6n zsI1MM`M7%z2b=N7jP1w7rM=}oBCuD1&uELs5}0KMZR*-9-BPQQuzn8IwX#iGn8wRc zyH+p{(k!il1X}yj3=}SvAZjt{DQ7&hWZnxSlcLIkVb(Ve;*ycNx-d}+E7wYvLF-L! zYv}gxc;6G)FZc&SWdEry)O1{@(Rt&$e++l6YX}z~SQc)xtoLsU_nWq2#@-+EDOXao zg6(nw`GoVxlu>SsWgriC!x-?$qYucvh&frz$Jz- z``CP>;{L&0oOJrY&>1 zI+aBnAhO{ec)k3)TVcvUG$ELN-K&r&6%RA*!MBW(%2F9{Ic;4*1OK#pD~VFZ`!vApeK_vdU&iRhs4Gx zN=luu`bB=-KA)VDCtM;iJMJgM`ql~i#Sv75-hBKRAd}&o443sv=D7HWZ^`H{0L#}f z(>Ue_`ya?Dl>b*v!AA5~90$Zl=eq#Cray&MhJ^aMJ>*gbk#^Y2$p{BvI-r>@Z(T}a zloNbrWSJfHpWW{+h4dR{nZdy(?(Xm~F4&v(e*xyO&`p(A(QHFGrEEMJ2uM1f#27>{ zxx?|NqKvbhgL`g}R#LX6yF=V!WqQ*!AZN!jUB14{lEfZ1(w_bXXEAY36pJceW|nqe zzj8&_fFOd55#3BM%D|;*<#ZBhf^JjuDm?z&DI{pm--KQ0-VtysM#Zda>H_Z}Pm<9} zO}(;f7GeE}jP!FOb1#If1KmsgcAj~Axfyox$M1$un^*cuNBu(Yoxo$)PCdlR-EBVg z`d^1U)}54xOS2rTzQ%E1=!h6jMt0uBr7q^V5=jD%Sr%rkPd{7$vgCe~Zm_SkH+Oq% zL=>8)w7XMuk-HMM-TyFeZtGu3=;orZowP|cg9U?5NQPTl4?+m?JcOJv%O=471z6`aEd_11f zd|_a(8A2KD}~yT5vv5L$Il#v0QWCIaA5S5fNN2TCq$rlpJp5$&0urpfq}uLeX_ zzTx|ad`4dzily|2X>-ugwPIfD++sCro4YL9-TwlEd8h$n(s!q!8)d+4rMc@mO{Wmh zAdjJ-5TPGr(x3-PGVrxmtkyeo7nHVsWZVsiOShV1)ypnxa1j6KWfO;n=gqOpg)~@R z7dRWPttDg3`GA#fk%C#7sTI;;DM2vIBaaf2-NQ~If1|C;GF3mwBma%SL2u2VHxp&ZMU zY0zn)`1N^+BV*$zs*6XMdveb5WwrAta|~pZRr_CgrM8Q3+1fkIIlA};?5@+553_Y1 zHG*f;IGTSwvZZk_(EzF20Cup;XmEYyCg?9)_{p!uHkmq;YMFR`~?hX3!4p~dwERdhps7X>0KMH6zr#j zV?+EORCyxr%>>Ge{)k%9gC7KLAbyZ9to6@_3kJ)BC#H;yi)Kq(Dzm0VYhmq56stq} z^}nn8k+732+dMPWQX_0#=gfGOc6qJyhitDa_4rH6bAayjR=>#H?OGBuPBx&MP=E~# zAATCopzK}vUgoW?+@nz#nM3Cv;=pDV9DcOL)+{tIwn zg1iwbjoh$(i2>SgM7|ndLh!Hu_s4%gnt#w3iGL8CCkPysv+|?q&(Xio&SMW4f|z-m z1unn-Xp>NaEDMnUK@hV4t2Me=*8YP8i9(zj%>w;YvAZC5fMjX>vx8lTMyl#F+ke2J z-T&GJghTe<_b}f+f42rvRs9Eb!iM~w`;S!z&6V$$Afa(`=!Jobz?v`rUUviOFa??* zOGDc6)>s*L2NFn@#&NV+)CbenS?pey^o!-%xF}G|ec|oJbwD{e7#1>`_ngIU{D=1D zOgGpl$u9XOCLDMK&ZkSvE{4P){{9zBll(jPA0&+lV)5HDvyo3{UbBlDJ@bV;g>BLa zlFQL3*{A@uMv5tkq($rHBplEv*-)smIoN~a2;}FASrdSR7y;5o+k(_yDK4E!eXk@` zUVMK?K`#+NZhp(fVjJOl`eq7&8WobmNF7wxAV!*)9Qhd|?r@GkG3-d65a(D>9$vzi z7isX_c|M(cqe=(JGYn{_O2?nf0!GE@B~Znj{j{NMzP^8Y2SEajj^s}ulDU%rh^a~r z3q%{|UUc6mX*wejm4MJcL7ARc``d2&s-994Xs&o{_?e5ksk>1?{`|sO7285XBA67J9y@gZphNQh_YT4Qo*5q<{8E^c_7xI3UvLP~F+%+EfwsfV}xPcl9H5jR3 zEmrEu)Z+{?4RF3>oK$rhXF&|h=$PclpdchXf+jsa$P(YCw8KjYVskW^h>pE)!4Y&~ zx_7Z$oou#|(Tg&R`6>RK5}&+qKS`DqO(L>bm1q#1PUeGShXg!;;6g&B4>qWTmmG`* z?d~3I8=U=mH8s`3!~I8i<2d?DS^iH>KAVCh>}oqq{I> z@aTv1p!~*-)o?AyV+d?z8vUgr8!6QBw0eW5zzJGN;tr2zQHN5_#Wo74Zk9L0+}pL$ z3+=AuyPA%PCY|s+7-<$M{ED57qDK2yHpM0`2pKah)4%P=ONc3(H;aBY!9i1$k0SHw z>(U<%x!4U!o;a9I#E4CYv^h09v_WH`!BeB6Ji za6uAy!5y9*@-J6FiZV0Dm7^xVugS=(xj2}fZ4i{S9 zA#w9o_Ku+O<9j{WJN7!uXGnB$9_7yu?d3zt^j_i)^|-NDI+RvJWn$7;OHA^9nBnaf z9@*9}UQiX`{CMAE(>isSPQ4U)8aH|=QM_f#$`X=A>qb%OyvF&f%$ zc^~rHRC+OW7A-nWS~4S&MQ6x1W#}mbS1=T%rzcg(o^BY#8tV>~QIV5HWQbLH2o8av8*|iv; zFXQvN>RQK`hYhNq($N>|`Tn)19G+&)ZxgwAGCQeCEVU9Sad-|*~%;YU3N|XKz%(jO(V9nF*pw5utG|^^XW1yRf$n`N>d=Q zYK^wV#ko(hrz3ZNtd{*Ixu-d+FNG^v(Jqb>?vabF|F_Wfna@=!BeBl$lGL^ryR)TI zc2I=p26!&~Szl$n4NF;79Ay1ssD_sVOv%qI_b19E%|t* z-?HDem@Y*oIKx_rEONAn1ns5wQbEzR(2rnNAR|>*XOeOu#md{QCbyt9J_i<9(OAO+ zql3DMR`$mSGbnEWlk>0v3uq>j`5%en+MkdIqnc(0Fz9WcC~lDBhJO!tFxp3prNfa} z()l%ztS@tY<4QMW=Zf~(PtqCob=a4>a+G;q=6$DB@+6ea-|RkIDL{D^MBmXfx}_QiIeM(9 zDl9ar!Ckwd&D016ZrJL_u&2N>;A^spn%&*YpHt@3BQFo848Q7R<|lW%X~v{nYF3{~ z>Yo3ID_HH-@s=BEHigd)#q{%wJ+&kpt57Rm6=BTEk2=l<4`CpDQav`}ov~_dXM66@ zWR*IyxnTXcK2bbMpon&qphy!i-D!)YvVza9BhV_IVIE)niI%x3ff;wbd|ye5%`a{p^#327lReGe%#rO|=L zR!XmE!~r|K0p^_Pn5~V4BDAq`E|R=LQv-L8I!jXoL*11PzDi%h=&tDVlzx$M^;gK4 z)k>ZoRBia3^K+DYXIM{w{$tF0Y2;Xpwq4|OjR{+~-@xODHYxJ{=MpAeT&-QE5r^NdoY`$zF$c~T zExbq6^1J?Sr+@lU*^7#2!bU>XQB!e9Ld?a=#b?aV89#XG$XFRGMIKnnmagc)x6h&W>7|8b zVp2L4G~JZOmRUItO`hz$@D(USwo0g~i&5A>_Fs3j&ep+$QEyRd_W_VmG>34!5PJY^7f%3lPZKIcJ%QRuat+6@()Rf&@w#~YswSZG(Xv}rk}Egbxq#eo6D{fQq$V)W|8XkN&#N%ikL zfx7XIS*5fsmIRcm6&8RpN-=7+Wcp?VJ!pw+I3EV@MfI+s>4?aq4d5A!nPx1~JsmeUui9Mn82)VQEms=s#oT;+b1tH342^XbU%WRN z*x^!_u_aNjFDPde?G(wq0XK};NE{xw#Z|h)#PZ7WNSXPMI#ZRO%QYfnh3k?~0~=R_ zjX9$?V0@{rQvM6`Qj_EJwR#(Q9$6;kRJ0nAdHGI%m?S9{w#F%Ad$1)YU#vN<9X&(a zEN1Y?8QSgD%{v5F;7Bgk=@mBGA_DTT!)`U^e(tyogB$`y`r5u6M}63w%!T*|#Cx6( zK+dCj zU5oFsdKlQ-+Prw`2NjEaTY*6h2DQM$d(C1}VL(4b)T7Keui=xgh(m~=aIK#qG`5^} z>kH(rnSazHNKvH^@xIafVE-RcpdgE7z;04@4BKl22zzfc9>Q9J7A3f0j>Yxa8#2HEG5R_;at}4-p!8K{_JJ_T8ViLFXdRkTDNXZWhz)FCZ1J9aD0Q zoS@X%`{Ls9IBHbz3;V(n{Csm-{Tl)apI_X=NHjB?DkC#qmd2AHhQDIYT-$le{L=4> zVq7t!$GPcU$}bpB6>t^QX6X@Z(z+LN?Ft-l`881ovu3WXLAx7@8;WINQ+3FGPRsgP zvWUkJki>G|;j^uu*0e7w1{?bi%++oRXiI;fMwD+(2xj^uPGi*>!z71jXkYeB8U3dtht;HZ0E$$5^-zOnvVDTA{%We094fya z+b>FQ?pYhxmf`}!TJm~iByhj_HoBEV4K=d9p}2fRbJgsifRWAqCg1v@UB_U%m5Jjf zB9F7J4U1E5Kws!1$D{mCmf4suj-ZvoE4M~*)!^tPL`5RIhPf~RUk-*ZBZ^`U04#hbaun`S}Kl=*lkj%B|I(iTP{%Y%*iuFQs7P!`T*!gf)Q}=|#l2b4D;{ zy@JwPW>pHM!SvCANA-eh@?&E7iC6J!NeLG%mGeCwS15Yrgogr;*57p{=-oxHhM)rO)| z^qF~8iGG{@4}$9!v`2C4&ecS(XoT^_xI!*oChjLlRo8~5SM(L`tL@UI*3s}AlT~HK zAfnD{dw=fGi#9)aIVH^fsitQM9O_uPk)7siWnPWjondo~tt<<6XJcAsAuj@t0Z8EI~66r2i^|F+kf z-Gr<0+jH0)62D5kN-&hr)IVcx_-`3Wo=||0v9=a^w$*Lb_MXn_64% zvn!BD7I@i(63*QZzSN%jGy452npfbETN~poT}tDFi0x%d&4A60>*BG8)H+Y~QIX1Y zq_m^e39f%;PH)JyrM_BI_smzE6_VMg&-LbdBUW3O3ed-ksH7Or6%NiLI;7hiQ}ESoR__qm8f4C_&o62e@j z&r?+A%^NP=^Yh?ch~2)O1#wU>x@JRjEt|Tkm^?5I)RjM}PpHaKWzq<@+m2a;ZP!K; zl@(>mkd>sjzf5Ivcf=fkw?L*UJI_q&E|czPo}5jb!M3~ZXGhtoaz=>oDQlU!g~9l~ z(bWe7^J?tBLA%ODG!48zpv?FPihwV?O4kRpT94X1&pKEEMMCFSDPlW^`Z!wV|Au%sS`75@f4EX(XB|6$Y5G*1x4N8fkxqD zciArk4y~Arynz^!j7l|B3m#J?>>0Ghl#_b0@r}(F%)4_(zsc+UmU<4k7F(9aa=VAT z4ZUFhH+@OP|EDj}qR6O-ZZ4})sPNy=89w}0=YY35w6(VM{g7b(eS-xCH{TWtPsX6Z zr(I6Za+F>@eS*2Y9F@D@bcF%rPQ1~O6Ud{g`%Qy84I$wvie_GQ^pJZXB=?y3hyV<3 zy*q5BVSf}k$`&UotLml4lMflA+Ks%2#F)g?Zl91SJ@IZH9t_?bR+sdq(HXVXzb|7e zj=5D9*T|UzJ6J4!fU(Y6v4w7Zkh z@VPVkq)x8+uxsSU*6*9rXD$}5A$chZ&aN0beO65cZ8lxiPO>yUUMzd9#g;?v+&nQd ztFC-+u}j;ddvN0Pdyqmr0*7HvZzi0ksWHk8XAqk@GMQx`^E$+=n5g5k#2L#v36|#h z+?&Ho+GEelQdj{0x&Cv9iE+c%tkcDI9XnKf^W$LsRb>?(r>cT@+MnFKW)p6DOOj?Z zwH_^(rdEIUb=#1X)L4iU6qi1z5Ct9V;R`iG9x3EI5g*owJqNv#q_zSwv3EG@=b}-Z ztB2BG4gt{!WWL>bR$2DWx*F#Yd?IQu$^u*`o=Bgw;kA{>F`^@yBA`p6{F;HGZ%^hNM7rBP$@a{O?0XQ-vBlodl9iKL5!D{(gttuQ2w&HmgbM#Xzf8dFJ-Sh@oPpAfHZc?$ zQ$*w=|9DGyFyGCq{14Vz_;_N2&$~LlmO_ShJ$&nojGe1x7vfd~{B(1uW*34bnQls= z&E`f;3MbrN{je8pmb)44PKn`kn2O}tVXQ&$fEZmo;vH*r>98*`QPe~V_M%q+oTZR( zK6GLNL7}JhuPTp8E$0{aVYS{j%XK)tS$73XI*ZZ+s4q`n4$M`LgBr99d;KNr6mLS^ z9B-nW7CGH52l!eY2r~7S69YaSaUZr^=250adaYRO7<7MksILTj#3bvsOS63(i(siZYYzCDUKVTC{^?eX`$>jWutf1qH@lw zT`T6hDL)t&^c4Jzb@&D{<4peP-PNpSG>lv`CBRYPA*AMy`IgwU zqk{yKKfbx}?2>;c_#^!R63thY=|m!Ohu@c9T) zm$#cLelFA{n$sumr%>7`QcmT7Nf(l@0e^sySR|()U!Es1P>Toct1*Q0 z-Svrhxtr`6Vu5`mKMD;QtYha)r_Ie`w9Wm7*qHGf%S$Nz|4nKoEA2$hi z<5A$@-aOnn+RdjE$Bh7Euvj;}dPwH!(K?2Tn~(_4=F=Wn7*(4-*+j8&$`2Dje9F*D zi$$U6yw*VZv)J=!CCJ|i!XO%xGPuev@uNLR9S&)d3HPh77$_ezjHga``0?!t!g|6l zI)efWcDy_vN6yh2TNp?0J<(*~Ik_d(?|El9SOphGxS7SWG@S^iF8y?w)A;o$nX@ zpd5slCHH`yq2>iiv@*1=ZxZ74VxCR}FVGMha+Tkb$_s|Qf`1Nxb{f!)d#!J|??7n) z;2gO$@_*@Qm~5i(=E&aT;eJ5cpNw?`Avf`h2S1}lAcmV6JP^`nKX+~Z%BR~+MM~AQvV*!zXWu0EW9O*9R(?I+b?lXFQ=G6%Q}@MD32*oK^iP_8bOIS3y9RGn!RuwB6w{$O$!H6W-^L zwmu94!QSMJ#(B5%he!)j77K60K7&55EQ4#$Js1=EsxK(ZQSF%`V{#ijd$QVfibYv% zqFEW-lkwz7WFjN9 zmQk+gKrVAArXv4-aaFvNlTk;~`7N_K~ z%JBWB*aqiM6Z=WvYC#}=7}Z4zRO&4z%O#DmabP1MlfJJx*c*iQ|B&_8VQuzZmv(^S z4#7RROK~fd1b6r1Qrx}83L#i=hvH6gE$&|2-Mvt>K<~-@%slhGb9{ec8&DB&Jvd+r@+o zcY{@kw!HMAavuO8s*LMl&{lv<=+Xwo3=#WDny~#5(YA{cN0x(RuBo6AlXy2rxN9zFx8>buClmc@vA0C}K3ygq z^S`Fmu6H+v z@@%B4jM$OpH#0=PZib23F`0&UY~;5mQV1NC!Z^f5PvnGx(%n@$>ep&ua})Ag?O0*x z2p>F0zJq#OYFK<9_38s^fAf03Kgtx}3O~f+MlUJuvnb@%o|~U|5EX@$$AtWRpbOU) z$S-Y2j$;n{(i|thN=2>Fx8GmE%Ela+f})}vKn~!rbh35pc2{}QkNb0aeEqIYy@$N6 zuc)sLXw}3Xv1!p79kb;0%{NPWFLmyOz}YQcHtPumy_zQ@Cd<@11{|jjAWR;7cqR@Y za@!nMRwDjBcs(IRV#EA~x2dsK`@JQv$Q0wyCmfswGm3>l!=tJPrEJ!dZ>7bV**y=f z8Pvlc=gEcb4;(!29xn>R8%&kwa=Kxd!54UiWGzF+>&7&2#tnD8Z@tuVvi49&ttq;MTQ|8ir7MScWInDPdZy;T z-!?qK{5c1j?)o_7bKSdmB@)N`qj2UnFc<-B+8{CDqW>ViSm@09BM;@$Qg@NDDdrAv zBJO4_$arM6O1#l)w>G0uoe<3?2s^JnE51STqC~5yOGU;p7q!9z74RivXeM_`sUt?V zBGd+IL#pw;jWDK%AO5NgHp?2cjapfZcQ7t{AIfzmJ4Y9+G%HU|Q&72YFsh7kQ4|$% z$fW49o#LG|6Wo>{uwo%XM$Y79R%EcP6=Vy)xapD&k&W}jz3m}2sd4@?u9cLkC3jt` z8=*`R^Fc{oeoyJ7|F9;tjXI;A%bKPt$>xg!C`7(3Y7_Y9teG2YDX!Sj*ea#JG|&h$ z{U$)LO+;Xiz6yPaBsoT_43!b4!aAy9Z>E5r353FIRA`T=zrHEb^ghCra5eD}L}}RJ zP`0YNEOyJjG#P-lkD@g@&|4a*dj}13Tn7Cd%;r4N-u*r@$232vKgQyPIYEUN1#KVr zfFog{yy6Q_gy*T}-Kmbr%T1kwlit|wP!ZwCgjGdG)`EVjD*h2;(v`JOqHjz zf-D4yv+7d$+5Zq5wTIK2(T+>A7BjSSZwWGm1aH;zM?exZ zb=Mjsjs@I)vw4Trv)`BAm40quOaYtPW+p%>$1~CrRmF-Zr_*LY(-_M*43sIJxbJm{ zm;0n?rmmXsjg=yYfnxDei?MrgR2IiorLfEKuPudWjWq@OzrDZwY}8`$Bcj{K#pNZT z!xWz4txI*Rx6dI;I8xq4C5VVv!|7!aY%@`ckv4vLM^zH$YSOkf%t1F5Ad^WwEO73z zVaxy3&`}OEI|*STXdo2xUO4Tu(fnQ=0dHUN$c)5_<5|F z_ljtjhC}0(p1Fl1X_6=}Bky@na!1{{;xW5x5ttX|{YkQ&H>V|$>xDWng~ZK9=!pxx z*Y$4XP<6~U&T-y+$0^XR^2s1cwABiaJ#wyZqh8Tdp-B9>(7FR7+GfG?ZaLP9Xkq?+ zk(MZ%;Or0YJ^j%fE#82Ga%@ZfxuFZ*-U>NvRUa%%k_oQC%zN2kKB3gKk6*ibi&{}I zQR**++>qL_Ek6k!NzQz956;T=4;$~^sQy)VQ0OX>ybJ~-O@9uBwuyo?fQ2FWc&vdB z*H>Vp;BnwLljhR`Hi})9j2rK~Tb+!XO@`K?nGxc=;-#<$RDW9AfUxd1i^1mN&$X4A zd^XryUhkFLWR512kN>E;yO(KFw(mLk-gBl320$&-DLY~`v4>tf(rL`pP0Oc#NMc})-QcJRWA(Ek>0o|G)L)&ZjN*V-?ZEKPVI zr&=6mt8z3#-AwL~7HBp5X9eK^dVY z&o*aHBv5-!kd@E7Ehwmu=@<5ue-!#&>O!o*ZV{V&neaMc{-@?Y)prItj&3fnKK%xf z#swRpc5}WuuhwNlyE%J2Wkg2BkGessJ=**G~y4X@Zidshyi^HLtbd{wgDqmwn z%S2UGIvwB^$*q3KQdc3e{k_tf-wi?qOcJywWw2yKO!J|L##As*GV*FMGV*XBkIi?w zp=^=PC>XY@V7SnJfs@s>>vi$E0?sNu>F!Y5E zHf+xBQF$h|*OQQ=1V|hQPKL48kcae&N2y=!nrIKL&TR*~s@-xT1Mn(;I+3@#V?RmP zB^_zJ3lKcqsIZ=3E5+|`5cdsV_A+9vEObI<2>Q+t+o5E9oYQ4fYsrOej!W&`JJ^Qe zHWgqzt`E^=j5utqBl|Tra^kROLnBAxphT}=@34W{GINFlZ50R?H-dykJGoBBzat1h zVy69L%d^%-z8K|4-Ec;HGVoZzM{ZvblUa3=mEi!IY`h!_EvqnRi`^&S#cru*agU=5 zyO_3Dan#Y#nVIJ&P@+*o(*K1{>;@CwM4jp^?W&z1ae3A>gVoe@iKd1s6(;89RQbM% z79Iq;AZ~uSkofy!!?Ui8!b6ALe~>)1Nxu~qIl5T?)*SCdv(=Pbr=dmt0gE+o~m|;>iggBksqx&2Gz3o4w%eK?5(_b6Ae{vC2BkvtRFup$9hQDwvyC# zMtWJDPpV|QPf}YI+sCn$MR714#5?3r#&lyIC&bx#ed+1^axQT#XBFj!OO$^7Ld8G;rk;hUgZyXD*sUsv*<#pCrKkyIT6vABxB=&qhSW`IfGZKx06 zgAC$Eh-BPxQnp;9n8X$g`YqJfxX%@*`cK$6*f^Al1(j*NfQAYm!aJrq^H2uEmCx@C z@$Vc1p%YW*)5Jj=-z?z#Yg8c**A6V8TWSqVhO`ldOIYN*r_zRqbnUd*X#hhn?x_JC&jWAQzP1rDK{geX$~2+T1Fc#&uXOC#{yR@_1Ff^qY#@zo;L9jT=EF+eE>PAznz z!^01vWiWCpy_TvsVE?~xN3sS)K&}x!^_oYk^#Z(jf=__l^;|obeqyrFf|U1pwf-+* zYhWW{UMUf|D!GQ$0xscEDmtW#dHUV!$PRda*4I(>6%4XwTiw(7NkeCGRg!o~~D6Z5*w`?pW6mg}fI}fx>oh^CA_qbbbxiK9)L(ko}!HqO$^7=^8wl^kc zg{_od>BK}Abud;TEFciKIl87TAWK(WW9J4-m5T%9kW07K^-%P!g}uPd7x%g!UIgrL zLB~O;&#L!&n>73rS5GZ)@V(lF(uqf}Wd;_5<<7;Akn`vOv*+X4A^3Zs_Hy})- z^2xP>zrj=FsNO@sMwrb=mqtSgso2iWJ~1A*s4(Rlk3iRRYR>gW!7$`;^YEuB>^lk# zz5XBGk(=hM@^K+5W52Pvj4a4}w9QYg49*Cq#O778tAOSqK$b)7J~&eS&6l^PCOyL} z6wHZC3QiXH#>2py-k_PLr(dW`nAl8@^b{Q?DAi6x+3oK2PHTcL?Cu;Lk(iX_1)*rA zEY?H@I#|f8iinn^QUIZfpi0#IJGJ^s@7E87cNFK`m49Jw=Zo|+HHmd9qj=TbZtzso zZO4Fji1h{SKa+G#Ihr`z^uMI?Rgzg-evmDTieVN`SLo)skM$1z3D`$$@`%nhzT{#$ zu&6#xEx3VvuLvYdFlhFi>S??EJ2V!XiK0Tu=izJ6MnX5Wu3=;1J&vK8*|){381hCD z6;!~8a3HzvvO*WuZoB}2sp0c~?;lVJnvCAdv~Bx=%fo1Xwe`cP|2656zIbw;vA@TeWTX!*BVVzwXw6eT7bXk5j^wMTt&2B-KZ1pkD%H}99 zpMrWh7^|68^`O^p$_bhQP&P*lhT36JBBZA{>IVUt6x;S4NPn8RA5kDoSN&1Su6=2r z&}^p^j38vRx)BuQCo!3F1Kb@{mtwV%0d)df2&X*Hl5Fr+cM|LdGi>PU7l`98SI0B1JwOySHim zR&8p`4oeEe7qxO)ar6zBJe^Eg&2jN7#rg4<$61Tl$?g@7qw5!zPG!uB>AMzp$ru_( zyi#r|+1n~r)9EsH`CO^u@6lDFTlvT+*w=kmCmqoD7MxR{j>7<=j`zJ8GU$ObyKqA> ziK`V~vtH|UQ|1uiaK-uv>Iwc-ZE(aE%EGN*koX57QwFOs-+t4~<`yoCwlI^wfuj%E z>^{6R&!UYkXYIPT4aF23-ZqyJ^}6$CI*P8m&4lR6;s-paQ&fd!DuvVO9S-K4smkyD zAmgp|_EhYY!mCpby*o?JaWp*lIl&m5`Ia0t;q~@zY*AmvJ4#g8i!CE53?_WVMK5N| zb;VIvt=2;Z;_;Pv73Q1j;y8a)dw)GGIL3qK`JZDEil&Z*F&rIYy2begZ-_}yc;1E zgBOAPSr%_iX)2z|WNVjhqi?{_%JG%9x)oMNf78r>N#dM*%CAgp-R)c) zZtgNYeDcH__!{#K16thgs@FGybXE=8BOKM(EPS2bdd+K_FYpRJ(^i#&x5Q zna_c?osIWD9#ew!5&$neK!svy;=$ZA*3F@iu4g&a#5K_2AfUEFP`GL4>$ambSF3~^ zY~1qa&$SioyXZ>F1h*znVy_u@3ry9ybe%$**!{z*2r`iDmE%u!X#`jO#fJeskykgs znS1bW;5L=@@?3ZqESh+Lg3OxXMysx7&sLO<*O%lSIiqcSXMbG)v8x}8om;j-9kIr| zf(nJn(3B_0{TG*74k6z^014+flA>J+qyQzmLUDR?(9Xs<4YISbJncd|&JtRO=AWjT z=oHV)8rVsVP4m3ipr0R>`Tkx0WRo>jl7YYDOzp&H)KC&_k)Ly8`m@p;C6%S+Ut<}l zcZIW`kvvM)T`X^f%pNE7Q5I_hRSm$jO8n;gh)72znJ754aVIwdE#k;m{ptNmbJ6sl zVch=!fYP6}*mtLs&s(0d;6Nenjql~u26fZp{{WWbFNt*mDGI+Yc*gxb=!A>twc{hq773KmeOe9zY`Uv^Yt5JgWr!569_F_@DK1DBjZiDPD z>%wy?!pt<&QdQqo8yP0EqN|O(HR*H)Au;s{-wRcv;{Nv$an-tH2LOlws*QJ#NW`L} z+6S0tWLMh=Ru`HPN6YKHw`fd6J>%;@rOzqI%WXfZV$u?wF%v1r%U}i3C9Y|=iaj#u z{_nX!>eMn9g@VNqa+17iM&ecj_F+ghQXQrb_&ssb+kb*CX`J36(b#(}bB$cD=Y{GC za>!B+Gg{RiM@`|+&uBsEj9XCK68zRQE^})XQ>I_wq zTnM)q%#5=-awa3bPN>!bIMrbkmNLQvd_YzRyx|y#bk!%n6hD@)sJwy9$!{+Pn+znG z&vr%ab=Xe$IUrX~2yZg222#Uv6%G@A&aEU2%s#X}pT%Zk2k)vOxJ!L7ZYXdE`o;f> zPuDZ$9<6^O+qe6X6LobqO}bT`W3*KBuI=ywvjqQ)*uE_`r)8f~RzW}*(r{MW>j6w$`$K8V=yimz7NM)2p5hFmlu%*3=BL*1M!vXf9d zw{ku9^IkaM?8_>ocNZ5C;SJW;Ak38Vua{0nw(FUdsLpP8)ujrU1iGKw)FIIhWA~%J zo7>I12%a-a#om_$y{Y>08bWk<2!iVaTUL%OSaDbu1K!Ce#yY9(;DBis|QJ{D;n?tSfyaHD}I zJt~N|HTrA`A8AOBg}>B_ciiD7?H90y3M+3@1>o*(LJR*lwHD6Z`tOJV!d97>wwPA6 z`5B(#(o3XEZ5cOs6Cks9jWz?^!Bfr&rg(yTF=GGkK!Oq9&JsZiEN6xRO41lf_tQM1 zo_vLK$MiLb`vgU^$TV(nwrJD?ZXv>8sMK;X?z`0j7P!TM^S=)m3XpgYAJj(!DvJVGHZmnJ{vvR z!B}TjI^n!#xc%K#P_{vxY? zSd|@&W?K92n{L$j9jdZuKMfX~!@K^Ys~O!f8`@oN8yQ(pvAVy}v(t`Nd8qu`kU^^u(RR&T+XyO8;WXV)6l|`>b#t@I31Lm1eRX=MF;E)k z(t{3$QJB|5q_EuaJr{&Y-|T88XrM&3CYrW`r@ywX?hd=H2>zR0O1^m)Dw&S9=qrwXdTXTjn!GT_uD+Vjw!oLkH; zLk~H2n-~ZJHA(#LSqOUh!qKv$KvgjWMaZuB;LQy2#l!i3vz#=5mQCJCHdne87dclsH8-LjG@+VZ`Bu7~x5_n~DTEriKH#Hi>t5>A?r8^3X*h_J0qe`}r& z7xN_Z3uJkWD_3H)5o$D^YT#e1GH3^TW)ARi!@f3Z<7j{)4zWi{n5wdFR-{RMR3%5e z3x&8aCM(x!`Z_LBRX4LsL^Up`Rb_Y_Pazg~5W$o5aTa81&A9$LAo`l-b(8$4QTs@j z<37W}F+HWJpvjDVQ=%(6tZz|bvY(KAeGN*cl?msLy&?b!s+@TqFRi71xF=>+ba^Xe3Av=9-M1+Woyz30f06I<`C;Rd2o zPGbkEn=^7!BgRfcof9a`T2|sW1VLN(;8+jb<4!t&hYw2PcpGh_lGIoCwW$=O`z1Th zWRAp@;QC{|n8CP>bp{RX!WuX$y-XtB75Pn@ACWw`0EK`%AY(qaTDz6o&ml{_Jyh{( zB(>2iC5d`HEp~S3u#3ZHqWC@ed?z}K?hRjayPJ>9j@?GDD4}4Y_P~0yGlM4YYWn<( zcuJH2emT|>$=hho(tA_xRP(P)Yx0&^f;!1ytKxF&cF?yXbCAKN#$7E|0W{`9Mx z7P0SQcg$tt+a=^Dw^706$b)jzbK(_d#NWH;Gruwm2Oy ziF$d)Daks9G4)eG0T()b^MP}rr6UNLTQ3gUQc}+b4OJ}q7VJ!$ zG2#X|UzaNQ7c+mgs{OK%sq^RP_UhiMz6|#A$Ee360|_{#X2HSfVkx$ASRkNTqcCmo zLF)cf%Qr8?QSm$fVI#)j7V%A^=B+*9GaO0I0gCa@ot)5%Q&d+RK^*w3vcKpRc;fX} zcAi?TjX%M~Fir0Zu>@2}hGln6brWiHN<(U>`OvIb%Tvi7`qBVLhNW|zwBW7|2nJr* zIIRH-JlmzgKe$(P8aXz?Y$_-#L-giztqshnmHH*(QYiZ zwJ$$0qZU?{1UV^@KU`6+iB!ARVu5;l)}k1Gk+kmhjkUch`s@G6Xng%Mz5HRG?cf7H zO{d%g#-g!NV|=NSi^?yuih%)dV!@H+v$s3xBP;7cj)SXo zyw00?>z;2eI^F6*rDFo;=o$8FjHo>0I^^E#1;EM1VbS&|HVJgfaU zCK}n6LeS+zAVYnfC~L*#LFHE5TZ0`yDHB3h+$!naXJ=oQrK3h+z(YUPRJ~Ik3z`Jz zM{dPFhB&x&snuxj(?-TP9J4JdS-yAF;JJ@ahAUtyGsGPit`ZZKxY94mgoWv_$-mW%#zA2t`8++(}yVoZ7dKn)6 z@m}S@b%@tsY=c1d_$T<3!UEVw-r(dL^ohNJLp2OD^ke3U*au}d-dXtz0auY#{T^e- zpT>^ZndssO&4p_<6wuvgwn5i(rdZ)I!v}f+SklQdwxi5RZp=4iAv0M|uqJk5<{6 zR~1@p1_Gq4i8Z0|ws_8iQ|R?^U3qP08QYsj-rman%@O_k_s2&(>GXcCv4>KJcqobJ z2$MJP!~9fpXl97Lf!?#TT!Et{Uf^_3UD~>`G;lo;hokk}D88VeXfcm7)EA)eI_b>y zb8_VPDhbgu6w1UPQuo4*HrcBCz92syWpFD_(Lz9V|Ip1WI`xnqO!#HINa0$DphLTAL9u& zWnu;NbJ2SJTSu03+uq)#q+eEg>nS{K&P$RuU-&$vyqvCOCZ)qS7F%mtgkB$a>Mijq z7pX2?rfdP9-qSEorNj4Sjh!+qv4`2tep54ID_40_7?FG&rpObq%zl)y`Z~>?DP%o4 zbGK2aHAd6ynxJ4jcNDzuX_<6Yz?sxVG@)JMS(;b%P4&Si5IR~bxY z+2^{jG^IKgWkmcpK>(Su>i5WE>=C!Po}a#M7!NVloX&jpo?n0Onno;zJ4N=HD6;|h z8=@0TbPjoCGqBuB+p+hWSb0}!Q)`qEvL5*Rz=3pT%OlvZ1!<+^XGI1!A&;?2(vPn~ zjW>P0J~R>x)t01Um#&!aI`K{>{wU4H5zdWASur!Xb(VO0xK|@cSzPYrq$ju6XvujF zD0mDpz7yS#jmbyL|H+DFk=)0Kb32mZv?9l6R=ZqG_F zelteu3Bq2v*ZZVAIxpg^7sXr}J0yoIYLzNC$&|HxLLmR2DguOUwjdAh7aG*PswNvn zWyzm#-Jj)MD$VpL*w`X>V)FuDMaZpXYI;%Q^!59@0SLb4tsHBQ55gJTt3ZBo8;n8n zy|Nx!R0b3Ce41>%C;7g8R={%fbQ+wFtB&SO^`QxD9EFCSi~*p^!)*a;j-P9+cfnG zgn*3+yT>Kr@T+wZ3^v^8s(-OwZ6MewEaIN-;_vbd3FCzy3(Q0-y?;b?ixb~jg&?WQ ze?p=WLIdx78rP8;rT){RB7lZqP5cgenV|mnJGH#o<9E*-txtX`{qwz>4sY6luB*n?yN z36(fv>d7|@{f2>38;{gyu}YF~9x6FQ3U|Xvw>dvF^M9;k-t)Ep-6`ra7{va4O?QD; zvPaJL&ky&O@xtcfeX=UcEZ`C5P4`+vdKXheRQbbB*`w7{zu;A?0Vk7YT0W~(F{>1O zdjbG|1HeFLaRjIXPBB*556u~}aviGn#eK{VvIGODt;S`yy3QSP;sY)*b&sPRcrn@L zfhwM3C(#4*@;Z(OAU0SqpaPQ#LddJCnT~-;wTbR8ID1<*>I*@d>2xT*f!LTB#}`W}lM9F3hZs-uF20V1L6T4!Pz?Q zuVQ|}A`zp)>QO(eI(!roWRfcoRLy9(Nqc#+d%>>fHo2lOcgnKSqCJCPB57Pm65BY}79S>XnNPrqOqakznr?32zF*TD`ADX>s zoA$084QfnecPPEQ-;s&Ib{gD*%2LWUah5~U+N>BiYu`{Pi$ZLR-vv^G>XKaBi(zD{(NiH=){w+<%qx-HRAWD zufKmZ>kfNQUT{a(mRNN2?oV{kk#z{3g$>WSpEJ@j8J4Z8zVkzCK5`8qy0i@r!PpUy zS7&k9C^LIBWlrQ3t$3tQEs4je$Rug?(HI$_K5VNw6f0>=I5IJ#MB8p^UgS|`CK}PN zHlE(Z-?nhJv2@D@NNhcHUIffVS6doB!m4h(n$mAezr=~MV1onK@2MN zQamJ}bc-yjVkfE1F~EHVk)nd(K87*9v11V#r>eV>slh6uyybzWL+U`>%qqXCr{`sdk z(I`@mC6ftX%G#;Z$0KgQeCxDG^Z zHLX|W%gz5!g+su2?wRqLR&0%vL)N@Nz&M>Q&ThiD3()w7OpP&T9_ymj=Sk6<9^Zbp z$$oAz7vet++zlpU8|TcsX4ZS=R0_rzg9SbW!OQg}BH*6=H%EjXhf92MhSuJwQF3yG z4i3LLi3DV_ysyl&0y^RLHK(m2Q>i!E!s5nTS@+|KHx0a4NWeH4v7UuUNkl4qGPZI1 z_R6O^z);5PostW!T~Z`!bk^n)x#cqjk%6o5Z}L@jV$KAIhO0p2YDZat$S=`Ovn=)D z9|tq-i!j<;%NGq~02S@SqA=27-Wajn(9meiB5M>XpsR)~$083(Q{fL(gIzT~1*ZMP zc3j;4GM-G~U*~+J+xbz=mZU!y8$GsB4ceG97?Ru-OwOgS5VZiLB?w4B8CN{&d<2A3 zJiN*R1Y+@&W5HdK%6Eqs*!GOrCia2QZMgRrEBirsWXrWmC(GPfO|6luzgoaz#ajSBMytvHpEAc&mvW3>SmR7lYwn2h4o( z0p5Cv%@8Mz#ys@)QRhl_>%EL6wR9~l{nvZW>GZ|LF9^hEeCF# zS7eH@o=E|PzHo&zqP2Dv0aeX1WRYMeb~~19QfvWFr&Oe&DJluG->6+^>};cLdqR%S z6gHNlzF$bFvPDba!#HZWt0cfK(AjBkG)KZ8-hWTKQnl8o8>sa#dWxAL#6`?Bh=odL zKF^s(m<`@|mE_cV;|w}Tcq^M4>g;R$VCow-kg_3>{q!s{zY`$Tvp?`r7CYYYJGZ5N zIJP&mqE575_amFNC6dubdZCB89q?Kte+Jy|?sBSGvA+g|5`Km?D?TlkxoC=Wdy-UU zwXy#LP&agI;ttraUTyO58J^r+#2)6@fPtL{*+VTU*6*Xwl1ZDC%L@2V-C1ehm#9G1 zS$uutjCy$ueC}>90{=ou__N&GEHhO)9=2O#rOu&ivg5xBL-qsxOX5-H0=ohALDM+n9|; z4yUJh(On|pRQ~&jD<-dTeJ&Z&85=oLh6G9{2Ly(Q^{i(qlPVn+7+DHkfZVkP@zgOl zROkT(+IRxLxsHG~os92c|0o1&D7ITJ%u8}J;(xSYa@{hcacJ2l2PKQWk2gRye=%R! zr>+2nVsHeXyW(@}L4)8yA6n%cIx=Pc_gf!9(f>n_evh!um0=dUPeZ^DZ*E4dSb%lpUzb7DYC_jcxo zP(zdd6UF!65y8J7yys)2u05rJ`?S^n`se+UqJDJhhRf#r#wDlJ`M)2_V1hl8%NjsJ zkj5EzHBI#84DpmT!M${AAU}i@27C=$+W$Ak1Fs?~5FY&T`JaVpC|Iu1F4_rSTC_Wd z)>+aJ^s^i-o_Ba{4KC8V7^+_bQ1eE?>M`*678$n!&g=@-Maf3-zv^(Gi##0pxCZ}e z|G($>zefzjgJ>8)MLMvttB0VL%aqHqB=-P6WHh2A~h2cS*%P~WGD&jy*!@jqPRhu#rSj zoUwUt{MCo3fy|>ik#3JN%ukk!v@Tbd5=7M&Yd~M2^QBEsL%YqJExQK=*PlfBSpQE1 z+9{^A2U1f+M{)kPkUAC4EcaBeL5I8>mXOmUh2h^c3SX|OcZ)Oc?FaBt9VJrhmfFu0OzgrP59oeQ3D@JvLb3$Mu%&5ehX@8$hq%g z==e4WG35Cb88_K(0rwWX6Nm}EioVUpFhjswk8TRS1n|R`xBqj!bVhel9bK5YX8p8M zeG^f8n5S>>&hT`-+;l~Dbcpd|%7TARBWvN}4+i>C&JCPQ_BljEb1AznWY?s*=D@L~DV=dYA0bO@SL>w=^mVJo&TfYdKSP4`xz4!E^9(+f zER_4TrK@B|tKjX6wh1?C`24NB9BU=ji+hm9^oPh>uRGqP#*K`x?8{i|fnwB``KEzkIA6np-l4rA zIib^pBa?0ldu64Hfk-55IXU+L-+kSSWZ)_Eu0M0AXNtba&D*%C{ywMJbU5c*k#c;I zah|(nORTot&oTT=)o+W``$)Lcr1i=@017~Y?-E%O=?nNKY64`L2Rtbo=DABhq@=fp zruVN}qQ%?Y%@BPrgKe)1u9}l%Wc~wS@}Ij)DaX_hH<|5QNn0Dtfb^_0cF;xbyk%6k zcp3g=H&-#Q$N)HAz(+#W#})Nfx!C+PT$L1gcp4~>UU^pMJjW~Qp-L)dYVZ)U%j!iF zbTU`u(N#k%5}`OYG1;2E9B{;gR{oF~=C#$~;N+yzBDVQAO;2&@ljfkI(}H%Fd%wT= zK0_5X|BZa0x(Rbk~(6WmJMxRBHqX- z&Dn^(WEFhN*>9DHS5oTMM`r-e04BG_L389QgS_LQjDf@%&uv!0poMaF3SoL}4Gth>(o}iGk!}{ig zhLlDexzl_fBph5=tY4|xCsx=tyMK3;r;ZVN3uZX7h})vcdN-v7YYs&iTI_ezr;;^I zrPt{nf+}b;h*muDE1YTc$qtR?nqpIVb-AJF(MarH3zL|*C|Ma3xnDjwFlJVZ6Q;OK zg{q#`@m^dZtxqBpZ_WK=YaefRExqy)oL7bVDPR_#_7kCE>B}X_&9@v%Nddpc(^*?A(6!0nV2Q~E zUSB{x#+3QyVUmaLt;GgbP9H4V^E>{5R3xuo95P+qkBv+gJ{!}riPl1<#E2}P@;a1u znI9<$Lh=F2bGG7yJ~;an#>Y zp2}L;(=+{($bU+PdX=mHB19`;hH>1pb_@Gu=4 z=Dl#;KNOi1hg_nO4oR%gB;O1%oHJAPU61+S3)IY76uENx&M)zvS9?$oBlS*rWco(0 zQ}`u)02_SUzZ_9A-ER`0vTaP$DD~WEXhx2^Ukm}*sl8;eXx^}asF zznj*7V9Lcv``6{jL?l$AdVSY*;6qWDe8KFd$y~U{$TQ~k?2=e{X-O`{ia^7!u2J_2SVC#l*ZqT8V5lPVr_AbsT>&$M z`F|{*b3S`RbMPW-C7%O6y-S4V!w$KtsOxBG2EiIhYQKlh@UQ)zUh6qwB>*$^u1{C+ zRr?WVi{KexL*o++1!wm0?^P=F8}78megDoQBD9$SO0txY{-(cu)YM z1y}}qp==)I&O-((&xbeu?K|_5Af&7TN6c%hYTBKY)dr{eJ*YAO8Woy2JC= z4NR81CUQ-}DtD@`U01UT*lB-B3l8mG{QX4T)xDqh8CJaw|Kpm&_)+;1eVh8)6r@ho z|2d+DC^Otk>YEtu>T3n4X$zYW`tnnv12w9vQsvhpvSFCjhaI`oeuBSW?44phfB9Ug zto8@leQFu8w`+-4ep@HZvRwEt3 z%x*KQN zH)@PlyZ6#pg#Oz7{rJTbW$G`T807WaU)L0!J1@}DT^UXvB2_+E*Kj*jEGfD)?Qq*+ z`xD;4oeS#l-*laW5BndAS}rPg7y25Efa-)S&=(-Yu8Z&lcC@Q*PGj`jz$?Za*HMlN z?L{YKU+u;A`0m54Lz|fJyC>;?06*6&{{ej0^I-wPMI><}UEfwG`0cv7GQ1!3A0CJ2 zrvTp>M8dfMV<0G6vX~D!2>OQB8z{*=d^1CsEFSU;8DB(^t~ObcyA7;9ks#Nw2&eL5 zX^Qxdi9P3ez`q|>3vaBK;S4aKq7Kq`bA;=s=SB!^0V;U?+^DXmh_yUp(JSK*v06o%H|1K6^?*DGez#}jr`7y`{_*B6x z(Xk>i+s`O3-^4y~+p)lc_{TEfF;=8c@T>QKY>)jv%`60K6u8M5IR=E_rhxy9iACm( z03ofFsODkjzfTKTI+A;L@d{X&L&QRFD9Pw=Dqu$#c6oYDMUR6 zN+l%IIN;U@>{@Dp>kaQ2D4-F0tNf7KahG{1{2Ms1*zS$`-wAIF5bO;d(x>m9f$+aPU`{)OWrXCnE zC!BS_+m&=sz?m~Eb}{nK4jvkVJhf5$DBkZ6TE~Go_nh6}et=__H+UYSyE`9;;BrXp zZ5}7S)7vokUjm#JT;#o#v^WhKQ$=j9o zeVrT>QFi-f?W@n)C|I+s$_gxR_5dF*mI%3U>!sB|Yb$T1yiFeb&Qgh9)2yd9&I@Wy zV)5Ay0rc6-WNd!VQwqXIMQ*e!RynyMyX-eNP*26LYk#)aVZ)|LE8lOax<9YFy<6}H zUA2Bzdtijq+i2Y`m2|ZbSDon@YaF_nOa<3g>^eTq1zR+RNA2pruh?(lJYWL{WP<1f zpdG`JEI0!Q_`@EiLPlw>taZw7amxpJc@E{UIjH>&th`eleDHys%-XYG!H#cM_t`T= zy%*-2(HX3Gv(h9Ed-yT4yjpJ@{1q#R7fUhW!c-FU6MOx5k!h5HmFp%i^u6)`K6fC+ zKvhOsjPp4F2TVkr!j}&C+luNGz|aX#9q?dvHzM_o$T-V3`pwv5FyPKbiB2hO;6KyC zc1$tKi+#|#Qn&hgcHI(=wD@C>-<(S9#}FTxi=v)v!DjA4+b(Cv7V_yk(#B@KwnAp; zH`%T9$&0e}8KI5F!C4c^3S`!tTGlZSGypp4%DC|TjODOFT64&k86It|E`5jErAba& zPuup=a)MY_#hoE$3cmMfB%OoBCW7SVUaDm574`XTr2dUGM%N(A*u&p~lK$K-4k-I1qmQUp|tc@1h%to{jw}XlrnawU=72OZ6&`svUaExsZEf zH8=F_uclMB&KOL6v01#ukhI8+i% zrm8-7bj_)E%j<69!DL^lMxshK>Q|_khEoDsH-BTsR3E{(;4K{4z(s}?B*KzRutG>? zLc9x(YSn15p=#ksw&=4}Xwe=c`HG>M`hY(9EY(k|Z!eQ`dZU>=B~u z$Oq@o9$qe=&^yGq3r;d1Z1@;*mKOAvlx9|C=bT~-bp>J_QbW!-Q#hIhE&R= z0V;;DdH1xpCK5Yh4{zHVG@*uLf#y{bFZ8S zm<&5FufAdqY0qT2{nZ~NFpweMuN3+Fu9dSg4WEBZS70+#<+4?7+GJeGfD;x*qDK1l zyP;yvczhlu&Vna6tTnC=ZQHNlI=PxOhVvGzkz~ChqR;?yi9V6L$*`+@0X=1Pku&?(T17?Q`BeYwdGyyY0N!X#9XV z#whu!#;oeqzuu9kAURX@4ab6hg#{rS6U7s`i+(WF(bBdUevI7CQ+8755%0~#{cAf{ zN4}>ShP9(Te2<~v6SZ%aW5@~PjLJJe&tf#`E6epns+i}L`fdx6+EUQy<9CYlE{dQ$ z^4H{N_&R{HfDISS_Sz2;DV`ibH7l<5tEGni4%&yr^D97&`0Mp8E8S?gVuxDRI!{&- zE^L^p=4CrG`U4+QU)mH)Yd{cM(%^C4Efe4Ul!EWG7&cwCELo>U7GK1sAh-9HAdgvD z5~ad7YE_=mc3N9-qBhUTCkKAp&3@eK8(Mxi-a0`?^slOKwPyzsZfpfxqJ=eKF?{_; zHHe49X^FbzpJ!+kncc89$u6uE_d}*eJVmxYK8R6D+P!DUw8NtJy`!{X4hd+l7r&^< zIOy}hBLM?53b!?MO=GiWik50vO9*o^zC9F7Zo#y0K@=T61{gX-Ar;SDNwPNJB zGEzsm3DpT?$Uo7Fx(UCFAnikwV#aEQWq~6>LFPC>*<*;?Qpu;KE)WuSCP+xT3eM1C z+mm20UwOOt@xAE|={6Z_;*ji5I`w1;Xydy#i!)fcDWu3%UMn%BYW5*QVVd1a9l`Sm z3`+1qa;(n{)zj%1Pr?V{3r!lG>gx7malN0%{BZqYo6f#hS;a?^pYiZ|5WhOZiSVeh zQgd@LwA_U>!pFxd2~d($%9G^}^^^rmncA)mO~1}BUzCo>sR(rJNj8uyyu+9klsY=HPl zw3q_=(NGasc6eqBHVQKi*-&YV8G@KYURjHQ(g`V3>pWllSRRl138s+@RT$O zXDAtVWU4-DNbGXuCtrpyM1TvEb6`aoGU0|NkffjZQahVPI@A)Mg53K+!a{@}clvHX zowkU;ppM`^d^_l4O>U5ci)GY)v+o&5BkvK_BKjjYrDBh9c}awrK|;DSG`+1;%?t-* zO}9}7-4nrjn_Ek2uWW2m8_o+Uv4p_JfV^NjQU4A5n_)L9ln=!-by_ocO_TFKzi}~< zopyg|N;4_FyM|(VEjBw-<*B02NtQP^&88ru2H_7@o=n!AX_`_#sbPi;_^Ri?CUlkXzIKAu$BC1Do+h(AwiJ4=Im4;afn&0!;hTgbx3n*N=d4o>sGbhv{d8RuQ#`igDFZq zBW@ZA8nye`WKXZRto;gT2|5*j>yj06Q`#yIei@e_%TH%~qnqO19pxJma;jEZ9{0o0 zf3ddPXbZzxE%wkvu_}kTxXIhBC_GoA%Ei7Gn?O@%2RjkVRYBd%)dS4OA z3OkRA5SAQnLwJLM=FP7g=A~cs7U~RQlwFkV_QS%Q_<4+D(gf-#<@TQv9a`$yHNG~q zk+4sfZ#q@-PRYgisHZ^R7phAvj|~x%P`7?Bc!-a_OM3xD^5ielexA00&sV4Ud6>Fm zU<{`w+-($Bxm4;QxTx#_aBb=qmjLyZS-L=aSE>_zN>UVR80#Ync>lchN+p^&NmQuX zTHZOF;eu@uBTWSqtJfd)-6#UihW7NMz@K^8;HtSJ$6P+QH{|u?e2S9hjWjZ|Wfu}Y z}~PDFj@hQIO^iGy`(4+|U4s%7o)(P=ysM>8C7I+V9YY4FX!zYXf!{v=d@ zz{k4#%rFuINeLQ9yPqekHNi`3HKELEF%7zryE>|SO0x?$M``gCJJXqMGgc_2pF=q# z>gCmcN|CIn?ks1#J?sm4UnybVG=Pyz))&(!6@eV^xjgA1fqAPy$Yb-T=_=SnRxnkQ zI>kQLPIij~PjF{h)0>7!H!~5&)SG4Cmlm{CiLqrkv%fvQm9A#JFB}W(ue+`Uolv2q zU5a*f;_#|kT!rfSUgKXgVAL#pE4{i&LB4Ii2HcJKstx+EK3H(@l8Y(sf ze%b1zExdSb)X9uTw_BJKB1Us1@zzRHU!^h}Q|!O-54zzyexl-@v$}F_cr0(FeGOjeJ>r?($5~pmpuy1 zhG&05Me`Ro4npeKD_CAv-DrmV(wyPo?A>AFF7fu;t~qjm;!sXrkWxl=KqdBDjY-bv zv{hH9s&9zkoRutd(7f#rAJL62@jm)(pgqIHzSsEES?Ot4?FF=M`~o`Nd)LVn8IX3d zGi}~}Y7?M!uXpvm)qfFJ&$`$nkTq_@hEm>cf_4G7dqVkqQ;o{FmO-=JN7I?JdSJuo z6^HOZe5CD=*Vp8NsMu+U${0$Npu+3lOub5oOj*bQHO>p z%%v=4k$Dfb9%0yvpjLSpwDn>Mu|n6sewImq3!Uo6(r2{GkLZXk^br91KKqgzF0cY#{EF^|?V7<-Upgo-8?wMk%uX zJSemllIfTg4HmR&juWDEnq)s2BHg(y2o)&F^g#Y3#1)0Dj}T<7ds_=^rJT-iML;=e767T%C$EhG`s75wUs%q~<;pZ1V7YQKPyD2QECcMn%3nY;Kr(7i{F47% z9uLO|E=pk$S>+8369y5(f@}TS!NIfG{xVwR6I1a(+pjh;n+262%yV3;`>x`}>z2ym z0OQ;+JvP-b>?(GX=SR553oT`zLqckMk2`5CE8+{qizU3KIuHVfU2c=v@ehn2OYr?B3ptrGK_diMq^{$9KEf3E!r`<-%Y!8&qf z0oc?|q7B$l2exy6txIwq!#cvypbHKM`FFSPZlP}cF{he|iSPAP z;(emMV^(U*L&z)OBXyNJe`=chF<@<>=|i7bft4kD?~T`c@=^{IGxNV#6Q0iw^6ZbW znXA)Hls@OItk|`FcR=yyd1ukxaC--pUzO7-SKl7MM-N@ zup&rKNo81;tv93DMzn(C-E`>Z()x|wr!kzmvBkNX=Z>dxqmsn!%GXmFzrW~^>%H}s zA$#k~5+Osb@7dy5Q{`Kj^^O4TQ*7E^1*P_$ZK3ej}3P3ZQk7)N~M&<$F zz>>UxkYpZed`1!N~UFn_t+s9e|Z_zX_AhVTC;x)7XRd5$^M5Tww zx3XuxD}9@PyS3Kw(WyC=qHlSccq#uW-zUl^ApdE;ZD;UlTJa+K>PxQ!p2;xl-n2J) zAo<{eqIarx;(65BeX*Sd*j-F5%qFG03vR?@V=Mb%4U+`C@emvqB)*BP)c6WS%_C&| zv0D9uawL3wJxyWR^6@Wh4&kk@$I}vDap4+%YB~Jw3YnjiFn9rdy-K~-OR2347^xLK zKbAPBt22ndv#MdaV^qH9u%0p?^^_T-L&{%~dY$x(`9#YZF>ufI;E53-(qGlbxy9!{ zdrLk4KYEm&!<%DS`ppaIb;a`$?-A#t|06x`@ze{5N9VX|CU>L!vYC5MmOBIG|f z@=*M@CEd?3w@tkL{NELw(85OOy;Lu8bZmik zJn{D-NF~*$=>h$%t)qmu>ED{2QLqz{x0pph>HhquMh(-Pu6zI1u!PB0>r8H2+;5|i zacd4_-WFAU%S}6jq3>k|33!%U!(i^-(zjKcYEN*F7f!T>j5a_pN0J&x-m9?qjdAXuZX)f z$5WGS;=UY0ZVf$@*8#h$Q^;;Gl44xnj zBb6uIM+SPaM?_pbF^>ULL>!OU)#G=J!K~qpYC)ZMI$4y8?8~N~e(90BFInQo?gdpK z&1_yQ*OJ{mrm+W^IRmFm0Mv}vgmMj9Sq5?<>Ioo$k8O-SV1Wiq=Qn^{aPK{^Wcd&9 zHfu8zU|@N3H&KW3Ikf3{lRjvSp=(Aww|kus1K{lwbCa8(4WkwYhk+N>AXxo!!8y^! z!v-LQ^~^y70Gw&4tUVe2xn~QIqK>#@H!IHT0Hl9s0P?!UONTeRp|)`$ub;Gcz1o~1 z86hTAYA|5npiFt8V6CneOQ=~~$ODG$d<=^OGlvtuqzxB1=y{nLk?q@qtJ8nX1Z#Yi z@{eb^<9GxP-3s0tT%~$=YV!gsivfYy*&x8sJV+5~QoAyXS~q#}fC&OOf3$xNe4h$r zC3|W-w9#YOY*LK}shHG&)z1@u5yJwEHUz+^;V+OqYR}op7f4yh3!-`8`_k-x-EvPB zT;cW#QoY4!-2qldK;+IvB=e*1pV!Vr1CF<AVNUgj@s*O%mHH==wM+U$XqAIqPhPDLOD7DeDc)EKp@lyxO6~@ ziy;OzJC394$TJ173)#mOu&Psqi|yMw8^eyiYREbCimySiUyi-Wh8JTyy>2p6{ZI&> z1=f2#oF#&e0X3&M2JI0iB&MAaCUH+81dL});9MW9(Za8qiZt++<3CnQe=yi8`t2`aF_ntwnfy zdRGW-5+j%wT+qgN-097;GUD2s5xfuI-Ik@O^PtCjHz|ZUi67GNZ7p`=t~*29`+$*+ z8g*5UC<-nPu1Bt+rV&F#P@ujB6Uv{u0?m>LuJ57)qkt?Uf^xQ20c!7gPA|xs27l5) z>wE{_u$Og{t8|chkU(G|;$%ixwvw8Q3k?1?39a~}QPnq!grADp?VCkUPsQWAvU0R; z=Ahnwru#Z6nda!|x>{n)Ota%()7Le}qwO{Y%e@_%9iJsF6KHKk6PRXZ-#7-rIoiW~ zwRgvUYdh1zh%cbRR&K1##$AvT-=H6VeqGu{17ijlUyX#yI+sY)cAkCW%;c9zm4w|x z89WT~NpJI`O1ZF>?KpRAP{Hc9?Kh{Zq#Q6aH_l^uEhwt`ez7HB?OS~{$Gt?Fh31Oo zVGvqIH&wTgBl_=YK?LiwaPO3co7xO352S^(_{N%{ZT0O*2A@Wgl|N*|}ze~u3A zQT`Aa{P0a#u^P9Z)L~JO&y>NAGy|3I136a*3afRQUs`y?>w(dCzz>@x*SimJM47|# z^QHRZmBti`((~#vZESDg6NFTb^4k?$3Ex$OrpbmWO)$Npb?&F6lB<2(fx;lMnF^t? zsG19}n-hN96!hA2b=Y^09ao=GjU8e`<|as4t$}kEQs-Gw`?|2~P%@D=OFxnc0hb~Y zKbT&FzFoZDZ7KFG_3O7n3kB1Q$26f%ByzEiFCcrh@BzfjgOH7?K5GSv195Y*o46KV zj};O*Ecvft`ji4m`?Oi2Ie-pTR&iOT96uHWKUpYIb&C`cKdFxiWK9MI*8JAZ)zidG zZ=)&4B8!U*lQOGzi;yQxPMMLHjmxP<9SrF+6kBvm^~f3e{)<+=AbEfUpoPi@ZjnTq z)NKOieVZ-3T$)yT{nC$}k=;z(Eq_OTN65& zC06`~+&P)jj#@cAqZIHX_ zh7NXbs9iCy^B~3#eGgks(1AlfPOB>z&{401_IKyCTsf7TO2TFK3#s#Dz3n{fK@F*d zX{mJz?zH?;#ZOOEai=*A7brc}>Kx4DA96QfZH=29etZ^R2TzR4!+)ip)F=3&MV3<) zT>l08=#%m&IsIWSR+&)!$J zLQwEkkZMq@`MqroVp0~#6_(UGB3U%e@Hj$)3(9>RB3T3?HTSnHk|Nv3EetnjlWx}o zo(+xIH%5aNokJeZF4>*%s1GCjEyPzfEZ7#J#i>5@R`QFtiQ>{8UYk~o5gS`dYGq}8EC$umYTO0L_AzVXX zZ`Kx|>~&fb)O=BS67>S=EcU)r@L?VdLYv%staGSa zC7TtR3xayvC+YM-7fx@?y=|l_pJ<)VVxC(Ww;h8O(ic#G^3!>3@2S;V@mohhZP@Wk zg47|zBTXiXL7%OKTKH|_hQ*Ay+(O4qgivLtbjgh1g;v8gSaGg=($FcDOHSOm1VVD7 z+|IeevPtOeg6N#biTBBewrf3QW@dn_bjGapz-hn6XUaFjlCHLB-}97X=y#Goj2Hx= z(mP1Vh^lyJy#`GXT1dTD+Hb-80u5B(EIknoEWh`^3fnfs0t_L5exO+ zz-rLw2hb**tcG5x#XG!qXub+)Uyvg#+oUeQS?3uoC@2tk1zjm?-SAdH?tT7Ai0Bg zb}cU;AkP7CxfJ8O+5vzaH5-GSEkv?7fF2?9@co(c}OU`WYf!9Y8q z0F|N+CCH&ZTBvyNIJx$N)Nkj)VqxO1-V}uXxl2f=wy$opH$|m@1`lZhgT=bGCVe#bU>ZzFDR#QKk}{m@b5nNhO=6oaklgLjXs6H zDQs8VxEo0Tpdylj4Cfd~?j$Bc`(u+F)|p6BhK<9>dKR708Pn6v&E0mR!V73&U=m;J z1qAy7QpU5n9F(w1f5duH*Gr!$P6X_f433lmRuaFd?yT4bTI8`DHsQ{zSKph*5JV~j z@&Y1_Bazmz)rcH|z(_X1i>*W)o8K}nxL7`-{HY;W_KT<+OT*+7`TA_CUM z4LqHRY?u-F=6KNC-%LGo(HKgYm^@xUEmv%n?v%Hk&MhJtKF2Z@*+H1z_^>GcKqdH~ zZ!K*ZSN?Hyc`|B6bCvw5AWAm<85MYA*vm{?@Dor+-No|sQVrmcfiuR5dP~AVT zfx{$v_i$`Ys!oJ)e+U%w0jjrLgKl^c7E31p`Hky_8moG=#be#|&TZhdyYrhfeRxQ)ftdkyEx(U{luemZp)BnuMF1ZVmgoC`a&>X3GJ)isK2JD07`a(zVYJZh<~oR5qPMIz$8 zIufC9ApUOCrE}T&iSywD6V=LOLpAzsePwxL7ZS_dZh^0X{cX?+TSCX!dNFJExuJmtn^yoWmlV5Yp4VVEv0$g%+3OM}>W8kU^nYIU@lXBm zvfI$Z(Lj-*Q+i(o0ZYHSMVfy+tnYC`8sD^tOq*n$_-}UO`|6N!2CTOKwERj{D2ls!BbWy7A zk-+&-gpqE1Ff53esQ8rG>vZ`aJ&#NJUupsS|6g2W{yrN1K7rCdtpv91eKU2rR@IgH zZ)Rv4iq8c6=*eM4d-}i4P|pePcQ2qkjLeley{|kkpnt|uwYF#2a(Q~H#ceJT27Ae5 zY1EF5yU=OjP36V))QFW#g$*67?ZQN*G-1y$|FBS#*r142JfI)C9}WJkj|XD{gJIV% zPvURT9`M^fD2fMEP(Uq_S{UWtvQP9%G=3~4~|FD~F{;w~bqF00@P zae=eB;(q~UPS2H~F?rLU-vGvKmGe!px+`HnZPM?^@2)eo;`XtAkYKvq9&l;0W}Xvj zSMEby0H;fCvXV_s);w|mbRr)l3-ZJQZ!t#kAd-!`iQ_{+R!49>U|E=Lh3Pns=2ovb zp+b$s>LmlPobNYAJwEDCZTY)bkeXReR+NH}x4-{bs;q+$$@~YLn)pC)BRvZXU^zrT zqcdwD8$jq)9EUITY8L$$gi8Qmkqj|DvpSZ;B9+{`iUJF60Emqn_DaE$;MN5|ccBSU za1Oi_VxSHNB*K@M0f}xz|2nd-_0BeRI!SW4FQX%x;n!%IJVzLkShND?Y`I zL!<>jk5FDBaR$GnYi4E(0C>E^ayXll+xx_ZSVA~|XqfacppJ^bHL!f=Yw%*np{MswdU{-lZXUER z;Ci+HN0=|8APTLF+EVv+7ZTIFT)q5@ht~zj7@QQU-U1xr+;0#8ZCIjkJL+q+wv#_R zL*m~g$4eB22i3vsYAi6=sU-5W_Hk@=s*pnv384X4QD*6+?YNHjaKPtx7L`lu3#f4s zkjbWb0dYXmmLHxE9G-{rANR>zJWd`;M;=(xFA9SH@9qdm2^Ol`P4FydSX_EL!^`lL zat=9aofJaxoY2^#93D$mV&ZIO7=tj{)22Nf_Z>p z6O~e|O@+zXCbxDiA$RDO6-A0rnOJOo_KIt3Dwg$i^T$*>cKFTSB?#g$~ z>W!M>Ege^}9LFTD{rFG_V0~BNNLRE8Zlvo5h7T%>otP4G0bqMoAH_-ySF>{_hkfdbZK^t-J$dGk_JCYm zLYzBCoe~*+AV81ewS5(Pd_Xk8D@l^l>x^kf(N7}a=PSaG^*!JXgKZXVuIB7tLG&d!wp{MZBjlt)8;(`{)ok#O?)i$7XQoSTMn0k5Q&*dB@Yr3m2hHV&*7~) zUDTqMt&pBY7q3xA8v#ocTOcW)gtRfsu^So&4b|WaR}%P!pe2yBYYu(uh;)EEgAms*fdTD%WNhmhQdoDMw)sF;;?Jo_icwcy*npwf zTf9JAIBDfjdw-=gM^5W}5{S(eT;&SQc5`@T2`251>k^JxPKX_+)<<&!r2YKp#N_hm z@|%TOSMH9Cz1sy8np8VPWCfNfeLOYPjOe2eq~D>S!r>Z7FuIApdVA6OJLcaNI~HG! z?5!O38!7Lp4s6-bbL~iejjcM`(Azs;H-v}#()KZi=eY8;Osx6nMjCH(u=dNGs;2W& zG0mH;E^N_kCwGb=LurLPYdL5v_!b@UibdfwBHlGeET^GU6?_>Xx7<)775#zacEx)tvva|glyD&=V{L{D|C+l&Z5+9 zv4REFZ{6UYR>x-6Gk^WHqQTLw^x!H1+a>q1&#Is50*;Dx9K4-3#Q~lGsu%jn?T^XC zeIz)a)0$ka;6v8OCfIxZraA2uE92$zYqP1h`!SpAg3OLm@`?A>`bhy_-?;(D^u}*0ZR^FmxGKp-vt@3E`R$@!e8~N+lBKX3=7-t0c2XLyuV- z58P(0pURM^|48&&t>+wr9kD}pfKIdv;jbTk`rw`B#MFDdE!+}#=n;gIqP^bz>T}?n0}gXMt5vYUEzDAR zsKRyYu@o|Jp{($KT$r--=`RBvJwlu_!f9*smh%+LhC+$6n#hpLi^QLC{+3qZmlJ4C z68JcswP|?D@@&HB4eJ`;VzuLW3~C7D-k>po;L$!>-k9G#Ft1||_no=ttyQxtNf`ui z^AODu&aah?Bge(CHNr&D?^u&)KUV(qs<6WSsIPQ1#6G2AJAh19RMYuA9o4ez$hc-6 zDj`DHMT&tyHzz8B6%Fi(9r=4Zo~MODN<+){_ySjBK8YdBIdBcz`=m;d9tjD$at}k zRPg$^8Jl(3r-NgC2G`nfp^khjz_M>kO^C=KtGBYDqQN#+84wRklI>pBkR`R#`=n6^ ze&>=lL~&wOZO(x5i8zWq%z`;0!O#iQ(43P(gu|i4;s%CK!{s;21jj*DAI|fq+HzMa zHagKT{CAo5xXw~(R69Z)s#v)&6V|V(i@bC~trU2LV&4y|I@784b5%%yf9>RV^`o<- z#eVvQFT5aA*v<2Mlxx?jH@nErtL*5_hj0d)F6NMFv8@Pmyp10zs1((Qd4@wQHE~j8 z*$NQvL{lP1)(yFg-5*~Tg-cR>$Av8zHSQ1>L!F0Brj zv^<+W|f~)XT6fNb?>CpVAmj20awjeR`75XY|);sVFpPhQb7M#n(*D zlp_hdG?{uG702m1yEQQ)Qm}2wyqM)-zaR|{5az~RVDnfGRwoB0=SENVikY#EUN;Oy zC$4$1d>(H3%i)GIo61<-axKC1f`Sg&Zc128kL`np=I*A^;b+r7HaLM9jCvkup48_N zSJ5BhCE;kluCHu808(ydAry)WL4$zpCJ~--T<%6d>aO-6i>6{9gk}!Og(X91s67DI($W6$-pi#o z7{In6W*;32%?5aM;gfj=rxWV(3n*y}YZyZUWL@YFAZ-#w>1I+Da1bBjSU}BhDA~Vf z3dq+11p>)4V_cpr#-d$Z?>`&GFuxXPW!4s|<0j)GYO8FS<2BHZ;=Y}1#rI1%p`Wl6 z75XjgGL9+-ShBp@yF4PG4Ze$&-Fk=pzV?l}rK|gzmfYv^LJLhO8zQ)N6)_n<;T`n5 zvSwT8x{}Wq6^}ge*eHF&{Tt7@Y*sIzkf0mh>Fg9gMjEh4XdMAJa0=3P^#TH4E_yEh z;N6!7oV2mgj(ticaQ(CwB8Qze{GcCETb);yh{fHld8}oKuc-d>DRq%Ba&HhO*Y|pX zrMd0)Oy6KDb>7DI=GhBK-g)J=z{laq9N!xLah>-{i+u$hij=M!3`-Y8O7S=EYbxeRxINS0bd} zT1(GAt+h{DR&K@HTpElPk+C;rG7STJcLwys+LV@`QOVQgw;HxB)j##&I^o$JyUWb0 zP!hrO@uA!{pLIhW?ayp4_|RJ26s1I_#P&Uj2mNOhi*5M7Blj-yRMtxL-mXyW5Y)eQ zU|&`bY_nMs)Rtwt7O%HgdV)4-Ut)<#ltf84x>;ylhRwKgTF%(IKUr*0Gof`1prIAP z3qwa>V_Pp6{+Ms;;ERI;vc*BHr_IWW6S6FO3yd+S7ZBHsQu+hjf1k?fpuTY6SY$BW zZj&vg{-AC=0)47KSXA+p=}lrcl5v%8AX?Fq^C%4rt&Ex#1MwV3@ysp}cWF}RmB}$b z9xe@Yt8)dDHV6UQE;sS)Sl)0el`Gt+I&o!|l33MKi?$Cokiw~cxbcUDASfG}l=TV< ztTD=TejaJ|haXuRgo(D|ROd=B5CEyGYXMSQhs;#o+b52Of~zYx z3m|*5ev~M{hjL@fyBFj0pohw%13u*oXqb3dw#;{KrJKsMt(y4v zo1)>e9L?uAArTc3)MMhhntnU*2dPA=NGmYX#rPD?I4$xJy_e`aYQP7d!fxooNCe!#3?T!v+nbH};$bM6tz z_6f@$>RtPJuRTxn6g-Q2@+zgE1<8}2Q$KsGtydA&)$nuk!l;d9laALlA>DGz2Uw8dZyrnn`r}~vQ%_uyB+wBinquL zV!it@Pjqvc{uS(#`p!D*lKu?lC?rz&1@xAGEwW3Oqc5m7sP=y1pUo?DI2~ClkXzXH z*md;qX-)s?sdEP{^;hSlRm$zIY|zeg{1}~v(3g>G(lfV|W{1;hB%RQ@*Li*VKuyTK z&K}D6-WAQS^zMMFYeAi7)CSJgm6&}^q|)n*zt3YSb&zzdK#yrP>CrCiB(dGJ^62>M zU0QK{E!wBPiY6OtM(4~evfiDbCl9%P&4q0P+qox3D>U!!L!_IpYRmhK0xRg6od4>n zl7oHhG2BhxCrU4ocgmOPcM+}0%kf0{C1QIPd-3~Irz#Uj?K&`AxThN(K8I|rOM^>K z9S@P?mpoMk)*DA@9KvaYf~8tEc}Mi_OT``*i_7zFuGs6X#%w6*~Z9>q}4esi=^?{MMEgLyB? zLq@$s8*fF>B&cqhJLjZ=-d~~Tl=5-+DxNknkoe;GYM|_0K|$Gguqc#Z zx(4(Pv*^D`N*zRQoS`jb(S(q}`#M1mv4oJ7B{}Mj0P_}XlG|%QSHcw@P1hHAnb-3P zR#S%{27m3cMbjj@z7(pYfb$M}YWWIyp7datQb0TVq5wi_VMZ&q{HQFR89+-} zRQwec`&Fdz#vd1z&PpGSS3EQ6Rv1>8wASsjaPt>HW&m$TirqP!PAI_VQ=oz21EmQb z0XhOs5;4zx%Kp`=S~J5b7QFVegmp%Cnx|0_Gp0sL;Ie2d%Dbw8TI}dApe^b+Nx|0- zzK23HF~fLHN@La&^cz%2WkseWOGwvKN=6BatKeuctSw0=CE4{qrh1eZ004aj{tbs_ z$teJ-8^dZ0c!P(kopBaackVQXWe>pv3I3601CUz|$GK1wH0^r+6jsv@dkb|EluJLA zhbLHy>unqJ$V5r}z?cNv=)g0{NB{y5c9Y9ITZ#!oDP7)TELeDh{UWOdDk zp!aICzgHYDrGueT%u>dU-+XZqa6t$XR)Tp*&8#a!`PGnWkjN};S@TxM)r87mvCg31 z!KLxMmo2x>dp`0GEN;DCU#do98l;&=?R#l~uZKvM`;Z>2gG$G-mRe(7M)HoL=D11S zSbC}9C?!bAmGaG6oi)5jaqm!vbeEV;X-*a;+4~gQr3n=T$|k1?7IQ4%IT%Wm9|vZ; zKB+U`JQM%ACQ`06syorz3om)BW>TJvNiaQl^Pz;dDh8!stUz>v|@-Q2(2JLKgJ(7u(DUV zrDF(kX7K5i;0Qk#$4sT)y6jra@cSW$h4&P`NVaS+m_BfUkIL+)8ZI#;nbWXg`cl^m z-opKuUX9mK^R?CE2*#cns$aTqhi5{@ax+`_r9Vtj_|IU$6hJ-}=1;dl|R&*7? z1u1CeBA?s?BxngKFTA*b6j0-EirS_!v{zMLnMTN*G-AR-JYqj+@kyOes~7ln-#ON_ zLY8lKm79Ma9@LR*D?79Gofc^(UV|HTOFYO{z>9%Njn*c+y@J(p+O6A$B1o5IiRfFF zV-(74rIMY5F*V}@8%zf?@TcYzgq0bkl;KTDPI^{dw0TNR-F+^)s%pwRmTE``q?@?# zae?)Wa1$X(V+r38F_bMKb5sL0)?eWpa8a_CKh($Suv_nrvc1V}Ur01ot5vDcy-*hw zSx|m0W!q#J`R3Xou|c0%SwA%0+JE`v#B&-h9a267$vF${?+)Y4a*`a+m=8MmC zeb4XTk)7*%0GSo>jQwDZg3vKt4Ru73zNqWm4#!2>D%;KeIxqHt&y#gtVY3wxF=6`l zwIK#J=qDZPNQnFFRKm8eg6J_E3mpwo2F2MR_CJ5cy(i4Y+v`V837Ew&fHuM*jTK$Z z$gN%1NAF#*qX9d=Vi2EID|!{cf#_fB_T$VYv)B@ zI5e}{r~!V_HwTM>8b1p=YUVz}y%LR!Y5}pv3AwR}781UGiS9%bj6=#E(qo4tNis57 zc63RtUyWB7R@;nhR7?&>Z4A#%R&^`Z%L8OrmPQZ#0EGezcjb|CA&b#YW)^obiyrvC z1}x$8w@b$BX1Mcx{3l`tvgn%B)p&Zl8=adRhJ;3bY$D_@4wr7bVIuO&>@Uw&I~W%- zS}rloNKX%4orF`8o`%=thO$m3DVw{+*ko^~Yl`|wyb7T$lKxfRl9gNf#niIKRRbf| z((r^c|E>7u7aG^aE=)B0O~(ozR{Syt%*v4gx`c&Ql{b-Cr;0JgyS{$A!~U7fk~XPN ziLpaZIb;0fHG)J)7^ZEn_X`RsyGmwt^46?M{0Y2;dHA^R+FaW_B(*zBt@;Kv%Z<|2 z)L%ehoUCP+yp+WW{p`vgdCXdcKMRS%al&oH=_e&02%@ep_0KjbVG=YU#3*hO4(LJc z{^)TtjI^u{4~v=^Rjz6GbZ~*0y$a{Uck*@ft&qH*PW{0CwE&|pe>M7ns@EMz)v?%X zoD>7gheE~4BI@9F^HNR`k? ztTRC~>rE`(yG-?zg=MidmwkY}XvBmHG+@sH+dB-~+dh{O+m3I}-MCgC!B|zIg4$`e zQ`G(b$O=QCPmH{JTA=}OeA(dy)Y|c(js0XmqP>a2swXOqS}iQYmtIsB6!AR{W)n;s zk{+Lpb&&(zBrM)9+lHsivC+lnkY#cDF`!yyS>xLJ);mJbkz){(zF0)ndIg%4Bw~3P<8AV z7Or5!Y>iEdPahjP=hY4w%oFUONaNrbG|*-wMD)-7P=GdC+{=%ksWr~44CD|VYC5k) znkcStasIV{>$$MN;d-*O*xu|!y+0BsReWQ@-!QO73Y~Ywpsl&CL&1D!JLJK<_GLQd zi`+QGs4y#w+}$9$mkpCLC8kepN6@3#@4Z!N+7Pp64=Z-kM;^2vg+FUhNCMTrzk9`& z_eFd6hvatzyYOkZ@#X#1V0;Tl6y^MaVetB5u%&=0uky4~zlVkX&19_Ux!Lt2ciF%| zy&Zjer0P!x%6Wnqq!l!y(wcP9xXLYKgL;;4wgz~jI^8QW$_q(C z*&3HVq`i&ddz*Fqp6dtVRORCrr-f*HatmWLvE=J7-3zr+_(R%wji;4X!YS3(LIeX^ zbzxwN2D~X$IZQ&6_o$`*4wldm-4w17CyXxPMPdxY_FK11+x*&+pMVouf44_rf!6`px~OfM=F8BUNl4%sfWE{FSc?#;@7Jcp znIb~tst`O5<<8iL*_MD4x%3q-%0y@P(L)GdMfK81lF6PBgeEM-*{9*?M6X@6_u;ERfZgve-#9tfJ@6uOY4VR7EO*coFv>YEU;>G&myNFuy2uL!fQe^g*))lydsnJ7N}R9!QFEJ`Z%d^<<^cq+{5UNQf^;AN`NjN93j&L}g6?E<@=y&nmlm)l zo#r_K@cuvAzeRM#*dUenp1z?_P*eGODm9+cI4T?W&ohUe2AY!$IGpiClj& z`)L!r40VYUbZ8nc@B4w|)$1cP`ajxowVJ$KyaxrL(n`-M0COk!f->W4P~Acno%#P2 z-Sqn({X5ZSlE4ADP#cS%3rB}pw46gbJ5$p^ef|6KXj^)ir!(|NI%h+cDF7wX=d(Z~ zw22RTTGsQZ54(7=cw@A~J+NmEA4qQE{lTu zS&+a3`sc_`cOdtj#tE6W;QwLlEu-S4AYoC42y0@)w-$QHss?o-*Ijq&_{q4{D7IEzHxd%wiM9IDJ1p&%u;S6}( zZXT<}U6k9R@MsJSTOO>U%&ht7ou!am@=?Fz$GelKILb}-L~s~6Ce2m66>441X4|SdeDGCS{@7AYR0Z11g>xX z!s*EoJOpUJfFiVn|ILQ`c}gK5Y!V_n$5%>FMfak#dym%c_&5v^==u0?`?$$z;DwNd zzpi#0-`-h|Kzxtp?dU!vf8O)zwbrEEslQ7Z9RtL`8?X6Yi$d;$`|&ye-=;_)d|{s; z2Jq!fU$jrHsaEh|R`p1Fu^N`9%WDMa^xXU}Y?3=nUZQ4K(qW&C(mnrxh6pAg?@!sX z=y8DH25Lxt0t(jybQO1pbx6T`IZ6;*SP10rbuWY%^oC>s9ZdV>Iv6dz3a<15@Mr?| zR@MF+I9=0QxMd*i1i}EjkIm>}HC+HS0xCHv?%N~KJ)j~9_$dzEKq2R$1g;YBW%PaE z;g_ixCJrAh_7Jv3vKTcDx1}Y>f`S6#9-#oM?~{?_@Ai> z$6@5Q+;bqlK&0jIURS_8Yf~@p^f}a4yvWpVrPtm8ta(l zp$*wVWw+L5G{hhaxz5H$hW7<&EugC2ElWRQXk!LeDXdQSo^@*7RC<+BO~;X^`Ji_I z4aHC*SK58yb7$mC>aqq0J7LRpdbT}mwgWgm2J@TPIm<1ybH!ZqvN&Yd@N%eekv=zM zK6j9YLvWw#-3&TdjLL4T%Vcx-D71MYoV;rKvT3H#evvdjg

    g3Z;g}Q~jW3vN_y) zL*v~l;aQ&LMqa#h%Ucn-12=h8s&v`N3Lb}IDLmg=<5-ACez>O6Janm|)Z(_B>m&Z~ zfV%OndbhZS+?!r&I926n+w}rlUs3RAtp%+zejQ0cc|;?WcpHwIr%WX+Nl}V4<^hga z6O#5)S8PAbSTZaVuNnqa@yHK+891$El)X%)HoOyK)B2_ zRMFcC{(zXl29$U3YAU!9t)F{6_b@)h5w8B4k(p&CeLjOP&Sv>W8S9Y%2Q8(VudS{Z zseC@%{4N(#KGg60T4=iz#|8V`>mJ=b01oH+U^d&q=EkKm-;ND2cgiJ0RTeds$f!&< zZTVhgG+5c*=mgc8sRTAa#LOM*6^?3raI*08`FThj(oCK!@Ms8_tf?6n`fQs4IGp3z zm!8E+d_-c)`!R~>`Pi_!b6%N%PZqGt7F-4O*b*;^Q|sep3nNqfl4z(J8V9gpsNhFp zThD}IWOa@J?-Ufnw>fkewu^mDB*aJ1f{bcGTuIJ#dX_DLr|FfhTvh@Sto7vi#-U{9 z8Y(ckqZVlFyS+c85vZgl>;S>Z*9c#rJG<8>T@*zz3@p1+}kI4a!@NAW8S?}Cy z`6RpIyy%{`&F&hy)&X?F@x+E$z{|~Vp7cBDmZ!?({Wdlfm34Sc5)5HGl`U0QQ$%)* zLIlZV+)cGx1=lY8{b|F~5+eB3^4UXo9SV!j-f!@+;{sBgV5zIW2z3FDb_<&5@HK8Z zRAPE~_^*uX6(QC8Td+Kb=7$7-K!QMmZ2XFvIH%-)`7=|wn1(0WX!!a`9mLn?qj?~+ z1P$lN;{g#D#fp$tY7_i*EWAIU@77$z%Vj?qYbquMKM$7F`QHy%TWim+j}{Sb-x1B;&r%>aycUdl>Fmdouk_+m z4TaDmLiwXYjk~bh-9&kIoAZzdpUO!+m4BciyS2XJL+YpHG)aOnIwYGG;*&aJ^+vq;Fht=)dI2e+8&kc$nktMYfHGxZxICJd_Qj zCG&_9Z8DDKn$o2fUv_L4M~4HH8w(OL!o;gYz+cdDTO?CDb@UMo>Lat2tTc_(_QuW3 zb90LN4nCooc;Jy3Ov-=UNn(YJ&k)mM5|7*3ZNT%dY4)Z1ZqGFK#-IsDKg|bltg`A|;M%9XbwwhETt4kIlFc06q%A?+ktI`V< zK@EE?(2Z&beCKwlHmL4EK6cI@C@#Gaw-X>I%k_}5vvHy^A`VHTv*LSN9}rxKXI^il-bik%R!XJgje49*tKDE0 zW*y95j@mj+;8}J4YA`?(t8%-$&jT_dK}(nV{>l_yNH{t~-B==1rG|Q$5GReAQtbP9 zqheb;?u4oCLa)qxn#rYYP}EXroh&y@T@%DzQl!r{Y5*S+Yg$9u1QtC-k?8(_tO(fu zDJv+mco0*jc7C;wj`d77D)bG{S zEvZHcE-u{*HT0`@fhL`~zi*?JEvAcnNks;W-(0*bH3)JWl98h*`nR2c`YgiEzi+V)XW*gKOaUqMI2h9wlk4kRQd< z2rn_9KopPsSPs|an4~Rv7qoZImuAvmd(>o22sGmCD&`z0;MOJ0wZR(wUqAKCfL%UH zRmBQXxkzRkfx^2p@^0Yh<>OiWhjKQRc4UrUXmUGkzf(!qI$T?0FuAC7vb0lr8ziuIwA-mN-Wa2x zVi2Pzfcv#r>aTaCO6Qp8ktf=$%=qGHuMe5c$0+INsBgo@Vj>K|>1rW4VEI_W1YCz> z$4)nP;#*dX0W2xkwth8*?#3PUy0?3lTumeO{4Zv|3f`PtqtX?8z;f&L^ObHPBIyl3 z{spLjhWrQkr}8ptC9T;PvA8<-M2XU9GV~P=#1|$*_~M~Q!zdHJ>nM*?fKVuJoS?9h zwi(uBknVo~V)IS*RTOPSuu9b1=3^bgQ-^SicfBXcKePti%!VYlRQQ>NqJHM&7^Bx{ zZyV~i8?$hIjD`=XFW=&9F3bHVP9-p~8=$ES$N$z5&;PlZhn4?b>d z>E6l9d$)Hvw8fCcI8LwM6Y^?>B#qOM;-XBZ$N2Lajy0UFR5>fmnl#^zna1xL=gDmw z#)g>Xc?96$T=-u`V2;HAkrq)W?0`p3r#2@t<>r$gmR>cn1#+&SJ zCgMqJa*yJ!$gS$gW!>1b;~g(t=L!O1&3o1Tnz)w3d~s4l#4AX`8=ICNwPRhv@$@t+ z4w~)oMoLH3q3kr=%bTjTVCv}2XS93b3g{Pcza;uOsZTJku+~}FhBRuUY$pk>$i(v5 zCgf>lCEt$;>S;DG6fy+XBCLj98V%uj_Sd)E;L&8V@Ri3XG%N^emyGUO7Nej(p4FXJ z+(6Vz5znL`!1qDtdY9NBMKi!P3Nesn8kw2yN9B1M2lgshR0aWul)~zzLUN z7+b*6Iejxng48jIo|}G-EvGYXA0I>jO)!Sk{{ww2T14-H!jD(uNK>&{gLB0exAA;j zquK47g)kB&JWxE6H<%iw&xtcJ1OyJOBZW>lx}olWhfWe4^lao%N`?gxo_akNg^x0~ z>knW<uvOTSa@OynfKUtMOb|!xd1{z04V3 z_kZu!W|_THd9E?hHvNCPp%wor1G~< zDM0A#V?^8_TGpgR1`m+cb-`%aYs@Gq0QWDtP6xQ?iQODZ->TrOKOh3RNz7NriDO@m zE1;%FxUkV$7YncuP`DNWt=rzV|Fx*C_5IPnu`l8dRJm1}6Yqpr+xz+VAw=YJ2KqMX4DjUNM zCHK&63|ch9NI{DSk9|6Wh=f1v@CF3!;y7Ni)kp&>xo@`W3%SS~%>>>}`(x!i?BCv;R?``Bjbu=iX> z-t2`hP0vd7dRznW{B(bqmovqYq&a?t*OtkbZa3Fuq+yQvGzJTKi4uBJsQD`z4y4Lx z=-}6h|JX|7v4k@!xi(M@^y2AC=*<9U_Mg7hkHgYX(CcH1je`~^#hHh@oBh(juTs?w#^u-qX!N-$D6WG)#y4 z`Y~G9X>hy1&Ax!}kp=4Id|f4j7i3rVwdRsUbbE+f*U!1{u4VPJ=bc?kePz^6bLE(3 zjp`b~W#yhMAlB3|UxnH$MBzT!me=W2P3W%rT68 zx=x*xEgT5aQi8a78~L0JY)k1Lu%yuwNUkGRG2EJmxgCTaxU5+D)JoZa(HK^<8xN9m z_#b$=2F!a@GE%*PLcXnQPbAe0tro>B=YALWOZs%tUjj!ZXm$h9o%g!M+LHf!5`uwA zP`07hRC|zoJQKTnzdX{v;4R@aVO?@<|$@b!H6 zzAOGu!(UhuA98n~`Uk{;`0i<~Fqy8*GylaU_bK4=qMjhZrjk`>u6f{Hv1Xk8=v?0F zuKE23mr*;U8OQQjLzj!di4CVAB8(`!agBD=zJds&o{j6Y;kwhkUTVZg{6xk#*dW?l z5;kpVSpA~PU`T1+nDTfWo>jaPNjj9LNB?5wuPx2;A8d0ooXBPM2z*8=c&XHO*gUGp z@f_a}lYoW}B2by=?$o3R!|l7KRW}RhF2{-sEy`2_Sj|{=7zG``&_j3pT0Z` zZf6S}@%P8-dq~`8ZUeT{7VZ6s62E_?{~nPbNBlKS{`MG&oCX5JeNemJiwJj(AAM{( zZM=@w3jLc7XlwjMm^UWJ zIVLs=>I-jwD(xw1bTwITL}Njj3~@w>JtDj6)w*(#WpZaJP(%z^h8?(K|8>Q#HO|Gu z^q@8B<}idXx+c~aVsZI}QZIhpVGLJ#8r{amamc1^W))G7!q#%y%oS0x({8jjwMu}3 zQOcq2F7|dO!QDd!0KK@N%f_sURj-b0*Pjk3Y6%|c#A&oYHv9plmSX!TmttN~9;ZCt z`mB1=EGG%=g;r&c1B^_f6Nv+|(z8;ZhqUV88;vX@ym*4FiKogy4|}&9ONy)J$3LJD z4}~O$KqqGfUjohVUQf_7ixH9+0rl7a)?xe@n!Z5h{QR@O3>+g0V3tm*$9D>e`u7{$CyYimk`TAzk<@9K7jlmTVS8zJ7 zw3cO+4tRCZ)xAJ6m-ixtc-`0l$O#q3*HXoQXr(}{Z>3FHNO)u_d-9lG9qWu_OXhrk zuqVIB^Z*-ivbBF=bA%u6Bhg^U!`%d@$?ar0Rg6zH%prc2= z&9}}JS9i<8(Z%JU)2!sbw}@vzQX$Bv*Ss#PJDHHsg{vAxk9>HE$;GF$+3}I`@KV|q zsAfYw69BIwJR~ssepBloB! z`z1b8w=1s)cC!usYcaWjJVlm1Ya6^o=Y`EYM}I(Sj$RW-CDEy}hV`#&7I`dsdZg{%!O%|9z9J{@?5* zcM0>S!}V9=GW{2oe^_x@|GsaF|6y6s6?AjAp+-Hft?)SCuo)l&d8U7y@2y9-=-EBz zUX?6G1f6@TO);O~R{j{yewRj%A%`)|?3EwINUMCaYfdqI4Z{);WY*p zPb@vo;d`k&E^&O-_qxNU82o2;%6uGMHi&H=nLcl>jLEwYYkWD{go zPv|B(TGM)o=GzOyeEgQQxm}w1;g1exyKnK^_un1<&XH%Ye;6pWIjP?!KIu>mQ>jn> zx2*^H1Nyhc|6QL?C-gm0`HQdc-z|M{x9t88TUrrl=_ewl`Q!^X^FN#?2|3uZs^oIr z+E(`I2W`@ggD!{bRYvvi|8uWjU8W>e*H!+2uGs#E4V8BtH+whR@jRy1^H}~5o0ISV z=424+)@Vblp8NlKTt2NQS7{F7TKTJugS1)?5N3@u`-fFRpBi&quC1na``rGb{&Isu zKH5yb5qiVD4U2bmZjEw1;PKSbg71Rmd`BQQbxnQkxv~6s*Q&EVK{Vr@XPfR0l3u zGFwQix4om`I*}jeb9KtOmrLemmRFSb&>M~EkJ&=$TLSkzDNa3&^jBD-pE65jPE*n# z-|`Gs?`Y69nXOhCv@%{kQx(K=)f0V{10hB)s<4IbNhj~N_C-pz_gkEQ{mTVA|-9Do?yzU?UGPTr7tm_DLa$=(d|eDbo*U}_JVK(ZD z*$X$-n1${MAz};_1r@hC)4S8dw8TeN2Bdg@F8(UjL0R zoau9x260HLn>f_jB<2M&2nD}0he{#%tJgpk_brfeXA_ZA(h9wSzX9%2$h_jKU*15S zJWz%a#sni84pff1zcdq*{s`LPbh-saX8~~TUaA&Bj!U31mV@uvFfpDmAR(@H7m*#t z16-~^Rlzk3*-3zF)bxbj`xxhRyW7`Y6fkrSUOHTM6Hqjku!9jGBCNN*255&<4KB4`25d{D;T7Vh?@7j8sLqp<@m-yj| zN5?m+=MXX{{?u}ac>9^S_7CW@#{{kI<{W)V)&`Hpc3Q-CV4m9XTMJPQL;_K9(Ie+y zO;(;XICizEI@+zu%`F)e@$>4?4b=47(iLEk{Eqt2U@1;SJ#w9+Zl@%&9`<0Ni&bS| z__T1n$M3narQxAO+)81E>tv8*WYMkjVuidroCKZ1e)(2?)U(4* z9D{r$LvGi)C?^ODf8~?2p4Ou84dsBu9KDiTL~iOr z!z*{Yeffm7)RH~3%FK5t!f`fL1a6S65u&w=^k6Z@@IB3DBviMtwuA8t?vbQw+E)7> zy`_H8)vM*qo_OeJHHRa_&kR*zBzEAzT>yJ=*ih8=9L?aPi7*wZ=-76gH0iXlF-;Tk z@#_zKj`dgD7@u2;y70Sw5gn{P9AcJ93d~ci6+xCS%w!`cL(L zK&G`vnES1wY%SX?K~4F)z3E|Qd8?&Z;f_JfBH}yBCQcVk)0z7v2=rzQUp7rGM#xRV zr!7+{LN33Xs=3>D%TvXA3^3_({qxq5Gbv%dgk$td#XcWQe!?k z3&fkL5|@h1%0MfRLIR8a;hHk|nF5qZAwzn=@=f0Mf{`U6>8rldQfq`}^Qa(8!XN^c z`ED0Rc_WZgkPF%#$kaMd#oW$;O{0(0FNM4JmY$hQ$~;t>KhWB~Uq&?@C#6%DaGrCh zsaPSLm(O{RuZ4r1&*}#g-gmEz1n1k_Sor*FBDI9e)fIAt*2SQrXXa`zmfzuN#eW;w za_fhVdc?K_N3zrlGrXp=T9&u*2KFGjH`by+(So3As&{@qnHMqA??3~5rg=C z-adH^6A#3PAnm0#`&=MoKc6w@P}BUkc>C`G^+EL8@94gGH1UF!5p zMPsf04iXc^&GEGQ2V|$jlpyt?gXyDorxWa=!AP7wr{L&}Yq=F?{{|DgUsq+6g$uK6 zaRn^YMR(_VEbPc~XQs-c39C(L)XJUa$c6RKu6mN@4zy9Twk|B#iO;n4=jg9kTliOu ztkt~ab*>&eBiWMPDfaSZ*5WThO!cP*>gHS5hIp(h22^<$QI4;e}0V8IZyGD^d!Q8WFy3*@fSF2uU2W~uFG!v_Q6JsL{ZajtQ z`G+U_>&qq7M)7y37A7)tSvgje_=e715@k;3oufhNOh~6@`lE6bIPhuDJ~-6_7O0TlyGFYj3lDtne&$A~Q6& z|MA^7zA+|yzInlyOI)I{%Rh$8v`l?X^s%ywHU|DNQN3%hXy4^2<}1vXi)#g78i78JjehzXi+ zNOb7s^a%7b8o2M?%;V1WS1i0}BYd2#=+$@74?U|2+{i?rhuoaEm3yn4 z8%pyItwfxCqGe0PsL5K5owVp?YQ&{5>Xk|p%3~?4ks(odGy3LB>#57vJ|bs0p4g{`HGawI=y&( z$6_vdk;0vQG;9&Kkk-HhZi;AB*g^ydAv~U9}o?NNUamO*a1RV#y2(A%}Tj>@k+YlS~PsjIjKp`rODJ#ouE}P zh&a?54aWvOE+UZ;&@C7esqtVeT!mtY@9!}JI4l&Xg|Hm# z&EgDq6;#a8w=J>uZ$yNyG_%Zq*QYFEYEC1U|U!66Oa;$ZQzPm6OQdnh)mnovd5Yger zDX{hZ=?^Gi*%9n=itR4kudy%#9tmacPR?Q9ZTim4uNtY*onV5*EtxZ(RI|M)Bo?i| zk9PJg*ParrNKGma1`|>TE*rQuMWdv{jm+Ld*rOKmbFz$&u&j%=9F~i;v>Qwt8ygSa zZ$)9wDEG-c{q~GBYvAGP#BsT=bU=8!wHXfgGN06}ufLkz_6CnYV&#Ry#Q*8i!NV(y z`@ZiFNP>Ko#|CouNlf%gw%dMfsr;cf?Ld~vv$ABV8b|lC|4HGzf&!PIqUl9K&=l?q z@}&!S-*xk&ZZXW(6}=$fUa15d-=Jynpmf><-{MXfQo|z(W7(^~5|8AF{n0z5k74O! zM~HN|9;;fuXx2h;UXZF8rgbri#dxfP@k;uKEIcv?WhLqFC2F6%Xk*8)_VvWE&TdK^ zruu!I*m{DMmz2Ag%ImExR0(xIXHCz^H(+aEwF0sW{H+O17Il@MI^0RVTuaOz>qQhW zu)|2=q?7~;A*vNcG;;Hc01*JB~=2x)&d!>E2 zei`)h9O){b(`v|UX%qZ;+&;{$$H0p-`z6Ata>+?B10EoqY2;I=JR+?A=BIirI3fE})TB?OdE?k=tLT38Qr(I*%)|7_^w-&-8t4TKpo?@Ccc38Bs zjuk^&5gvI_sa#az%^%3g_Rwdz#D28k+_q%bBL31$WZ@@~57k$8Ohm%DgKMWEGQOyc zoP#m14{jK5D!842!j7`;WIW~$g|J3`j6oS>)iO7*G7gH4?jW{?!$I?`uxOcUk;BFL z=I62?{iF?0+d@)4bg-|T0au5HYtcuaq>#Gb5hODOuXC>kA_^7>D;q*U_T>tILYFu6 z6Sih>K+p;LLwu6!8OwzlDnt2cp0JLGo$_0V+DR4$j&*Czk_4Jj`mG?r1rXMKax!&G zoYEDBR8^i?1(=Z_=91n4b-!>$?Cu;|qVIThxxNdb-^0*XI$`Dd_A*m8X(yTlhVx#g zt6H7oD#q*MCFNY$KH`q0eLjHSpclhIvsPQw`8f7-r;-}&PNuu|EuQ|Y#pkc_jm3Hg zP(KUA5TWI9UDLHZWIp>lq~_+;xPL03!Crm{4(r>6S(@;&Y)%s6+b+P?MHgOhg()iQ z>Z``SJg6te7R%YwpK%~f=07N&{=_N^xr{R7ydvwz2@w;M)XpS}EMq#vh+&V)jG3}~ z8{t@89f|0Xva0pjiIes8V|u!FN^bIJYcf0xGH>@J_Wo}S7**_HsWI~ZYFon|Jh;co zGoA@9V?P~m6QJlkxY8^#cGOURln$uBg8kTw&8#^PR zFS(R{Zsb;1`IyEbUda3=7IpUCnI&@CC}NNW-iTc^in^KlD@Q%e`vW6~pHXxlTch$% zS013pgCO-}<)>`ypCY&GniN?Ym|+!muz!~Q%+2v2uIeREoe1J|thwZmIr7*+0vvi4 zlKgVZz~?~cr!?E;5%v`kRM ze`!xR4(%H9C+$`*T!%B{;b0Y2lq^P}(G&mubS~LpmDx=ljz6-;V9Fhw*nMPJp7Y;| zS;cn*SGoIu!+9S(A5Y7JVx?g%b^sN zOcY#k!F%?JUd^F8?Yx9r$)RFfu{uIKVtn9zb`-G;TIU7assYjq)i6*Ftak(e+-{2i zR5WFn{4nloYx^KKkfH@-r^vcCYK3yas=CAYvnaB@HjDGKA`0ZPsq$~4)_^C9JREui zn|l6r{WgD}-YV$V0tWx`BAz zW?M$>WD=pXlZTc}4#)P~$8vPnKfXFDi2BR=Lz`NbL{tkC9T%HSV z+6NQ^?}?{E%ITh7vTw+I3Q?;BUQN7z{Q(`$+xt92d|sP;UTIqa;>#KEqkjV6K|aUN znf>((S4EqB1wTr9FSTQ6(Xjr#a)d2vvHSsfL%+IJlnUG;LSP3wx}#@<$X?!0Eo1)y zy$49gDcRTW_aJ})meNSM&!|PIO?f<@SJ-KD&u!qn-vGb=oL3}q_ig+I&%o>Vd9O(7 z#hh-xI-|Ut=$RqE;0NWUg#Rpu7tVuy`%(JA{bjZ<*>PdiWv;S0rl0u(@8gQ2{;pK?Xy!*I~~hKYl!9>?0+D*+?y22vd4_PuKn zIcK6^ujZmKiJxu}22nk8eBQulEX!j7{sx-)Kx7Ac24A{oC5J}*@alK&xz8Vv65Jy` zUCBRIwJ-RJz}fyw)1D^wmJgMEk6;}?)cv`=lJ3d9Wc}&rMR!>>dkxspo2uR7y9|u* zL2J7F!;LED26=?H*p#7D$UIW$;6icPg7?G@F@j#URscLSEZo&2BY%pY915?wa(sO| z-EE%k7W0+e6Y`}0e5BP3T@$}`67|~sYLllN_q!Jv3hMatA$a1D7>+>{&np4k1coQ& zs6Yg4%uPw5u|+(yqXFi9=E1xF9fG3x*Ygq_+q;H^PA&pb?CQYVX`#;(i_`bxhU@#( z))4EJcH-2Y8@jL;Ke>9?p?2z2lN+I6uhjQDb#s-s>x}ABJRtp1qlWmBA^#_(1)E+) zir4(A$||a93jqwNvBw|1-lM6mCTM~1yzH(4AZ!jiB=cT@1iBYZAREoIFI!fn;S==f z>g1-|c0kUr$0WG%oxkm`+j#$nFAJ>U8`2MxM`U6>NDp`JyDB}o2}3vVNLETpD&mJYj#fwoMolS{>@L2Cz30xvZh|FgT92YkKHE7p=<8~C{f+vjfn3+WUDS$npVuB2w z9?>jt92sO}3XKBi&KLDBmnR)I*}5$vn(6E;67Z{e*@Um0@ z^PZ4j4vAq2P>CqTL2>zewF>Q@PNL@qJhDW`|7Byf0iXqKlTTX_CL!fN>+EEBs;j+< z+{{w1H102_d~3=#vl@3WlN-q+-&u+Ei$>HPm*#8pI!ro_XHXhpFh%L35Z788OwUz8 z()(mVqsAZ6EWf?HIlpM9|2P|7BU!pP+d}W9WV{@VvwU$&vX><3P-GT87U7aC&sl2c$Fo$Qm0aIXIu0Os6z9>}@3vV!^v;f-(JUY?0) zn_pC0j)q!}sjI#eTIsS|_4k>M1WmQ-<(zsLyR!|s;fjq3j2Z3cHe4Gc{?>3z8KEF)c#-kW~;K2Xvq{qQ*lBzNr9IhgTbNp7k6nj@B z@J-Bn1z#wv_Dobi7|$$VVY?=oP0M6Kn5@|AoKXBP*zN1FTh0O;G1Uj^D+D7WVt1Ie zFT$*VQkpn=5me3uESt%)w~WE;-8`|*mhu7TuW)sr4US2|?bh(Cv8i)|oQ)Z4PL>hp zEO%{*R2>r#DhaT#Rb`-d>%hJ7f%;dIE?H_3#4%AC&FF2rXG`{)L^Jmz8xuHpD(pg2+xu@L}s28E?q(|^j~ta$qFeA40wo#Rn( z*i24(N|UzNSXcVJ;PgY-X1aT8!szw!Xky6TR~=&=iQyCc^5%4e%_dx-th*%`Mp zo`u=Y>2*sWre1`d#CW|a%;u^*vMQ)%DT#_6BWSY*oMJQ*m5dR_LTfidR0{Vr){ReR znK6>N^1(%m9;rOw3wfNLS-P@m27-LHD6rTz=&Z zwyT`M!E@5XOZJJ4d&z+^liE3-eWJ^c`{u=)Z!2N>`S;xP5vYX0Jtq*=b;wN`E^6#(b-(*ra z+F!ap+%5x}y>ly2fURb#=_pi;gI2vQwXt4sg;dOR&I&rZhq$s#1Nn=fKL6@BbK>@_ zw0*YiPeHYg-iZeGILA0-PD>w5<}n@LM$^HrU04QiE{19$RVXPnV)L=sSEGmG5{7mT zg{|glY+ER$)0Ypj%{&=~5KAiTR!Yk7$Fhj~Pbc!8N zC5nHb8OJAWEvlL%Q4_{0K}iiDL%XjY#oPDmJ|lA0lEE~6t)yvTWv@XKCn@XGCMrf{ z?ZlpM5%Rv1iFw^ghqG;-I5NNOH{HXyn17EqeHS>{3410nZ~ykB;I08b-|9uZZOq>7 z@g{aA-K{?@z$0mNn~AMyp<7hTR7bRC%RkPXdx_Zjio*a#MU?6ji0D@+40o@~Sz-xR zn7WGrIf?nFtJjP1g_`hT^#QO7vvyTD%WzL$F)rAX}Q_T24wDRkU}(H4xon z9)GXcsF?tl5?;JKS-D&O8#CG}CGiA9bEv7wkTkEHG8LSeX7#0RkdEANR6S%Ko|oC~ zAam}bB8jm6O{fwYdiXf~{9BdZO{zQ?`o7cl<{vd{*sZr1GZ%ge!|E#D>j7nL5I8 z0$-Gf7%>!bjDup?wtotTId4a2T(QJ29hr$dbxgL+;*^5m_}87r_^s6)E#nz`AcX;1{immI&0F?9nx0sF#sp zeN>L|_rkwXK?DP36WCi}IbW{O-GoiK$~`1?KJTG?gNH$O`;O2B7YlHGR`FRVJ6sFjN6 zNyVq@Y{ws5P59b~Z)YM`S)2v|55j&?jnkwiqhE%x(JQ0f3ZnAQaVUeIgdN4-{P2V6 z-=(zXc|5UD`_&JcgVF=SGWl`IvzX}qSw9$ZyYSIsVWL}$`=4|!W znbn1=@EnS48S0=RU`#>xFPgN*AKu*5SPnK?P@VEMvlWJ-j(;xvHdTw-Mi%nyt5dJZ<e#Fx#e*GKLyW)t+M0dH;iyq8RN2U2GYm1N1VX1FmSY9cVR=E1Phj9fpxwHRCBq}j=K8!!=hIe&^q|#s z6{=PDy^M1oWr-;c3=(2YOU!=Pu^l@*d#x;v#?FWJBq`-El@7&}3L7MrT?+&ml)h4^iHO+(X@6570Zmi5%%ZfQaNYR;E3+3|$508! zb4Fs^78c!v-w-QpotU;Vh`q}|)LTf;kzUgV>o79=$pYPT z^4HAi4L9-JAcuX8$^nDH68#>?dU_?^0tY3+gtjo)B%(nv@xo*RpFp`~?zf~S;p*^E zdR|)`tM+6aPSqW$pTRfE4@kC--Dq^>5ASwIk5QRu8JoMA zR?&{b#Yy`IDjCMcx-X!3&+P6A8TN{Zsqel77(JJ>UTt6(uu0QN^ZbknrNS%WSZGwg zwg#$Qs9XiONIjxdBS3!_-Sj_2=l)hz6J*0 z8!U1n_Qdq3#4Bi|)Si6$kn{D1#ZXw<{)%bdvJO|e{&lONV)2DTQhTnhrmD(Hj(V~( z?GvG7D!*dN9!F{NEm$bAYJQUwks(6ySG&nq!4tSf@jbS{?HwAQo+n$CRnkiJmTtB~_O2x=dK zZCF~scpUa*!rL(`*6*pc*M8hDt=c>E(N1_YB^F<8PA?@VDsGfB#rhQWqi%Z#{vFt3?FQ$qiB^VE zJ{kqxrg&-A<*%6I{kM_*&IP}HrIZX~&~D*FMZR**;VoRnGTsf8Xo=>);{1+NyKad* z-bQC?U-4!;;kyan%#8Hl@5#n*vf~aR;b0nJ6{_5l&iMA7VmZ3Mt+2h)2>}7kx);2B zj#8$tx3QfnA}rho0Y_LWDOnh%4h)FZSc)vy84l%;N|S~t!~{^H1D6dNSH-Tkv>)>e z3=9e){mLu^5iB%l=jssuUPNr6Y=+%ksi+nuzxEGEqd{Z$`_4hiF)cLU{(i~{!Xi^n zH2m*0_6pul;PyD#JP3UPH!#BrrV`Nrcmwj(Kj-i~tlCf{K-3GK-{g)jZYMFXIH`jv zqve8aOipg!qS)j3Ca?o}3n2CsLcYN9=B%R)a6DU>s?n1n@l*`2e{TQz(pG-1+|5?RY}04J?LFfabdz5r z&=<`6I_(um+%#r&)2t9uh=vf}k>U%0q=W4U{DHV7U7ZL3zW`!PCNC1Y2fbxLv^RCV zPT&!;0&s}wbO8rT;6I#!d?Wnn&gbg<2GE|8-lPcuHHQTly*K~ML_SdU{n)<>M(R~R z{sFD~{sCoKluW$%mkZS}oaf%?hx&Y}tM3=+?wBp0czM%Q4ty15<|Ey!&xgxLh7-Eq zS}OjLz?(+-+}|wmxX8$`P%%?5;e*Uc@XKAGI#)W~Q|27$N1cFyND1DMNSL30sgKKm z`u8#PNkt}K7^LOXNzAr)ui3jf6klu#0fXMTR`~*=a?|n;K=!iL5TOmK*I!C8etKGV zsZaQeFqnOiVV7(-pP*zl!qU(J9kJ%9%$_t%glSxl5(RMu>nbz&OyQ7q#~B1E zHzgY<1woPemTb>f=IWL#OJ!Hi(L5cM&5wN`e9q{4%_z9-%Y4W?KHGWyaDBs3Us$Ru z+M!&ZDxh1YdN(i2O6z~=0QYF0zKk|TVd6t^u3K2#29ao<%ZiMULp_|A$|2gBz^)Q2 zt?YA}{y$yzUP&yj4?SZY9NJjP$IP`y1~Tr=R;2n0_gY?rLvNi|WSOeN?d&04?{d^r zq{)oG%5HSXDteel9?nlz&RP}7&L3gC-26j_3f7R~TnGEh!)dAhBgD~*aJYdJZKbO( zgMhBxr;w_xns>_C<#l3_{;EM58YMUwwy~6D&CGnx?()tmxSf6LWnsF|sSU9x zkiTOYrzOC;Q2mEN0wY+M&L;>oSQSX$zTn&G#t5AK(`yG*KpZW}4uKI8Tl#nv4&$kN zH-Dn|pNCU(dagcFFc50CK2^~9Vn5@bXUP=k)%+X0dwJc+nMsCf$JIYgrzGoKMdZ+^ zqWOf>?#U6mYo9M(`|1q(KaA+v|IG@q`*0*C#zzb1b_x@=QntxM$ga+Te(Nmz6m^nY3%tCDqa|7_Gojvc~Fyd~NuH9s6C!v-s!9>UN*f+p>9RVW&n3<3nB?dwSOoi3?8{%Rzm% z6}?{dMrDeeM(&n)!Q{o9)C8^AZ?;dv1F{=z4HQu1ri97%R_;BGqRVFC%3@FA)v;)N}k zd{HRUpUfS?OMTsTzTe^f(baBa;FfGH>+tk-<7M!7GlQ;@=P!FK%fm|>`03m$BLUrm zu%j^s6TbZ15!iR79v;p&bSH(`U2ZhJh5rw0Zy6QW()MpQ0Rn^|jR$wv;O@aaxNC5y z2@ss%?(XgoT!VXXx8Uv$fipYj%)HNeW>)@dY-RB!6y3XOSKU>0%k?XN#&vQ5)?7B> znp>amxt)uPood^Erm0%TzaEF{Nc4mLKkHaS@aa!;)Z%brGHccjSZ{k+p0|IPaSCdI z;V)&L?}Hw{Y<70ExaF7-#U%?)$FD79{^twJ^#5*U^Zun%|#lTpf>vC3$Cj(MNf*uD19sA;h?MW-0D0Yg(Ju3L@o?*%opGKM}G{I*jmCpCJ+_-X;sX zix=rCFk|l^-`*zGv&p@tkf2wX7L^{bh~-Wnu<+2C*GS_oC<-Q4b;>X|U$)aMlVinO z0Zf|bX<51Jab?uMR)IOd7y6GS027#-Pshz$F3V=~LXh41d<4h;WHg%PKJ8D(LuNZt zU?9i90*Bi?FaPj|)sSRUfrMvEY@=n7obwCob6?KZ@-I~o1ojX1h#h!?Kt*Qix@@Z( zzkq|@`ncZpzaIHtrckY;0_mNn+L9??-#-1xzRld2n~xthOj8|Qg$X>-{J~UKS}x42 zrM@Q^ATT#x6*Cw)Jxx08xL%sG)vmS;i&SYp)|D1KbH=Cm{wTN45^nS@p@lqZGCO33 zqn9RtiJCQ1vCnc*`0Hkqjhu7RG`=eH5LsOvz}Xu}!ehh!2eW765%kGAC2S55f^_)8 zScV$=NE%p*Kn_Vv;+1(vmVUxum2Qociogd&wrEAJ$#bzP_VVfY;Mb@3c2^0UT8*~) zVA+kw#6GX@#oEv&>zK0N9o#6M2{slVyNYst-r!b8xy0bJs zM^gYwoaj&1G;`ML72FJN@D;4p)F24I^qh_A8@KoC}UR@FxjCU<%b#4tWcQ^eazH zJN)B3WjD!KquHwAUOiaqU5bx;BkIvTpB^n~cp5YHsp0x4b*M841U%gvQlFZ?KwN}? zG%JA1Vj>aZ{|gitT+e*`ia!lVQx)Pw#~UBH{7u0A`y}aC{kYm@#3tTOyx9!Mwhy#Lb*Ct3Mwm-cSx6x%t}!{< z(ZjszO*W()2D7m%(Yq}zacPSrHjUH-*Ta41+d_q6KYGC{{v@}7+L+wRn5rQ^6 ztO%m9NazblwB(>l!Tzb>UEyZaWDb{+WPIlTe0RE+cGmGc)$sJ-x_44)Nf%~4Sw`N6 zWs_DXIZR+ozKAg)J3`keT^vIiotx{YxXZB|x%y8f#0@@OoR(pEj+M#$LKVjDZo`0A zi?wDtLwps!x=W(jD|wjwmXm@;Y1!(%Sh(XxsC^SW(qfm`;C3<_Q|a z3!lUQ=WF-#N4)`tni>AX{G(vgAsY7vTjhY>bOe$|oExM$KgJad{tU23Vod$^vJ9^K zOyFy6^tR5AGX!T*Rph4)cX3t@h(h#YhA}v^8;O4LTGp2t`(WC9`xWqk`>?HEyF?>@ zqM!}l`(6&m;oFVKN>AQa!-lzT=y^1ma(&0Xs`0n(bb05e%H(|Yw1sQNJ3|5MZq_o zI^RC@sVPy~)59FA)^Ou#p?veLF*t$iEmzr8LJQQ@4?TVDre|&~B{yW|hVsR5*DtcG zW6`9F>K)8N(}DKiIKimzFW=NP1tU+cD4DcECm*^`J0^eSa!D!=n>jt9V^bq}UJN}; zKJr_)9@@^qm2R>Jp96_0WZ(pL7ORC%?MV1cWB;hBqBQ)d~JOE^ibnt4~ ziX2{PO!%$^wFk~bsleH^ngZnr66M;W9F-6vK82tIa$_aU$RfbC3uUCF*u!R1zKoh^ zHrrkp`>+BLNn+KMn5cS3AQrfzneN#?$I#-rvN-MN2VWVTjxcPnO}defugzq85QT&< zErB}0!k}G(`@$h!Kh8W0BhF2Ct2`mKi2zeXqGtcO;V6S5RIk#2r8i9G;1gvVF`g!( zL{q3y7tSwd4-wVtt-SZDsBjgdt#|T;2;`dVtK=Vb$QOk~lM;xjPsw#nWeE2J8_i6& zw+c=M7m6Crp%Gr&X*8y|l0T^JBRY@L)T{PdXom)(1If)uM`Aqv!R?N8)I9A4CfOTo z4~Dwv>c)jkRAgJzEd<;tkS-@4Q!;AuSW*VxZ}o4hq@74(WDQp!3)EpPdSh6Ig;oh+ z$;Dh$NUTf2RS4GY@95k~j7ohU*E3 z*#@`w2^#1-23PfUQ7-hWJ2TcT>T^v^v=yG1%aXZ?tt8>of7}k2YuPos3QDTaMUA!1 zt``yBLTlq5&UsVXOY)XL$bd9{^X5Qk1jm3Xd8xZ@Gvte&qx1(I#fCBuWfAJcn^yW; zPv01v1}1%~_YyW~O|O#22J?u~LV7u0(J5OfT&W$XA7xEgmy;M4*vGQB{1Q8qDnp#E=UW&VY zpSThyL7pKZrB*4sT|%sq!5)w*Va4m#%^|KX6L?#GbAR*kgYJrBur>zI2y}jQ{dS84 zdsn#?H(L^yZuT|~qjt#vbmnw!M&bMvfg^~@*GU3N?x497Y9&n#Zre`V^W$95@fV`b z$LWsSnJi*Ufnx8IIpJN%*+|rx?Cq>HZpFsCFXm>idPZy9I3|ZRwjB$3>usxpYgZT4 zk!q-%bQrX>FGB}t7&y9ZF^^MC&2!>3Igt`HSrOhQr}r-L(jA9(Ln{n?dqeY^>ZH4-{1@pclZVeU&K@R9DSe}i7cYZV9&nUoKLv* zt1mX0fN?N}pCOUc_PuMxOHChTs))_#>m%?Lzzw3#0C#plZ{U(T8^6F4A%TT;az&8$ zjxOzhbSaPb*7AlYMAR-fz{YF0M(0|;7g>jxSw-&&S-E9cM>)`43o9MVOlV+~?6@}z zcfkU*)u*E)7lvw1_XkEev~xdZ&>|AB+KS@9so7MaR&_U+hRkm`jmhZ}SslbuwQ%E= zR=#ePSrGlYBqJBxDh20D0)U}6H6pmScj1UMmImq4}PDx z^3Cw#75}DY7IIIS!-~bV3+DC3;M#f_Zt{c1JYs`^_>yE3airgyPStU2=i#->hSdk| ziU_*i?jzfoE}TqxDplOFrUDnyh|E<^F}~4!%!=qUt4!2E?UzHWLG#f3&L>=<)UyV)d*cOmn| zGl&iySqkk=!MX_@a^&obFt5FcmmfAeMn z&Ds>NR>_Hjv25uFLuzf?=TBDZMokbJ#bJLorA?PvW^kG)<%67l?BV%YqiJN zn&hiNn&`OmMUTdcG5E^~`O{^tl$Q0@UJ7020Pz+IQ>w}cah?wkzhxQ`6P6(Z)Frq@`IGd;R2C)33kVv;P z>GtKvuSBmB<#R@3Yiedbe%K(>-V=+Fyf>Zp$e@&5(Lx|+^O53{Q<~HIM*e>|w&#Ki zLwTb`mk#e9dw>L2V@T9*IF7HDD}(Ey zn~^67tGqW4bE%|%dVpN-U;tcd-K!==2?x~mV$Z)ow!t|mO$j2ty%G)=li1{9!^zf) z07=O6pJRB$!}|4azUm~}Z$CFf(QjBY^eS-C2#dhlnnIA|wb{;PeE%~&w2rv2GA+}V za=C$_IECgZbSo?N6ACO8K<;&W=hj>jf|)kZCni47sN~A1t{9vhYQ{aP94|&QLa!)x zu;-+Sh^w>5(#R02#B`Zp>w*bG(=7Z%35qYsda@gtI_Fb|E zg*Wf$)eRix(fxtj0-?z121)^7hc`?Z{xbZab8dq|D%52Zi5h z(teDf$RaEzM=wb@3e`F7dUu^_UEIgkxOZ%J4vpw$^}T5zsp_9le12CoHUTz0l!ljP zIva6LdYDNTb!Vkz%&CuB=8cioN@rA=88NInRVLOm8>JHU5v}P^ZLwOH6Ip^)bD41* zmyvnZx2yUOMg(=2vxx#yik>Xkt5p(fhQ|rN&REB1@YT=62Ln6m$n~=43S&hd$g0oQ z6Zq;)qhdc2$%@}uoH5@@zqqFC9U{}+41(JE{ zH)h{5A5nWemq3yiUG;*~VX`$LW%PbcF;Aw6ys7E6>FAi>NYeX;CyUzn9)nlu2d47e z6i2EZX`>zM2i#|jDCCLFBVMVWC*%v~9CVot4%HD&My(!8AGEqJZLLa1HPjPc)(XN9 zs$vVH8mbRW3r~vQ$(t6P1pCG!U1_$5V-J*M$Jj@yuLZnR=u&tM9`oMqXdD0MjkRF^ zSC5OW&P23>Zf~3umTx2s*E?z5{%0CY|5wBJJkJxsr~utGKV#tD_%7h zh!&-g^r`N@ri=`7$2B>r;PUL0`f+4Wr`N~-jCfI7&m!H!+NZ2yuBx>#h5vd^1qMyy z?F6`Ku;-G;D1U5c#;)6=f9UgmW>q`FvsR1rbIgM4*&n}D8)eol|16FFpx`ijy0ai@ zwEG--8hg45?=!;2dTCWR)2lYd^E5yV1Mv&d^N%w-XV*^-zn=2;pIr>~6n^TNx3@3X zWfW{PM(jTF<34>-i*Tl<6K3xMq?=~=O6C=sJnIHCyh3M%rgdU~irxswT@Qwj0N zbS8ezbHPE`<8OGNds8cjYq7I{Jf*Zu)(4)mo2t%~+lW|K{4Y`99_7=P<^*?bzI8?e zbUU`Sna0OZHme)*gSeZoectZzSNwy5#OL1m2kjMnV-2pC(6Emm(v}jZ_p?6aDuJfd zfH=w_>i30exXpSYi(QXsFX5j+4cxScmRp+j+4gJ1>j=(z8p=od$?w$U0&zkwE8E%^pw46U;^>G7nni0;{1hc>Dq%m(72rqXVi+eFcy1*e?X z<}%Hec^{zsp2_4+q&bW8K6EO}rwD53sNa<+{AZ-5N0&c&6Eo}QTeO#msEhM(?5waQ z6e^-#8dz%(=$HKA^JG5OsphGm!Z^nj>Qm{x?(_Hy#Pg?tEt>og(JWy@evstZ(g2LB z;O(FKv=AA3ZEb)`0Q5)j;}+`;O7_dxiH;F*=5R`i{wUgBDcUWEdzCv)5DGb+Cq{ClS7z`NyUkIp7Rhey4jIaMOo z_J0j1%s*VTUcFo`dO|mJ?F`ISnQlLN?+tp3PkwijOACn55B(x zW{mf(a@oJ;b;XzeEZc;(>-B;Y)*n_!A?#_KMPIO4%r!dlI$tqp>PQ(#YC~KD?)4zb zJLhUhs~vTw?Hg}X$sM1X(Ii^tsi~`2zQeGasSGWO6j?Mk_~pInG07>sWOBkQ$#HhD zqai%tw5De;YXt2bK&yORb*v|pAL4#rX4yP~T++?l%>1ZN>dL~C2q%Gj8F3ot-1E-b zV*s?b|GTYIpN`;+Ql5SZm26fyBi++XMbWYxCx7Y``c9z<5xf!^=VxGXnJbs3%(O)b0*XvPWwaNJ9)8!RYcv~Q) zg*|1K$aunNj2Cz`{UPhr?EnP{>Uy;&ux4hab!}%b$%?Xlo`S-b`}1CN3WprV!w*}r zI2vf9cn~)bP-8G19RdPs7v+6H6Z2cFklRc5WYSCvHY3%TZ#uO#zJU<(S?vtW z{e@gbM!;l3Z!JR`eSct(26CDIV~XaY{?%m_g#Ek^ZC}@=v`oRvb@m+e;1?H~e-Gln ztT99XKPCpS8*sMklGd7kv~W_KlV%Zpq8LlE)66FeufN|{f6-el+bK#p6@Gy8f2NW< zvG~_qFM1ZoWq*uy9(wHF>}>yoDg3|n0u}zpSp6@oe~wO9K=lveP2L{jrZ_ZXd@XFE zGSO}#nY1^vwY*Pj;pp$yGJoB(V!m4!xOE*Hce?)djN(i;G%`ix=@7Yd3=Or^uW*SR z7#ZfVUD@8t(o-de=X|tU-%@u7Nn2ZrXihtN+m(2Es<(_Refi2SG{|$i4M4&RSTGi2G(htC5hf2aaUT4}1tnsmi^?KIeks_xd-G`d|1)6EV zyoKel`LtP*()kf5YB7!pcGKY+sC#-gZmD^CwLbf;;BUc^5!j-8!z_Vy9jdo>Ip2Dg zj|it+7qGhW^FdyY&bsAQceKX4NVK^El8C$oX6WkGJ~!C_;T~;y zyy&j2rQn=wfjZGa-boBgQYEZ9@dB_+(;EoEl%m2h8?Em^^HrQfN5^rFF5l|13=_X(Tp64 z8lpG`XOm|!TSHd|B?jk$=;eQOMgh4~t1PV;)KOvU0HO)GZ{0D9`u67GEBFI(NyoC! zgX`6CE_F9CK`xY-qI|VWe1`F*5>`neF<<{lE;T^h1*orF1bIN%Oq|3`8fpswi68!s zan;}c($gZ12OoSqJbnW_>EH62ifSBP!vuMkUOc30F>ca?N=Lsd35k!FlM9eL+FM#Z ztM55;>D`+G@JkNekBEb9QL*eSeBdfqfe4ydI}2aIUmzU}v4fBurpKSTRI&;*-t(|v z9wRrImnQ0vY4lgazjiJ1hl(zVXFC#vRW}_m8mIN(xMqADQPV~a)O1BU3doS%#--v1lC*eZO+aj zbGIs!`C(BJ3AI``!#h&`JYl2@s8Y1tUJ0h%!8-MH04*n_w=F~Yh=p$a;$uB>+Bq&S zrwgb&y|aj8lyA1)ajgk3OZyCGDpeZ9$_a-6+ml=fA_-3M<|E}*>sVs+4*Hbr3HxOx zsvPq^{-a?t5*MgeSqjn1hJ)%`_oto7@yj+oDj#q|cMcJj6P zlG(lw4+=G=Q7&}3?bl6VHw%kyay+R7b66aD>A1bWF*3(ptLt}A6eKQKDbRnJc+DN~Qi zgXzAiYSq&2-2_T*gQ20?&Ev)3%G^nde`OZFt$7(G`9G;icAb(hudQ{mYDQ(IHp|9 zWhAZTVsV^r-x_)?-aHCZy1tD?W3}EPpN|hPQlVc>^MTQ=KwBPMO_eM?137wpSH?JF%lv`v=J!Xm}4 zk9Czt@LJoqqU@?QI*D6;-_*B7np}J$_`OIJvkw#q1_s)8ipjar40pAhsLODuDa;Y7 zFUE!0HApy=W9Nawp|x>^BkD`Ra9+YQ%lFG5D9NE#VX?P1kDz6H(t{slYhwG)qdH;O zEV1B+>M_Cre&G*Q?|7sZUR9(wd@NAH3^u&!V+P%vZLLVQO~3QHwD<0Vz55G<(6Ar2 zqH+rh#P*-@u_Pb8u`gh&jctlkK21ShGAb!!-y^T|(H~4QAr{i`s%i!ZlX67ZtgPNh zvC=CSUw?&_nMmFw*U`u7zauCKX3l7J(RQGbTWz-7P4l2%ol>UjbuC?qbxa+_jFL1m zMsLQjhlG+wImW1!$0#b(4%3RnXk|%frGArM*Llf!8BJ6Lo2V3~3zle4!wfFlJ8|9a zHr9G%IQ>`-cU%jY8&78BmE*WAJ>@DdDa0R7KS?P};fuPgA3ix5hyEnYqO@GU87h{* z+=xnpIdILy&BI4|BboMOQwh_di&KpXU8a>S{DMee#TAl>o6%(764TP!LoMVq2Y}pL zf@}kiwUBvDbBWPlk!+sUzpjp#7&PBK#q*IpNG3e45LIXDb_mwb>&qwRXiF#d9ddzC zS_G*8ZLIws0HaUTET-irL^fytAfQ)D8mC<$#3b;OO?WLOBq41vpv3@-i@B2PS+ z@)t;)y9m6=`^LX0d9jwQ{t%yQ@-(25}J7r^4c~>Sb`<}NYX4K#t&Q@RdZFMs-fnkGAYq(i^ znvuq9C=_d>S%Rw8C~ctON3{RF;hw8JcKz2O(B?zLXO#=QffU^DozJp4EI-+gEY}DQ zt`E9cp0Cf%Tmt4jT05sP&m3Is9GrDIMH(f>#s+PgB_hvl!fcG;`)OG0NbWMqR4|r! zZ6jJ5?X0d3*IVT)I6C62)&^oW!%+-947+Md`HTnU_AFJ!IU-kbZ7XIXyfSpFPk8E< z9_6Y$2tVvBT#jr;nCLxZo+M4;Vqeh*l_1E88jsi>&79&o51{b0BE&E(UoHhYVrwSF z;Q8a3h;J-+Sc3V#@02n@wS0dy*N6<3YOv-+t*R&;@vG!XSDmdpPC_l9dVD9WH$8YNUpxUlp6y0z5}R0Hl50@QstG#w&%Jg?Q27Zk`>8BO1R?e5=dC6d!a zW?Yt|VvxOLXx6Nk=6=ONO-*WwToR5$X}y>^&GL&Exr;fyc?pLRhia8&;VXscNGahW zIb-|?LEjQv9kX^6x)&~RF0ih$ObJ5jvBxK(e<1QTv;oSLjz2`^iX5ikkr!O17&WzO z7v%UW5K{i4ZlUvS1bfUAvqh%%LT>pRO$ok<-vE24jy46-+nI`Jxt>O)MAZ$KRmK(p zQ7Fk(ze1LVW9lo|K$Pl}{N@;CRmA~$1mgA^RPJz?I9K@mm~HKent}G&y`O2Xmcmjn z33OqczsC}gCt#c!LpgBThiVdvwrTJWe^+bso2ubjT9n2yP0vS~ z1L#i|D`P$H8Khl8M{DoirWH{LAs30L3Z?Jv>=I55yFs#Oc9vw@WjF5+@`#(ltbnV^ z;FCi`3H~0GlYxzsRp#E%qGcM@PAXrc^cA^tO|+hPeftmRSb-IrN{QyKMjqk%u}aU| zT8g;8k4MtK4^D+KgjF8fhq=^mUiSkj`&a;6p)>;rbkYvCBfjz#<8u~=^~y_Hda4s| z`T;Kl1%|q9X|G%&4Pb&7=xvRvZ&-%}H{5B!SwK*L%J$rtDG^>Wy&Q%aL$vYaSG+h5&*QJ0 z+YTT_3FNB=1}{LnljfgzHOo3PRJ`}`38_meo;bXWBy1C1KdORb_o8HBx_%S2o!OXV zjIx!mxOcb*_2QEMu`yQ{Yrp$&GBM`VBTv%ZpxM?VN>&5SeXD8joRB6ZGb=NxPc1*7 zcV(q5qIgq8O;1g@JFMBUC6vBp7-x?q+z@=>xTZbwZD$E#FFW_kc&_gcr|jV7A1rLK zQZ_?WAygrBju3I+pRhqjwB{LXm(!YKUf2FrB0CJKaD?= zU+%>u8E3shjGQZyl*mp+lXEYjU*-N{7Z;a8l5yjY?jJxr=Wx=3Zz9JdB#s%Z;>B9- zSYgd1qSX5FZiIca8B!$wnD`B=shS2Pam#54^D^l$5Hs6_4>RXRVXJI143Vsd=^yq!!z097*srR#CH~ zPX8q$`%#anNf+@<0V4hK*=_IemhNt9MHgycR^kfNg4#P~0Qq@$dbm>K0Z;h4P2WEA z-|v|Ea34hkM4&}8CF%0HZX?JOP*6SO_|x#nxcjnE-C$bK-EwWLw=KD;ju4TV3nYb| zqOWBF@vHNz@!4bbv;3P^<_d?jK+wgZr_-(OvMf>H!-OXj_6k)yKM-`;*vl$gs9Kjg zgqg^iQO&Pf*b4HxviMI=6x=;()vtQS1=VZxJK|;#as-RZr1We4SG}NPw|AH#jH^0J z&D)p*-kSSo?0$6}4%mzhGmQRuB0mU4^MT>dn*{5-%|*90I%&jKtW)Z_c65$*nn&`H zQJXa(166$_C1t7B(|4sfs|68PespItEOD%|#acN%?ucG@?*Yu+PJp$4TUrg(Q@{jdG zSf^exE>_Rr4usca`un<*mnK_sp7t^wocWU6PjL{<1oQ+uz-Wl|`nehzbfzCEiM zc?_?F+=3cIDocC$$B%>Nwfs%=HzW>w&|bb;*o1q3^)8cDc!YHlRuTmJTLL_yQj@vb z00P{@8BiA>*})fdS=MrdvV^?}hyRG8dCL}txTFAFgB}reZ`n$66X0>#rxXEP%QWL_ zl$}3DUfvrQQlO&4nF7kVI!4B|xr!WJog-W8tGJ{Y7{E!cYNQFM6U#vLZjQ-r2bO?GB0WgwgoXuc8EXK^(yE;Pozy;2&x$r}-s>(6bkL(j zVPD#x1dkz=+Y6jq^vioMk}sac>LzHVUXu#~D4_tI+Hz2g7=4oBWEn`2y7Ts)-Mgdx zZ~RYR*;liQgo4go{yxzMxQ;GPB+IvH7aBjZ>WK{7Ev%z1495lQ)(s^qt+YLDJ+xj%3-$3-Eek7ZhMu2hQ?3iiyQCyui zEnh!rXy?fTa*8<=Coa&0*gqu0m00bjFym67>pT`u>j*Vi6Kqf zx{ap3FAnn{#N;^{8k+~W)8zAR@yI02IpU>Wblg z*Dg0SzId=z`4Os(5kftO$7V%#*u2&f^hn~5&u5AJ-Cm_pvPb??ovf_qpQg#sMVC4B zZ_!C2m&Qi#c5O<7y$w$??gW{5p3#ip2n16aVq!0la!kV=BOCRwgWSlLQC5C%dOVs* zU_0*nuUGtx+^C!$Tav&mU{#yG*J& zYiL#Aw7^%LvnN7ZMYe?8%HSL73Te-aUmw(-=2e7PL7u7$C_`si8Fvuf@Ix$@zBXkw zT8dUeMrAjK@CtKth2&V%Tm7Mz1f)k3@{qcYwqgO%w}JN>VHKmS?)`AljLr?G)s%BE z5%WGayrgEK7l8)J0gm%cXmi}Ly}GuBY5Q9!_Sh5^t>p;yzNFbM1P_@`;}^-pf6%rsJd*MWPsM@YyvvK@a%&#ZK$_>rUjo(sK)S(}}oB^rW3;>Wa zAf_TbhZkh}Pg=~9;}wSJxI1Y;Oaqws2Kia<1S|^yyoKnyH+{Fl7XbE%Az#~0%PZ%2 z{S@#-;=F}kAZ8Os5LWT@5rVGcyUnE*X!IPldCmsN>%oX9My9A29+?0~+M zlD-YxzR;3Jiu(50-@U94h-n9aJVf0|18FD)NKnjq{DK>tNeO$`QC5zD93gc0n>24h z>`>sOONw62^Q%t0BRHox8enT^MReN(bLv{-= z^YW7^^{qX=coVgXDgB+Vzu@Exy?g-+7LoNc+~fQd=1sJjOA|^8fBd&nbUy~HI^MmH z=ek#L&DkcNo!p>h;E7{D_j2H_?>A|2C80x9vBWL3WYG6luPB(6Fu|Y6oV>rH5uK<2 z5=psKew>{5N+d6{g1?qX|3CkRq3ByBg|u?jtBoN^N{rz{7ETIDg=&0d*hxh+bRU3k z9RN83JhxJY1*SO>;txc&sD@NF0zp zB?*SVK#sB8LPNnQx)z>|n}E^vH<&io(7~xw-m1IkA2LlOd0Tl^kHmtix9iNZ+I66J zt6x-HoSIX2g`>0N5euzb42Qhe@_KF;e#>Fh3CniUjJ*3nAMpaQr8XTyyVd{I`Q4CP zj{?D>eP@u`;@I3yy^}ya1@Tg2tnr3(9Gp@_3)dd`=dehT=)vTVNOvxh48<|PHJI=y zvx6$Cu;x~y8vI>@-lknOwen0~VS|5Q)w65b=~4gvdW%O^R$BhKcg}jj#R&kn!F)fo z6+(#C_2@MtUSN1|ic9&rD}EY+Hi#B(XzQx(#O{c>mN37Oc0-XVJxU)o5ZcFafa}*M zhe{(WHmC~iNE^SA)V)Nc&EdJ4eA)i&yogi!`pDH#>w*K#ey8P(H<2QYbDlhG$gN-5 zI{RdhB-VEEJ^8FU6G3P$r5u|N#_m}2$!VTxQ-px_$aS=;8A3_#WrwFnv5`lZvAHpR z4|&wo9-1C*|H04AP3?r8wmOIEgIzZpRvqzFAr3IpHGYu(C7KHeU9i*Q&t{+HGqA<>wPkH< zDe!MUE@Z4--fz{TWaJT`;i#6!`glC!gH=hE)fgwPNcyuHe;B8oWYj70r#K0w3!5=S zJBcT8l*~xDRc?8(3Fc$OC)!$F>cahsOgi!({FhXUMO0!UjnIWE&K{E(C+p6_IwyIm zauEv!eT02=M)R-(f_RLZrn$(vT&E#1vZ zrnx`LiQx1qQNZ)Yh{Y2p06#arp~MD+UAatBp7E7Zvd(+>(%`l@iAFa&PFK1;6#Nxi z6ZjN(Bz)T3LfaO+LM2SuSJm;LTmc@^^#A6{++jTX0*w7i8@!_@y8T!@`sL)u?*7Hs z&@BAlC{ABzbdc`-$jk(v-NY_u+*hg*6Z zZH|<$20l*{_6W<=rRg;AjudKcFE8}wPY00&akBac7(-sCI65V~O4bP(evRe}?Z|{O zmAO^AO6vm^AffW;3VP*}+|yxF+u~EO(sQPSjTv((_h4&EKSpF{N*`h^l9PJ%Hk1Xj zCf#N;$g!(Ju}Vwu^m$P8mL+1eHV8dMnNo>+6d(bD!K8Pd6o=~iYPyS%lKiqFW)r%^ zlc+FnPjS}z^}T%4RI$P`oOfxyyeSbs%y;tAt|L;Ku^9rCcO`S}sWDo{E!@;i-9ke% z^DH()xkwzW(dCpa^qBf4Yc`IVEU1)BGjZiBcek_D-<0;#?AUk1L`Gkbl+UjG=QwP>?g;v@qpG083vzq9X_ybsb+$Nbl$saQx)yu%jt$O05Xjoj zr6!&5BjwvT2ksQZiZ9nh0X;yZ@#~=q@1mAwcT%D2Aoz~2FVEl0F&s-i`TDcdelt_W=1)O=OkiETZs7O#bRt zGfY?-wDl8FBu7Fm!!nfd(&tvC%2Sz4ahzhaDF+RKC4<(ThZgcx1)Yao!u3!|HwhQr z7GbpeQ3BQC^Nzulv~cylK*MXUZ%1a3L^zH}X1S`qOSPJaov|NK7U^`gcI3ty;TmcL z!r=lft_KEA)Oj#hn-6r!{g=CYQ0uC`{1s%&b~eR}{LGdxm)H&yIImf-6C+PKBNv+e z;+v!}Rh)xJwpNO;Gf9Jt$#9$E>V)3BB4H$0M2ca7 z8z`m!kO`NDJ%nLev1QdH&KA{(5@8(WCKCvewtfPCao_Ac_!+%0M9+ftEd<*>)J@-( z2zP++vOOH5PIZ6)n-_|5*z%1ne|#HXn{l1~hvB{<4yo-g;T|){d9K!(^%|k%rDiP1 zq9C7O3$atE&1x6c;6oZUI4WAk;tGo|F|$4bYTDG+N`ndA9Wj z*GUP%eD5a4??kB=Q>LRgjT+V$XaP!1g-}<8*Dp>sfdi;4w6niWD1jamCfF83g>VYE zh4YFHI51TZH3A%$6rX*3m{kKpZ-DuNK(C6}@$8|5!4~=|C*tgvr``@&4sayLi{o8& z?t9IGh5x<-Xc`5v$Tem~1H!n$E|Mvr<(rem&c2;oMlS9ZYQAeEN@cDs1!9bD3+ z--GfSS@T~+7`xw~XVo43ZTntUbJ0C_X%acrdG_E9;XZtrl3tvmD3#TB**ns)u= zWYMIM$kMQ_BhWcYRp}pr(YmAh=fd}Lzn@$7amHGCe_btbZ{3FVlkak}`)yy6;z|7< z6-g~}8+JG%t`kWej;1-_2pT!n?rUd=oJ!O9e+m8c7T$m9kKnMm;QcP(H}M>SR+72P zbWi+?5>O-!MuI0Wu)jAC6%4N$@t3P>+9DWzE*PK1q+C2tkO&_QMI3NAP zm!-Cs^S?m40Gj(Z!<*f@g5eo_N=r1ze~Zv$rD(Dq+VA{a{DgEQW8xi#?Dkyv^hVrC z3vk##wJ3D~ z8Spmr=A5GKG8bkE&%S@+)7z`pm27@?#1PA+fiqo@&i*2Negl-UbA&X5S&~hUkoEE4Gsa`tM@ynw>OD=J_PR-bq}x z;B?k-Rj!wJft#uqR!%!9HP}aP6yr7RJF$0+R_p@XIu6){K{%IgxkvTRW;PidnjcQJ zxv+yPSDoc)%Ki3>2TRFor7@(9l0kjU*8DCZf>?f3$=fCsG5LP*AU`ftVNMuA7(y9j zFBTXD78(5C|BomHm`GGzd*PqL+s$ce?{8}vJs?;0RIz?73^apji7RQ5?l*M-V#j#b z@ILuSs+{a&VKiUf-7e#kk9L6{o(e)`cC3uAfplhpeOaJaCsHf z=vUKXFZ0KJQGGvt=#TvL9%DLc*X{dyzcIEq*ZCho+f?XTIp2DzjtFO?7O-9_GMK(+ zTouh}FbMX%eYkzx;4=0^$|PLZxQ*-h-hf1UkM8B{KBRQs^WwSItl9&(cKXX&WI*=; zUpl;KNwv|g`y(swt4=BhLQguClvLV`5(DHTH#xh6Xc0phJ#`_q@YDOyGFnhBTc&CJnS`* zORWnEs^RF`19ckn9Q&gPr z7J@#l07k+R*kAsd7#C848QVq?=mb14d7xsbW{G6JC-YDeHK;>oYc_Elpnuu?IbzD2 z(a~;kcVYr(fEEX)0b!mCN+QtS=N2B27zhy)Mn#?kT})y?(~=!Y;zcC}2go?=3ToW@ z4~Z%512i|%CFA&v~dfD^?;Jk#^r4w-ECT{VRkhv_{#bw zhTC}Hhh%kFV+I}R23m%y6dCI5rWiUr{Bf+MuPCrHT0CUmw_Y;=S}0a=FE(HSa{$X{NcM^TqfAegjgX+0b;h|3K|J|R7+v-ti4RoHRS!v|&fivH`XQV1));WO;hY-w zTvpOQ;&ZZ1Pk&6I4J&!aDn;-O!%U{O7mCiilRKvzcf=FH z{?+q|+SY{iXL_5~kSsE`r-Y_hz60v-g_1$9rHNr_->{?meuV|ofZiAd<8UCi46f{P z_x<2>;G`-q69Qr3Cjn}ljq9xhcFUd43>`1}pA?mJJRoCBg*5E8VJ6`@v+r%DNNGY# zZKi0+Wecc_i>RIOYz8bzTcS`1sX5iYk}&>qVULtcVnJGUK-vw!_w0?Rfh;CDUW^&- z5H2gDED8p?q1ZP>{cpUzbx<3DU)^64}Fkdz3v;LAqlE+o}RoV4dlH9(VJTJG+^qQ~$>MOmi{bt{A-j`nJQ zb**ByD_j4OC)tPqrj;{R-P9e@S~6q9pXrQxMTn5IsGr3}hB{b1!6-S%s%SZ~lMSrw z;E90aVD2-|B1r>v$MF1P!_}+G0c`Hd9cvro=e4>%l-Z|zdS=L6y1jy@mZ~5@8-=-( z8Xx}<4(`_c%_7;;Sum|ijTaoGSP=C&-Ac`Yn(Zs1YD9`SB)B`jyc~uWL9QKJxJTtS zaE~_HQ@m_G{VkRB?FfU9N+_l8qWmAwHLwAo`wbW_&87YUd5bGXDwVMOp%?x$N$w`= zPZzkR0+g{TScPh*a_^Jz@3-I_%skmI59)!BDH8O1ADA=2Ex1%RT8PLM`dOKSv3yX! zCF0m+L##XC1PYCnp$irI0Utq~0raZ2Em^NBH^;2r1w~Qj7nd~uHV+F;UGJ8<==33E zw?RW{PtLwJ=GIoxnm-ta#Rs^@7H~P#kpA+q6C;RYZIDd?J6AvPx zR~GK|3iRMPbV{L&S0a@_yQN9*EvsPPp3)BI;> zM}yThB4m|apnNv#!5lm@4%lze_%8NV|QE-zx`3C8o%n!liYmQ;Rm=F#GuQ3Eb_L8;6c5}2s=oa-dBeqRL1 z_K=otC%o5WG}H4t9>uXK$u+_`{lON%irEEP_l=}iD|Dxh$~sqPET4DKH9HP)h(?vf zr@9htlE<6~f)~DK6PCf8;zcGpCl~H#^BYyP@tbFl^cgf3ibANs$cs6spx4G+XyjUP zjVNF%GDYbNwbVf+uYY8L7%GP2tR+^o5*Qq4+Ej^Q#BGMtCxP4)JAfJ{+U1`WH2*R| zIc`5QQ~$OTI`Kt8vslFk(_eT(ToD`!Br7D)Mk~e&%{uRF0`EO?xRZC$XWD2-$vjJ$ zl`9pTCa)1{<-M`;B8WEh-$g)_gOZ&I$)ycSkDtuVm(@NCwHl^1lpB&!VUxEk`FiuZ zY=&d{@qh`~vZc{vWe-M+B=12Af_h}tw?zRTz95zNTjHY^a0-iO9w7ap51 zeuKWqUnNWQ4ErmS=TTDtwq+wsfNd&R@ys>C#84b;HWU+^FvpHy_>o}D-8wXn7BiU! zt9)}+hyC)r{Y#KL_>meI-^!WRoQHGy-gFf3m_Pr$QMls_| zJFOi^rqV*tR1m7&vfJrhS2EFzW#s*c)L@XX z9K`0MQm)p}se=J=gh=CyXoHW>nL)-Lo5{z&N3A^Buuf8cx&GYb<3|lPccx!suqyd) zoi3mrE~2>Tehn4ZttK`S3h-B#fCPtt$jAg!B!)BO&H32lHQ!gFz@-wH#U^&druDHH zivO))M5ob@Y!ckXy|Mr5CPCW(1LZS!UwQ*)xw%Oj<=^gi9f<$%{O7j>!QYM8{~VyI zoCZ3?AgSs6867WO*zv&nGXLPsR~}_g4uOLi0fsv)q*q_rImTM9TTU&%uD?7oM74R9 zH~I1thjc>Fk$IGKjG^iK(k#^Lx%4;a*Fhipm-*&{2jV8{)IcnJ#}^pkTY1Ha>oJCA z;iXx@*K_sC<({J=jd*`dv>#uVzufWzzDx(?DxbO_{`vdC?))eF+`MXyOFlC7(M_nT zfIcdq0AiUop_>EWJBn*=&-dF8yGD7zC5!DCMTfV*Dm+zNDy_%YZ#TC}J=LG&tvl8i zYjM}~w#mlCH{RW%VA#~ZTz3BvCdLr?|GJVsvA)B~;1?TP`}K4#pwCr6rkb4(D>U@f z#Ru&6TFX$dCxtnnTbogPfh|E5n-3oLL`zq0sO@H~0L$U3VbgiWS9M(!NT~uUG1)tX@-;VEb_J+hHYxj5q z75oNQ^oM|Bt!?-k^nxVzz#&`8i}eo(`l$*)Fm26YoxZ;7k}nh~HD!AO!2*WhobLC4 z6MGE4f0rKRMd>gQi9KKw!NHKHbTENyIcWzxe3;;7R#$AXNos)8F-?6)*zJ|D<6a@%R~#7lzmAJViGnCt2#7*D7kpK2x-Qx%3veqjt8lZ>$3j{% z(~?Dp`nwAP@)!+7M|{vTEVykBr=%tLw^}=YU?ticYU_-Vcj%2{dY|Q6+|p(i?5lZ} z-#?%U((f&Zmz=rGgqni?fLav*U&Y;v|Np~OG5CLCsz_xnc#cTu2~Yv#7W~NH=8wKo z-$%sNd(`EfWDnqaxoc&&Z^JL$1fD=o_N?pz|6P;fN zZkSl{ANok+q?^h8alOqx*pI7|GIy+wb*XY{oK>`Qvykjt_&!lqxQ2y5(N`rsh3GL9 zP-;D2NN-3k??zwZtXtxD73}&+N*2>%TX(^Hp;u8Nv?Qm>>ZxQ_o2VCk6I!R6Pu5$a z;Jx2-v)ikwS8j>w>Jp5f5ReYss;%8(Q2bv{HM5sc##{|v;%2opPVENP((T7mSt7gQ z7F&;uPYRfxGx>w>#%}B^cZvAI+Yy%rN9lIjluvt=k$d;)QLJJvHT3kd8tA7b;ZLiM zs#9+z2s0iUW}T@DE~w(k-xk*G9t}1pPhRh}48CMH@NLS%S2!csn)@Y69t$S+e5Y&{ zV%PZy{iw>ZcGcC9x`z{8t>RC_`Cq*c{tW-MG~WLIy)YvU zPw>76YBU#c4P7-_Va~wDn{wb!x7Pot`Iz#3Ch5-o5(k)stTa5%cSiQR{8%f zQCBZJtV~%ku*Yh9rF$x6vyHU>W$kcEiclW#ot*6n@k|CsB*&6ITfm z@r8y3w-hp2MgOf(*TMOjMyQ1^dry7D7UL9g;eL%S5U`EIY?Y~NrooA?+ zY=$?Z+A}FzWhG-X<`L_hBbkahLqMtGzm00W+ExwR(mUMzBhhHR+=iy^kH3tqIZ*;-e63 zwu9647P2vz7UqaiHu|F+op_5584K{~{dN0oDST9zhIJY%qP(+}gGI2cFHczzK>jOcoYp@_J zO_BhYBhE2zx(d(!WPQkHf9C%0MQZiT_M$@rbG-$n1bo%Ov1M24gRRzTAt8g!n4B9o z{n}Z`>d>OZW*a(qs%cl3h`uzN)`BRLt-dU)Uz>z1V^H7dK4xexs>>g2PQC;YjFZQ> z#0GVK_N{_&{an$m&YDp{OnFb$e~q%b+*VTX6;kG$8{~4v@vXF?1ve5#qOOaLvR?%H z%v4VMD+KF>G8Ul`%4jR*o#u}v#X{%`B9;wC>Goh{9#dOw*@g)JsKhR8j3bi#oknn_ zFVvat9Dvm5{k~YM)!BfvdMwMXM|2WnA69db34=otVt{=V9bo*+pzwQA5)b4>DSoBK z98V^d2QBvKz@1%}L_t;Q@U1vc07XPAcWY@#$^JK~_M12#pDFbD9lj?sm|9#{2M3rp zvZ3PGAIs?@bY!iXTm7hM9YKVTV5mGy(7{Cjv2{XVfPaG6n?kbx-NQ1|Q5~S!(|LI= zmHXEiJfy)qcfa4!Y}VGKwcv!>Gs30b1hCFLZkOLmI>$ve6+7A{gIE`~Qlr?ayur^K ziOKkE0q>eOy$+siv}8&9#&!b~MBB~%pki95t)k=CxiFLG4Yd3LmvuQ>N{o04`7<-N~xLtU~e4Fk7P2Hg|_M8MyE+}uDFxS zB^8$wVYB<_w=}+&bertT{Q(ay=jJLdlM`8u((HxZ<<)oWA-0)sdV|YsxPkuZ6D220 zYo?i{ZATo1%lJ^JshP(@*E|FsG_mBL!7P{ofha~J(~5pi_qqNoOkSSb{av{_-y0+t z&=m+utr_taAHiI9h|>a^X2NS6*tK@O0Mv?3+Pn7{9d(QauBty{8<>%X+_2z zoYYZs5CFRWy^;E2?|yinP^D22ngI>Sm&?>->#|(@+;a`{_F)4g)G5)Xb(>er;QEcbfcvKN|_Y5M(I`9R5xEM`Pz+5}cdOMGOjr!evf&gLM`C=opeltDw26-z6!Qks&ikgNzxs_WuE&eHK zm$j={UP+lWvlUGy(b5(S_G+pfkH1i&z%6I&qTQAv8B!J@Qmz2vRg9O#k!L)9v*IUI z#6~n7HnEcIEa+g*D^;tYN-8UI^-hhcX);JMgFm(jKvFd{mQl-6;+&{bCii?dXIoJa zQnGO%K$Hw3g2cG@Vu|Jba#<7c3_C+; z{yK>NE-UG>o#gJbG3QAHWu=3Vu^MsSq4TxKO+1QAu1IegjunLO>u*b?(Si7$I0v)z zG5GiGJ1il$_O$j!XVMZDzIIjkYx)$mC@<0hx>1L1Ma*yj$6))&-PhffK-`(`tu^L> zp*GZHJISAsc=2&f_bI0MLsdPBSFS|IN3)q^VaL2*PcReGF{DMX@TE+Gumwbb;pU}f z&4x4?agC+fGR35c94cwv9cmCUCn6QEceD%k$T2P00TN1F{h5x6Ns#${uie7pN-s`( zSfFLXb$U`iov0xR0y>sXnCI%ViMT2)7^_tKHF%K_21ARpV0cUyzYo>e4kxS$x)is; zDFx;TvOkRh$$x6&VkPzB{gGqo%(fMA|D*ZkBc?5z<@SwDMH2^qu!n$Y7VnHDw}sCnuZ>Ar8m)0Dy8zZF zH$E9kUwn`)QgcI%Gc#Edl-qExuabjPCeBQ2(S@Crs=3G6(`RQmP&)}w(+b6$*)oGI69Am%OrQRW4(Z9 z9e2BO_h4#)F<{$%G;+sVEDlxY>H?x zL*A#5+bYQ>5;)#z)+88@_tRCMfAUy{T3nS}CZU+zoK9918(tN=pg~$S-6W+1v#5A`Ji+dH{gdPzZU$ z0rbm1y;~S|?4KLNM{nJ|t)ev}HZpRRIu0%_5y`XvHBbCc!*N+nU=TW7TU*=SE$X5~ z3r83^#3cW{1HX3|hJ*O)nd7B5z-dXne;~9{((TjLEb1L_MM+nHX2#0?S+N(DG zK3a=zDD|u6r?N|_RYzStidSvd@0Z-Gsth@r01;YBobPSs6+i&3m%m*51?>8zNFe^L zm#8qbAO9;Pd#Rh0^u<^!^}n!mboJsQel#qRzQ_cM8&XuGS@(gXcJ77E#JiGzas2}# z$(4U=dp8+gT1O@t0c-;RBzOf|^_G!}6%2~k+PGY$joQ%XP@{eQfily&DSxjCv9=7c zOKM<)k{B39T7@k4f>YAU_Kx#j!zTO_XZq!@&hoEiqH{^QpvYb~Ug(c?x5)Ex9e}VJHXU-F_b`bIy;BB^~>GDaDf(PHzy#+&o_yb z8U=)(1ogbrvpD!2;?sDx;a0H+B;(QGW`&3OM&u+9Zs3KH?@ z7qN;~0g)7-3<4!7WW3Sk3E;u#S5SQ*40H^P0@tur{Zi*Cb@JNu0VdZ%ZlC@E^`6^Z z-~7ixfw{@H1wZ${0+0|$>sH2~x9gbndgV93^R^RcaeTXfue+@JevNj&^Q&qX%yRU^ z^+yySCF!xq<&XhH_H6$9i1N^^Ku73Je#dLg{E0rCnA1Nh4}{BUs;~SWe<|Y*3RKbp8{r2>KzUCvRZh}WF76jBuI@N=iX$k4pZWRTaqoEhLB4zF zs8;WS>DBJp_F?FGxx)?4oMvQ$_$};pN4iSxeK)7;9l{S5jkUl>5Ig)=LQwc)!4!Z*|Ee9ovx;XePi@UU0!9;F04`soYP^c zL@w7b3xev{uj=M8s`~8NT&5iIMdA7CGaG7<&qSwtuHQ`UoVf(?Y;`5u^f5-dJ`H{% zHWVGGWG`jl!cipT&Bav_Ri!Vz>$2R0L9?5j#ab7&{3M!`0p6QDGoGMu&kI4#35#h}f@FqSQ z!@8yB7K?cJy-wkZY@V~$g#-`t&A=lZ9Z966omuaDuH>`Zh+jnHFXNs*F7W0MVG-e& zK{z{vMd-ih%!@Ss(jC#H?2RRer5`A(zHYzwkv~Ftc{PMq)SB<<@RRryai)j!2eQEb zV2yi3jq$yl^}6Y!Uh~0%Pj0=?hW#mL^ux}?t~kl!e~iyL~=avbXHi{8mWnXgs~GSv`(JHtL_lsh<>^D(DOo`O}C`X zO&er?cz0gNAb<9X{alev!i}->Ue3bexClHU`?vq`5m~r<3#}GndV3oL)FoSEaKRss z9U#SBd7v|&KNwgXcbbCEAa;yy{d<0bGnk=PZXQ&yMPbH9A+F$IFraZaj8_AId6;}8 zcewfu-%xSA$!|xmzx);mpZHjw%uUFs;7b3_youfPg-V6-sk#n*?+x}fD=s0Zt*8KrW5mVwSQ7&2aVw?Xx z^9Oh<09u)$@$DRL3XppA??4Suzyb;yv%|81d=tQ^z%f>RNXp%LLv+YtUyZp*cO-+0>2?)N?Z96&ZuYr;FZdTE%uiATT;@ z$_74{$I>67#?kMMRED-gwhcN}bUR486Iq~`YYQ_=P4M~^#0oBuU_M}D5bL3IJX3PA zE?*L5{G=d=Ba+eaEAuhbQ;B0pvBPkiIR?rj_po!BjNWu#p41TZ2oGOcLU#-C3ig{*U869H^4oKavo@U^o!=Ryq=7sQRESbg8 zN}dV0fn5lQXJ_!*V4s*#%|!V6HW!DhBR5aXz>m4(jgnMf;QY-7y=RWfx-dGq-KHI* zG73Q!4l)D2?&DC%_*k_&cXirIlf3>JDa2`(HWqH!P99rl2fzhhdo>6g(8Yb%=)LiC zbH*XFu+tS^6sax4PC_XP7ZFELo zYfWjTs&|t2>qaRk<)=%s>K*7{VebmuQ}Z6A#*7_^zxpgNqAV?8VXg{$McfL>BVF@F z$VT&8<8nE=!PEQ6#T;GD&Xr;h>Xf11UwiiHP|ex+Z{;fSrjj4V+lM;q)B z3afNjtPjVnvEXwtDy%jFT*$4|&w`;L32fNyOyk@o+D97MzN0f=%h*JM)ZkGG4VtQh zqf9Snc+!v}lrnU8FaPYr%zE9``8swbi5iI=n&vnmPzKw!pP!pVv>c@F6KW&f5{o<^ z$NeIscazbyqW(tvTZTLl@tX|Iq$+hLBFslbPLmLR0&I{{?$3rF}$|6 z6n@Qq&#^>bS|>_$tN2u);@<87JsxIP})CbB@=G8R>90UX;2mBe9C~vhKc!s`_YD$8E{zR(N&zciN%xd3UZ$c z6We@J;iXX=jQeJEZN)I-EpP6jn~=$SbpOF$$sh*HADty`eOsq-5<-LTj9F1s9*%I< z>!L%C#-!sL{05UGX~Yaa{`slv>h><*G9M?pJ_K|#Iy{yBoLW@nspcC5_EnMTf}6vh69fSY=TDCkTtN+2`nYNHn2z}R){GWon_>Q~a< z=pIZ~Tv`oRf2SEWAL zwP;geDHGREr_CFb|KUviqMt7Gz4Rerrp3w?tOnM2~-8hgtf7oZho?$W>uG^19uDzdP|AV84(c7PZwSr7C$~Y_~i)VtW7D``Gtr+m737h*wEiyEmq5wJ0gtWF|>+-QZ-X*IlC%aA^8*yDM(B zo*AK?mt;4^=7H_nS*Ah8Fl>^6tc->JD=)Mx&$e@2)nH>dLzJ?xr-4HF;uK-^iggl? z;RC;1uys=qmlG3L1GJO&sK>A^YfNVJ{;KPvR~R#%28U9UL8#9Ot_J54+>E zEbS0xR5m{PeS|uDx#Po|nWaiPV7QDi`s_C)OnPMVX0GVC;g&l`u` zwPgs93i7{@gW)BRP2yR!$S%&U|H#ksg7-95r)z>!niL8N>;#nf3+*?cVRiji)5OO6 zI_kOG*hacI)<+lbYRzxS`-n2@+0(4soaXlieImqX6v~38l)5m-{Z9SYLGCXjYNr0q zCsQN#+MDxhXuv$`dp1*yc&E0%zH@Q-hpmydfG@o;`i#^nt|gZ8T~Wj|vD>8y5}#a> z5E$trgJh{@e&rNc$V;p)si%4;rmV_y^o1#K;WNlLP5#^_T8Kz2DH7}du>u>B>}+f4 zB{bipNO|GWs5?D7sZT4inS&iX!(&aLi$nq&&ch*)6|Fafv%=L>d-1VS z|JmqVb+;8tX$7V{)DFu3^c-p0YwXb!pgAtYV0b$J)aw%xWr`EBnA33Nmm$Iw|J7n*6{kFWL;mO z!P+CMS@)tT&Z3)weFlEeBC@AIh*a_{tx@No47Si%4p}~+OyD$*m*%q`!Z>m z{h0ObSZ^LCCho-e!hDbjX!SI#bgXokq>zubo5Hb6D>dsZMxoI*Q2c;0N z02UN?Gsg(!yrZiO_|W01$>pl~0ISi!`e1+EB?-@+9@Wyg%rln6jim!`u`oWt<&Rz% z&6+6Mbhw%FRiChCAsE@6FB);3SkZjVkSdFI$hu*YkG}qrjJLWXBzt^?Re%RK!8Cz$ zuixg!r6%Ql8bV-x|H6G>g`GZAuoZxj4SBi>|ocWduG*p;kK3*t8BG?+#6%&Iv znwf}w&U^8HK=cAQPi(cKcRuT56JK_l1AS|m9}8NCZcU$<@U|y^y)-Yu7Tma(Rhc`( zR=6%ObV=h`kO#Hzn9JLiAp9Yv#-baS8hz}Yakn)>68emL5Ui*}bI$EzX=GtdSMMGY zw$pLIeO!%)I!4*wP_3-BtESp0rLMMD7ZR|>NMOP?Cwbfxymy7#=Q=lxF~|Fd&*B0J zW$bY3>6md-jODxZ1hJYzSTADSIwOIxn>rhBqa?{nJCMD~>kO@GQFiYmS@7rGF=4k$N2Z+4@H8tYrmKz^D1np9)hbk5FG70*-(;F2CGpxWgurZ>`C;tDntN@Zqrg%XBYEOUd-#ZZ85mxBkD!`j*m3QF3gO4f#wXrt4~!TT4z+ zT&51Hli_fgl^ol8E}x!sJXx4hNos*o!K;+4mJ3Z)!W~B^bCb9s)%nNc=bnhB?4zRt zCT_emHXK_jw@;jHbKO?9k>(S8`YSE{m~t{qUCn2nc6L+z&jFJcqvl{S1ESh+i`EzJ zYFmAIPs*RJBx4{MCdwwY=5u$yWv^Dmzun5e${=mDvwwmLw!1ILFQ1eJAida-2OWmE z07RAm)K2oHPLoVfAu&+*g&*cqgHQ`@(E3_1?08ee3)-)jmR5kBI;CFaPw%fA*nW95 z$&KJ52BJa*EFq<94CM_5ZC#Rr>hfBY@HqP}eZQ?JLyW(on6tP;Hi0D%dVvG_(*w zVk0YyP!E3~!6hA&^bRVkf^{RSK+7kuu8jH~$yOYo1tz=WLkcMq33~Y1 z|8?*sykX3jX@$Huiu*z>-t@J-bxwbHINPq;Mg865R7WdBXjyiS;|Gl}nSZ@3=pS%$ z09dn1(`d6pAg;aMc5ff%a2h$vRah{3>G~aNLdE$bxX-w>=_F4QJWnUo+#xh*<&ai~zOI{WYr`Ds`;@rmkG)*g?9Mj~uAO^%ceP*k#`nwlYj{s8FZIKH1-g2squf z^%oL_F@taY3;sF|OBHOebBp|SU#@1@PjWi{NX<8%uL`~lJ%l|4j|qh?`^See?Kg|wG&r^y)2Vx9#xQOdf7;nUc#tNJ}4gK*f{Fn|d> z5W45i)1&NMQc{*=86MpwFVEs0ft1Cust-&>9|;M(e!iAFbJ!buCfFKkb#1F8fFspg zJt5e#+uL6dW)LUY)Vj}d(PzK4bWn{h12ws6=qsA(waLpy@-$&>ga=mFBo&62^2th( z98-%S4e9+rI*Pq^tvQM9r#|E?oFQU~vcI!xX}MM3yH}Z;>)0A*3`c+>1kQ^5dlpa! zcK~VdbKWzo&h5U=P7h1C#dr1z>!u8+i0o7LPK_;?*GzrMU(9vXbXLPf4*6=k@m#rm z3O$nZw>Yz!CD^={h*KG`J#)W5l&NI6wAcqQq4Ts7ccC#7=+LI54WB#D?;p2I!?`e3 zgZH;~jpAcitHaDW8EphVg<`OCg0`V1jiMw(8iDvsS`!y=hg zVB=Y;2CSF}Gp{e9GDd%=_(?BPG-`%ILW3@0#DZIny9UJza!i>C_i74!3@@Pd^O4?z z{UVUY?u2m711DnkqAt^dMRSTNHvB<5noN4%>JN~5j z?7TVGJqIy#s6{1G%|;sAm<2MeCT~G1inr%CRj5 zgcUJAPLwZe96>|W`dZDY>-VFAgb8htH%(P8CmbyqwOp!aEPk*%@bkksyHUdq5>nZM zZwrp)Sar4UduL2A8)yq%AG^A?mr2?W0^Y6~Cl)OUyKaZ}T1rqvbUfsd0}9;@hyy=! z2}I-MYPagAeQ3w7za2UMfLa|g`vs~iU$4qhvdh3NN%R--ew=7Uf_o)bOEW=t^w<7r z&RCui+uYU7JrBv%A@|;utGumxwz7^6X7?dCe%Z@BYaBh{L8EwhQ-c^SK2gG4PIhX^ z58d8GoB|*4@fS8X)A{x~iH+@GMoo2AzbJc-2IO|sOau8!tiAO!S@u)mv&~G$p1(Eu zzZ$NzY&7^=_J3xvloj1@#FZ!tho*r<>K)jNu{YI&&CD zFu)s;u|d0Ckemml>iSu>uMy%KW)AXlB1rEmCxB5YoO#=!; zC=OWI9P{6ILuz16(}pHR<^j*_x!P%^M2GPyloW>Wm^s76+#YJ*I1)_=%?WM>$us@= z5&lIk>@@PTim3&cY|eC3p(R%?(U}ZI@v>Z= z0a2`5ag&c8h3i(A-6Q1e2TzQd1u-I>&ZN{O;>LlJ1+HBFPTuwHW4R#`@TM-w;A(%s z1#jHc=icVJ?25lz1>A5D4}w%RS0OXU$R~5&&{gmikb1CzNIpyo@W3IQBHJ={3SZ&9*s* z?of9F#BB`R>aZ*4=ZG%I63%_QY8Ya0lLb z=p$LIRd!1(36tYFNct;$1A{bpd|b}9x+MEoqO;7DIdIv|GzT43n4^R|zW9<|&;o@>vBC>}G!6goKONCUV+azZ z$bcqEXsq4u8g`^O=z2e!&n2a_gYsCe(!QwikP&Z8PfcQawxc5Bs_EU9;dV}(GqwJn z@5us#)y*G41kP+Hqxs_Jp?*08h^sAWu|g_PI3jekw#6yVuq^P@P)P(y z#dqAjg%JvlkEsokd7nP5ZtM_k)m{pySV{xNijT~4B%&_Ot&DCex)9lNGUF1tADX0c z)|2WG#X>{cG2~BK0F#i1m_;@X@j$C%hW=!C30cWdg*}m7S^{TvS+T9*Xp=87K;yJn zVa^LcK>BtplVo3JvKELj$R>Xi5}{_n_2Imd`LUBPI$cRweuCQ6DTa5D^xzvZ_BT{E&n zVZ-c@8M+Fjm}EFl;*S%&maVxnT&Q$H{kOKYG9!!8dd4yZrDk0^w(jkx^_NTq1AX){ zI;#~FemaXXSp4rUlqo_w@a%?M9Su?*vzUIaE&=(@78OiyssrpjjcGt0Z9)tG2XCDl zHjlzJZsG%riYgD0O=pY>?$*6JSaz3&@kUpoxh`(|oOtOqD&0)2%s81Dcdv!wp<J zTAursU5JYOAhDo&RG66tD^Tb-hNlajg`>%_`sxuetpD0`QXYerW)yGvVdCu-jhm_* zR>fgLuhtNylR~%Myx`6Fa$3)H3OkXzD+^Xmpv7whLt@#zZEm$E%b}+42MgnvssQ6x zXFGPBuNV1+j2p1KUt^QwVx&^ZYgjQIH&e1_vzZIxT(A9PI~UtsMOz z{me*Jr^x)#oC{{;pKQ)QF&z)fq_JmlNjUJdSmP6C0lngEuA+ml_N_zswDYb0;jrA3XS?KlQVB4LjjV#!; z5!@Azp5Q~o=NyIbl|^YwS4PtI(h%K>4GbqIyT%cygUDIi^$DUC-dZarp6(reh5NO{ zCc&CKhgj)DZXNc)r1ryxiz;hq?a_mUt&4@&P6F+RbInr`-J2Ec&j?Kk4l|81LROh7 zPKfASwI1ao4K|fOZ}_4rwhS07)K*eQ6chqoVbyGV+CDwnRl2{Y1y4X zOlebopumoU)trB*b|F}v@1Bsir8h&Xs_?_alS59LJsF~77eD6NvRoRdGvJO#N5LC0 z&rTW1^2;;*l8#C;-sl|jBQ~m&nco6;xkJx@k%BPbVDy{GdiTNfC3ciJ5}6h;qBR*^ zslt77LuHIBEDnwbr^>jgYY>PhXa!E&3AzO!2P`6hkRX07G+vu_1e$CZ20)}tWu>tp z!dIOZ_-;{DWO6hOzPM6cJrhh+9J28q&BGI8nfoPi-U^*_rZRu|w+8+n?Q9_NV;=l( zlIH&%M$l6vt}LNOSRN!4=m8E&jN#ArzXpOLX-7WFtb#~Z-++9`)(^m}hy%Hh;&&jy z5-~GIV2srF(pOIfyB`FyBNoAy_-6rVy#KvKgnZfME-WN z{Hw!A6vU{89}|aw+mCSh4#pLpJ^#AdfbmA+;Az1kah3A_P1C&!bBM1sZ;vd z{P#J(^Jeu8|48lEO;hu$_D5HHhij-yOD!o06h^7JMoOL%#9T78SO199 z1{fzo+twB1-(c#yPCx&R3Gh8%1n#dpMBUz(@c+ZG;dEx#^uF0x5gtsQ-ROR z!x_vkYC?>F@|{93WGJiZBi(v#BGUb)nHi*~!VQ4$LZ32`KW{!5%6hv@vw98BE$1xH zlr%O|tnsvDbE}9ZSbd9KRQZ&bu&;)puP28;#8j7aj}uc%6zYBYAhg*3?Hh`tzRFy} zqsIM*uZ(W%J+rMJ$jyj(V)A-xr#iCW4`;TFAfLrpwt${}Wum4<%uUPdC!IDTr-yxl zv*m~^)6m=4pCw~xrt8EP^X_+!9T8K{7XHI0{_6)@YNsOe^z|L4yIZ3<+EVt@(Oa9; z$u2CsQsJe7?alog0w$XUc@{VwteUoqitL?r`kx#&e9W>MZxnUh<<~lrO{>)HIR97C+g}fQKb2l-@2@)PZDjKh&?)MU( zO;0p=*dZ1+0lH6$d{lzCYF95yMUW8bgAPjBU4fFJ|`y54_4L-5}p3V=uh z@n5BX{sAFV2(JTve<1c?Fzfo2H3lHd;{DA=Q2IanTr}`GI3O{hG9IIN`LJJy{54O; zoh3_7S^GP&xUku?=8w@PhgZua=EyWhBX4YnW9{UJP)@>L7(}-peC3hIY7kKpR~br> z7BkXYwbev$F}3ndzV&T}TXi*A2GZ(g1bP^a7;NlVwK#ccVQ~tfGBV2w)8u_Tm8Yz9 zQqHT9-<+sz7s7T|NG+$$T}*uU?z;!CEbR>7!Zk&g>gYbQU=j0eS$(iBKQi5x6%ld} zg&E$hl0YEGPk!Gb=xv+4JKW)Dct!&Li-KqGXjcX*nM zr=*y*Oi)81E;Z9qj}RR|hCN4zqz@VGgjt?7AH(1c#X3!=FhkZ8Sl2mZx&xg}z-MaK zv#X-t$+6qgcuFZ$YM*MSE6f@mLglCYn^M|OYzO#Ik;GR)_WmUS{%QrMx@xex>sLF7ROs z@g1#f;vyd0_Kvj!yL+oGX`utCJ0|+?;6+9?>y_Jky+ARvTSkr3qW_Dkvy5tM?b>yK zA}vyaySuwXaf-VKiUxPr;_mJg3-0dj?gTAf+`a8S?Dvy%&fly#GDd!^%(b3*&HI{M zabC+?-SmsCCSM3Wcr#FAt;IfaR*W{)PfN>znnhpyHJ`5Qo~75;?c zH&m^7FGKr9>5=@abqIFyxnpB*-Q9OB$|r-FzLo2@TNj8*J?oT!`SP%~|9PoI4EJ>Gp1&Q-TOP6ggF%D5{XG5Nz}f0}WgIY#rQO=bFyx zX6ruyB-_lSTht3bvkO6LN-smbpzhl2Bd?kwI|G$hPsxLbwH%ZuYikfNZ;1+NuH_1)82M%Bwms|BfZ~99Um> zmwu?P58j~hA8n!3pWZlcv`K5nx$4NA>gRWGo$5Hkbv7XADo+$g=Z9-JW8ROS(ZEk5 zusZBFAH)Zw#<;9Q3)3tFc+-MQh8wu25Z1FiLCq_(&McI&@R%pmj+hRhGo9@jlvc(h z)Oe{tgyV=$=kH4G)-S`t)vu7izh&B#kFnp6yyLfv-%|6v$Yp=UUmBb@`dm9*_pQSs)av_HXMU~4F{vE>}n z-S?W*fJTnigW3BPIUTbY7!sLkP1i>{bYh(9`1@d=+6Sg_1tfB9xDtbpqh4hlANvWf z*eM2vNJU1Sd3M192Ou~j+poHW+6(ZN*h1E~7~sPN_tJ|=X9}gCZT6@_;IglHc+zMk zVDOQ-Q}e_K3k3yploF||?6`>IyC_LAT+>`h4ZYA9K%_0KzNC4OW0I7_JE_Tntu?|P z%i^IJ8_5+I+mCu$=~l?1@miTe&IuO9QWdnMg)ALW0Rw&aDW}l6gMFa~!Ou>+*7Z0Hx6P6JNy!Ma;+t6h~hdNH4 zZj4g)ByZ?A&WD)HLF1j{ZM`v_-+UR_>_#tn4AQ*nq%u-8FAd>b^@H9kJOe|U{55C` zVn;oWhkm(7eC%Q(X8oKXE?awuNK}}*AdO9y&Th9UVX;njICua0SE1!CKOUD4OWV5O ze*lV`npFr-N_qEJ!52AK@pYO5HAS>k*Ub;SUNZ-RM+(VW!Cz0#=8NkjYBw94KhYDZ zW1B0`pz}Ps3&(2A8ep|ayF=o9If9Y|+URyRX56S2CSFS1%hp#XNGRRYd(M}gSpNXWF`x)qZ@hrX*ubA`8OSY8m*ctD|Js|quEo=JC~3YeLevx5pNxy@%flW`#& zMy7NI_UDY8VxeGL79vuvWkI|P;h|+NwM^Ndf=0R1bX0@I0P>RT$!zPzp;#kF-(}?x za1IR-CeQL0g7?Y?E>8T&ppwRk(^A;8ccnO2-DKH@Rvwk!`rYoI8lQ^mu(+`K%aSG4 zJ08^&q3(kebZJvn0M1C8jp-E$K$v zS^v6AomVHhFLfz2nc( z(Sbcff;#`}4$N2^M04$uJ!oc-MNnT#pRq80Cq$l^Ozbw0&|& z=99G7^j4>>#n}92>K#P?!GQ^O=k58f0&P$AmN@_4rH&sXqtwc3wn*cS&W~d>_TsZy z_LsT*T4mHjN7cjSj>MSYJ6EPwgo|a!mW@VxBinJPShA=12Zc=CJR6TE`NJxrTP-WD zGb-xFb0)m3COxKet9(F|Db{snNlwjuA3_zfTC0kc<)a7zF+^ZHH_Yn@- zp6^#RHG+04YkJtmc-GYsvh(Zwx%Ki1y-3yM(@`7GrH`G%A zv==gucPF>))t3kq<$iYef3L}^Y#SFIbg%)gk^pDA1&)dH%{PULlntZ!{F7f4e2!l8 zCV7jATp$YywlDf&7^^ModXe%Cnqaj{Q?jZ@3(pP&K_mZ$lOKh@61kTz{-l@_oM)#Z zkVYmR#N2gw;UQ6QJk|#Zi|-Ec@T3FXPgzh|EYXB78c;GL%zS^aoolp?Gem_ieeIJ7 zkvfkJ5*AI^BP5iM=yXd*NasQnIM!@fS@@qf@b@4C*7x~*|DbdF=6eK>h7_Zuik5aE z%O7zOvAeUgLV6X~f{wl*^27ISA&e*{Q@3>cp6b^g28y+^GHNvA(8m{6x92_vGsn3X~Caop9W!`rth{TM+^2{}62d zgSe|_^*xY~Luj)E0Q0VlDEiO4_5YWw3!F-4gX!ZXWo?yI3M4;UgR2~tR14T*SCJDI zC49^CbCnACUdXac<182-WTNCxY2cPLz$B*%Af3H-Y1g0SvWj&K4X2&< zGTn$|*zpxLO2zKWrvcjXspo^#Fu9pk*LX9HhvfN|ygbptLehb^aX7_;)KO0mWn}#V zFM@%_DYC-)`C>_>@$BYB{fP54-sV30c)#J3%D<7$v9yL>^QHE5ZJ7&R@z&VwfgT*4Om^iFBTwQ#( z0Zp$!<)Lf^u>T!aN)^Z02$vF7 z~??z38 zUx$?vgsA(0;rd=;J$+Uu8*NuXD(ui+A56>lWn8JjeAogdTR&7@uTQ$)WP6FLODA>6 zpxgD!nDGvp1eJ%mWwt4ie$_5^`%?ol=UxU2rc|i$Z3bC2Cw|U?-riU%^L!Z)EWC*7 z+pJsNlg?jr6gQ3njW*&FMgxXTS)H6s9a%IF*Rl_`+sBGVOFt=budi3FV3y3-)RPR& zy2*r?o46rI;2kjnhpYLb6mDai;arC zaY5g#3|-#m;{%%y7zhC+-#&#QA`RBs(a2l!9_Z{z1TKgnj3!)XZMuAz&vNw85X0gC zFz66bqV?u*=!^BzvJZvBl}wW*_@@atjNRc!E92p^Y^q+Eu%MKN-nh%;Mww-uaK>cx zFnKa&DG3)UrD#sr=?bR^Sfxtf{S*(tlk@<-GN-fCv*&b+#V8O^R~80YAiT_(N7j;e zJsWKDYG-0OLa-UGRStPNi?F9R|qg$^JaOHiu;(L97 zFH)VK&%L3SgO2MTZy&IQGEb8@zC{bL*%$~V3efK;bJkK*sj=Tmk_DdI9}XuukerbG zj`c(Pj;SbPt@Segs<rcgl`)KQWQJe!My!#b$%D z=$IW(US{pf%#feP`mbc@c zCwCAznuk?|EeeJxD#z?xzgD3?aX&RvUTi+3-gmA$2_@B?B!ml}+u-ePNyEg>xMWG> zx<>~P5ntCfz*)A3vuZ7x+ag#jIFyInPUA091{eF_6Oss)^|ABMxO{b~nM1O4^#9Vq zx#v@%NNK+E)Tof_wbMeq=*R4SWb5L!$$`tH^;Peu`{bZtsN1n-q6=YS$$As{q)24o z%_dm_KWAEBksFt^(mILB1YUW~`*hdxsElK2;0c$B zTu^SRofVh+{sCiJN?10n0=KQb87<*|3xEGtVSdq$^!qA|w_n98Mo&@|7vJ>_-V!pg z^o}>%2ye^^=P(a(z3qq@#rkYKA$Q8bEps@g`&d(6jwRA~sd<6THr*%zF*Oo&_pL<6 zZ%(~cv6cK{P-H)D^pwL6tG0B2JTf+gZEXe|S?lN%8h0ic81_Zr@>j14GwR--9y?4@ z{-{za6}eYi0;CLRFlww=7EX8nC5~YAW)LU#eP;*j60(F=RH#mqGB!J`+V^VLdUSAjzUuz?x~XRV_= z+D!_hAx8`-pR6OT9R(tdA)8}+yXa1~s(A7>rogT4LEC{o{bFJkd-euq2-ug9)A+^T zJF~*^Q)WTQ=Gg5Gy4Qb7O@J8NyJ^No%nNAgyuy;xQ=+6_)@ybQE?ejS2Z8+e9Nw-C z$;Z(D574Rqt|WZCH{(GSm-7ANG=nz!v*5D+)%Pss59u5xAJiKgoo=3c&Ex&k*L7q5ycdvMU$P6B{UHrL~7PFqff+6l$hgQazc3LF+icGiZ9?S|?Tgih5 zesmuA#hl|U8+;JsV@2>5B2Sdm-y}9aR@pL^q(U)fHZhlPB08cB1DXTJNeXxQJ z$U2uOmi=mt{>_kCi`5e2vLBcA!*e+^-69WD86f zXVx$9Y z{^Dh?HyBsbd|!KwS@w>7R1mQOi{co-${LGuC-5LAtA6%d%5DAy9+d_7{PI;Y!rK-h zzvGDaP=%uJ>&(4Rn&umB-_pk4iq31-l~Zl&Zv}!+JbQLQtXxGRs{zd2#HO@N>(&l2 z_X>gtIGH4r%q*|+QVnI?G2j)VPd9I+mlKhglA-*|8b|Ime)mbK?mX%Pt3y4xL>-*H`guVXSRw#NxG!(JJ92*{(eVl_xC5^QyY|ua`)5b1 zRw-Py;?Ic8SJz>L{{Xn_{{d`jQ@bxKAIATgf7Hf&T-H8J^8fY5NVAz4Lfc4PQ1C08 z6}SAmyu|g@B6`_657dFB$yNZUHb%ifG_9ni@O5_%D}aWcKTgo|Y~nm^d_!h7^Ne9v zP^5Us=5!Cbjm=aAVQD0=X4J2dD6b}n4PYVb*kmo|SVywHx-D z;%$m$Fj<_zY>yR+{aX0K$`{!}uRwk5J714B#+063!D(nY$SxoRo5D58cxrMfabTt> zK&Wy;#68yMT6glHeZ>YOV`8MQy!L1@Vm$c_?@y{7Jp-bQp;OVCGsgn zULQCJ@Uw`>t+gFHBV_AJXf?_g)L(cjalIuEPG`9HY#EakNp#E3Rlm1FFJaje#QH%T zfSvUSHp$54HOn&#%Y%6ClE^@-6E9$&4L`9u3@JQcFBTO{r|SR|JBwHdOiH|sTfVv@;5N~kiN;U*k9 zSr`|(6x9mZMj$flr$4x?k^jMhFd|xVLir^jpNA!NzMR}Cb?h{;*I-Pqt4+!41M!1s zPTFYk5bQ@iy#=;YTAck3V^&NBZFlfFh@7cxT6j!25M8!I69C`Zy}7X*roQLt%F|!a z#3K&6;K1!%2Yct zx+~XOu(@ySMH_u4;eJ_K)`Aqbgp`E*d--M?@~?%xIfa=xgQKtA78a{6?sDyu)Qyd| zRvZTLR)%~y>qA~2$98y<^$U5KH=p!n@TxMv(kh48i_wa_EYzLb(VP?o?c>^H;~78J zSr}d`Tq5`FAZ6I-gUnd2ce&?^KGswT_VDa(%}9M-$?huwZhAE{2UB%+j5vMf%Onkp~(&hK}C+hFMy$wybxZ8wY5Lu*=RWp5I z!NF~v+!e0oEQ*|GnVgLq6n@PL@kb-uv%PYc>#!jRoE3OsDWsaZq?EJkr{cb?BHmM-MH*v zIlH5fTxT(hyNh?4ZY*K`AY8oGF6Qx#XB98aD2^{AJ~k&Bw+|}Ve+qB7xZ##zyIquSy3D`U!A}Zu*p1YTj?=>V(zt)*GmosB52AY!0*-9id17}hM@}u!^f(MLOb%?l ze(A10Nyu83s>XL{*C+pS9;{r*tcYv_|0tQsr+*nloXF1sMgTXqfa?Rcjblt;>=K+(Tos{b-a`a2V@Flbe}58!f?Jj$6d8YuUAF&)r-O-c>pb4I z6}u@rt9akQRmS_2M~nT=4d^<(;f8B{ND0)?c)wTi22Mgn%|f??K3-u}m~)nGF)>@n zpaV{jdv=*<2WR%?2L*Rjpfonv;E)IE1UpE7EK^%mk?*F?G=y~+qh;R<#fLSSscq7K z-PG;tbS8ZvC;L{1#&n8H13iSOHoO%!oi!>)tHG0+yj4;-gNt}zMnq`s-@C*)19AFB&Bji#bvzYXo5E6M0f1MSUAW~oKlODLrK1|)(%4z5Un5EzbBQB z>;Dm6#4EYp2dQdZ$#8NF&FD^|D2~V2O{vN(W%T2)L51u$sdu7fybN#9aDiYI<1@TD z2z8)0>Mw*{vp1V<1#=u1jk|N~MxVpmgVl7({qk8Xa9MG%k^nl+&oJL{C2dkc!yqqJ z@1Ason#?{Vis;eYtZWbYPXpf_+zB7q8%3}t<@~P07~}|TuFbF~5puclce#elw^g0h zhFz3+4Vv+&$CXs^({$vHu|Hv`t(@&K(?z$1>P4>FXBlt=1;B_ZPU?jD`3BRhB6d%a z^>I60I;i5&hLae8R!!Yu`ak5Rw|{YyC3fhkFXe%ygtcgd8Oj;EqV4H->4TZQ)cfj0 zv5Ku6`Ydwtrh@aZ?7jEL$CO{e&xG6Y^>N&TB<*g6cLb+W%L>~g_j%k)WT)XAr&gbb zkB%9Y3N0iE;lqpfpvo>(97T(EN!3(rsUEpUMnav)4lef~fj!`<`CC^{mmOlm88OtI zQ7YXfZ6p`XYG`{!&G_0B-@g~V%w;CczKrcjbEQ4bae)fm{sGy#7e1l4;Iz?B$fv|l zR+oqS_+w(VpeYF75CfTPBT>nioYiw}N;_z+se_V|#6`e*!WiLDlZ-!37(co`h7ivk zGLf}*EjOmiYb!Y=r`4jw<0I(^?GubZ%piWaBfM6wIAv$9KV$-TBJh95tbuM5tBR0Z zK>e5&_V_yUQEDQqO%LLONq)}RZ=f$Qu`cWL`>y}rL(BikzG%T0Pakc2fsObP75+sP z&WP0dJzhhE^KMo|)P zs(+ULixm2I;RLuq|EJ)wqb!P)q4@mlv&fEhL@Vr8fXTVYx7KE$6kNhK8>z>omt_=w z0)4pi!{_E>sHDD#cfvzJgx7m)2zn)!kDui{mfru%3yBeTj6{?yIg9%MH@8_uc8Gy; z&J{nmd;+~+du@hSCDl);B%=VtJwCC(|61-s`X;IV(pgPfeKhsgr}kZk#P~fz_h(ah z(0vA8D6aVc?zU(T>>t7dRpBY#^VDSu_K_CxExy60+JU%u$mJ-Yju+;DEXRFWPy_0a z6^csy*@1v$vD|e%MDW79$kp4fI?Jx&X@6qH0CDZ9HT;|qcbHwv7!H>&6_ftny}xwJ zGBeqxEy}=SzEm-L=831_D$8;&tR}lrvpO?6c)l~%W^{83cAF@28{oA|MVXgThnuXuH=cwvuh zeG%P=V^DQ|*-F;Q6vN+~wAkAs=sI2G#A)7gzBpQGn9IAu>~nKarq2#`G2bR$jsINV zD!xs+};gkJv^n9)HmoFV5i79bq7=3`U1idn%tuSN1eaJs6j zSIs;Ik>&x6CqSuMDC#AfKe`bR<3@ytZvHs6Bo{2|c)AP(AAFpA(YacZa#N5kXAJYu zg_hC{8v6`V57^+XN7Ua+=hhECakTy!kA1*uO1bE_F+G9I)hxMq>nbJKP!haI!v-$L zVlrh}<&2QyHXUAQnDs4-_)YPXDnNsv!t=#~gW;}z)d_a@WX`tKv#B@wc*p{mGiuXS zZ_e9!Q`$BvZUV3D(Fk&~jgC=Hx4fLihpBE<9JSsY zIp_fTuhr?!@PB#2G_Hvj0x>|Azo9ym3S(u2SkL+vA@$(?<5}g8yG8?%{jHbEN=Ub_ zGf5HUBkFGnPJdO?e;Y1D6w^hov2};SC(vBdq!ZMl$A$#QrEr|*;lB$nmnX4tO4*~b zf_{RyoeSwpTmEnq^SPxPQ#^v7^#%|JkvHQF8ju$bBYf{`+Yi$v@S%P?9yk=X<*xNN z3%D^wV4)I)Lv#s85>r&5Oya=vtH{bYLmK@r6wP^Zpxv}UhKiXf)ozhp8OI3n1Ey3} zi2T{nPwf&}ajXfN4I@4nNxJBCnp~$g!;=kZ>WSSVJRC^s*VT`6&P_w9NAlhznr=zv zi;@MDX#H>7`-d2=W(tQSs+(WCR?bJ=rOHFox(KBNJOtfD!W|qY1Hx6-_O$XxtFTm2fXc6#NSIjDbJ?*7Uywy{`b zCIp{JFI+yEB-G>%;Uq2mnMfci7BtKmP{jyHi4I$uksIeL#jo$E*OKbJaa-`|!625; zCNxav4t1 zx|#0=zw-rMKcC9bgZjxSiGm-mku6fm{VX{>MTtHsE>%D=s*EBln$9@|rC?~tfKd}# z#A&>AbKCZv?J(wR$x!n|?trg;k^{)y>V6+1ip$tS(LzZ)X4D7e!v5$oFG2tQG|2Zy z!AnGU<;N{;#k+``hkakr6Y-fR$dNX&&3>cDUF*1mHvefww%kw=gc-LZKhdsOyk4<(bieKC_9;wsK})z>y|7_74fc?;h-}~9uw+ZKIwG8--XnY_E;CQN z{Tq4AeUm8aELouvp#Y8Kx9VxU-*Mq^gXQLBWj;D5L}SLr zNiqm*xI)dbRNOz>ZedT4;*tt`Y6J*Gi8VRbM_@(aXLw+b1NOY~U^F3Aliu?~9g!1W zcO;gRk~a%4Bdeo)4@Z>JG#sp-)@60$h$wOCjn|!ceZ3RZTP053|FH+6D`eyXm8e?ZKy&Hn+IAUL~;V8?2EQCrm_GdRj+W{s0@rE~hh1tW($A0vYRsC_uI#?Z^Ty6czn z!p$e)d2@LJc^MJ`Ll#6fA-RlZni}_SQK-c=5T`Wm!OX6gPT4%XeP5AXM4cm;GI>*@ z7VSXCbuBx1+{{+N+>Pm6I^gsn+YhmPAB*k&PSFhvplv%Z>arWlTJt z7qI+1YC;bexG(6z@=dF|)$QQyk9OwkQzN7%+S(382_7R$aoOJ(`p!`_te}=iky7aM zAnQi7|6?2^Yi7lwH#qL@|D#s%n^{gic>ivXKcZd1%|k+e5l2#qv;AWAjB0(q6~Yp7 zxk&9atORIlC27=zM>J+uWPPdp(sxh2{1-J>hzO0;Fqr*qXp@2rR~h63vAi2 zf+dGZ`u2_hQWwSg%Rb7nKSH}#3$|y2phh-jf4=lOQ=v;GZ}3veG&%ox!^-Im7Bdv&(L-;WUg5Gj`*l1qwF{~83b}Rf*Tx35&%MjneN`?zwRZ}8a?o6tX<{~`l7;5`VSzs zTK3Aq{7Zso?;_Se0O#&}I=u8ki%Y_bsPtymfowiYzZSm9R^pvF4u9eA$>;LY{=0Qh zWpOz@bxv($3jN3#@lAT-!8X}atIQ6ijW&K&w=pS9Iy&{RNocwmn&x^9D~(}cX?4K} zJ~G724b60e5&v58b6lTr>}533ygMkIn2MDad(y3qN!;o_W4sl{gdh2u1*aWu7KFj) z)b{$pL(kt-zui;b2?Q~IpTnE{%eB*MBLdLrp5NYSF^6|-T@(n|aC-Y@<4v)3m;bXY zTI`o7qFtX~@4Kl$?uV$VG08%}%i}yQts23bU0p?)Yr`j$T!?>5_;$J!|Gqv1F(3`3h91s7AnRFMg(}hy*qvw=a~YZl&b_D z3z?NXW|VJ^ZQ-a-BGW_pQLAM%?&^^d=zK80eXz?`9@&8$=8o_wMLK89CB6laHX zjPU$1Wc4{XD`b)W_Xqv|avwFcR=AXHmResQkxvv^@BmCWq<{x^#BoVABiM$bz1!!W zcNseq#q$r#RZ44@h?X{cU)#Uzx;~Wjzi=^{oAZ9Wbyyrf(1$ZKYOQ(8(u}jLFwh`K zFR|xWwM%}A4$2UYtjyx<`BpXJ;!iD%Z{_PUH(b1Z=_bi+qxb?q7A*8${k2iI=m1qV z^^4r#?QgVI|AZm~Ka-JMp>t#vMudo6QC&GA1%t@I;Vw}`jIFqt$7$eli?YJ$z;#p_e z$Jys3{;NqH<^D#iLj+y$=}cw9NP&GhvW+?s_9TTUNu+3Ai<*Y2zF5DnHjrnA{^F8~ z2%9t_?lH``A53IO_eG6jv@>i@2>8Bxk;d6uR+LBD@@@m`O6_y$YaWjq?LqaF#9)Co z%3~dwLKIw%+@ZMRGb+Q{DEG=#w=aePKDI%+}sVLRV95 z%)*Psrk3(>;h1wCSUoBSmgPJ`4d2uMO;M2zt~0_^QC}F;lvf+ec?=uX))=$!+a^(n z&z8>_93QfA8v7^TQtKBIuU?)(qrqtFhM zjU&!cDARIxp@~UxVb-0U4SQ`Yj+X56=N~GWWQ>T5d430nAJU(_vk~Tbe2ycBSGOP5?bW(UkN)|Iq5L8fcp^bDup$zevC&m+DAjR?SCRh52jA&2*r0AKF5 zVm(sEV5=WN`JS|SMmmecFMN8pz8J1+Zwg&QE#HQq0(0V8A_Tuj z((P>r=dbU!4svZ5oHrAdw6=YxH+_cs-D~u63TaSd1Tn#F5_P`&RN`97iaa>xQPLp9 zk&{B06-P9yP7w0fHnL}Bz+WWDs@3D*T4eZM?I0r?Xf)(Pgozbn@HCh3uxNWRhB5049=0SRuc84p}urw9Q-GhQ`qwF_&hfc(@!1fsZ042vrsRX~6%sV@Nngn4 z1a8--T=0%qr+W7{Q-6z^`#%5!WG@#{IwNjPc_u5?=nwu#epTxkUu3*o=)ZfkF8}EIHw83VALF(Ab;M6Ah9o*7+1fx}H@cC}G>tjwSwn)YU{MvNz=)j-I{ zVow5{{jw%5y`jwjmuP#(BMdjYR_$+j5BJ7?-0JVmfEp+&n1t?5KmpyddbyBPI+LHW zjNG#FiUkT*v$7Y`x|JMpNzv`9{uk3>7alZSa&F_^DGxgG_9M@k`eo} zzZ<}{NSj!P(D?638qck8aGUZYx4+!ubiU7f$(%eF71RIXF4)e1$J9IQ^R3LboS4@( z+RQk!fWjVIcj^VD_|zKU!v0=?Il} zLiNq{^N+I*BkRyVZE5cvSh-^|04n`PLW7 zwzO0trNtgFZRn|M-bF{F2iZ5M{+b#YVW6ngh?D;L3q^9M{G!Dtsh&W=BwE-+Utn08V+=S@<_U6sY|P#8<=J?ib(M- z%-EURotZMxsC4(#ru9Ddg`q}4hMqQ(e+(1b)_zmgrH%xOTq_U$;7~f;x+Ou34?jil zpAzx_J8`)y9xx3i{~Fvgt(TJ^;SCD9wtrzLdw(1PP+8k5m8R)iTXkl7Xs~d*wjHQA4fQLWuNwr11IAc@GTyIRxyxFi;9nY7V?^5*^S4XDkE z_ni%QmK007mk6(@V3qfjUR;tvt-<1(X6qoEb2GnjZ)f)_CEAVR)$DhNwr`(xG6{LI zl&nv*GM-pC(Q`Ysqg4b*B!n@9(GTXk&!&~#fms8M9#~Qv2!ss3>f+mcW15#yq;i6N zZ1XVh@-*yQAB{Nd8Oy1a&EXV53|j6H<1ZLK2u)0DzEegOrb--Gcx*4ybs)j5Bhy)n zGFfEF#GTS6F*p6r)y>ptfo=@yPhjyWplf8evM|tMhP=u_qq|_WnETbm)edA4Y-CdO z$N1nS%W}d|2U9t~vhH8BBcx(@AZby-pUbmkU9Euf$lUA=XI4KAjDC$|5(%9Ut>T%* z#GDW7MoPuBR3wFe9<(k^GJr3{H;&h^%hvx4`-UjZHMV>FmEw%ThCF5?=~u~DMM?cv z$4f&ZJxj;eUu|IBQJy?orf&g#)WnR`pAj92j-gK0H~m182t;G_&AM5Q=cZ1BNls(0 zy>LpT7ORl-rKL$seKk}~BXlH-Gy?BvCoi)Gzy>T#JM$mFBb|ov+#~6(!VpKZmd&aG zz+4E(e;K+hvAg}3Lx!kPT!hmL6S=d}Bc8ny*?GVxiW*$NjN;+5yjyfR{KBl;^g$^@F0FDMbdhrL!q95h1>G`dyU zOGW41aTbD$Fj0*p+XB{1HInETK05Ul9z`b&w{VkJAil(juci*k_(ka}m|C=OR@U5g zTC5DYUym@FD{;HQ+91d_YODZ~gbL}e&ZMy2VOWftrd${g|1{Vkqp!O@`zcNOn0_={ z1Eru5$kMBBhJzWmlYbwaVj#o6uVk4qH_5RFzLg6=?>s zO~`MaY+4qsU*z->@#Wq3M_H=6W@1V0b8sSB0i|GZA5MCv47+w>#@ytOFGk#)2lre~{>eMlkRFe5Y8%+yN-MGvzGL9~AWOzwU^GVUUa6RNv!voMJ!)4L5C7!%>-O)WmM=Gkp)E zO6>cEO05Q;O`CF^=CES9A7dAI@S`f4;~b?j#(vV@`5(X#YW;zd?Fh3TwcUoUSp*0d zb`E#%+Ip140N|Y@rKyau7;=nNqKn*H`hXgY`G*#MQO_=|9y{) z41Gl1#GL4ognl2YU-)F4dCqbsVTh_RYYC(zWocnzoVFO9qb6&k?bP+Xm_1~~+|rRC zhhQ7vYUc=67)@+gp0zyg@(Hy=sg1j0%%gb89$x#q+VbuPilxRM?iF5j(?8`iyj86A zmSe^;Fc)A`*(3Zo1#@V}$hQAn!_PyUS$4hdYoF%PqDx<3N=kW7cr~sEG6!&3EqQ+X zaZMt<#7Sa2eDiX>xhNB+zTcFJ!DB^lWag0iXHw}_D;-}Hm4KTBa8Ck9?;8kYvXeiB zJ+5<>bQc^`g)#!zeNSa5-g%J{C-3Jp=HczJ8}-lX5qT=LKua@k>C>{Pz%vws=^lej zNAIVLN&X|0f*6V5V?GyzZ*dl~hU;32pZ49j}JX_iJ>tV^shIf7v)0Larj+|Xe}bV-5r zMyCnzkDFNeYI|WabW6lvgB!Rg&N2;MTDkKekq8$Ftx3Gfv2wjx`uSvK+E%U3qCj1o zGa5!}W}t6!tdmZ4@Lc%~-3CExE<=3B{m*Sf-Qz{C6D?XyWIIZQt=y&rxW9=&tjvg@ z4VJ|hUTSwBPVGVngqmfKh+g7p+Z>#U} zNLEB=A=9aEB?Bln!@nw=j}E!J9kqrU>HM8CUPo}qW^K`l;cjcSA66tb`09d+fE~K0 zY$r%^EZpp3pUrrXL}Se+uxyhgSW#nV^aflxhqVuIq8 zmT`D^SFq=G)TXZ~nxBlIM_TnDxNtC%Bu7&ez=Ni@#95R{=Tae!bfKPz>0@$N7bzNg z71M+)O+*56^^o2VhkcZ}1fMg5$;0H~S@g4QRiZ!`^iK4@Ya^}&j^x9}S(p`NKs2uD zRY|z&qaVO!0=WfA*tSfQv96R=&5j60y+@vnru-YoiUhX9?j_;TO)8JyN%y67^0D>O zUUc_mZ@Xx@I42W>+s$%XFd#+YVVdNJ7YX^;S*XW4kcQC8 z=Za=!M(B%k|NeC1g&-pnoAuGg&va4ckvgIn+=pEw%;AHD~0hv86TAq!%I@Z_9>_T15(YB`e z-3H9SIJ?rc&QLt$HxFV_!|L-CQLiBk-(-z#d`x^!qP(`iP+9GWy_CH)Z=%o5Moy-t z+S?yETT=6|DI=QDXz`maaF3L0W34;VCV#J9Wpo|rSYIA=uR}~ek zx5jWKPl$1T5W%(at)#;~AG2lfYO`19x7{vi@qTM>k9r)T%Hkf5A;Y$duWOK#(!sPy z&E|@QO!bcqi@E-I;+G?7v==}0VKt8bRBLReK#84U6>%Ed^A;XV>|qeRuQ&@olOLq6 zHSwqTKb%Qr$HVWwq zO|W=2;dXBQIw(RI5sgKqBU;WYa=XQ@5%Ue+(>kbGbspkdkKfM~oBnG+{?GFNPVE0Z z9hs9;cMnj-0*ZbS5cGP8Pm5@Rsy%*Y^X$0*3TPs?;dT2TElD*gB)$&ukm77*zxY*9 zKo>swg#qb2dsvBqQj{rE#D3z$O;SV<`e5e>RG^Kd;@|`+D$wo(32w!xkU7jT!r!NH zv}gCREDCh>iDXE~@M`b8kPdWOMZQ`uQ@eY%v0X@a(yCB2Weh{Iy-tw@L+1tv+rC!C zbi558z>?e)D!2{>@_wfCCI8P?BdOw`Z%33mXxkOEF5Q5?3qNfE)r1$BOH8kSF61ak z#BiP#m}j~W=JZALI7v;8ug%cBo9suP+>=$(4L|4*2eZy#E3`AxZxWcvbB`vF+WGCGh^FB2;=P4!YxrW~cvl~YCS%yOOr?zGIFOofq z+P87|yJu>&cm4mQ(+>uj$~qAYj5HAZ_=Zdyk{CWl-4UCnE7n;LbGxE2p|$Fly@{$F zE*O}{K|H~bB1z;NDeS&n&chvkag_f>buv#sW5fW~Znx5R3o?5Iym{O$*qw)+%-`m6w%fRIehQ$HT=) z&x*8Q?@{gPt%}b{^D{mAafEzfkdydgEm@;+Bij90Cs7kYn6`oCPi{@;jlOnRv~4No z5Zu>>ta9lG2goBnWXmN>b1J&*2`6oc(hHD$eNxpJu5#Ar3Xv~iY?|7XNzV|Zi+a=h z-foZV6ZzM=r^(cEHzu7P#_0^rLJ4mMe6H0$$}h5-72n0|V=^^#3uKTE-Uu=rZ;$aY zA*WT1{9>OthL!~*W&#A6B4a8(w$yXu2RJvbxc{j(Gsz`(LKwrTWC|rux)8Ff`h!dU z*&kfRZ)CWtxaujC(Tv$zN;phh6iHjrK*ZqG zUQD!?QC>Q5?0UEmcs)vkyB~pzX!T++>qA^iC}C9r0Dx}$0=D7_$Buzte;`3j88YR5 z0M02SJ_euwggaHSupK-J)dpv)s1@$d%&LIAam>MW*4h!M;@N2 z+b(zBa2*Cg>7mQ=ZhU9gml=#b`d3pkzP`=rJ0HC$+zb+%$tTM`oOyQ&J0DUX3_cC@Aj(TRRI z$Q02Zh{8oJEE7&Xj?cVXeD`e38lzknVAWW32UHd3{tshs8P!(XeS2fYwYV07ySo>6 zcPZ`!4_b;8cXx`rYtZ7s-3jh)MOx_noZQd~3y0CiPUTWJWMw2c+w?jBte-nRQQ z(d@v0t~Rh+s{Yu3&!u2-jDSptU|ADgcI1RcT3rf(In%-D)Rr7S8`s$kj*j+C1xj7HXs<>E6xJ*}QqFKR=#XUJ0mIL{&}Nv$_# zDNablX&(Z5nG}=OCJk1wVFnrY4iU($IK&pa_wBlM43ipAv7HYBH|nJhdLD#Bjf8ml z>z&=mj>&%)sRa+sb`%vjBYN|u9*2H$TGjYXUaSL{BK5Sv|( z5uK>yjdJFE*{31$6P*am-OUL}@g4)|Dl-MH|8HI6@N?`%?h))nX1 zEc*lD_S@i&!wDUKScB--7iFs8d-+o^gMFDvOHP!SwN*1QqZ(q9NCZOIkS5@Y#8M5e zLXhdQN8Ui7NfY}Kn^hh<{USllA%e?RWFGl#Z)MJ<@Q}PpjdTJ1RJZPJCs-3ZTUN36 z`4v;>;2sQHj?@GrxuhxEG{~$JUMR+7QXoy`u@)b38*deEY|HF313klkBQWhxPFAE1 z0T{U$5M|BpEwa83fsicuS%)QQPOeoEh3Pri?kTG-{{u&Sp!U9i=med#c2hRw!n5VJuN4& zi9XBw@J%{3-iAK)v$PLYYc!x1eiBYj)heqBPT?$f8NHSpE2f++in8wD!hCCzd%+MA zlX5#%$!s;vESyqN;SsSGWd6DmnX}M$?O$b5IGsAxMP>AXT)+k=gBY#kuuBynrww>! zRueniX1s`sz$WUvj?YZ^<*Iw6n&WqNcOo|`|zxjBN49qjet`D<)2HP;CzYA$!(1(oPSJrZzKDquw@3i z2@Adb5H=}`f7QCkhy*^B)H1O!KXqEpVz1wrG_^O4J$X;ioE^_q zCTRdT=fIaL+_8~qo>U*+u^ir%ON2D!?Z82lS=mmEG^OdDr!{0J-$Z?BvJZJTW$@T- z)>8$bAB{Kwpku4+UINd*=-dN$C-Jh%+37t`_djj7dza2pDX`Hr7FPJx{^~V9puEt( zy!UGyj5S1X4E@yt~CkiL%4)qd)|JK*;pKUFd zFPAu*#0Mx8e{hVR`Qk7(HAZef{lPGM=Bvf(|CD$aVkWFkPRkwvXsL%-H^(i_OjHNj z56wt^-Whan_La!|9Bo)bZ(@ZVSp8^VU z0(C^Zeh=Jam}+=H%Nwodv{<4@MB+*t9ElV?1y0aSQFeV%i}xp)4tBEZ2ve13zs9g# z^GCWqSj`&agU}8-Qz*5@VEPQZKotTFU+uM01v9DlUlN~CKGfCP%@qg~yIkR+#L(1L zyHK>xXZ(ye-&L#zHYx8LHZQS}avApV@>4YE#=;&mHIWNSU;sh4EA$;iGSb^w?t4m$8qxzKfm+Em)UR> zyM(5XX&P^zdhn90Vf}aX8XJ-;0GBzCDfSjbr3uVA9-Xs=_0#IuxYZqOs?%NqQ#~j3|}EOpdbNPkg_w6N_Kt zjvZs_3mQC<9XY(~9Jf2f#itDY)-V3%W_P+7DvhHVF$q_JpE*nE4?YPeq$T<7$o;9` zZVsB!HRJaTD@VjV&xY-e-6<~(_EII7e4B+j^rzgVslyOmq$#8+k=S)YmFT!`t-SJB zZNctzxKggsw9&LhiLAUc#1~OC7d>J9nA%Ke^M>d&sv8E&a2r zCn6xgt4xxu9EJu8>kTar_% zEaXWNQ$KL0PK*cL3z5!Dc7^LYm81aAi;9_obo3Ib+2|sFo5`y1>0v%Om!-$S!Hhcn zNLtL1*OL4=R|+jieRlBBpv)PtKzx6ry5haY>U(8MaJ|!FsB^4G80`i?g2_Y2ZkAxNDJLL?@t65^$naCK6M?bseIhPtPB z?8Vo1S$FlNl9FrqSj~nugQfw^)W1^9+8!D+y&)3n>#)Vao)?R~t*ks{m5-@} z#&%2(7cx%4R2(fW6eV@IG?)F5X<9t!9z?|E#s!+9dS$Xqxc27H>mb=#C6=8ZdwUvs zwyQKNIr0Wt7MAkbTs2FF?yXZ8-dJB(9R(5K%F&vA0ABFoug_?<$?tv>GoN0)Y%@(F zJs_^=6%1v&<`N$kxE@I}NnM%16-Ic=$EfF272TycQWC|R+1%vV^KNAYu^fvbX5Fh9 z1D0z>IbthlM&zXLK+S3HnDtS6567=|&h&{T!Y9EmyNiPym;U8P?O~rG{agd{XXEZj z9){0r59(%8#UUwO#X)N zDX%2g?@taGtu;{n0qHWzTLo(Roy(f?dqd9~w!L+kNGfSUMqwt-KIbc}n?!`?k83eN z)IDkV4(eZo4erGKB3^Vh?bn%m;Z~?v%_v267eaIwfy_=xanteh>?~%Cdp#`w*O?GM7>fX-8+o|gC9Bn^y(quN| zR^Pc%0AJecVy-zQDfZ|VVLv}U;Sq3ZaIA|U@4-eTo!fm5=1O|ITjh?>_5*kGD6JXI z>uD%Q*x~44@htuEtYAQWODEa?ZV|(tk9BNev5#*-8<{~h6(y{{; z=C)y_uwdL6+5an&qa0c}EBz4l0~V*tvhEK_KipWS)Rp6rf-{s7MGOFp{s&HYM~6FK zmA}!}&`=|qnu z(njl{t-XUeUPM!QSxik=w)KO&5fs1`x|}%TUHy53#h(+|Fz+4`XIQ4-$e{u`bOXBs zUABua#>3%7)0m>u*l8B|y|twiAB*>BVw-=5o8)9?nZGNz9#k=dndC3O{$l$NhZTU9 zLNv~^n9itG?W#nqZct9u<{f2^=lIZ}Nt`=BJvrY$trt15+jMjVD-7iRc&yM9ABR4s99Ua@Ft{37)_mP?R|(y|rwM?^R;I;`axF&ECUoynK@ zi0M>DMN+137{R`PE+%ETAEe4%KE z9=4wSEZN43a~oMoBp0_$t-*2*^*PlWe&g}@p4P0N_Y%`${43j6^1Fd9;FUlC*@QJF zC+e{QI=>*OZoXVsID(%~ev{`I+Yxdn#?qgMR};Ti_{7++02le8f z61&J0oS33mSEpEO)XDT{h$Tq^2crRL#Yo}me19%8*+~!1%~5J2?2(PDR|wp8$sOXi zzO{O~_*7a3rLU^J#M{R_#Y=BsV@z$n%4n`q{Tp)3m~ClNBEf-3fBeQsWhE4O>xos1 zH0whUDN9*1T64m3d~()FX{(pobd{9Z9HfFce9vI*W!a7^!g4VQcwQ8*bCpxoTul0= zKoST%I6w@cE%{T?3fS+$U_BJ7fRD0@hu9CZSa|C_wQ;1hdGg0s*F=)Zzx@#!-txU* zcdk>AdthCVJP}w_Se*(D9?dNGL7w}DEA(kTK(e{i%)ZqvW(WQkQPh<~hR!$t-@lz< zq1Wjp?Eh_-jczSaI0h`OD8B}8XD9Y@V4M=3Wko-G4e1xeU&Ux_=Y09J-HoGGrbLUt zVYV_kT970t3OM0zk@G$$Vn9k)-9yGO&O}-Fjsz#+d^pomw(25+>kE0sE{{u0b)UnU zek^gm+2lYSC)RK9kdNT6tY+J)viq&UV3Mi+Y5cX}=qJVb!K_arLFdp=kM_90Q04*L zaa)ZN-eQH4ERiQGJUhvH0qOpBWU2-grOJH96J|c8l&tyuhbUbCmsi4H0{^!V>Fj@m zNLg|JTZlA!PBxmg0?Kf872F~jj)^R&LwP-s*zRfA5;#ws=;rLp?*ZWJY*5Ls&3Ue3 z`V_9-buF2@PWzPeq}fpPYYxsze^8nABjn4zL7fJWc;qU};5z3+(3q+GyFYKlTjmz{ zW{$lfXnYS216}4Yffze#w(Ac`X2-qE?c#`nezmRWK3M*4NU39Bav;?TgBbp))LzQe zR*+y;J?$4V7R^E=tt})L>OUHy&^hIrzA10+uRLsa!$w(k&G99);K`CX&e_?ewzjg7w`-+c+rnr6H9_=( zocxChFF6Hw<}i}wuSM<@KEAAgp9FacK}xmfGg8xgs;-6H*EuC`#AGu(6Z0KrD;PGr zzrQfspT1_^x;dI-efi$C2)>`3DJUqR6wykgNGn&=XUap`!qQ02xiDSQi`2IAQxhw7pK{mfYsZR| zml4;~^C(Z3V-orMTix(suuA^rp7_v8thTP&wBAy~ki&boH0}fG&C}y{cCEUAYeewK zOM{(=L*IT6;QNH#HdwUO|=3 ze-7kRO={J%O!6@D7Q1|@Hu=EMgd7A{#2nfJW)gqPixSZ`%CEn9u$rp)I4)lLpAZYC z7{PWK1U&@T@Si^Qz!>o>EAe){+`%OFRoj-frY{ALRP2x(UuMfbVS$c&!ghT3j=XP9 z=UZ^cf}I?SZv1ScDEbL?&&KSY)XN2T+~ZZ$jEMQ6<0i6$EpNQ)k_mS4>iu!(jSXc* z+e_RHINb9K%WjOTF4mS_Sh;_ty?^cAr{6IGu@qy-N zcYnyz=;d3j32djS`B3iM9ce~u;w;^X3cTm)DcLQzoY`zt8>_Z>jnWs9@Q}*>NaF;;5`ojh*R?+R zF-0>aA5(_c!3CLp^NcPMP~*)W6$0TTb>3Xd>iivxO8$9S6{mhA6Fl(x{F^BT8tsp` zF9P}-uMQ^uSF5LB< z3YRKb1~dBo2X5Z@wz*tiao(nHD%IOQ+~u7+ zn>UBE*P1xB7+5DA(n`cRrh_h-Gi`+aD?X58jn8UA)bgtCJK^}cmR|cnuGMaGrD80> z)7%zUYAxZ$Dy34W!2#9?)0XB2bJb~i%<*hZuKop~_pMzCq^&I`moLS`XJ(5zvyphC zfmAN58B@_pSGC%vt&N|cskiINYkG0tNcD9p|KH+Gz7%(?6`Y32pg;D9%CncYUf^yS zA%~o@Wsq%3bT_cvHla30_Y>E6Dv{rqv|2CETiN@9)pkw!3G%^bG=aMoXQ%H*=NTnM zE6+ESb$Y@{c?Pa(9<0S}KyegbJCkrWcHqT3iv5btv!{V1ZZHj@iC7w^cd9H5yc1%_ zqy8+AEqHyh#vMt$$Jf>d_tlw|Z^gFZh2yZUpq|2i*jWQ~;%;01E-|c5rU&*Y2?rx#?24Q{)91&Y5UU2+uJLtv?jfw?J7+GI7V`X+mEkS&ZNl3g6-f z#DAS_K*vsqIz!O=bB`_)W`Ee#HBh~q+y+ikD0BIX8j&{l_dG#zPwb6blQME6nv3R= z?6?{V2GhNZ(Y-AVmF6hJ%ZPc8448=}CMirDew^ol-{6Bz1U{Pk4O}?1Dzq5Ho?(1U z6FB1xizojbcw%PaBpM6UrD^_tIL?+7G<|3$qrQ`T*C99gm*~NL4QpSVV4J`^Ke|`8 zmgJZq3n4$3(eV|L7u$J???I#t-LF|BPv@tvSYl{fqm75sK=ZAivkw9)(t6v*Z~^Er z%P2=6G}F=CNyc%1rM^9DC^1ashcyTgbPv8#O{GK$zAJZj!jHF9+93iN&ZAM0a z({uMjyz6cv$5x91!49eM>UYQ=FXKhJX=_K-7+xD=ZepOFKkf}KFw&K7RQ{6hM!R;h zDYkU)bTcTpk!gxQ_)|8kbz!CwrShL_>&WO4immBak_o41_TBa*9{vF?+%*pv@$tNs z(oQ8aNCA5~V?kG2iM86MCQ^tAQ+j4abkCZhmYw}Nl1J^(6cN4^T>Wct>0u$47E7kP zn|$;9?riCE@}OJJq6={$n@yJd&WSnw_kyAC!kg%MIbjT@1na)*0)kYoVeByz?P9ej z`}Bca3|Cv|TtLAvMvX1Pz8R%Tn~cvqTjyK?FDP0^luuJllWLU;>uHhxnJo#ggLNS) z{fp-7LD9oN$C1WFL?%!nz8KHi`GKh2H%B1PAjPJC+)~VyElB|z_~nyQOX1IKp1aX% zmlBb0$?;o^gtgxlr@H?L9BWchez}FiUyJLA4I+xOc6-FAnBbU1{y6QVDq>i}dKj(8 z+vYQ6Y+^2xOS`)rsl}Uba@%xH^u7_lUN67s+Rof+IBg~6KBhnR>ag?Aim&UrEl~}Y z8iU#Pj!8G>dvat=Q`_O_R8p(O( zXoAR|dIX*(HVgI;XutiJxnfF6k?{z9EZF=;~ z)mT~`)KS3r3t(*`{CGMd<|jGGwCsVCEUt5g&xbqeC!s&CkSb(kn3{NbZ_9D-hF(*z z*4+@k(4D`Qxcq+5H%|37#=Q3%O@PgBqr~Ub`$Q$f(fZ5%jl52!%?sSWg0kr8n#W96 z)&?XNB>hTp&c7u&=3O3Ci*rr#nj9(VR$j}NfIR`!)_g0g4laq!JC5La8UH-*e!)mP z>sHm71butF>^tJ)I<*9AX0F$R9Z>CfvWDWeY#Rcf)1nXb9^NJj>@TyA{+8MgOJ_dD z`OXyc-`4;jmFDZ`=)9u+`Qw*@in zjXZ*SvRXPbv`4m6MeK`$u2C_aRO0KpSK%~*J;SmVx@eTr{UEm0aa&+bwq-@3!T3~` zPUbm+z~IRG&Tg&(c*Dqeeucd<$y1>0)1-Ok_KVF1>Cnn3@v7R48eYuQD%Po_r@3Dr z>d8xZwMpz&t9c8k^#tH>E~vzIUM)pH&>k#T7ml^bz^@RwVl|iPXB*2hrlY2#zs-+3 zL3>=eeXFvw4uyy){(Yfw3>3<9O8BuV9qGzSSv+)cA2p+eG(T!QX>{RCMy`j{BH?67 z^{ekHX4;7>`c%)Wr+c<0_TluD!d({{+VxQUC2IQ50>1^R8>6+$a=ib^9 z2?##{Fa%cu6`jOAPp^o{}gSWx@& zU^B@N+7qInTl%qkp(dVd37^dBj=BZ2+?HqZFVR|S3+E%wCh82aApT#umfR9bjNsJb zquw-(I7AMJ|ElqyF3R{VikDjQIASQt;`Yq=+#XoeGmvIx(?exTz-wB2;_nQz(}zvD z^_LyFO9nOUDmt&SD6R@Cau30%{JVE^@y2UL%8hM16uI^W=s@-P1vjZ2CEI0mC19G353bYxyzxZns-5d{kha;v&MrQFT71#q6K$(?d1gxC3-zM zq$k9$NC!F1PPo(KW!BU7Dn5L9;Is?{t&j!HlYCKoK9XZ>x#|hS)(h&|um%+Qq{Gt88HfxOM<(7Ppz3qTRT@_+^x%g-5aqg zSl|Dv(yr@a{W+Uf7=qe!a1XMwR%y!?<_{^EUb;yKw%i&fx%5B57{(7O6CNH-T}_88 zi~Yf1@r5?j5DN?XRbnw==)+x&(*V-)NLI<`dE47+GsUjuqw+P23odq(_C(al?%<{? zMew%dh3w@)Ao{`tNG&&RJkLm2es=aoY;Lwlse;p#=}5ICec+obU+-?{S*Ns~QvAFk zEiex+m^y95L*f>pWCmcH=MLUn8{EuVDmCpXJHM748y`Dn&dZ~*dM1&iGsj!?$qSk( zPOJCDsz3FJXvHAsSH#bs4XUlANGiqmO#E}l8u;)m!Tadd7yL6 zl~16b_SI3_n*OH|be(cs^Q+Z9%}Qu$+|9DDC|;ISfN3V5k;( zyORg~=#5vQsRnst;n%`Ik@^YBXdwoR=@oDyeVgf08wDrf=!LTpg-&i47p6SX5-K2( z>3qK=jHKEsv<`ur9E@dbaz!E8IOR-kX+p({a}ONP{jo}ZrQ>QEXSA{Ud#&*E;HFI* zmGl6ni)(%9mHDFiC%R&{HgNV>ruuOf+eZvvz%}ipoFepXh?UP!tn2x_FRHAcUc*=9 zCYp!!7aW?T_!WyyQ&I}m0gfz_nyizuiH=~)1C)N~@65^AOE6zr@WP4756@a6l8*Nd zHfC0b%y`k%7Q0afEZP;N7JJtgmXJuCHfpiTwU~SrHw{k|a?prD)Bb$Vmpkz<+Ot#d zc?`t(l%@a(rfOhY^CBh+{`{I43Q_xPlUJQ0QXaYCWA+dE%!KPWALckdylNNXS|c+V z!__hjQG~yN^p#kjH&GAs`)rP7HGu0zSmAk|FTM;anpV&*Wl#1JTTcx5cpY!)$|}!a zgnTgdfq6@2zcM&?9+IXZ>a9Exn5oFuTR^6S<8T=K@aLtV<3DhT$5)r>yp=XPn$tOC zNh}BaydoVjDTnLyT8+ajcZWagiv#UTUF=FbXcLw*c)(-U)WY2}FXA{H52-dY)niFb47uy1HC#yI(gr)b z95$kXg6`sEb~CI2m*?&ti~FzTp*m>soltct#QrPz*mO6;$;2r0p1siWiD0QsygrlE zL(F!em;c&&lVTC8a24!HO@;6t+o`%0BMbMV>@B53}%Ovwn|qGuyg;#_8OW)e`xPV;L6R`R_{W5F=|$GRg$}*ZK+%tuP;iDzrow z{VJ(+xT4Zv%+@0KoWpY^iWV8&>0L<~QvM>+D}AqpZ=0|wR=h63864e?1ot)hQHwx3 zx%>+5CCFQ@`~O#`efiJoT$AQ=)ZXsVW^{2Z0@XKPCzw7WTg?0$J)R3LE-cb%@&7B1 zGlm^@#M)5xYnHH=#Gs76z-TeK6_!_9wZKV0bgERc502a5zX}39U3D*@jtdpc9}8#9 zB>Cf0WOUmNtv~D|`r`HegaNmaYv5c^aB;ku;>=GB&LR8g0AHS;>XN8h_+1%)JYYME zg6YPkB$#aM#x^)V7`KGci}lwbOh0BxdKRtV>T5inBq<`|-y9EgU&mG;_W2LoLIL;g zT3QZbx`M^}C~gT04A3G7;7p*h*w$yyIkhT0aXzKlh%2lEpqDo(9f_x*_{ih=-?{ z6%EJ;XCX~a%nWT4DqnW};l>j}lk&y7V5+ap<${3-BDc>+&@d8a2I(CxhQV@x45 zlsMGWDSh`0QpVTP!!ZJjjGqj-kDY7~JIl!c#n;%jFUF8n?0oNP8XzBp?eSUb``Fa3 zho>_%RiKyw&#!8lFEn_SKfPw=EzLqsZ;_^}FG~;4>=M~RRR(yOCg%7bIL1;(+aF5c z866WLz{->$nPDaQX`iCiN2R7AP_R}v`RqtrOOcx+QzZw1qAhv5C~RkFPf-F_OgIxa z{7vcMH%ymr?ah6}p6BXFu4QPg9S{>vKDsh6lNra8nNt4n_darKB2|f)cXd0a(8XRg zTS98@?(Xr32KpnL@FNS?zHQ1qly^o>&CJ+lz&|HqiP>h>1UDyj${N%$mZHA%1qZjY z?qQlYU0*!AISsfyc0#C!`U~lVD_z#_vSq79g&QP>+3WfD1EFskWl!&Q!mY>Vc4MXd zjpFD;vx_xx5~?PKHd5we2k_H_Cw9uTl?-?7()#+`I!{;vzNO3!0g( zqI$xUaj~s$ZQqD(j^BfMh!TlhEsWi@D33;(Rmt&sk;GTq26rdQv~dXnw4>qRkhe~) zexLL>ZqZF`$&Tzr=HZRG|FfRT)J~GUFSY{REqUN!DXfHfK4%h556)_xUM>b7W zFdIa$GnDb=?Zxsjbx(MjExY*VOsdpP9yv9CI=nbT(rJV(Cm z;`Xj%$rImU8I^xw42e$mJC{dKlG~nBcc)BK@36Wjq@Midi7hz^bF;*4Y7wNM`sk|B zMf>RKeWpuQN}gn@si8p4bxaOn5MCAzfrAsoBLkfDl7a(x>vy6MV%;#Pd?tGkJ6V?~ zV!|lr^IEB`GW3*XYLE%EH3#IdbrP55BysVHg05`dR(bG_!U`O)N8$vW?jTY#+ah*z zIfJ_HtUS7KdWzUF%GLgfa2C+Gp9-_8?at(w7rSZjPNUtAl=BM=111b|ZE+4KuBaEm z!acq^bw|1gy{gmO6eBcU#N2`(IcllL_VS`StaGGP3wlL-t32tx>*pR)PQHy7b$9N z(B;`P%qP!&h_Y}hEqDdx(OP0?VNdhSF7r9u#V@yc;vrwd@O2Ey;l{0aa|= z_9iz?C%WTP)OTwxRKcUGNX{h^hIMGpQ1BKbbn#k0h6%%$2Sas>Ej}&f_k~jOc~-S_ z3Fl{xG6dp+)@6*&R`1b6-OhUyL&K!}%UN`B~5d+id345C* zKk@Z^=oX*3Fg(MU86ZX&ouWi85i{s}nUnWe?;T9)IgSl$d=T{-AR{o=@uBp!X&$y&CR1EpT z|G?cX4K98t1*HwqRVbIsH69d@bVKBdIGrA zAM5m_%J6)yVplO99yTH^D{SG3bZge07MQxs_h9gE;S5T#-~8P$WHD()-`dlFy_>5= zryXp7_0c`f7YU&%CG<0kT~9lG>Wv8w;`&L7tuxP3!Qi(eXZ^d*%v9%KQ_>`c9ks^y z@chQSA$7U8wciM!{RAhN(%5sXoz>!O3$8$#pZUD{(jqmofk8t>4481=*PTa8g<%d6 zEN^sVr!Avu=QTfr(j|;GIwIlzD-J;^O0=lWm%jHp7&stf9}Wswy#n^o>3=>GNVyec z0OM))PE6%2v#8N*$1S2#=sBgjuIy$tE!cEWnZ;#Suz{1P-vNE`x}(aAzK^iIJbCG9ffjR^X8CCxb?H$;wd;;K(R^;W ztPUOvynM`9q{@C>a);S_K-~y~&ymqOU24-FAAs7DTSuS6=_x zEHZ5Fz;pnmWW3ZgxmmsIx-POlx)O3F@}-!xY>Io1qFl&<>`3>cBRSv3NpNLYt$5^+ zBXGRtgNh@?{9)CI`D2NE+BUKfF<%x@GDhRMWp*KBRBtCX2R&3p%HyZpTPg*oWgs~@ z1~k;^?RR~z(NF2sAI&JV-)>p80%!jwNzx^)#JX7q78$t zX(T;~gile;TYoe5{VpE8g*R=5df8zv;+V^3|LNnNVq?QGO@tTXXFN-%1)l(EMnyVd z5O4-$(DI(7qZNOoy;&zc%`M@jKM9eAczC;R7jQdw`gm0DIU=v2Kt?@OjoVP~sh^uX zu-F6L-ddC{n*{n|j@W+*c?N3}gf0Wf0}rqDq2?kFFtGfIXa5hcMAlBzF&=OWkZL0P z&xfnc**qD(oZhSI9#8h^o=nWLA2cN4=XBG1XPxfV+RWc$@&}MUq44edkenEfxEp^S zThZ6ll^S}GK|GGRZv%%MkYR*+V8Pt6NOwZdu0u{9SJg3lxs zWzrYZQ0&ilZw#Pc&~@ohQ-poEJXY;$5_`!i;Qc|QH$u+jhCaKM&a2+QeHO{H=(g=a zv+4@@Fz#>PyyYP5x+J3LnMk)0E>|1qsW}5{fSiQ^7B62+72UDGdo>Ye*!L7*6PpfU zea6Tgx5P{T6Ap^=4VMDT}VGe}+)v zQ%;ZlmQjtXso%7}0&Z+ed%L=;RK1rGEsd)vl53*Su<^Jt$<~EWOi#ip@H+20wmu`} zFy&}knQZf9rK=s#H)9hY+O`m#N8y3oB4kW54~rPv9=ojD$ro)O_1mlZDluVQNYeal z)=uid-}YmuYlT<%O&@rUm}~bEMX2fJhIO&;g%I*I9heM9gMT)PkU`xsB4F8;ufQS5 zI;E6m6gdWo{^d_iiGS2zT?%HyH-(Bd-S4}K5jN1ae66zbx6DyD7E7MyVNe9HJt#^r zPJPu;a5rS=0taT_h_P3Ob(EbJ53ka%dCLl?P6yaUg&-NVWcW=UPU_&Zn-Csmn06&a zeZiOENipN20Ol%7I_cyK;3tdwSdzF|gM2E07bUG2n4DegslK>uC~%HjUc(s!;?|{z zLvO^bE4;FL{9wiS2~QJxnP?)o^1}pV<8^!~BSd*2kWp)wb1TlV zv*KF)#*(~X7mtKetL>ga4+q^ro+>9kfg?&ZehDyb)L5ZYjq4@?l|iS}Q6LZ*qcs zq)kan3!`*Lj8CjNBr}AJ%7ollv=gIyU^nIOs^nQ-h2%=6?mNaBd*C$b+oK)M+qK3{ zTx#DjR!Oky;J4uFw;5fG1_Cif9Q*T|nT|(>To+;yJIfU7`}*4?Pa@xTx8;d+j&qZt zLk~tzZiqMyB_4F>+N2;%6^F-o_x7x_ zH?l8M`(}gE$)g5_Ia5Fw#IKaxHsSN0=osxsMlUiR{cmg+Wcy%X7i;cbdI9O>@zYe2 zUGD7MAb+Nqu5;PEOR3@aCD+T45^KF_a`G)I`yr+#7iWT@)5_u%N$EO%o^N5sHGv@%kFhid-QLyr0LE76ceapIokYN zoLK%9JF&&yZk_Fx-7!;w2_LxemiZ#DlbkFK=h?hwRu+&QDcm}$nA(%V+bxA{v97N9 zGgjYNBPKNA7jQ8P>3gJh6)v z&#M&pQgw}Y@q`0x&+f>GMGR0#>67C~ZQbGLmORPWR@>{5HWC~-yc$mRW^8M@{||<1 ztSkHX9{*?8e_d67VP>t*!d=R=cUlC|#ft>GyK7(P+GRDBt3&qmL^?igZUq32W9dIe zG2I@#^!+4u#dF?}HP#|3AqT-yAE=Hs5mA_KTw(cDn9&7p=3oCd{1iWn^?+YT3je(` zmv&sj^y^>inEd!deQ-fUu?~c$qeZ-IuCZHCgOT2qSPSsprKZ&dbL?sjEAx zb-#p7-NzusJ!lS}())Z)d$Vo%pZqJ6R1-vVk|A2`<0_~^G)LTxipqM)$7cmTQ;oX7 zYXS7B5tBQtgF;a!#g2h(h!0Dahf%y(?^TzY(1Q$=h`CL?-iK4V~Of2t87- zFFmVvlygQa;CsPF0vgZU>2?h4XHR&^-$6SoV(5;9$Wl$QV-KwE@hBgrvk3)0VW}F1 zpO&YLJ}A&q3~N3^GZT3}t|p)05ycsG9)M=$H)ppyrq<6pt`>fHnD#{m4ZQQqm8&uSvt9ajx59Q zPQ0Rf&%Cqn&_g!qtQKTGN1iiWS_?0h%_*>@7HkZj$`W)*aB{>%{51qlOrY<2Z&B)& zFr%Ak2l(7p`1--->zR6kbLQ+Uwb37ene~7s1yBjM{!31>EK}*|8~&xVK68 zwm==z^y^ywW(j`l8=Kj(TKcm2*^6If=O7j|=5kA>+K~j*uOp&`eDJnV$(Kpq^m6fw zkSEvC(3}>}&Ok{97ga|rq0%AJY z4>*K`n%zZ9@GAX7@kt*A=IDgD94v9%J(fJ#T<1K^USun>&5l(}WM4r8ej?lxLTlt> zy({In;<@a7Oxvy;W34$1D45$HS!=yExPXm zfhhDHSq_JeoQE$+m8b!V);w9aRI0h&3C7;=$sI92xjRxNI#jWqS=(7FK!LBJ1OJ3C z{7oRcn8^!Lzr!hNleCttN&hSRA~COT(JIFX`}e^#uuWaROu7u{_Aw)d*4V5tc8(#W z43PAdtC`Ax&5sSmKvZFbQdp)f%gmb`zD}{<#85r7B-nNEqKfyXqg<=Qk z%QdF~rnUJ7$vvn*($%WHN}a=0)<-4Y&VAKoIlg@~fx|cchuLahmxYz7Rm9ba@T8j& z*<12xCRP@A5Z(3zohg2%`@KYdgr+hh6A3$|SRy zeq;aoDaldv3d3TpmUtlVv2@k&ufj0S@0WmMtNKzVS9a$>bjx?G0)Eyym+<_nD1q(7 zhBUJa!1$P7aKKE`3N5^4{((-kKU_oNX)g0)4>h))!cop@QVGNO7Rk(k1V z-zi&T3-=T;ITsF1&X9O35_Jme^cGSha>t8%@jY)Z9{JRJE-Vosn_nXOh_JyI227B7TyS2&U~OeUqV(f~ty;I+PIzdiAK3Gk@S0P8A*p zI*&aU7d#S?a$v>lK{zM{3S0@6Q__mB0|UWD)}#5Wg~vnB&0snzGe}4C4_*#J4zvV) zISx_@SY4Y3tS+Sws(Y2v5l9x8g|RtyO-J#MsubXjd_Cz$+~|J=Zqc21^-fMvYTb{^ z#~IgvaaRT`t=~Duj}i!LVjKoDA-OKurE4$bEndI%@i-hQYdx zr@g^O4gLVsCURx1f!sH=)=6brA91{0ej0yV;CVxw(~QP)MmtULu|3g74MBc(6~!#x z5$wFf9_Vo#Xd<)^03fcd9o)b78~@?z&#fP4LO?M458S6~ErI|5%qBZAn;n(pCdrN` z~^4`}9**nma_HA-dy{B*^+9C|$0KWao<{%vydTm>J!fJlsDd!3mMo#72l6 z5D%d}-i)rC16Ot_bWYqy!A|4T%p!80y&lGvbt#HTS&P3I|ww-k)JCZHP|utwX?kn4{O@Va8bdQ;olWN7bKs~ zFDUgrvBRzaF4oEBg1yM>wcQ8+sFV$}Dl>U}W2|@3Vui3dLOCaz=<$PF2@-?Ks58{@`8Nhai6Szq~f2E8G=I@Ltm z@nEWM(6eQ{a2f*t*CiHgEoMTRX&r*$!=qS7Cim$_6?*F7qu5#;$4YEY+!Q@Y_q9S! zhu1YvFBb&_;`zA&)ndNB!kOU<2NNkH9b<_01&;vD5rZW%*Xb9(0U>^<%%(K4Bl<*^ zT{S=bx0ZHVPi(&_e{7MlF0vgWZ;h^ zrjW#kxdf{xS8JAw%8V3A9mJi}NU(Rvfz+2~F?_2x+9~|imE)k+P)j|-4DxEHA2M

    Xuup8ZDqi4;fY5!4eG7Q)N_4VLK@KylWya~Z$1R6Fn zMW;Vix)bg8Zp|97mUKU0Wv>bF)*5c_JX6g4LH)veWPL&=sE+T5)zy(=J^jhIq7U)I zuF%lNe#GF=@5xNpZGNk&#*YxYcJ8mo=e|M{(+yQ++6kWlhtlDt5D0|n3f((8M?@E6 z;fX*NB@c8Ty$3dD&SGs|cd{#T_Mkc`)IrM4XO;p;TfudKkxbo>-Ti4>eDMak;-|7$ zTaoy^_OI-y`Ie?Fva}Lo>H*Rt*o>M;rsSSrv6Yu2Bk^+P&9%MG1d%=7y2B)OkwLIe+I;(~&we z#U3Lu!ygHVLDM0!q%Jm&f7}Z2+{G;5GQNK~FU?B-yp*5lmoZ0BRtvHfJ=j{Dlp)Pq zD$$|jVbLLh=Ms(!aSh};CJS1TPT?(Z7;=Zsw8R5a#S}p2$!0ow(bG-$TLi$!|&82L1`K_uR=vVl}k;T6PM(ip`xmZ|Wx8jrYGg_HGS|~(C zk=VmQ!tNQLVlPN8b1!qs@0Q~WsS^O&zGudHRZ!#J8`GSSW#>ZVG7);>vXxVPe(rdFw?wZd&gZTtP`u)`ES}Py z+Q#3LJuEX)acDyJBG`O>kGa;C{}_6pwddD>lI5;+T9xZ`Pr<7}*S4tBQb=N*s(pe_ zTfmk`(@hSx(=_x@y<%2MLrQcFj zPtc8J5r%1E7f!7SM9|hu$U1`kEDku@`8dmz9_dimJ{MpX;l6X3WS3)eo406XW&6i8 zDG~4)(GxX2FWo=j9aFHynisavc737+MerkQmd%pzHS;g&8R%yz7~#WZ_O}?(C;Qsu z@qbU=mW|t8AL*b8b$Ow)gDy{2Up&(58;u-h42c9NyK+ajlj#B_EMyC!wakFi>pZ@W*69|2~ZpBcJ?P>9=vHVl;qX+Yu@N;W=>}Rx zF3Ug5*wpYGQIp5hr;Xh}8`GumPVn~Cn}efHUMg?Lo1N_J!IH#Dr6-qwmrOcR872cJ zVxoUALFA<+9FsQ3+C-)mrfKTecqo(SO|!LIR~^uFJ{F9&^zAVm60$i(rM_7_Qik2t zfMoK_r4+%@WD9C)z^E!F0SfR86EP0N9k-BGaqnV&@-aiIUz|GcG*P+8QS^hsPn(L>_XgZ*<9f>gymPS8)mz$*)t-BBW##CctFywU+3}k9X z7{i>~qK;as#8$tw!V{!!Oiy=*v-Wd|mye6}#%M-;{kqGCTBuYbP^=xV$ZVgQ*B>Nj z|C}ye+|pn6okvUqGw}XHH@xf&%YnzUd{&CR_y*J=%iQmhxWP!y1{3`&3#+kh)Y-&{ z`F4sdZ01+yUFJ`QjaGY`jPvqkyX)E+?1J=o+ASJu^c zHNG31TJ%BQf?)sQwVwU6hHyv>nK?i+krO$Gb%Y?l$3tu$6vzWT!PH8n*Hs$_X#u${ zia4|vaKtI9Gxlf0GhLBAv~hh{#PVfE?Jpu3IuAe~6Z-sLWfJ2KOwG0{WaNKiNL|}f zCch1`>AUQMZ65>c2G_K8-%D8)F0LovfGRI2^zB0mGanCU-h_b2E13(B17YkvLfsZIZH`CF>QyZorW8K6rLmN39Mq87 zp@^>_7l_1r*dU}+3>o_7ZDdr2#-OBNMne5yJH}b$r35taLUe9$(#GUd z{)KIC^0(>Z-mR$&QSknGK(v2&i`}QHpLV7NbCi0rp(XtVDy0fH17NR`BeRKF#bXa1 zvIGRrRBLG`$EII+>^4>(Cg+G2U72ct5mFoj`iV8h^@4$^7N3<;IefSyjaO6)iYr3c z*`?Wt*ne)OM&#!L8E2HJ1Zj(%)Mo4F)EmZATM{r<+1I!f4eG$BV>s2{rw1?<2~dX9 z;KbZKCDLudDRn^B@$- z7c1Usen|WG*A5%bIBIUr58xgM5N z4NV~C9c2~`KUmz}hWv-*HY=$`<66in!kX;?_s8b)`zX}Wsq#7vZM> z=vj{2m1I*XvKF4A8(Ig!7kr-4{@SJ{V#?U5z3sPa$Jf_Xin4H!1(5`=r zliQ(*67{kwS6;-1;qUP@DpKK=28fQaj`K+!L#^Xt*il4iKgN&g{0x3|63q_)ORGcokyccDl3eQAt#V%PBgw67?6C5#|mg0oXqBtDdz$} z3(QyBT=u{iIAK9yFx*b+i#ACcl$wr5l#bL+v0gujd~=oBKQr9sxK{k;HLP^{&~evgWW9ki z61A3INlYu;0xDpw%Nv&99yn*drDFcN-d`6>qr|NJeLpGbvxPQ$0Ylp0x9A-MA&%5P zC~cTDgC}J9!BW51Q7>pCnoU(^e{yQJ!ci*@dT1Y;4 zS0}C>C2#o;ujA!N985%$=mXCe!pVFUN~;3ZoUA?lB!{GM8IhGqEIOc{`FxtcqN8Js zBnKLN^3A`}6S9WH>uA|oaL<{_m4>HU1Gw7UHewIJ24X|$i=LKdS@x#HlqPy>#MVb9_oLOY zrn>hL87G8WGWT5ae+>(%Dx)geeo#eZB()jb{SfWKLJ?P`P2Dw+>x)6xiF2K(xZ2m7 z3(mU4?un>&)AMM3;`;{^8tLD$U&;G70HkN^O>~=unBPDBdbzdQzxM*xMRE%07J#eM@Sq{eOA_U0$WtP;&0PlC%$5#kD z_>d*)Z9DFqkGDXD;vVT+DRw6Z8U&#~J{x+l_OjxszFCcsJdV1yq(ONrD_^a9M$^HV zBW&KQH*q-emj^NN%Eij19jqUuj8PvT5Oz+`n2StGqjQ)Nsv=o{@oP0@&1ZyNYWKoV zep}Ul0F~D7)PY6x@3HR*yKsr9eWWoHc;48#@ybf)2;Z57rInzUjLSp%(CT&uZ|jNA zbVqNHq1ZHkLR8bciqqVr%euFVfhRcZLP1OU5hZq?Q`v1P(n9C)K6bsm)xjhym2XZ) zu!Kx*;b~Osb&3FrIj1nvc0fjO<^bUcmT5@wR05tHq%~7(RMnuB2_JO z7GT6HV~DnUe#dYW%R`MW+oYql|L-c5~Gd9pqxm8hXhzLq$@LK`V?C`6V8luo_J+ikbr6fu^UZr-ZPDA$a* z1Wps?Z$1fh1x5Q+z5o-Z-JSCO1dZX+e86%d+t@i=YxMP0R@1l3${?GuYQ$(_0??9Z z)+EXRqSj7BQoUB@pmeu6ru=ZK{AboMoL1jCX0I-XB9`983G=S1Q~u~I_S>$3oA{{A z-lpWRTCR%PH-mOF zcHq(a5F?z^PKzh;K5MJuR1tY7$u1}_PuX=5Ms}?Mslep-8C79Hh9G?*h*BCuST5jD{)rUTiAO>#KdvBzZ6MwGdo+{%$EE0R?{9`vx~K%KBGYb04zA6J0FZ#_ro{0ns)4xhp-osPE#$*D;yzakGqnrxq!)J^DC6#LL;R*i z{olR*ZIDty^WH>!f_yBS4n8|+;%^msnHepaf!%)A&%+wArtIeQp*tLdAHsRy=;1R( z5QeTb`jo@Y+s<_dQ+dQ|dKV@RclsN`8?S8jN3PH*&Ih*PA>&N8BJQZ0OjhIi_AiZt zsyFUPTSIDivxLVCn%e1zq1#!4yNqqdo2QmWlxKu9C&Rc3fy=vs)$vtc;Y*d3FO-#{ zuA##Lg}5^8`0NjogA8R3ObL5X=wPR8@s`7}=S3-0@4j*Oipx}IWi^{f;k;p=h0tVx z#uNxNx_p0{g2!Q+SxvxJTTq2J?10=hL+zF`MM48%>PmG~HJmB(`cy|1KO2A)V9w9g zKbkz-{Dg>t?E&T5If5G&RpJN5v&*KImN?_kArG%5-KO62XNp;SKlvIhVPUh^%t-d& z0_Mlz3eD{7ovJ-o2=!ZS*B3YoyT9vO^0L*lP9f5#&r;5_v+5VFJ8}uf!15;_li%-e zt|XYc8O6u1a{1hN_bv13+Wm6of;KNYW49k(eX2plChq)1dairQ0DGktKKMWq;4Hz9 z!`o}IQ{$Wq;*+)GO}^&4cYYxg1oY|CS?~Y2k}kFk$PyF&X!-+d2c?w!M?LD$gQg*oh)D0)ODdlGo7@fS4z-o$A@5{*^$^odL$OWo~{jN z1pfrt2zgog?|_tI#()p%qEZ-2=~ZO4xrQR{_BxmLn`I%)yUj!lVU9i~tvYhTjcm;P z9gg}C$OdS9?qrD&4Vutu4*kIy_Y0e3TYt<;H4u<~oea`rGjB~1_{3}rCiHFF<%kyY@Y-Bx?JD*tus@tN+0SYuH7*)r*>Iy1gQEi)Kn<87HaPRPnW*14tuJi9Fq?$UvQKEY-U^F*3w$DxNS_9ki#FU$VXrN+p(gDmGz{aLf~UpXj3MyU!td zihW2y4$IyB<5xLu)I4{|EU^bd{kf&pLA?&0ZLGq+wm`1^Q}~n}#S#;5Nyg;3taUz{ z-d3EpQgah?w%_A~Ed3c32_n(&9vl0u$;oA(-e18_PG3%68hR`hMrW`l+E;+)bt?K1 zU9{#Sy2v-b9^Psi3%#hc<601~AUS|tMWHnvpUH*CcRzMNh3%>%8W1;1m_t<4QY(4D zHtsOk{T5Lj+?`^w#bkfcWVHi8Z5k-G2>}hvU8pS^7{(Ob)cM>T(W+gnYf^%OWcK>Kt!ywxs4WAnmJKkE&xDQltWX%vie@G*Ef8Uo?l-o2wEGxZWVQyW=Z6d`gwB{TZfzM4u7K8#Fb5R{*e)w)XWd?)#74yV;NJ6(etXXYT~&EO8lw&S9-PeYqFG8N zUUYEP{+nKZ=WZ`1#?+y9T5 z_D)-)y$7Co1w0-`nB@MsIQy$#FG0Dxf>}O7+-WSXJ3~Cny!C#{lWUPKLPu@Hxb`A+ zrw#ui*(zv`!Ri(;xO1GxBs%h&5U=y`?8Q`Ex2BIfo`<*?{66p>G0M``(z5cwG z$He!6tXp27mtyC^%McaAQFM;*vof#&L#D|1Qy|yz#$F!X$bX(HKg7t>Ph9!G1%O1Y zz8Ng84ZHUibJ4>poc-}i-EfyahQpv#mdY-PA$aSNHiASSY>)T87Z#2XByp8}Ch{w~>4F%wjk^L#nzDOnx#Qq=9&Pf;*>I zLC!1U0L$$4#)sKoeD59dhRJylWTS`cA^V=m|1@AkDgI5|Wn-(0nqSj%MdMDR3+9@> z*tP8}Yq2M%T(a}vXYf-r>Mj3_mMgE3*VsQ8ofx|xM(r6<%IaD8mQE^_c8piqb z8Hg!N0iKWuoZTsA4dU*?ll%6E%85<^Ml!@hPAp-=ar`BrdZxd+uj<&wP+`vFUpjYx zlm5ZrzAfG{l-dVwBHl1KGkDsdKx9;xjOqZL3Tx@0~TX5+^oo9LZukimuH| z3pWd5$u>^wqczcvLC>r1v;AFoW@TfXOjk;%i7L;@?|--#HPinc4o(J_3bHElk^kp` zUP`!ymt@HMfqJvxOp87@neK2!8&#cCzseA+rqxQ)*BUC_!pyZjh2RW7Zl5>)08$vi zx7c3D>Y{Mo6OeM+JYpx5J7N!LxN2C0&8j$tg#<)QjNz@6NUjueNE&@o4~x@4b1W$x z`+bsL8EGMVYSKhhK8D^|+x8_stZ(RrozGndPa9cR2kv|0R?{3$bL_T^4y4*RExU`L zda#^>h+R{2Yi6q1ozOx;i2)Azo2jjDj2!cV`zG_YSf-4oTQA+t=@t zh*)iBiw*X<2CEg;ihpJt&7Bx53QRnXx(O$pwu$=Maj)e|d=k1*jPgv)AnD-CD*l;hV(C`801&pD&70_ zi!8#7WGzll1>TIC za^tr|SzCeM_X62a7pVZeKKIbr7KbX1M#kaAg_~imA#Evp&>oqFN?w(Ay?s6yeS|!& zU)oS2ipj`&9|jqc)N|dk6XzhrUIQ;THETP7jj2u4QZSb+y{kc`+EqtxLz!m*hao

    M*s{hiqwbnS1Ph@X^_ zos;EJQIjVkpc1{TZTqd3! zSl(&9`^^Qb_+}klFL|26@w7b~)Y|c7!o+d7O+WUzrMep(9rY(tT&1@G^W$X6XM7|Q zFs{428XW;h0_5tHX{Mialr!P~X3IZHOfHO*n@kExS+8%#R(Lv3ziV&crIr0KchY{s ze&VpM&t>D6%Rd*VLni^5H>OV(T@K2S+xp2nXc z5ld%^L^^2(htE34BC~ zZ5u~=-$GBCZ*!4ZuX=8;$fI45vW~0_^|)AEi6i|fY78I7>N~zlB1%ciCyg*@%NH(C zBpg7yctpcwawYENUg@%(Fw{A9M_3Zf5W*HGRK>cZYS{C#m0H#A$dlF>oD-wh;1S8W z&$>-V+e}RGF0IVUD{|!qZ8mpL-wHSB2~|N~dhdoe$<(m76mhF(njkIz*pY5(4y z!UbL$95~pE#YCh6BVY2vgsn7l!SjZXWj60dxiw@;SqhXXGMluXM?rscT{k%1}8p@#{B? zD7+Hbva2cLPaf_d9_OEIyGjfs?=1%JOZ-T&WD+utrmFiUAp_!`- zs?oSF96z>mauM4Y2G4@{xM+@<9S7!xhnhH-hX2*CSZG7)sR)ay(fn8ykXQMft?Pp)B z(Vl8FBlJNVuAdOJHzvOPz%Hrs%)ORlNi}(5Dafa}N%N8z>OxjBTXUh3cQYf$m3-v+X|dzFaY8}=xwwaQ zi{rKlHZ~$lh#|>q?YzzIy3=+#eu9xwgE4vOiY4m0(KauMP;xR-BF7Te4}+%fxil14MJ=!anvW(2@0ob#`QZUH*OT9*>2B zpUh$i+nrR@&2V)DG*U+>DnElUSf6Rd!}`twn(Addu$5#(SAr#^OMBIjXYKyl}<}eUfcut2+ddB10E_Y7cpw3}34RPcq_g zn=jpoM;A|Xmg;pP(@UdusU-36L-ku2=t(Ed1A7^v(zg+3HvFMhETWgMm==+qDFvUJ zZQV1mt(<}jZ%l^i0u&lSlSC%mc;ZEy}&qY9Ps#SZELJ{D?7KcNOGbu@z zBXNZzBZE@Q%_zBbkiuXc)0_!Ws>c;LEy&Fi1o6MGWEx!(NJ)Vp&;m(H8?`=-$OCTa znZ`tDCu;y~0EiqCLD&YtDFfD^|EnDMcloSSaQNwgjYsHD%I-W`bXhDA4Pa+ttKo;d zp3%9c=aCg`vNZGYxU~WX-5_(E)ln1EN`P3za*ee?*hbxMIzv1*-mPIm8aFdw%!d_i zXHVaZGJC!RzpHMg*G(idS+fy?`FH%TuvAr7c3i`doNUKvJ6e&;d7HcOw!dN3QP`A0 zBo|K}@IwB55(F+Ex46488wqSL? z4VWf6$8E%f9S@(~axT!`;(+PTZ(^?!Lang2v1c}rQ?2JiH}p2?!uOuoe_w-tN~zMM zV?v4mFGRj#m&YUD%tVxy5|6?ZUx-YIewRxB!e+F+YWA>D%$QvjC0hWQ4*^?9hSxbf zAY2&UNV#tGNlLDECqo@ZGGB|I4;E%$EXTcs3J|2v+YysjS2o4X=9La-m0BQJQZ`$J ztyU5v>kwapA8) zP0|}E6Ca@@A>I{*8ff92V3r;O%FCF@2?B&kNS1f3FXrGHGz5?_1o%|Uht}g3@@}Ce z9gcuATS#6}d$6(dO16P}A^n5)m*_@Q?(B;~SViG?$n|7F7{116m&P3%ERnW#{;tJ< zBOlPR~X;<2b~sxhS- zwSe?MYU2ElB{A|if-yPrNyuvG`G8s))3TE%s#cespfqV)R(=p}qELb1&$pb<3GM-U zDInd@`%BC)CLF)clg;>Sr(xqhX}bDKdSo1ce{8SLV7H$9s`=Qx)-j-NTRpL0KH2E$ zPj$i2$&HSWC{vRB2jDT|Ps~gMM-r4ZXpctLKgK=C%^!zLYyK3L!c_$_QF+|XxYP#v zw?4~`>QwBzZv6!)kU?;*j_o~}hscyJuEoCwz@fCeRWP&rJKzFvq8xEl>M=&Mlu_wv z$Q*=Pa;VzICo5%JHVjIDc+S*mTivZfU|49>mf1%t68j`Gp zP?1NCKSTOwt?id~F@9nblQ%&dlxwYZ&ja9Q$)ENAp#3u0y9cmmM!{EnE^2vl?vi+# zD3NR&b9oY&C1Vkool5F3> z{}x=6Pu7ch{@#7~sPAL-tJxa6NqZ98%&|k}_jUZrZH7Rf=iz99iMdx*?Z{afHGcg4 zB~?CH?_6Bu;Hlv~FeB*KJ{=TnQAE1>M?wGk&9qZ&%PEy^Zd}9 z+==`FtH0AWg(>)l9{R7+I=*&e*1BWH#rvJJx9)!gp|JfnFN=*ywa~{yUnj{oGsed0 zysg(}9hEw4HJw>uP`=gS`@(t5>N4^8+ocW$&6?}*@UE8fuFK~ziRb#l^JCZGCAowl zu2rx<-=}?2szrQ+E*)kvFfpNw&~TO{YvD3?>2>aj%vkUd6lcv1mUpJgI@}P-0yFS7 zg+0^KNu2-DcQEl4!#$_X9o3UT3%kvcs@zd^L~fO!xK(_4%d{$yOt*>1w`l0>@{n}v zu7{7TZjRbEW&wCVY_VxPR`N`>+eNbbse9E&c9!s zg}l0Ya&yQ1PRwGu;)(ZurH=joI>a01zq(`B>Z-8GRqKDVW4n-kmoFr`^laHaxY2j;)&uDuYN1KSs_4f3iTuGgJHy8j+BShqd7Gq?oD2ku&b z4+`BX9b6kKIVS60bH0W|{(uw7f@x}y=_GmeE0Ri%v9Zw)sQ|>zzokCzYz9Sw+p>4~ zx0G!yzskbrAMQh4z=_|oyeUWP$??#Wlyc7B;y04jEH8wbXp(yZaAebvo#QYYBHAjg ztw@rSel9P)yi8;s@29xRV?DUC=AIm8bkO0rpfK;nrG&7bZ%iFx8V^Lu7eeQ1!Jfb_ z(xWc}2Se5Cj5#5&1mi9)jyM zM;{2ireo#Re6)gdW{RWAB7TEOU+P5W_Tz84IC8{g_uYm{MWuyT2l zs&sngy-_@TOHFC>+Tjq`%+binpJ$S)+52Wql_vLeqLpZ^?nlrwj`?WMsp+>ssKL{i zr$0@_TU?`HSKC= zp^CGT?^cNsKZj0`2%MhqxkI0@-AFbs?CTGpzw&{PoIWGKw-J-cj3(cbNn6a0&f?d9 zS#-`##djdXJ`7Cx?9f1-K@ZeCXZ{?Ei@TYvj&H@Dbb`4i5H)JVw^kl=pa)6WYzY3q z^qo`Y+_)@7Sqj_bC}^Da2K^@bKo0h&eob&`ln!akz}(#HklX`?dGeffj2$lY28!$iwJR-V4sA58ijJa81tGDX-fI?Y0 z5IY25F>iF11zWV-bAThgPSnMC3;?d}x`0c|{zc0E@3QJYHiS8GSYEOT%Do*X{i&j0S0h0@0w{PP2(Aw`lD#se8o=fR(`C%W$Us;u2Ak%?llJ|m%BXJhq1 z&RL8NQ!?SqRWC-;Z*9s#!l9DBpCyAr8RNwW61A7#O_AC>Tgzv!*(yQ`ZtC2FRtwSi z@qU2AauENx0L8;-#fvPH8wyhtLNg`Zwt>g`n|t3PuZU0dYJa&$Wxxy2)$^Y%Gm=Cu?Lv zxWN}DU?yfk5t_A#h{V91@phrDyUKY1uzP9Bk!Ynw;1m2We9e;KdpxeXEuFx=a~mgb z%oZeTh=*@?akoR*gy>+8OrG|}c_s<&;ejF6ZR;^gu&KGx(MXrXs=^%#g@=@!b_aUh znWV37`zA6lX4-(ytyV?cP3oB}st5*vDei9Cx4$kk_!O1wJ~f)hzQshoK{0GfGH(Ht z)UiJ|#!-!wJ3n>YSX5`K;L(b_2q@yXg!)W;-G0Kn8E%P_rl<9Yqet!-#WB}@=a{Pb zDd)5<+>4uYsyo!p9kvaaFiTD>OD=H|4>znISGe-YdN@QDc%GlF5x60|kh~fjn}Jk# zk*J8|Pyrh-d1URMNN(_N)>g33s>oae zs=jcSNB^iE{#;l>!{VrNmXk~vzO8{Br#B%M3;GO+*Rji~#pax&`N+YYpz>KA8>g?8 z{T`~aPzd3PaP2a;llZI=o-f=?Z^yj)x*&R1ABTr)abo<~3@oUVIS;SdLf7bJK`qc2 z)v0Mxr(AV%bsKq_T~^L`$v|HOydlK?G9psrs8UF5GwE}IpymdPr>7SYwp*y!;*_yb zzyD)lOCqhg?Uctx(LHx~EcKy;h2SbGR1tlA;^LuvLMFMZC_#dsAQrbj?n6U3ZcPBP zMISp-%Wb$7a_e+T-EYGqr|P6G7lSSDx=E6Pp{}gLSf#!l@e%pGv8O^uhrAXJq6=s_+gOt*+ zl)1b%k36vivdpoIxK?A@xB>|z2e8non{OB*u}%m=R~mu+iF?0zMe>eozcTI{qVjlX zuwyY4B{1atS#?T^zqGM5_)T^if7vQgb>Fg@)0lvrODHR?sV)1t1y2+kI}bA{`F2!b znxZSpxVVOzTW`&QW-ZL0l1Zb_y6hbwwGm%r&7$Lf(MnM`6`Y`6>u*it?Ub+h=cIT81)eEE0t(+iU$I6=$BncFh%y5|HP2#cJYDYuE`TG{}C4rU9&$O0bu2)Vp&CdN*apP z+zG`?zV`a%mF!@OU=iNxOELIQPv-Y#I9A^1l| zlWeSWBCoA5mq15MLPbR?asq!IAbKXg0eU2}djk>6K;ub&6~N8A(hkBDjSin19i1g2 z3=eaeaG4>Mvm!PRk14~L^K=?lwcxg*)C{C#6p7IT!o~!9hM$*c-V+C#4|HOhO$x}0 zIZq<52N`}#rMIt@prYnv=Ow3pR!R71-0ei&o;2-4NI>-Nx?H|2Q5UlZ7XKCaIu2x+?!|AD={M5cTn1@#bA~w z9cfbyD&D)8-QF8NKCyQ@&J6dq{|s*Z)o(Qa#<{Dy!Xyyc+cEtY@B@-mb1|uh^_=EU zdCe<_RFh=}0Fqs>KYBkxGcL*UFm;{(VEb0mKIrW1h>1`psrB*+>K#;bvF2rpB>AE# z7K0}y*8lB(bXAiG^=+$zS9RqtfUuIxRPy~nQ3RN{Ix%?lyGCIL?L-H@ zp{{%$at3N7=;Orug{=9djeMO_MqB>E-%l|wi73CqxCFIcTy4%ya7!2VFW&}!>IQnB zO0T_!dV>O*q}ivx$zRT1Nlq@eCV)$)I;CV&%`Pr3Hozr0F$nx+NdOFr(CZ^0+ZF^0 zQ~Un`g;B?fVRGe&o-fOZlpbKrKW-R)l52OU$9Jd;floP4+j&&jcklmria%e8i=eup3HIN{H_9@>#^6XTrR;p`{hI-TsLZ$Y=fy7{eG!kpcC zvSlZ*9*;Otu$JJ*-L5Wl%Cb(jMbXZ9*AgoZlMb4W@1EKOuVQfr?Kr76@+X^nhnjtL z1`&HiO_Gxf01y+o*m7Let?vCGen@1cky8V&h1Zh>7|LvwnGj=lRch7!&aWGxzdXx0 z`DHH`R?9`)B00*9!Ebbx0MrvBf(CofxS^ZkBz)19STOy*x`OeCcQE8mQ1f*D)DrEHa;0iuUgB@zzRyV{lE-$AA;7@rlKYw zF6C&;u#&G8HWL?7S>lnlqd2N~_B#qIv6y$;SYGyfA_DGH>0uyoO{Wk}r$dXxvP641-A?5(nmYDiEQho)kR@YTYO~sLZ0iLPH^w8?HCEKoBN}HY&o%X<3QL+Tq2vo~2L|?;;ZkI1y1+$m)%iTgAfbAl7SFodPF1iI+hptxc4+Q!h3gH>ML4Sw(P|Dc;Kdwrqv=`>!!D|wmqQ}QGe+iMJc6aUT`Qt zE|}M39{&xIQgzCbl-U=0%41Fa;O2L4{O*pAe#C?2Z4Z-|$ogdPM84HJZmPhFbi@>0bfGLrb-n{+6OE&YH|@8Q@in^M443;}TTYHO{wftTzu=V#I5nAGo+EXkJS^$N??h|l zHJi~U$k_h5Bl6igP83g+(dlDMBL?pM*ePJ8!*@Thu5Sf@X3f~`v~M+OG^3ZShEy8a7syfTheh!DRtcEia=PQFtN`J5xBg^27k+2vli+*6I0Rx#m;l6pqZ zcFY+TdTRu>n6`28HKcm>Pma+&?S}iz7^G$!PutJr6)5x7TTYib$5oEHgoh|~gLEP; zV%l})IRjl$(?$0@u8QCB`Tw;QZB87+nWe8(HI8ox0v5=H)pJ+*2Rcy#O_mgSd%fShSKyd*hi$hjAlRQRS*YXfECSS9?uwiPKVCP+j znH3c-gG$|pEQrZk%oc69^TRo>WqN~XfAN^_S14MG;__4mfn_>)mk;uCV_%+@8t8Q8 zaW$=+!r?WyTbTi8_|3~WZ`Z4R3Zmy7HpMlDImh!ES#&o-3BmG5Q&(?Slc>^EY&<+{ zl#S6y`u6$=$gIZ`7xWF6^p=p?__J)V^|3{eOAID3;V#t0-DM;UiVM~u1IQz1H(XdlE(@4fF?VNGU)*!LC zw7glTC3xbw{3onGD4(n%vpy9wvek;4`!2~;UR@Kr@60{>9uV+CWBvoPTj>;~aP-K% zC$m0*4DCZtr@~D|u#V_oz(!4|UPZe7?+eN_L5sq-f%u=(+X&9TaEiL~e!3ppV zr+8~XbPrCw>?@;z&$1RjFXGxM|5u4>eCl6-j_f$k9fE!zEWnTS*j4h}yj(P=-&*cGyR)6_#^YB@FD1D?8Pma{e!MgTRPN_JClHaw(Y)}{tv>=IXtp(-SU+V zyW@^++wLSC+qPY?(XnmY>e%VnHY!%fHoB+I#kuFs+?n~mzGv^Js`j_{e%D&RW$6ZS z`p{SBbrIC)xLvhgNY%c~E_!zda`<-#sA8%X=4knDe+3sX!gE>A3@(ud&4GzGGFw`7 zV$u+CQ0O1tJQ*jQ5mZ{01bFN(CK0F!mi4{CXFP)yl_n5ykjnxAqB{Ik{(k|8n&3`> z_`iTHCA5AIUmuQ>CFV}d!>?lZ& z!kRI&u~2`r4&MD37}=OR+q_-13a2~8CVMEzOOMjt=dW0@dTGxe?-L~6lx zA26FHk=41#+T)SExcthaN&P4|IP+_HG;&WL?;z?GC~3J#*0GUDMmwu!`7CBa<*d?G zk-8GVdh>{Bn7Qa1U|k{O%;}Cr_&|@r{Cx%YN2q9+dnbC*%M|9)&yJoP%>A>2iySsi z!(TF)1F$^@apGqN*{yhI_I$UkNWZFlZ%StDoG>1e$QV#!wWCn zvSD60d8W+4MW#F5H;S{ctz``*BY?EHh&lZBq#lELnGMoW`8od7qd@TkUL#lm>4omg zYL;)=J_8j+oS{W-JEQbih0AEzaBHOE|4#s6(y>^#1BPr&F z7@XiL-4^tKzv67szOBdUV^AKMW=GiJL=rF&Toh^{&EULn}9%!%z zDkoR?$Mz~R4k4#KZ<~HwJz;qrr?s`ZD2eQ_T;CjGX~bbmpL0eWMFcqRFH7yUJYcH# zndiqATr+nM8bn=+ce;Gr=$wF0cyFHbk^1GA0C}P!b{3pS>@6zmPx#==YmdEpnS}TG zIyKN&xtU~VkMH-22ItO`OM%S|U=UhQbq+q2^Qw7)x0D9Xm3%k(P$YY+sZ0}%P_KnK z9RS(nzMvQ1=3P$^Ya(lRg`hMw@UC0!cwggv?^1P6Xrd51J1NL+dH5qx{1I6-Bo9+i zww9q8Aw5nyI4F=_`2A{H=hi9NH$sdV@xAnjaDCtn{RW%%QEy!-;aBk>mC1;Ld!c&L z7Re)QH!vi@B3+M=tLu4;)QT{r??Ixnvr2;sm=CyWd4uz$D@n!gS9S^-D) z!bt&maf+~-;g0~-&xp{|#Oz2EJlFWk99?dVEiBr!DUnGZ+7Q`TVl^* zadRNSXg<8>^2pEVtmcsDqTqTGHXk*iFTjHHr{k!kf9^2q^pPlG0P{a+fug!} zrKOS|w0ipADoL}=k1?syedAqy(8UD*DUC4wUHTVcL{UStJYJTRAV<&7L{#^?6v19$ zLF)m;>2~Afr||ZMWH^9wXfH%FD)2v#-}s{t<`o%t^AE|nLL(zrrOG>8RV7ns#_pS# zk4J;Sm2&G#MBdxL$9jRB9lob-)$4#&H*tggZpiTEdf&QX~^*0HhT2$ip;9pY?pNt;RA0WZ01%ZsNi zCG}nMfw{KoDgtT(stYQ=Xw$f48&wq0Rjf^as~niL0%Ik>m~5g_fxmzR&XM3wXX71XEHSn%HG-ey1L@@ighrMGWsRLoOB0poEyV|z3?k}KDgYDee zlFEipb&$HUQGnl>HTH`ZMM`yINnEIPX2xMG=?MZ;LUc@x2dN6#!SZb1(FK(aJ5CzR zZF`zgD!;&Csl+Jmya>GR=<0C$vZVu5qC`#|CKpFlF_9>$p}5uMvTp^wRt`9YX5q=w z^ha%&)7vJAP+w(q=yQ>(Gw11k06+AF01lxAurT@yhDeH7R#qWl1OZ9&kKW~V*KdBc zlXzc;>W&*qY#XHT)iBWJRh1+3Y8GD$0>xz@rJ59$SB?>FqZxrWFZ%kRSin0eE&q}n zTRogMgfsRU4vA%*Z}w4YTP!24WIL~1Oh_|#y`ydC-J|j#CXk|zl@l#s!A+{wnci5- z7`+rIVGpso%ql$XXpHq^$ z+**eZ{|)w+x#x%#bYG3xbVB8Cm56!(eEmMMXj<_a9wx)Ed>va%f*-eWB9~pO<#(M{ zwc6rD$+S{_^u4ES$T7IEFVw(bLN?nDV^S4#AqbV5T9bE#oUWbcDIifoeHURF&GZ?| z?c(CR6uE|5s+!Qar^)iH+<<9H=#yPDW~=#}-3qmu@(?G3l=7rhP?8pYjZJ$J-X@t` z9J7qJC%i)kxLrF6shjm%%>xHej(^0x1um!`wR+uz4)ZNqADLXVg4d(7*FLI2U|h(u zeWIq-n*jW9lVTa|g@}-_{F^W2Pof*O8-vkDEQqIOLUT!!JJ(|PU?oDbcUNAU%*Aox z`$}l{toX>p)kt%L>JS*6aXR1T5vtYr+ zxg;c()2bIM7L%okQPbP!wC`WDat;I?Wp1-ZTOednsbax(8W$EOR@8N`pf4dtel|%H zv0Whc%c!XyLgj@y?r*tBwXS>as#l)gkmo}yh)!fZ3fQb`zhKz+!}ZPrsnkl=g`rQ= zx+8%*99SHqF1*vwG`$?!w&gV~Hz}+`g?=PN(BXEh_|9N2X(%n&OrH9J5o!-p0;dkJp;@+Fg5Uk^KSScI=X51IP89tESez#;UHGM-}Afj z25nOP@@AIvj8^Mlu+oP3==dsY>TXWEC)}%6Rz4|mk}Nj8m=1xf7pk5@PW#L?KOY$@ zr%g?i33m|ft*>rNthmNwjAR+bI$5vTgNo)wf5`HMpH1)C-|sb z)+5^vx_6-4$TwtC9%2v{&%w3nwzDbF7J3*q;vA;u3gL(KUX|BQD|0Os&Pcs{ZLwBk zJCjZ2j$DvN5Pgc-*S)vXVte-cam7&u-uUnBfZutqo{5FT$rK1GGFqLuaB zj*%cJ+CYb1=}cLG1kJ3Ji>dnk*z{MJtMi%42w9>HGb|6+_Q3f`x>olyg`^$uJ8#zV=zt2e0+VViwnhjHTkw)@ns2~|KDDOJ5B{R z%VNM%RV&rqPYx}h)Vrea>tDdZR#&$DTNc&XkLaa1rh-4O6uIFeXNN|QJ}VUVFn4s2 zTAHfIVBv@cYvfSUrxR&WY+0E}vK%(qy^wKQ5o#WAPSEu+PU^4X_3{4Ng92{04`_$n zfA-s%!-9IwvbDDd&Ul5ls~;TM)$@r`M+zA)qQQm78FW8}hL>qJ@|mQ|^7+S$Y#&jB zy`a4#|6k!Jya{C+_-mZH90|9@1%RZ(Y!nm=!xc4#oNmR_C^Lrsv9?1@;6 zuIxrO2u_E~_I;q$N>8-N(7$>3)!I}3@pZMWO{F6&jip(&r?}yd8_N79L$; zIH>XZ8r1uk6>WTUpE-$nhVT;zx_t_Y2%#*iPgQnW)nR15oQ04nVa8#RWLK$^y%N@m z;fz8?Q!z%HJkGTU=tCtJZ{zA(4c!?1{TADqP-wT7k`lN48ptxFlGJr5<$T=Q%QK z(8n9f3>xCB74fb`Af3UH61B$t-D6=<%%lsAMi)ceoVpTiet8>x-22Fa43%8EiUl}(gYI;1(LPnlox6vW45$X$3RII!;8Au%1j zM>)+c`jzqd?J%{id+w(!t*&s5#kCeBYb@%?-ks5`sSFLG4$GfdR&qteH#>;&$Dz=+ zj*KSXii9qr(_~AetN8?%R8)(;bw|}jy|S`V&JNmZBOln(2{Z+oyd{D%nxF9Rh`)YTb*=oM%|Jp({R?nU zd`9QnqVk+`rxJ9@D>+aY%%ilBUOSd;^E*j)G5+L!&8MD3*R08}{Wf8BS!1&uhq&qg zsQ*Y{nhnn<9Qyk&fV|2X2+YH`;SU-*34sp8ABD8u+@i z3(-q^Gq48z=&^DU6Jw5U0Z9XCYPIK(nyMKoFK=LO51fpeOWYl~k|V%{rPraX8Urxy z5KtGwb4rHIu(pV}ux54*peq0q@!*3@u>|pNHkm>DLOq21aPVPol%3os_0gR4HFfkd z=*1P=EmHMf?u)y3Fzk53k~>CK<_&iIu_&7{EHI;E`r_hS`2wGv{ut+wzY$doAiW5N zuTQ;K9>yg!5y=ca!AEtUT#gycAoG9d5Ba_7dfp=z=*J7OYZOnl-dN2b1H7|52oz}B zO%Ci}=Wl%by%#nUdvXaqU%Mke?pwVAniw9?PnaHgcDK9MJ=G?N$Sl95MO~t8<({X! zU*F9vooif`l$B$B?@>}u5;Q3#e48#y(XGGb3_9`nwJY$ihXyC5Li`GADE&rc1)g&L zZ->my*ZcAzrY-vso9=zZo2%wDGP;gjviBDJRMtuHgP;HI!5ic4M29O<5Nd<33Lg)B zK)MYCW3|t<|5By_wvsN5v<&k!-y%34nOU)zZ~e5jacwM&?4Aw^AF0egug)$u9SoM5 zA5ZF=#PS;1S@YWa_!|QZnzCmBu3R>ou)p(Ibq(m-K4eV;#uQ zz6HZ%+$lt7$rH}zl2_JO^2pFd4c{bLk}_z}mIK`;vdd(9DTz&m<< zcw0M7gf-tnVzDt2G%Cxl$w@$qv$D%=!k_b%lj(!5qxY5c^prG$_~(|z5bR=7>cow0 zp=%9o-m0SN^r!6EmYZ@Y7x++^5fT!a5h|KbC7sO`2U#N5s?Jz}90r7RDlroL9LkG| z-Sr$lQKz;0Uw%W1`q1~HdwPq+_~@3Jb=3od&hcFn@6`Qt_haG|i33FYjn?hKt0%il;{l_ueH(4Q_DeMefvMTf}eP~_C*&o-d@%`cx?nMzOP zG@dQ0_Rc1MLFM+yle!4noMBw*-*T5aY8f8wq~JqtvBT<8;n^(`awHZe1 zEGmARb6FQ1LcxO4@G;sP6&-c&&=xT5aI30a)0a0*=7B0DI1Esp5%Zr@Qsa`7Wshgs z+gY15(cX2C5?i_|y-rYsaW-ff=46%n zhc+?)o+49h=}4V6{YaqN;k#79B1iI7#Lff1_8%0F*k|oby=%+F^pmQXDIbf9bCRjw zvy$`PgFg#Hvl~OwlIS}PNY>F9OwVOQkfzN!g)zR+GpEvv8MmONdio>*@tT-I<{Y#eW9^m}L;=NwG^7&R~9l+o*VeL8T zruPRi%*Xss2kzh|kxo%PEHZh@srEuVdX-TDD$=p|!;e8rCt$%c!K3U1)gpk;Ru~Pb z7ovyJO~y_=iQcTjNga#Y&2+GEj@qg{Fyoz252%pS8WVG*`MW11ql#nfnXdA5m`0gF z45E!{KbHq$8P_BCBMdLguwqz3jYT_Tu>+GKfm18nIS9MTuE}doEtFCD(X+lbtOkvz zgM%+XVM9qZA6f%!2Sgm9I(J_CkQW<8%)$&GNN17aGd9n%Hg#)4?JN&}E8{AdA-=)q zNBDtZ&J{go@Oepm__9#I4(3+y7yh5avXX?RSSU2h_3fxJ@Ix$SAb^;d_!Hzhjc(A4;|mTx|THgkid=`|Y8`1f(9a z?{;!}7Sh6W6a)5np2=(0&gNQPvf!jn5C^+1-|P!%)AV6}YL|j^$}$2le-_cdfV9Em zT9e}tFrTaU@}W$vnXzR|N#d70f=TlyiBx6}YkBp@7wg;_Moqh^_PjDjlz$BygmAF3 zoc~-$rII!Ipy&A)P$8o97f?Vj^k<{>N0nNY@45caRT@9vQ{+`QR_l>#?ljGdkBorZW7F*z3HWOXV2zok)D0CLO1^ znj;hx#GVAsn1q(RAVKEyzksh{=zV16E=ZY_(iLz8{qG` zuU;0ZSZVLN<4a-h^$KQEaU#T}OxRasxo28wHPu-uv1Kk&DU@+)-{6g6647B48X;LD z0Qld7dZP|pZofpd?2M?>*CK|`mEL#YXS;1Gpa&^?b6HgpoU)OxUoauK7gyc>aYoGq zN=Ar_C-@tYHYiOq=!jpmrzaJgpuddB=D!Z4he8IhFPVd!K3FPhiw9UbHgd#xLW?lV z%8&~qE_n5ip1x}p#%vJL;TcVSf_L?r>^sHBUHL_Qs?SK~?C;yTpZ_Yp%q1{Uv%u}F z9Z@qFC)q;rVngW{CfMC9m`_BqSzARtLXiv6x4)gV^aI zxfHP*>i$9XW@%n>%!)FmLHvq~H7ku_y>{|_Qrus1umq?=2ekew z{S?wGL28$zye}b&h#TvWa!2-3nkm488mlZ3J zi;9LVL-JTmdCs5HEvW&GI}54IBWbZ)xReI{wusmrfbtyHk0oRzJtNEh=~nv-iTzIF zsb*kj1s)~zJ)vatm4y7I*d9e$l6kcYZY8hvhH?HTz6Q687|R!7LX$KnTJl2L@gZFL zwp$qbfT?yOo*f2;y@|cO_+}QnsdD&Cb&@U3jBv*d6-L`mzb~xfQZn*iW!z>c@m=Il zHDL`|MABVr4cF}mk>g}iu5IbCM(STRbr@7tQ91S!;&9U`6D|?Ic6Tq3STZ`C!1~`4 z4-{vjD$ys1Kt>?4a&sx+Bi0Jl@qg|?a%+yb&Rz>~;>>k2>x*D*;?wl*-bjX-ecx_-bIc9rtb8nV*q-O;svpfUw{uc2q@q<@>AYwSNr=ItCyI35omq_K0_Vnf8o z4L?yg-ACSwB1^sarS=&rLp6*wb8R1LR<{ZH<*tQ3G|EQPjJQj}73R&t!_pN@s{95R z`w0(u#W=)4>op7;14S7beaYqDm^U_(dvN@(YAnapL*H^ojl;2v5}Brg`FP_HAa6o! ze)QoxxSNJE?D1C{={J9WXyIo_`eC8)7x1Y>pERE=;i3+JiaK}-006?npC0WE0f>X5 zHa`U+x%RkX{!}TfvR4^g6y1o({R#M>TL!Aj-5FtFYenFK)eg7{7PGq5lL{a0h;p$p z6K0^xw8%vA(AR1uhz-u0N7og0<2G?-$J4Se;EDr1nq7pl(3g?f2N&n#-+kVT&5Jb! zwiF**wMF)U1~WPemA_n`0C08f{`r(>ga?P8{L|$+%ig>E@giPYPeH!#YLB6D!LtUH zOj=bUW4{evuUdYEYqmVsjRiXv(i$v(ktqv453M9^zOn|73eZMS?WPkW=orP&crdAx zJ^eXBe$yS#6X|t6hDTmcU!)rr!WX$w5rR=HJarTCc)I>8FbOk1@5>-Ak+2H=I0Ez|Q!lEjB z2$>){h#(T*H>r|51m2)12zo`DV19*;kWm<>k`mzg69+j6@4=A;KsiD=YcB>a6kn5w zn4T+hk%Uz>{v5~P4LlEF1_xWuaY^sa{v1nF@@Te1LL43>9>XOd;9q3b!jQ(IgQ`P$ z0MdDecgS2u;_VX+RMv}HWVBOh4lmly>J*Ua%R$3%L>psl7emFZDkKLoW8OeA2Q4?1 zKB92-$hDzzV%`Y;?A<|j*VWa|?tx-@;>USE^e{DSEvQ<=?!=Ad{I!hAG;N=|iIUzPGhR~r>f5+moDat)10(c2 zX0CSoCpbcN)1kGP{kV#N^>Ui^W0U$FgR1Qr0@x@mY_fpay?NpGHmZVrKzB8pG=t-*VZQ$+Ud-l4ZY}IR@Cs_2w*ukfB$awDCamxovH zkcXwUU9d?tPp@)~4cWky2Q-{2UDUirU_o_^fK?j4b>$C?s%XcH?u?BCN{iUh;b=#g z{=Lx1D4qipmp&0%)p*@XT;lEclQYG5n1qpl-M;|F61!jQo>(earG<4v71dFMNB)aj zIP=TjhIuSVH@P@!yxJDo8`7qg#!x)_Va^+PWu$i-sOH33URee$*c#G{T?~|MJ|=$#7V1iVyOL9sz>Uh3 zzuMC)Uu&OGMjFh)O#e>lHQGvL2OoC&SWtUN%ISIhADQe&2te9v@4Hg(#{=tF+l<&U07dhTsCu>p15Le zI7Y&%v($y%#{FXkMe zk_PfRBm11SHPB18tL?P(ob3!X<@9jVr=QR}>9qIlJ#^?xC>v6iD2SIgI<*SdYUTiI zprnN2NU74SqeIdm8lfEs64C?rCAV$4Fy-+T$<5m&ce_|^*IS*;amNA zumlDojZRu6HnODck%4ZiKv7t-6<2E06-V+#g)+={y2V^lOR*h?IBiYc(tqeg~$WE;p-RGt&q0YCF7iCf+1B7=zO`B6I77H-ayIMgIgF z=wfDavTOTBkzEVFn`B#q1qtMvn6t<7hPj`;`--^C9CfG@)reE@8?e50<*pH;=$Eyc zV6(OSadI^!;5UZ2lx7wg&4_l3tnUp5 zQdJTM+vAOFyqb&Z@hJJH?AdnmO?CSmOf{|Eh2waKkJn2_uDde~b&K7A-7oJxq*o9I z#>K17ZE7lEij@^X8))Gn1}VE3ljtGDwu%5`o67Lk|H1t7A8J)IGCom(XT|n?>Ys31 zIZ=ae|DL}6$IheX7bM8V812{b!RMQH{!034I``jpJxr=UQ5W(+d~V5ZJ?-t`{r7@q znj2LxaYgY*{<^G&Lh|ebQVp6*c}2Va0s<5KSd-(I|# z<-6?XjI(1>trEQ-L3{eC1Z*VfydvgdO|Rddv?|;qHU1nBJ*o;mHCOS8H{P~BrSo(-^mQ`&z>oqiIIJ-jGRi9#Y;#{Bt38jKC;C0o;?RE(5#MxakA zscoDgn%}CfmkzgP9wUNpX2*=p^~zeV@jhl2^pkoI%Uh7q>G+lsf{|ULstA4~$AYEK zw;Lz?K$Vf8m~`Y0Qv@e{#w+bnkn>{0^I;W3Q037*qguh8zmAs+N5sz^<&k)>hUt+O zPl7h5dSNbR_ zB9Tm`E8tIsiF!G{aDOOHf=NxAnJmyL#FwVZXOL4vTiHpgr)lUX0g?~5zKf;8HUrKn zmz$@(mC%RQYF&|-2a}ykz9FyjMM|!^8Zg5?hkfEHa-#lrbJJFPcJnc3z$qy)=R7D% z80pySaG?2xXIV`Q!6Yt?LUt-)3f7-0-}M=*8xezT*Cc!ExCw3W!9#rt{U&2Stj11x zcawR&<07)L*r{ajA?a<{M($Pn2ad&h>Shm%mw|>!`q8so!+eqL8s|pP!TP7EzV&hp zR6PK9rKt0wF-&Xh$ZRa6iab@jt5)8p6U0aK zdPVlE$zknH=#`$>@$`C&Lb81fCxdv!M(y6q(UqM0%hav14~EtgzFb`4b-`~|!SN3A z5^yM6O}oE9NIRsE*i3O`ACMI?8d3@ve7VDG{hL(P?#qhrxE`ZN0*XiIF0GYf z1;DEHgP^>u;f(LNpJ-Q-G80-fdD|=)Y+7J8ZSZWdeQ-@r7O0}N>W{|mQWonwo3_uA!k}Q3K>3r$P;0p^8U#N_a86(9CUg&0M~8(kT-}7ub~;* z4nIgkwq>&XRd2X^DLau?N||53@14L!2U2u=T#$Uyu-jyu%1Q;A$sumHJziv_m`YcL z4JwI5O6E|&)z!`X3MY%oDX(cLX|96W`%LY*&nrxiTv}G))XXl_EX9&C@N=2eu5Yea zz$3l)TbnE~q`Ir}7-kO4N{@!8m!=P@!cQ+I8=Z)&2aE$Zg+k>0m;@#~8NxN*Mn^%9 zZ4GwBEGwa=h2kU76{^YvOA^`=9VKK8;M=)W=R_{u*kWOAVFmTZTohhCWe4_Q-!| zL}ZY5#F2D6nj;i# z+uFouny;xQ36mNv6np~Zk0bS{)t*7>~FvLq9A;lXJ$T8!Jp!7{tW_! z$DLd@W+c9$HnOQc;U_4pd(M&IPuEp=wXm}un!stG2^K8Qw$zx|%B7oJR+B_t0(z2c z39*+Q#a#192IK|PC$~`Pqt@xLcmdM7pvuV14kDy!iZs7S(`?NrQRmL>Pr6RU@u~ho zNBoC5#6N4CIjnP3B7~vgm#Y+!ghAz;kGux9d{}*MHQ&b`B4rokaBMLEdbL*j9XUl& z`#q?}`2A8=d%`{ajy@uQDpzwt$i4U=dh%5%BRg6CEQadO0u#NKu2I@I8JxKs2@#Dc z4gEGKrdb9gA|2LZZ_`@ritUAwKz+B`eN092OxnPpQHrnBLho1VpxYy~CWdBP%vB`2 zfo-kSLS7TrQx~J6__At4w^U7c`jlD(eB9w1cRNAaYb(Z5LS8pH^Jvr+bUs&j_l^PcLkkp#pk}N2>^vFQ8?s zTsD%5&_W~jme7_Gq1ZPYwXK*wdQ2zc!<%D^CaBA7gf-z-2Kc2mSECI2SXK->^v@Cl0%}QFHte70nUh61I6VB}!ZZxaeSd+&0^iIP;OuWWG6hYS zcEQ-)7Oi)xXKB6pDPt`i&+JHE&G6)bim1um_CZL$?~MMj1Met^s74u+tQjJ3&UwyApgByf%y{v2bR`JWyPn&FFIGaCgI#z)SY^pO`C;*$(?NZq=}J$^iKb9TaJF;>`qc}Z*0RQ zv`C{5rH^)PVr9u4Cs+Rfp8hK2=WQu$-Y5b)^4onN*18VUBsL?2nieIS;<%d>8l+56 zY$3iB!GzwZYbDHsu2r!c%EaR}IIJKr;PBx82=~MABM{@x#|`aK9n~?hp3W~v;%OZ8 z$BGB*AX%_I=@LW#+a7!o7e8HdK$&>^<%)BrlUz?q#u_Fri-zUcOjp}Q8zr+`RtKI3 zsZIs?MPNm|hC_lh#YVs4+0V+H5D@!}H|-jSy!JXF9w$a@4_>a@09~PTv_fgIiGfER znXLhSOuYk_)vod9Igr$FU9~rn84#Jxq6EF#$XUdH5&u@g1!4#8xD_KhndeJMpG~O~ z#&;%r=Vtoi|32ZK-(6Z8o2h_HBuxggRDXWhh zDoy^{PJbvIBp{u&yko_GNA$2wnQ|PwSQwpbE&RZwSYa)-GAqqx@ibA4t4V7O_QPJ* z7wgVmM@7yU7~K$sTT2H%)hGHSMq@Ktp!v5as|KokGDj-HM!-25<32B9FgRckyiw@v z?W&e|D-t}(yADy|SLB}8!F``^9w|E}VBgl9HrC#6uElH>>x;kmJevHD=hc{k{gdG9 z5ZAEUDG;idM;4kS$Qcl(c#dISAA2pn2TGpIgtHqbW|~7GtOKa7~_5=64+921^nm2c4uZ zD5lB~YS>b%Cn2-Mf#!#5{q(Zm;rs(+4N*@a3h6<{-Dt4_F|n3Ih!|!@QVrx%EGmp9 zLr4^W(<2_^Ihrtg5}8XSj8tw*Q?Lmh-{QT~&BUg`d?c;imS&*K8_CUg)uX~Edf1mb zjmm9q{R>9r8JaVC$Po`0qQ6@$^*K1X=CYPL!K`afx`(#gRw8b^Aw@1e?W0%5pNS0F zD^Re7(a@q5yxTU-ry>{GKel5=SlYZ&=XMjgH|SX3P`*X&Il^W}&k$pD%P7-sPu;>} zN26{_Ifd^wRjk-_v{w4S$`)sC`O`Hm#}3^M!QR$PRE78 zTr9w=v`V;GNP&%w{G9T-&Ae?c;uzH^CYrm(z($#y{-C36j~Vrz6WsNk^Q}^Eb$)5u z%xC~oM$$&1A}Yl88{~O!pW96njoXi~on~xbSyc=*af?MxC2I|ql1wO;8^2#r+@SJU zGW4k|{_^oQ5l1WQqMX`PPAePyg{xkCy)tq(KiH0=9Y#h5C{LD77`HD{)i%Y z_oZvNAw<1u36msiSKb{c*`w;wOzs|Y@tPBCWQN()3BL_fv?WkGIG5ScYJISac)ekg zVD(3Yt`8)X*QhDoW%}Rgpl{Miw5Aq z8+W3Q>%dKLc&boN=yBp{>02Lg*hfl1l~RhBrxyeiWSYPXg{;@QYWI5Lq_OVdl(z7` zi`8>l?rp}bGT^#mIYLkGJ9%uUN$6F=Afd}rVu#m*?~k%97f}611cUton0urG-Y+)J zUpn&X$rHEveN$pBEfjAU6`@4z!t7c=_L!Slo}5*F)@DP|2_k0AO!%Yd0H)Hn~ zEt}7R8COQRyQ|soW&iN>aUsLmHYY2h8PP&B-$&TZF-(#YlP&V5+3*qfy48fR(zfF2 z4#=*!HLHl-r#Z)}|B-?ZhiciK;@1@JzN+g|?u4r5SoKT8((%NL$)d)GC5nlMG;iBL zHM|zG0$Ow!uc+h9JPv%$7EH419Lq`_t2~`eikIiT^w*RY){7bq3lkS^h*{!Bb4n4F z6)?M~l^JMs19cK^9&j2Jx&oCV)-??(r5!-m><{#v1vc&BhtM_e)p$uc94`u7+;H3L zZDU6hFkQLt7Bdg0W+PK6>c2-3rt0I6$pb^r4w%FX+;1VKX4BpN0_b!YlN#};$B-%~ zX}gm^;jxmYc7HslqyGZxPv|5}X>0UfD+4CaxL^l4yw0jOUxs4x;BM8;-Wjq`=AhAC z1ze;!jMplyD9uzA`Ra~|VM#^N?Cv&u1;UrQGwtu}4T*l+!YC+puC;hqmup@${#YNpW zDMuCNjN~{EZ*WurM4|JRFI2}6QrrZ9jPWin8CE#`F{!^bzEQcL^mPa|9E^ z+YIzGx&qO~rdfPG{bMw4VUPx%OqfDJaeX0O{(p_f#p(`d#wnQXMRkSHCzno%G>tB9 z!F|c?PWVWQ%t&t`sP_LJZZi10@?XR87>E2yL&@%(KoZc668bt^%2$7Y>+^A>z<(L7 z|BVud_zz0lyU1#uxvsrx*)yt!ssSR~z+>d|jcLzTf&Cqtpz~_h)@hZOH}He?=jk8B z6KEeo*!0V@nbgPn`{Nea!H)g`txwy7PpNYAE-mFGP3;vri6-cIlnQG+J+kg%qvqGn zKd%=g?ieo3ZK`G~h#a}3obGL0g4^vC_gzg$n#1oV`k%Y?o_y3s{O`L`{cppNCJ9R3 z)L%me+q_vu^|{nVyDV-AX6H}FwagDkTU8O;<{!M>CAnfq#iPV5mu1)UBjL;A#G%lf zfhCxZ``(G&bkexKB8nSy1%$Mr1wuh|p3vz-MhqX~k6Uv<-I3xmcFKMXww*XgJeECZ{Bb_uU&4!6Zap=Xv ziZVTXEo@$RN<&I5wd(KH1y0k}UFZ>A$rGtlRlLmyn-`ar@6lP&I+|$+iV`NJEjRpL z_9ryy3^SP*xDNZUAkUx7TN%pWy2U#Pk*!$c z64SEV8vi4Wz$|OUd(V)<7{u6_hujF1ytI{FkEgrb@Ebun`?Oh5h4T zH%?4TL0u~UNE;rU5hB$pu5s|l@?lms`|%yDPFhY_wbk-+Fk+9FDTAuaM$UrI_KMvm z3zGWZ>hxJZ+Pvjr%ak~fP zX2!OfI2md4%#S{*#T`{LQW84!_@!g8NU`qllo9gf5tBwZ$b`}k$WmIZR=Jb2;Q3N9 z0m9abcv>A$Xz>?i?^CYO@N#IGt9>}@bXjdTn7Xl8l6LajK{HeQmugoLkctc5si8Ua z)Ynp!N07{|f`HLjexO%RkvA%0-(F`)Q_>Xs>w4?Og)J)jEJeHfMm)JNR^(`5gwc_{ zL<+enmSvy&SbWVRbZj7{DrC9}aU8Xjje}Z$yZD#Av%H&HoVxq&%=*|Ij-nD-+k*k) zohc<_Nt*%$kLmAn=PCWVMoAYGw&(4}qmvb+<$)Db?Y0pwPF3IWK&)<_9V?YjS zzntYjvG$W?o|~&tUt9V#_qQptZfHcMVl*?W(wb^tMZZz$AAXJU&2 zQxr*J{S=ueMj}*@il+1|0)EaB?Y=y07~B6|W~@;dfb7S(eiqyM^lQ{;mGJN%1MHgr zy3GGe2>Xu-w6;y`*C8Zq-b@+4MlV?(?cgCua7WnhwSR^&Xn)RH939TZtr(QqH+TLw;3p1%}apaqUcR76*D#v|2?f3S&^&I#W2?zp_shut@{exe^m2 ze!}ckTBonSk|Y;0U4yg$%-T+A+tgLD!azN3$+7Ex(cXKyVycd*@L?CfYuKZ#9Sm>Y z`=iXb9+QxTWRogYQX$}6Jxo#+Mz*aXm!H2W$nuqDQhZ8Pqr4aukt+#mDI*rHl0!xw zDrCxa0|eZ*6WZ`R)BfN*X&Aks-i?i!HqlHojPyfKeavC0y z3*%@ey<7}vpEqG#>WsfqDPwkyF+h(@4&}3us#;d@k1NU^T=b0fuzC=a7d5M~TL%Hx ze2FzZ&$c$XPCAN0M-YJ%uBm_JDm3 zy_`G~KHA;Mr=`0{GKTW^G7qi>-8Ig^k`XE^i2(^vBzd-By-;}Jq_nE1$|@aj$3;;j zbbiv<#72(YXnG#>ryYqMC#^vacksm46s&uIeue^otEX*#})zNp<}N6qn;x(n|f~vce47d-9u|6Vp|Z z_fi;qu|NVnJ*>a}5#LG4=_1Q6gK(&ejU==D>|jJR%chUBS5fH#>ncl|j^tMdK&q@y z)xsmoWH99ISehU+N&k$$()=2D&Gl@N@ z%uF#eV;nQvGGoka$IQ$SJ7#8v#4U&$=r7rdV z-SeMwiCD6*MV{4OW}ZSQw!ecJsF%szkKdq4wQ!kG3Tk$7NSZgva z_@S-k3sr2bpZ)15O_u9aBNXR$zX5bK`&(z+)p4+u%QjB6HH4Rx<;=HUM6(~3oY@^V z7Tu{`Fu*vh&4ICBb4xK#ag!yF#YJstlhcMMZTh$vAU2-y8$O|!o~`8Xhw=pYZ8TQg zYP6nN-XvrgaGOa;Sc82?1MgahM1vEQt}TN@uEPqdOWQBdZ0mX1?O2Or!z*MINb{yA zkCL*ytmj2uH^M3zPC{Oc+9^rOL_UQF>YjV8U6sa{e+KU<3im1&p_#ho=F*|V!(rJA zdJZS3c}e&2BDVCn{nebTRF6QRE~MX$z#ERWTWCO?e~}w8K?3aYxs()5F3Dn?hUe$o zMT;PfQSP4>WMh+s{3loxV{y_f{(8M}aPrWO`{tSfXmt7c4Y|-IAbB!B-HoC zJhr|nYxS#S{?A09U~=yxxh2gkeXfjNKNp)nRJmwDVT{B$VutYEv{yt%qlJOoVZ#OU zPB;1@j$Av-AMEw?!@aZ)?w^Kh3F~vWtadBFU7bVGyTQ~=;ntW7K&;1$;A(mUJ5{#5 z_G#mn8fDYHMW20wLQ&@FNrqWx?Z*>$oa9|eid_$HEX9~RN- z&qA@;$`_gfsHMKi&T9{TvGexT`SQmO&8$Cv8YmZ^L+#FUmVO|=^Ovkvdy%NV(*4Ii z4R0~Huq4IPTeSpgze0K4%85f4z`B!ngS-cVbDDkd_;-nr_qf&aH=el$!+XJ!N0p}2 zcaq{QBO!|5p3qYcuJe!u^PS1;GPv9a#oFvHjpKKTSNLZ_W+Wly+%6N&G9eU~e|@i{ zix8=|yCM<~fKDh~%1?MGI)>{E=7o0)5=0G>ZM6fdzmL;dv1veL8_ z@MoWO#}yr^k7qucPOz7dn<68q28~IsC@5nv(*DY0#gqAsB@QAbSZFXNeCHM6e@2Du z>@$fG@E-cw)Wi;_eVSo9qlh8TZzZOf{^ntC{c{hADDy_b=-R`jB6~IH+L-Sa^8Sj; zm4vudVux;1KQJF74Sv>+l+T9KCPuxTPqrD&6Z=G(12uXagZ&`inTVpdDz8+Yuy^=` zC9J0=B)I`T!|Aci8Kx@RWdYvP!E64Zpv(t?$NLnre^@JGp!F*cOTaIksfyw<1YQ|| zT1PIC%$5_q02!w)cGH%4|C&`1X6n5bE<%r++M0-ORIw@+LekTtxhkn8Gsh#{=M>7FA6g7Pv76M!P0szD zO}xfsTH+$!<=C&nX3iqbbi=(J@7i z%-##4Rng2m2}L{~7SROA1k>nC3$wv*w2{e8m(ptr@;qfSdsz);=t5Fi1ucv(L?@~! zed%TlYhE0V8T8d(W8thkQexB51q!~&N6O*mt z8<%-Gt(n$4g!y3ii7QJ-Xj#Wu;G+hDX6L>QdWL;BG5q7gVKAqv11;~7uv$QvwR_ZT zkezkAD?r{#Cj46o(jP(?EM@#h;raU?FN6*?^?D%ly4;r<82X5UNl)l;7aXnD_6V^N z>Rg#tIBAm}@qQUQ6+pNg*)lmKP@=fd2q>^Vj9SiOlNA=LWV^~7WD&t4F7zb(7w~pK z_7~7UgVokQsczRFv!BTN)q&LHz+{d`9G%-gY2OX(ARtyO?2bTQn#p?jwF8BQHES?3 z789?Rnk|Y60~2qMsDF?(WS3%*oG(@nU84$B+J^$7!d7tnRNBXH4MuX^U37)Wr+8N2 zgP+oZdf6!gh7~^2BF=@y; zulA`)LK5%EPyt|;X$gR^lP$DhBT8;U4QN2^X)_eT@ z%{=4mx2$s|9=WF1{j<7w1gi|8%0PIe8t%&bdc@x{@Ys|?xjH6#ShO>1M&GmpOA(SD zbL9evRYbG^K-f!bXZ5ytebr`KpCVukY*g@sP_lW*0K0;1e?teT7W0aSV1)VOLD}|s zt>%fenS9Q3AnQwB-7!bJ*TrC&Zb#uCf^+du+hArAw}4|mvbNXdNgmAmeHVzUj(wNl z(qgK$cwWgl!jniSA=wa?(r|}3G?AsP`ErohWUM#L;g-fHj!4dRm-VtjUQ_{Yffr3!-_Yxd3eMUK&~COLRk?#-o{;@xvWF#>xQeWKCbS2W|f(r zwhCeC4M3_PUzJGNyo6cY>(6|!BdJ+TY2vP2nQXu})aIIKDCRrkH$nUhAeQ0KddS&% z9ryI!aJboCQIl#*c^nVq{JDO_d8AgN%IX?!?Qw99k;-`Rg485>)ESAI7m*#~+rTY8 zyhAAGVc>RG`S{;jxE!A2Za+S7_GdqM(nb| zQJd;dpcBxL)HWnR+%7RM`Ad*aJ0-X2aPMHJhPVfGM2l5M5xrYjI6#ibP+4ntH0(zT zTj&~yk02HXZmSRrPbYUqB|fRpsbBj7jK!zKePDCfA} z0%oXQElbxN8OM!XX$?Oiz$?F}Mvw1{3@mFxgdLLBJ_7HU3u=yHvxT<3ylTN6>>NaG zM0Qn)H%S-@AiLx6C%A+k1RN42$@v~>N5V(KYo*EZxsN^}%nxeE-?X_K+FR`W{Y@nCqlY(tNa`hisc3 zhI=_&k>{hsvIvb94~=Ehs)P6Tnih1S-HvLJF3Y*w5=uH}vl}y^?XwV4sJFT5&|9uU{!~8*$oVE?K7+6JYa7dMcnH zWU;DlMcsJ(BRoJha&S2zn@cy>xSRk;=@u@>p7l@L&dd=u(S}T=)|DHs9@_yEGRBL` zmFo$y(YlRoWl@i#T#!$E?voimqgw$^CZB#MdA0z&$^`VCZvF6l2#x+kTLyRLnYdy* z?kq7Fq{=5)a}p4V=re}tSblPiq{L)Tg%-=Bzo%+s_x*&Gl`YEmfNnEg1SjQdssGYn zmwigVKX`H?sf3C5H7m)EC$M?GD-&2oAJ3c)J9UY7zfIJ9Wp-#0o<*(TR{&>M%V2p1 z1>l@5EUM$oTGgv!8C*`-3vZfjHz6kw7Wf6vC%D=gbJG8X%RXZ$y)_jgGeD}=|2qh7 z9lBSEya?fcB34E5QCXc^DS4gQ+s3yswNGW1VBxo;{frvh#+SelE0A+ITs87IK#)E~ zg54q;dcu0gp~l+ZS?ZMZ=cg-d%J?DLISMiV1HZsUR95fZ0o8Nr)`o05Rt^)1BKA|H zs8mst)D|@_N5wQGg31f3lp`p(+AXhst4Gf`h6BvS?KIs)j&)3Vw3@T+>7wYl?%83Q zlIYMhn>&c@#!lHGmhrJPr?`uR+DhS0<)agX+1*wu;%c%+RvQTcp3k>7jws4>fktTO z<$(3PykqlE}i2n#Q*#}qLsi)+lxBneWw(UT7jKxb< z!o)51_U3m1E=^{Hkr=H*gFlYd_%3GzE-ga}*@d-KqY+mVfkUqTMU}zT>wi%${>O%h z7O5(TSOBcE145-kAy}bS+$iHxLp9rrYyU&(2>d(!pDbFYS;KIjMJpt%-Y%BZISne! z>%D70T*c+zxm5YqaX@F_VAGE+ z&Bw78O#t*rlT>F{99*#~PZSLEyY3(aacO<@3mHxNe2290=KS&TY^}}qS-zg^E*~nD zl|9yVPsBod;rF2@Vv7EyLj9@5Nw$HT=G}*;t8?d^m8sp5$jkAJF*Y6y98gh+jEf`Qh$#ChoXe=1i)vP zfT{8a$KzM)+B2F^md_K81UM206@p|Db#OT(ycVq1=bJ&FnRWEq%BxHjwlv ziZ}e?(1IGhrl(NVxcp}|tyiL!VDk!uzjkF$$s}gZ79erz4n@3?kU(XJGC2c1!~QcJ zK`C*f&uok8N1)oPXl8?9$9-gF$ul@JX-oM9>LX{>`%hOxPL3S`=QG0_an&joke>o< zIV_nOZa?o6dUjFN)hEEe_Go>p@khX*p7xUbo=k{hqQB`>Q0(DxZfhqe$M*H>zlLHu z;^x9X6WdXBDc_P*HRk*UAl={DuT+f~Y(Mx-XNGlrQXIZ>WFooxMfUP)c`kI269_&m z$)Bogt1b(r3lHB<8e%=G8he@kHv{pet1p;ydJ{goh<-Bj-JcVN4`$`BN;>%06z5Z% zW>L{hSLBAaXf0k%-`)b#M7u<#rmY23nt_nmRvVXL{`hX9xK#L8R8%qs*-OULMqcq2-4??hri5rnl%ze=XC{q zvl{q^Hug*rx2hasIsrOP5~A!z`T3ZeC$P6QU(lQq9lo9G7LT~hISs5HBMj5V#q!8O zPt{(U_c{w8I?CbXHejJR+WjV6n#*SbN8>R#dCve(Kzq`TK`Y3`@fm&&_+O>K~iF(CWKWW z4z8#$^?gyHMqfuf`Fim3+fi}tGkG_87zh+GsU{D5Lf?8uSdt$>m#wCz)K?>wVFE>X z#QF&Cx|+c)W$jJfODXA0G$*oV)3B4&&@JOuBCZ%puN~ss56WF6b%}iXR3t#PkM$5$ zb*@3VSB+oOKFgO#a3Wk<3ly~LDg-eXI2&89PSYsz0dCsJmSrioKtJ%PxDLLvEEn(8 z>QR5x7qQ6+%8(!51J(YEgUxZ|N#ehsUW6WawS+6xJ|V1z^Ip%m3;7LB5U^ff=t{pv&P>lv#(zmg2j@E&~>=z32*_h3jl zj=Kt;ajLO?jTrEYEIPs37muKos$X6Q6$pIV&tyP43zcXIq@3{Jim6d3` zog><*E!S-`-@sK}@*>q7RTy=zL|}4#O;6N7Svr13mj)tz`{XRXX())YKrHQ^5OjM6kdISV^BZ;>^#-94I8(buxI*%I- zzP^us50#yE3BLom%(D$1?qHXkeyU5p$0O;Y{1BTuDJYG<&(#`T078RkQIJRDLw{hS zySj9%JAOoNgNgsL;u$97Gt|_`9*7RCcE|b6hjI_(5Q7Lz^2yfsQv%T2DS7!Z%wqgGQ7OBKFNge;+$P^>2N*+`-J_nAn!cJ#+K49`} zAf$0GIAd7ugckU!+5l8Y0;;zXyv;T?-7tCo1q@gyV_!g}sS5TIsRFH#q6eUt{{qMi zQb_VcecR#NFC!&8JJW^xI{lC*Izz5P9bOFDFPSecnG-=L$;Zzvo)b;1Z`)HsKj9Bp z_>A%SMq_QBF(cGwuG*6}uDsPfNjL4@V*H}LzFI84bIp~2`;(E1mMstR=y%dH$Ef#4 z2nBP>-1q%DwroU4T&yn^t!JtfDv%efPi)Tx*lF}M5Hrc?Ut4Y_*@uvrrB3j@MTtKq zZ_(YEw(vifUc{2YqvD5{sY*u9=e`81MBoI`{H4$fgC z(L$t)clz(Jk{-S~O32Dp_l~0&w|NKHC??M|Dxg?0I_o-qz8uVACmi6^>1FdVz$wj7 zj#rZf2C_@h<;TIn$}*;v3wKmFxI~4?9734`wzbKJt({(@yKaej3=me$GY8XpE;X}V zQjAkMRN5Sa<5B&}N2#25k~XS1EIjiQ=&eaNAe>Z^)FA=1mey^I&VD3WH|Nous(lJf zsnzgoUa3t4nNBYj$J>?8q>kNv8$1!Y(Z~thdz)}jv=*o?^&K%hPF0LMT9y0*+N|dW zcxD8M3fMR|b)A*ktk1#&vf?_+S-XcFR~sqWD~^m~^~4Fu%;T9p%XsE*bi)uyOU(U0>F!F{Nd_J<9f~ zaD7Nf>YPxqI(7IIck$V53AD~1({Q=H>D%sgHKK+S?h*HW!b~WsK4b0HV~wV7h}hDa z{=0nr8jpplF6BmlaGhh5Irf%vEMHJt2~2vu9;*_PD1Evr5AT|BcATfRb;4NikRmlv zx>3}y<>n280Ujx?7^{uf{YLBR@$ydT1&W1pDE9@QG56)fUM!l=ctv-KN(H4OvB-9XchUE|==<`MPub=?UW{#ilOZRwDdztQ~EFZ%Z48V;;s2`qa%1=q-&ez zzQu=$5&4sYR{UeI-7;r)1Pu~-@IB1*R0Ae1@ zkReBN9v zJ)QQxowJ)745(_+OQbkc;oSL?r^|JjD36R51wxx5VV`U)7)>%M%SSn>cbT#E z{${BuX@^Fd&dx^<>DRq34seQkTG4B$$k?GFn)K#yWyV-pL)*Nw$N; zsAXwJDW0v$jwj2dw$2@MknJL)H77&4pm!ntpb%Glk}#cPRE#kh%R{5*)0Fa^HP|PWRq5l@zE$bAN%q;Mle*Mwo&{bW z#_Y*0FcUj^pg{a0q)z@o^W?F&ex<$(D_QGj`Q}C^F0rc`kxsuE$mTU`1b{x<{E}ZShBaMt=c_owG#-X=3?5N)y$Dir=K)#Y@^(YpTXM z{CNB>qz_y>qqka#7h5ua`1>Usn&lbIEKry5dU9FTiL2M&kkcirH9^8JAbJjw0lEod z$yz(n(%Y;C#CkGf;;Y{r?H>A3GNC9$1cc)X{PdBH92_Z8#RYdXUr5BY3azA0dIf6q z)>s@SCW>X<&VD#&=R2>PBj)H@F7o0i?MEte;@f@zkMS9xe@P|SVe!ap3%6;A^iaR# z@C?@^Pz!EouM*kIJZjE`q^3M@$D-GUmoj}e$WWDG7WJmuA?&de7{SLxkkjL)ze#NS zey+O{-WKlx0DZl5#u8?Za>2UOQzsx&If*tM zL~T{lB4GLQZi$m6@rQqtkhgxn5md?eYIjh4UuA7Kf+#^iIJ^?8s=p_y)$0Vo@p9Kf zkj!Zs&WcZF2kGaR7qW&IIsZiwvTYB^683&!Z9-n#9Z4WPxPvFTM(2A;+R&}d;D)V3 z%7*B!`iobjxeWR+xdzSm@6KL()Jp4sh<;UZ5dFf=TyYtcwDwFNZ`i23U1%c?KeY(_ zVxz7oW)pi+tK-6y<$!x5)!3hUBCLct+H~I~8VP@JZ#^jt21CV-{~knvfaCG%QBSk} z#$-j+3PbJWFB7gtfykz9EMt2Cm$v&@>do_HHLg(kZUpgTPX$s^Y9{pW9Gnl`-@}n1 zs7a{~SY0e0{6l(4Qo&K(ZCHVsxAKY2Pw^~Bn-cQ);bM6NpI7GV165-pu?vVuO%^;f z_mg>alKN_eoo$;@m2qKLH=En`V4FNlS~%EWYy7zpk|lUp~zjnzh4@L z(~fF)&n{6DDz?J!1`wUb7=E23LmU^oRPk@vSNlB-|L6UD^JcQ$U4~)&mz>MN0RcClgVc-=gAm5(J3U-K0WjfehvK!Cm8<>f+C}sLo(t`OVS*j!~KvhUtyca+*j|D_e zs@IKAVsuIJz9U!S9Wc3R%cB${NGei7Qx+kUGg^jrgZNCoPy6qlv$X&JBn?c&3J4p> z4~T!SLzR_=wXR;w+Zhps8WQIskng8;oy&_n`b&hhbfd8X{4b&YMa2FccP0J%MnM+E zEbPvzerGB9>d(A$@^l5DJ{h=W{A23Em>1_CkR+F#7aTcV1}pMJ_lFQA5;~4!m~WsfkU8p$e7aVfM?lpUQ;$XL%<=MbbKvZ z5{S>f8t)Jdr5l~dpR01@+_q(OVdyRQ2O%3R?@r;n%#1FwUpO4*_c0u z9-=iQpW3=LR*?9h*2{L=$^Tn2T93XAEeVcXS=?&IR>d0S3pMN612JeiR$0$nx6Yr2 zpz6JYdZ8{)aWUbBIe`8L6*jW^m^Rx+N-#NmtYKNZly(cPM&mns4Q^<_GMATe+aSr} z0ti-rc-%56{W!ekh;CzyCT~vB^!i1h#|AFSdPNgO$l@&h&tldXx^5YSmm5{yzRd5X zl=>_bbX2S-lC!g@CY$tp#V4=H+08=wuLxyXN6XM&fxbV(@@XSmS6dJ+>Qqr~#~9Tm z)(OSh(Y=vwzC6$;rY-ajf1+1LV+(^;F(Qh>0&baHoHZD&x8I#+& zO@79;%P?C)_U{cq;wxT;TC{_q1>Cyi>phA5%1o6I((}vi9DDRd_hq;E_d88Wioisi zKUZ8c`-M3+w=L+Sv zFERn8p!|Q`WD)nP^luZK_BUE!-_UPMnabDhUi!5ik=tT(YO<=TC*o?>xm^Dh-;C>OUJeDd2CFjqT*YF>-y)_KctFq3TpNmB852>;bG<_$yAvaF z_2*P9aF1>M)HS<5Zo@gLhF{T~CzNQcc@i~hz9;;UKI6rzRYsb=WDDETxPFY%eO)lS zd+>(VVtTQq35RB#xvh){c`VZvB}BeDNB97lg@jP2QH3wObcL?ti7)Dc(Zxf{n$_P@ zoryfVui2?>E~&x`jfHGtqS>~5Ce}oe5x>v2{y7#p6K>pF$c;!|bTlPPIr#z4m6(_` zB}`wPolE$cGQFqVTI$cV{?|>!K(i`x_Qx@ko*V8PMiTCblhX~TV5s7qs*=jhAywbU zC#e-J0&?h)(kIA8PV;et4QIz64|yK~QI%*TTM;t$55GnPT+PfrcBWpY4)8jJg3W%h z_$-u2V4}_8Lk`!Tb2Efr?8Vi*^)|Mze@jGD+}Yj+*(vOK{KQCPXOS``xFtLt`n~T4 zfM9huH@+ON$<8~XK&G-|3EIA|7MNSwsmstVj?55u>{H3ziA{b)wM#Gnq&W~uQe318 z8l_V(!qZzitV?1PCr5`Qw2~<+Qe`1-F@8?dU0!oqvVy3?n2*=%>HW5AD|`C%G2_&fd3DTS{ucl?_IpB%6^wCHl|3z9lzMQBaaixW`op%Q z_`i1M-})hMp#2rEKd}{Lc3s#s(ZAEA+8r z`#>1Fpi=((@tyB4;Mv&Adu;0n)5<`j>oNTB^#x(&FJS)1d+)r9lR;^bme@x&xE=1i zTV+%KFMvDq+e^n^K)oW@*0lQ6N8Vq+B~CzI+)Jrz63NNd6H~g=9CAmx_u(CX5&M_1ALjv`yHND7fRO~>u~`{Iw}02?CwM&lj|sl>+TW*oJ}ES zn=t0!(eq zDwL_o&V@G>3KJ8l)iy3$TKP%2r{!7eX&b^QFC4E4gYqC*0%ex-;L|HjOZ*^E`JtUj zk3MhE@v&97EEv!pp0zFC-_577>Zd&D#H_XkE0iwIYJ}fJkn4v^n?cjq5j$wouY2mS zl*$d15!>e#hTX=sq}1H!_eP!I-ki9$K^tMFN@Zz0Yw=T{ZXR0SlJheb}K83d? z@NR}Y(_XsD7~=ojcv%@~$eCo%9b(b9m)Z95+@7FF#!uv@LoPZ2%rt}f87r}?I@~5d zLd30kishaE2}b;j{>WWW7n3ce$>I3AX-g{ft&6G@B}&nS`eRTMqoHBI&)*FRS2~ml zM1CLB%X@ZQ)sA6xIKxL@cyWy;yV-=u-5Fg>Yp+(;Y)V<2pQcy=$Kz(4tdLy5{`N)V z-!#R%gCtX4Qae9FI~vv8Ql#H(R-7NGf_%een)fVz;K=p8fcpJLvsD6o!-YmM-;dSf z_-FpPa)N7IkFACXf_Fip)Wh9Z!%X^ZjIBDWdXiRv29^Rk`TN`OP5T35$%7ynJ+Wim z8eEl&kU3YHI78U>KjXYTbdl_F{S+r5b9&z zZd_3#8#XuN0djPI(r;baqzL=IBAU?#zAj};j9!sq(k6B@BmkK6X@G09KPoZhHg`Ll z$}VaI0NTy6;i^9}r!!g6N7;2M=)oN~_TtST_2`RBLD#RkM^pFS~%xlhIH~Z{=bR*1&qWs zympLIZZ=^TIg{>iv|BLhZW;pk$Qayp&#IG>B=95G_1t?n9P)iA=;+LW+S*#Je55~% zSY*e^MwQXXyJ)cW$y?dxbJTa*oQ&kwh*B2wsURGxS~4^ zM(Z-v;dt}{P#7&vb_yWZkbRxzV@KSXn3{U_PNF$G+vt%M%4e(omJu8F`l~-M(QrtE zM-uXX0Y1!Y-ykVJEl5KPOV8bh96c1EL70^c!m_)|3~}la${dq@G~3zWC#RN$xdnvcSs&XI|UO7YXek z{JL1I2No5s1rW9M`}WoIwG{4vpGNYL;EOvPH=ZgYi}+;@-&-6X+K^p0#OEp8sU1msz9CrRizO8tvO;(rN6tUc}v7%@NU6V>T%6*V1;H1BAW#EF!zevsXc}A{`TE z;!*WBZHWc6BYU3I@I{;&rN7H)*jd(DjW_c7ekRF*=<pb6N@tXVuo-Egq5Z6rSTK9w2nM&zkgGaVj+sF>Ge_XJDOW{q3SVF zkWy#$no7gWhP8r}bDAjmYNwmOr%34I_k;!ggtjMj#iR>@;ewX`7KRs$w!r5)**rM$ z$d>N>p^wH#*vq={25FYsuW$a7qTSFLF(jPGnkS!6x(kuSo584ldC~;bYyA~LJN%wc zx~`&Na$Aa&AYj^q;q6pbc?o;1OrIoGrQJSoH(N9HQp0VO916cWx``R0xje~mBiExZ zatU6SN$V?0ayrU)cZRB8XrA5B+|H(Ysjq62-gv9(KL$X(1Tm(JT&Ou=l8U6^Q>7&? z>{rX?j@~XPd$MWTm#2r_OqnrYmtKgzI%>qAxr~^Fe(L1fjSFUoC=|P&c#QUw+v_ZF zyAzp(weP_JYqHCKKvSP|W8DR%eQdus)NOQeulNqC&rT}2U1*G}P~2q|hb3jRqU|-u zwb|(RF^}lw+CH(F@zd}Pg$&6C8@Vi?J(jbC4@z6fF)tc$fFsO=VV~5wIBRd+q7zwt z$|NO~gVUoDCm;Ddws*{`xwR*3qhCC()m19*wM)QNxSB5r8P8z#Zo=L{owK9-6?Wg$ zP;p;uatnQ~)*)hGtqy0Mp}2o-ZL1|e&Y@#EAv|kWRX8jQ+A~TR&tLvxI^t3&K6_zk z;cF4ge2g487jqt6Ny2$YBfT1>x_$}NmdUUO{}xb+6Qi&7RF6fqygJzsw$i_*Of^CL zN1pTkln%18ciIi0l(qgFlA}iOveKe#>-I})^GjjosY{Y)Ge3t*)q#trVVCq!LP-ziL&d@9 zry$0BUnG{NCvX&8*@r=KYvzJHE==U_?E{uzn4-(q z_>huj1YWp4Uy17;gR}OCl7RoWCNbIwWs_%d6ye9gu)IRQ@2^H{;>zHI82p|67m=Vd zhDZ`zbA{^>R{<-Q0a*Y0WLjM_P`+@{c3{-@NVAekut4_#t+s&MCwKi0>I6>wXrq_? zlScE#7OWZT|Iy+twv%`F%jO>#!ajEo^cPSuh5LgKiQ({ZrVDp@Xa>G3N^Q(b%|#uj z@W1Ghw4Z%P0}lCxEOAi%BE;@g4Z$P9&rY1emBZ&YZ!$|iiv9w`KF7axP+8=_c8Ldu zUM)F>cm2{VJ>l|U$M#aY+9>@MlXhp=ac0?50V(ERfow(|(5n z#d)I@r1V!g-vqrkUGd%T542%ns9G|lz@2#@QJp!9F6l(3>qeVPsqNZVn}o<_aPS%= zWyB{+mD1YMtZtZpIAat23~M_W39B8*#>qO^iee`!`&1=4Bd439HUfuJBx6XgM;Mf4 ztR8xTL<+OKH%_teEtKOLS`Rlzb+~2BZYQC^oWgt;2g^XBnf&A-mc0Lwfm0XC&h0Xu zEm5hHJi#TWBxR9OG1DVx-o zHuQT-d`1;2OevL|4K`;`!@>w_mR5Oy5UX1Khke@@$`=mL_S`?mkzy!^Btn9%+UjSu z#wrnRTgfUttNWV$6uY>POx6xnzIEIsHpeBzUqvM#RLnJ#;cEQK77Yjz7IZMr8Q$#Y zN98ldV>TW3ZAm-6k!hwcy2XS^{h@+&E6KmMVx_~FIih`ZMQLr~SD^^eAFz(E_+21D zvr(;&O%9Rku@PP+bZ$%$HK94*yO=UKHbP+C0dEDwzIbfJXj@;O;;&&8G^%ad0@6~{ z@!_v6=z*h7RV4ZXpTGWt36s>Ha3o?pUsK3oVpSMq#=>sS<{3e@3Z=h@TQBc#?BS!? zh*-lvpcSmp{iiUHW@mPQLXk$2(y1lZ@|ejHajc(RVTCnfg>_xW%7clS0U-;0wAk@X-g9%2HgQ{~jE+)|>V=D6;p`(Xx$VZCWGF!rXiP&XJV(l)1 zr`iaa+%i4&b}BjvrWg04qI>ecjrMb0Dx4W|V?uSFyqHfY*}q0To=VqtU=~RI&^0_b zSm*5q_>>dW8dNXVVZ>yju6&%hPIE zq_Mv7O%;1p_I$BU`vdeb6iZIxNj#sb#$+=LEWJ` zbv7LIR5G9C%(mS8lW79$;iCko&znRu6yX59ekcnD7QJtfuNw6b~Deyh6c2Jv{la$(x`;Ahqf)u5vKNa77=*XkSOKf?zKF3uId z-WKFrH4B)n+Zwh(K`e)wWLulync1zw!del_>_#1xNnMhXt`4=c^r&K)dClB6RCkR*H1}+dPa;2#=VSK?FM+i>_C?%7Y%^<1GFe)K)K=(b2o+u_&^hZo1Hyj2GG468WTdvS%urtqLEzCb3Zgk(vjT81lc_rDc z(3jJ{eljAP<5AL-a>8rFE2Q&>hUV?IlKyN!khaAyfvbj*?K3vL-8QgJ7_=Ibhw*}c=N1lpGWhd$9>*>zuA=IW-Hu)*YUF-^?&zD52OTBF`4+zQZjA zqvCn?EeU$Tv#E-xBO2W!v!W-kqFdNId~lok2#xqiaGU1zi0BQR0bQ!Y@{|(-7UDT> zU2_yi{?j)XSl_+9n<0;eYfo6dkw@)sNZRUivM9^!>}e#{Rj%02=GMH#h2TysN1?mxz;RwZG##zGkYx5mMp21U6yU_?Ux1P)z8 z5H{s?(MQ*l>Lbf;XL^ZknOIv*5<*$tpAn#aBG=56-C&Zx1O2=brOooCXH7T{8wVh3bS95>&@`r>r~cGv0jm+)~&jJl@oC z^d@j3f3pFGfiu!Hemz_Y=+`4a(qLi$e7Q0_D9L zdRxR4R*1Qf%_4Pe+S4uiN9Y{aD45W>+43_}IodU!7GchVWOGiVT{3?0YQANy7cO^` zq5~BqB3Q+8StTn_5NNj}t1AOLe=j6)kw2|$KoZn+O zYH=7$!l_SsN9p%xY|~mDrs8*G>k5k@4$`S>I2lr9T#i`bWt7PP!V!BuM9twfJ0sa& z)c(98j~+T5FdCSyoQU^t);x+#`dpU|qkoqxlg@L9&2L*A@uo}|DtI`eYX(Os&Ta2ozymRbAu zD^6~b0yK+JD^KpkG|E@Z8&OBJiefX7R;W9Sjc0}*vh6g0^zb#Vwcz1v!WZwB2+r$> zPiyP46d`SywI42C(LX~{Qs^^wC}T5~k?oP0a4utAm~BJ|Z4@B^xPnyW6a1oiX-ak>-v6Zwa$lhRwDE4ePXEn@_9;hjVmIRSo~+*I%`@p zNFy^`BvMO!@tbsOO@*8(w&M4Ezi+6T!RX!+Y1fn=Ne>ftyU5z>jVbWnF}1T3wH=$M zdIX&lL&FS)?ai8k&TQ!G$77s+7>u8jM&Lh5vdF-)VuhkD>F5t9*h-oXf;pu^V>LXTGcwN+0U6vy2;{vl22vqcCK(f`9Ha~mrbowP7x@}hM(*kkG zMt7pMxyRR~bIvi@&na>9 z(CxMl&ioz5n|ozB{Y*8Gj|-P>7$wckhPjCe%JX$5Yd@tTLTG7eSg{Zw`ABMpYV6_9 z-3HmBjFAV5`hP`E_sJa!!uC?2O?9C{%aS>VU%D&<;JGLP?LG%N=95_S_p@{C5Q+>r zi28bEDq^F=Ei+D&e}dZ!B3ilKb(^S4ip^^qD+c(iM`KvpGmx^|m_KmDwP|m+ zv?M@}JZ_i3+DOv$aRobNHUx5lB+lK=sjPuC_Qsyv0rm-BGotWkliXNuS&pRJv<+lk>uagr={&;2(De@odsbe1*3iBBRYVaNrN|_tQuH9GVt<3Ci-d^=nulh3=Je?~rqeH`c%32mjWFLrP^JB@EX`E-mS zY_N;2e@kWT54z_;7I3=5px2ulFc?bOplgEuAH2O~SX|Mzu31=s;10pv-5r8UAh^3z zP`E>IcMYE4?(XjH?iSo#(zVY%yU#wi?{m8U+~)V9*5YB#RbzhR9p9Hkg2M7F<@>ws z)0Ea4<{9}axJyzKrJTq5edI~IRJLWmxae_!^s)akZVU&9=kD=lchM*-hlyqg08s2~;JsPys;H0I?*IwVx-eGYIruV#vQSU)E_pyg61r zj^=JZT+qz?|9yJn-x+~_3R>8GaYZyqJ!|5+P>rADH^}rv*A|W%&?HQsL_{e)gZNtC zUcqA_M*y(V+F356<^S^o{x!N5DGESECF;qgHH4!2QQ7nO)*DtR;)e7mQk(4W+&>g8 zaHT?q4}zKGpRo>vrN|{5_c3vgCBh&u^TvdNw zvnW29e6Asecz1jV?UOnZS~gI=z}*rXlK2bI$!7X+#nqTN&-=k#6Pt_Si(8g*SNf-% zQT|^7(|?Fs4L7gJP~+}DW*LayF+&fFd%(ZR_RG}9UoU=nT)Q+7t+ zKOvR9e?lste?ThL|DPZgOil&(IC&wGT&7wF_9lK<^AD!#^Ji$VzfhAjy8LH|CN(te zy#E%y%|OpwX60O|?sHa8Xo`>wIk=Z;XTcfe%d?KtP=U)|x}W9+gDb|Lp-fpZKdx1a zo>h9NWTuDtrwJ1$c__NdFfw~gGv#40>P(7Pwwt3O*u$ia>#F6V%neR*Ph+_dbZLK_ zUM=@c2lX29*ShQMG1cdq6dtnMBIvfP)6!I??;_km3u zcm{reSI^bQ0-AB`pH`ue3yhb?nx8nc{YUVQ2roM1lOI&w&NEGfc3Azt z-OI1O&c0wTA@Wux^Yrfvs140UI*6P-MM1_e?d<`ACo%_pzR9~v9ryu{pFyJ{FrR;t z&;SV5&UKv3dGpv+TzSvo=bxgTLAk|a(M5Ag^lnHAmG#ogHrK5v0N4;KWB`v;D9nQCiU$yRbW zFn-`@Zc|z?iy2eR7O6M~tH(t3-qF8jSZ@zEoS*~q1$Q`=ZCmHth0`H4%A_&Be+Z2XWKQ@H*l@t1VZhZSwu+6=3QDf%pjO^y^YanADu*()L8x zEjV;%u<5zt#*tc#`mh`!(OPKp7T07WFeys z3Q6HGsOD=Uhv0%!4PB};a~+GF!}!3!7fQM2CO=0k71l^k>Ak#pf(u!P^<%$VJJV!h zQ|M-FLY;=36a@qt$Po!M%Y~D_2K{nFtw$ zA({Oms}t6mpkYC{5eZEJ z`npPEh-nr;$<{_}1IPTD@Jiioe`)Txq50AGohaY{6C*poA*9x|xt2pqRYZ)UWWlcl(2udkb{Fn%OemZ4SgXj5XC6_e>7JC?eZh`8o znYz_3V2CTJQL>I4&q_;BY-&OzowJZ>7{`bpD0skjE3$wad+fJu zD{R220c1!bMD6+AhP&qCDYfIUwGmxgc1I4jtl-jpmoXwXR<4S`7kjETCtkoNf6zTi zk35t4`2OqiYrX#=xGn%gzAbBp;!JSyfOXN4AgEEn$;O_`XxW>?>XzIKz_LqrFq*N% zGc)|KE=fIonXW%=7CYri;_5zs0?}sBPuax@)`xsrywxa4GMZu?iYPr-g!mj+)g#_u zr%++_R}HiMbz#IlwgpZq6k(g`IMYpQU=>A*b95WS=FWcO`arpRgFwY-30dSGkuT}Bz@Mk=Z=49v&(ApXD_UMaFdm9%&lV!IFS>d zr47m$tZiZx`DJ}b-czQ(uEq`IV?k3$RVOK0hG79wsPm+GmfHxFM^Jo|NR{mLOt8Ln zmZe)LEi07Zg+`i59r43Af>;f!^`4i4+Tb&qfZAu&5iwgoruAHTac44#X*|?lrmoML zN}sc^N2k3tSC`}U3ubR3OAW9Sbu4)QWAbTNB3b}7iAhdcL5UUewod$j<|eftp^!vD zIpemF)eS(5rBu?ASB!MKQNh{HU$nNMWZTgA*1)~=`OlY=t;1pcwRg2u@CNq@Z>&J8 z?HXMA_VTO0>mImO^`;{AV#|GPtlH9#H)h^?xo8}dNwUIzB1cA{(ySU5H;Q*craEed zs2n~HL+HmhWIg373BRJC1r^T2DO|4c6I`1+Q+F}?UIk0{o@Z~99XB4VLmeH1@E<9FHD#t>*)vsZtBMTX zqG6`wcan#UEG^A7BJ=q|aUemFNQyI675i(3WlZ=fWcDv0%(ysWK3HNk^)3Q+5~j@U zGMUd%$4@7zbd*zE4a#i*-x6uAsHQtwLl+vL%8E$A67QIJLq{89i#zaL6my!wDa1mm zMZT@l)J*nx?>5&TQ~Ho=q)?3D1Ri1B0fI0nV*8DZ$6a`rHItn(tdF^&Z)jk7bh2$e z(Z#gH8~PfgQ>YDBb6lse-xwe;9!)&^Ikz;6S{mj6DQI3oYhB)5d*o^}u#a7tcc9V) zvCnD4b(K+PZ*F<8DH?I@0~2Nyj3>#+cY?nFY|iDUSYIbTGGgNKz1d5H=Go)5?J8<+njIB+tOlx5LeOUT0AeuzFwBaK1+{KvH)d5B+CywCFY?* z9IznY$jGT+xQyYiPS(!CmSXmtIn+s0_ZD9&rG0h^V`_4wlIYPKyl``{mc5Gdjdc*+ z)S1;t9EwX_#S02@(65V^T-9^psQo4FA905MEzOlJz%k|yK<#&Q<{(r=44LL4@1I+t zzw6b6v&_q{;DJ8aaqIlrrh)^~A3#0o7>9ZkMJk-hXeXav=z;;VnX;;eU_yS2$%N^!&PUVQK4v3K2Mtc`)j zqLaX!WAO{~3uf$nhby`GN4ZWnHXRUNkfoQV63_Ocv#~So1R?e#8`E{&73l%ui9YBr z09qAe`5HP=o`t)(aYUdczhqAs=2!7(S=@73g`b%4tYu#T!YX;cB6I=rEb&`P0 z?~t#t=Dz677priVhu>G^FUXdf%ZHP}@+v5iid$4NwnRbIxNUaEy9zW+oPA!y(1mk- zEb3B}gpIl)1S%YEdoMWtx%3?(tL!|t0MA`;{{@&UezXz@S}v2UQ)$IJPP%c9(a>mVRi9!yOs` zKc>3=x*Vl(KNRIs!P)p*5+&5&*5=o6vb%59r6DwGn9Rh(1%RNFVsL|{XCbkJUd(}N2ge<7~1zsR3yQ$q#tHO^~soXVzWwf$ovoL)(zkG|Q8?03@rbB>J*Ymno@>`-^^3TpOe6QZD79 z&Wu7sfo(mW@|fk&Q-6*A$of&hJ5a~}H8=yy>@%{8BYd2McsFLAfYcOsSS@|crWRSx zP~**#-nqNZ;zWA@C(o~Ur+9(nz>n}(65Chl@ z+Cx*(F8EnY_z$G8NEPPtsoIT>itsanf^DBIsAW#;TVG(zOtV|uW>6}{%aU2w2hfOR zsX#0Fw-Rz{N>~H+%KCRlU@yJWP`XE^rt0L`bd$55a*#?LNmx$gs&Y9s1kHy#UvF4v zlrb^tkx44~eq{tAVHag;)>MNDtoZbxZ6;Y`96NNSl8M>AGH0sP!J_=Os6c zS8};JcYF@(Y}3SHa=)n!ta2&uVU*K)G+f#5KLe<0yy-_cS~y9b$dTZr2_}7-MLn?X z=qgTh4u1i^{#pG+Sm+fFW0hmK@Pdu%d7Fc%Y?Bo&JU=|mjQZp%uM9O(CWZ4nse%%q z*+SM|t6fb3rhczR+}mGV&xZv|AHF?+-|naxjK!t*?cSb(-vf;QrvJ$|yjA;-qP*_T zV8djp2!;J9?TQ3?oq1Vml;Ct{Y`#)i#t>hQhO#%g&8=$_PqI$DH2+Ws?s!F>lsAa}t$w;v3W+}p`B1e`F^`&= z#*xcx8O4~2J@p#Vgl%p|Vcf-~ZbH={YN7vDg`v{>V1^sj#Ka+aasgj+uzDk>0sv86 z+{O;BaPvYLR4nAlQhp(a*H;7|!7U+Jt&-U&Zi<^O;2N4V1$AzpQZDJzYi46GkQHp> zT4V{-1^iOxv|3hg9pbl4E67Q*uji|s89w~Vo}f&tVVzc!LOK9N=Ri%9>eg7eEM<&D zgs&1f(;C1)R^M+;Vs6}zk9Y{nJDrvbqQRpLo^;9u!#yCUNCue>-Zri}m~S??$&$`v zv&I~`qKK8|pN`4UL&C)sS#TsNkSyakqKzt$JAzwW_IdPq5`Lu{C@(AZ4=ka2{Wwn6 z(Q%ZO(XFQAww{re^MAhm-kKW5FG)ken29GY!6B`$7xo=RTQAX-X-ZEgd_oWZnn5ELiE!W)Fh&GO zLHA7Br(l1!WtAm(Y?kg`vUZBT*i}ql=Ystt!xL)5L{L+(CswuozKn1R9i>DRK1$?QnM+^De8q$vCEGFRSboZT=9g%`U?`?pDC{N zWH`V@Q>+|)O5k2ShlOpaS-7qa?2f!TIZ>M^0Eb3o5cR@(%9};~9Ga_)aRHTEIkI)8 z>4KKCz5;|hr++r<>(WU^43U0rJ9te+Hct8sNg_xX=NKX~swop{F+Xp=Hh0d5T`$M%fV(vl+P zv>;dV;wHf|X{lPOi)=GEmImNjg2O4zse^ztXtp7r#UCA5=V zTuC&{#Wl9?RaIhRp!*xqutTUlQceKc@6-0Lc1dcOq z0SI1wTmv~<)_NGZaC8WpH-$jqw?uFyiYN}OKiwRvdr?3X)JVb_uZrxrUb7zh1Q)QJ zjfsX~{lXtJ+1z`)hCG4KqOmr3Ba~g19V_@hL#*?_V-;OKegis$CwIF3|TNdc> z=^mMo5L>H)**wL%r-2ReJm{;Qp$k78#c@|&SVm;V-SuvVBkK<=2bjhHcBN%5?(QXJ zX0TKD;(Q=UgMmCA##nn}Pa{y8Bx^LQ)%ZZN18oU&Y?A5#sj|3Hc)2Ph0wPphOo63o z^o4QLynkgiHha)b`FKDI*lG-sJY&hG38d=LTyQnr#TqPMJRGlKtunPKT|$QZSTWT= zTA_IC5s*pv5h94m~_1iW<0D$N043W$#^& zyWS!bsv;(fM_yo97$!apW#*K9{Dln2F?`f9h3()JPO&rpbhlDO$eUg0s-|kp-dQro zE*YNnU5~!N{0#1HSYLl*8L{RIz&07}Uu2PE&taX}Kgpu=YJOcb@_k36C;STKmY!&4 zw=BpHN>nDBii6^8XgimtOr~#=zf|OFN-D=($NjH3Qp17WCUbQ;ZKH{E>z}vOS3%!s zL|`OXK>9&GcC7Eou2d4;C$$&qg}tYG_@zwGm1DbKZ<8JUCt4c1 z&wJ2pJ?$Qk0-tlf$$1hFIB!5iP-j}lSDb9oT1zQ@ncGXN9>DGGADq?`0DP&oTl!t z0ieZR9G77n6$I7{?nmgbhB`Y0xIsTNx);)n-*_by3kO=g#LWXN7q9@Dc-^rm1B`K` zey-VW)Mn7!7Rqy=)ktAdND^6#${`2JCX zA`-^%F#+n>N|72-FEY4IXKSS{W7Ci^>7@Y{yd#r>s02IBesJe%D{{&Yr>1s{f+Xk# z%!XVP2EDb(^NIxDs1AJq`?ln(jZE&q1f~fd>ae^6Dn>6x1c`!v>ERLft}WRD zsEvyL4OZMV6$%nTT(~pL?4iMPbjYQ9G~--2`(|zgTtl@n7yLF;=Q;15HC}93O+-`K z56)HQG(5+jOKAY-^~`NTW4(tGn;|HIpRBwEl}&<7FqKU|`qw)1`W*;*+tu#lIPi** zq`FTxU*@wmA`28bV{U#J%(6OQ%{iIDmsdsOt&w=yp>NfkQkpRu>fK~g8F3cZz1<{nG$tfTEJgY(Z|MbN$73|Y7mIera z+e(lT!cx&4SC{!k5Y5^=@VogWiUUCC;IO`YwFlg2Enm_5Y^|ZdP1MrhR2*#-LRVvp zco4;I^WK1xw5z?DGA|_G!R+-_a=M9h{Nj@t7E|i*r?R+M=>RfEvb{VWNI$W2y38gW zzq5*Get`D^ZZr`DB_sdd<9hA*szpsqZ0i@I=Wi<;NYG8K(0U$8_oyRLQX1c(tTw(c z@$iQsBI6+M^nZ#u4aFxSL`bI6oJp04C)Z6CZf)CC?f*1oH~T2%!Xe|@=T zfV)wnFvYaSjO+Si!;blVCS`G9VQsy--^3~TF$K5_eOS-`ZAw;6=!@>9)JAx9cMF3Ut*?}zveo%VNH zx|bDw-iShWb=Jv6^&LYG<>HzU2ME=PY5thQb!iwV9OLt9ct7dVBGL5m`5%#v1>l#% zaqWF*Ep^o?5#(Cy#`ucs`AJd`2gTa6=HM_#^BV70L2+V%?}thxw3Co9Xvbkz$& z9SvF)?yp45%FmFWpG=|;%&E@$b8PVSM+8hW-yD_L%9_>Jtv6)Icnrg(RTnX^Sdk6E zo&TlW0_Tp>4x!^Yg2M@U+We@T0-*9MVh9oNJb7I5(-FNsOXO{nF0w2RR@U!&yc z^oTXf?CD;PIb8u(zr08rm8H&&0T`$ist+?X{au$s>YWoy-{8nL`73Nr4Ucro%ws4_ z9Ju>=G zQs|Sez7&~U1RXMHV3zb-r=cw%vdyQw9&&rzM^}6aqihX_m_(YlGQK~nERK@+u@r#a z-|LRPxD|e|WM~5qxesZ>_IZaNxHjvJ!%58cu;Q1TZku#F`i&x=#CU&SSrq%hjTYVc zIwN>gvOA|g17)&J4qUzvukZ>atwBv-43O_8H(QZTIGFfvO7-*Rqk2O#n~+rtbMKtl zBY*mBPquv}_-VTe;u3-Rni=-xXUIp9#*xMt6Z?&F*YU`EgUgat&$GC2N8N>*^NJtrfcEE z*0?*S6Z!R&?wx|InvMudGXNWD7n(siK6m+g;KD`TATykscAPMT@T2HK*_bB;WqBuy zRhP=6#6i}ZK!`TSD>sGPb%SPsAd1loDcp8dl##-bf)FR(C?t>9s9Ke^R^%mv7wq0@ zKm7rXA0R-#!m06NtIp$9oJ~bz;h3EgBB?-MWOz(ZWma)Jn{c6JRv_5({^i0ri*_0# zO&l?8D6TEG0;$vGf$3=cGRlVD<|&0S$~ajw_>*RUtd&`5whZk)V;SX@;3ZS|ksRpH zn9MBC6#~d2iXEwF0?+Y_r#l{ELnR8(#6)ahZ~N*CRH*wpQ)GYdZTrO3tWt<%~@)e(XL4Ajp?v_bsPB2K@$cPBl%I1kUZkSzxs z2qbY?_^2gU)678Y-;@=@Se5K#za2L^` zMf{xo?NRWFlCAh&itClZ=jF1!ki%MriO(lYQaoGky}nFe1qOa92ujX1X6Z0ed{1b$ zIEQyOpI1IpgX?2AUtHC~NQyw~PU{iRrGQFWyjOL0nNIioW1I~sI!FHHVcn602bF*i zuBL|UfdX$YK{~6Fnz!l{I`G7q{_2Me`?sy{gPMN)|C^BLpI)?Hq1D`1-xP8R%O#T7{j0{c|w4Sxbe98a#x<`WJt2Zj%S`9YZR@B>f zV+V+F9N>nQL&kkOY z#_u(YWqES}P1N#iBqK+ssT$g|W0dR=;08bi+pzqPftUXksGa~v80Gy%`1_1zc&}#u!O!k&I6wAowN6DeG*ZfVKqS{kv*2iP! z@3WAu2Wo9cAS`iYii-vei{{_!Lo|L)fUqoM9Z{e% z139_%4TXkqs5o*Z9GtQI9u|2vnzdNf;n5L%9|oLRUfoBOZ4`t^-9TIQ=DRY`u9f3Z z;eAOWDw`D@Wc>4t8V>XkXa`GJAYmkAXa8vkx1_K*w4eI(S0u3Nd3H*zm&Q#UcLovKC*(!gSpk}TQM*o7(z>&~lm zwbz|8ae5x?yUnOid@YQtl!?WzdfU733+{aE!7;t~73T{Df$)#EsBdpC0~#`IJN`SL zyS>RSAq-4e&QKhyBCaC-xBuyg&nJ*pseSvmH#0bp5yl5oyn&AIUB2Kv)P7}u5dc4A zSd$V~vHSKr!h`}iN3H2j%-EW&#~2N5M04NP^oN)G-mO4VQ^rFTr%eZ|T5_Zfp@rTa zEDVeavt~H2w8$xoKTb#(9GoBc=Zr+~D(p}VC#{UrW&r{U$NWF9scW`auk;!%? zUi|AUo9m$wA0%dml7eKQL(5WSVR@3;E)2n4p4s!s!QEYy+{I}_iblpP#pBww#<^=E zE_SAsT2hg;2QM-6#BMoCDUk>~KY0#Y~Mu*7#y2M=5Jux#CRFu30KJyc)_1ViGZV^hR8 z>npX>)|}^LX5{hd!f?Gr`tNfoDY_FU~lSz2B=E z#J?B+SNDfDr7H#H8BG3oYm;@?MOe(BENEQY+WExVe!eGr!tf@x)&6$$PARgWr2HRn zWs-!aE!Ge74DP4$5rZjO;6(8ge+RRc{=gOKacMy*opUZ-*V+ezow&y6 zaYt3;^$gDBqYhMO9VbXgPr)MR$+2L`fT1z?sdGpuO5G=s?3uj&R|J*topsw;ni?0o z9@XS(i&lmev`(|Ai>3g3Er)l4Y_bGiD?hBf0a{%`lC*<_vpQs|2eO!rVgIg|NqiMJ zoUNf74B*?tPG(V7*6cgC6t0H}ND^YK5k$wI16P+Iwa>M6A#RIgfaM;9Ou&laKw~DP ze!+s&{K^ETF?KwY_U|#$Ga%++jE7Fv#<)h?x^*YF4{gwe$oXhq8a(%*5y47Jwy^#A z&2XbUmgbuuY5hYL5s`JZ>=`(9A~-qiN4ndPB5sV}e!{%&vV%i4(1oXEpF?l3$F`$t zC?vi7Qx{Th{%>25PC>D^>P*<)rVOV-k*0%F`Iikl@N5mJ2p8+{XO_U~m9g>+Hj)-hhGZ#l?PdM* zN|ckkzodYPayCRKkXUEx8R&858mg1D9((@P;5a~DLu;Mu?n3mQbeC8ZFzVd;d7J= zpeFUTpVE#6whRfW?O;AB2nO-PXuCg~y zmtJXm6SHhrb{AVyI`9FF%Fd&g?dzo^Y#-|OKB!%midgIqBE0n z#Uki)t1imS9j~QKJ$qOd9_C0dLVIpGKNf}kfUUz!w->P4cF22!F9ITdl_9f zb8e2XAT@$vnJ#v?!-?_h*HF6@iCV+bp?wIXq6YV?TeScUqj~3ghVrqyxlTU!euqnn zl-$F<$ml?wl7T7G+zT!Q+w&g+91Dh=PqtW;P(a5GMzP((C@G>FnNk?v~0SM*QkK(u?$ zfBF+?a1#MN|4FbP~GD`HwuQNvRW)Ir$ zyozOX?ffXt*El<>EGUbg=>g>yCb@{Sm%iIT`mfs*c0Pr&^pF9~X~S@|qk7%+m5pwq zVLNGG(-W~x;}=ikU-VsgBpQ418nRY?jcL%=R__Jnm-F|m zX{nz=)#8;_$X5136V{m>mZlHC2rYiHTVNvUz*+bq=EsEGcn^_KL0je~$-HY znc8~e@mqQH`084{5x%bUn$y${Mz$TS{a&L6G#NXzF|zE)3r&ahXJ@&%Qp|2>J&VKi zYt)yjo1Y(`Az}A=367}<9JJ_y4_9bf~H_@jwJuK9rN)ysXqM7ATAy@@D9|8Qv}JMViTymL zBR7Jp4kZ_=afxKgYUNY1dhM0ivvko+1nlLEt$1g&K*Hai5Zc|7$@y9C{p_%>lRE2u z!8dJwF_{+7wP%u1-5h7{Vy+Lh=ARnL<`=Wx%kRd^eV#p7k!n#9cUJn7@*Km}i9?Nj zcy}~Vb#{cuD9ilNgVTKEA9KOeND0o2Y=NwkXc?Fb%3w-#q%o-^t$|Yx z10eS_`+1M7Hf{SKZe-YE;0(`uD8iH%^wAd-*~~61vdKW(F`{^Ba&S&U?sNMIKyIWG zja0vxd@3BEs49t(4GSF8Au#272P8Ve`Z!a)@!Pm;u!DF*-f8uOOs9tsl;<%}D>um2 zM=@a*dre1+!vObi!G`k&0Tx--Cwqmw%m7HKkgX=*lfkTh;sav{Ym9G#n)w9vwvsc# zeKCQ`ldJX{FB>vW&ACmD`$2wfM~3%?-99r7JqW%ZJtb{d1O) zX8TAQx+9!_6wJ$J{pW`2M6--G>60eU;X$>?he(E5(TG6+gjV1~k;EQl5J1pVinOCu z6U}4Kl!ab@Yo6#AeYr6GdC;^wh#7`{|&>;7ji&jgAc2Q z<{?aV2n8?bAR>Y^cIpRP5AYI!275lGIq{NRkS2X8siud!rEu*H0;*p^|A{w-*btIo zYjJmhaDpE%iJ~HG;{xQ;AA1rLVjmxAzr@Zb7Zr~YeSPvDdNLtcPia%fv0bo?vS~lR zwHF`Z)0-$^L_WUOWi?KdO&`T$b2dj$LL?)RP=9me;4Z8{*IhM_o(m2qH>n-@zG8c@ zt+5on<%X>`QFuvM@QLQjd0Lvfz_>~?p;G`XsTxe=BqRmR3|6>hxVT<^^|M|O5Nc=* zZ=$13U_4<)Z`*HFdesfnsRlj8n3u;jsOd*SFPH|_Y`q;u=Lp74&psf&Ny6yKqV{6Wms$8-{T{WIQE85Brzbgqgm|T2e0=>YWnXTjW=l`Nth4s#~fb zI^37BuLWpS9(pZ3>M4^x#?62v0+y!QHCRg8j`+_985}sYDAi7wNHvY8rSac)?k<+( zWTX%~Blz4++yYf_mvqYYWRI!bXCH?T?{S)A(I}YJyK#d1LY+F<#(x(6x@j~DuD)=& z;1B5g*>FQ){J4V^kQ)9iV#2`c-thWTJ%x*W|vl~{0SEWXz>Qu=Q8PI1=bGA)l zXJmUTkqFyX=2SpW}4M?P1DuX zFx?nor5U2A@cnXS#cG$08CS}syy4GaY_s7EYSml7NF$2_{3av!isRz16HHlH&@e@$ zLgcD##1`Y<^PXgrz<-Q3+8n+D_+)iMO5<>CTkSq45)9?VFz6TD4q-&565yLRN1`*p z;@hjAB6k5dDpJ}xhjr#Oc}~7nkE~SMp{=vj7DX|@+kX-p&DspG%rD9BwH`|be(7PS z`5hNVJ6_}0zBj4@fX6Ypj7bnGhu>N@$r1wRf{cMqUopN;AmG!zXN}mCOw=Bm_+QiT5=%Qyf5p z$3C%@45m!;33MCusuf-ZYb!xt1)X77Rgd;{ei#E_(EcIVn7REi@v-v0^NfMuV5odhMwj*ICC z29^Sz5fCIokIN2BY}p+Umw6p!+#g2{I1PT_gO+?i@klpD0`%a z3`#j`5WknVszh^T7MW0cE-Bb!NP&_p?IrqDYHDajT;=>lxq0qsXqT5Ug7-%dN;WlRrUQgLDTS zbglFVD&Rjj%owtyH0~ZUJT-uH6=08!ymeX%BR`Z{VA`!))BP0v{Gxvm!8_t^^*+L} z@~oE?a7>bc6)b7pYO{m6peFv)#(DDBl&h+bWlY~f7tIA!3ztiSfBaRNeMAJi3PQef zIitHtVCG^d=Mu1T4jiJ4YG=P=xPFV#`^QOTum6}X4Wr4Z3fR*0OJX3bBbJatGjP@# z0bhHl!EmjHSDntX(Rv2p(4tEtIl#?#O2vOCsU-pJ;fkz3IZ>v$*WBLx!LAmquvn{| zmPHEm;8xn6nH7`pqYiHvy1P zpo_p*|NnaPE?EuE7Br^ry$fbd3Xh{1zzxCY(OC(&haSOx=Z;8 zv-u`&AnYFQL4!x-goeCe0v4z$7iP(8=Dv4)g@kHR{q{91X`cmNK@>d|8d^lUqhJik z&V=Gt1J`JM(A&!oDNRyZ3ik}bF=_&L z|4b7(m&0BCb3;lJtNf{M~-A$>NC7HP@ve^2d617YEs3J(lNw;PR_IiY@53y>Vu7__U5sOadwLcT5N&8{DFq$2GZiS8 z22QvoZ(${Z%+cJ`M!pOn-#R0vD#+AX#>&|ZFjR@JwB^qz=4*)&tYLDq21%7m7CLaN z@MKgX;G6PK+pS69EUAr9fSp#nol+DJ_c!ac@F+*S-{~!o)g%<62yT=~UNX_g9(9TYYmqqo4kWA0fSQ@90q z>C8AzbuHMGpAR@Fj5fQ`a`SW3oNF*`w5Vwy>(aSk^2QjUwf>8Dq_|t7Al*ZK_OgsX zP`)AWO5#3!YI?GaGzxXNy#+JV_5Y=-{~wqP)v>g=mDBF(?>Gm~L2&2N?QyxLePBNB3U$ zAHxf+$s0NQ(ME6sbXjXiRLrZtx7?CG=CD35Jeez9t#5qj2qhiCORTXNLpH7&ddpgW zxVO2-@0?xA^P$h5DQjFSQ>fqrU)CA#g~Iw4<94l*$u==t@?29(=^nin<*?-R=Cg~Q_+hl5PX0+{*bMxl0{~G8oNclh!6&IA1|H|DX(f$nuE`ouanbA;QfUy_ zii{5K@YbpE#TvqwT~}eZ(~*!I)$~0%49=GcAie=d`~4k^U>+~&Z(BB%BT+r+Ah_g;B|L0TtgJd> z7!cDjwZd-ssZ4p$c2ByRWU(9YCpt=IIb2eB7G_kbHAwH*SrzQCoe$8=MW2;i4zbeG z5D4F5;}CGpSI&w4hyjG0mgeuXz$feB@*+Q7p+99U!PPW(5`)tGHf9pV`{JT$O?g4J z2=hA*v<=A*+jqG*t79d)?wxlvgIN=L)N`qXIe}&ce(&b%S^cR(0#+e6_dSP~XSkl5 z&Nka3bgpaF$(0Vbta01V;Du>0e`zC&r! z6$$$()H+5|Q;6G7vM>Q|7arLP8r2gH+L(8V(s1PxmPd$<;0s|TFRn-ewV#NS47g=0 zmM)46``b?<%r;i+Yj9%H8?#r>!4zb(Rr z(DtGa{STPGfHrla8rnv7Ky4v*Ia2C+sCYEgBP)K*^13u>nNBPMFBe}S=_XXtg<4^Wf892#_n@gI^lzZo}I|7X4Xsop1nd!dp#DylKqUqEWfHvmgv~Y}q{ylbMg3in5BpR0F8T z4Qb$97AMQD8RTeG)QqPRWH%hyRR(|JE}yg7*MXoU(rx>Zvw?tt-4FuNGd~EzbQ@mX z$hNAY=wwujXiJCWY^zYcQv})D@LhU-l`l@iNF;OJj<^dO_wi>@4K}*CO9WCIg{>Ef zH3?l8hu?DJNb!oz=AGeRG2oDG+85@Wh}x>wIg2BEdlwedQ`&2j8vwUxNAry55_00Y zIJS{U*@pMN`INAgDoz`Ld4J?=>8E3%Woz1i zl>;CTR~jr!W2%&xK7SB}LlrHG;akzOo=qtuwy(YQ?FJrx^@ zC~BXGh{(tAMw?|E^kMX8-8u2%cX%UC*9-1;E!Be*_|X?wl$4tck@@=B*EL!FDT68M z?rzvTvPPJ6?O{%+gGUHIq7H3cn9O`yxsf6?cIL-5HHfTE%}QCIlkWj+LLvRdzq&76 zZ1lFB&)p+4TUy$iS*2KQ*;a*Od~1%J7g1}sG`4P=nm>p!h}}UuKoS(r_O~-@{GTjG zg)20Cf3^0;YZ)FA7;aI#gy>@O+TeWaZ`Di7OphWa_v+WtuD6scW;>|bIt-;imfY4x zP*I}{RaE7jLMg1EuAoOBBTOG=6X!u|`Va^a=Nqp@8LPXk4!dcPYjB{7@g&Vsi496n zAqT@Ac!LR$qk`?Bn3`a{h@ z6$*IP9cObS1=X)oYusj?@yv403tiPXEzK(|H1LQ!)u&s0jcf3xJ8QjuS#7s_!G&a$ zrnB>eSw=A75KC>z-Ka!%1Cg!<%2Ldc`b3YWo2-!EHVh3{uG2~1WXLkhTAVB0Piu0I zU0m?l-O}A@-}Mm@HVOBkL^b)GMOZ{jaqcCjwB_ifpoP-&^NbP}J2{yUJ%sU9cLzGc z1&&6przZF9LUIe93kigLZ!Vm~go+tx5B6 zf#LZwd1d<5SOeiiD)7mm(a)d=hRSw0Q?_r#sB4*#F|}}TS@N0E_0m z%t@JtVpgFGZLkN!NUv?h#hmi4ar`b7-B)q`k?>BrawMr;(d5jW40e&vA`3~4n4$Iv z8^!NN(!6e`Bg>Nc`q^knlX-Q`yhPu=x z3%a0u4?{=Hk(Xt34H#>^r z<)u}LrTJrHDUnq_lvGjxOsmCrb&-`@pXv>O9W?u^`_YjyW0j`&*&H^iJIQfAazSp< z$(%B|dbW6tCwlo6CYyqtQ0XYDLA`NPXFu?t%@au*OyJ(oEThn)tHc*3JgMN&=9}!i zl{i25{IEZbu|A*PGjIuj{&YElR9edlg#~^IfI@@15=X>zJ@2 zvBI?z>i`HwtlyO$WtYkLcui|MW|CCJr$`0O=1x*~z@rZFMmjd~@9q5^V|e{4uC3K6 zf+OGGYOvi5X-N~40n(D;epbXWEng#&pY=Wzn{w@rDus4p0vdUA)eyH zN52y6-qoa#>KQ>@TwL5k*gbz%{ZOz0Gm{u2xOVv@!ueo|C3tFGQgJK!x*PB=ncCK z?Ev-lt@o=(nQqMYCQN^i-<{jnI*318HS^kc&+>6ppzX>EAy@hTy#7*oiI+Mf8X{WV z$)aY)#a38_U4odEtKjlN*V+A@B3FK+PGDQ#>={_wEohpd+ki1KW`N>xsygb6M(E1* zOYyqZA^h^LJ2$A^SmmUox){^2#JHEkrA+mjNVWj6>g&gLgq90V}H&{J8E%qm$&-07I`R4OFlFpziB)|1h*2aTxfY%o5)sp z=f~g3u7^9q5egrzS4%eRzPCFPs()C^vf9KB@a?e%-9-3{eJipF?Bma#&g@TfBn(tf z7+WpaNus@rP(AtO)DQB9(T^mN1?~F(mk+@5aVR(JMe@;t!Gy8jX1`m$x7|tcW5cyV z$B5VUaBP0=%xWv8-5kceRg)inl;1AZ;A7L+0VgrH)^U2D1mrH$7y0D+pMS?~Cm8nO zv6~_!kQj60z`y*IMzGL!c1L4{zU52kOyr{%xK*pc9e%#^u2#+}>CiT`As5=ar{fxOtL-+{ zmKRK|$FN*Uh-DTb7K{lg!V}E*d;az4FaIW5+@}RT#fxtW{l=xe>`US!5gr zV&z9-?*!-$i^CH1F2RJ>VXhIl_?lm6f2WJUSUC!#a{N*i;CI(T_rh;R96;ClNFaG% zHs>6J%dqLDT{^{3Ic3f7u_%#t5)$T&mBoU>_y-E{a#E@14XMMv4Tzkbh@yGwiB~CHTu3)@j4w$TDi@ zHojHtuQd&3{pFHc>w$+Y&)eejZ(ctNzl(JkbU0r4#pRfNQXb*muFVcpNcDIw9=$3goAFlA7Hvq!IV0eR{bS zKaM*f{oog#1N>cd^m7ig@I$iC>odqz>N+m3S6nSx+PK092n0lnz0L{M7c!!>mHMK; zs{7+CKdjz=uT^CUHaoH34 zp&{pg!V?k@|3LYvNv|+rZvJFstikU~hHIJuwQ@AL7y^riH#<*H%+1Q?iMOk1Q=ue8 z!}CcQq3C29DX9>Pnot6}Yrg-IBQ6du`GGE{Z^H|N1b0QWOrgM9S{|EUpBTQiV)=zC zZeDc$7a~Wj}35%-I+BHswCgR>vks%+j+`uD76@wkQPVv zMYItkr67=|n)gAy?985wS8~-jS%)4xz4r|^;SD7YGitABsqh$?;Dr}33=3^ymoagG z(P!z)eQCc65~Wb#P8s{q^|kj8RDl18ZKdi?FQ9SZjZViK<S4%5Nd`pyVHA>sU;l;=<(mVU6}JyuB;HDH(y&vU7|o(2Sc%-YfX++YzSUY&nGPlxLIQ zwc`KrY4FtHezMpH5}EeVbK%tD{uFnb^$!%qOGNFt+8?N+3D26hkejf@?Te)8yjz+a z;ZlG5{HzG~)4(2xPXp!$T;&tB6(153wP}xAmTckDKTx*0wvY^X!IL|V7dOJgbpM3c zp_O|GJauy*_|Ngi4`-h-XY$lOv?^om>X{IJ{*H#pdVWew@AmtD^iHjZDWs=RyEZS_ z2tV(0ZF&oQcJ6pyOm8e+k&cwg^EN6)ox*o()0GF74H$>;(loqO;wLyb4mup<7h{?@~*1@VjKV5!XxR_?`bZK!6c9ei(OL8x_(YX+?`O>U`MuPwKyU7>M zq^`5XhV1$7b4y%P0GgAa9#63q6MS_$8oBjmrCkzUWk1D0osR%Eh zL<|pKp)@gV8#y9uJN*L{;?%+`7j5s<8C(0P**5h5wc60A|EJZq68C>;wT)IYH+jw6 z50dwoGb3>CwU)am6ty=02o<J&B%pQZRlgt;GV;EPVKj&?e0|+q=WaHekg}e*U9=>`6xA(VWepXU+X;yCIX9>{@hGX1!+@ z<{agrC|N!Cklp2byEM&qqB=Jd`4UGS+hCa0)cSb!=juQ*S2RTPu1#`T6D)3s@Ucjd z5_jL=({if8`0{TOk-!#~RUaNc8>%E*O8FXi6zc}3~ z*_Bk~amb_J71ERab;pQWb=1h^&?u|@G0clbFm1*Fz5-Z~4oG-(cj9?F!6%w_9n7+E zo zikDZjpF3S<9P(Y`vdQ5UUy|q?nTpMviZmT7l#m~f=;~5}?W=F$7IY2@>fy%Fp)b!b zN1Kly%0j-zsYX>$XQNKlHl}p?{=oi5Oli2FPfDkinKHoW)Re0$N4J{L z9@=M->=gCny{vEU5%cx2`qM{uz9GATCr*@1cGP73qCkl=*G)1v3_5kPxP$`)i*1H> z?^At*t<$}6J>45K!=Kl$>)GQPZxv4PB}P&Qbhc||tN8Z=QdC-wYJAkks?+1EZ&uWz z+e_7<9%^G2)p=a*i<)+nkc_6FV|?+iVPq@qVMe@?sL&<-mdD3d$WhU*-zAjrouF`W zK8~&=zrlu41=A~@z>8q+iT)5La`Pp{R`Vg=4 zoUiYGWuF-gxY-2KoOS_eNrx@WpW)v&wg7Fjqy|T-IwETtOrfYZZt$R_yGNBF^djmM z+bjo4Yh+mP>gjNYL4A~wb2W_}SmjEM-SjXjxHHB^UOsa+Es6EL-GUzyb;Hj01W_$n zF`zpU=3uZMe?~)rvm)BU?ZHW$JqzLh;8y3bfvJp+%8pNLK#@mOE^#l~ccFwivikcb z6h#WUW)W+UIXbA==5W5FK4isBD+2^huXoTTP#+@Ru?9~i$7Hse=>!5Gc7=KAD9E64 zZ2JmHbp%UV31$9>>`*pr)qQ4?^^KuN1yl)BUmnAjTv7q*`9vO~zyhq)<^uirFuM=l z+A(Iho#&4nDXK1QUem0$G=O6`F(()nmWAc?8%Ru-X4`|}>VON4K9DU!ewK!)%k~ph zJ;s5$ZiBxI_@{SrV! zInXOHI?yYKwY7?xB>jBm4Ei~#`H5|nj?{F67{r zl3X6IAg)q(51h;l>LS*{Q|!+k$IW8U*y+v@5rGwP4ym>-Uej(@$MrcVV#kIRl%Q0_ zhPF`DRKSvT1Hfaj(8+vSk>N_<;g^m7M&80EF8dkGLl;m=8x{=*C1M%%I1{)06BL#JB+w&lpIqv;eG_V&}Bp$>39PJG^`ih#m8q zBLLk_7U6B+2F=@3W2eY~%L!YxUudjAosy`#v)EfLz7(2pigf)-o5+P!JhI39qUgje zpql_fXmIn1C4uZ?Oq+#0Es7QQwA&hem0rm1h3=B;F1K};BSb&_k%sJX^yIxMQ37S8 zYWhiX)CP!525@P2Vn$_(o#&OEwZD%tq^u}HSiI)JI5wB0jxJ;Rofg=ZeX*Y8%mWe! zLWAnku+9{JSY=h~J`IiIHZ#A&Om&s$K%)dynT=YP0NDh1E$=?mg`P}F=|v~dkG<_z zFo{<@570KSf?TB@lgO2Pca4~+7Hs&>r!ehn#OPeQs&iZuAEk=n5Mnx zX3lMKDUMsx(@W^IltUBl@wE93I(Krv9$v|b<^AtJoRhxZ0gX^ohC(OW*~I5@jw^lj zY#Juz0n**5O@|5~neX4r{zfveFL`*^FRd+j+%?O8#;qwy8Kp=6O~P;C_-% z1DF5}52Le!;)#9~1XA`*K;1x3!9igL_6oiu>Hh61k&0Fj^7i%z>YB@c@(yU`DXzyb z6oM^keDAQbds@h>0uL?Tx3!YjEUxlzC-M(^^Z$;|Ac;php0D~eNuYAz1y9)BUwLoa zhnHIZm%%znk;H}2;;KjP5d!k0Xyf9l^fF(PP+w=8_ii2$OFZ>D(6=2~`iOgELAjE= zUr}e5g}1flu%0l;`6HFzgZ>J9`~Hs=mL(bNA{nf>YDJ@j;(P#FvM|dR+DHlMIkbuC z!wf3jRS+4;A1JLa-OnJf<_zX4Ky+1T8xq}>!I<$ukPz|SL0nDT3j&!7H3OyK z)p(48XD{cl6dukYchmpB1jaG5T?YwJs$8HK(zT4k$OPE!7ScujXIap{$x;3@NKul5 zn}LZCXI}vt+M9DjU_k}b8&bEiwQ4?#S?dm~en^DZ^C4`T{k;;E#^-O>y7+MF9Xq;x zZ*;r*t8?M=!|dbop5iZ$;Q56=P`%!jo&H^3q`BWy)~ib2zhGPe8|P+r&DILv_)b42 zrB^5C%xm ze%e^zzTNd88+4!iR0{3hd>!FCdC4kx+LoD5EH>%H!B;>$F%O= z-H}@fA9~QRjWQU}Y?9h|?>y0R_;F#7!JFEgC?o!}_Vi{3Rnw%j&CG39+wO*3t4V}u zdI5DXJ_y(kbld?|yn~^24#4};%X!alVe7)N%ezFSfwitP@f@*A$|Ul|w4p~b3|jsN z5o~}X!13KZrIR36mN$Omp-|?PpnGgBq8*hzxtaj%K^YoKrp4IzU+bEjyj*>}2)wY~ zysTis}XRg2S~{^J)1( z0NpBAELPyBDKf|FvKIo53o1Qz`#ji;dg+zR{lv17S7rpUzEUejx284(&eTL`gz#(H zP8|0zDQ#4f3Ra{ItZL6#8S5!$D@XSTSSuYlVmoH&X{zFYA73J?mv~T^+^whG+0%+? z0570Z^Ha{zuKMhn;@ujW`0rQ9ABS~hV-{e)401N@WtNFSf)}}m#gA#`(u5OpDd@0zYsdui%R}-B6LaX@g9OW~fi_ME0#2To%yc9w-)c;< zex7<5qbAqKFxiTa6IBDD?D3XchLF*jQBm|s!isb_;^TI8OfOhU4`!XOiHA>8#sXYf z2zhzbuIOwb78o&7H0#}NWA*Q|G#i}P}5 z(2j+{UcS3py;FjXew>Nguv)C83k49tzVNSMf{=f9X>WTC_W|g5%T#h?!`@=?r`Aq{aorIa?16i+*-!@B-8sHypt)WG_ zgVcatndr2HJQJh_%s;!?gOMbKMNj{(0nWc`fb3suprz>Ca<(bONxj1dU_MM?*qJC> zM0ndqj0TfYT)#a3gJ@ny8jb|C993^&>FO50%wGhRQ!l%czMon(N}Yya8PA>a-^KwD z!Ygvr90yj+t5!_tygoYqY+x?6FOv73#Gg1-q~G;KMMH05R4*>uWaWwGkW=KV_{xs5 z)@b`lF~}D`Qqh@^XQmUhZs0jbO+}&}R3Gcmo6j{JUtj(2KW$_%TeV#{PAj@g*G+v) zxy1#>Zo&b9*CAie+c$TzH95S0YUSNdjE${GJ)N~)97W&!s`}>u@Oq=R5#FaWR2Um5eJGDo9JMIb6h1TERj7jA1g?ez9 zORc%@7o~@xWk~iIuzAdV6L6{8>?oC%rI8N>(z@Z$ge-pcrjLWKWOP#}!Iy)bL}Fx# zsF&QG7n8AKqAG4KU2a1N_-U7G#Kj9h4*sDYYf^DsM)$+hh$`e)-zr#3Z@I0hy|^j0 zDZ!?R1SU=H-@U-w9dC34|BXc=VEgU?P8#YQ!Y+p0-|X1*yOaH;H$Y%3E$G#GO128V zHUP%+4p@52;Qp>bnpzJ1V(T|s9?^q)+ApgXyoMOIn7J`olZ#onI z9)Uz*x@B+mi3THoxM7&foKT*Q?p@h~m_qO#zrou+^v_Y4m-XM?HG+4CR48>CJ$!jx zNr6jS9_YN!z`=QqyU{4-6u{XjQpZ1;!q_UN5enRn6F>CZoH$xAAW0h58-V z)E*mt1>aA*F`*Uyw*- zkE3vh>FrvP-N%z{be)BJbC*T4C&bI+#U|7lV1pB$A3Za-;N#ntXj#DrSSPG<8OqHU z32E`9EXQ_vDY|&e$cAd~fy1RyI3}6VgR@BUmmXK>99w}=T*H;5gBpQ;BF`_W+t!z3 zI%jDJjq?gB5$)#M2(Inw>I9|ZT!7E^adfyJBF-6JB3KZ-H?RiRG=1;NVu?H&YHlAW z@R31xTZ+Rxl%LBP!akepzh_HIqg3eLRLL30oZywPv=re(qz_1sYI6E8fR9Wj{mXoz ztR3n>TAl{Zz4Y~z zE&7A5iWP{aNKAN#81~>YgJ99b&AcOS5I9&QyGA3WXVx?v(UAPc(awxd5MP#i7l@vW)G)-6Xs_=$)Aw9ClP*!o!~%J z8A|2Y0I0%%qGj}dT@ZCvEA_GXvV*{BZDllXvH^209t&-zat#OJy=LwTK5k0~q+2m^Qv z-1H39G~QkAYn<6wyPwum>Y$+CLrE|cU3|1gX1rQoO2wQ=Gh1=l?Yu*k*+a?rT4Uu& z=i}zE+hw^_WzKg=D71Up*B`Gflb^B0BZ?_YjrZQ?rBD|+)(@eAge@S07q32Et8v{GfDy-vtTnYn%6$zEO4B|n28M1ra~;o z9&XkjbLk8ZOUK+%O1_!!~BH|Jn8V3M_s}KUkM;jAL~s??x5G3^v*^+ZH~Z zv^KpsIxV5uR23z2A9Ws<7T2Y2Fcne5U?KQ^ojx(WM?8ckX)8aRi?AeZtqWg-KHEwkWjfYfKD9x;LqRd`K>aXKsD**K9TXByH5D`;LFN5PB ze8KizCpota0lE#{dFNB+7Ez{p57LeCBq`d_d`(UR4RXf0xnf-M>B2ae>OMGc5>%$B z(adM1*;j{ml2*1#^nN;|{{uBs+grXUVU-JNZv`A`e%YAMqSW<-`|c4clalevNvZ}I z6P?pq|H3O3)uEr|9>y3|=3z>QseBr*OyZmjS7;nzz%lshv%H~`>1L>Ke$Gd9p0e#o zh+jX!T!L@Xszwo8t13(7-tiShA=I3gWzTX)W zf#Va08*ImZY1S1Q<+Ee8W+Lh|alAE(#O_~H7tFpNZg+ucEwc6TCU9)cT+ZZ>LQJV) z*A3d&29D0e?!_1Nyr|&d#ymj`VxzK(j#ZDJUejpEJ^5Nr4-YoHK$FPd2Oy>s{!awG z2hZURU4^s&40tv4tBa+h4RKYJSi0RzrPYbyLBD?Gnk$g?{+`Vj21A+A8#iGT65Ql!kkj=SYrFd+{XrNdhfl zcW@b`e0Bf$J4*%2bx+>DS)SqrBIkLwO;D=iA$6D(R})cY`3$9k^EXf3|Ige%kObu7 z%7W~A?SNwJGFiS8u)WO?sKYq0SD+5kB9@^3((vZ!>Eqk^?hll6cs_nokX!QLgennYLPpA-p_JCv+b!9?i#bL~_C(MQp)ehC$Eou+Wqb73JI9p$2nv{1^Sj7LQ3`v|uY$&$-l^@^PbWUTd@ ztS&in*GRdt(Y(ZHHeO#%6;>T%*_AHuuk2jj8UK!J*HqkC+`=~>6=@vo`^?I}tD-M! zc2poax#_soAcRAb?}VC=;{^YFe?8*KEWDFE+Ay}N$4`F5;;vEESSAoCr!&-MhnV&3 zq_w7DO=+4XNn73mi(X0|X{3J?>8P=vc`K>s$kZNTuEB*u3r_R;R zn3pKGr*dcE&ry@~2MYSr@_vJ#3`>mEQqJ$04yE7lYPyNzPn11eq#7PK{3joNVJq0n zvAFiVMcPF6uyqwtJ5RsF-qBc;o-n_zY0l7(x?|LueBIfU5z~8gU#{C0lZ_Mz0uWJv zHmSJTV^V36;7GhwCy%-EiCuSUKphs1ZY&`h?&}0@7LK@XdCY|fZC4|rAuRUCGYdW`l1>s690h~>M9Z@i$OxS6kc&NeMtd~bW3%B z*81Lmj}X)P=IFAAck?xATC~UH+mK7c(;AUR*z9%w-bbC{k>G@(ttPe+k)J!?1V5k= z3Ljj4_-T-Kv>`(B@D zu1WkAm^9-`M5_MEJxknh6ZiJ&dVM{P)OHJhcK|%Uc6+*?!vdt|Zug5T{x3hO*)Gy8 zvA%n`H5SV2$GwEOe*ga8SUb-|j=j+cfbGK81^MF<(xZ#Df1f^%Hz9XBOh^0G6 z#g`~f;4)&>6bqr5Tz1&n@6<*-ZAw)d!5q*LezRQMHRwy$dz&l(H_?*mQHGPp)p&cgD zWYg0(mcxVyBTV(4jG>*T#aY{`&q?hjyPn?23U|bC9ux}W3-yf}3*2d6%{pw?(l{)K zS*^|}OPt*Cy0VFni*|Ac_U!Fj)B%UQE_MHW$d^{T_`h18;w1b-i`H<^1Umzqfu zZYS!cfJRhVZlsx;A8NMg4WO*ySx0vXzku0$eLpxaYa~M$;~o2IVn#v>MUEavYV#T_ z)LKY`3BiWx$p%lf4jWv5!n`(DbU7A{m~E1cR*UJdq|Q_aRaHW)D+gD#k<({p7m{VD zSze;U_G-JPcu`8=yf?uHHCrZIU`ivTWjZhUASR%*%r_j+J(Um*o$JUq?V__`MczLY z#Qp`)_W;wu<+>Xvu6p>ptLF|VuY%Ry%fiwvu7)LH<;R>YMak>6V8>Co0@2VS09|GEg0rhOw8=G&Jsx?|8XT8 z5uJov>79k{d&|iR^F#y?3q?{vp#S&D*CXX!|7tY@=97QFi+^ylm(~mpqJ>UAl=ONf;YLdMg#dvG6kz z7L>Y**twx82t+ZCR|;+^f;I}noF}f>Yc5AqZ}0P3AvEsvU7zMN3da6>tL3bE`$E!u zcjWr+>kxs)UO;r4o2sr3jHEr?*Mk`!@(^yqZ|%-VwfXS{L}T1 zJaQqYpsHiYH;;4%3Th+(s|ss0U%Tf}JlHZr&wgL`Rr=0+!L)m(7t?xK_N1%&akhg`D=H)O(ENg@6aji3sxqtLWpNK4$^Nt4Wz@n=D5V(e#^H9 zotLf94YcvNA5Dhdj8!V#HH=Y%8w7?A(eYCTxXUp89wAFCU|Wip6KB2eEu4${agGwr zCU~Qr#ak7%AJ?#y<+4)Pu>#-$lNGgQ>0mtwIKh=|FtRxoyNG&Y^H%a*+Rl zZ^CbMbN+#Ee(u0&vN*VAIe4@$Z>(RG8&-eLWAeOYGz743Ze_ih4yw6Ooizs&TbN9W5nH6;8}E0fbX+rXa&&%bVT_gU(3%?26L;3IAFEVW%Gc^M zLsS7)dKOq+fK=nVww9y(oKRm!py zGidgNPcy!n;VAYYycU=t?D!swzt0rNPT$;0N6;02rrdb0i9h^y80ax?>c@K&+pbAI z3BbDf{DU}7`jZE!^o@_s6jx&fMR}?WOuv7`&w;VOYcRcloTK|tFcQ{<a>2v2siY+*G%ewr_&ZuWvYwNa6fD~#$Jgj(sM0@M%p(h!nSjy&?X<{6e zesa@fizB<6IAw%V_hL`b!=$?Ep5~bj_G@iwIty^TEaD*f5Ig*oq>;*iEk?8H9&IC$ zj#XE^7-o5jp)MJVO`&ceD@%nzAGluno^165s45xB_0z+0YjZ-YPz>8-Q{tqNtHCl= zYGGOXP-E7cjbyD8r&aLd3-{@W zErWNgy+=d?xuK#JWV&vU+0;~D97@^fR_izf9QhR9v>lL4B0W@#av@{YG-c%6A)ac7 z^(-RaF!h9^4V$2ohjN$|jB<*LdCIle_>`4Id>CcIq?gnPh`v<(!DnA6Yl?)QW^Kzt zs>gKxN}ktLb6efHoHZ|wOS!sNOQ4s~!9pTDNJLPB!YiUAaIi{Mmr{{O9W!zr6cbnU z7g)zbU0Sxu2|q+HnVD?5AY?`OKvJ3BUFH=KSYAwBK(mqJm0;rai6xk!-EeV0a>26k z%MF*nA9fPM>l7#9uo`-lL?)twxq9t2!rYC(*9caiN|W*IK5E!?;sMed8hl#VXg-TK>xOIsXY)rJI8Dy5KHf*G|B~y-i&QZ017I64%aGY zG*Wb9y2i1+umq%6VBLE{Ag*TzkoF#$9RMi@(~!*3e9WN0<-bs4ZI^xzMFq`jFTvz! zQVHq#&C@-!>;}fj@(n({SY1(Sk8o#5Ah1p$m%EzhtaRH zL!uPwIx(ynKgm~vi9gm*(aYkAgo1`%VWH#2`$XhX63yWT%Mf8iNJIeD0o}>}J?%pl zv`2(lsEoy;j2QaHG9uI@F-C1~9018h`7drF{{pi7^F-kuqSr5U4zmgndIkkq(Bb+{ z5gV*Ra29D0ad6ul7OYI#O$liyL_m%CLGR@n-RljFt&rAd_R~37FwX;$ZYDcD{tAhW zudVX84llxC`Hk+`dQnI>z$((|wfVa{*GOEAN{0O&OR!0z_cNdm>OXm?Nc@@q7vSZe z2Dnw7CoIIAHz?9%UAd5f$BT>;Qz>}4Rq^9Fh4E?$sVxGBiP4Mtza*sf zqZJqM)>doj!|CU85pu`06Ll--YIt!ni|fyS&Tx1+r*L!0>Ob*!Zu$+x4+Z5fKa~F< zx-j(-{#;vo(Kit8NKSBCan%y?q9dJF34VUqmaq8RwpP;wA{wkAecOITv6i~Njciha zH7pbzd^l?x+McaacTMWSBSEi17-0T|eJ=)?5Ys=_B3A!bDvc~C#o0ce_RDWbri~X; zAR@#TzpR;k6bBH3^S7$k-gMH6V*KiRz%`$o~v^~Sr9jb7P87r zy$uUfhT3W^1(~cv|HbRL(WsDR-~=nBa7u)@1|K^(n^!R@C~ay^7qFB)RevZ6Ftww+ z2%nrzEj@R`Oq}4pjjZ=*-X@y&?xyF74NkQ5kS;yJUT{^H4y!5erjVNwnBMEzq zHPE(4z}VkZ9dv30c>oG+vkeImgn3^$ttw`wt1nVj!xXI{&f6xkhIY@=TxQvIR;(_? z>R?7kZA;*1ugfSf4JUY>!9WMt&&wmzK^)b_^pD?Fn1CXb@~Hy;B~|B;L7; z{$qN}=6JGXC})bA6`y_77A<)l_qdK%+{g=Yly1;^LuJ7mK-2 zLlWkTsJl&BR>4TD$8IYFVY-1c>XTf5l~qF9GfSK;Z{%W??bXohj4m+ea1K{g+PpuR z411GB2AvP29h8Th$Eboc1bDPOg=vU&)+9Fr#+F+^dHP@BUXJlrXr*MiStTm=3dk2e z3e95hCm3yef^+c=aLu;2kgXSg)g0us3*t6{I)^Pbd|#8@=(dm*F~7NOd0Ufqbmjyb zq$nO)XJ8)kFz+egxby^b>m2J0?Lxo1kTNkF)$edh4G{nR+9y|NPRha2xoFor^HQyq zj>l@~pg$(wdb(aAH6LO=r;ha>ppPtQ7K#g=q}P<8PBFUOT0r#l&m zf6ApXaadFTI8f0GlRyxP;v^uWc6g9$wiNXeAV8nw0XPP;6PkG-N6>skg!zv;rdvhi=;i z;1T!gb_4ZSg{Hc(;S3KhmkA|u=QT|B#acF;lpb7Vv^K*J=37QY=a;6tF?$B7A7F)-Neu?Uar^lHM~KTJJYreBqeARvbI(yDHmp>2rDcSiY{K z5Y-f3;~L9Nq)>%D$aK3jmgI7qh?02UxD;I$(JJiUck_-S@t75n&PiSquei!3gHcP! z49iIkuPJ>SKZsjcQ<~ty&WK+}ELVnVqt`OSpWRrS6fjw*YP{ORC8cvD#mLKKhoU^6 z-jtpP45F4{C`NI=s-lsTb{VJam}{L0cPqSHNw!^(_R4qNQQSS=XzkJz7!>3M}X_^+9d=!0yh_)E`phV5>K=N4A`ufx*XB|D) z0HRH~LU-M|i7xx{yQjBM={jh9)F3rV_KE8+7t_b6Xwl`5k&9z?VM6q6fv>(;^-9?Qxj#C^Zp6EV-e<|5nTC{g5jVnLz zxQ0?Ll>V%2&pRLO_`D1EZYermk&)t`l6!hDB2 z=lZ-(WSHM85`%*RYh)Rr!3gL3kzxBBy1KpMN3T72&qZ&(nH%+CR1ILXnCuh5%J@2$ z(q>&e(JN}4T2oY~^k2{s!%Wdys!whMt@STG>-SP)%RNdIr`w%IjsU;V;qrC(&5|yC z8vvDFqdsq%pjot7unH$iJ$R+I6UH7<5@;W-?eK6gq0eTD=2A@zVz&;#K*kR6vM zMBM%NHSpJYf&y$1HFn(1pgmLR=e0QEKGxHBD!b_|ALKZDL&*miXba5*GB?DHTp4YO z*Nq`S~M>6x&pD)8*2J6f;fY0LkbCuikHTs=X_@6~f+ zE9f4FNT?0HBDqrTC{G>kLMHOOQc8SgT^_~+O-}gpY;<_0HZ1eV*lLTdeIa%b4kB_J zf;^5F-A+TYx(`_IvYMWdgRbvqpC)hJ z5_;&{>MFQ};;d{|?-$r=OxAx8t#I{)aYA@yK(`(Ed&)mhv`P;Jdfz>(*PH)pghu7G z$iugRqJ=^nT>!88BAZSmy|`vF6iuvMS5TO{Dlmr=NjDZSC`?sd^&DkBacMVHNp73V zcO@vN+bz{yUN|@AIN6$B#+s(5r_I#n*^F0l^ifDl$IqfqYqBD!FAUV5!&uBJY}w`` zHaBGrpe?(WlN2Io+IkXYc18D_wQlL!_ zx5!-0t7wgeQ)B98Q*(YXlp<(IY@(ImIkYmg#UaHBF;U$=FOr*DwIv5Rt!p|N;wdIa zS`h^xmo$kJg zxGvV{t@B4 z1o4>^5G6EeZWZ-DGz|TZaWDaIn9-!f!9)C2E_+1tsz8kK$sW;ytxN|)xyP7fodUOn z>83=Wls)3Rga3!Sw~C4@+O|atcPZQn?(PyKxCM82cXtB8-Q5azcMI+i+&w_>;7)Gs zeeZr}pLfsxc)#zfTCFwPT63*7N7WpC^wB$OBtpk`ZrY2G3rwqLF>^i>y~8|!9rj$eN)l(bj7&q5*4c<5=Z;D5Eq2wUc=;~^j39Ny!A z9q!jK2U0Q5!OT=lh#^e5rsVXn=d7iPoOi4;FLLNJOOI>C(FmEkaAA&3x`d~-sGu`SsgO}X(O*Gp88=+KoZ3Z^`%)oUH(PqYIn=WV z&CU21)nje?S(4G*TI%uFJ@53-t2aXnW|+WA%QT1%uyk6`2rg6ycyPO!u3 zMEd?%qF6Br%NS;?MAZsTbf$e7jLr_9&vAok-45`iA2di% zI)T3Eal&<8jUuZzMBZJP4IkbgjE$|Bm96jiEVJjh0hXD(J0-Ltjf1)h_j|qG+3l9< zCgyRy^)xitaG%2xK!bH!&RMu~e@=X=Jebn0Fh8f`>xiWr`=Kj0+yASz+K>r9N>7?E zT~h0YJxQ9!dLEMa6Y*#bT`S61&D-iFmP2sd27Yo8C~>oi_tGN{`AgJv9K|xVs3-Kz`X)DmB(YrEBh&7_hYl z;Y&RqRnItlg)o|2rQ<;aOyy+C1{4kE%st#`=MX826xAbq7Z>+fjV_(TY8tg-wK};i z!mG*T*53$04^ui6?UdA31+u>!A|oVt(7H$5D`PKMda*kLTN@^;TR37GqJ0rk8$);Z zl^MZ0q<>mp)2#YL=P15q!bri{?1s!i<_s7gLI5}XT)B^?kjM`^r?xVSlNe!xnSRa2 z@yI?j?zP$3U*?DXrr;9|N~F3x&_qqfnQ$qq{uteJ2R6)4J&fXk_wA-~n-I>sb1q(xHMSo1Ijk>y zwx@e#SoI^v-I1%(wi44p`wE?KT&pcIgNj-&%=Lwh9-wnul9eWAq+b5PNPl~?F}WF0 zUyuf~jdikwiRn7GTQtR}?#z^@K$LaPce2h!CU^G!^zSE;BY9b;NZ7nfDNt2q3Rbf+ zgsi$Tpjw#~Rh-A*HV6})5;V)oSg=(~+8<7nFa`?9Au@0QIFuIw`@xU)jxk^5V(w+i z=Jqcj7Q`syQV!yiqeN0VG~%fSJ9dl6(hWuz;+e&WIe;u=8I@^MHgZ6Ogsy-&T%ET5 zvDtw~LO7RrNQH`Z$@&Bxs@r3_{9=hNKFJY^jAQabz_2zO6qcO0K~M6}Bv>T}LtRfO zGb$u|Jync!>{kZYLAK7)u?}h@k|D;9Omeq*8}SvjV)|hbWP_UDQ78krC=1wbeOco; zIb8xK+my*jI)i>{rihYBN`Ed09uwg+Mh=jNtLo{n)Xo_5B@+M<4xc3Uu_Qe5FdFq( z4;*^L2qPW1(#C;uq9z4{Ob3jcHJ(XibHqD&8HgRo8i#OfWj@Mb(67y<{3{3;2IgwWxriS~B#;ej9Y85Q@Bir6TAR85`h(T`tyvtl4(maR)ORXi2`Is66LLQDSxthd zp(5PsQb?45Jd=VF;rS=Hw+*kn)LS2Jg3`}3MZHR#DSi%zWgCJPq$2MT|-TydxIk@B3{Rmyo8vRjAbm5?A(;~ zh0arplxf`KkFIno>tivdNWmDUBx{epFnF>f1yN-R<5}$z{WJOECg_#l$$T|j02At_kw=Eu9>FgQ

    WIP0CjhZ zweC4KcsI<_RtkQ;MczM7#V9}ARW}w%*GVf-+HT?>;xFn|!H=_rXZa^e(ecse&(dN8 z{y{_S8$(U5q?jQu*JgJs&xn_Mt&pvUg4mdDh^In@vpx^z=+8e*w9Q%Os7mdGoMK(N zTyCHfdQ(ajL=y+l>WJL%je%}bJb^8~p{j~Gqiskt3bGNZtBkd$i_E+WFTpzoDruLU@J9R4;Kr{WlaH0WE%y!*>2f0e)PyIAEe(cq$E^y87*X`iFpPM^ z`M4b>!#V^BhGOy03E+hrhHQvrGWhY^hYOLV|Cjr!RhGG^k9$&U8XJm9P7R0q-Wh$>R?;gh+&Vm+x zoAjV+n`ON<$Sdb@*Wq@-;U}3VX?z-ucQOt!c_yuj^_@(XU=&)P27%>wWb-Xkdg-+T z{671H*k?WXtu?QexHuOF4Qs!x-;C}HT_qIky+l1l=$$`~0r=cw1yAFpi7?9KGFacL z-9h&eb|=5Hj4rFfp2QH&CRDDv8e&7jF010s_I~$VF}WPXm~#beYS{M(UEVCjoF*L^ z^CXvUcK93=CnPKHNt|9nbSX*l_&DijqA0%5c+4plWLrOK*6dNP*qq7|qhc@9E32St zMGhy2&z+pm))3cDsqu)r!<*7f34#b?neTSHzf5M_i9emOo9o@1S}z!+wMxtYm!}ML z@cd!*Vi_4OaxSbr6BPKe~(eXxkP}Lg2t>a<1IhzUkZ2ky_Q&U9LpC6 zo6@@@p!r(6>SMBHRkSwP=jP#Kit-4m;0`y0nt_Q!G4v9lKjsFlnpzAeYeB}aY^BaK zFis3$$vypf7Wf};z^AfP*!$R~Pn_zx&a0o@l2~dtuj4QM2+c(~*+M$0D9hN@)O$Vc zwM#mtVtiQgDj_DK5X(P_23gbgrU=sT+OH9@+-1XjGqOPMc6>f@zj|9p1lo9%Z{w3_ zfA{mP4-<6>Y4wQhz{lGbVuIoON?Tw_k6ueu*JBZlM9Yw+ru;9+7hE`ERDH(-1THT2 z9~|7f94LJ#`D9j*jzgBreu*#M5;KyyaN=5=$#%8CaP($d$V&6!>jN6L52dT5t=*0W z#@oZ(I`(`1`AH@?*(H!(a%pfOR(yDpeAJo%w5utaDBb5eOWes2Ue`x zmu9_Dw=G=z1(6w1%3RtiPiR(b3L>9}3kZN7)hN}vAAED)(3|C}UJI6n)}5%BG9|iPOEzA~d3gNnwnx~aTYoe!a}yU1>ah1sgZQX2DYM^* zLR9aPk(ODNk&J5fn46H{wcDd8EktyQfLY*IL!939`5`uett=|W>XP8s=UTT5Zsz9Q zDiYWIZxtkYZsHV@LQ<{Ic_&uUklS>*eq#43pY=U^x`})IwO)QA-htdfR-a|(b<@`; zzCAn)9zKcCmljm~`Q7M}Ayt*`$l|Ekp&-iWIE0P^QUw5B_5FMLNY%NZ_X3DCve8lm z_($uENIxw)6!6wS^AB}}ZCo6nxxx8==dW-R#CF`>GL|ylG)9WkH#rUouZY2q5R9z= z7Sw}55^tQeBPCMlq&l&VB5w9fKukC> zzXruBxw;9+G*&KDbf&J)9e;|rx%#y++%~9Ek;do~b`V=dq>$f~#?Z!gnMbm*y1;5S z6$pLfurSVSp+BhIR=m}LbEH2=)Iu=q&9x?(FoPQHae}YRn#hhNQaJov*2p4Y4!gN(U`0?>w^8)wlRok}?MaL%Y``y=t=hs^j zwAUrY9b1yes)xwuXqfk-va4Y=g7E#4p%8i23>QN>Q++Z{=d9|Is|hD>`9$;7dlH&3Fgk7e$0A1THaSr#L&yu<_Q|%|%vr&H4#^N`L!a0iV&kfN zS+{uX3KluJ4wPVOT+cmb_AqZj3;k3*m+D=p12WW1(1P!cMBKECbp4N6?&Vqam1e0=XBjKcAG z(pz``t*4Yo*K6X3q&PW(0R42Kf!ySjY_w&R@Gy zI;GY)ydRSJ1l;r%a{?R@Nj0hps-#_7v*t4Q@t&eF=%z}ao$3`udMF>Ce%YEPK`UAB zzEh`3t(hoyzxPUad+zHTeMf1Ydx@Jc4AZ&&eDe1G91r(?T6WcP_`38e{x%%^ajW{c ze}A?UqlrOeYGe{q=C`ZBw~@x}WbQJyzm~py_~6dm{wgsgr@b;R)-rQ8Gu$L9vm7QW zHJz1sDwnD;(CC}QI|2yg+sxv zZn-l)EZrJPs~{#~!AOHV16(-r&>BTW-tXh?nwa{}{lV@37;EjTLqbF}Ef#T8Hx6aX zaL2hobIL;>fPXgdSa$n(BuM&LncurCe5HATd5eSeI<2@9O}?fV!jaZYY<{R4+ic1Z zPHimDm0+1UKz`E9A(K5LG}(SgD9+>eAaetZ5K7`BOteJBrWaA-4`)RPFK-Z3DI!`^ z^IFm}wW(sA(B8&_H}b2Al7bD^6BBhtftmTF^DB?0r`0=J?O>G|EpC}BwyLI}EO##` z3~n0A%*n_#XZPnZ`cJ)mnA&}>EPa*+n&&TpJ&1>c(+)8I%%k+9=Gnh@6r#rS$V>e& z>p++ZNGPwQ{6$0e& z=|96YjSu;CWMpdE(Mu-Ru?aNzi2*~(<2kNzQZjX(F3WlVIS9zUS#nmBtG@5vA(T~w z>o!}n!XQ=xEjY4b9i0K)%nDd=V1ml}!RECWjqXb~DDGihf9N7mr2tP z#ujsAJpPQaG@PmN7trw9dEa}*H^L!(pgUo(ExDiAa_As47N#-^@9>*loW9gzS6*$l zLqv+(z@-#6hp0W>crv!O&BY;uRA*hY<;c*|d$ZmzKfDAOH`GMimmAlO(`E}O`dw1u}_v0q`>uX*#BTFzq1 z!rD}O-t6a#Q#1Y187?(l48d6p7!PG~1jPvn_A>ZO3eB2j{<{{p1u~XmrDR2(IAcW$ z6OZ3M>g&qluFhK@u>3u9eO*aR)f6Sj;l2XZzr@8O@j%KL^n1gdOpB7%15G*+qaN>t zWRXVfc>5jNkBOZpWF$x-YEJa-eZr@>&*(Ub+9NOs1!IxY}391iH45 zQlU>bC;IDyd$Uz~nO>q=8uk@NLY>U&n=N5hue2hP%}!m?k1o-PmZPF3g-z7-k^a`- zj{&rR$lw-gsq>*#*tuH;YPkvCFa~auTHj10szHlj9=>YVnF_uAWfUgo4x)2@&7R2f zD{iAZ3=^;KoEJqAko#*{`w(QHX~^S9lD;puXO7a(4o8DoE7KR6P53%lkhZ+NfieF4 z=MK0?y2c*gCk5TIdDE31zm&6>^(s)bdy+&Q%po9C2_2ragfh78T}U3BAEaM1qc^T? zDbxurBv%W{S@N}mbR{>YFRNo+M|3o9Zf|I%dkpx2blPSyCvHEreiy*9Qaht6leZtq zFKoS*5Sy-N`A(qLq_+K=}V?a zXbTDpb6wJaGiJlU8SG(w<5h{LBlhF-tD}jfV0)HpZ0)`1XRDQr7n%|k(b`ZPeYH7J z!hB)+#z~@z;v|^?lfm-JGVWn=>jY?dibVkS3qTK4uh+yWS0li{Gi-^pAoY^l^e4vu zFM!WaXewO@ZOkd7B{!3`c;Z^qw(9T=gZtLkMy5O49o^4;V$Fn6lx#F7XGph4e0>4= z4u97zu;ORGaWWi*k2@;bm}rzgi-dC`($(PhwHME>*D#v<<7B5maz{^~(4s`i0Z89^ zTYEs0cdb)+@nY+{8OxLIVVrrZQ^1$3;o9@^RI*K3{pq?=bUEExri`Pxs>-f?W{a`X z$f08vvS;bq!I-DN+7Y2p6J+yJya^fX zSDDsum@H5uCCmgYpOh1_oWOB+Nt0a{xBV=3a0s(%M{JTQQ4(yYRKzN$_-Oa3Z-^J? z`Xe_k#m_<3YBBt32hz|H^J*_j?hE@tQJUxoA^=U+dFxCBm$tW_lSgb*M4qgkCuI~H zt8=02S`Exyba2jC>t$Kf^jhmNy#$Kr?EgK7n zD7%bL=^LW8rJ~vr+ZBQ98g$06Q$42LhgO`_*%&!h92q+6(LR$FXVL#FUmAOfxVti6L>VqBbfCx1;m_h;uxpEBj$JH z1{g`N0}fN7p2UU+ijfr+9!aT*wwAg$w)=XpXQ59U@s-b1Q(KJ{RxuS`6PR(+y>O>Q zKa(cWX%b+LsuC0d^j!wAe#rj7rIsD+2wPQ|9QROTo9|?DHv?Ha7?HM zL>k^=?OoMoO}!Ex>bz4j^Jq2wMm-u|wrF;{aNn~tndCJ05*Tn^ij69Ekks%cTvxaA z_ipecI{KYN9`k8p0DGbAP+KJu`g}s6ja3=PkffS~t*->Z(~`VPg}@ zx8e581^HXrgi6{XCH@KWaB_)H)h^{O)Gm}%d_ko^Naic|o>))Y%(?J^bcxh9sw_S0 zRW_~n>d!6oIf*~b3iopmZxSD~?4b!VzH@l&uO7=N^9CVcML(of%i$kL>pn7-@bFm` zA1$|)MtNt9icwHtT&EoNxnOqaLwy-8tw%5@u2TsjdV3dD7}*HF$!G5r zKrWs#h&3=e2R`=f1V@zq@I?6?t@B^Na`ab|XR$pn$FtJ-c^5=$;SwoU-7l^r|Bikg z_HhCHf=@X(+}9zlq(Dv4js+4rjs|1PLYFR%Cd!XL0uaep>AQs^L_T+tyP?jm8>77a z(_F0$+UMXr&iM5F;=PkRMyq$m6fJ*LTzQfx!Xs?&&&L)}9vejU_8YASOzXnJkQac* zlITn66#-iw{@cXN~_Az@1+LlC?G-5snneq?9vti$FShYqJu z^I9UgM`p44Rp(ANbJ8~8!esa~G66y?5rPg`H3F~kbLXn=GPZQ_mh>8b)YH!Cfn-Ov zLPyfkV8`i1yR)QL!!{iu86g)@2Z3yZ=tNJy(?v!rb0(uOP65L-y& z03R{R>Yj6;XV<3xiWIRD#?Tp|s{u|7(`m4{H1pAE%C`pj?k@}sZ3z=OM@p~W^5n)( z^eRu09hPg<03Q}$qKVKpwX-=71G6+nTKf-?W@jH;SY$jSqz z_(zOaa*t-)Q>FP|KnB=&Xr{E>AFl44I`SRwn#QNj@mg*2FMzG>FCbSz=>^SjRRQyb zZU5`N!Ong~`iCjlIfXx~@Q$RfK8xngbSU?UgFZ9xh#M?u zTv16XdiIL&kNL|fMfLc3s)7kgXB19<0T-40pgW=eb7Nct1~Wa5;0)Oon82*-_$?&&mc!j{sHtl}4M%H79JFB}b$Fv8FWg=w9h5udtt zyR%><`4^L9e_yE`Oy{bG=y7f5EY$V2){?yUd4wYVo))3=CY7pY`Z3n8pQ$G@u?={( zi$x}>o92dfm&S?E@d!kn_h!yc^s1e)_-3H$b4Iwg*TMtaG$)5u4)Bc5=teJI7bW1e zd8s$>0)QYUewy#s5#e1&SmGynxXsW3JNqD}AJ6?hF`}oBR#CJv*|$UJw@+44WM<E=x$ZB(M+@yu-zl&!v{LoX$A-)+ z&u;>a36{ye9S(Bc!@OgY&oAS=+02mdC*4N8jl&MTSV}l*^F-!%Zq|f;n*#@8dQ|Sc z`Eou9)QXwPGWIB1Q(90I-dA^2XH24FzVGs;cmv=ry!KdCwI!9qDc7CzP$xMr@7TSr zx*p+GyZ5>66N@cqN?XUxR{w!Eu?4r!cplM`bccYFE+ zS2eYR0G|X#-7$3Risi%k&(%dWrkC8-uv9TijWCJHQ-+DhV17lMDmyBZ`S`6o3R?so z@EIO^s8mV(5xxAaN+O5bC-#0P_Zb+!GBJ4mTr1n*$X=qYi4bMbfQ}YWCINklHB6#> zx*D*nj1}|{-zBc|Z*NeRd|NEav>kxD*E&ELw$-~5LmL&`*oNGLakLrkeyErJeN|8M z@cg1gT=0F2^|EJz`kpoW59J`$sW&X^DgouwA4D-Cv&|sc zTL~|oKj)hMe=y8;94G3|jq(CwSh3D<`|ezU!^flR ztG<>No*VblBcYOErXR1OhzHGU3lp_9_o=XnwoeC8u$?nXU10kH4ua4lh;gz08xdY+iRuhf4LMKkkW_xNo zvQ>{LN!*`BcCt5^Gh;N34g1?Eoq`D8=8H^$3BoYT zuJDd)msi(nl?=zZHICD%Rr;^~s@lir749pOOoag~4YNhq`DSCi(ib%Qk@4>YwXf9b z$4{i6*1d|@OuJKk4~ATNT1@q(96a0ar=Dxl(giZ|Je`quG;@i3Y+YvBmX#F$`#TGO(O$%6VkNRF<}cS;^m0@Bg7c6Ya+wTHd6HE|1n zaA1@0M5-XZ$ZCHtg`)l~edKJ!^79q8PcDMd$;;Xp$639v_CjrUOLkwMn`Ef%_x>#@Fa53%$`Hg zeCi;`m>biVK<9YBX$rSaa@CFCB6EB-Cqg{T5b)EY4SP_*_*hc%7@mQ}XB!?a0 zV3ge7^cb8{v4#7qQig_J22)R1Fk^CE=d!l#@O$a$D1Q35!T1aKfcOi*Z>&)ad*h!~ zd@8YiBemVe5;p zA7@JPs0>paUHiu85E3@tNVi_@LVv>l`y$2e3U?YWJ;^bx4|Ratv_}2wE%fj&YvkZB zE3PmDUkD_l>l5^F73=~nyk_i%1yhsk#8CQ;W0$K+y~{FZDWuH>OKOjhz87;1N~}t= zAkhhDrZ}2|HRAV;4|kSSS1v#PWUq*NCk8}ugfFq2Yf3-I1Vr7IEeW6F6b=gh1(ZS! z&2BGgg@5$N3Xb(j;18arKhPbqy)ew=gG;RSO5tIkASaq>z`o_m!Mz6B_%7A|G)y_b z0xWwf4;NY1by`i@{rTib;)QmGRIRT;ku84C!0n~%J@~sI7Z%jb+fP*Lz{dK3KmXH^ z=vz)K@YE~8bK3aW(t6+bU;lq*t~zCUr>h^(du<6h{{AFxS{?vS0jVnu9d0u{#*}~vJ;AXkg-mi%?9BJ9jo-U9w~6txr1)| z;+K01b;b3_F7p!sg)xy1PXQb*U_}cSqak=$nt91KwJSy4VGo7^Lmyl{kt44(rB*Gi zl!f@3^_>+S9v%<`mhm@g9$7&GR()WPtnMCW@BZYIGP;_>laVtIY#HH z$1i|5HaYt*lH6a;cp*KP*El@B&fv?z)$~`|=tr>Ewn+$Vd|iNsYgy|`<1I`4*-{fn zJ+H+pM`+H{6hu9>G;5oK;|$h=nj6w1yS9+&qg0D%x(Ivk;kx73m2 ziRHsgQu~Fr!}}XK(XRdwqJW*S9BUS0wW{fpJq)JUX>mWTn64AEIBT}vstYm0+4A^N zTt0>QS_!vNf4PGnXG7>QP)`3=$q5%rKY2@Og%O!*9QF?j0~636K^SM=fb4gxfjy0a z#HQ^~3RWr^wqkb5AzhFN7ip%0``d)DU-V_#!Hp~OThn{;Io-^0Z{HB!M~z+J>Am12 zN8OR~>n}r(qF>wi&z7&u57_KBG+J88GPTvqI^W%n`rQ+>r^mEU3VZf;JUkB47>`of z&Ii7h5i#bBe=^V{PfR)93^JnoPGX+9a!dPu!_uip!#X=DyyjV7F?!Tv<#;EX@GiN% zRqo9f7N8aA;vc$tLBi&P6W*~)wP{uXM&MGdu78AP`eyuyk_A+n zpr>8&&8VR6DxI<3`=%VOS$MLwvnSxv=$@&GK;fgF0=D>lBUX{q)GOogX`q;1h|kW!`R@z z$zxm?wN1xqv}dMYp4($f+I>BzJWpZ25!n*2eC(QN4b{dGI&@Z9IIS#dpRveX$PA7m z&UV)$+jh31c5$Y3uOmm=?W9)BD)UMNZd?0~W`n6Z$ZjZ$ngtnd3lSx9Gdht17yu;G z&3eS5;CogrZ~p9at1nS|guNs0Xp{EW`{ai7woJ+>#sZuclBpWlY6?zWYVoWn$S5=U z0+k>vZt@h{eAg-SFy2;Sz9ZTohgn?AvA+*ps}C)Kt_qj0g!c9#J0-6dC=d3I`CIdk`D zLNDR`eV-lK)DL5%#`$UY)BHCwt+}k5YFsxH9GLn&&sB%>nfH++ZGLqH67C~tXN#Vd zU0*L?;CfRKRbSG*$xNJ2m14RKDX zepbxW=sZ&+;huS-ic^`i)ISB)xaAA9xZ+%Xv0);SqhfZb zw7>AzUMv$<1iu{;x%nI>I;w$#5qZ0Z$zsn{d9E^9rQcW%1oMercz7Ms5(7E0mX>nF zu%g}3z80_Le3DJ^y`0G$^KMlW4U@OV zac<-J@26dR818w6KlFR0;wgGqI5ktyw3MGr&mlh%yBBs*wkl?MEH!3zha~69PI-Vp z2n04H4-%zxP+Oi-M76Mkp&7mpM~&U-@juP0eFSweFbFh89&!P=`qQ7BsEYE1=$C{! zalzY=O-=B2#NzwwZe14XoyCK6fMHs1R^{usgCTcJ_HWxjXVO-hY3Lt;kJx_!e*u|$ zLQiym0g{ep;fK$TCzW;G${Vc)#8mh!sOC+b)(L!ai^IJ-uq-QGP zW;DXih;Po)3)+H>0m`ex1??Wv)F};61IZ%rBJ9&g`Nu=MfdsYntCf zyex)z6#956O9vp%#CZ@8nQ{W)E_K#MyaqXjneB$E=vgPmDhZK((;e7_(S(QbU6i|K z5!+%ANW%qn&a(N}XzV}fOX9r1Q<#fOgbrvXZQKRvKv0y|F{bY$d}fP&$~U=Z3+)YI zrn%K*oIYgLtyGr6vzAL`NTkwTKldHUWN~5rlW;6QvmA?=iGG9<^U1KlR;5bBdiHDm zi|-;gR(nLX4 zunYPK0Fk_Xr1>6#t9t4-U za2{ka9&E#Cg5F)i{7akK%upPukZ@9ty&Z>|R1oJrFv`RZ3(M17du-tQFF!#)mr>;# zZ=k2hXeWM#$nNS_s#R}*l+kjR$vE%K+=FS%FTZYM2d+rv3}X(y=@`L|+RM%5o*&v} z5w@`}xNT|IvUa${CBwE{1X@(69tlX*EMpijZ-IPfpv$V;&oF>o$>jqEu<_r<2_it^TKyf?V*5%_9y zCnz?wq0oNDcpw-eI7mf;IM&N_R%(>^hZU8SfSdTnAs0IfN$)~gd#qIS7hS46=yNIR z`YIva8(L3~8FBHh_X2S?fR`IPYJN$cyu89KjF!f%(aN?0Z~lUjU({8Uy8|lfreV7J zP)`-Ma?n~=bAt=(Dz-D@2Nz#4QX<(W!+gjd*Jw}N9@=Zfg{{a4R!$EsOOJK$yq$3s zo1NC-HaK+dUlL_L8&{ZiMQm@mbiE#^8_1q{h*^8KoGf*gUg&IH?+uC8|Z?y5NCS zQGmW-n!)V{GoihwS1|@$!+W@Jq?S|tUvyllWSYJi!~Zfhn%SdjI9GHd0+N9(d%o1V zQb*wJ8<8*HYh0$bGRIwh8?B#njux`>S~Rs(ZjaLQdO(~>ZNK1ChBsSC)mkxzgiM?#ucp_Xbe%!tc9c||5kUJMrdV8vgxew86*l)MezCVaaxX! z#)W>&Gn0fXa?fgAb?V*USHl$YE>aS%r0Pg{CpDtFI9OU&aSZ#>+={mS&d4A9|I?%Q zkXbt3LD}PI0hxI z6pP#YO5|VL7Z*_&<1_p~LsCa-2*$Q^r_Ku(jfuNOC>~y|qLuX5^-F*ovl}4V;Urdf zA`r>;q6E7Pw8F-cxGIcGVxJ&!mq#d=S(W08jP-B6zyDe*|EBUG5fxYjcp>l-K06%A zH~K8U82{^=s%9b2;zvmfnaf$o60qFwIIkNyZlUbkM=rk2$Akf*m$={69$ZKOksfBx z{?(ON#-pXno&M6Mm0QjhhF|MEhP^whHt!LUX5!_>i-8FNv>7?-cOBrR?*;sZ+s{}V zO=xHm86Kw$;Ge4V2*QW3-A@!E!Lo@zlDg*@VNw^B*$LLjsrbgk7^@F^>55hH0P0G> z6m?^ABY}7_Wc!eEXrC|w*|4P6ba80FFp|rsoMGT8o5(Qwrl1k0 zC#Pqgz9C+Dr#HqphcPQH4=2CH;ZDFe%?irj{C)gPU;W=JgN_RL>X7clGKH!3^02dl z$9V(Ec6iIkH(b12`!`+*^_w1;&Y*T;uA`02UnkvlZh)>0{&&GCZsW5e9sC|~>f&$X zG=fJMbS4DZl2}#R06BpL0#c zmCFA^J%ZL!)lo-L&oL>Y@ErPngv4A>^kNRDAYbMz~_^ zQ?kEN#_A*)+dc%!&tbJa)(576=(5PuHjcN!HcBLm5?tcSP^;jA3*x`*CNe>ErU3?q zJ`ttj+#4GxzoYa6244HXIyZ3IfTCqWu<~#iZGu!&)wsB>1hb-EzEXJfB>1PXOeLh< zXBet(3&db|9Vqn1eXk@IZusqCrCoSE*5cU)6>RUOFH)C#a-d5jE{+9;@ttjV-qT+*j-(!kIcjENIP6}L|{d0`#gE!xlea|U*_H8LTDYodSykl}=#XTe)8yBh=y6M5dHiX72iK0`SY}eOJ;RwG5wx$HLeR#q5JiO< zY(%r^i*K7c{l{>0*`twjbU2*q)VQ-LeI}JPHr3bqeFNW;cMC5XWHB|9jA7dy5~;)0 zbD5RoAujW+X@E~YC@~2#s1uR=f`GWaIoT)ceU_3npFZ%RnNuC%nP1YgZz@j7~jYX z?+k=V6BC>zSZf{*Z7sqIOWyF9YCX9SR}cQ6X?2Kdg?Zu{kG= zRTT(R6x&!U`W2F^Sz$_Uj^}8EJ@GJ1N8+YhKGUGMBOQ83brs$SgE`!(You|#lj2+e zb{`H&_H=pHHHs-xtAln_>8a<^t}WK;hn&bJjVl{Tk(|GHf_}=kR3{NA>h=upHu71` zh-HCMr!3u$yrF|Ll#o8eb7;{?U-otKUkY-K9L4lDp7rwi(lCdtDI(y%0Fpv<64CRc z%BrGs?;%T2mK8mWIaNO94&m?-U~S4(-*ld3*zR+>6j5d`&ct$0cBU6E92&0=Jeldn zb_B~ck8ME7#b3awy&v_>cxJDxN&Z*0SDTZM#iBP5+IG=v%9S|oQ+7+A3b-(Q&z+~u z!80zedNPr3|Mg!ZQZ+k~S}tVtwf2`WG-3NSXqxSBqjC1sq?!K&3e69RZd~H zF#}|$g}pB%m^{*+$}mVUsyZF|=XVhjd<@MyaJEsj21p}~xq9uYsHlv?(wg_}<}Blw z)C-dK+eMiB;eEmGA95kZk)&`*YurIg&QSTsg-Z>%JfQZ^tY$>V@#Oba3E>#lBNi(i z#dX;iH9t!-x2+d1+)1@#5<6r^)Fs7J+lM&;!I3X6@t-2#?-RXuFa+deG^pL9B7fE@ zdZ*q!^yKt=;6Af}od%LT%j7E@;msYOq(q_<+BV$~5}6NKL=Z2g1P4@rx;vdKXCFf( z?hxMt8*u$aL=RcxXI~K=3U5$=5c`9@^DJ=2=)}eP?g(NTKZHAozrdi3j$uhS&)_bn zg|Vahj3wxa-KL~r4W3^!AjlyGF5q8;$@seIp}(-_Y_QWKJMHecaFeip3=cqg@AAIATfk#VN29qaae#UI_e&U zGF6|SU-T)S7U+-Ss=+^M?-jVo!E}A`J*L3=bjJ-X(n43HL$A(mFe*A>>ufa|0jy&O z0Hkag*9XB{)sAPDm8~*cW@X8c=eAojxe^`mm3hs8zAX20I_6E61Lb)E3WlQT}|Y7gaT{D)BcF!anhrsy*n2`wq+R za$vf};<~rl)D9J!Vi~=Ei@?7|Xf|7S?zHBe(!g+d+N?VebWSXrdNM7w*dG)(B2H3D zU?_zUHbl6@I(!|i_GMMGAEoP8j@V}xIUfuU=UQ?{wGFo)bUNz%LbNaz3{UY58Usf- zo34T|^%{;FPb`$Em7E(=AY?3TljKPq_jlZRHuK6{93{Bf=%J?jdZe6jzwl!hier1&4Ib<=|b{7U?hG zJBU%5y-w_;B(c9v7tllVg;B~GQ!Jzq-Zewvb`bB{A3h>~B_i(VY&)X(`gE+Vj|mqQ z-RY3h0Xc+X zh_ba(9<;CTE~_&q9y|;crXH6)$vWiodzNKK9+K~_T*C6}*KcwtbB|6b-=PRWoAUk< zwf)&9?B|?>eU|D#bN}DQF)A-@ZRjZP3V}E8 z;@Y~I6B0YF;e%jB=LGSdkiN8t5(P@*Q!>woho|3B@a-OT#^Qo+0q;QT&C3}`axfoD zHx}p!e;>X^MEsQ>Y?Ghz72?>}dN5(RNv;7y^rOE4XMV-;nTbc%c>m>5f$0C1cFg&&e3k|-0G zN9C|{m$SWxS+bqy5S-?T4%i8VQHq}{2OLrmS2F(^%NnOf!UI7}r~=ME8`qyp{7M^X z>a^z6-Fn!7UtNg}o#bhlO+jaaFHCl#=XY{9j^DIkq3h?7+}!ZM^9Dp!UC8H~Z|kNJ zIG1H|5+=~*wiTYb#@6n8&{b!kgHjq$j;{UX}{&%Ow zzQ4==DSQ2A(o!L%)_FM39QDccl1bI_+&64p9%%ll$U%lHcgqt)Av|^dVJRMR+2F2y zqgiNJTau9oNP$=2Oq)@_N{MP!Ga?kp68r-`yh@Ni+@VImrdzCPj4XHvnx0@iT5+7} zkLF8LU*?JiX;7uDjkYjldcWc6%!j4ERsdv0O@-N8k|9iBmB4eZyYUlZX=_RHjf@}m zNA=Z_`%?HWeb#!~|8)u9Qn-V_f&azVJ4eSE{r#eoq)8gvp4he<+eTwFwj0~FCbo^n zP8!>`*`(>6-}|n6aL-+5{+l&>t>;;TJ^TA%k!pI1h0xIY)To04T$>C_NNBH7BNegc z4~hPMss_iICag^3hSXH=hJXl8`^q>RWs!=65mX3RsBx^NbF=@SVeP*sNvnh+a2zBJ zwQb_NEX0ipX2pRjiRseIPg!6ZhjpKyad^{jC-8*1w(b{1e&uzuBChLN2e+<*`Xb;e zfl7hR+(i21OMC@(ofkr_g>C$&&jYtnI=fly_oTSW#2wU6U#Rhw4RIBS0kKu^K+*OX zLOckV!@f4U2Y>PZ*AMPLCippc;5uC?Ngg~fj7bG~Ar#G|@U(Zcv<}IZ^xIdsVEv56 z0fL*QGq{R?cQ^7kQmwkV7o=RQ+ouluI+ah{$HK?$xVXo`&qe(Pe^0SpxSdzZzw0#t$99`sTi*R;!H35xag(&u#R z;*seqG)T~Dsm1^dNE0W}75#BSIIIm_jp}~d zt*sI7$HY4qREkk`v+b6bmX07tn|%G6ozvt(49(5DYw!=Cm~nQomU7d7;+iN=+*5=Z=XkPVtSvVIq+t1?%cri(r&Vy?q>!Pdm9gl0Qy$H{fPj2R z%VmhG^NF^Vmhbn0;ky0`mIO9I$Mf46p#8n+WK3iF<@B9w{*eej=QLM*T9?ctK>Z|X zWO8=Zl%E{wB0S!nWaKu`-n3e!auS0;8~b)_Qr;tIqM`A+h0#YBr}yD^3AH)@3N&UA z(frdwxXq*Q1sy1ib>u8(B51N4096m5bAzVY^#P0E!^?%pK(u`SLw#z?7DC;K3Zj9$ z4O}$r`P2Qq4a_ja9Et8E{EEH`n8Tj0-1X<E+BfmtA$!bRm5p(Qj?5UtC9 zkDWA8`a9`3+Yhfa;10wB=GE`6R#7bOuWLvEXZB{hpc@GdsrIQah(GW4)sVG>}k$zzOI zm{=xqBX9!_iw^DqE{9rNqiq26vM3Q;&9hM?yQ;aii2NOqJ4Ksgq%HJg1@Bv()i2%O zn#b+&ZauUcrO&9k%|L}Oyg9)|_m?JsKrB2bnl3i^>z>A%i*f-=oY=;}wbP2~{7Ad1 zl9nB$ADdUEc!~7hTz5c|dAF!?4vQm8O44-mMKW1|0$t#3MCc?%i0y&CAMRc=2qz~R z(_mtVDhtV+5LT~vq`5@zT$z`1#&!cA7BKr~jwblM4mM8gwsfQxyo;{hI#R#_1dt?6II zki%_kEz&yQV+-7fXZ~eWk1Wj%p59k1aZB_(+r5b@8VVLJcISX6lIp0W`|g$t-a7hL zf9egiWo+5ZRj4r{g?|zZy4@) z67|zI!&0x!@HW#fLW3?x&t1iHqfS^6+$A62;F#tNfct>W$)N<;96?IcUt99RgVO#VcR2q5!z=we z|17bl#JQKkzz?i&+&)Hr}B# z>MES0$)NqXs}54g#@`l>S z8X+JpHgG3bgak1D`c;#syPrmoN*t3!r_fn<1g6g4QL3x$Nb7{SYXwdHH*)qo*T_;H zYqy|+7I6b`ZT$_J>yK9hBftAYUJqJQlL5C4JD$y!3_ipGzaV=^P^o%=8JbeAu)aY^ z^z>_|VZ$4VS_8M3Aj38vqse)HaI6}@Fs-D{%m8&bo_F5x;nsWBc4pgt`&q)spz?^6 zW>*=5PEZ6ISj=P1mCk0C9$LRz8pO@m+K)*rJA#E-LPow68w9rdjzu#~Pl*M^6n^1V zJT2zs6Q#+DXn&gwqucq}Kb2cql%@u${+nRy_F4{iWUEtpZ%Ce|U^Q~23cJfWv2#G> z8ievYKxD#R!jKU6UjHZCl8{bb((KbqoqEY_71dXhDKFzS9Z1a)WoKKnK!@=9mq9J3 z7}MOqZ!A@9rz>n#kiLClZfKsR|RsR=_T1FG7-;cE}kuTc;juf zrkPd|Aqi12sZCMkECx;DV_R6t=v2xy00^Af6)yd>`As1vY&iY2v#me5SBs*MGs7-X z6?!b)XX!7@rX zfh53H*aH_~yo~m_hZ@T5Jjp+RfCRWi$n9F zUMayH?TIPU0Dv><0750`c#Ab4?{_qayX1A}dl!cj6hHNNkaSLP z+MESYk?999xOGOxyc~o`iQDZc9!_X(@;I>76^e5TZx=9nbO=800wGNTKI7Ag81x>g zsXXnBck$G3%}Pt-1}<{-+hNdZ@}Bi*A`ae%$wJK*NcqgonXC$w%~Rm8lEl&Ccv6nk zF;M>#jgx4~PFrKpBt_ps#5ivVeRC|+I^Ljr(lsuohr!oT`>`U6IxGNyE(&v) zX`kPr1YK+>hxdnc@Xeg%_+Gn*ZlUL{Dj1(^OVu8UW zaJoIE3q7LD(s^@u5Qi0obPh{rqNP0nX*NVzqA#oe4|U6IROu} zH@=6%Nm0T2%L8XHxvrH~gDn*vyDmeCRuV+8}AGtE-J@ zYiLj2dOEkU7e^nUgBxWl>&tNBh<8Ptr!}$}41djJSVbpe*pd=B zT)TaUK$43aa%MDEU0Nb1muJhW-X!}xwAvQENpNVOp#tOka%Rx1J79AS0@*yLh}r0E zcf8U`&0vQu-6y)kjF|K=TdO4d34_z><}qV}OK-3(vWF&4%CT(EEPYaV)sXr`qQ|5) z5=c2MqG}HHT3o3mm~Qx&E5$p=lJtvdi|RCoF}a?CWMHBI-UsxHqQIcN11buQ`Ri=% zXq}1J{94c{x9GdI#TK>8i@q8qdA@-CDah!XCK{}hl_rrCAoXrB@3WnF6n0aO~+d-kqo(sz#G`1$nXoqR?AWE>V$#W^$f1E(wzeo$DyVnrSQ!jayePv8yp~a-VBY+~E1Yqm}+ggpI_%mH*4!jgw|6 zP=gf2l4df4L*SODw`zlJMpz>-*BL6~p}cxMpWbyuP*4$3sHWr2azZOl$pR7X7v7kY z=xfuWQ7JH9-F=h5iIICm_ziVwSdo2DGZE+zM7<16Y=b8=48+%@AU&q(@pi?v~p+=z4$Za8u z3zETNRVFvG8w_H0So(~5r1w6Hj%-!y=de{{M>1~0;UZ z&LN0e`q8h>Q|wL!RrIdQ;{{x`(R@n$^%{(M{{#GpXoG@m_YJ!z!9RHi z4KIH){I~>|9#;h)J~`VLx`}oloBsiBw$HD3ZivHAnkn6@XoG$!*{Mhzv{Av0YSE_> z=dlj)x5Q8zcv3@~Xeb(QDq2K=jslU5(a>1YX)>go(D2ixl^LNG*W2xWCy-359?}{S`E*>9s!2|yDz{0|EFr@x7`o|SC0%kCh?9aj_X+5M8CX15w-!N2C|Ez zsBFPEKA%eVU?gD+c(rt}9Z>`!OB9L{6agyD=ZO^Ya;M2I=e`SYgV{U42R4=#zb={x za#_kJ2bDQ)t9BgURd>;N!L>`d4|+yY?tBBMlSxwgQ6z&(v)D?=IwqiIR93mxt6CwC z!}XoiV+xC#gZn-C@**q|VRjX`kDf%na2@A1ByI}$JV?iFsQc(_8O!~GEs76yn(!v8 zmbL3=WHv8ybC@dGFex^8Ie$i|7Bt;BK(Q}cAKCUa5TCZUqZ3sUr;n56FD$uC0toM> zUx5_oE+7ug>fK91)eG_l6wQS6?@}l*uz%+ zg)nouPnr0v~LjY7}5v?Mw?y_`{Jtrz9IL)AMQv}E#6z_)V3Zy-_NyX=RON$s*v~( zE+6HTZCQHPWqCL&+4C@BWQr_EhBAddJ@U4$Z`HLQbGAm}nT44KTMulXPu){>%GAVC zzmb9Qof0*AXp1}!yai123~y?4Y~h*H2cE7W1O z8P>~?ocB^oh3bW{vq$?*@f@Zt_I4z-h${m0!a7W+J-yYV>a;AJsI=IN{d8BK+_|l! z{cRNTd`OYbKcP*(``*@CJ;v^jJFhCZk%#K13d1Z24HMU#OVz^W_B|bvY#p=5X|nal zc5MsiRavi>h|`BLYi*@uYMItY0!PxB%=`!5I$NQ0@F;zPB+2!)({?kg3BqqOtDTbV zVV+%Kc$0c48Tq;H+qOBpSmp&i8xx67>4Uj=vDp*~4(?QhQQhJBH3g4B^gt&_>WoA8 zun|M;(dMAr`E8t@YWa45qp-d^h6AaDiq@&U%!_vsQNj*kj3DaqD3#&w;eF>7RR_g! zrIl%(#ZhTGYszwMl4SG-1ioiwM6utxhhEEg%LesThC14)aga^<_de?{%iFVqfti;v zj-tE_X{1)qoAxMVTPbFgs^++WB{hUN^%=@$`$bkQ<^ISwlppY!Z7SVM^{_I|9Cs1e z(ZO3hFt-Ap1m+8$FtwAk553$?9#hjuy6K+qDZEM`^ZU5(4ieQ zZfX3m&*b^%bhkZub|!6@qgLw%6wKqE!w7gKx2=-nYI+)oXk+~X_FIDcQn1`|id9ju zd+{SKU!2Gjb4RD_;Hv3!uExx-EqNyPa?M>wHnAr?teU)-%?#~KjbMD|;Q7V6vf5+g zT_c#(iY4ZNm1T)XQ#%qF`lnEcoHaPJiUm@72F5;)?TlZ(hYpX;5+!U!zKt3=ip9xj zVKXONrijxWM9%io%E@I-L?9e(UCdu?Y;aV&ClPAjFL&POmb~;XnOCK%;{(&VkB(l- zqs)HJ`ld)QI80800sCPz75gr?xey-zJ&6Y)TMxRUrVe$xF1D#w2ZP`6b7@1F-pSuG0i)O6RJgH8#>vDF7d{tcfnlWh0g6(ivVWvkUvP@5(RE z)`9z~i<_I)9D8Jq058q!h_YVo+gIzPZ_6D+={%eOf&hf?i09*o4eTt0% zQQ6WsSzI*Yj$nff8BzUm!dM>@DQ*`CqBm`8WE0}MNcJlMuM|RIG}_FDoIRS9O608Z zZ1>SyCApsk@MTyDV+Wh+3!-bx!moS}C^smE#Aw6vJ1tx!!{cfXh_r?q#EkUU{gdeY ztgx_iw8NPNkM0ucajZ+5uo0d$q4r~2*_;Uf>lpHVGO^h_ieNRUvfot zcbX&KCWrWZRhwbudYtdTuB-RZa7CbQ?$FY{Z#u;Gfpf{scBz$if4bR446}Lma7wdL za$H5)24w0Z+gaF1yhv34cO$g~Ky{4zwJA$7$xYw7XW;2BzVCiD4XUY|+6K3Do%Ueum{$*r63c2*gN^M+ zW-h%Bnwe+Sab*9j{F=wy2&t5y0Hi~C=m zz2dHDIkDj8AlJ0>y@?Bgp)Qzb*pQQx%YiPN)nJ!JH;aq~Zs0+Zq2|=OvmS>VQ<*Q& zvL&~E+(2oIVXh0Uqrh;<9zpz?DkTELErg)f=!BVX z>uJJGq8b}NMGux<9c-`L^gib*)3W_Kwq?4uuUoEP8m*Sf^sdS`4nHVgbt;opsA$@g z)T`IA#uumXV)na0t8?yL!eoBdUp8=z0Dxs;yTL=1Kc?@T2XDH<>EK|k zzdul>lJ;Ew;QapV@=E^Gp~Q7}PxF`cZ1N=?p^X>Z@UvUi81>+A}8ArEoFGO z-}M4*8vv769PAdS=4!rW85I|Zf<-p9*529V{M;vpJ88e;=s(=*xKzJ{D5G}v4) z%iIyiE^sJXNWxEu$z&0KAa@xbFDCNEr z>o)XrfbJS*h<0UDI%;;Mp&e$A4O3@fn3kRih8TApXpkJW6SOa=gvTXakAJR)w;3~! zQN^>KZYUP&P}4NYN8Fyj^ixN=mXlJ_00@!b$kON?bdPsZhf~C|Zumqs5(j=0o6Bcb zjZF$8oNFv6)fJf_W>Umi+c<2bf4ed!C)7DgX?mY?>oi9+(VyhCFHFaH9D^b@>+^G8 zT-3mD;%jlRA<@H&`aSk$?)&s}qpryGx_fb-jt;=Jm>b`;vCo(8zd9P9%cvh{u{?2O)4tJAfFeCTIZB7R7Z||Xp`pO($;T zt+Un#%MFTSC;ylSP2qSk^Jfk(Ubgw>jA!stsHHPz~bx9 zzjIu^Lr&vX$AClUgH<%-P3|I+2j#u=LqUY3R_m|XJAW6eO zl3d3pa>U2cdCA5@kEyl?&9=^wicuCcR~_O7r2KB-qdLJSnFn$?(uR&UqV0t0Mdi)d z#-zgla>G}4$JvRLoXuQ5Itq<1+2K6Y^Ixyp9n@1MH+jmAzGqp5#m`Z|-G*22Lx!PX z)KSO>?tKom$n3F+1k)QaHV4?{Z;8DafBL_9)I1I8d1@Vf&rHJahUzEbL9TKnyLFO) z!@PT4)!zfxrdpVLyL+(cTl-ruZ?QqKf1KRk7%WO$=Wr7I2;&-R0<|Fj^JfQX&< zh*sXz^_0$7#-vnPh4BxTmsn2eDi<(4IXgWI`+(uE*1$^HDYPnSK3OgedY?2DK+?u#H*+LxoO%ulknq2)HQ}^lm)Qo z?`=`x@gcE&uwRb{Bbt{`!6@)gq03$qK<{XZJj>a*aZFb~*cyj2c8i9)UKf;+N!A9r zclI8gBHjbbv?!sa&)Dn}=9ZYx_LFDImT9;!>%EO67*bq z2fN>$U0&NR>tbMUrQRt*4G&t`mIJBsuk}4zt6X+m3@DE|lLjA8Yg+yRn1vm?#iF>9 z8>nKR#IV9yHuM@0c(0L0c*$IEq7!Wz9R}n^zCAjyjx+2PQOXgD7Z4;;@baoDN8!S* z+^1iKK}Tzu@K6$yE59$Qs}7Sl-`bartnh=2^IZCz>h-79z9=t_W57DDv?Dy!Q$X7n z+HUqyve8C-wI!uIN4*Pp7c(rXq;{M?A;6LnlR|}Fj%c>s9B@TbAjj*u1?#DHlv?sneo8+E*Jk6#=g&-yC zYS3~fr5d1L8j9m20n5nTnQ0Lr>h0>$T;cyqBO&3h2+2i_TDASOlwk$SVVuKBhGlPb zqhRS3x5zoa><9bXIbe-O1T!skok24W+j+$0LhrGl(a-YeDMV{-2^;fZ0k5=2MCRDQ z=nVdPh_&66O4^*>aB=utYI6lfz|>-juX~@ABpXu_E2Zn*jT){^uM_ojiB(}918f!^ ze1ae?h$x0sAEp>)i@2sFP2dGcIcK8q=0rwY^{>AG z)(6z*!lW&uul#bxKlPWd`ECfk-Af9d{Sn6chvcTFw-6_oiJIMmEr!&OrTYknm)>0X zk3Td)9-8|oc36xQspv3b3N_R5((?nS(qB3TBfmhnm_ODvlGl$mh?#fzK!#Hu^5MrE zWwC1#1tgpwYD%_&PxoOh}_PVBjafx9A1uiG2v);4lVx%xK=TzIQTk#_7% zhXOB6A29HIIp89tR$3LgD2sspnBB))P31}Pw}v+R3MX7T0^G7Z-cs8sk6(j|X><17 zo~3t~^JzAr{qF7!OxZ!_%}&VFJ~=oYj=dS!HU!z%8#1|jUZU%iv3<9Hr>zDX@{FQg z^@$#ubFiE%Pmhts?=GivAKc+0+K|eIh|dnnBBm?xZQyeHURqj1JV<#9pq!DemB?mu zWB!I2L}lBpZAs2MeS}KL1+AF2C$j`9MO&bru|)kySDl~M=pHd&(xBhV{q6IGl{bu= z4ZHc=4|D&!xZO}2fw|S%W`5FD&QmA)Y*w&mQ{u|b{5X22@VLVXlf{7Hbg^^OWVeq4^l-QO79e;QH;B9 zTMcVZvg-7#bA{=QE?da8NGf#T%OJJ+Z6vnIllbD7R)uT`-k4Py(3vamN^k>M1GtG^ zWYmbv88i~VyD`}LILv_M?tkC0Zksrc);|g}?+DAHGG=H)R~A*}wdFF*OH*&hwD%zx zmIsRy;IO#}!wZ%MZdL!AY;ny=PhhN8h;#U;@aoh^&5yavt|B#XP?jsxDQU3~6>dK< z0EV;jnd=RYR5~YT@P=@0(#4A3%`c3ru{NtT%yG#|BUJVu}WP(!T> z%fe1JI!gB7Tp= zV{|d#rJLzGJiO-2%qck26eAu}N6F=q=XYgdY!(oRzzI6d~d(I}VuO<9bDi^*$9uKgoTGCK&{f}LF9K_MG zBcJWJ$A;~p&whc1=5?g3W28(AI_U=4XXUy5-!;P@5f!ybu}f3MQBHAL$@HK&O;~(U zh%8!@?QQOjwP3YP_xV2TkwOYL{}>=y9U)3;3%P?f8*Uepw^{G7_D?B1a%Z_L&a~`2 z-K+01dTT$3y*VrA4>hLnqjZKDHhoBUHOIk5kIeTDEThHxa)-HM5M6*IIBkBBi+RG-A)(%S z=a)bq1iz(~9ac%VT8junS0O5nnmhYf^(htg5P~*^CJ-y6*=r!3@s6y0ZiO0ye&Ree zX6y^YQgFmthX?Y}bo;KiXFnY^YqY5jjKud%E~Kwo_TUmsEE>WuLs~PTd)$My_)z`F ze-wx9Go#>JHKvM9Gx5x28z49_Rdpsyh@X$=AdoA8MT8fpZk{ejt;io}&GsKe z&J3hQ)|)P_z1UW`1%6RIU0jxTRUjBtG)QItc>P;J6qFIq1xwc>D zT<;K&znNRfB}`2SDiG>m(2eP8K@BI6iHM>>@J1O#?}O-)=Cuf7mNIS<=Ss_1)Q_qiO-R3$%@u5sLSaI!R7`=B_(06g*4{<}152J~$7pv+C>WT_ zKdvZr6E%>HSgV!1@o)D3#=l3LTcUxhn|I0?khaD~yxsQ*>ms@icgy%a!I@{-$llY} zM`M|ag^AWXc?o^W7;v)ufLM_`Y>B(ziPc7MnK2&S>kzN%N^;{p7f(k?4Z_GuhRF2J z;LJd$O3}y!;96pqH~9?JfR&F4l^08TME;0nR>ja?Tq|L=w~C{Qu}DGmc6E92=`7j_ zTYEzD7*xLuVxZ^Mk9+ufGHJgqIqO30aWL{5Uv5j&V8OaxG&o2SH-15W619|BQ3}c8 zi|#Pi41vo*5~Q*9HTfHc9#y}ursH;%y?mzYK9Y3*@ZJ@-wrA|Iz%A8w%!I;; zy$3_h=plXS9BM=^q=$2fDB2+wR&3wdFHB9JeZ3(iej6Xopn zFvk_mIU3Xuj@ms~+x1-?m+5dA*F&}qCYw!&zTR=`$yL7c4>#u~8y@j~N;7%wJMKj8 zo{}wQ5$Q{+MubZ$gf(X$Y!rhvowzLU52ZI+EVUUTe+k3i3b}o}zda8HO1ROmZzzSKT@OCEKXqu(MDFA&EhbAdJ9kB4c-mw!a9a^#Ae;4rlpS=73 zYyOp>Yidq}*c5YoxV!=}(cFg}KNYq+-1@jm@Wcek+QMx3JN#Y;(cWjW`w*+V1Vyx6 z5{tY-Mr6Y#2mwG;{fA(iY-GLHe{8eM|9wI+$v^EA3d=+J^X62xilW8|R_bfhpZ)_x zxHoX1`-YSzJ>ah<%9raYx1G&4G?W~A?XQ8)iS>rQ;TBt^F$_jq^F;E)zm&E}gwFUl zI%pD5IN53(#?hSO|1=)@>o9Wtgr&pBk9-3%fnfkm{rC&Y(%*eY9Gn>U;`*ka)g2_u zatir@6IMT{4P%?`zVai z_dnm6#oOxFuY}-5b6XuqBg6(~>TAAB5wv>7%fh+-a4B|4=$qvU(INFl3eE@|a)jr1 z@lNpASbtK!x?i&T11=c4VxE-w)TRRkT}qPVrU(R(FoS~`IR5j-%Q5X@AgexQ_|QZd zaA4|hp1V8rZYwdODWS0?004sj07Phrg>nZw;PnQy)0go4zCt%G8(^o!k8FG6jjGA} zIm`o!XZ4K?L?YZLhYvKq(`YCr+I(?g4M9IqpN$=2p=R!vs)fiR*B!{_6u|pqCG4jA z)oZ|yl9Z60@NcsoJB}>j{cXujnqd0>1Geo-q7|$Mgk?Yi|do<&E}B9PoyhhD&f9ngfwM zBE?7ZoFc2(o}aJ}XpXeZY05CqrNvpS*H>EofT&z&{A{Y15E1v{Rxo|s z-2D9rGAB zM7g<=UEjGr>Q?-FGONr8M5gfw%zi36o=@b!3fs0Zna6m8vhuW=P>RaZp@)2aR!V1S z_x%ytDYiLb#5d?d?u`}vuC$g7K@y%uXq@b9@g*|zyDZ=1aEI~ng21KgRwMnp;RJ(6F)dNdkBcIT1l$tUFq{bEpBl6qI-K-oSMaOFKR?_T z5F00s8xjn_0f{ppZRB)xVm`l`3fq4G>#NK1(ep-kq|CCxja+97@~}B}=;Vndt3j4- zt~}k!ZZkHRxi$p*kAbltX7R0LwyLVaG7RB4Y_&0E%`z#?DE2>Ks8nzJvPAmQTXKO_ z-S%M+9pIv;jI;?I@eBvbrrsk82mO+yU=De)_Hc3_mIV19?5N64gj8u0jSg@94lb>* zirVs$g1}4ec*nCMDjg41*rYd#9l_8nDeSf41P87eHYGC{yfw6-XNCPWT~9}b>Abrv z+44b~tyr}^+!U3)RsW=BEv?Bs z^5_4k{|5k+y_Y-$PoLB`Jp}&)_}%UFEdHnL67yyu@*iOCu1u--hu3#-3^IdoAMNLv zz_t&9Fpu!d4$=FT2v-76scQiV7m3sP(+>NE;xFou4Yi3+k2m8_2&EU9C z-dC^~N*LUA8RdUA^bc_Qx=^;mDNuLfpGLBa`48Zl=O7rGpF{F~6ZiMJfIym1jZYaR z8>Rip`zG_L?0fQnUB&;r)#3-QONNi#e}Eldj~h3VMgL*`$9?}tU+aY%@GtP;*Cfg< zynm+>cizD78I->-qd#9X;SX*=J>COGA2L}kid7U(nZ_pXpp%%4uhab6JWBJC1ZO3^ z;XErdy(COnpPJF(d!wj#wlUdr!`r4s7G-JRWV5pFrTnaGul4t zta@=^(Rq1!4@UM98P2M#u(Yr^h>T;O#*%ev&D=4u&XP#cr7PWu5fHR}DHcyPaAX8e||GZ9F5cfpDt3=YwL!8*wB>gpABhLr$5kNiWmu?KnCt=)GEIu`KVCGD_El>bPlT-0Vr@jwd02&SGlkYaDOWBG!>D z7w~1PNKIFImuPeQ1IOf2{tAc7?ib}13GZ&k7PQ(kJtr|4r5%wxB!f=-3_)*M=7Z$y zL}Uzx`Y>XM9HsEDU^%9vv`-=hF~_n6*)S4q1+p_MfbcyE{?%d4WTdZb(H}g85AF1m zrbhC+1#Aj-xZRUxYSP)emh zsR$_iB7!K2{uH*?u1+|6oYpmyXc8632AL7BkU1&c(3-mF>U>?yDO~Kwf9Sl~Sd+Us z%fl^;p8jkZ=HxoThh3LK(5m>*x(1axCjp(^WS045Kf!LL1B#$}3Qsd1t#0eN&t<=h zproX}%YB2OcZeB|Ww+__5sW83C34J%Us4j5;r*f{-&sge}DvmyGO|=f5%&uS>{I=s!cq$>LCXe7zgQvsn-fOk! zK2m>6HdtrsVq|2ISO;TThYd5CPPP2Mk`bl&0-Ap@z77%0w6Lc?ZiNC5`*VLeEs5kb-vBo-cO>w>)N&NN z8-^ktQIBQn9wYJhQCfm@I=cHSYnym^r_xESmc8hXbB4S!{G<>xLhWAm7bGQFwlH_hfn#f>n2rr&qX7-Hs&vkFB%g<@1Ny zTkju(aeBZjG6~mY9adCs$wHAM44j`Ts~cf^zm!+JYt%bKa+8s0DrLJ(Bxbfc@VPN) z4!;Jg$G8-)VJ>J#0t1l?!&3?%I>JZA^&LuD+CH&LK6`%u1E7g3$=Nu3(98Yx$^QgK zbYxU9?L=eAFH?e~94T;MSrIEzPopT6GPL-L8sN$60Re7vIQC@lnO`&Ep@HU*s3k~I zswrHM0kFydXf%0l*Qcz4eW7o%jBBzcXqV#2uiajH4+j^`|2 zRj@yAlK%masRiH0fBy1#;jZ&;zUPPg7!3bQt8gV-`lslA?U%3r7Go{3uqSQSH$`3L z)6%bPs)o9<29h;{)it`bRA+PR>@-h7v~cJU7mznv3O2a2W9!TH2!L7qSy)nh1^{6I z0KkI`pGk2?k-W3-`vY16Go&yVolSho+wh7WHq3Gs6S2(=$_@J0Hx&pd`uPCou)+2@ ztiSBg(F5Zt#QEx@d8KTq1Z@LA&OGgEds0V|j<19m%3)We zZd$+NCVl-I7vR8_ds~D_sZ>j2v`&9=>r4*8whb)NKbs~Aksd&#Z@X5rBKtBMUXaP8 zzeA=zR@Mc3>7*^*j%v3~&8wlpU8=N*yJ~x&%x@>Oplu*7%dJ-yzL6-sdMU~^7VJ2RFR&WH{%!uM!>sZg!YL!6=R&qlwbA!N|Z%o1ab@iJ5+M zWNijm=z_W9VaWb#Z~d1IhL4Wwq^SN~Y{^aPNbf$F{a27D!-KQG7z)=2MBxQ`ZCRqO^w?lVNS43jrILr z^Cw3;=O~JI{~>*0XbsId7^qO+W{5UtuuY5jcW|#sW&n3CJ8~ zgG&Y+eVL*}Hi7WxgC?%&R+mVFEe!nxN1@$w`cFQgnR|(A5^`@A(>o8 zr(JvgRbKOedUwIo;bwdjn1HUOnRc2f-5OkPNNPj^5lG9nh)Pk*mnT}%qRPW42iO_6 z#0dRDo2>5-@8|e`XnX6RxS};*v~dgW4vo9JCb+v>aCditHtrq>?(Po3o!}0^o!}0+ zedgSmIdk8usr#zt{kghU^;*???cV$Qes+tv#M{CRM%~fn5yS;%I(LKXc* z71S*rO0Ldeu1*f%95(!U%Zwd~SWbIwW%BE=ZAkir==Y92RZ^4WVdq}RH)4Jn2>;OY z(6w6Anne$1W{rWyfbn`erB=G5a6v6j2??c73BAhYag|7ATvrSI2&^4BS8Yj$_!-Om zkHk$J4t2#`9|Yl(M7&%BR3-O!XB0)PZ8w+-JcGlc&SC3P3>2^jdydd{a_EZ_G>LkJ z%-4;gF){H9u6dKelB0K-_QK>DlvBd8yLgh6=R|V^YIvpI-r>vkui+djNi$?%W|l=X zM1cH=hjX2e@X%iXdsSp}&iA3_w8OSr2HTR66YHVp-*mOyhjIT+7 zCtJhx=PU)B)CKPJr;t-90rR&_z5@TRICAu6wjIv`mb$K!3=Bj|JK5gk#3*o783=c1 z^_7&fz!X533`R<~D0c8}8?)^Y8-I+fK6kJFEx0d)G%=tS2{rA80@a1cVQk5R;yEglT=b#VVHZkI8h`oLXx+=2 z&1vKxiU~q!&YSKTc0$>TH z{_eJ`x6x_`Z`wUcr1n5 zV`HmY^`?My3Pjn)iW6?#?;bT1(qOq&kJIOAqscv#zE3k3HY(x2=MioErCb%Mvyt5z zK&JC}Xe}!dOwY~S9*~V;QY}4X!>gO!RCI}85EE7{Hl8NEo6Q^Th_*5D+>hb z$UHc|WxiQWNs4uu7XEFE&67&fKh_@ZQBRcEIjCtZ_c=Ama8+} z(UMi4B+*=x^e6DV-*3`_B`aGeG#x@npstI6dj>)HEp!ZrXv`F&Q4ML= z*UZYJgs%n=1H3hYn+E#$P1G{dbZAdL%kop(g@Z=5)d;uvGzZ)BF%vM@zgu#cizz_! z3OgjwTc}D{0#}e5M$tUBRd=72SXKU%hcV7QqBIto7TJcyf|%fbs5Ex;zmzsOjQfXJ z92xV)K4-)AXW5)=GUCOW3w^rc6^ipUGnY?1wdD~dlN{(L_&Ug| z7cpE;i4cA0BCIz>YmtLKW7HxkH=T(bQb``YXeW?6*?lpQwLHAijdPy2oa_)Cx=+;Z zfvl`vRz{*yIO*1Aj}1#4rkOKQlxBZHm^((DfCH63>8ro82ViZ3B+|biTd7V&u{sZ& z?3A3=`C}!ZI+iGcUz#_-nr_V3Lcl*M0+;V=v-ML)Nkc|RNFspDh|832>j6&(3)UL% zguvfpaWIo$aqdv2dH0TOkeWdybL~O$eTH$@4T1?b#4)4N;Sp(ReEy)UyU|~_wq6l| zvEu8g0dKUvk)Sr3L!`3F6zo7C3aJhX0_UdzXU*MvcH8fW8022I_YJUV-Ql#3LodK~ ze$hr<$e(PJ7pe8#4Lf*K7IWM>+~e#^L{@c{6FH{Ic!fzmiVKw^^b!)pVr-0-9&V~x z-^E-pJ(IfU)MqIBD~p=(%g;Xc=iX-%+Ei^GkQWR6ZH$p+q_p{c7C66a41~KQ$5;R3 z!kSvWJ{)94CMs&8F!3nvQ4vVhM;mT|9MKvjBmBf(zZbAb)C)K9u6oo_-(k@-$d$2C#K*P)y zv#TA(B*CbG@wvmUzC*;n(Qm2A27obag;G!EbcU2BAVjs=g4#fwV0T1r;RnaD%L@a` z$wpT_L_ zp_?ALO~imCrwT`zi#k{3)ZInEW+3HU3%SlAmvpHpAGTV-Vt$E>4D{}Jlpt5C@+@F% z$8U9*Ewrd6%$u!L$FN(iG#ib!m|9Q3kmz(%gDgpcFA=3fREA8+uLG!HO`%)Yc|(G} z7jOHA1Tz2ZMpt|A8rELh594}tS!o%ZIxx?()C}9W1PU%oG~ACq_LfHE3Yhj;$nlG5{^v1`|sk~etb8Wj4*Wc zFHb+}XJf-Y*D898-ASazPZLZ*WiyO zMfJ2*yC9FH6cLYCQ@$f04fQ+botu4cS3WDIFBDJlIAA?>*w`hOJcDG+uCe`tcoG7) z=^a8n(ZBjMLAb7Xi49H;CF5v1VJ4hu)f6g+Hpy2>^k93LFZdxh`K& z%qNlGXM_u}XS4(@2ki7Px+i2IP260BS`>gvJr%@x_~|5BQ`t=_Jx2Iq%tE2Xc?#&m z=Wz?D7B!;D9d*`{`!q|`nxh)MMBALRJ-Lx*309#;lVtG`q~b5Mip(~OG0`O27nrxY zpnXOgq-Gy6-WhE*6%MK+FC%HsL+~*$m8y__MmeihNMY?Jmnu(Z^9Le36%DQArl@W;)}@R8 z14lk>WGrf^NnX{Okc)f+qvd^LF-Z@-HK5Q;afK>lYJT7K2iJK47N=NO7`V zqx=v;^;;oi4f$@GqE5X7(!lx|^@AX=FuXlbzYFf&Zs8Zk$^XzNXB(^{`CoU8!yL8O z=K^^6Pd}LuQ$EL*=du&m)0iW*9744UroeKIWb`FpsHx|fawe$EQw=OJMn!@WK7V6w zV2Ox`Y%MS)`wHC4`<+j*DlYbApuwIH6CImqmD>3_F>x~Kb2j_~GCEMYAQ3)GCZQM{ zrUSq%*#EbN)<0{Ee*xP6A84u_e;64&7~hKybEjHUf1imSTNc-6TVNY;MR}dY83)EB z(bEdo!EK)1u7NtCs85UQzV{0Y_r~uPFf0BOHT|cE9*6ED2I|-v+`X<%C-4ut=TH?% zf{BcP3qYxTYVKUX#M}4?|KuF3IuvcUhl?UjHJ2+#6bHMqlW0eBL-5J@$=&WxM`z>f zM8Wd`oPcbmA-L!u@N`^!#(%||dUwWVzU_*9Miyv2eT#XIvG{0Ru&|Sx@-;TVpK0?=t1;)020N@#Len zL>g9tv=2iF6Giy*{3_VG$F{e!Yg?POzVW?VO|(&u(!LbF-)?4cD11`)T>E;lY&b+r zHrfZ$j(XU8xTd^S`^J_l{mHF94!-;u)pWlXaM()!!b3cjMo}a8jWBpW&gHz;j4QKbL{+}@myBTm zff(et*@|(B7MKzoajBK(OCdl5XkTOY00gFA8}(=y*;pD1(%yO6i*EYF{N7=RFSz8p zU8~9}F8#n=&Kd9DSL9nLsPmM_{A!bS(#6=$iO-=vPR05&a-I){13-5MTX=J+6=U#Z zjz)TXtsrja zz2BxQ^2JGsS%Bxj9xmN%>g?ehrB3XdxhvVG@q$8f-a{8fVHKBZ?RnUFVs7HK)&&&b zl(c<${0N&=(@HS&vii!(O7sm740M`CFt;>uR1o4w&dhEQaZ}5VD9Gr_FK{PU&pszR=yyqv3dBo$OjwRfxNorE0JfZkLvp7RQLm5duS9Y;_6XiU3GT zd+i~llTXq0eiH^dpxqe&zfWdSt|e?V;DpL`OOyz}%uSR!@o?YitLLYo<8_J#h}Vh( z6~{h%`=0_c(a?yy-2PqXIfd?pQo;oh+B6f%OjKOPP(r;p@+nF?;xNUcs-YEX)lEyL zxfaur%i;QBgpM^48(3r{Y07dj~__g(c&sQqgLMr5r8YHp)H1LLn960S%|c-%R7 zbI~?OLZj5F_SB=l0G{n%4*{tMtFH)mQcq@;Mq~{?M#ou-cV1J^eP{iXdvmEhUb>_G zZ@T+^qk7@>Y%zzAq9eZ5lvbaUa(*|dd(QO?_sA%47OzmVp-f?~&qRL^|MDw9#$1zJ zH%bWwDdPb8IaJL1t@hw67ZG#3l98?0BmL)9(p7eYJbOZZ+tZss?B3{>^kABiiC@nU zq2o^dol;L|vzn2i!h)j^*Xp^S%|#MZjN}F$=>vUO8a!_Yr?<809eXsD==VPbrZpkN zH^fmir`6YUOa1f$^Mr;qRj(4#<{rX@x=gCF!zY@TTba_6xHlkw;p|6SgqxG>4B&)| zt9}+MQpK}x1Xm(dixP@U4X}NEOHBZRUx$ESZ~#CZzzHfy*KL=#ge|jp=(;2GjIE-g z+@dVknv`*VhT;3OMVby$QId|C>krC!XWxz8BMcep?1^)k59J?!zO;Y3)$#c^1`hL2 zo3a8eBKETEMD@+PNWzqo17#4S31P|s8*+URe<(EEFgE44VIElT-FZjk6p7kR7xip` zU|yu3o5@x8G>+Cd+mkm4Eot34=C&{1jN$u@z^WME=bv3HxT=!oWLe<`Ac)uRAUp`j zgdk`ZTk|ThPlH$VHeIAjRt^Ka93D`65DmyUj%Zg7_M6^k*_*aLqou*+*9%6zzPG(l zLtTEv#6+pJUiI33WETdUdht(z$?{=SimnD3v3+)I?k%~UsUtRh27AtB?+t3IvY%M| zvWJ7uh;p0y5?o<_LtQeM$D5=7hv&?HK8kU+R3nb$mM>t$G5CPXDcxPg8v<}&Pag$S zA!QE1VdORTxK_aDWk`HFUly+4@`8BX7ghZ-f;-Ogq72S-9vm4yi?;gpDl@OuT_#Q= z6peIaqwZ>uf7;F^6!2TIWxrMpB{?;1PFZgy;|=f1t|xX@(M-td@L-&M5m&w#VTQ`ElM80U=OrjJ;*Dz3&N>#2PH0((TByrRZagHAlKG>a8q zlq6D6-24*J+xtWh^pT->q1Q7i^L_mb2ri)Gs>d>Qjj}bL(BTLIL`shKJ|Yh|Z9ss| zflw;Ql=?2pZOZ=i#^5+LB&~b&1d%6#xCnQu{(}p-0O5(Gw#|+XW9q$J_E?#&5N_4_ zqW!PT`usW`uJDv6^_bYtVooFuDm)eozb=b9YLA(qZPSiILpzva2~SZ1*4u#;4oEJ) zBkQnTart1_r|{t;Ge$(uyJtzMfA-q~OMXsg_W8NZ?ROk}SO%hrl*Oy|RiT5 zGdCFA39Pvi+nn_tR@(W8q~{ zPX@gz)0Bi+^S}Pc|4wZC&y#@xD&An!JgM0Eyo!acVh(4#0-uQDit4Z_!Gvz2ckHPu z#R$&viL5E!Mo3Fb?L}|K&m4v4{Tw#twUI6tuMG?UX{pi?4`hh*d7Kw8wv_$b3b>-< z3iIyqmqn>$w2Jri0iU<4PUw@yPG8puYULij=)`wI#jy5 zUQw1An>Ta;Ebu1Q(qQJin^xzx9%#1poovpw?t2M2c9ct5q`X3m3Tpy40kFgXrIgMD zXU(L-5mv)Z-zZ(LdGt%g<#~5YA}h!#{>`kM6O9DNEtsTOMTcbenwl1o*L2PB z&Zb;kU8y#L?Kz^9m+tr>O$#7bz8`af)4Q=|a3KW3M!pYY;sM|*wM4VN!M67zSm=@P z8_py(v){?%Cu!^Ec+Q46(KskjO5ihXI2Kq^5S6Kw_Vj1=p)S{{;Lf3AM|GGfXWx`% z*`zzIcw>B{+xXMBcQ0|xU95MsDb!Xt4InLx^z_(oah^=f*Er~tN!a=w`s?WImoT&d z0K$Tb7zitr7Gc^LG6h;3U{!Xbp5tN@YtpVlD7)q0F_s}Kbz8wm?F0~TO%qBgLxd)7 zMKPZ=hB%{>swi4qC}KG^Xt|oHT;+Kis;2o#t zW`l|$z-NMo`xP|UF+5JS#BF$DXTX{sD$AjaDt(>QPbs1WywIWrlr65o-XHVIet?eqn=r7Pr9ez`xT*^#sXpDaD7BaR}rqCuF9SU0@bJC3g>sk7#s0H zVh2<9FhZ}J;_8&D>-=#0k(IlwVyqats(OsUZ*uLm7lKbB_SR=weoj}|X)oXm-=Ayo z!(IXNNgYIWzAmGB+VeEFz=>dgXThkLuxL;IOJ-~;;)>O5$x~jo$t*fF(Xb9n$S>b? zJgJ_oMJB*>+fKkM+Cv|06fwG(`tL9BuLg$x>Jq?Ulkyia5041tfJJl{ih8k82yxYZ zSp9X!dZ@AeH#dnkMVR}@AovIPh#zU7X8JF}ZF_C;(U-GW_T#ymK_vfhEbb)tTyI@_ z&0R#7A89{HXX8GF4qd;0iW6PmD_}(SD)C2q*9gQ}dR%$~6}knbvcO6M~5 zledp*`(ds4F#c%JZL-Gb@aY>y*og;YvaQX0_vMCA!o?>8XN4Xo$Tel&msI}Y_JwI=TtOk{KoxcFR^G2n#c?DpC8ZqQrDcBpRh1!H z)mNKu^HgSUMu8^soi_R&isqwnx6D+8x^qZFw={7VRvu^4(i<)k8oPf`OzgF#t==enGR`rU8#cx zOMXdZIdfa6^FuOH-5XRYIolh2$dSf-RyjI$o;25gjf1D)v9gXJ(WIGWET6p97U|Ce^C*A8^RUTR{ki>Mg|B2-E(7e++ zp)_E$`>y^*{vq(5irMLpA^H9tEdbfu{^K>EB7gwwqkCGqgL=JvUS@JOOM%eddrIy= zBDx&0S-Mku4W5AprW=2ZZ*TTQQjGnCdw1vxJW{(_e(Kc_fe(xWyAbP0#hS6;;0x-6 zI~e%z%qF!hZFe8-Rhzr%;@{2MJDi1M=a05%Q`;QMN9VF*n_b*fJV4%#COU6i^x1Iu zj(C@L+rBqT8ZPg&EpIP6$}VZgpL+fUl*PXlgPRdBx>|mYr4Q+aVF5BP+bwPWcoKWw zQ^qG>Fxfw`n&8LE{x0h(<3Vd->cQI*qg|U~`If^ml?BbJhs1xGuXXe_f`_MitE#X* zG4H1Bez}wlh>P=lLA^!g|3R^4xd^M<>eXapq^z5`;GW4-!XzQt96MLN9aW3tMe_VJ zJv`5@O6l8SeSo~Md~`i-YxQfuzRU!UyuDU8rdJU*|J$GO{Z=)$eW6R|-`;MzZvx}P zS<+d@g{Hc4*+;d5gkbsbyGD$G4vUPxwOilbN1;W`9N^=rC$>*&W5}!UQY$kD%w0(h zENXl@HxxpBH0~|wyr`l5cY;(xJXg*?2~tP)iEF>3NGXz0`!;P-FMsu4F^f`16k8H-80J6AYFl0xh~!79%7G4d;}WJHL2d8_+nYroAC`lS2Pet0Bk*(+A2vf6K`12w0W zGtOeR~ze&<&f-FJwp{2t2ZJ*f_& z!AQJ;8#3y zF?aww*1D^JiJ$w<_qO-4)>7{QYOjk0H2>|8f%@oNMxa#iAoU7nhXYE;!}zRSj(In` zMdC`YA<0^NNS^i(kBYE48P;4*Zld+4MggEc4j)MZP8VH*OHu*)7q8B>c@L8>@puJ9^<%0rM~1$)2P_eBH! zb&q|&WSog?X$G)1*>mHFoB5YC$w_7gn<#YHj;`C0j75@+Z>gfDVpC%Cf{0CBK<9+G zUs02DQv4IUlYE8O6&X@JJPizB)l1Fk!V-6!)$8zSPY#mih0|1D#~+h7b12iC=8b!9 zgcZj!T69Wlhk=nRA)C|%mW)D^akjpR6!sh6W=DR=UcL1eRRi^igqqp1?6Ymw9kZ(h z<0HxK5G+=|NUExQhZ%BPxo+iWVlqM`V$Dz(^c$$-Td?Se#2Qu(Cj%O@$UNX)DA|Ci zx*0tb%|2OCF|t`L)L+aC&GFGYcyIwrV(?yVMADS**V-O)b&ODu)y2^OQ~XZ}?KAV_ zNtY;f?ac0NZcf_q&Hz~88JedJLUkv@FU%8y=$t5&ywE;E%2G0fmK#Tdyyl8ZAznB0 z`Ag#CzG9`mq8Qbbt}qC}uJ#2IgAil>61IrSW%xgP1uVuKq0wy!6K(G9aSIYuZZ!K`4)nvkHJCE&M3pb%{uD-toQ(}6+hYyJBAN{w-?Eg4~3?er33XcwP z9QWI$@?mbexc=MbgKHcZTF5cppPRQ@yU7UkRm!De)+JR<8YLB@B%bH!d_+l9(9R0z z-Qc9-k0$=$!Ck6gnPecZ2+ZO{(TYo(W1&N0@vsIVL{xbo2l0`p<5(3iylLOVRqYm$^lz~AWCg#%*3bpf! zE7E)~1A2>#0{}ee=qpg0=%;`J#_~3{oEsD>5!um5e+h01Ea$5BZ1mw1ara|;yk4m

    36DYGjfah`amFDA0VeU?31mEP$5Ueg~gVFF0N(js~ zSU$o!S}wqZ_P}x@Z|o0__aA3k0?B(jNp|{5NJ$($-`!kGvTII;Bqtx@avMF-&vGf0 zAE|;biO=tA-U$(Be&t*cI?5V3$F%30mhA8D6PHz3<6|wNliNCOz-$oA+pcuRS5b7mF31 zc&8j6MOjSw^Xx2@tE-MF*qae+9R$QnyH{3fnA@dD3@cE&?^5ZN2+($!?kBIe7O7Me z(LTMIifb46;L50##G@0+EO_fmi`&3r-;Ahp2T-}>{F>CQfrYFb-8c`G>s3Y=nOKrY zbN}bXKf$L7gm8!r2|TCjdkFGCfNK&5@V6E)a2U@=UN^Uyz-e)gTb!P4G$sWM@`w8R zfg?`!-3}E;)Y$P^aK()@JKr)bbU-tkni!bKs2=OTJTXvIgR>Jt58=!s({w1XvBzP_ z@c5MKz?|3ud!6+F4C`o8HvX>-GPPDUdrP42grQ%9hapo00Hx?Fkf7pgp+*$F27Bth zEZd?>Cg`rfHp@s8_y;>OSb2chW&tBJ7Ym%Tkx%F1=F>%IYg`16J}cO3Rzy~^PQQwv zUbMo!Xs81j1Wksj(n^Xqi;Ek~Xvu@36KTttRW`U@<@;2Ch*cnASmWAap&{TSR}Sz|&@eZ5$5F<{>c2 zL`~817fH=jBgK6}dFb=Bb^Ix0RTJ`50a$seDS5;}s^LQbls<3({pNpdsLcNlH&n2& z)95KN;lqDpNi1%(vmcW5>VcJz#pn_;6!Z?N5xwFD-wGj10H#6kuf|{?RUQCU1_gEi z{y!mG?a~)k)cn$rj~;#N2dIT9=?`h_DKA^+pm`w*k$>8 z$`zXU*2T0+jRtB5i|TljYCD*j zD?^B|{1IO{BCd9lo)Tna1InW{<_iit->!9JzLO}AgQlf6Y_wl~c%Lm`Iw^rc9^_%Y z2aD_NbbhL#)YRXCTOiDgr#YWDq_z-&VdDBtB9~)-0avhp0ZUZk+GNi1FXS&3A57JM z>M!yQi;N&0LoO<1y1)d#GJ*c)7lhuLc?op3IJ(>4&{+OB}(Z2w;Rd zFO9l~j$+`{aAf!}g6-Vbn8}xDj%b-P;rD0g5ci`%HkMyEAK`eW4>m_EXR(z^+_B+r ztp|=33nG3DKR66({c0>w%bN{<{rImFOS2^h0`zWL7i~y;FejI7w;3`+PVKdt=te(K zaw8fhJYpx8hJIc}58r)Ha^$Mc{M_hpE`5D?0xP8=%l>>#jA%R!brwhHbJ0?((4r7E z!5Wv&Z5}c0_!XS0Ja|R9f*7oXl&jxX!6m@6)@e*#$znPc5;jqHS`ufnERg8HeWGPM zr%MC=02V=xsR*H!+0?5RqvLM#?X!n_*H=y z`3=z+Vnth%E!4D0VbDpo!e&xvKYRkZDvMnT5^B#i%g%e{N?VdV+(cVJrC`YVsJPk+ zH%@z#uurgNB)rY2U@xkoW?!`%+azbSG(!cm9qSem=n2d<7T5Izegj9L>puQtU_e7* z+KEc3gG-#6auIEDHFBFcp6|N;7~_f{=X~x0sbwLUtiw(_S!7n}QX`=Nejt@-NSk~Q zW0j$di451#CnWq#nfw*7D?<|maHhObV~bDR<^Aav#|=PAQX+$s5t1EFM@8rrdrsU$ zuwar$=08NY)IXLw6QFO#8!C!Z%;C!Fw?WP)bQ?ASs1oJD91p?+0OYz`own;F#pG>q z))UVB`w-MLk^|26nq9jOI|0Qxvvz0Ja}oR@fDuX}mV)5ow?7Wb*+#J)%SO+U0TJnU ztOKNtT6}@}_S)V}c032Y4E~z=uRBKGSr@(suB`qF6%S#`>B2!zGKMQZKT&w^uby>& z;&Q~8Z2`7F<({4f;_+BR9#oEUmua(iGacsc#A3Ty+O?VFfqzMc>lyYa=tiiv`nb_uNzT1v~B*A zI{EXSyK)VC&CwT*bdQNhd~Z^GF_}m%{yL4dp+1Cmwe*qERnXHWtQ^Li%h-8bMqXy7 z!O@=0PCU2G3qgm2;t20wDOkN4vwla}kx z$tQhfY_mQ?2O|!Ymsir(&r5-%D7miXALNK)8GR|OT@6RTw`08RH`^>xCbD1%9Q6_- z6Q!F_Fy9w@j3#R;t?3_#fa_9UkUkqwC}_W5_&1Mk-VrS1qxbA!+1eW%mtD7TOjxznX^oBaemkcE^f>2|YYm+!tAX=}`z3+Q}X@{mRR=KY!gE6(rEv*~Em z?S45^7j=$Ar)Inotvg=rB3E340+B4B#~X*s1a@@8bnw*u3&1IhtLVP{A`|zsOQNkw z`=y(H_D$By)|N(W1yX>;21)(8y<$3Llr@dhplIo1s@0{+ArmB*q{_a}sVV2Ny9soT zHO7_KB!g-|3W9#OPN|ymo+#C8Ba~5faz33j!QT^M(3B~A&Xwp^7X*dCmgq{Xk*SRBNKj3G0T?&VlW(LVjk4j1&}!S&2B;Y%0oA;@7bfpDj^|mY6asz9!Jg*R@zF zIs*Wh4rE{riUjFl&;iTU$zQ;So&CE?0nHS|xY5r1U%=bS`b(j>QWjK7??CBa0NDNP zUJ_J&mT(=O!~UQ&)}BnKt2K0#(6G3B`Os0c)LCr2w>~Cd(l4m}bFg2U-C>-Ik^&?m zh@Hka2{ec11_1YdbDkBFyl^P^ak+GfpMr8=ZjevE(5ug@7)vW|?E)i%yGdy?_{X8z z+-I@dIbxe_SK42>R&dxckQt+S$Ylp~r7h@GEjw(uV5-YD$M_06N%hm!yJqnl4`~+m$tb zB@~ED3&7QEc%nbgu0pKt{qP`fW)!o;BS8pRGHzljWlZzQS~>9eNJEUUF=KCFE1u^o zl-~U{=atloqPA**omq$HoRyW8ag@@9Q=fk_-`^kfR{Ie3q3WPnqv?v)VsHNq4DiWpVvAdUl3XJl&bTJ0r;dA6p*p`g!F2v|NJ z+B${ms@FXjol=U8OQlwF#0O7xu;Sej`?Vt3oiOv#Z#(&>#kbSczRY)kda~S8NnDq0 zVsK66Mj_86AJY*A>tOGZv2bz@9W$eXxgtXQlt>Y1yb{$>HHlfwN9aJ5jzgcDl>B9@ zalzdwKX417yN!~HiPw58QU`WazA@UQ;3ml?mHGlr0a}?35defV1|A$VjTBm2l}qOj zJyxQ;ND0UP2_gJA#GQmWGuMMU6umT_`0VjZ{R9(6RfQa!DICuHn^KDdOiYyx4Gjvi zb>09+p+qcgPE4l>TdqU&|BNl*4X$6z+c5MS={u|W$jDKr?2RA z9!%(NWjXv-^F547!es5K!080>Ahq%>4+J+OQf zUeVANMqFg*I_=hMFr;tEC{+^-X@$Xk>O7JiZFkCS3Fs4ZOEvgHXy1z5=Yh7}#Df|t z6w;jP>Y-^|KfxFm;T*eyi-BBj!!*C?w968pb;!)0Z9UuEj$%Ua>%y(e4&wIw4};j= zE6Sho^n;ujwsV3}tS4}km*1A^tPc^Y+1bOgpTS8`*G>fO6E?Lq)ulcW5|wZ6fb*QLSI8gy8&RBBu6x6?z!$D9)lzY)=iMZBvuEDMQVwB-hIBAK?CcN$}l>8;M;%pI-1WME!gt5 z4Rb|Rv;t!QsRI}?J(8-b_le^|eSY*guuKnYbHC1Layq1L+T)$42sgElu{2(vUGeWl ziDfYhWs}3x)1~Js;T8kR8Vn})s?_VXFzQ%*$EqApE#p%LoPyND`6Anr1}de0S43Ki zLd+U09hF5tzH^=A=529qm+t%p6wJ$#24Ev^`~{>1Heh)!{7Cr=Xi-}r9L~Ob6S>p1 z7W>nm-3~67{sPRXUy^TrJdFE(Bp!I)J^AtJwaUQy@8ld*Es-)~l;5dH; zHsY`@M(ss(IC^V*Psl!18V_8jJ4N18cnKhVVdBhx+)?=Fa+v-y&q}Z6-XA)@;t4|Q z4dv9o+Zi6X7RUdgLWnl?aylvKOB|D=YNs?=`NY!cb7mMY?&}Tj*-qy{DKI+U4hNs2 zE}zGSJ_%1P7oUTuB`2>dX53iacPc1w2GIrD9FXIGvATfC>aexfzu0JTN}P4t>}PXK z)`6K-E>@vRQZ7)#>Vu^V5*72wHTouSq*PTt|HeA=!?6bYp6j((u)a+2PmPtWr>f36 zto%WFL z6?m06j^|^{ebOwkq&QDf%4@N@8Zes^u%o%}^`VAsNmT<2BZG~S?V&}7lIKw2*KDYJ z5fE8LF$etU$j9^LF}>j#MGcD3Tf|YX4NaN3aBmzS_`H_MMhq`?B|IOUW6VH?89rZI zjLzxlO>i$ph9N#whaIr<(Mf#oUPd|p>5tq+dA$)h8`a<;&4nwVE3|;AfH1pp=nrbNV;ra+`ghBY zztDB=u5a-K=>1&toO0;ej#VoYIF_~DtKpS&j)7@cE{NMMTR#bK$U}~>0Zv>&eF*-?vjM;FQ)bvP*1MTgO8vrScS83Y_DocHvA+fMOr5P9VK zq?JpNV?>z%a0wkGigkVyhOSyQ6_!#}33iJ$;r{YFMg#t^AqM_{(+J4c5B*t%B7_?0 z&ME-T>dvwwG`P>z_`tebG)UA zjbLDCG%MTW$${2g9I5QHGD<`?t-dNh-QZA$?q>R})1=OVhWV6g4rOm$T!%X1t8dD` zBa;8560-bV_@C{y{ThZ00zJT>yQg1Dh(!W?LRznp(Vd$l(Ag0qAS2>HodVp&;z2-& zDRH%he`P$S{M#TJ4An|P+;Oo6E>FY;^!a3#la4{2<%S1_PdD@WY;<(pe>IMmB~>^+ zCp__fFKf&FxQgh*JY+!%?C5#v_MPAQfov+`*_mB>`Q!Ut4nbGiO)!%?s}9UzIRgRY zqrL;Ev&jbBz#bBOXUPdT5Ed&w=I4A~;n=wU2C|GUwq^4SB* z7wr)&mIx|uS3|$P2a}B`e|3HzA?fK|dnk+YIy|6_?-o~9L-`UFvc7x!a14s%i=ju= zett`ls0{OAk6U*T!2w4wgW6p20@Codu~TR}w|^N6ClpwbQU0 zJxtyM_i9n^Ka_j6&$D;6(gM|n`(CVn;^L4dausu>9I_XMi*=c-vg5Us}aNbc%@c_hgg z)p69q)>K6mSPKg!I)v1h-1D)Q2l@Gzu0?=ka*swnN2oQ$rCVz3+yd;j0AyIAaRMEZ zYb1O%sFJKA@ws2m#9X^uIT8h|6LA1_rnH^&nzE;W$qu%SvPY$~+oRghP#}G~!!4Ug zhWdznk%Jf)eQ?1Lb6=uV6@a^XHSLt)T5&Wd&QznLD6N!Ye)QQbXjvLRW{j^5BB<4{ zw7KOI3N8Sx*+T@I3ulBoC!!AupTsIB#{5!De}gFziLmXoB`w)s+=+5ihm&==P!WPl0qioYI(2O z{g+V9fUg5Rx1ygc#b3r^!*^gZQ&V%&@jkh_xnf*VS_v?l>@5!V&Jg>81 zzOo079NnQGUcK6EsP=k7f?S^W*nyk@oFB#WQ$`J@wzd{6fsGtwgVAVs)KCgwELAwS9A%K@J4Izqzm5=IXOc#0^K%#+*66&us^_ zJH$qrA!isr9Y}JexKx<@Ric+^~V%vhDVw#Fr}O`({_eB~t#hOsi>{|mSW zv&O+5IUjnp;8d}X+rI$4cZ`d!JYpe)MGaHJT;DzH)tb-M2!;!X zE9lq|Gs??P_k-hd5+4T0gVct_3{CCqnf|Dr)BJYTXvXjoYigd9EWYyZs4K<^&Q=U9u_4CUB(1J8A{u{oU=(mrm55MoUXkQc zAO`22K#7l7(2+3~k^czGI)>eEAqEWcm|5W%mY~O*x+pb-Pw1)tp>!HE()=_>vgXt` zn7@eY*}FmYcZqU z9<+b+6*)pqgcX&*D`ZwT!&d&3kI61UAJX1Q-(aXc;myOYq?dkki4D#BL8=g>6h5yu zpho7-mes?5E6LfM-E9G@VU>Dm?G@8pKYHQ3@}7C!V66z(+c&^T1#?%KHQ$3ExWdrsW-G`HlqaU@1o`bPQ;r+e05!GYr{y2Ww(}rAmBmkt47aqy}$S6nM6EKU~Egf zwh>P6-Z;!dZ|qX`k+;FdN_l|)y=5mJgASDYPzHTlS zUE$d%1lu4z1n%)$@U8Z|$?O#u4V&&Iq=omRJ)tSPzHLOBXu!YwH`0SY4oyFIn5zB) z>rXGD*E_|(Q#vJnIvx)kW@#2b{AXCZ|iti{CDIGt``C;l{IF{y<_9wUQCEFh1_zaS(lieDv-qj$kz zs|CtKw1NnNUo0DCouCotz_eHUcF~hDZm=AkoegHk2LLG9(=6DJfTSB&KU=x@nacy9t8hD4F zwk6ZBtz@bp4QXMI0ev6X?Wjw%A8)j)pp0uZ;y=a;M-d~lD7V~H{o8t z(wK4iQj8?&0lO8}BahhIs~NVsh-= zB!J!_L^?c7!1xYrmgFc)XVxD*q=!X7g>TVWUTf6WC7NH`JQ~fpQB{Kr4qFChz~Wvq z>wOVdr3CiO6@=K~!|G4Gj~ySVjD))3lHIWj9V6&+0m{c)d$e~f?KU6jd0~HnnOH!) z{wh0V7TH2kSgrWuc$4y+p~n#@J1ZIpVE^*It@@AisO{8zxSl5NyX{K|sf;V1Uh7e; zeHB)#P9n{k?bOF(8_GBU<$L5goLCAtl2f`^Q+m;yvP~>SZplg|Y@!pNPDhpJFifFR z9V7e6uCu*WR7L+G?%n#~w}UyDt?KDN9B`=5s>{A&z8*57kIi4}Kf|o?nE;TmY zH2hebO-#*0!h}RW#t^y1V7z{Y^Bt1pyA#PRsoV-r9g<@n^xnL_19^x?Z~?3CIwq9G zDH=NLxVW^i)XrF}*BOutvo9o*>|}CKV6^6*Ew<#8PMu38bz~@{>Vue!6 z-o|4Urjk#z64RlIgiDlB!2svW7@K!2uR2;&!c>K^#dE(uv48V0=r2aX*J0SXI7vSJ zK1h^eklhR8^I7-UFlqL6lU~CNQThN>s3Hy59T~G=g^)gZNa_8?+F#3SQ6jm)jFe& z3|<#@+I_YrPPWM!;F2L$K#5e_1>1yZ)kt5Ibg?2osY#nSs0mvko}k@01cj=Onamnd zMMq_XmI3+w7hkwKs{G$?D)Hw2DSVHh2**ohY_U#2ZN67TmJM!WoDYXgPP9F+Pi)eD zrhqB!S7jUGU=H$%m|C^}N!Yds$766~Y?-h`(pS`&bb9PvxE4J$GT8*EtfM0o<~nfL zhpSyQdakq90B zJPJfCXmqhVeFc7Jb|=wDAfK$PfSF5USa0}-Btp7$W)B$w?c+gIYMFL^8++J-_}Lg! zs-kidY?H7d%^ytpH(zVo9uQK49rap=nv`r=iCsrqa;~cUi6y9fiuV`Mt0x3R3>1_R zCmZH4vs(Cm(Sw;`pKfN^{&$g^JqiLh>qr>^H}U14o~Wo7cx3Yt9a4+WDTkmyp&t=ljQ`D? z{I3*b$bhC_zKi*SM*u|r7%~Mr;I~V&oPnQ(;Nx#0AXXYZwfzm>OgMkaVaa~^3oN=0 z`SH3%CLms3j43;nwU|F1R^nHcUD=+vdf`5jGMgE1C=J8(DhA~4_?Co$G0oQqlayZ& z4Jpe*`mlYWx*z)hhe_#)*dwE@W?BSF@?YQ2M(e-?Bpu#S_|#>L&Q=kp^xvJp?$!BF zDicKR<=jU0+HWM3T1|EN6ETUjZ3jma3ZU4_RfDWKP?Uwq%$Z#!Dcr^6AW5aC_}n9g zT@PGL&Hj1t!m$)%+-}b*(U6uP-$fhiX!7# zu&yh!Kwg@q@`0`omLKe?AD-rP&4!Rfm!Yit0K;w8Ke7U-k}DIS^XJ-^4o9|9ZMlCn zc||uM1CXu2BTDpfz6X5)3PGVdI)Hr*dbWxd4|k^ZeEd908qq=w5gK32VYmcg6khsQ zk?rbL&N$z~*(pR;?3g`Rk=KRWu1;yniX z@{?!#vu=J|UccviJQ91j=`)L@OHWRZ=|77eL3_U;_c3LHaApK`yL89xRO*^s_YLmc zL8{||SKj;49LFo=24Oa>wTwOCPUeDBeRR*72$O;uj~|l8fBtmMQhamdGr$tBm$Vj= z=)r3~^T-CN*1CcKmp@z%8N&k|v~{Y;@dM;<%=N!dYZ;5^!A@tYK7>2KUSY*2DAF#GvLlEyPxQ6xZ3 zKU+o*? zb->6VPL(|vFXEAYQBHp2Q%qwZGFD<>!P7stuX4@hGpe}QTrD$;^Nox0Hu+QyxTp?qwNIj+(qUu; zBTZ`j4s}AL)@O2rBg7INuJMH1nb=;pfpr8XSaGdPaco#$58aE z*vl(4o{i@UynlX7XWGZXt(i3zy90>?)fs7zXwwL^0k?Igz$ly;-r)H-5bMGo@WB0s>kuPG?Fe#!13kESfpkA=Bh|YQOBgMI_=B8>DL`m{Yq2!nI z$#oH_+UV)GRV0a;UPy}8pFq;3$(mj##710}JFZI{f`ltnRTl7XuFX1_t~6grZ$dX% z=Gc`giwS063;OQ+6%s}GlVu05xA1#=g^PV`?F@hIgOjxerJ=o{QEKyRoYpvG%P$mR zNbnVKc&QV}5Zi2+AHsH+mQaW?MB-mv0T{`;$cde`=qAh^a79BCaHw;OFu4}s6kwF+ zXRF+SYymK1Q_ze&?E|aP7k^Ve`E9mB&i9b1}?D9Ax!b@wa`3h2+GDU}@EozO1i}2kv3wJ~yIm%(0 zBFW?6$EEnU!Hh$~A&)xR)sD=YDJnQSN219V@4T!m9Fq}>$wqHRobrYC1hqB-JBKWk z<>SBbahDPJs5mRp8T)|>?Pv!xAa?`{a*IWWu z)^w_Ah@i;CX59d@YKPs{P4jL~yR4_w@a(a>Wd|5%R3|fQDRPEx-Rzcym_D*Oh2Yna zE{ruUv&;<~HC8b(&oJL}gBje%FLl3c?x>)`pP7{*S5w82^xZhPV^W4X(KX3$Ds{HU zksjvQNW1sO+Hu*+&6xBiv|5DvYZ}vKhXyP8*Y3XRR~F;blO2rrx$o zKnN2sG6q;hlbC&Dd$kSu2BdV%yp$C=&y!BWPnSzTPcwmQGP<0{#?4&IKnTH%3F$q> z?jaKeK(T_Mv`)WAtu64WTG;SgavB$(cM}MN3y%$UJO9Wn~lL3Q{eHbLc_-a^vu*qkq(b1i!+T znqcQ&iVV)Ti?(C7+WxVCYjAK$^!&tqxEgj9#Cn;YJG${>w&b|e+(*#Cz}0?=@BP_! z!eEq^&Esep=9c|P5_?oA%4 zw&ZYcyYVp8C|hihW;<7}P>Z-^dt!f1^YmZ+ikY(#p~s@C=BRqGz{!NlPbUEhYyFQdUW55m|A=w16@*N;D-`;=;RC04JKs#^~Gv8vx?`DI|I09=xd zdAa3-ULKRucjqU{B#blH?vCq;VN%l;dL0e0Y56i2XrlL6x>`eRC9?H<<;{P6;`cP? z%M}xi6nzqFYA>_PH#s-(NFi(P&N6v++|@^JIO7Qzys7k@@>-$I0QR?$$q%skh%U^( z>m#LMj{|+qFt^2cY;jM-)ryl&$6QVu+K@IzTtbyjkF|^{g

    Q6Y?1YXJ!@$@xP1g z$zOr4tbc($sRwRP&SBQMBR*HSBfq(s_3dWpkloq*Tk|7QOyA`4W7}M43aRg&P8kza zqqyln{*>1kn4{|u(e;nc7Nw~!m%3=xPOI!T+IID74t*~9v!N`EaIb1A8#+y9bhE5b zwnM3KNGT)M=kMReqCQ{!Q33R?sWG2YI-e%ID_9W~5VQt1d-k5QW@R@O)7&G^zG(ZL z*LC`I!_D&#e71PU5`>fcX!;)V2N+S1NB~&Z5^>03+Mi&MQ5jx|;xMQi76-ZJdWu+s zcRa>nyhc|<{S>h$xUhQO@r>PmYZ{LXiS~~w5OksKnwAi3l7-5yRNyWt2o&lZaqdv0 zaqU*R>m0hknuCk3KtbMFvnksthKbKopkuVjqBW%vJ>Hoh+9dP1c*8si{j2Qs@1S^P zY>kDBSJWsDh+vnN0kjZDll7(OM*b(^0!`JBuV$MKD+C219Bdadr+V6w#2v|)DiF03 z1P7l`&Xo31k>bvu@#6Am9i3u~%vSyR9wO48tizlqnd&_7CqZDQE(sopFC%59@as4{ z$&PrzoY?&7O}#xK6#MYyBvikrvJ5ych1!dNRdARSO39ocZ>jGAS>Z}!<5{$)A_pw2 zQCV-pv@u}d{Ej)S9d}qvvk|e%`h}IO=!85UCN3mnrp5n7m0G1aG<@r`DG-15< z`_7@Kly{Sf`_JhlL-slFA9s(~&z12Xy(VqFpPnW+LaTp)Ez}sY1&F@>Fi^ z0I}ek?64R-38SiXq;0anP&m2x1?I*{D5NRm7s{x?MI$>LU2PLZSF2-tvzpYmfrF!7 z$x4k}>?4XL_$|3qc??!}9I=v}gc*-ej}_52o8lsr%W5;nRaF9FwBc1PA5fpZ46c-3 zgDgG>8Zz?(XWU9d44eMzOLI--Y1Mf_8g0M$$Q#2fhoCWk>^ya+4#znmW1vKH<$H4Y z+4cFV&wi&XE9W>K0rhB^c1&{|Nxe>paQf&qL~Q{Xc@uA17oy#B1}h(}P7kzR%_8`^ z$dlwKG;A#CcxjcP5TL;i(Jv4dG`SG+VTM3@4+1;c=X5)OjKRtHBo8BKtx-2!mu;vg z5Jv^j&}J85po&FLxjkg{F%0)QI&8!gnMqJaI|$d5aLs-)$o>hKdTU6a&uI+0JQ(q2 zhdync?X7u6deGB2&&`a8x#U?(5C;kgT4%2}dMtscX_+<#;HowT-KDA|c`a$fzmD*c z-sXLYoDSK;@!)`_glO)Gi%LmLf(XZ2N=wiY4Ynrv0ZW0R@io>%X8)}#O8&>5mIaSu zlxmk;Vke!5juaAsu8xkd^`|_Stls=*q^A0?V1(#*Z+6NNQ)v?myYDqMfP&vWY}3V- z;;W3M2uJO}Vn!Y-GufqmaxRCVuN(DvB>e!%5|_rW7^m33`yZYYoj(@~dGyw}jI|Uu zBjk{`$ZoDuI>=z6Yn}YWBvrFgP*0<8AbbhhcR_rtMXuJ?; zqQ<5w8|rF}o6k$K>>;>-?Km(}aJz-p0XAyR?-(_t!}oA<ry9dtd7`%uF@x;9kgs!e`N{eahg?DYNbi#QKi-75x-f$Xqh#=w7 zy|KC*0JN%V{LT384R)9xMi-e7+@9+~@nuC!A3Nv@MQg+U_;RbYE|QeVdtp-Q+&+1S zIJFDcQaSNBGq>Em951WL+2SUe)uQ89=<((^rLt8y{jvHmh(0Z4tmeNNANK3st)ISh z4bOrXs7?!>kc7Qch6)qxkrwJ;xxb%H3RDTce?C)L?s5i*NWPpFF?C=D>`mtG+LK-K z1y~3p=eLPfxACP6b@@EJ3(-DL2m~~(K%sgzfM>6Ox!)swDBU2pf`1XyJ^uSq`rn%` z|N7GR*Yf`+f}*S7pc3&69?@Am?4vGOUm=L>6H)T{$NEvMf+|-B552r(2mkLpJe0Aa zNbc?;V^K|#k2}RA!!FTL&rm;md0rt-RZ0RW;6?(%@*}b0p1dZ`&_p#dwe2kORBeNP zHzbP;jC*z*#aiHVAkOgZO>$l^Xq)^vkAGjk49M>kbe(szxz+7PAD3$cyd}fHAXlYH z-iIybZ+n#d-d7xFadLX8Gz-+Sm;QjUE*#5GGTPp`R~h?g04Bd7Er=!xQS|o@o|Y!Q z8@EtD5tfCMHIL$Na=vkL z#3*yvSjUnX5JO+YRIOjZUsJ>(CEY`SgcT9~F%2;7MDM5)YTi<00=l87P8NhyrB|W8IX{({&;2PmqLBl?Fpya6>=)Io=-CrN&2;&Kz-3A!eAy*Te-D z`4@(Ga6HCr5ph-hE^zae2#9$qeogfx2yD)teUS;SDk}LW%oX(qNcT3)>3E}^)R(8S zlC6C0>0{8?6TL0Epf0PXb|R*3TUb9$ZySiV()XqnifYgt#n4&U5pGP3a_>J=MK+AD zT-aLZ`pcW0QwjOU5kF=o@Tj z{xA`9>sIlkV=f1aONA4)RP+k|wK$)C7kg~eZePd3NwtJSzv=L~9fjy-V|zx(M8VQj zt=exSR>4mpw8iH9HKyz}tY!t1kF)IPzrbpVZ_dq~B^2INR0C^1q|eIOxgL=M zmjh{rm2((5I$Vt28W(W)eNXkA1QyVFk#Ht{9t@0(<;TW&vSYG4N=mk*CdN|~r&*XB zKv#mp!#6TidWw}Z|Bf5I=wUa{7_4w@C1v2_PNKfzXtf5(GIN(iaceWwZc1C_t*(`1 zLTvKIipF?MHo{!MAYgiHMDeh9Q8>ghMPaK+PDn^S6B1a8GL!2)+Tg+C`PNdC3S~i* z%+A^Q&wgRE9DE(I*Z04&_F#W&e0LlUxY1j?V!QzDV_&ZeUA0tt1)qE?ZZ`+KiT6`EvTe$%|d zcuae^xP^amAbtc!>_reI&H@%Di=c1PfAQxK69@acFKo`ATRxk=Y(>5A=G|^?^a=+e z4t~7q&h4U>#h>ea1Z zLccXx?VxB^enRxgpy_+!4>BgEQsOlr;bN@HTZ zm~8k1xxJI@Ea1B5Pg_4(Y~!M+w4sHc%1Q8qOsDGoV`_$6pW6qA;9sU-K(!uxfY|Iq z|15JqMb?ALD(joDy-|!&d`)e5mW+m5Uk%G~v0iXs>L9Ay&VIh#iKZ4F=4V236y4%wBG)f~o!YEi-;P^1^0z<>h95&`9yRO;Lyq z&m1kZF3sxAUIAakBLsukbZjCmhUjr|H^n9rw56qRZpGw$_wzi(&Lr@*q0m-H>q523 zy4XU0hejx)9&n-!yc;lvu}y+@>wm{dzuB$1-c$bckCf@9xj^0>&j?i0ieFQ$a%Tom zKZ^wRz|F&C{rIPrsmChfC2YdFs3#TTU^ACPo0e}XJ*YOctz|ex62e_dJ3np)b&gX# zVjj`L42BVsGTaJ{{3f>Yh3yF~)z~Wk8nG_l9sjDjcD(kQi?&dw&m{E z0$y4|H!{pi?<{rKd0Q}V;wjI`ZNoNT7akptcgR4985mqC;EtShvJO9T)lk%hug0CJ z9Jd(^TAyLEDtDM`5uqKomRQtICd@?J88pab=0vj-7we{Ce&mRmFY?<1F$Hf4y>ch5Xni zrnZpEZDC6cXR(f0t`}{&cYNMb8J><2Ko}7<4oGH6x~!F$-jv7MX-AK7NNvcn;-UU- zuB=2r?1JtJ7KEzSHifhs`hvYvzp_buTA_psDkGuh+jw={#KS$ENR z(24FS(|r={BP)kU}N#S{e&_Nx>`dk#%hqo9!|2J`Pe#DLz< zwhLc3@oj8HxC?u2pNL@{)%Kbk7ZA6_B|Io`uYVhaF(mv`yT?1n}9jg+W` zeDO829(t%U>%`IfkDcU_6`~BnFQQ96A#@dzwLtD#MiAN#SE|m_G)gN z^ihxvsosNQeeV&~|FUy51wp^U_pXz^bmA88!L3>2x$ z-cG!x_g-5qwZ`=7of)@NuWY46t&cF8T`@_jVNjZs>!|D}a|lZvHyV)Djj5)Nj)_Q2 z?o#A3Az`cecU1{SNWZXU3{c7yQPF})Rs>P44?vwGz8puJqbd#ux&ZPIANpQ)=P;W% z_?|27BtLlD{sPMZxkU6B%4ziujB|#ynO~JryBr}{g-~1gd6Q^!DVMamFt+*bMR-Lg z_A6;q-A1s*=6PghbwafAXrQus2bIxcdh5Lqj#^o%Tr7)lH`@umSdpV`*4RZy{RO6c zuwiV2n-|#T{8nZi(!4H73jJ77jftqulGuWv-Y`t@iE&99k- zG%_+15P4g%VXpO1U~01IwC9I7FLA&g0y4G_$-9L7rNG$nEb3no%{1zo7baCpka;xq z3T^HH$aR}zc}I2yx4?YSUp=S&qkHG8&hCzlNEEQUNfZiU>%3nj>~5#-m>uElOO?2~ zL2pXf2FMyM@R$p+CADi)fLfHHqp2zl^G1QCnUW(hwli^1c}3alzR(O=F}+hWQg(29 z7ccD;Wu_q z`HI2)o4qv}@4mHv&Ufo}YikA=U8~1Pw+I>Ac%e?pIVew(ock7{c?A$1DJH=H*+2_f z@%e4VriwL;uyo5_6w51%7DyRcI0upy{fuEk^7@Q{pDC`q=~!nrwy^yfrm~+y z3TK*g=ORW53vNm<63~EAO5;Gq`qKjp33y{2fE9m)e+IQZ|HepsVt@Z*_E8~AX;*7S zF@v&ch62rN4rIp_gW?`X)odSj>75gBfKP?Uah_?Ln864EvJ!(6^6> zm9zcA`B1`H?tv~%UVz{FdN41rbLD2>)U(Yq+?hL+dfrgMcPwUlX4+?!=F*zB@!C z$6h>dIpFAI`Ery{mmNIy4^_{KXgH z2S;Zd*sau+rjf)a)qjDpEJMHUl&4JB_;vbQ6~8wBJCW`#ZleII_E)%r*9ZJaThOV& z*zg+oRa7Inn`Ic|8vck3u=$`&3s}Ph>pgr>khjj1iCLtGmvE_*YotyVIiZA)pviDy zi8M&(41KtuV)R3riyXc*X0k98)bP;V5&AGs^jmM_W~sPZ*-i)_@SA_8B`tR$}!o3-@nobgR5GiGqMH9b)SQBzLe2-66#wYq)R+K_Q& zB;(=3l8U&b+DwO@xtUv05-&URCjPMQu#q!?A=V)kn-ODt}gPI3!UGglV%fV;g z@YK}PuIcmCkTwR;2i<0i`7MD#gNa3|14EE~WvB`6=!BqMNJw4qMA4@!DD--g!X^;H z<%7<&;urmGiGlP|2!XTQ>guy@WXoI4C>CqHlQr}k*cS&L;{C8WP&#V}rh@(u+fPB6 zWe5VNnbo}{i`|;Q+)E-;GZ*e}A->IEn1xT#ikm7~eUq&h8;+C~-$u};ofQNdaWg_N ztxcjavy`=foWw=XbHyc$N{$q8C}7c5Z>K>R$P;+jw(ee`68?3i^%1J05;yXYB0$r! z2puqx)BMv|`oP^}!ch-EeODb{WQdj(Hk98@5o7VX6=+iW^NRwm1D+u++LIY|IH`BO zX!!eE{{E+>NIKo-MpWR_<2m!Y&avPS@pbqE%twpamHwyAJWZsS4y?PoJF>&8*IToA z*hj~==j3*F+ZX0Y=ycQX--dIUIE?RVbHwCQtF6|tRflpFf9cbgsiTKC)_14{|8dI< z`ijb=^kt1?eMnowdPQkUP;=a=nbprppHxKY#C^ky=*6oIi;x_DM4+DxE+%=o6J-#CA$b*OE`>B zRB#l?!8RpCRNXD6Gp$i`k~mV6!@cH>L8|yN^%}D>CVZW3ZDmw+t(m#Y^jZ*k8*7Y# zlMt&oDaePc@Pz*$z3zx+9eVuH?=HeEj;gcatsv*z$0Y?Ty8HSZpsKxRwn&Nq$PW5L z-hiE4@50pk7Z{lte9crD1=F){td>Kn5WF)ew9dmsJPMAm_A%0u=K#fSQ57lSV)`y| z%M_#Q@)H0*ue+~yPE3iib`~WuCNX&WHDfmKKnjqn?YHJ()0A&kgSB5$tE^iu0OucE z5>wBNaTnm;fPO#eD5{@yCrcTTnu)j>kcO$@h4jgr#mOWp0B2Gth8`en7S~R*@C7)` zNjJtTI!Y73zlL+u79@?Zykf=w8d&omZE~jh^zyohq{|vlRErZwSK=aF;87!;++|fz zM$3S4M47|*|H3X;{x`8p73AgPd6e6SIcyEobuqtY@lsS9LX$5CMNG>>IThiWQ4!^z zCE))^W6zKmGIB!sjF`GjOy6n*9X29v_nUY$anbP$e!Jq?=Ez@QM*cEt@%zDkr*uhC z{{_EV+#PfF1#rDZ7%m8_lb?t*`N>v_AYTisV_=)V?FjT2F_Eq`A-hDBqd!1B(nP^L z_Px-NW$ZI^aeexkq$tU$VsC%)qoRlkQErtn29?)b9M^hKUC@H~Q2Y%14G~d=6<0_X z34`#%qc@6}%oE4Vf=W+OF76(WqrvNF^TmYJ4ToEL9t4`{7o)f3ul-xBx$^&{La2*N zf8I}jW8o*w>d#qrTf0q^f&8WQoWTEPqhe2R;Gd z$a?1C3rvH)fWb5fZhLslVJ5I$A$ITincHRh4sCelHme^cIP%pocE=oSr~E)&!5pPz z8pl5201&oHpUUT9RHbsHk}7~h@r0NnkH;22z+Cup+anWAw_A{>t%dDoEZOVHrxmp{ za`I+nT9}$43~v6uUJ1Hh=_&jbbOis|D@Wm>e-2_a>n3N?RN9NL8@%q+u_h$=RvPDr zB8ff;UyZXnaELa4*qmtFOa#u@H3(9}df*+)I0&5!S`Hp}v`fF6$(=T1pKR6{^ksP= z0l=47l3Xl67O&1L`DxtFXe>V}0PZQ`HGhd1mhfthVXbN9)7B;#!rSsoN2cd9XyOZP$4 zc4kE7@+>_EFf9@~!4ywh%WAg4adpf69LXG6=>Z&+#{8I)K9pBjYawM|mDlCCFWTx) zmSW9r%g>xF!E!kOigXbF zABT~D$o=J-F z-CWwak?Jb_c?S}Fl+AWg{}5+Hp`ZYm!!@TG9lDnoMFt$xB`09iu5TGn(aK=Zp`_H# zt}Zst`NUcnX}Gi`A~Zi`KsL6p6buZ0;Gncsc@AmQ2Uy!Fi$QfFY089CJbK zvPPHZjf;BnQGOvb>gM5T1H=RdJvfYMy1f-f8)K?$~`rQ7GX=o#>iBSzR zGvDoa*Nzkvf%k#zYDlj2OyTRBow0{tn+M|4D4fJM0L7=jKp&jL<>}bLc&&_`$a*$m z-Pp=%9kIsPc2&c4cl4KCESP!(qoBJ6cm}py-)m|xdF%BP7Qlkxl%j%W_lg+t84_d2 zR4y9auiE`S1?Gj-2c15ZLyWiD4vJ`l)k!2XWY2s#@6L*7-O|5LfME*uF>NuTD(7|n zakaD+!eMJFEmLc*hu4s{1|i*wCrGD}2~V1|B*mu0VFGjiV1V2fU?AnyQpqaFD&-s^ zR8^Jiv(2^!@bXkDn0n>mL z6BY?NmXlRneoCNwGk(jodt7?MmNdx^g2Mz3J#7%?wcTP%Lh0y6+XuYYrqoTrxI`P~ zhq@0Z1o@1mRBbG*7?P8Re3UpQQsLR@7vj8*wgz_F_OpTu0$IkeA+z3&GaV_9Xe}<} zz(TIQ!J4|+$=viV&H=HW7ST9#s%WdQ6p%voU5#VW&O_>;^GLcoetc0wY_B*gWVax# zXS&Ei6hUf0L)|Cx=fI22O0c=JBPn(3;xgTgma?m9W z8NYE!0yAwZ2Cl*{b;u+dBN__~r!2;3#?B;1uc2EFhC3X3M3T@x>tUl&ZcaY~K+Q$; zqYuvlw>`O;CZ7_r-8Sb?7Jr6nfi!gnFT|6w7OHdxX$M!H&IS>mWUgQo=EWEZ(@;@r zAIe2SLcP%05T>dIP z#x^t$`pAxuuhdee6=5i=8)~Zpf9N1J- zA?k!`CW#N^OkeGNjp%%zd6mDCio9-EL@S=qokVoJSjX<&!s5d_6nf#~T)9=H_h&c! z^wib3er##gycJ>zxRHFk?bHx!HPFfui~~?EnVecokF?J$q`2c1ok=oNI>c6^+|ZYLJ_7OGnE~NH38S|;x@9|hb}WM?Rl2#G!<_uvy?ijl z>qnDrY(biSB&-7Wj3%dmJQP`O$>Cpu9q@tHy^>_>d#H4SofoMDoAQ8-Rn7CI7(!6- zhQy^=D>Yfb5FatcqEQQvL6%-0e8C`J*)d5-k9G45mur2UZ0F-HYy&}9_fV$F#7b*z z|AG@2(a-0(F&DTg0=pK`fiq5PJgoUSJT1FS>omhw>ciN$Yy3A|u5AcVqg&JjqB4Hy@Is0T~JZHaX}p;dOt2ZdM!M;j8ZZXhp3+y)S9he_^BuGcB;35pyIt1;FzpiDFh z3ZcHKp=S(0pMuqet>s%F(dW0)=6lq0!pJMCCL5Rgx$PE7a#pu~S)}le!5K2rFD(Q{ zk}iWWh~ljsaDGa2<$Ot15#*PiLGm^gj+fpst~l+JA8QloLY}t$k6b@{cK@Ag<6mH` zQOMJ`AAh#G)R2cBBg7Z-n)$L=-O3o-YFj<&+W$mNHFlQlZvd_|BwNZO+;ACThoNE` z6QRVupMqgTWo(#y(G4`}$-x;}^8kdN1FONx3d@IdRpibq{NgNjv$TgZOszbMiIQCy zzViQqC!F?WE1k@Me40{El6jJ47{u2>Y74vJjl}ACLJAe>M&~f(DjmM(E#XK+_r`lf zkg5(&$?=6_?L|s^75@f$q;QMWOFfp)7)1{j`;q9ej=*Q%JCQf8CkmL$fT&=pa2BGH zx2WBpiFOBeMeE8ERvSERKC~vH(<4uKUB#;U;X9qH z{NEyr@A|Uu=bB`Hfz9j3zf~*0b5XZ2h8(gAKld7LW>=k> z39Vn1JtlR{>9d3_*eW&&(akqHQoga-Hmh(0wrLY02ry0%pix#^y4gl8(wH+izhphk zQ9;RLYUqwM0I^iz!qaAee}M^*m$3dA#71O9Bn8G5F<`OkH`(aOtqG??>4nivSeG(y zL^ltQL7(mt&O0#9&DSaaXSN#gpIW9}#LpVVFAj<}+Cu-Hcw#rrD+1${`sj@Dls7|! zB})h$@s~=eu^nbq1esPA=`>{v9r~i9C12YwgCU4>#0m(-QO}QwM&hRURUNaX0>o8>GWibNPaZui(pigUR))5M2)@vx&1CbJO|-KNlU5~JX08#XvwYKjXreeU=+##qO3y`XtLSN z#KzV_KhKs9Q?X2Re*bYif4u1l*%+HUIwfFolestfo62mFWDYxaR^nv9z3bZ_>Yr@( z*_DuG7Y7WwyTe1zrYNhemA|v&U3o||Ev{0G8F}=aN}H3L^Cj!nb}#!y5>d#q@gnNh z_f@dr;RJ}q=m@0eFotB)0~R9!4aCCl3LF}kK=*SPaAf&W9|xvF(-(pF!$tHKHlBCN zhw*Rjj(>siv>u>()C!zBlAV|+(&;@7r46vJi6ZEGX(%`xM^OMhO4~f7`X^-c8d&3o zeqYvc3WKYG9*42*q}1bFi(E0XQ8nvyI_~YEipKe>DNeE#VsXvR;mZX$%{Igb_0f=8 zY|(?sEI=DNCZ@SJeDH-p}K8&Ohme#k!7IilT#F=3_3(${1QbP+{Md`V{r2IyXLx~L3MTry-He+ zAq-A*$R=9z*_GI6wvTaj7~u1|X$~125dmJ9WF+n#{*;G_OR^dZDk@Nk3SS@i(%V1! zd<9q3?~1XA;})i);@KH#8{t&pZ}+8Oypbc}?wH*`+GRHT!|InFL>cw}$Fgl~jQ z1Q=ab#SCW_{>OUm|B^p>ohxFU|J9~!DrU6fbmIDQHmqaKz!^Y7Y~z*U^f-uPyQ%9bl>)EaN4flrM&c4RtncX+tlLHrk4 zT(7Ai;%w#Uv*S_zK&VlkQ5W?y<{MqpRcO8cQEt3n_y?x$(j ztpX63;bU8zRvUVy4-v^{+BvPwEXr1~x)jP1;H5|~ougK5&HvSk^obSJ#AiN%9TT&d zJtLG2^LK=sm6l3)D69-V>X##%ac3#-49`meqc8NSOAQEBCXHyX;xVr%$zLq@cyY>hnD-$P``S4ub;r* zq=h9G<9qsxSMbyhwnuc0tkL4Eo*nMocOrwd!UH?P6cw*Z+Pd`egs=)XEE9KQu1leS zv9i_cX$9(FhcLE7^ozS}Lyat6T+U3Qk@ge2?0s=obOm_Yy1)@r&Kpk|l>A_P5~DWe z(j2m^v4QEPUS_MN4W7HJqgK38bRu60ZKuC6yY7Yi08yEOj(GPBJ&@AVxqdtxtcGE7 zVw__>&2a7e9vc^v;6ZoK|9X_hz+c|k)kk#QaIU+8k)6!6h!>d9!}xZURc3U_kehuk z;5Mtf?A~T9DaXhcVrr(=%7|r3?8uq!2_Lkl(O#kjKoK)DgIbI_K?zlN|HAggFXvMT z$CPz(R6Ev$d+1*I`o+T-3(3`uvS?iO;hM@&ax*qTNmPQf);y9|$jyZnruwq#w-u(YcV`S*0hr>}Pk; zB5=ZKQpFZ&6+|%(Xo9gAH8~SGRtE6-B{uPBM0RF71-i@^tgytQ_X*dz8#&bD8rHON z=8-Zu^BOW!-Vyk>D>MNDBtdZ_XarGrY*~MS!FWyZ+*N-H6RgpBQ2sdo+*m(9up2?A zVue~)JxkgMI4MMD2}-5Zz&b#qQH>kJJhDw8Z`ak;N_5H2%dIyD#h&m` zGKx}|!agfUMlM1fQ;OrIv9&?aF0Jwzh|S8k+Q9~yq?Ks*X)%_@?Osbq)6VPG34SH9 zS%^`M%C%R0;Tu#$2B#CqVGKn;aVUs~^>l8tfo!v5hqHNDD1tGX5b1RS+}0&Eq+qg7 z3JRene%e(;Pv(Cu;kgpk9a@_}D`hxHab*V%7(l|pV4|F8q_q(U2~f{@#T>%VQtV=` zXJn3}OTz2brAiZ#h^e)>t7e{3&4Rw1^-WgcsBVzJh$1v4JBdnBJ*|3Edz$%uz?oVL z0oYfKFBKdl)p%c3*$0}P>)JKTZM(Q$Nck1A)~PZfDpVEO9oC!y!F?);{OO@(dfdwV zYGwAMIjp`b!aqXWDPdbh2RSq)vPkhE91we#g+q%42RRJ!#^ zQhLU>fCsn7=LaP$3=m)%8RnTt1>!EO#eJnQMY0Ob`|FnbPiMDWx?dDRjL%dNrLC%J zilPz@h(MB*JUUGuEQ#rjK0m#GP+bXwtAjUVJU|^+L>_g{M(CD~(ooxSx052~J-Rd&a3k`~y(I&pA6Ox#~w?YelwcZB6W2xlgZ$6Jb}-y zi{;GCbIpD|Il@JkLo$b^ka!HUCBY~H=mWKM1p>n3;9e|f4*!a*_f}X**(eK#tM~Ja z4{b^LQR^=<);#+j1DB;&!ZAwE(bhZ+=kAePoPM_`go*l{C0b75F5s4XAEf; z6~;^Ku?Lm0+@)Z12FPcqArZ|b9C-}X7-A5x2<_Z;D;hvANyF(P@Xps z(>3Sc!gRIGt?HD~$_4peJ%PBco1xVfbmL-x0Y)2$t}Uz3n)QV*7`k427c!?`zG!jn zbz(+^W!`RNSPi^<+evvpZKjX-*!~$9ef2Y&$BXK<1>~ceB75MPNjo;4JMM^v1b#%& zc){^`;&&C6P}t?MWi3r=zPXgpd`tH#lu*h8nTJee2t7Ff;^QB_hLl*7axtv8gZNl`z;=ZPwbS%`r2 z0bpT_iuYG0_ysd%#9d768zg7wd@t80ZhMWZz|<3>L3`e6Yg`_!n21clFPrbC#`o<$ zYiy>nF0n>W*_yaR(F=LIN66Fsm}fMNY|Rywt|y46w#KZB$&#Jb;Bs=qqq&~P&geT4 zuHzt4yOm7xP;23?U2rQn?CYfw*+IJ0FX|tvAh`(uA*@06wIMS^c@@fxrY!xAG+nfX zkB`o@@-3cPZxoM3s-~UOvGWBJxT-$Go?m}jv@>(4)m9P2RA z&ae#!+2-m(>!qh-=8-U@t^5_oO5m5%Rx39KALTVoM;7g4N$DBpU>UM!f@1F?MAL_E z)6%@Q>uSYhk{JWxp5b-vm8O(}@ZCg4f>sRX>K& zt@#Sy3w>uFzhEOJn|x?_NGW_o6sw(Zb?KPGf`=e?YuGuRZO_EGN8NrMNYPe>#>KHX z{;CSMX#1?Cbr zmz%58FZHfjNDjSAAAx_jU(%vB5d~4*L zu0t9f|8fGfw^3lt%6iM`_02ANTpuB0fc?^!!NH&?IO4aFEtR~25a z^=4&px97X)PKTq6FKCwPwx|M~v)ISTyzvBVLq7F5IJ{MU6AInE?UoUBmS7>lY>gK} z8@*yGXjW=%MIbtR&%3Aw8(XGIpjtHioy@{=-yp{8T!#!f9v_;m;2A~U7Bw+q{A1Xt zXHR>eYggH0mOEM^S4^DJYM~3iXC!aFO7^#Wy!d@BOA;CYgbdJxV*|QIL`5Z1ndDk+ z#lia#DGPYi{s7>V3Co@RAF4p=$=AkIIC$(53%ByGLy)(X8rv&j*sNVx_7+4y)D|_X*x-A!Obw%8gOxjblt3%O?`JinI z>L6bn-aev}E3M^( z;wd|XNglgdN36d@y`a^`I$e+C*gBRdr|XbJUb7$_JQYJwvBvt63zDq!jcJVji+yKXrUDoWk^ss}iH;Ze6aoP=KIe56_AcwKXd#=dBh8sPz6@t)VB2HBaD?5o6lGWNs z`&e+-t;$k~5XQy!)cIDCm zSTz6*qyjIN0c$4j)*rje5l^W>>Uc7&)%DtCQq;>&?J^=-8}g3q)*@o(08H>4nRBTR z#hfeQ*3dicEbG6TsaQNVp+UW<#EV4xeS}xem5tK3hc&Hvmk|DEG(C{bER5A}SCh_03{h>|w z*9GAFnHSh7kOXX|WA!`cm-M9QPPE;Y-I2)KJR>x2+Lk;b>!-AyY4Gy&)NApfp|bgm zV|+CIq7>kK@Q*{J7@zGGz9EXGbROP5)W+=NZ9MCC-e70dbJ*xPInk1S5~oj=JJIc9 z2j_;k%~N6$g)Ts-Gc_sA{@;FXB^*?GC<-j^M@C1LVq3Vj!%B?mr0WC_7W(G>jGno$ z79pSa;i|kC@}|dR;wK`kxHo{cbx)+2-$-FYi>b!>Yi1&wF+6@Vpz@oELs{VWIIz!)Ij4w9Q8J(j zzLUUK)uIS6;$@Lg85Q{&fb38N!M27)mGA$j!Wc_(Zt1XR>FbRy^v5&JbJTB&?lAAP zdkNGJ;Uv4x2yed7j|8Nf&2nIuDE(W>68DES0hZq$ZNvv-)%&^Qo7pP}q89!2L9JEK z>8(`PJvDk(2CM?tmQ#_h0r`FU3jYDHYUxkOn!4r~Ozjnp32=q_ai~@xS#E_|ZNUow z8&%vvwbvL6$H!+-S+uCIq~;5I)Z@f4WwiA|9%!SIO}!ns6sMEjr9^*P`iM>=*juPQ5RskJc`@|N&p(Z1T<1ewbR$S-~O zh341`PI+Jn`+k3>ei3*>vUR`gx2KHx4@gnp9*dP>5422k=~_J{%5#ov==Msqx8ytu zvvQ2b42K?lPQ69Y(hmxiVj0A|9L+v0Q~d(2u$b6^@{?mUa$4tUyR*T9Lp#=pwlwar zhHK;J%xdf8)yL1|v?D7z`9{pi8%gaC#kSU&E==hy%MDkZk!;1og$P#n_!EYNu<3h+ z(4Z?(X|r32(H!b5Kh(t#mHnyUocxh$Pa@9L4$cn|^KHAMLx25m?>ZKh?(`T|zrAw5 z=ZR*jh~a${Xgb0s%;OGddi>mVI}Bzjo)aZ5$U0!cQ5abZUgFSKO=%vGFe!!J)Y=h& z{;2)&eBtBk{LjS#m+HbOwjDeYaK!nBMht77I%ZyR;nDL(CSz?T6dFeOPuiZ6%RB*M zmTZS8Zo+IDK}e(K_mN$Wv7s2k+Gu(Zf2~;=W99VXBFvuJu>+GGM9nC(f+3XLqybKXK;awcc zEsd_qsu%OY74f*{umHU1N|d_M46CjFeS6nwQ+q$U{CcPI<=uPG-X{zcWbRk{2T-ih zW%3sC@Rws_Mdfv^tJLbyB0KX8CUXFAMeFlx3;kNaYvgc6n(^|Ouev35skZM?D_)z+ z=6>r1J6QxNo?I`Y6DRkt(m8;vGzAl5=5r2XRJI|?p2oZ@^X!=NGT=vr^FwRABrK{F z_MF8!EF#6eL*qy&ciD|UQjY#GNV{l{x4=hrRP9uGvRMUWlT#s8VR3g}u>sb7vk8?uh8>dc z8_ny2(7M}Mv8^ghMzPy1>|Y|~!X_n+S(Q1I5E%I8&TwbU8nPMi+b(>}f4E7R!jDCW z{Mb&lW8w{hhBlDO|ll& zOl(Rlv?*0ync1UtL4U@iRkgQ)8T_>;ZMsfzDF+FYhREBF{MPESCWZdspd=Hp`??xO z9M!vQo#%FJ6@SNp%-GP_A?dto0}D7|A1_|buq>xOHto5|x=@TA*gj{P;c?ke)^pnx z$4qVxLy9ZvStg*^gidK$w7i4RXVzGwH;7VQc}fJ4d81R31_*uqMhwvI(s30 z?dFIQ|Kd%H-(xDMWnm{$SJ#-f&`UF$sn0vdoDFtfw^d5cY+xooy+z4rHu`kA6oqWC zoIlH@`6=8L&NcAjj%0U1NrhK^mRVa%YA;e8cAxP0Ft&kEY_JV)V$xcORA03sqDfB#1qBm@5-yTPu1X>tF? z%bTlAcI*4k!1g&>iYZT(S0YAGqQ?m6?X{C9g-60gq(AR2NP4!yJDYFBG1kjvLX(_t zFhmp`zSS}>f<@U%5SyMhPw%!w+LVEW)k882@mwL;#<9?Fj+Vsz1@x}b7v|<^R&}xh z*aN$!Cf^npC0JKs4)G161(*IcgdywBl+(^fX$u(0`vG_M<-c{+751CK%TJ>*+l}2` zloN>{WLv_I2LA5%S5R#<`tet7RPnmOcWfKuo%#W%{Z!|@B9E7&>VErcN+96Hv(qML zzxrBhs&nqYXQ9cO3$ANeEBAx%RPg*V2Qdq>V%>u4t_ym$a?kJU`gjU_YHqyfy1M)W zfZF^xz2CqRxto-Cd9Hga&2h?hzlfoE@M&Cab{09gRsE`UHR%QpM;77y|yX zAUV*s9gVVPha{-5G2C)?$NL$WL3Hx5tvRe>DqrTG{y1M=!{oULFca-r^DlqijrK3Z z0Bgj9p;8*O98E*ldEyKfn%fvZ=>1e$mS+V`UrY462+>vbk{AJKgd^9sCb;ueZ3xk|RjVlV_U-qM3`KCYqJ8Qcfyshw z5@ICUHz;c4PFwSQx4o1jRY`=;mdR3S?_KqIF^qxtl3{{9fSSiJ!3HpgPLzc~+;U}p zyNC8BJ5&gwi-<&hCY=x}n0xv3l02G(L@&Wjfq>8HH*n9iB*%92mllUHVk|JtZekdw zw1mIV^CXm%qu@8C`EH@9sM5nqlxTv$kO`VlX-qpws)lV;NJJwho96wvZH=naP@3x+ z&{SakoaigEkTcw!oFajWm&^ikgeu7GEgZTip0HO&x^S2iw7Z*i=kmTggR2REVVqgE zIs?6^g@_Cih}KKzI%>dp%w((J{_}4Cny7B+!bs-$PuIi;QwG{RUNr0u>k^S*zR9?X zDWEIi-rF6#V@xN0jcNd0WF9a{1pO1x{}IKDuRg6B&&{+l6X-hMk*5>ZJn#}Og@;F# zO%-eJOS|tdP#HgbRkqG@nn&AjeQ#rJn7HaO;7--4lWE64Y{CRZcTOZ%H z_j8>Y1WG?zSy|J@7U)=rEJeaixe@j6XB~K7cVCx9EU4q`oY)Eh6x)%<%E??&hz4suKF^r{`p_TW?jdRgn?^ z?+?+xxitSo8C$3+d0zTr8jn^XM0E&Is3I`+#b)j~9CDUAqdt0G690B0?EOES2yy=a zx=EPsQ4YzuQZ!W}JeKDpm0RLGffS!Y4I#iKDHIRYl)%8T28>~)t&ME*9n^NQ`N_b`| zC`XyM^k;!a>7*j{OXx$~L~XJO2r{hTiWjJ4e@z@t#Vh^M9pu(ped#;?2QcK+J$YWJ z7O@?;F`eg0_w6^_JL;6E(!*`jE5EgGmG*e4y6X4}fe8BHDS+UybjCRx`LiMt5%hW< z1Nn?+C|{N^pYK(CXoHRI=-9%U_dAeey~Y)+`TR7Gs(^z@(EBNmiWbWdBBc8W%a$H+AnJ0UL>@AU<;eh6W3ufl6;GO5Kl5Eu%ml+tXZAvjE#~~Z-#T0UpcS)8! z;DRSdMtN?{u48a3pIjc)r9cWFlVPA$f8zYt8(faJz+7DveW&@Uz8c6u5V#UxWLA1<4hFwBPsHwYh z+FTzy*yyH6>3-tyXrE&Phk4@#Y`bgrgA^jG#))LEknZ%SGh z;ej61v4*^h@zOOA?gn!0jNRYR|RKf|87a8o5Yu zbwT1p={Y=#IH}E#S}=FKwu8e*ICFCw4%Xc?^$02hY(l%zf})D}!UgOg{30I(gGdqN zs5+=V00U7+3h!pGw$t+rL%r_mY}BeHo=R0F^|~%D!Zn4Ortz(016M1m{5;bHP&hQY zcOF2hwTHCw;ccpo|AvNzfVFFJ3b-qN(^~X!n{@jL9OC+o$c+1SU`F-Fk;3mn=SzeR zlH1-pJRf1JJ2-OdJv?#5ZF4K5jtNUfS6bfNND&t3TkLNW?nxmz6OYAFf+>hi2Icij0s^RF8`7DPVg?ZYW{9` zW4>AGB9V3}^b8&NPAPX`UHCT9ZA`zVe^%93sgKV`SHKL8DH&8JcYmi53}Bau?FGI(nS414k81 z=Ig6G{i$seK#d|JC!vct11(H-4i$>k6g8`@4!SHn9ms z7}Tnn=x_(8U=(^qo*Cs*-tN>_@S?gr*eeP_|p@Ll?Z1RSBy~ zfP3EN=GuaukrF@l5J}bUXXd|%%#xC>=p9&FOsP?=KkhE^C%IZIu1dQRYX>b<1~4Wx&@Qx9SBbDSBw#EK*LN55u_s$qN2TCx>r|Brlba-}si z*B<+1^v=D@NAC#HNniejNVk>iLv)@UzCGZ#y!vram_K=nrPvxhL$abe3+9aQjWW(l zu{%j?((x>~Kc0y>4g6TxK{#*ekL}j7yyWaM=@12dDe4TBWo(j2@f8Ro@JkNYv59lc z$;o9q%R%N!OvN5X-VGHgIZbkzGN#X5vM<@a*ulhjCI~+PIzpZdo}B@|VwBu!eG4vR zK5DsSuGAaN(=L6Vp(A}LRW7VmJTq+3_MzDBqZAtH#^_tZ+MPof2%0WATP1ORBXC*1 zpgKWWg3=&EHABno`iv=2=rNzk2!}?+JMCP)2^pcNsu71e{qPs$S(tx7&%i4vC^z0M zi-5{AUVcpOjInVDVVfYrY%M@OjD;ZzVCX72FH6shp)q~o9@)as(NM!99Bybl_p(e~ zV!Chu*<@{tqzi&Pwc2h1UQzuLDPO0nEO-|${*$!}4(1>l`UsH#^E$Cus<%Cqk}aq| zkOw)D)bW7U6SmoO7d2KgcWPS1%C};-;=m7uhFtCrx)*Tcb&T>V`)Hr8$&D7m07{Aw z#-^{v#{Eon!{QvYGCPwjYk60_CDl`(4FXr)~vU z|4tdr5q12!Ppy8o+}yt$bHexsKycbozAwB5jB>6%tetWHU~cK&`+T)I{AI|#`OCdD z(r!{YOUNJ|?b};+TSeJ6dBXzh8PXlc{?|LP!ngaOZ<>$rAKW_icc~$FuF^e^S-*oT zulwK1)i@lk-s)NWwkz!4P2OF*I~H@Lvo@YE3AVx^uON^oa1xaE+e4 z8Rs|~ihOiMh(rut?+ka@L4&V~poSJi`FE1NUzOJKi`+o1rl4G_itS)Iklj+b{o16u zWN+=P+BmN>$7d1;f=D68L~lb;osIv`%ds-8bZbH)UEpS+`|WToQB2PRiUnDt4LN0M z_QhymwZLSKbIaooK+FD$Ck~spw0K>O$+o}WvQ?Ivq@oY8cD?h?TOL<&36FD>Et76g zoCY0j{UWq;=xA1+-27Mhp0bMD5Kiq~9X_{%&BP2S=SG4y$)@~n0nAPtQ@$$S#zc=h zsUg+M8l}qg0R9?9sr}YPCzvJZCrl+$7;*Jj4E=6~Gln!gp<0WRS`=i&5gY^NO)fKC z;}~uqFonL)B!vzzv@X-EK^TUJ;K{A0;&e`?2|r@NGecI=du!8Z$u1FMb{vIt+WK8y zLR?6=nS*n84~$CtXb`p5*Fi|yxHj9$7x59B%$a?li$+7@q|T3+=D_x+ zw|b5JT;VIBsm7VnZ@QZTTgJ5)vAz`vsvQ_UVbhh4xzJ)}jFw;u!d4Nd&6)u2 zs)$nvA29{>=(FfE zxC&19Vx+NkmfK=|u@?$U0*(3-|AoB{nMe6s<1H+C=z8bQ(80Tq#^nxiVk;$#aOx57 zdK`=}Aa$52rvj2%8ZRu;kiZ|Jsa8urDF1orrPm0(8&2Xy+sB~(eXigOjH{EmsfEq=GL$L0aC@SOJ(bH?frnjy3Z+Kc|}Ebs-~6auFwXpL&|ctP4s#yN z1x5xwtlIq6j*bP+!vCF*LF#xp$DF3?D*cuO!Y_aVD25Ry@Y50&w%x?ztvaflNKIUv1M)kIbIq;<=DZs9aSjoMXi}#20KKUbk$IhB3kg2$C zqeI)>jb}TtWlefnn0M)AesSC+$X&R*USrpt`!(t!r0d~{`~Gyt_3rkk!_LMW^2O>I zx67$dUSLqoVUUE3LzF;y9`#E>b{5DmMJgtXIIh{XO0zdwL;dmHBq>(A3~pn}HTr^! zXF(-$F>xeh2dB)>>Lb{Ple7dl$q?0d+l5E^SJwFH^=wtetM;X+t{C8 z;k!q@odHL^rrcB!b;X5&-8VAQr2Z>stwjM(R8q1|sa0hhsgzB;;qchnpI^z&Tql+U=c(dS8OO>L_F;L7^yPa*M|C zl-2D~+I{3kpGCkJC&erlDt{`W;cK%r&Y5Z4qaJdI1{$F`9;|zMvF~a$F{Pc|;5!zk zHY6$AYd&kIU*OelhO&zDOyDn39pS5B4>_w7hZ$ec4VjcBeD8n8OW&QCz7oYHwdY5` zUljHYL3(`_7y-#k7}VxE|5N>by7~X9-=#^8Te-#qdA&T^!Xcr=;J(YLn@UYHX`Ery z4wUAdOB)E8@`cIr2^t~{Kvcj~()76@?rM;#ktU9RGlcA>NJn|;@z7GBYd(zZ&4uQ8j>7%xjc z3Q-W{VF&<*%24OJ(11p|TU13aE*ngf0-2m^KMw88%LNbRObZ36bB)U2`4dAUND_ub zfR~^oqO#q6`^4*%9N$9<^^Uu}b|h#o$gXfeVdT#ImPT~smHa@@qq+&FOIig>q|mF0#7ee0r!kV!gO3^{+rNaIn@P|ia2=qB!e<#h57 zlc{Y!1zV;H=licLmhL~Z|33INA|_T9CN}upMQmZfo!~eERKQ^IVJ7!ZJ$C5}42ezr zZ))eSDqqoY{^=PkWlbR^5xliLDo}m_er z)c(#Dp^CD#2tJDtm*~`jRfDb?txOy;q#ChbZtkqQG2wwAU8tsz!h9&)#Ej7k4ej6# zuT6OWM6358%yryegvz%22O!{yyVLu;&dJs3IBfff;12+IlB99x3~2H8%ecjlI{CrQlg($D>fYT|H1NEH8KNN;@Ly&Vr#hrj&>addd zdS?PRbguK{#4EM-Je&TS|N7c#uAOIQ$INIrnXmUfa2%qqEqaBQcteGgym&q`1<~RE8(TSjiI#a zzNa=KAmXavJpSy7g`zT@c-Dy|-ZHU(evVu9^F(AJcyJFMq^hDe2Ey3UU9j z5ahNUE!dZyCv^U$85HP5VswWtGA62g0+ZM$bcailh75)fQWshm8}{^00+TqxM|n^i?n!yx-t2;aA&nQw=d^?u>wNpH8w9jh^c?XwR_=lbA;>1A4Z z#nL3@x(FYZ+SW&rDmMBxCfgGF;0RR-_&o@Tr>8tp+O)yjrDdSI2jg`R#t&(9B3(1Y!o=}xZDRvY0K z@jGKsSU*QR>c$%He(qP1yQI@4nIpJwfW_l2UonVK)g5;l;*dOO9IV~a@OR|l*jcYd z`vDok!y8xJY+SbdI5RK1g?BnYhuwJ|tbTgTT+s59qRRb{7~H3Tbq%PZ*yC>-X`*J|+tvvO5co3LiK zdqIy&|9V_MUuD}@9+`)G)R|+DIbovRvd5l`D!t!GM%TDMG}OJf)89ssw=6o@m7LLR zN98f+u1J!9bi!*D5d3rKvVqKv*#DQ&ytcG~w9T_!yjfnfRLeo|-aCA*zrmXx+HL zDBt&$X<$y*A7BdiuIaLRy_{rg!hZvynYxqC6*fa~I{s4Rm6)AF?W^+BC2pPp&B)m- zeBM`d!9*^n4p`2aXLw8jtD&FbwPtL;VV`PdhbCw~3C~ezW1Ix#yIHYfT9R9snqtz( zN8T-R>8zv{=n7-Bilmknfb+yq*#Yo-Lm#Eh!<9ECDA3IHGhLyRDuD&ARZ0WxRCf== zc84+0vln{bX%c{o2ddmJ9Wpc6H)o598H;hXE#>mcsLY5NwFbRWQArz}-Vdt6ze0{Q61?MR!y2o+^aSSGLG6!onR%?neTnfVyCrZ&HJi8o}$d_OU?Ly0ExO7 z7}j;?%O_nQ=~U%}r*?qGI;k~qk`Kdk<55HKC&W)?INkPZ;-gjJ!5s%_wRgVDg~2pS zZHdd6O`2XN!X|gU=f>;CM0z_t;r7qnxP$Kq4Kpv%K>c9p{?3!P_vaYs_tWC5#-P`Q zSJAh@fR8(sr`?e%@!!e7RkS*%#(_j_o)B_F8;)3WjlN$e4LnjAll zC{dfE_@OA~aAm6DirgWLupuS2yvq6bD>@zv8pc-Tj6lmxY#0OY%5Vv&fWHqj$Vnot z{cOt4CeH}fy=4ZZ=tZ`u^2%SuSv&s0&=U|Q4hGJd+tVNpyUs3TmDH|f&3}fqq#&`i z{EH9b2B-K=FbeOhIx%vWlcbCx8U+mR2j-crmr?MzCVv0PU504kETcd|7d|$&wwgAA zFTzG$^a`iXJ=%|*g0kHX!8){tsi)U$N84q0Goq}1F2!_^{lu!vUYUiR`E#PrRja{| zEcKV@jK!8+Y=-OM6qD7tJ(Y?Pc0}N5<0wJDh>(f=^d$J-87|q4&lM1up#3RyBTP32 zG5My$;GYiNb1_H<_x80>uMIWI5TT>Jj&#Ks^ng;q{z1a(lKEicIE=b~k*IR`^~ z$rL|Ealne@5aIewBebkcSPdclE7v!<;@7Dmztk1K9$Y0XqyLJF#rg{NJ`VCW+)?`j z2>dFl_N8x6CblhiaSIhDEd%H@0mtv#`+Y@2a=8^v(*0(jO$KE|>c&*ZsC+MmZ zxruW@=&V;_FM?~m5gi`b{+mqkVkA2>B_&!8r8>DI8)kMM^H3ur36_=mZXmh(pl+^{5zM_xDG%H3bbZKi=aJicd}N=H5jPUhR{i76iA1o4y)$L4alcS69Y+z>)p7PrIMO>8X^TOew(prf71>L z>o<%Cxx8)ll0mBku8YSJJJjq7;-`eAKBj4>)>zh9S`vqIMKBz;4n!d$ZX+R*X~ziv zB822t2wWhIQY~chQqU}_1GOWpHzk)r%4qt5Y(Y)uHr7;ZMHUueWHfN7VMtjD;;Pr@fD7&#@2;$l?+>+IBUHp4n1~-Nmnl3`Ns~FsWsx1 zzg{Do*5Z+mj{STc+;cp;!tsW$Z!x|8`=GPJJ08xLg9wxtJpo(I;tYP$=U}9bPOU5U zW9ikVmO2Y_g^~S;taUrFxu(J@^AzUkYfGRQy?Ii7@&rzU6r)iaGX#-?DiABxKh4u8 z_M!;{2^mIfjJ;xyd*O!QR3^ZWdsITYB%~T61>F-mMw+#A)ooreIMB~-5N(Y0l&^}J z>Y3z?+ZBe&NPMb=g65I=3F=hz+6&?%Nw-n{&lRWq2QX6`_n}eyrEu?Y;p(}5S0L5k zeQhCw^W<1-ZB9HGW5kgQ_o!XBWjyt81-mpfRGhAtIypr^@*FE#Hkw=gz`j-HT$Xg{ z!Y(V|k;t?&(7f2Zf)uN~s@#o0NvbWGf~n1l)yl1?bLe6k26NXlL)X}|+QQYd91dIO zentd4E#AsHQ^C;}lb6nZP+M!@{cu+x?2Phxu<5J@vt4)SzZ7RGH~Q-p=FgqgA1w`H zHWTu`RGew8_&iydHz=Qr}72`|z#(|SWQh26b5 zzf%$?CJ)9HE==^sxOCmlwdFEx`~f5*vrsD7c$uyzFb}$va=IB66-$#dh3AHr#P@U- z-+(|}!~HecnUjsw)%(V)SJm5b8ERCS_^EVr0Vq$6`m!HndopCbOu8+Z{&m{1vbs;; zv@N4A#C8<$#wLWte8oZNW`k>aD6-TPu$dRrO3I15I|{ zrtG3UdGst>wSilSK3-G?>0m^J$9jan7{UKg*7x%Ex+&b!{#G;Jg427Q;vsxSdZTH+ zN_>v;=HM^>a?qXa_Zj^Taz$XIdPgnCo3i7s_9_;n5-<0CR!Cg}#lJXyXg?oa=PEGj zCcK4zU}!$|dHvTcNy|3^uzCc)6-dMmygiG&Y?EH0Nm!8UztOM7*P$}85H-8xvJt?> zUdfbgnKJh-gHPxd%~#>lDVK!JaY-9IF-9exze1Epwyym}$BhJ!k*<|? ztX^>c)y@PX{6MHf$TYyHHNw`z!n4|`HS|sx$Cb!(u$dj1kgK8pOQnw)D@e14QL_mA z`>p-0-qifUat$`kZ!mg`BNy)Jj5sPI9eJKr9dg+&PdMVpn%^(r@?HVCWuUhQBVmWo znm$Z75g;@l4jW_{>28RFM^KSmf4xDR{*osDdyQbjtA$;%V9x9IZ*9H!A>#1(k5pQa z%8g6ZtgA>x3eUK`+8t^XzRli`dls7;7u}ll2V#=r#F525Eyvf>@3_~s3?6X6`IPG% zgc0|${l)_=xn3#vPgU?fn6E9S*ag+X2ap-%qrhB5A=H?VkVlUFahfi8<$!kV=(cn- z8NBAisyQ+{B;$s*$cB|3JWk9EjR4NC&lIv~_PKHrv%6^!gU}y!XuUD973vFQ$knDl?j!c_x>=6`GE` zip4LnD}Bxytroo47i&A+7KgR@{^lc|JcBW*kF?DpG_#^duWw`o8pr6{e^W!zxKjLv z$@wF)DQV;h?Nup%NkSOcJ5t>d4Tr20P^c_-OC9sQ_2=NeB4VolLx_f|n&AioJI&2V z@=t3`HGBzE9!QgT9+?2PTZYWI00fzuWZhpC6dHn`i8Au2AQ^Uz|H^W>AAvia?p9$G z?Us!8@7eHx{v}F|rY3&ikni-1_e6^0lfoIuWjU776~_NkInML#gHxFLn|(zqmYYcN z`u=wyHLLDw9V8=?tROaLpe_4EW?ROy?+qYx-v`-unqa8=h5QqeiGfY3&wnIJJR zBLPzfw!)B-e$=Xss1%xLTg17<1t#2=gLoYLlb${kp#^v)-Og7qp_4&Crwwzd^B#3R z^<7u8(VA%0Wba-qKaiWmiYztsV;`%;B4Uc{Vm~iI*-{vDlV^?&va5DyjLTrOsOYUs zCwUc&s963N_5sh&xbGYMv1?UA^vM36)ijBXi3X}$7SB3T<# zR!vx99&LI2?X7chpZp~<@(&1=gOeX1M|&ou1{%fA8#Ie{UPOV~z`<3+K=tj^OpMHC zMYVxI*O&e@c1kCgpP%5vK79hmM~}gzDR&&0(@ecDBr!=H9rlmiASDO3NApJ(hl{O!wJrl2FlkJ+mP^)d(_`YA9vq>>F4a$bD-c|gtw^^TSdAme z4X4nYJWI_;{4zk6-L60o$0dO}X428C9yZj*Q z>D0auRYCtJi5K+cVW5!HQ?>!edvu$@(#@j>?P!g<7lxSJ_Mab}=k|}#^M#Thk{FAe z)((Di3ZHpWD8FZ2MIL#+_(*7NVt;qhX+jv>+>)MK&qn&qvCYpstUJ7som$;q-_~AV za2$L5!l1@2jm8S6DM~XonQ&Qg_9J1trgr}fw#k(6O$W2vyC8~a>Ijb2>7I~y5|;Io z7=yu9f>ZFee7U)Ua?A29T)z)T_fR*|M_%_IfVpC~2bI+oBvTSDciW-_jTpP`IQhV6 zs7yFaNuAsJys;TFCRmQ#4SCb)23k z6V>%)8)78Pc>FU9Rg5|J)eDKgeT#pp*JoCX-6$;DIoFH)H_K`pFph%rUM}x7k26}S zp5J0@Q3cz?SL%A;>&VX(q#bn}V)Y)q9G78hTxIg#J(hSc5KE!^^o#2ABUpUc=xV$>J+GY? zx_%p@&-MLUJC%=-V=~euc|o}w7W0l<^-7_3#L53|7+x<=1VoLqk{dGi&Na}l`+vN> zWpv!!wk=q;4( z{%AJUD5zZ)TmL$LvDK2)yd>>5UrL5+;$4q@$8%vURAg= z3?-A_;dj}CS4(Q6#kt5qH%@UohIX&o=4fw-3z;Naow!_aIAC8A#J<>N&P({r7cMh= zcAn8M7gPSJR}(QNE!M2!t9dpoF+K#NxyY9w%`+s3+S?_5j)wO%f{Q5kOOs-s8(*hR z^&)b)+*z5LqUc#$UEZ#vOn|L>q6oo0@o%!`skJAr6tzUn#^ZaQNr7#1;B$IQ<2dQ#>gS!nFGRZb_=D;fI!2xXNI|1f=U_Vs^3cnRj8*bm{_6zx z?wT|yl%5E;AwzIWVZ^o(5loU!vs(2_CAH2Fj2J0XY}pg~sA62!Tn=SLc-IBeU?T_s zD&BsKC052@8(P%|=E%x6153-m3|{Y!no0205>6HSE@A-yXgb!KB! zCp7E+aK<-sh9R=v_kLZJr=Qj=wxf<2xK&&(E-hvH)^D~Ef8Es`a|CZ>_3AdyUSD`w z3%dej+7xUvAh~xf5(X)u;J^p}P&0xD;VaLqP#X8We$PgAr;8B8Nvotm;>*8~mJrvb zf%DPUl>rgBS{uzepCuq4ug&=MxiCWP`*D(;8+`HS;Lv5ovky~}oEIdm!UR+vB^0cJWz$K_gH-H*J9IuVj&ktaYT`RX}NNEy3V~(X~X9< zVJL>q?fBgV);Tb{&JZMWB2Fl!qSw&Hn-s?-qx|+ITt=I5SCly$V$K$OxjR{MtWjJy z={sJ3u;R7gaYJp6I`-CgFizq8ySS2uHmanNd?u@cI#WI?GAD#ZRwO}4WaH*uJ>e!k z`xiZL)g!chQRL3vjk)K1TV3AoXoio1lHNzxo9G+?2{r%iaxa?j5A9!g*Yw@xQwn83 ztXtW4#}}#2&V(cvYtHeSrIz$|o$uwdxZ$W3U6fZzQR>3&8ecxt&Bl8h;l0FXh`(0$ zI;xDz3f?SvF30=M%6;)u#u>a94ga|OspJwqc3KC*xKTlQYx&8sYCA)&O&HV3u!`-S zI6Q1QqE!?w!9N0m&H5zxOI6?m-x;-#jI{m|0%)g_{?&qTy?Lj_Y)t_P8kr)z3+t)~ zo6rUm5i`>XnQel{{9r1}3CN*my}?7{v-{h@dFzos(s?bNA~S=+nIY0;J$*<=%8PA1 z9X7SfYNaG`KP8gP(xq5AQf`I4dSkX94WiZ*tvL|TfY!{d>Db2A-JuRay7)EMC+GAOWbx@F>Wl&9 zjCFTFyc(K2d-YV#&gVoL*RNXc*Mb-_fTEd#F$R=KSEqt!0=HB{N9=CC4IF1Q1%d)do zd02TKEbdHY!zxs*RePyVbP(&F@~JxbE}}{aGAdk^XG*V??2?$nBhq29B0b<%pYe@I z2|La}dt-4%d@N&<)l^Q@fJIC5-1Tajt&3cM9^d+PC&Uboixe9> zHYY_=2syuywkT;AdV~_wR7cLDMq{AedAcjweD3MzR*d5z&o<7~K7RfyT7Km@5k?RV zy&^^mfJg;-u$3d)LN_%~%{@*q*6$f z%YQ+^A=;q7mWjW)eiz+Rtn0?aHi_4=tCxK(cW-eRQ&c_`8j83?u_+VZ)-dEFLy-)7 z66WFw=6bn>{l`vV)23y}?!u;z9?&iSK=$=Fwrr{j4+043heNvI#F;PU~T` zJZI3J_`+f3o~yoCvec7oMQdqOer`jOg?hH`IokMeWGAG*j18o#W1SawS_(rpODu7X z^*H2XWtD85&uO8Gs%~a%oBKlF1iQw_BvE_*T9X5TN*{gG#9L~K;2ITnba3C3>P{NI z;~GE2A{{~F_!PQDKgUX)!3e!Y9$IbL4tYtU`(r9poZ7rRK}3F3imja^zkRe1K>i}E zs^l4c?aC98$w6E(SY9xeWtEJ-77n&#G$gYs{l5EyWkK-}G9@395^aU|48wfh-HdL? z>Cm?01g;(my@32@{-;N(F3jhCmU>3ZDtf`8$w#^oXXFNsE5cj``jXTpaq}Mw?q6Gv z?0k54dun9-7su40s}k1P+#H9#+DU89GOROquHfBqKZM`i=_ric3`MeXCHXB-)Vzx|dugZO188i=km-fZy+i|rbBs|67lMBL9sn=VJ z$$xCr^Of+jMh#>{zB`Euagx=_XwP=ytt~BNBbePycd}V(IxBJ^%BHqmQtCyX+qgli zTi45`D(5!sW7#)aqec}rijz*L07B6edhK}7iAfn~?4%`zMH{?mXvj_uda^a2Rvu3I z{GaD?pNPaS@Cx0K`CxxY^8w-&6J3xP=#xpNW1XFLHV1zP%L5Em zgW!NSBIPL!p7}=*2A8I2Z zu_qXr8^~-nrex?WHR01!l-u3i-Je)ZhVJ)}C&1WVFCyD(G&G`k^0L|^5Vl@cNVm5b z^3q^Ftm=f(iQeb9A^pmBi|9NsgT#`ARM5tk%E(2y{S(9Wd`Cl%C9A@xe5 z1k4%6UN!*BrH50Wn&Y27Wkkut7Ml3`$tX6(PA)CnPJ4a$5GTlb2QKobHh%%GB_CHG zW;RuEk1Rh>kCPOTaKa_J<3&+pdyPpAj?-I%!}ugz}6 z8)n8QRAeAsI!5ztpeQ9I{IKkR-mB1O;K)#ffYf^4j>E|kLuSA~UUE&+hRlF)!=)$9 zjuJbAGY45-_>ly!V0B!sxiUiC^eJ=B(6%mwF^ymD`c0_V9AIp6Gsn(apDp&a5P2ra zphL}CJmk_}gjNkhGCc8ym8IgaUo{Gs(mi8%!{*Mf#h!Sa{Eya4Q$XfAIN2N6QL?V+ z&7}AWzt>Fr4g<#BRVflj6olH@h@=icPF|-dB*vcVH*uw`eu?=PK6;)v6xBG~xIk8q zYUIqkbzA(wU^Soe({@swJByP~T}92imSb)0L{R6n_9dCMa~Gr=V$;2~6<0S>-?03v zw+`JG1GX89FUt9`%l$%C{_~Wz7<+_+8j8T!G9%+|Wu3-!u{-+YW-Z+%arKevGQIIs z(#RMyzGQkn0f2cahGUlOO75&apJM@<*w;$q1eM7z%8?oAPPEy;~wb;8LMJkNq*M?j+38;X!L#u=mBm_)hLRgmgx#(>@ei^TUAr;e*|^k}_2Y#_8%r|Kf71XY zCK13C6;X{_X%i`9KNgw#=V|4>AzdqKrljG?l-`YQK3`rER6w9Uvk=>=8`&{G{_?9s zF4Vc5+PRdBq&{w4dYirQXor!{`}#yB*b`nrQZ_mwy#S1A~ejLg4ui$ zNaWyZtA1=zA6wig>t8+bu*2!9eOx_!q_sY@enFri-etW?<4)*wbbJ@;4n|a2WPBbH z99dKnS_i72(@Q%Mb~&9;^=-hcF_dj&9KoZjYc|J_qyb{hkWc$y&kIWe3SUDe7B! zpb|in>@J&ex_kQt;payCh2|^Sj{T`HUnZ>i0nof8v$80CY~w*CE>54;^$cP?ccW)} z<_k}R+FDAW5$uXbirac&+Oh~&a1Z$Ktsz#WC8 zF8woIs;2Nr$y_g=ne2+>e#C9+_l(a!wv``ui>CK-1+CABOd`2PJiLu5T}(W65?PXN zTJLjxGcz?}LjCI#m^oEdwa3}*ZKb?mLgh6a_=^a zt&ymbsl@mi4wf$9{nyU_7uqrW839LIpH*4Z!DMo`{DXi?6F;d*jRPV-FGJPmjjQz1 z#7hO3H~c@ul>7SUmx3~78><_7qqBGAu6|6cxrA^zNY#ayi}qFOcsF4#(7fv%xNR%@ zJfC0>ijn|#Ot>`-q1e>7$b;LnJYWOu%uwfzF-0`pKVb=g?H+lM3nw$8#-+F+ zA5Ei!QlwQXDFC#V#h+27$X*uuB$`K9Vwtg20Fb2&J~mKzmQ(<_(@|#OEiOvlVOB>0 zwC{VCV{p-nSK%6;1UMtWE~v9ETEFG_e!5>G-Q=P=9gHD+3$wIk4ogjoHRoDkvnScl*9_U6=fBf;UwxUqhs%uYfdJ-}?WoJkg8>Sdo}~2#ca^{4>*FTEEE|KFVxeO|q~LmmdMBKRfUylFll1)ng)n*vBRN@a!yt*|7uFMZ21jF=($&$?Qm;uUgcYl0+f^a$JL{Y zoxVf2U_t=P9&xvd-$Pfgcdtc2Mnm1ERnMDJkHck*pa_G!e^GOpmJ!|#uvirP|qO!%qgR#%U3ignH0a@|NH85uKzpN=x8{=`2xsEV7+7Lc$_@#T; zRfbe#cpqYORA4|Va*UID9S)baR{mmKK!;<^642vUucFb$6h8aKtp|KF31Np^Qx})Qt zjyyzbZJ}F;HHfJ-l>JM{F1qV~I*GR7AeP9X^m8Y2%_qMpcBY~fKOIK_fU+2n7Ylrz z!K0!oWUHhrpZJ8n`RTudGb-)8@`}g>uK|Q;5|^ssc6|~K4!>F>y110Ig9f!VN7#6R zxi@9$v+;1%&!?Uzhg`zRq9;Y6AMoftNSuEwWSTb0AwmcuVaN3e)QN-Bn%_kkfQuW-Xn=&p9) zTL8Pk?ud3a%3JI(xayYv-r`DOpLoi1^h$NhuS)QLyOqGiHm)P_ZAa9Rj*Nq?dRvfA z?`qnAcSA+k3wpDoK`^o}{6>lQ;llFAt@z*iE$cRD>YdVDzGC03e z73BWdh6$4$8TBNj$l*hJ3Yf5I7z-F(qFGoJ6Iw!^Y zq%$F!B%80C0)STz1b`QfGPl#3o*bURJD*<$b>_;i=Oq)2RnDOF&~tZM1MKNrzY46Z z6EPY;eGiV~VrBW5%#9L^l3#SRoNqWw!7Rkv(1rWp{q@%^I#xwq<0EK0n^zRRH8&frwy zn-zJeUv2kX} z@kEJ+D?Ca!kK-s0hE&lom6T5#xU!C0hG=UMbywy3^lc{08)>oqP=<%)BdwRT4b@bV zQ$OeA+zuF=rBZK~hRvM1Wi@&EwlStmFhw#DO;9@nHD+oj9a$jwz6yR2Q3>jmkOjhs(=CWKlCt4TKpURZ0xLsUus0O4cWvED$Q?!B3 zE&!ZD<-owDfR*r-(d<`3v(f!&jukl*u;3N!tK=^bo{G9bH@XP+&x^3*`KshAd+Zzc z;9SSI?KNQ$Oi}YZpDLfSxbBVS6Q{e+kHGKOc2H;GL{?PDHca@Nt*t_BX7^MGF(wRD z4~oJbt#CF3%Yox`E{CDbrMPJ%`14&Xw+!>y86EU&bArzOq*}ji81{~rftbW zFP@v&C>^VlmNre0?jP3u&;*O8EjPB^@U1Rd_=m||TZ@SPF-fu#VrwCL;=n$_^$Dpr zy9b)B;eE6MvsT!HhdN=7@e4_QWGDX)Ib_uT~EVdKi5EUfEdvdV@TEr?TnZZ&GF{x z1@28X8|ykTlG}&qx)Q!}kwlII#HB=@q9~ad_lYbFf-q3R@bs*ZzQ=ZkcMUDDu{zq> zL|!}Ai^f(UrIeB2nb*^ac44 zGQ&$KDmvOsrvw!>GXC`ZeOScdT@TG2%Ql-uG=f8n9Zi-;MT!iQeV#fZA|-?bqXcQl z2QnglL5Y${P0SUqGFt+k{9yUA$qhDgN(}Vywu279`3vX^oW;Dj37%r}Ke15aR$u9J zXbAC7V%I2%IfCsG8%*02m`X#=XVguGa8MY_rV*Q#0cA#wE_OG0b|uK(jMyg%M+uGB z_cM)+a0>7V zv}neCSoXU>KeRciWUtpId7aBxqjDy2Mz9mxEdG5NDO+;?^j2$d*kW^gr#@=XFbd_j zt1<>+yJcXyVtJo%Fu!wnpM6jl`3CFeQ?93qu4;9p)3ebb6(0;6TBs9%zk+l3HRzPn z@Y|!CClUnARxlq&&wPU3U11<4Ngg%9+oDlPNolW*7>0L^AEFJDy~Z5$#q6TXl4`Bb zmYuy5P>X6=3$xx69|D=*KL80Ft?T$g)uaD=IE{HSi;kv~Uiy_k;52iE0xpDA<0FR}Y7YL!jYyz>!9IS9OXE%A*nD@S7F z?YfL8=wP7Fi#ewg&h4An@Xuam3RCln4{sjG0bDCxvKf6PnUr`>zn*<|eJU*x`^g#xY4m0su#`naCf=9nP|D}vZLFsx4y9oeK zCD!2ivJ@tJS7=Ue_T*lK!Gl!!uHZ3G4(zuACbT!ByGT8Iyh8Kq>ss|n3jPI1>!%3Z zo^<8i^gaaHTM06P9l^`0CS$oyVEzJ5Wah#*{kW1pG(LXIO;a6gonzd4IhDSX`~|$z zcq_jCD*g8v;o6JeI^Tmj#N~FWM&xHlojP=MqTeLEN_%A#WhHR-;4sT(C+Ix8L9ELT0G+JwjB9g#_nZz>`J~li7+P>kU4bQ*y)VRs6AV;RIqKoW;2UM0HL^r>ov#bHk3w|(wdzpmk)gEw5h@^ zv#f}S9vvZHyjGCaufa+^Z9hxzAd01|zG zvqRfh7s!4W-P0)?HBUN3ps59p`H**lfyiM@C z^(M{1rHL2+LSV4JiCV-T$Nh?lktX)NBscUyiLmaiq8h4-Xb!J|L3!+r^-Q}dI`fr| zol^Y5w}7m*BRZ`Vxn<_(+;Owg7qPC!c*oHXb%m~ z=MwMXb+(-G#B~cK*#f|)eYy};QF*zS_9&RsEwD^dGh=BzrB?HWg+k3_TS9e_umur% ziG9+3D~O#&RyelTZV+RJZ>ErhY)5p$8H0IhszC-_{3Gcrv{I)G4XWThYT+ z2MG#Hw4|u)rIFhS&DpLhGDoMQddB!p1|JGmk!CU1JE(fK8vWx zgd#P^OM7h|L-ah|;=bLZJp&CDLGIcvYzVn-`H!JbH?1!vus~~SfpOD_jpao7e0bXE ze5Tm_C z>p`X4GJyor$Mwsl99DTXh=O>QIz@sqPv1YZd;`eT!47Lxmek2wtMo}p4yv{htze zBz7=@2^1UnhNxmg#SMgkt)FX*=cyYbEcYjW$SNnOI-2lnyU#X zq9fwBI!#v1iuC;nH++q(&M*kOJJZwqsHbDlf z+(og-9Ydh`kk^7jWeZJQ;xz%E?}ag!2b(s|zX0dfyLJrYUG-J{1zy+2rN~UKZp>HBrUa@E{cmEG)mjX>h6-*0QD`YI(22Eu6 zb$8eKtQAsY{HvMqv2yCyXA;e-KQ4PXw;{>X!aXKsLoSWas|4!d zzi#sPzH1kc1Sbw{HnWTfUG0>86GXumIJgwN(oa8fCD@QQ^A#M=(CsaGBz&d*^=|LR zc-0g6%!ZJD*R$7ahWi&#Gn3u(LbX4|XfXF0_nu<$0pzuRJy-AY4w2EV#}waNPG{%15a2*BU0Bp19> zNP&U%V}bAKy$(Ab2*UfZUkHalMJ$s2K5G5M`v3SMP?A=#_7Z$At+35YaIe+R5aG_!4 zRil~e6#^Tbz3dQ(*&#=4x^KKbGd$VSKX$>jTBkTqqQ|y$aBQcj8MXk%z6gU3tEA#* zR4MO-29}!WLw6j(+F`5NAi|Xm6hY%@o>35oMW&D_LC>((o^8k z`P41cNtv8h5edi(f$}FyZOJWuXMyWdVk;wJBx0wnLR@I0xtOHKQXFdn-_gZ_P$^sF zP24sGi;d@n2HW1RNlgL8DNI(?J#A<|ou2?#hs;`xKU%GG$N4U~UuDFmVo7ch{Onvf z%&`w_u_+FDE3B`lSB7i|DOx1RFC0tD>RZFbGEe?>>dO zrjt%Y0x~nF7h5+g?F~8=UVYzT-klUaz|nJn?t;ThW8S_gSg?ox|K6iI(%!0r6O3Op zGvRb4=Zm`rUZ4J>s||0DXVGjJlRo9sBaE$toy-{x0r-WF;wZp zs6zATPKq1PZzC#X(_e@e$gA~<(^y;XqjFiIV%^R#F4l8=_GN2De=2EnZkS!dM)?N6 z#b4BrNi^#OtP}ET|GSah_1RFsyJEn7*NYLu zO*-gvR#&yr70%~Gw%fJ0-SblYng6Y@J|QyEs4CQ#-S+&sqB^scFir^X*0PGW{&cJX zo+{(aFtt(qdb-XeIAdqaCh%)tR|no&HD@bD^?6iZs`Zl~RJ4z*+A7NNGEo2wYk%6f+UuPXhoaZkm+f$~ ziQS1qOl|#ZrMt}Ia#WXjUhHWr#Y;u{G~Jt#ZG5s}a0w*4YpgnE!R6$GU>YzHWVNi) z`D|;3S1@>1?S$jo<8M%rE%+v681S9CXEf5!ezkY#4Df;=^1v?hIcrMYx*H#Tmp(a{ zDWl6F@`49{;!hf{VT!94Ora_06w-v0_FPEWu%CsfDGzA00%L@F>l9-GKlxT}oL&{FGrLr8BTUe>)KM|f$P%~2E`fk6Jw;fOqX zT~k!j!s9c!PZz6P*zth%O>cp}abc7MSMw+-Fk?arp3IOYCar%)>41wm)Tzhfyn2Mi zdOqm93NFbCB%{SX+o45l(m$&_>S8hl2e&P@20vZy%wU@sRqb4mlG54}hIL9HAYh@Z zOJo!aRdJNnt}6)Rhdwey#DT;(&?zOFtk7vzybqEthCBZ@4PqcmiX_;@&kzkm1NnCA z3nq7G;QYXx?N`C@y@RD8gXuC!2!GLq@5CVzj=(vn^i4uP0?sGz*)+eGNM|nppiE`V z*wl5NyY1Hyl$ps%w!(fyM6YM|ee5VSl^b&tNq2S?hXh1i>b0)ImXinSvs?W%+*)7A&z;ajV@>K3F(S;yT`;ZHj$p+NW z_YIkoY-l#u7W3bR-~SoP{6lv6?>EZ31WV4Na~uyV+0^pY!}g{+n~{m-PPnSCY{uA?ZH0LLNnc3BOXZ)x*T}pX5+04Xtnq=NdxM8wV$LBibfb; zb~CDHRgCJHJETkgLq$;RY!$)R>3_lp`ll}-; zYv{!uZ!cxL3MO*N1E07o8;RJ@*R8x+UaU#rpdweTBot<;UF-|tc@o4_mj#(!aE6&9 z0%2|WuHv5!&wGcPmj)G75Pk39y)_*+Stdl@=^*RGp%d~K#w+va!}nt5vpo?A@V8Xg zvpq3S@J8`z!~Vtm0)1s<}df>)>C>X6e2=9pwfQB z&{8<^`B`E6moYs{3SZ;pNl3+K@pbD4n^4iSUY|&|uvpu%0wg%t2>1}^tRpTXkLF`7AX0zwu4oGHHVTAHv zl+nwjcIf%&zhPQZ`SDGzK!DXS+T7?k{6$g1>W;T+6_)8B19bRx9#Zt|@A*SL_H!jv zzDcaA(OGyC5-`P`lMZWwU+9n6+1S{bRbiAP5AJmrGR6Z~@>2!5Z1@7`uq?pPs$^Ot zC4r-T?hFqIkVlRRfS%~pGoV6+qt5_4FlI!g@%2irf3FQ_{< zPJQ6ZlH3SouZhjnHj(bQb@`cd7tM9!Hjiv4iA^a8&>jR#x~jEwh_pOi6Ua@Xvna<$ zu+Ufcbt+e)sK-4-aBhvH=FQe~jfhYji6-x9Tmv8jG4cV5;3OAV z?2R`N096hqL?|;@{)bm`$xk*bvgrliVD(=a0=Au8Q$Il259W(*zOl)i$^AJMQQ-juW^);5pv|@7JL%bzSH$KK-@~$;s`xKMoc} zZdl^=9h7jsfu#VFEzgf^ayZkPAb;ZMFIWp)9QZ(@t19WIQoFc8Zmc`Z5xEv&wJDQP z%#xdakj5kE?1Dp}T^V5JhF|Wsqm;4vp*7Z(X}^kkR=&8`4s)IVqIMG3cTAn^YSiWj zazj4W{BxyKBe$+(W#US-vrM?`{}G;a{;Q4Enw!Nf(`3!NcdnIhY>6?Q{(?~WG;Vfh z%blSjgjp@ylxwtneX1_IR}ZMyVmCgc16Lh=0;|bA`t5Rw&xH#eJBcqn5a1#V`Ooz; z*^cPyYVXcnsQ+{Q^PbFqjGhyTDu^$}UJCdXe-WU#rxHIpFR-iyDv0jHs{uI-b{>oD){euZ4(o7JXn^)F}2FA)XwQ8uNnX{2gW z-w8RsD3MOAZC@4$Y=e*#Dy$Tr7v{5M4NsE7$>4@$m4 zs&RhbYbGeQ46mRy0dsRm6($d^6Sd}PE%&GlsgmO8#n9_bOhfH|($CJ+<#OvwW%N~E z95Iy4d3`m7JS6_Z7?}Ms2PfnXXHdEC*ilhVWF3>D&_{!5C>_bZ$mCjHS+&NcBC>yh zcR)cz`$>&5^8Beaxokkck&6X65a*L3a%Hs{Bc1{UX>3u%Hx26!4hrJ@ZdOzJwp-Yd zAoY!5z|hm$XgBi5vQqajxvH*=&hpo!F~Vk>l&Hd*Y=V5%IC9xO02!%9D_`udkyLx_ zi^F_w#=4RXeM>&Qbe>Yzru2=I02O=VF{w8b5>Fd#?E|ti*TT&J0zr+rEqV^EIs9CZ zCt^5tVB{Ddw3MS4ZJ?Ig)b68RHUlnhZUdfiQ)XEG_+bw3z6ky}74-?_tclB7U8?kL z!=(x@w`-XYVUuj%XW9d#fkKFHDHG-EeIQA+{)DdnYYin-(~@7G=G^AdlkGF1q*#5v z97;hWoXc*@7D$Zn>&TS5l@>1UttEzxmk#0@^quepsh{|n^o9oqkN!rJEzXmXOXV)? zwOkX|gX-bqAjCD48VZt|rx87bIDo%#T4{h|&O8{@^)aiy#N$c#NIk@-!_}ntxt`Cj z=5UGc%U!~rNG)5HR2u@?j9O*IN(Gt~9-9yRj&Ca-*lRyvLa5#?sKvkB&5*6+y%hQ^ z8MiMhOK7rxpo?6DQiiE^+3i}>c{OvC|2WV-)S#iJ%I6Fl)rTUbJRKVELRrbA)A%aZ zbr5gblbZ0q-|04jB*eJg{Y=ShQIqLdOA!D;krU+aNUj!HdY5W)0kFg(%2>5FVe-@kV z-(wlPkK#Yd*)f`$oQnmvXR(#IFHKNd*~MDH`8DoEpgbS!g{Wrh3zNFgdRQwOvwK`y zLxso9Uw|cL$>?7|%fAewo+s2OF#fZr8I9kD{%^_8D1xPFl@fEI7IbPDUm{9!KJTn9 z1M|RHdQ$MYSHR#5Co@cos4}FOPTW4>mrn{TkF3QaprE0p)_>A#dUL5M`8@MIyT z()_t17fKicAv-G$K8+D&I0*-;pp9Idr^mBHs$Nk|TqoHV(wE8)2Cz!}MS*@XIL{M& zQ6<&&7f@V|S4k`NukVT##{79B*MF;j1xgHa#qR9;O_y%%$Yc`}{_5FxOby%fb$#~} z*I5q!9~-2f`d@0soX*h$0SmQ0+KhXKfjpb8x{OOla2Ax3^cN2Z(=l0`vZrnCSLmjn zr*#T5;8L{QmVjemok>MBmKYKML|d#(cYKY6$i-M48%f}$A+gSs@dGR@LH3Uc<9i%L zmCpl^_<;+DL)4n9rd!7@AwJof&|6C(Jp@Ds+p#DKw%Q+q5m*WRF^uq-ze& zHK`M$bsTSfz4E%ilhOC}o=o6XY1!egkMjWd5?}83gWkr`D}@aMkjEv=`>)$t>4TWT zE7oU0z5T~W4MW|^Bib-Mh+;NUrVkeYQ3)-hlU;_a#nz3FC z4#v?rc)w*L>!HS@le)}-_3uL*`RV9}Fv-3ejpor3K^T}*GVw}SBSv9eb*_*`Jm<3r zLtz4ko$D=PRm>^mC4W|NweIkNpOjDf&M-nCu`{4j=r*U=3F9#qjhi?IBP0wIIbar> zh-{O>0+}ie3Esa-c29?fE04KQ60a=EXw$j);>38yN-mIBn;U@}g#pzo0$m2h6MeFg zzE*fb_dnw!-+#M$d_;MT-!RBt{x}uMf1iJ!cwgCn5cmsFzu%kpnOJ{#=SI~uT z@g)4@$9tvk2C=J0XRki6@PsdW$wmETj7ZTpCLo1z`GQ}>t4ROm&GpKo=i_X)>$vA9 zwjN4T9a|k)-l50ZMoGB?yUpfST<*i`*1I=XF82Ju=`L~ZW6z>Rl~Fmn7^B1FcK46L z*SzeK{Y!&f=La|EWj2l1$&PUQwMR~1($aBvvm=o4QTf1DWK(v5&wIJOr7Hs{c2N}C z?$MF%Y<~OuNTSpFJ-7_ffWrj&f$T)3!q0_M|FBRxG>Cz5(8uAPfq%4{XB; zq3$HJQh^woh0T-9(m(AY&x#<)^$BeV)ia1YsJbw{0Ui#YozaETBsl9Z#}+HW9`1ufFf{lt~|&Ap`~?sV?QaSHXCnse!)$~?V@Y5M!dP8IOc zz0KRDqqcvJItD)z@OOkeIK29G8(7!$J}EqUF@skEk6xTrMG;w=7Xm2l%qxx_gNJ>d zo=y&r{O`+9Tyf%~#OJf`nZd6N9!!s4U-Q64M!t_fJJJC+R1@zg34$QTh2R$O)2)xo z7W9U`l?OHdNB(NoLqpFl?JfMKUHHJ`T5wI#9hmoI;6DAU-|zVkzu>3KcVaiUAGWTx zDGMpKc zJL)!hO18339b_3Lygz^q)Udvn)0!iO=c#M1UOEsi+vCklZjmrDCMLmV)v5WbS6)pt zD+*Lx(Qf>MriPxrJSuSRg3%ncBNl+qFA$@$^lfbb4`sf+p9GgA;?Ucqg++$zshyO= zlJ3u^y9AT9_BF$563ZE%L>!R|(}y7RfQhYMsqS8(K*UMc>6rDcWNsJ*mJ`=TP4v+S z%VxX%5q3vSdx~fc<9UZFA_WzR&%iDiCWXus3KyXYm{DM-R>!R>$8XyU^!x*IU6KMX z`J^G*$Q+mdQLD5xHOJpmq{QZ z3?VOi2JAnt%}ia(MVRyIm7E{kNCda$>lL?e)IQ>0ntt1oV($FhD5KzfgpD)V%89EZ zm3>ScWFmyu&1DnrEZ5Fo>}Z?#^O&fI^Q)qP;Ix^Q_wL;1fKJDS*##fe5!X(hS|8KaG#f* zU`k5LN^BxeDlM%`2G8u)9eHQI20D^mcoNuEboEim3}#esPjSxPYt6OhoPllu zHgxce#cN8|y|jx3^tT&HYG1-5#<`F}@(T!d=`q3UVdr-WD7US_&{rRKk4F zQ7Q^oJ!y5`R@P!Q^%Xg7b>0`sSq2jV(6O``awT-Drc3J0*%h15B8w!E^G(5ISm@z9 zzX`-Ze$*0E8y)8u-m#60xs_vr#PF4>^Q)hqFv`e93yD`P?FG zEj!Sd*FY!sv`3r$b`S0tvMEO5e2!UgQBL4~#3#oVz(RYzf^XHWWwK0YJ$$Xso?Z82 z7zQ6&So;A|-dsW(%F?YRNzugyI6QR-vp()2%+7}%I%|@~#f0R@cGDg#-Hf9ZjfjG3 zlZ8TH&4$R;#QDMERw7Q5We#(KOXjrWSMh4(Y{Y>wSvpr^7M<;-;z$OU=o!lm zWN=JtwC-7_DW;ax@Z3{UY94p3j1#)VFp+%dv{-h)z zoNr-6?DQyZ-4jvI8d9uf4Nh(N?(62}!n-)?lUrp#Nk#Edc)@0~IKH8JP!pBHkTV}^ z(}rX&!i4i5K&!sxl8XZaUc2W8Wqo1aJ6GI|MQxOA4H{{`5`|wdWT=DzDhK9(Z3Ie& z%C3s?oMV-%zUNIX6;6zVsbiEW18Eg$&c-;^0?dXkedHDh`Ktx<%7`Yd_%|j#H(+4k z9#^;T3|A!sy+w#A2Wb`iFZLt4`|f-oCPGyu>zLqb{qin0&VEZz8!;=L|BVCevwiw1 zHvd6z2@^+y9!3TZlb~=w#ob+Z%G)jF^${+nn^1>LIHLZDB5c6 zYHhXu%1-{7aQ!bZw^Y?MtR(IFj3k$3i@2!sX_07pRctS?s1^YtUgc|o$OrHbby(QV zK`8V2B{78-7w)L68x(E%s4aNJT_fg1kMNJ?sEges-wSK<@4eV8wXjdtmyNMIYDzF&!|c>+K{iUc4U zX;J_Z-f68mgjEli<+dFiYG%!Bji{AL1p+r@Fa<^SuKA2YbP%ogP*McWr>$FE0yqJw z%xDOuXq0PQ%UD)dOJm%d^_qv^wH5yU55Vg;gr!Du6ideqlnZ0kkyv0GZeM5pA%hEz zUlW~H;|aR@e$sa}83}s_+#D!18H>ORjIg1b4X96HkU%&Gc$X#j_E7hShqCcA2ic4Q zSE>cYMa*t|hEfEp5CN3ln+Kc(XTT{!`KQNeLJl!MSggJ1i_eOvN|E6-nLOwaFr_Ga zG$N}G^rJN&B|fzYfGl8n=B*VXWx8+<=VKU|uKz=@Uk;w@n#${Bo! zW+qV%;svpjg!n;2(K_IOO&?E-E+|UMa|~puS3&nPIDyZvsl=2i+;VS2>;RvpD8BxN zLYQBKR1_i|^#mo5TQ4@JE-N`PG^6_89T3XVg$NU> zWz>}DLdqPB*)7DB=ypB$aDjg}j(h-k2*9rA(Wv0XycypYJ%DW@T16Ds%JX=&QlK9E zLh{jjIO=x(m$(JYw9oTMP|M2nGMI^bMPW5WAalrzYuj#Sd3i4ArhSf&Sr!U{u9m_(oVpLY!BOG^@ zLCo={OMdVau>d!>fB|B5Nu;2|xONL+QNN19I9bO;LB|;l=y+~vvKoXuX^PwrVN_*5 zsAG;xl;Ci|&n$OYTB;%cfLgG!E@rwz86CL|i%&mBpg=RK`NkFaX3Mqd6#frpo>3sN9j!^*0ooi;iDEuRHMn075U_1Ldin z&0z5pq-y_w$ z;%PId?z4HlETCi?&ub`cMC7xXmN69MFB;4Eo8nx|W!YOoGBWI?8&nl=C<8IWrpn2F zm=l!v1z_9;dZioO<7RpH(3t5FI1#pEMmqYPwJ~fg)uZWnVIza)Byey*)pbbR#aJsu z$dY2e^Gk1pKH(ihFCj5tXpDcr(G&HzX8VY5=Mf%wjhEbHgUqrUen>F5KPuIqIbW1Z zEVtYeWkJDZ+Kg>Tw&3}!IsKF3S}q!c6e&!?1yTa@tO%);plW}RIkd5{m6z9Brm)X; zKus`MGD;=6Uw0W=?rqF$9^E6dR9Ms>Z@NhM$H%KvYr@(&CBsi-@fba+AxhhEyZ1#B zb}(%!HX8$RN78FnQn;)aE7N&G!WoCbn!OsZk1@%A09UBL#}ge6@UKpJ`F9d0IRB%Q zW7s`lAZ@L2(`@(Cuu1B$2i{v$>$R}-0Wm>Ms};qTn!8G2HDYAls5?5M^S%wi8zmtX zFUt{DnIQrv!^@YipTUM{O|zU(8twLk8hfYbdcg7tjUCTF0T8^q&cMbcAG&DsBFb4X^<1A>$}IphGjnV8>2Whj_S>yR=lNiV7oOF?I00E1AxUuCX#1NqozcaBE>ns7w zrc{6D9YKid+kzO;X!2pT;n+`gK^SnpiIl$+zql}xuxL$mx7v~TEPp!<{h*%iKddtv zrWlJ8gb~$JnUQtMS3mGPG@ep+Je2IzVj*_jKl{;^`DWn)s)^k1Qyxaj2v%ez$#p@P zH8;Ag0-5Y;5lJe?z{*~6AIqu*^~nUqicGhPEX7Qn3;owIgYmq`*2du3dgh6b<|H5h zG>9YT;h2)0JPBV*T+>cW;eflv>_-ysTz$2p!B{SMY$(kVxko@+2m=7dx4V&|%1FDa z4t-wJ_x3{yMv3^GMG@+67&4+x`;H~{^}`v#ZyLPUArY67NlRX`olqb^O;0bL~w zQ!1*fER8nYVmbqA(q#0a(oq>jeoURqF%2r&qJJd&4HlO%SmLqxxH@1^I?6-SUw)*M z*C>$=ML74vHge(e$f0u1(jB|2mqsH5$f}Hr13aADULdt7thvNtYa%2MmYU2as#AbV zEa+;jBs*3@$n5aZNf@&wWHTMi_u>EtXOC*|&ZdTJ!V_PnbD6SA zD6Mrwfx;|peOod5xKcZwqts9ISyGQUt0eL|eo9#EIt$}U*xPHGz(>6uEPhP-&k*AO zSFVj^YrEPX%N4Gbf;R=iL%;8s*|l>T`^q(z?U-v>$8(3i7A(`F#Jz_BK;@u@3szTc zUb)aO9eH6Hs44qwS``&K9=R@`5Yl}WsYduhn=p4)QC*lDqf1k!zKGJ;c*E%mXB_RC zcqiD;yhma2$E&ZPA_#GF1M`-c*NV>4&x@^8HO^?t){v+b z1iB`}#hdNAvxvQzU(5}-!Jcq9*UHqwCYo_k7%X{Q+i}g7K>eg!t>gTQ0vsXP#z)4v z4)>~bA;leMlKTX`KnyoAxgjZ>LYzY&++4Sjg)`~js}qq;o#26pF$TwmW@f|{a9ZV= z1js{Fj>{+tON?cxW(Kylw_)BHI&S)VqqArt(`FO>6GUSn_Xko5aRt4FF6_J4Ov~19 zMUn6w(5m9mX#&`(;e!Vtw56A_Ll(B0X9L1Iw1RnftdJe5ww!n|*9HhZ>z0Lf_=`~GyrM`42*-u%o9?9cmW zmo?VL|L^9t6*N5s0ZJk4sc^Xn_Q;3K&2rzF#Vx3g(AM%nC_VU#EN3!M4Rj<#TFd+~ ziS|`J03MBQ-~Eo{Gq=P+7Rr;og`cRUNXMUp*>;_c=p}V);17ypSa7hpqUtELmm7K3 z3@G+jrC|=6FVtx?tlye!Y(>$1rKb}r*C}FfTf?#X2uxY(Zkc;;>78^L$$4yCsxoW7 z)#3=q<~hc(O>D5$iRK*NMoq!3b2gIg2Je49NH$n5>Zrp@%me{hlvr?5ww$=w17{=_ z`P~=B(SA4_66TMaziLO4Jca~Hv!$U#Abr&epQP8PMH>Zg9iHQD^ zY{gvyEzr-3wmK@2NfZdh1VVyq-C6F%#RU^f{gf1zVM%nVl@UNZyaDFAA-sip0N#QR zl;&Tg+}Z=MZMUqfXf|^TH|H`Ig?c*>cYu{G0%%TQp*~O#_75|KsQhanpc3Q}z#qpnR#{bIA1ptGqyPcHYwJBo z%i^S^Sv!#H8e|)%;HmKk!?khTq9hfWSN@?D#<*GE8qgt4&oNs#sLlEwlyEn z;K=&WZR_s4UX`k}!eI@{{cflJ0MK3*t}^;LFAPuHDhL@U$qm<==rVIr9-I$q_t4sw zNSgR_275SRzO;*wdl|+ovkXX4t>8h_Q3T=NC&hw}`TEl}dfa#67 z|Cwg-E|{FgbtpRP`Qs8$7ppo(wKEJ!4E{EAcnU|L2goTb(z=L)6mF)z9ht zNAlcWGVkkrX4Ox`-@p>DhQVORK&5e)JH`yYqCWu3Ebv~F`|bGt>x<)4QRklLHP2fZ z@#~vB+vZeX9&>ls7ljAYED$Nh-yDm?B8D(VBlM zXDP|S?9mBYsk1c6iqcq3s*|xcl5=h@VHH|s%~b4kcNAOIxu}_$l8sEPbY7L^#hgbT zd20MDj|3QchhjKaWkjVg-gMvnbK`3=IR^r7 zns>|D&T2KS=uA+PVZYqtYU2xpvcz&Y>$IgWcZk60W`qL~SJ=U);=Y>DOwBWno(7dLi~F3Wx)iRkcq6m7WnMVLrWBsdSXF@udZv^%de= zXLTP&U7a~}B-wzGNb1TluqmTfdL17dZkW?(MNGbkvqHxvo13A~v)|(f2R9=6YH`;$ z26G*RH+|yhuhuZ6bMrC;S!TkUZlu``HoF69NBbr<;_^xb0BQ)nhS zR~=%hq)Vw#&XU?;o1@BTOv*A>ovZz1`JXMvuUmUGh{0|6YN&vQ=Baa52vt-$s0cZ?dmK1NL zj-CB{9_KvYjf9U|)}&o5DS&nptb(rf!fi^{KZNFh{t&J%vP;R87(4KoE;P2J2psYT zZE^pIZ8Q?u(v9o|Uc|QB+Mk0&IGaL5Ex71;jp)cZS4QHSt6EKZW1agyyWTt-WgbkO z8Lr3f0kw@2=alPYb5q+$W$3cXt_n$;rH6P`*stGA%f=JR=vNyAF(CCxWXBqN=STo# z1}6|F5T_+v{cF>1PAg9;L=xPtcfXQe*pzWtPE(2$hA_D#0?eU_v*>CD6EcNC_g3wq zRRFv1y4wMF;~vHfm75)6@>n}RM9Bu-^8|uKJ7+N*N~dCnxh1HBKTun?1RkR(S*N-; zm2j@DQJ0siyFO10H16`Kj`#o}kcJ8Y)?>ai&FWANZQf@;?J0;V3=X)KP@;^XJ2D0y7CL12!>*!7^f8j{YLou5_f9{;+(P{DG!cNV0 z{{iSRu)aW?m=ye^Ks-cLPWb1I63(S3==*XbzxVAuO|z6(3M->h`MVU^R5u72-L5QX z;Gvao$x~Sr;eSpUZV*S>DupTfVO$A))0`|#f31`OnBbxK@%1waSSr42_J2oyK?8Gc z6qFPu6pd-%Nw#`aYnlj~sgAZmcUHhd;0Bjcc|DvT3}Jg&>|lP;5aBw&O~;Gwd^L{h ztZAz%-0Rd0mnV*l&z|rZ0bPVhY=l+vlmosbH9{Cm^%Qemh;83q?KFc!!>a}rN3Usq zRYa9(x3na}?Z>gRnjET5=77}L28y&+jj26B1gRDN42;2RL2UE0*bw8!Zb3+h`>k(V zq9!)i#2gp2)DOT6x6~D*a53aQ{$~{qi6VUidiPxr`>5r&FfP9)aG^z}h$xqZB1J-m zh=kM4yikGLhgQmAEgNB|0cF-B(Yy*Pqc#|-^0RS8YAj3TU`zwb$o6pZ{Cdof)E=Fb z<@&E+KSFPz-2^MN^#{s0&j3Tzf+(>)jov`17)+GhF-U_c^+{lngD?RzK)oaA)v(QzYbNec_ov7sg==!&19 zSTq*nmj)p9zmMgwYr7UnI$I&x`-GXL6rdwNREuMtd5*g7E>p3EAJ7hyW1D4_(MSs( z;29O!0hVmB_uA>SYC7qFGc4LJcw-H<1FKAvYMA{wx5zAtpn80JYyzD4F?S*_9N8L& zkC&g#ec2~kh+@t!Wxk8{=Gw>Y@3Ew)81*{j;a@16Y_6m7p$u3C%Tp&Nx;EQ(a+#g? zY28wv>Ut7}t@0Kp$c&5`f%G!!7k22MVw}o;Ps^haG9FQ}+kGRp8voYH5On;jxmM?i zc4eotC@;og-D+E&WP}A9kL=TDO0r-pyzV$TWl1(1Xl2Q-$>v7q*~V?r_yfrJ>nbF5 z2Z`M`%}pSyUd@HZSIdF=j}T5nAFSHq>pZJt3|+f+J<9g6J!e3CYOMG{YiyMkHUnco zK@uEoA5r(fa)SOxWJT=aMmx3IqL=Jw6~K>NpCX%eoYWrX)}NP*eqjKQdY$ zSI(qYFJSk3qxt6;OKU`JF0LwUdfOwCs1N?O5`0t!qbcm>J)8c!zZ%_f{xN_z3fn=O zvCEJ1Bl3y_yRZKpw>w$We2nT>O7l<_NkWXw+T?*R8rb~;YM61Bz-!5e&udX6 z5{TxeHF2;q5xbFQ4^pCfoj|)!Qg+e0V{xfzT1WqS_5zww`2Zfi2h6DataXc`JB~xp z7I{Irvo7tH?`TU&P=PL0 zLIR~++KR^_N+{yw*swI`q`+GZOlRYC(4HY!WDV2ugZn__hed1MpAjssL}*M!8YQlR zvGTxMHw(*lPCD)&Q2=s~_^Yd=eV6sBbRaDtJThQZGi+|X9~q1F;ZTfe1bB@$3wpTKChk%cnBEWXx zO}^%vYx=CuGx0h;+)X^?iD~cd#!Y`Z>`e+npVtAB|5F|A+e7-LXt2i!KF{lFr1zWb zW7@+6<lt*mi|>9O7tE%t-K#xr253zEh_jjn7j?%Y`O zwDmf984w&jgQJEncE-tk(X=LT_<3{;o|CoJ)-F>tr+PoH2>id{g>}E4D&aX3#zNMZ7DWe`GS_~%t?eP zIYWqkN0De5c+7W@3^a)~R|JdN8YtZkiC(xax9wZtPRJk z7ov=p=cv-=q?UW6MF2<(XOvt3@wO5&k>0R16Og(hzJ4?OBNuG_GS&H zr|QPuMd*7=R{P97s>dGDK}5W_BzGV>$uI2-kl=WQYI_dR{jI% zhJSDCbPlOM2FrIr%fGpKpQCdtcXorhhPryKB65k0SKvX5$rsZYh0?EB{P+7{E9U>| zSnN!0{;lDkwHV-26brw8Vtfz+qj8Q$Km94+hvdOi$V9y|>Rg6@G!322eMd@uAqAV5 zb35{P$Nd2qeO}M|EEoKnMei)&uX%w}W*F(Wm~7{eOm5=;IVg5cnGgj)ff?dKWoSW^|z+`!$&hDafPv;;l-FxWl z4smkvGNH*?Y))A%I}s`JnZ_9HvKW{9w&OgNEUNJvq*$+{bEEKt@j zUpOqb%umG}v$l#rxD#y2Z+sIX6k_WljDiMTtl72o%U(5})LIjSl$PRoebJM+a)7XAj+*bv-DRE+%g2OytWegxTtt#l_U-10h| zT%L@ws-8YeKGWHKmW&z;CN*#U3|e2_NY}h+Y@OVwMzCTyyog40w?4Xvzj5LJEMo0# zZxLBy`7%xp2!=ZEm|0h4@$#s=zZ;};XT2nAcx;+4S(U9E*j2Xz{va}YawdRk;t_Yy z9Em(Q^zuTNC5q%(s`R?3)QqfOm2B^?wUdYX@(8#01xUN|X5-52yi3R2do(~Oy z(6|nV6Ap?u@tO7jK>OU-G4#`p>7keO*ANW1 z_0bl4&U6kvG%3e%wqMMwG&Zzk>{u=Yg)afoJk(st0aa^I^KMqF7C z6Pwr&2j#;NYzFTuYK=c)Zh7GEfiINCADrhgNY*~FuKLFRq_F^x zS_oE;S*%~~rTPs54RH<~sjELIpk1AP>hJ3pYY>cZG&1sVTw#iiHd+d0HyMssmPnJN zQjBFCfu;s0hK>meq90`aup44(aw{zaASxld0Gt3=@C)aAFOu>#I~?AEz(7z#C4lW8 ze**l1@@d>mtCbE@T;qN(%2l4T{ggulPDE0qvrtOW z*B@hq)UjP3K1kV}ma$=8&Cd=?D^5MTsUL6^$ER%x`(C0+&<4t~VkOKds<85k}|iju~3Ip;DpeeHUGY^-*rA|+j?>1t7({&nf< z5pjJUraVeIN%Vt^V8AjtI_?%0n8p5_nx1SygFS2cexeKQ)Pth>d=qX{^!4bgu1S z+tdc{2~<~@JM|DI;cc%NOnEj`J%k#pv@JOPBBrp*el#E<&MXp*MRbVaXed(_O=_iv zQs_+>JZrSXlp4^wg!`pW=@W3Rc?Oxgx|Km6$pQZd(cV>~mS|mj)pkO4ukDIuEDS1B zvX@+UNXU<`A_g7>cut#++FiI0Ot9dQO=|q8Q52|!)|kcbKXfJ|E|A=!YuuP*Hj6th;=t zDLUr}n^-VXp7hv4G7YVT!rzPSO4YHyLGJgd;bC0GtQ(^Zl23H&L^-j!c@%lVM8w^Id5Tmsu<^_xrV(F<0+YK)uvB+>8vd5yT$kuGK3@wr^PYo4*-%^Y~s>& zX7YrHss8Z#j%u^+7vDbJ#bYGhd+sh`P^MpSbN)hDR-gehQ8S9D#>iLET?dHKAu?#? zV9Y3JqI?`6rhAuAl8eVc{tqWqT;)2hd~Fx9vk6kl3lD?l=*f+PaEiA$9YgEL8a=d; zycGOjc|ZWHiU^c7duIUk(%tF+4zQ-aIHKaoBpE4Oys2Ury2bTTjYFsvZr_JXYCD44 z4C*7djDL+XCqX~aFEql&z-W(w9N`wgb)Ztf5>)9|m~{byb{|5YzetyWvz0=MrceT& zH7`+ob?wzf1pyc2ht;2GLA{rAn&-l5=-XS$*bV;(ZT?*d{4@REfU0t;N&sGr2aqS4<=!oMRw`-QYZvFA>qGQ0Qjj*xAy70^(VHhq6^EeZEvd&UBI08GOh zsB)F5ar2-+3fRy8x2`7~C~AYV+m#T|->YKtQOr{Q`Tc9XXt-KF;2F=A|8##K8>}KX z7rp1}xosX7_Q=a_R>x+3%ckM(GTWYf9GFsz6W|TI{EoijoDHU`)F0Y}`@b;hVKmNH z6K}leE_BoHJ|Eh8vLyv2dIcU z7c1}ii7i%swLfNg;XvbTN-m3_T_jhfvkGTt8iW0kIMG?W+1qU=q=#I8QuO@hh_#cw zb>6jjUcZcx8FaPL!uA$gY{~VwgnU*+P-=ImvB+Jg%j7ie6rTtyqcY5pXk93{TTZJF zPOFyXIUyUpYadg8?4CrT1B1HfJaz3v*qXL#{he}drQ6sgQ=S;t$j*gMA-*heFM?tGtu0Tg)X~uPgq|?75q+QpmUKCW!-Te!e#uNBR9j=>m zA9^2c5P3K+qRia4NF;C64snt-)v!WOZp+ngA0L6sAu>VG$(!-OccT+8f&ioN!+NEw zB#n|9ek?Z(8Uh{gk&eLC3b?iz$Cm6rGkeE!lkC*#P}^)moGF?nsMSdB6l>!+u^uN` zPy;+a7$?LmhM-As+!|&RDC5+jnA|f#!j5LqXG?)0V^dI7>iCRuyCOR1=|Cs~S?GP= zVp8lJma=CV;Z*&jrn_giWM$$hPHj32208;u(0b81f;^`@^=K!rFh8<)A z4^+K~3wj^Bah(i?@sp>1if}=a8v*gRN#3~`n4ptc`vq1AlbW{REQd@NVsJ&4)-Ekp zK|y~ZoGm}c)h!PE$`U|?7+)CBl>&!MZ7c81aLc*5OI5<(?Cpyl^O>8|8~3neVoHd) zX~TRl3Q2?Qn>a&!9Af52+T(fD@<-jAwL=4jh*N5C>&FW=8;-NPSI#{ozpoAqXui}w zrh8oKn#EtKsj4Cg8wx4r?!yyTz3TLUYM&02$s4D;8fi!-`nc* zzVuzqZ6n4v%+MH(9;hmPG^oxu-s?=onw!8X4uFcwcJlZmA$aesoRwW&`Yqj+~$?@0n7mF3=6J-Avk?ZR3Zcs0D z56a4_9R>7MZ_>{$Z^q2k8{_CQ`T1{DaQDX^a=jPZ-z*;M_7KQ2?@7!UPjqIh!SFKQ zgK6lAz>MBpYq8#fJf7FtG{&57L1(FpTxUfV>&tQ;y_W>H%yV-6`Sb9uUV9pudyHf1 zJ)_y`ef&VD2dl_m^ElC+Z2}+4`@u9^PZ2xbyYP+Yy*6d>(j+A7f1M1kgr@9s^4;b0 z2=K2%EzX4&T$cLF6IWERgU|H26hjg$lM9o@uc2-ASSO;boD_RkAao(ie0-L*Y}>)X z7{1cz7Xo5bv`&04isXNayuAMa1nmf~ zPd)f9co9ExnWn14yLouKvj}~3hg20qaQ~>09&&7|0SY$%l@y#9<(wwBySGbB;;1I5 zh$WIplF$W-udJ*_ETXfDXT-H88Ea{oZ<#41r;Z~cJJlD8+mFM0ZZE3M!a4mqSN60cPB`T3}l!*p` zP8uLRdCKv$Uq>*g@e8?Bb#HBr5F0{?B=nNcsS?G-Tor1lPjhEkVh1WiVxGvq-oizr zm%cw#VYMj-R*744yGJ7Ox8Dr6+Y&MN)~*f>ZQL5I8tEAD_i()50jzRaORzZ4cqJgBW37oDb+=bli^|BWa( zLA0OO5W)QhwhEQR?Tlv{2hvEHq$sVOn+!nS>~ecEjl&r~mw>Wf5@uRV+KPlJ+VP)PiKCN1 zoMpBD*4ZSYE&5j?q!Yxr2`S@33dV1N3R<0HkfGmlR|4OrIoZ$}@we6Gi@wqifY;#Zk=^Gafm88KaZ z09G&@5`b8Z&wXwx{nqbTcig1jWM3LNpr^*<)=eU%oZD%AN(cfaWjFwnbOUx0SBFZt z5xxt~w`$n+tszqzKCWxmN5@2ox|n7;Utv!m*XXTH)_+tgnZ>v7P&{K^0UARhFOH zAGg|GV+^vrqPR*^lay{Fc|30Gu-x!Q$d z(;|#Cp@1w0rA(1Rh!qUDF-H?a>QEGO!od3qYOPf|#M*xbIVjirQHYLkrfb>7hie>W z;S`6!<{?q?n(K}ye&uGdv7kYowCwkoz$nF#VP9o9a}|z5Yz8*Va92uMx9ziulT5Jz zRrl)gi_TVT3q3(Xq&p?F0@qla3+KD5338ZZFnh`f5V^G}&9ymq4JOzTePB0QTrw^m zfsF}1{LbG4Q7^Vh{Y0Jc2b~hL-&bAz?njJ=k4-RmBN|Yc6C

  1. !)!kgULqi`Bd*5 zEfVojTdofTC*(7j#YbZVT~HtxV{yfm5s7kKIHQ_|Eh2rc+%B*eE!M$MFF{nqtwqQ+ zKHbzC4D97Ff6VQ(nfU`>qD;l#0-PU1aw_nXfAUpz#=Dd4wo-$=ss8!k$~3(G`ZpNR5VJc|CC2)`F0{|HC5q$Nn&M95IS^#DGUOx;c z*9%NfPHSZ4J!-negdDs*{wYn3gG}Nc|{DF%l+OAXF4bgBD1GAnF>Mjgh`d$;}G5|VqT z+nS!y`tp|kpn$!N;Trw^0$w4AG6guOwwu8Eu9*55u9M);rm;7o9UL5zyN-9&`9^5~1@v#lm{tF1#CQ;GDKlu?61@+hWBPr16B zAN~N$!QXw8o>+DzfUxOi8gs;WpW4YO+NMcF>nMBxERAa`hMLfJ@autWaA`t|bg1x) zduMH>Yq?whz9f~6bAAiHpZXzk=8w?uLx=A4c&rVlVf4EtF0Y#vjWqVrLG5s{!oI3f zyIe|R`^um>Ov$~UBuL>n9-VYv2g6llXtl5at~3uyd%d;?C<5(=5zF$TOb|^`pdTA9 zw8mIbTJ>_Sz9b@LfE-CoDFoc4*GbGio0U+#{s9yF(896oAMEdf#l71fmOePmbC~d{ zdvQ7GqH2$%+ae|5)V@7}2DZMTXTz$syauZieNY-WiUvy~2blBaeks&_N^EFHd(hoZ z3#zet*q*3wtB*JBixDYQMiKuQ=Y@`hSVRKEYLTc439eAy7_-fAs14@(!I6RZ16QHA zECIdLcRrDwY$XNkFf0nZp0xCjZI%BLn|P&7#J4eMzPxhIOTk>+Zh!G(SM>MIj2oR9 zXQW+%4_tUUf*GFyPnx}5Jcy^0CB6tZMNDoe4|Peye=K%wBvj7OKdKfdMTGtJ!Jy`1 z@S7N&;lcqdm6C(Ozih`J)|>RL zaB(d(7lI<1tje946X=kTzF=S1piQG!&YBV9;}cD@rqvma*NV!r&eBK-VFIAc$qv9f zpyo6VNvJbe10OcKSw!I|R7ACQC%r#i-t&u{2=8_R-jLq1(A&3gZRvo@P#C*M%99=H z5|-CX5ngB!}(csM4qaIfuo^;Qh;n}LF^A{`8 zDAT3%qP20gfK{;_gQFQQTaknEPXS^53|*h)m`i1NJ$;uj?-TJECHwe7>mnO-UhZ%) zgw!!OBI`{)fO^r6gH@Nmw817`WZlPEbd5c+ZRAV3d|aPEyfbVP@s@p(t<#DoNz!$3 zbEoV0vUGBgTw9BhQtxZ1tNP-{npIy-M_-C>co5*22hS~A--fi2pE5E4;!%Sy`Jh3D ztHdSS*aJy#EzMB(#Dqebo#P$UsU`FD=D@n(F>Lgj0{d}tieFf-vdHtjIn9E1uhv@z zD)h$@ac=d(EZHdus>|10Wjl z3JL2G3mW5OM#PCP?mu^;!}c#;4VT}7<12&*8%BPs?#GzE@757WVR=7D4@j{}=6h6) zrYe;6{h&%ij-n-VT;s4Tfdq2e(jpwGuu!7g+vVSOgBLR_bZ7Iww+>N#1}1HioqIhT z#!_BxQ5OGs=yr@5?T1#wCIjRWQ{1Fhj?g&fD1V8u@{i*rQg}u?ihL4FTwU)lyPHNGIzg~ZuOIp`42Ci~YJT9Fq_pZ>TU~Pw4d_wE=I8Ve z;F3{6T!2`?Dq(M}Im0pkt%d*fMTvQq^`Tt?r{QVvt6K+|>k^u#M^XA3{u(1zbyqpE zGal6ass}o^7Bys-|8Olt7pETqz@nLLd~8>ad$jLqWG$-sSBHGlrE78JM;!@L*H9|p zM6raimP8kb$BpU+dGUK!PJ#X*UymK9{rM25uI;J~a4t&-m|$HpisXi5nR}z8Rh3ql zVPMf5#1HzA?FIW$&T%&Jt6e*tUp7{g)29mxm`#G-F+}_%zYU)odiP&QzxLol@E}l< z^yqbys?M*eOF|Sox@Wpn%Z+H%E+QEPewGUQa-G?n z-fv=&NryypA*muhgknlwexB{ihHJfP$G<|DXrsv}xwQ>E%FH!oD@npQyVmP=R}eEa zomkg%qYFcf@jN+DyVO1Fr3i^1A#JyhSF~~2NifGEK9e}Py^WCVN`(axeW$(zE5dX3M^g=Q zI)VGY#{L;sfmg_X2U-6|Z*cz1{#OztkvwV>$*)eK!avPJntTOve*pj<%73-bhUusd zml1)ukHUjh>ADx>Cc`Hu*T|ACV4;b%K%V?W>&l{ptVB5FcBuUPgy`}V;(A%^+w+|b zU=Ssi1Q%)%1&o(~*ZY55p6G&6@S*SFxu>s)w(;MYQ5ZF!Gx@pKWV48RojVh1Zn6J+ zhql=R)ZDnly973;ckt(6=<-U>)0n#XVRs$u+cy+FJd2S9op$TAPjx(H_g=0WY60-p zO|{c;qeS!3b|KK8Etg}<2aP;htXIRdvf(DwE9NkT;@H{7N~2Uk>5ud?cvgLO7r!xV z>4&QI;EVmt?qznsyp9=I$!1>hV3bEbiz9iI$z@c%6S>J}Ny;4@ z61f7Rc+eHlmbw?4K-|R$<<_WrMC3AT@tzoRr11V%z47%5m+ zV|TkYOYUh@6}V`^2clzn^Ncl`1!qJRDpHD!@ykR*5Fm^t3`kOZJ9?m+BL1)5-a0JG z_1hmFKtdF7NCl};T0mMFWky132TZIkQI*<8@@2;!4QU! zk{9cF?f2k*g>J%p+f1%Q0aMNVwo+R>1^D|*-Gc*(?oYNV{c*%ShYs%q@4b>%v(#NW z8zlcQ8&rMg>DO)5oA)I1l6{BE1oN1PV#+Q3b)uJ7drNGKjB@kd+@$;%Ryjc$5MjOc z^wYH;G?RQGUUOE{I#ewFuxsq^%uF$37G-gJfL#2_w=U0F-X&g8i zd7dL*<#P392J8=s99_e_HjX(_^NY`A&j#tlB+2dE+82lt`D z#Wp$P*iMsp$>^B3@P~KyF`vv5M`l_hf=Eq{Nk9{}%`Snq8_U^1Xb! z{Ha(n+rR8$RVY@7(oumk)N)%x?P7Du@&j~)e>bhbmGWfs(T$lL3TWb1h!XwajK zL&AYcia?kpO({lVE=9kbSWx?To!Z(2Ra8xLy)#~70~0KR3!`SQT%Ld`Hh2$tSqfTJ zTYzQljdsG`HbND@CAer;f1fDt@8E`U8X_q*5og4(8nC>@!4Jnl(gDfFq>XK0?rkh_ z53aY%!S^4>CP+gi(2uKoJ80}vDMDKhR*-sxjLz;&BI6LB*@t+3*IeDip&FEwUFeS~ z4`!xzcMlL*?_G2X+k`Kv6EugQ9lUcCAjhrc`E<4?m*@?P#}EFdeW?(8e^0GM@yh#~ z!3At{^OS{Fuwqe1jaZpL2ReHlQup^GsJet&+976`SPtj@;dZ;l(Wf?xEN34%tEt3LJWvlb0UGL!nL? zaCupEjJ$XELN#9AAQevQ6Q28mjPW%`ChA_xX3Z%^i${dfJV<@_d??k?XC+Ju*k9XSs8laEjQ8ZzH_> zIMNg{IR!E3(c_T8VprHw7rEp8EuQ7ZLl*&!=Wkqd6DT{~D$~#1RBCD2DsvAr*;%A)Ah9(iFg$&AfgqB7`!u5FU*3TOF zm0pox-#*co9sH;to@M!gADe9y%+W0T3cEnO7pi(PTiim%VYK%BbFV;6*+Qx1b#KQW zxA>(M+Id@gb@j450V9liRxV#zn7dx<0}X4>L^fYZFuKi_G3|Z$fn7hfd69GZqhMf8 zUq4lUUhiARz1bJE@!Uv6V36Us02?!>aGk~NryZT;Ql!CZoTd?kFk%FB7!YYM052du zzqC_uBDSU7-S4=N1tbMAMt{F4WC}28$F?qvH+`LSg!H)lOKpVg8>kpc9%_f^RcS4g zu3IFSOPLyez4nzJavx%*Q;VxE9wf#e4U7X()?JQ%()l3^7S)ff`rMU`$W3c7*dZq+Rj}PMq%~;u96D_OgTFUG9NH{rhVy;n9s^I1ua!RDU zx8H*lO)0;k2Ct!%j;NK76;~qq6R|%`(pcS{H8(;@FGl%~JgvI7C(WVYOj4w5#$h&b z=pGS8w-p@y^^OWfsr}RS2>O0S``TeMLN-fhbuzz|IBXM<-MS+U8^RAK(z-+vGs(~d zlN_2?L#~euW#SAw7P8cMx^B-1s~@TitZLRtvYK?H6QmlpOXh6hKe+?Rj0j#~ZT3^a z^Dd`~SgZ_L3Dhbd$SS_Qb^Dc-PSK8C`Eo%g<2)bfQ14;y&Gg8gCXciqE(s-N8}+4{ zuQlJ0@X{oEK81~9U>3cGRJND;*VyP$vaXUnPxKv}>PzknqDtTWVJ@U@VajrUoHR7r z{uE{VftSFSck!!b!}WrssCykYHB~%aXCLbDYIVS5pt8U~yXJ^K63NLk?h1$T++ZEJKjEq()V6(td)!=6Rp|zM;f9b6WcafbaCFvn2de*uk3YV6W zLe-m}`f1xa+(TvrU3NBfv>mjhNbVz_t`hr)#!gQysOhP2tDf(1CSa|X*VKJGHJ*9B z+CZ;X$`umg&I|pH;dC%5cfX#~+(jM-z93*St#-hqc-?n2S8SrdW$ERcC-2|Hs6S>z zMTAnn1-b6Q#(#Gl3+URze6>VMlLbexQbH`p#^0I`=959q%Q^zf>@sC+uk#rD5A0{~ z`C>-UW(+cOM5SEsTCFpDL0fNIlK&i{bR_Tt(na*x`$3a$W1SA3B>MzWuk^Y{)t zVhEJb=F>pZr5sne`P`U8BIfmS(SXQw#T*HRpN=e4YpU8#>%g##=)j^|_>~;50;v_N zrE~+rC9(b1E!9kud?SU~>Q~J(^drjwWEfFnGY;$u4&=gdneEJm^+1+SO9wmZ>Am&31o_fsWKtkH1*e+Z-Ly; zJ4zB85`Poe63gSuHtNy#c2+eb#)Fb>Wr7)_EXCIQr zW%o|hQFFKyfXt!^*m1{6`R?>}SDLh+RI|_-lEmqEsXk^~lx=Atk%Kf9y-wOY`3V|* zM@4@w(zJitaK~Yg5K%$sUFXLKAe2ZwL2vQ??uB&5ia*Lk{xXUv=xf^zWeb0#S8Jd@ zvs65BBcLUs)5!Gj7p654|r=23ZkGXz=c6fh+l7R7wX{Je^E>R87i>EWY zFMfjdSe2ZopD`@-{{(eST$qbq_~%;*0^mr(PtY-iXCKgtJWwgSdqIPxosZ>My%f(7n5l~RlX#-FRrh1pec10wFVxSG zzbQHc%6oouSu4hbytm;*dic$t^glTKuX1b-LEz)9rez>IMR6H#kr|@Sa^3p@8fX;5 zzZ7M;N?h+^Bfb*;Yjla*ZP z;^wE>fQiONhR3H7gK32aUaXWHYvxUZ?7G*FUNmKMZM@rip07TBDT*+w(0eEB$7vcK zHQb)7QLEys4TX*8xgOZB-M<}rk@+`8{RBC)|%Q+kK?+yxpMX{&u75t8COH&lWD8j%v=R4ZZaAoiUn^0A1N|MmvbCep_!7+w3lYMDgd*v&>w|g<@n-m-KyXydv*7~SQ23I&cik*6*`@x*cN!`Zj6H3xm zB#QF9g?W^NR_Y0<8;%sRg!dn-gDBtie(b2x_=t%`{3_bF@`^z+`U4rfJ|<=ORrJS)Pr76MS#G zp-RfI+Zdx8iv+QV)Is9fCN}m)s1ot-M91x5F|BLT6junH0Yj%IiXG>AmEj>i); zaKnmatp0i7s}h>yDxzWa*?dE86|m8_7$&j`Cqt8URnyduV~K%Wc*Q5DuT-&q${hUIw0G939=h$<-nYKa7F zzD?MoWKBW%=^^LCmB(1SHt$+vVsK+&KY{4a=^egshvThY*FA@p}*dduUHaQi?b4CsICOt za$hRw7lSJ?M=VQt%98^w%R{i#Q;1;~i-1UX-;vL>*t@AO!I%|JNR6*pU7<_ZWUSqI zcUKJVLk5;zR-+uB8Y7XAQsRgW1_WFUOPe(1v!U$!s^VwH-zwN1wTDhiqpt)+cqN5d zC-@<0PMB57CHhEZ7H@GV%VeYB`7uW_Zw~eo-c8BSl7C}uNKZDbcjkWIhbAJiB5&CeyI3{V*g3W(x`Cxdp zK2dS8=KlSJTlsIEJnn&7Iz+;_5wp!q=yPzVB_SgRY=U&qRf>bBpw zwnyBKoPCD<(#-fgS#j?Dl5I@vJZ)`!a{U&Q9!!dCMY>|sr%F~tOr|GB^8368PNsF> zZS!+KR_yr2_XIF644J$Cty1$=@$Ygn#GP5m{K zd0bY=1F=;CYN$|Uapi-&U;`^n)xzwa=R3g?bk#}WjU`X0^ z-}&lTG&Fg$hF$tNtJWt>JvM4GWAD9Qp)jU;>SFrX;pR12EVzv<5HOSlK17pFG=7NK zsFX$ti;6q6M6s>fE+&1!DkvlyJEW7-AS8WG)aHav_hh4j#!{SHxZiVn@a)6fM9tE@ zq-zE^mB&;(hO@INnTg1B=y#5)Ik?eJ(B*u9ocW(1b^_PMbhaT%?@dgw+3%=dN6&}W zPgPiUHXP-6xOt>3>d#pXDM$Y2JaGp zJ6dlCPI~ZMIOcAXedpJMa%>@=xAvUXa~j26FVG0>bGc>Z9^b-ib*}@eyu$rtvLJ>` zI0|E#v|?F|&bW%}pex>xQkRWqN}EqAagZW9u`PZ;kvm)HQ3; zn=*`IVS+)8GeO`^dtg}6m=@BNOK`%^`=w)P1FLgOxZYG_+d0v#KuNizj7>{DS``0% zZgn!1&pNE_yv4US@$a+}&!fz6GYTISk&o9mS@-1+H*D7&(i;g468n#TBA<{VPSh-k zM2TfC@~-ae3Ub9@-mmq#=C%#nI#UdPEJAsve8R2B@OTAf%ZX!4|74F5AK##k$sBDk zQ~0{Di8)otd$Do01vkdRVUtYw9uL2|jU+#+1AS78$ItsCCU49}R6zvsgf+%>9C}6q zop$g#Zrr>u_o`~lY`7vr;Q7rYpY*Y{I2If0hc^NitP_1k**Vz8LW%g;<&e*A%XUG~ z)&ec6!Fho+s891Hyu3*XU)TxzxSwQDW>e7!kyM_$2>|nyRWU!*WrvvQlZn2ly*A7o z)D~S$BM^51|?uvS?nZ=3zLjD_s6iIAdddZDQa$T!LQeI=q=YRytfOyBOt zIB;gy!ttY*dPr*(_LS3X(qFd3fc8JXG$vsl} zl{b_RnUW)Ua+yBjF!Tx%P|)g%)#ayN$sFJd>i%uxYX8f%{Qa|k&qc5m-#d0{J;+6c zUX_=ZcU(Ld@sNhJ2M&6<;|Wpk@65}WP-UA+?1&Ysw+5~lS|6OWRumtgcd8UQ`ffAp zCdZx7t-YYW$+y?xUa3fuPx|`mFF1^N*2@DNoU@kl%Q~iIlTk;hz5vDTFQ1S1%IAAW zr7M2E_e>ZZ_NAwF{kTYa8gJ=2R#{2j;FTLZX6ucl5s`+>%jv+!5mn}t^;mnq9a+sG zICspFg0q+;?fVbH`ugis71vyGc`&A7!H$)W_`bh|3l#R%erRvBj&@IrD3Z)GAys|w zd2Zaf{`vEQn~?TM%MZhDeRTel`T>merOir&p{JW@u9V`pn}_f|q#mJCtX0@4yq;Hx ziOGiVZ7QtKG##$2V~o&)w(k|Ve7F1>mYe5JHUmjrGm|CulP1!UE{9egF2nyJ-n%%KbOL zt0O$II;201hIIh3B;dRGo>g9!z8B4i`~<;{-fKV-(-~Vv6b?l`gCD0e*?DN`x*)P8 zHn6)dYvCK-?}KGRr!<{K1Rz7d>fA0hdyHv`a3MkTT%V z<1_dvwLUP2hPaM0P!xi0bj+%##u012FGEmRe8z?6D*Bky^i2wB+T?R`Yw+EbC_>Ibjd<*4Ex~ray z(@}@UH@nyGO$k&E_}46Gf20lGyki*2C5f8u!Ti|OmwborK6&-M5nQHxIyqF5!8H82 zP99umd}QuzHox`*lL5ai}>y#nLWE3WVVD_ zGal?`ee@1X?9mzb|8m|^oYc=%Sx;*6^+xt`IZ+key4smzWy9V=2-j}G4~C8uu++VX z8s1y-Swid|x>8LJ5k`&P+{f{I?zzHznsp^ZZ;To(8gftX3U^i0-)$%;s5GrKBmHn* zQs$mVCUkLUe&wlTx!aU6ex$vxEki9>Ff-Y^q;vt9mG*j=zmmr&-Mr6W)pVf5ej-(n zk3s!5hE&xX$z*03wZ%1&mFletpM{Urtfh8ZWSGl#vRaJYA|4eAG2QX>aOgYc*`d0O{*am-DKYd%e$+G7i6+ESH*m&B|Ryn|1pxSSXEnS7H{l2 zYav4)9IZeuTHoSpscLboO!9d28e~^iV{POlTmDH9HA!R#8o`_hh$N=lKom#j^pBesgLP?jEl7_KOPeR3L z23E={mFJt9`7k1WgdX_Pkl~bl%p3Vlhe;O5)}5WTF(RKMD!*Tn!eoI>DLsIOJvd&2 z9yjbk(+hxJAy`+R%ER3rhGz|8blBf_b8o^Lfz^uY>DnUFon2b<5m}K3#)kkGgv`c9 zU?VSTBvpID-m)}0-sGk&1(+V^sR6W0kpp>2xW0P=SU_)SzJ&|4E77*Gv3 zX}#-DQXd>mNwYb zz`v0P0zQnMT-X6`S6{D~9ngIfZNOD?xF(yANN#x`+!6XwuigIBm`fRDd4G3vmO0 zU8lHiDLdNvH^tUmh}%aha?h;!wBoTiuZwM_7b9R1V*)(Up&tWZ)}J+dz9ugDj#IxR zFp!NX#q9dD(^mIrsEVzAJ{mH3_*`Ik^j?|e(;M`H+3)y!O$UObP1CRoZo;H#xJzIv zJpZjh)${M+-2cm6y3{9@7c)K7NJP!|OZTB3>a_TH)4dMTF)^s17d)G*L;c9Hw^_}M zO>o{;xO zWvlo6v^w0SdhhUpW`Fi4Xsmrs;@o84+gYMr7~{<5eEi_7r0+9z&~(o~U$eIphIGL` znm?`BY2{P)U~pynJ~KRXba#LlM8mEt?%om~PiMQ`b@!%7y;T6BYLDT>6M${6U%UnI+$Wwn0G>PW zcJ)F7;*RJ6xs_qqZ9pF`}U22A%zaac3%bmt+hD||!MT*if^>BYQ~+?}6DX35m) zl$Eb z{{$t>sLXivn3<}J-gj^D{N8`@(p}X9g9*4v%SCxkBF)`W$eASTT-M-Ymd!)cjKk-q zEHdM&Kkh|!BfNc3@iCmkXDhZhy6k6)RzT zAE-PALcn4xeM1&aIu|bhYO+v2fGlQbkTg>wdh&x{2v{PWaVF&_Ncm9lvt79 z`w0S2TB37N0Hyu)+(c=j!)Fz+TpAn7T0kt86c}hRfMOH!e+fJQLxBnlKg;#(2?LPf zV!%)VxK_p`u4QHwi>O!lJB-d>c~NxWzlo#ruXStbyzdZksK2iP+iGo;GHc8-D^px#h#$0A+45udSMCu=#k33YlNQ3f^!hlA6t-{Y1~zxv z#)#m&T)`p8O*8R_y?q+2mYPL_HuM)m?Qz=u=-1`GD&2Crp_Il$?0pQk##FLYie3aW zejKLXIkxtC$W2iA2j zq|i_~C*Q66gJWOlM{?I;5g+zzn*36L<;IFTwG&ilX zQgkYkRa~ntUDZ$GDzn{)+?g^8gQ)a!-YA@u-B_uZqF25fgKt2u1XA-sQ6)pN(C<+AY3cGn!wqg>gRCcYx8DI1NoH$r;p491?9$t865O;!#4 z1U-uOyzekp;Q~{SN$jC_P>SfU2BjB}AZyNS7W>r|J6gw*R4{8fMd0=N4|)lQEPS|K z3Dr@Fb8b;MCWdsDZXzA5VGe>?K{2YuM3VKJ4j?}AaQ=2O>)?5#75^m%dI9m^k=m*6 z48tzs7y*LvH%!8Fc-2sK+Uiz?oZ7hhKI+nx6bXqTk5{B_+WP2(hu#eL?hr_EwNEby z&Uq&fi}H`GChq2^^Fxm_mMMF<_`bb?{U$0vN1SfKETJ&vrAFgo70r^-czsN*PWDJo zfsaMvZRjS66leS_)y5;Hz`ysKB-#-n=jcZjPB<2Y6$Ud=5f<)qCdzKG?*ae$+Od@Not#jZ?3knzs3kkUPMC! zv)`4rR&ES^H0eTXUW?+&HtW=gaJQSsD=$!0aA=ufSc<`v z=krmfOkG56v>$&Gk)nc3q~r9)lUqWydft!g$oT#Vpj%?NK+h}eHrkA*9+b6F?cj?x z{G{GwGo87uHT)`GcX*df)Uu7`Qt!rca1+I_qJ)K6n}@F|MK zn5_&_cCvrUyKBh@E;$$kx%^#|?GZJrQ6e#g=rw~&t)OPxZ}W}RtA zyhfwK)L@_M@6W0Pb7I35NN+jepW_NDpH8=myS+>@!5i=bkyxKNp{hMO$8kP^VyoA` zrsz|aw#-H*p<}9oZU>o^esk8zfs3w}kcrVwX7mxr4nO^}*c+H`%SRC$m-~)sHdgaQmGk`UNd5FYyKeKB>@w#qA~8T&%D-Vs)tss!4i># z8pR&ec{E@w+O84So;XME8>*gUQq5&^IDkWwQKqiT^2=Ml zx@k#p8{$!r;d*YgpMb>#{j`8rwKU7C@BO&ei49~Q)#qjJif>^z53UB8UkoW z=^?Z~II7LZm^y+CQ708ZysnddN%E76-`u!sJvrp@rud*Etm(m|E3L3AluzV)j-Ej5CDiZb>_VTCnkr4!@nY4u#LdVf8Bb!?qM=s zB^bIn>n~Qawkweae0#!t#dGyG-Lsxqi`watb706T15ZxBGUa>;Z%&;5>c0W z5LU+xpht|T@X)gc;U35a_a9gNvV#AK9r~|N{-5q)|C?I#|LP&xD(NX0sXSOOrocA# zmlwLpb6(5p=kw4RRxSIKtYdrV(9Pt;b|m-m-Q*4tyLNxUdXL-or|1}UxPt7O-<;t7 z=Q?E3`&(~e_r$2RLy0atAf~LlEhHv$x)%vAijTMXI`@<(9l*=y+$%bVG1}I^tPAp9 zp1ZWz1y4`n@ws@d4VfOib9kW&G|53nncu|Ys+UxSBm=__VD+fz>(jO(;R;=);LRxJ zTu`DAkM**>_8K;Aa@?LWKl{+bFHCo7iza*4SedRZ?n-8E6KPJv&FlE;HV}?f*U7)q zBJaDG8)XLfaU%EyZLmAH<^034%ahgEdHnMaUuWuvpi)eg1Zp}ueC`>h_URQzv&ERt z21rE&_dQChmYJ#T2}g>BF%mmF=E-xb-~T~SwsA9LC4Jl9Kb+Of<*bVt1b;_MW9;?WW`nvtvVlv47fXrl(MI@53GX`bM@y(Yr zdX-m9a<H~?vCuDd7S7?>ev;#U{OV=uHf$}E5LTDh>EB#Z_CVZ0DP+TqKkr;(j)Ds2?8-v2 zT+kA-e*E%T=ITgRvB3fha;$nmt4;!#jdeiJN+Opg{OaS2TiF@EWkJK>pfs8Raxq2BxH`tTsD&z153uYMBj51@gq zln*Es>okRg-x_ngqWM=KTW7C_YKz`8FvEDL7RSrk6Khc&ZnLpU*g*Hicxv#$GV9ls zoV(eAQnx!-AAGfqc|rp1>-`j&$?Qj%ob?cFkPy{){qRQp+;T+C#@9x;KF%>VZjIc> zj<3)AoXno?^;|!}nK!zt8oBAiC-06>G5oy9{`@>iDlN}p;QGpwBlFw!p_X565mZK& zuWVM$9JIhjn97HF-*R(cryMfm2O10 z%WwP3IYnjr$)cX_nn|`-ocw?A8&#ZvEzkue`HjYmvNw-9zdVQcDzK3B6-Ms%wNtvw zkK-e;K;e}yW;fQP+x-%0LRY)8ZV}2Jd?gvixQlmd0IcICJ{s@ltpxcN4PewJNQVqs z-7gfmBHAmcc$__FC@9-ty;?^EwEUc1=b^ESu(FWR#7f|_0VjKT>1zL7 zLBhW(XV1T_{qN5oldYB+V+gw*swI2*P1I<9lIO@oP9fKkKRy zKpVz#MsI%4@P>ufzFTb|EXL4(#%PjollXNM7A}<>zZ3RjdL%b3ehMG=^eoI^7irJX zUX8Z+jDmfx@A_Kg=kA)a4Mal$Dy1rH=j>Q-Gs$MhYK~69h$DEZa8<#0A3ax*%{QRO zVhyPu+DexU){@)ne;<@Y%YJQhvsq&_%H2Zu;0@eAQX(K4DwFZ-ptB}XyQ;m-S<-^N zvrEX1+PX}tdq^8bQO5y&mz{T0|K=ALYejx)o)bD?Q~*bj*zj~E13CrGSi*CjaV;JL zS~|^zo3C734PDt5w>~#zGv+y@K&Kr~C30k8pQgTLGx5tB62rNQ_P%A>j_U5oIG6R+ zty3)D`T@2uo6%dSu9tC2t1reAZBTTx;YN}vUr;rV(zROi#LxyuRixCZ^O@Z3Dp1Na zxb?#6O~toDZvfwq^@t0t_0-pKJ8jNY+lRdCoxfu<(RGqnU0LqD%A&0#@TStZz%^i| z2Q3Y?#ILp*Y~I1k+xsf+VJ5E(F4{S?m$5<(av4w*>LI z;?^r{ZA|1B*=|ZF)2uXm9*=0wtX3k|Nq%zS9b_D?&%q0d>9}XhjhGE4u}hrI2~osK zQk;UtHhOjH7Nfez%%olwzz*iAlS*h;bjD7vuyxhLpwL{FczJ1ScD&kfVkjFSR_E{qaO@ zx4(*H*w6gP{<%`hLR(`?l>RpoHGyFf%fzdSi(V!QB~N%UMs9J?$FxIaSjABvH@@46e`C#I(%`{XA#?cgTj`RqrpuB*ESh0_DPvmi(l8J zkCaqFmHSr|0kEr23=$)|H)@VA1_psSzptPQ&t>E&wE^NiL=_q-2sBeZk!AHE<_^{sr0yZ@gSGOjooQP#(K5!{PM;|C756J#3~e#{O+8u z6Dp_jK52dzNR2(V2rTa3@CVyS92hjk6$356FT)6tv?UH3U!VZUOBM+WU|EZjH*Y9uR8}M$LiqsXeSd#xwh9C8(!q*v%fgsJjZxys|Cao1vbVFok%P zFx5Iyi&hcCZsV4CIh?t|Ndqyxd~3G0wzh%JU43CjuZkk>EEL+ z{}(Fn|5^RAH8HKf2MV8SO#dN0^(P?erQNXLa0XUueuRNt?J|x4T1=rN##W915tR@pI!L6mzY0+sdQ24O z0iUsA2m?yf5survp)DhnzJQra_xSjJ18nC#2FyWTO~?aPtgB)Z|#fJT)l1up2KgjgLWAdKeBQPQp6Y8$BhRCAS>BEPII zf^~NU_G9;V1E#tBe~Li<++_VH?=<~i6wsloesu+g<}srDFP8yTepwWOJr5kt?!WkQ z#9Y}}GyTQA8+c$z#`tJpFZ_YC;`gnki;AruRfVXO6qBTUF+xo?2^3FlQYiq^;>X`N zO6}C|0*Rj#O564a^ARw*(L!Zgd#G{XMAkcjABdq~eE1rEeT zF~QdFF4RmRDTck-R0i0p)s0{~y*?0LEymQuhO08HO+^2?7f=J_xDO{IeOnH=%v!V1 zhE&18sPT1Rti>XMA7fCBv-m77#F9$k=m{bzFk0kRI+H^iAG?~PvztBa?loTgl63+~ z0N-7IOxaqVkEp8RZ5DaB4lErhASJi_h;W>RPR@HEZy|ahiZg0QMEc+r)cbF@o{XCI zSnVe$h8*&J&UQv|NT^5qF$ zSotf*Qxjk8p{s`{B_LzramD=rs}(t9EDf|cj!5;vVl>AFaAF<5bB}rtfT}8$K0GL- zv|i}&$OOqJCMrV=UAajaKoE+kT#@}P+2;Nb*tXPkJ;syGVo?`FO~(FRH&=pIsCJ^z zBBvNy)v2p4CfJr3uy*a&px0bhPz6MVV$@8zec5j|WN?{qmmz z>BRYo`NPH&NH9*4-q-|o6I25i>(-cT4bV1uhr5My1K_AYGQSE698YK3p~sxKJbWR5 z8veJ!^qZL342i}N)B=z9?o#kzAKOpaMOnd)xL1jazrOYVzl9_FzbL#QRp2Ff?Xd;q zKhZA_2U|DUXn0t($k-qm%U|1U($=VW;l^Af4C+_Eu?!@4E;Bb8gT!SbA1^!v07B)f z_0%9JrMC8vhI|{jiU$Rq7{pqt=BVTu;^AZu2h{PO;4<5{Ryjbu`s$K&-~KwTkiSJpyXYsk8Um0@hZ6wrz* z;qj60=I>hKS@Ag4GC=M;`^!KU0^JI5$?&9pK!?7egE?rc(+o zbvdjL=6L!O1ca?8|H~5aw~R3SXJ6(YB%O^)Y0Qn9W{^zhN~4s)JXE%@d$?gezc1dO z2{7w5kV^m}^Rq+;H8AAtI#lopq6*mlCm_51!1zJpjz81vgOgmqI@woEgbQ6TLuO~nnZz?`EG8BK@2HJoy>}BJ)B(CpfQViR z4cJOJF)n0Q^{iwB)>UGRy}xvH_U1F#&izyDgl*v4b^t0kFhURNqIiAsehO@zcglHM z0sG{Q>Y;q`b&-JPcT@SVHk7z*jv}r=kP&J4%N?o);T*t;hfFqwJv?m@**yx34$i>S zU6KM^3d5fs|C+DtJ+1vfN>TsnWZB;5LpzjML<4;MPyf@}{=*LaKfm}t$uB|_M4X!5 zOaU!&zouK(6RVa`+X2<-wtIiNBEPSdY&Bs2i3mCm-O`|nfilm=sMv*bkuqJNco~e6 zqr*!Gyb*NNCUij#`I35YA=(br*h5>STtUhCP8?lwjbY+>Nq98x{=fv=FnoU$7>TIA z?~=tSMkyxf3V4-pGOF_@F|=s6W&oeILaq|zmI2lJ22^tZIb?}-_QtC^mS0ZIa)vTv zHrkk=MRg}sD+??sqL3viCQ)1fFbOIrioR>#DBTB)N!YkfsqTCAjF4jSaqq+tldmYY*wBfD?+(5uD2Vs;U ze)FyWN_6J$cN#Ws&M=^W;8FeRP`*K|^8t8&-~YDQ{5|};f3^K=%t||NT{nQ^vu1yJ zog-thp2+gqIArlJ{g>aDi`7Sr@;b9((#xATU@QtB?%2+Xl9AgmiZJ8 z21)mx!@-mF8&IWLW)JNu%2Od_7)@CZn_%dvGtm1R5KqAG5?I~+UvhD_bpoVk6iiV5 zTGy0$o9{uPv6mm<1t+7OQL^1A*{YgmhD4}4JO_hkUi@$fi-!~6Z+7k-5q>WXS-t_( z#s1cyJ&8%=2vFce;2q5L&j5~Aw-V^|jeEr(ZQ_4zXy&p!nGXXOaerGLyB{L0p5`-T zfF$tzPwM9P!}a@G{lBS={|ju9Q)*7)6yBym9SC$i|MQt&~#RxNQ2S)jA6AWyvqEkYSV9EC<L~L*G#L?g(O5)A1ej_Ds5MlAN#58TB-Z$ATkv0-bGgF==Ggsn z>1@?k%b<@WNI@KnjKRs+|ChJ;@8>7@udnsX60-3=+bOxE%vQTPlO-@m*A~EQPPlya z*Mk3tB}LvDX7mc3O7Q>=bCiG{g{$i^5DTQ@mS?RJV;Ft{CEsI3PACGGi`TO7oQ&HqGJCa QzQ%v}ZU6gao`OBC zl1j)v&DfOeGGj9qGqdJ9UH5xG&-L6_&+}c+d%WNAKF4=lQ>&R-&6;&?{+r+LcmB`e zckvm}ih~C%4nP6|0#GIR1M&MIhy8&b=OO6uVQ4c1K}#WFK>y`ihdhv6RK*R$G$|v)Cp}o)&0fEK8|LY+rEV%d(5fTy< z78MZ{T|AbGNr)|7D!x=yR9sSATw)n`h>9)8NG@Bx_S^g~3QH4#xj_2rLm45*7hX5|;oUC|&`YFDSSK zG*(y$bXOo4{68clCA@Oow%sDq)@MZ5`^xBCk9)XOWlw&U?6DT6s_xlKp9gkrg+;|Br7vHVRoB$k)i=CteAn9cxxJ&atGlOv zU~uT$_u(HSqpYdvnOXK6GQY6cF9AsKAKm)5p8ZR|q(HxxfH@EnUF?^@k^pcBN(l+C z+a|Jdx3%aQU+MKa*O$udiF=q|C8nZ#j46BeQj7R1RlR;S)?(Lw@7Z7LSm^&&&;G4r z|K6`2Xc;ifB~pS?5DwyTA4PA3{yzR5gTHOypEl5d+!~zF?zgR(2&j|)_O9DKU7_u# z{;55T+c&isF`0>P`H-tDxqp{@+ZQu0!6uCy-}=n^T@yBf@fPF4#7f3EsR1WC@xVKv zhNO)o2CWck9?)L#VP(?n)Of|md!U(N%lw-ipu#~avhz4wlX?4g860EmI1rPiP}D5$ zT#rG89_!cDfhNSGZ>N0vo)Axyy<`>2O}wWCzMLIr2G6sp1?8fANXUbifGRkeDJOG` zh)M)ar~n`6(025m3oYeh?EKtEubfC!te9ieD3@luY8F46W2YA-o#Z=xa%*|QC&0c zPBJ@)4?V&#-T2Vb`-XhzHfZIqTJ)=Pf4A~~_EOSCVY&O-IP2k-&_H1DP!S&8{Qy(S zhX!=8-3sV+J|stD-Usi8p5y*}3JF8kd+_3LKdOuc`A~?1HXmBs0*p})eM^}+oi4zK zDz)VJ&>eTd2|k3}j$|L;Ll5A(Nv^s#ADZ7x{`09a3ZgzaA;noo>Y+2O@T*BJJ@oN5 zW>!Bfj3{vpCS>pT@0Z+pJZbd>MnupC<-4GdKC4t0?2>lwE0>TqZ_)n=pCTN7lwb3?XBtO%LOIau~``n&xa(*yeye5KC~w?!iabUg$t4$p^L-gNV! z{;U=nQU*e+PBrf|cFS>aPZAmHcaBk%FnQl3zGn5d&DVchxl45!L%J?Fj&rn%BZ$^H zd{4{do@6$Uw=sf`+lBPmcYBiLT3f#d?v%!kke50*=#D(iT0v>#a3H9jQP3!?`!{&Xg95>+rm#a#Iij#fZL zSC+wiNCh~XWCkE41$>A?@3sXOpThB>xTk_Q{vOD`2lCHG`nN^?(Y3F_<5lY8!W?%b z`DhDC79p_RSQYu1y}W|an#0Wcq)zLqmz$E`xeLlHdzTrq&hn}1sx{Dj=bv2j7tX3O z*uY)ohKf;vLg2-63nA|3n2g|hDZWx%Y<0^{&6 zH?`*3_FFQZe%3qiXDv(3^zrcmfycKX54%s(C;F}Y9FZK$Us1|K)@GHB=Vw;bl8NXjEdH^c_W z%RQOlXWXYWeS=H3ckR6<79dr0OYzt~*OR+;T!zq_?o@SNIL*r&!=B*984IxdYF-rQ zr3}Vw(yn+n`6kCrIOAoh*7cWlMwV+%Lu$HT-<%B*-}vbN-Z8D+>&Tdxn~>%x5FHRW z^X-dKk`eQKe*c)onv&;-16=gWR$hZz1yg5wHVU%b&}FkcDpB_#+FYT>OC|2tOjknk z8FXn+`BJtP;-2-o_{=iD3nvBVUL01)iQ|0}b`<^I%Q=isz%fs0BkQ*0vjXbl&^Ah; zP_nWl?_s&h*7m&I%UP=$>ai z;?e_2_L&#sYNK`R?=d08_^YNgYrRb3{~Ie`*y!C3EUxUSp~b zL!?$~ye8U6XF4=@2e8{;MKo8!tIIWfbF98SA2G_wee8)*rCiaA7;*7%G(M}voufW` z`mbwXg2+uUzD4jmD^ncY#mRw3oD!$ogMsQU3}W-$bRvll<oc`pZ73}9yoV0^n1^DwIqd`Js&G|jJB@38@gL)#ct{wTz?0p z5X)1bRKnb~dQ@~9UL3AUrA$Q~c0u1MKjTA>lVlefb}3_kCSJq?Bl+VC3fNV@KqkzJ z{?o>;b9$@L!8K{y6XB$XGued-2trk28$xDcRV?()EM z&yo@UtZ|U44-7N0z$_#+fQoKgZvA(I|3{7RA)w|`x|76Cnu9eI{Pm4L_G)N{Tz+sO z_6Bx6Z7awzvt!#YPj+Q9+TWC0R}n;`zsGJLJo-%jmd=up?a*>amg9<##xbwia#N^P zAVDYqj@WwO0p@#s^u`BEDoTNuNb;d~XJI!AM^THGVB07=OXIE}pvR>bK}}b`H#ao| zSLE=ANRHbCGg$QbeKr&xxy%;5Sx)_Sh4x$@}P_^RK+wP4-q|6;nivq(XEymu!u>os9? zu4Gz%w}gUy#@B~^U7{abCvN-fK=*?lCsL*ow7WUL$-?7zW00as3abWxV z&JOY+39SG=lmJ}krakTqc|k=Ei`aY7xGDIDz!`>V+&zt)WpK;tm%vGyP65jO4mYsM zs>=nvS=WHBasWYYgYA#~G6M69;jVyGgPl3B1;;Gtgy(h0NO%H!HR#_qUy%8e0IhFK zT#(uikpS?l)ug;=;7Q#gb2W?U=%EaB-8o(a?#FE>xZgDoP;*z(4eP&~`ag42+0?FE z=+aIOU@%oirt3VNH4z;1J5B;2pL}8D`hi7$Y=PvcL!`o$N zW@QAp``{`E+&6U!mNp*Tft$%YI6qneZ1Yd~2a>Vg55dQA%=1~?N5?_-DTsUykEn%{ z@;is{+%?mKlIm47rg`qMV3!kZMfcQ@Th9-~J3BoVpJ4A446zG2BCwrJ{Y*uizk=}o zu&J7c7yt(z_#ycG(JTDFo*lKs#W+iT-ZEHP$|6L#rMpQrC|-TMY--zf2DeL!^-wJOvCa zpn;0R9A#45TuF%rOP&CYb|%cP=nkx}n)%RBs1V}ZE;G|~Xb1Im`MN;NVrXEs;R zrp^BY_9*#7aYftDW8Zte;mYIJ0eHP~qu@arFbu{Ia&K}KTrkXC2@-Sq(hlwQY4z}G zP0Ai7J3ec!P&-BH)vF7^UH!L*eMct%9G6n*!!dGU=E>$r3e$qnJ!&Nz_jzD<6z2$wc$e0nr}s z+EL488NE+?G&~+0pnI!SHq1E?gWexiOlj1ycx9JTiQ5G;zLL9XwYY*(t`vts4=36X zd|j!B&-mwlv45X=uE3GgIJrLR?o>|xVdZbekzbZe250V^kE_XR5mcx1=%1}yVvjLUK48Z&R~1XH^z@IK?-KJ-ZDK(SEF+>xwJ0*W_f z7{gnf!X@TU?ZTRodI0!3N$ZhD#ifEN(fF0KeQt-26Z$G`w$$9tgQqJ~Z2RMh|zGlUKjQ>0oEm?oQqo zT#$Q|QCJ>nT^K#^)o!@-zEGT{f{2C8?FgZZyA?w>AN(Cr|BkBH0}sGXB{Y-iY|}C9 zf~^{H7QY8H{a*v-??e&zjDqMMN3A#Iz}aWnDNG`q1WKXe&j*LM$kVcAD#t$3<0 zs2xWCc7w&6{MAE)Wrkur0W#1>fa>f5#Oww0cFw8)fdJ`?Fbo&~^I-G5Me;ZglmcPE zn6)BaoRHr!)grF??;e-|6;!;14{b6=z!$pw%m?7pyY)-1-B3;(v>BtzECs6@ zdWhv1uXtdKA>6gIL>C#RT<{yxgN|p!J&LopPrN&{;^OWnExWK^=c=2Y5h_*(`glAJ zdXi>Y5~OX6PCVjKK*%~LOzW3wyLvdY6=g+IgAF-*6td-h%HOib&zC;`&e=}&VQwvWWH%gIdiRayZr?IvhK#l z{!fGYgL+3rN3^-pGdpPScKT@*YuSS4>dJ@Z=?47$lCiL{}sgwyE+GBGkbm?Yu zl}vbv|6DRxssWYgV_BkNmV@ScNiScsvZ{BET>o6YDd^(Co*`~q_m1Z7??XeFIONOY za90SeeoEEi#qgmEv`AVhwbBGTU{+&tRVkq6YT1NOlwa1z2WzzQR2sJ(N{cu#D{OD6 zp@BX2-!|&M?gSdsy=)I2&2$6T49wXroIAC9?qr9S8*++)T{2Qu5%omt#wM-YwyMXL zs!uLfxJ(+|sLbAWbd|9{sGZ=-Tg0~$9g-U`>%dcLz6PTwUVGSvw^=ge`HJy-*S)$|u|4J~}Z-9w)c?Yz}&tM>c3 zRUO;p&RKVE7#L`#TnM1H(YhMg!KJ*rxO3zPnxt0md#fdgXU+Z~KZ>cjR*Px^D$<|U z_Wc2-mLP|=QcAP93S<_p`f64KMy?NSfg$ex%Sox>9A_ub0(-@nx1|A_3wuv_t7TZ6 zdU#JmU|M7wIz)O;DH^^GX4fiI9#d--=`c%)GFBfj7h)%0R6a2i_;~NM*=7Tq!P9H( zR_yoUx+41hgdVwmpH~cug8NlC%2;E-@?^p1qTa5#8h`04CN)b0H8w5F5!@uS1SeQd zU{G)4m>#wh5nnel%f{f9I1rek9XP>*$C>iDQ&BI5xVw1zZ^XWRWch|2|-I+^T`bl8F z%+X&RqCbIZ3)UTk=U+2%QF_|ll)){zTAh)zJ61JSeqH-I+0Wy+vh?Bm{bAZ-2poxum z6WdQT=1KCr#c;zU2kTGfX~b7t{RgKX1$yb9ax(Wf;92^(Z!1$9cy~>X^C1gOjoH}$ zJq4Hx;7wQ$ZRi6Da-mobCufxJNIJ3X#EHungJ`v^ZAbez@p{?d>#f* z-J^g~(FO^^Q2W&WU@*@@z}fEBf~6Stc1L)_1I)y#KX@|c9sU=p1$FcmictcW?Y9TF z=48S@ZoNZo-4`*OARYG$`2k-8*v862^q4CL2XMWn;q2bWc>^y5R@s8Xy1K6G@lW@@;zI7spz zbo3g2Y3$?;RBngt1*~E}6HPzXy*??~hoRK1usEYY_lhpDR^}ijNFhA*!?qZNh-o7OywQ zD~)F2dXdtabhn@WmZ!~EJ}}mL@0gO|8`gfry4#Aaz`=2^GAR>#nfMxbg)t__aqO!M z%QYT9()ogtWZoN^W0ajOVzzf$BYP7Rs)6WIy9kIr02zjE97UqtXVaxzE0*Mw1ZHWy z_lAd=o(?x2X%Lo=dZu_!Z4+2~U)sxU-8u8-cWW9U^j^8w;3;fB?S?*XMPS(R{Fcim zt2!)uIh^h!g=^bYjy0>s)(YDkwNPaU;6Yu4EX;U9FUE7_n%E62Y&DqYT3eh1x(qSd z>#4l`%$78hfpgjvt=5dgn0vkDx7_!<`;jwsT2$&Zse@jeTt`KWRM@YQ0lgA5c-U{% zO{q5Y{Suf}r(4Ntc>ajiB=;rT;rn_Z%VqV?o%94hV&e9oO|GFN{X z%MN{su==qQKg(Gnx1Np8Eet20D=%+##4q`J)cKs3$4T>g$DMn(@_=cE+JbPrzZ{Tk zVKZKg@lKXwO$V(zK#s8Cex8Tq#*`WFgDWchUlApnA}yqD3TGtg?1?{d4W&J_N3!<3 zX`NMYC+P7GiWZlZCI*-pAIUtmIzZS$=&C#yXqaIK)ysIvG?1lxrrBQY)GZszn52?q z1K<2=!!Dnn7q&c+;6sN6?GdKcm)s=l8! za9*8LxKg#Ndb_KFT?px=?GQYU=R+DWsguG!tViXkFx!s-?*pvzHoo{W+(Rk0orqx_ zua{38ZuWf?cx0%@Khul5Lvwqxi zt~N6``KI2fD^15r(XROKUct(?(r;gEHX_jO_OH^N%KA|CR&?goe$saEC0oFk0H{}` zK1f(WR6suAJewnX@RL5}3WKX32fIF0OblsKdE0BdcBzkbRQ+1`HU2bQwGn2N;3YxW zep=?7@o=weFmrBTF1$wjX1Q3dLGRdx1Kp~3R@vy*Qm68}s0yczHk^1N+Wi?|b7S}q7-pnxz zm;s{WaJYSGprge)r-`K^nR#x%DaM7GJ*yndB{7Z)IBNr2lw+CIkcH4{;Dq|*Td4+V z1KN>S-6FT-`QP6>x5UIkR_D$p+!cGZsa69aowsjKgbFCP;A8O2Ao_&AFEfk1o{6jW zHW)SEQn6`_9Pn)E6LGv%TeZ21|ESH+4W(y#x5`7P8zD3HT6g;D@_VPcGswOKEsOq3 zLE9D2eLi8mOIYSVIf73CH?slV4RwaA3}D8?bP*(^(^e|bd34CVVsofYozLah5hw25 z6(YFDHr`P-tS+94krCi=9s10Iy%aw+Dt>zZa4>GQPFdWY-HI#BcF3v`L5D^9Nu5@l z(_ki5NNYT8lePTw0yoGpeV*5w+>3AU+>5ddVm#|!Cz*`>{0HmiO7aR|MlyI!K?_(ILPv!rAPV9wp`2VwIGPAe(J4P=^2VQyL03!v8J`6{=XqC{850= z0MaR8p8y|F8AS1u#BBGUbNqqOJ;Q+I32AK zeo1+c+}gM0Zs}f3t6DnKlQI#-ph=F(*XQ=*g-6OxCU~oTo9Jt}HLeoTvHEj){7$** z=TB7=DxuEVDm)Nts_barRsore7f+ReM;?ua;F4(}IHosc!i002tIIOEA(g^ z5WzU|`edGB@j}2Z?0fBTEEwY&QYT)34|!8>kPKMZFs`l__?TE=&B6BBO^;amzfon2 zp9VBISveZnolWio)F+%Bs#DfBFeG-X;e&L zVO?rc_LC3VQ91oV-rrva#6;^x96J#fDzN5zc_g}S3$GaW!=V??yNLi$sSGC*uJR`~6Uj-viCIswC)Kc7QF@s-ODUkFq| zCC~Aw6>5RH7A(0)t}f%g%bw1hfzNtlV|ckP3*m3&PnCCAhxI2WUKjEgpw-0 zBFVII-AC|9wLBLf;m{oPD}4>_905_AdjsELvisbebUSwf@?-K2BT-Rd!*S#2!&%mW<<(h?QHm}#hPU&NI2R%dG-8O+UjuN z!>c&?18OHqRhQ2W7cGk20t>Q$0Rk_o+VhjhR8teEi z#+2?`lrMa{>6^&vcaHVJUeg_q-@Hk-E>9f@lDEiHY*Z<=J$uPwA@#pzIJg%W#K5f< zx6BwY8lfAAuRpW7W&w_L7SKwLeh_{;p*e5Q9;asG8zKRT#AhcIZ^YWQTzm>~rfB!E zhz^-unNUMfFx|+-d?w&N5f49U7`U&z$!+Jcp8zc0h%xesUt`@B>+5Nvv9RUA654W- zSREf)2Fz6SaUjQ{sF&ahpw#iL`v>1o>s|Aj_nUp0AD2BRPg@Rqngwg47;{8LZ`u_9nl{cwzobl|h0SMAW|sX#Hkv-A}e zs$D;fn%Uu{>1r=jbgF-gxy_0EXzJSA;J|rDQvm^Qj65%lHsaW}(|xKPS=PPvgV9usPc*BT5sB1HA|mU2D57Pp_&f-3^6U%>1-N!6xU z=FeLXFH8$MAcX3LYnwWZ&pZ{jR;!(IQH?*^bdeD*EPH~oMP(ZB4EY3x7bT`b44LQH z1U|wV*3%TrgM#GW^PwH3`8T4tq@JadP+}I zgY}kI4DB%aPVPFIL=lJl)xJtoIK`(OqtL2Tx_U=#CnsW=`z~R+DCr}fd5nr^=ogVR zS;O@}adnxDOno6ek}l6|&&j6NiG6bboqBoFwSHfzdFAljrq+tBi`z_vN{|r%%7q7z zS!O~%b;5QqMtT5WGb!5br5iYR!Z9k3dm`TP$CSj*=9vhB+Tky!3A)Q1>J5|)&`{D> zJo7lAM}bY_z451Z?__J8k~`2rlv~b+u-pUfF81C;(_w+!fv@rF?`lfjjJ0q$JQ^J; zcL%-1)j`xbUZf^G({ZwANprth?FZaIX9FS9d09aR(fV3Wcckf#HfOqdVvb7esoFBJ z32P``-L<6JXywygrc(&u1HyNC889P}u26&p0J*d?LT{{D42kx2dqi|*_PsPBPL5s5 zf26W;wD)YpIqR3TqXCN|dFT+>`m)7z+mEXO6TTe%J}Llw?u3Yo>NmahwU%aU-yUC2 z_B|kxn0`itSW+XFu|Z^cPMV1Z*lqZbvF*FZ{6C|bBAAD z&ON!Jg1A@pe#|R1vMObZ`}D{C!CH7SooODtkyHgUFRD*?bGF+(En-^5$!`I8%4p@C`;)I%_o}$T9OTD zgfH4aV{h`HEckYMu}4G1Q7{J#mQ}14OB)rZ5&B(YG9vq%Z(QbWtGE!Q_HtS~rE+4* z36x8Tqfa%EHbAr@P1k;4siP7*SySxuT5P4@%Xgd46_rGEVYuPDuyQTGChY%QeiYz| zz*TqfN~wc26s3waU+Cs^*OzTX%dGDF`J+Z32!89ymy#Z!vYdYWd$3w=O9d4%aFqqR z&aSlYGfC+S!wpF|`r^!j4|i7oTxkCxI4AxG zS?HId^6v}4S$L+OcGV=ZL3?7GKQqIL36qJA1HoHbCEi%fJk1>_E|RVirZaCO>qwM^3Tv(1j&ujeshe92v z11_aEU#JGfZwT6)8x74Tpeo+TI#AUD4^VmN3sBGX8LssPtA0PoTmb)R9a!#Fni38O z1f|Q9fy)TIh;&2aYVP|g8j~FUD0Cob*vU-!AuP0QU+wc%=2!B>NO*`` zjPtSTNnlH}2wVkT{~N(dQ!HXe;Fx(TD=Ay6&3O-$QUP?KHVJpbCUpYkc={z>?(3C6-e?`sp$f;nAHo;p^TM#Y;qKeT%h; z>D!HwKApYd#Is4~I(#~f>17q>j|20)5|z$-=B9r)_3lDRhEIGXvqoBid*ijhkul$M3Rj27NiHJ-Wb%dW#NxR*V^#Nik%xcR+SAe4-|g949B zog;muvvAcTcq)Q|0anzK1ONC&Z7ciBE0O=~!oNOqdx0Aj;J%3~n}W7~i~?<6>cvV! zC4jwb1gt0YG9T*Rm;g`}coRbcd8VoxI~9(>!d-4)yItE2edGf$1Camkf=^Z%!Q*!= zK(P{l!}TG!t^azr|Li>n;J|sL+n=d`O2{#>HYHQ+(XT4xn!-rV6RrKqjWlgz>{IG^ zD=m!DO|3V?gLL3dg~r%AMTV*BH;Xuk>hVyr?0cWAX$O?`6r$G9d+4aG$zoCC*)n*f z(3bjTGvI%@eCV4WJ%kUjHL}n&{i_hKdQr;#>&H9}#2V0D-QOk0eC6W7e#wf=L8W8X zj{?mslQp$xci2ShJ{_uCnSBtc-y`smkSG>hdoXM_ zb3;V$T-C5HDC9pA?Ee#0j|_M1~7Zo|i2*6!{^#Q}#Dwv6$oDHBh&F6Lio6klEh zDq|xiz969+$(vh)dJ+I%4VB^s_lRE&E$TOo8Qw_Q6#$#h9+t8ioy< z%GnDFpfhucyIB*o$ZzGHKfCKw$_3f?WFN;R9X+yp3!EGL>N#Ac3Ns$yUX;7p^C+|n zl6wc*bMJj6sML62g)%;Zn1u-eK7p=q=+g9f8WE{z5Ww0NY zA(R~Cbwg6m`2;t~+jqJUA6|$?klf~+6O1!wj+hwPc70Xny+?T$%0?z?$M@ZGBI`5{5m{Tn}obM_>}3yf1p{0VB?LBx-pz)OMMU}XCsTd-|5 zM*V0(yOzH~kQ%e}mX>$*X!@AIa)anSNbQEaoTCuwFCn zZKl1QtDW*vm6v(~+(F>=%W-r+$vurR!@9p^^tv8=>lND2+lMh%h{mS;TKuho}X zc|Y}RtCFe9bYZ0E`|Zn&Tm;j=j6z^puT;IRxm%)6knIP|RFauhU535wGwx5oco{hz zcYg9%EB8=BzL!|9*MYOUlgGesQz4;_(g@%2{DFMIBj)~|6IHA z`LeI~WeNj7)YVlPg+IHtCgq_dE-gewf#7nQwyoEXkvu-a@!1O;tC{zJh$R!o`d^%6U}o;nm+ z4Ysvn>dC!+s6-~KmjTz~dL)kBs$B@UQN*ER1Ji1f>J;kb-NVeLE*J=i3w%55zPeE% zkKFPA*lveC^u2ZGDO9{aSnOVBw=@q;0RXESX=f@GMRXG;j;IW zF{?5?I~Vf!mhAOKnqn*J{UoL?`7N|?&Y>NA2<%n)LPOL^Y5h1+kA(~J#rJO~IWJ{~ ze)x_@LV43^*|&)k*n3~kwJ8eD$$dY!7vxG2E~)lv=ePhz3TYak*1x8X)1tuED(x)R zTr5FfXI+A2sf21vX5;pr9|cZUYqxKl)7iwiD=<$u!`Vvu(lgAJYn`hqp%saSs`E1R z2umbhH_LBGTirG>Q}A?up&45#^KGgr@iupC+LoR!&I7ads_o-1o`u z0GVW8xY|VM>$!DR{@uJ}Rb}D8$0Ter)!MWcGN=zJLWqx}r$|;oE zOsR8{M_aS!RR9E_n#z44F2bAEz=iqoo{r|ao|6eV4m+?~)x2npAVuuL1Yx7;KnTw8 z$N!5=$-4@^PFwGlHq3bHy!GYoDSNK*n}ERwh8^O#V;T#g)Zv}zvT$U#|1;7jnj$gy z)yd}l%n5QNE7rmCbpq~(CXLmPZ;APxkIN$0IF3LN9Ht2XBxGyFGw__{gySP=#WZf- zH6|9V1E8brJarfL<%vIN^m~J!_KsW(D%GtatYWn@=1ZO|ax+F5mT7hp z^t6^J!0e0|FAwr%c>7hQ-Yt9b+f+~58>9Khx0=qqjIy^|0d;SVKdKkz;xjm9hOPlL z{}o`j$LGt{o(GZ#$Td9e>x9Q2iDw?qTYhXWNFjA!xVL7*#sNV}S}p`zv`>+_(l9Ea z!Sq7K?+;>b_Gnj+5D)lND4c2#?j0?$?yY;iTjgEcR|lEIrpoWD8t$pwS@JsWlEyTS zZ3%|3ZKlhA^$fO0fq`cB_Z{rx-g@I$eZ)0(hd@nGlH8$!eKNDPQ-+U*PR}QER|6rE zLj+phi{${SWy%4;38ZXcAW(!QlNJ>c9dy$dqDh(+OSG17)99*(r-O6E*;u-n=EK&V zX(`KB9XNTsK>yBDoIzU%NzDo|wLNV3+L7&6;TVi;F(ziRhx6#;TsNgsl0K`n)&ze9 z3?GQRRaa59z%=$FWUqQXVfk2U9`)JChvyCrI-XL_U*_2h#pQlsgo~r$8Qb!E70N?& z$}OYuOnVsFNUp*o8qLwDB4Wt)>-*C(+zq12xz3*OmObNg>ujXVv{hcOUmt6K zf7ckk$&9;d7^vyjQQ5J@%`fM%B3vw}nsz4(AYKRBjNJy5q>pfRuueYoa}lt#dk_V; zIq6attealD236@Vd;>%NgLjv-$qT?RAJgmo2B~AU$~uT!2I4bUk8`_{ddm8Ocf7{P z0bB>r8XiWWtL@9K?^4bLR&@tVRX7(Ygu<738N@RTtTOL+hBxH{st1~t{ z8ujRgYSRi0g6^7t&2ks34QtMwrE<@KE7KOsRRFG4Bw7G;Sc_kwe{+^1HY)Am@Ef~A zv7)RnVpPukd(^pD9lT5SCRbq##Z`)(H87KaF$+TxNx=B8iTW|*mcEnNu&I`OM7%Jk}BQ6iV%iWM`PMiyGv1V*+ECD zBvA!)+MPtaVp88F22Fc=XWFCN2lq>K5XX zPw;sxVwBwgV~A=l{%88hA|D344G)*5+NPUp9b2Ct5ulb9O4C)oWa5<$Ml`VqhuC77 zc=9r&aF882fR!bRea@NjxXjTqIKC{|NN;KOHIHQ}M^)v{e?PEmwAall#klUYzznXA zj2P`@tFuZggUuLCqz|ULpDU#Lc4-3NOtx&DY0{N{;kvC#vf-z_lc?Z3j1=I8hRB)bk^{D98ydiPt%(S$R+RhYn*ZThH z<_2naFQZ|+AK087;_5#*Ddr{bHetdtS{STNmw8n*eWtsgR;+5dAyeVS?Z@wuB?b2B ztZ>;O_FD*i$`n(`q+cf~cwGFUk>Oz~)vDK(Y~`rEMai`F-S)`jZxhv;8mm_~ypvhp zj!bj>;i~Ug33O@T^f6|06$PRb?ShRCl)@`cjpDl<_7yD8^%1&c>ATw4XZ_l)cS%m$ zW-wiN2E85=O=o)4AbP!{$;zfI(V90ty)_*d>Ihqk=G9&q7>x0uQ{LjLE)OkKM3pK; z!Calh`M}*|_A%ChTn6S=x?BO1UQd<|OwpRLTJ5>uo~{=Yzul$nc8-Ky*~fyFwVQX` z74^;E4_!G)V+IX3V3s-U4ITh=tD4sJFfyg!CtCNL^7Zp^r%q6gMULPzfJazZA=~K; zI#<@J?iS--j=naiR*?R>Djl5nr}xGCWJ!^vSm3|>{z6Q zLGB)8xJ7ZjSSlylE)xWiD~)-@w_YRMw<{IHdyb0e=oW6)^vwDA9+Zj+pe|gMfk{DN z2>W2hH#j_f123UMnI33cwE*AJ^LDd#bX=EJr?<-1!XWdRp49!M7K^1CFDAa4zl++S z0k%WBab*D7GGkIvu_)#?ZUD>DF7;!_z+UgnktFM&g{0C;GNo~ZRlC#$)%p@wNWDr{ z!Nt&|Kt`OU%Ll%$)9K-A@$QeGE4Yz#vO_;=GB4})Wk1<+^Yx=ThHpi4by18HVmVO7 zA~5i^8uzzwP9R=q&iG|G>0Q#PA`m;5xJ7ljz4Pd|5$|(+OZaIMql+#-$26;<^y~z` zTS(w+;BIHqZje@v9rq|v)@dc^ZF3D?HfMOtrz2a{%_H#9600IX?R#z9hRu~B_Q(zp z>hs4;m09Pm27m>IZqE3X97eNm|HP^O*Ts83?$7-kcxSM~y^hpQs>hd5YAC(aj19>w zm3|U!6|FzlB6ZcyWwxv2#0BDe22`fabbOqijjs8<=JOWl@IZ5KC;JpH9d~}htADbd ziW#A;F!mpqSn}OU67exH@zG|S?^86SxU29aSDlI5czXCXk9P zL{n{~&@R8CkO|+`ACqBnniFHEEbX!^Up+eB?x(sfSy6Xi({J^=AYQ>A^aVlYG}!b5 zw9jK`56qV6fM-}wI)5rH78J+>al#YdYlT)_ZAR1edU!Seu{gB?r1#K#_?;%rgTPU9 z-Uxut{`O#jU#?Y}0%;};9N#2Ou>dG$fE?D+gwOJy2XI&f9Pi|bIDixn-QWJqN#& zF%AYP=RTk{M^8TWDQgQ|nLnP#g8nD>8mH@6YyMv2uk;tA%5a!&`# z7>5ph=#oVWg!=P-+Oohcgpv_^Y&{Lx)Ldz`?2Ds*-;>P2T=fZSf%~7#F2^@f&d6^w zt?Xn^>=Gs^FEWp*SCf@6M;2t6!>Mmb{kHv+69h12>5F?@^H1Ssy0gJzmF$19DD|f* z3X&<>E3dQY*fhouY$$E1|2p>M67(ZUj-WVNf|)i`<0Rf+ll<`5#N*J_mmW5-Y%@r0 zbPSI1yo@p-HmE?3a5m;q0M?C+A1y46n8+&TL*|iIUy0#qAByA3`<3ZiCpY7-eA)5| zXHWqlx@?{mqHR_`VOUe4g&go8hi+CFS|CVh!TY$d*0ruMk&CY)u4PHH>ezZhar$ zWV9^eP8n+E1d!jt3t-V)$C0`8Er>OCV#hVcS+;y)?KU9VHDxaC-6YPV5Ymd(ntx7D zHGVh_K1&YtVoxFfT?y~trRY;)zG@=}Nh;1x7Ou=mhplE{Q*mE7{kP})D>*vP->aoA zSrhl-kowv!yM!oAdzv7L4qPl86-3(D(X6bHnO>@F;LmPjCB}!%t-{LEpHuekn_GUz zfKk3A*Q8$b*pdCD47f@Y>?ZlT1DWIOMyPCSUN%=EGf;c5Bg{qhnc_AL4^!P2Q`0I3 z!tYD0Cg0nmYqmb4l`Snw;;!J%zOu%0=Zb;^<|#k#TPJI z!@b_hXBFLcRwSlyjw1o=36?E))g*%uX}o(7b0f8RV#lKq9Vdh|w<}_s*JHc8Wq0!) zo$NcIowUVHMMEj!a_y}047oT7u3P3_N_j zildnt{jGpx_j+wZ4NxzsA}BqHR+2m(lf`vm1yskl4ET56UQ@Bg;=x||JPL8k%tUM7 zMCtCKAeyWC#fv9*Y_D8PLzjy&2@~@V(fW!t_@1yjnizLC;~Gugz9zFL@chya?kMft zn{8Wrz1MWDlY_W@_JKo3MQ5t^llEp+(-F-}0KwF~<)vQ@D2c=^?8j%|U*x5*vdnn* zxH}1)-JYhH_KMAB!?0&x;CVw!G20IWb%8`&;QB7C=kuQ*MRu%Je)ESKXwmPJT)8li z76&P@4#}Zl#}U4J)LyT-XD1^};=YMiC4Io#L}I7?iohT_;%li2`(qxDP6y=mVY)zB zrx<6E>Quu8dAZEO0k_D@**Ha25qcec`D}zcA;;(JyW;jZ?}9`#p`5rlP4#cVk3;E? zY?uVD3=Ng!B9_2hg;>wI`##Moxd3?c+R%Q2Na%MNYSwG4w(u7(2zvkKv01E-Oi=g< zEr{5g1#TuyyFf-Z_@T7AE!LIRY_klIQ=O9r0TtXc!OP(>QK4Y1*_nO z1eSUwUYJD3uEH_ODau6@NhG_U0P?QUTvdm~;NcVX2_6Qi`0g3sHN_$dal@<8>LV+D zoBu60xb6vJg^KrcBsaDeIZocd6&prOm|B7e>OP^rd+Eq`@@@F|++4wL6zFq-EvTt>Am0Uaqs1l=Px8d$|<+cvGncdI04>M=F<24L=Hryc> z8NR)^Cxn!SR^yliS{Q()Ku&Ju0=cn5#ghU+Z#Q{DZ~!a)*7o2h`K^v0qIcYHbdR{w zsNsEk<0i#@OH8i;-;YA+rdz=CB$1HD#_{4ORnz*rQ!sUys5liRgPm${>Q~X#bg|6` zc8h#VK8sbgP?<>pBPoNsV1;bToqdgVQ;IHJ)ea%Hr&>Wo6Psv-a3Lwhk1FN?n}&Ag zwkX}Z!ZY9j7UqJ9fM1ZSns5SK4QBd%P?*?*-8NV%JpATfi2Svvdnp_4h6n_ly$G!a zzf14OKEg}ps&M2;A4yUOp5cgn5$IA?BIe?r8>Ts|_Bj0*B&k`T`*z}b@|EpM8ZG~} z|MlO0rsTi9NJ@ekbK2dcGud1@E(q>7RHd~UE2r(6fCZw`u z%xTHKg;0`FS&}r_MHyS9k}O$c7L`3S(m0u!^ZI>!zt8u6zQ60b?)!Hi&vQJ-@%(ZB zV;pCV^E^MF&wGEpU+;|Uv7p?s51hc3^X3gUb6UqgY*2Z(TxhE?>;VLjEnnCXP$^aK%GBPD&aYEYF zYmKiPcUxZOWh22;Awa-KfCB;%KO`|hUyrwb5_tzB#ttrHC_J>^A9>mGs&<*znwmoO z)PaA4;C?6pkr;=u<75oJpD4#niQ#S+$c`?$xvAv}`NFfK zQPmM&J5+U03(a9z!ZvauXm{QW4N{O~{wB)OPY`@0c7r}!F$6fJi`SIbfs$w-j(a)G zeLJBxtj&m`?LCgwL+WeWkL04Tw%Z<4_Cd6l zRHol2AQA$}y!=H{%&nN_Q1kY6&nErwT97Y8;HBhz=Gl*z^=i_KG9~7|{#4_aQ^DYn zeiGA~6ppDed#H|;Zjgb^+hiqjPfhO~S~kqlO1yaBUHmyS6f;*N{}z6eIV|jCmOQ+6ut0UKy~ct2)sHS;EJ^uD`O_-`LF&L@ z#(B?xmY9#BZlL#2kEXQef&z?#O-M?mZr1Q-N5Ye>U#K+!`rhZp4V1R6S!&lADxp*7 z_S0(@p;$zK8I!WFRxVe;1+u8=yBHqZN?^E zt})ZBKy{xll<%q6KaiaCMSME5P>41)tHD=NDH*UGU~u5sd$70p`0SJs>%)Lof5@F;eqy;wK@ z@`6E^-G=d?(~}ZfXS&@FKYx@FEvy!y^@|@7E&yJ!3@8N)2Jlv0yBKd~gN|VPBlwCp zfx6Cpv@&X^cb??cg{;Vl^!h*rRMRK(X+abL&9Q-+Dxk87In!rjSF&*8BTctPc}=z8 z6`P$B>s;9yH_#Q|OAopYtdE>D4Kbeu{wwf>#lX+bUY%aLPWaqnsDu3>nMb9-hYEe> zs?xOZaUrck`Jl5MjQFX~jx9X-5|`EcOjP`JyZ4 zFBui@99BPiFnV)@A15D~e5*5jgKYtOaXbhHzQWv7OxMV92)+E6uI+yS+B>@tb}&t2 zQxHiYY4ZJ`x`#kKiG3O#(3sQU?BX7P`$^$e3dA*bC zGrTvEcJoCbo5L#}VXO0!h^mCME^>r}V}d;xJ9)oajzRtKd%fic&c0(^M|xR#Xnyz* zP*>kpWnI815FNXS3t!Q0E5I9mbxy+B_34Iq%ANS$Dto#^vT5SSk)DPWc!DEKP~#Qp z&hgv93CylW#Gube)3V27V4tT>Zp#)+$>sQK`Onhc?8zHfabTEp&4v5`)?zJ&yWIv9 zD#+zvt>bV^KXEG4fjWGob&St9dN-_zm4L60Z;P zgF;iU*KeuZuIO3TE+2KqHtHl`VQF;e1PF2pE#(hXg-siE*xVX^!@%7(k!yex3aCel z+n*op9j;umHGF-;X5$`p2MM{2KkqB%pspK`^GiUkTNH$-LRf3?+RePG-_+Y$%w(+0 z&Lp=>LAq)$6x{TORUG}kFPr;}j@-%_H)f)+CmRe2;-HyDhneEa#3WZ*;Ut5sTKlQ) zeTy^E{>jru(M|4}?~iESd4EV?jj(DhZg3nC`Ob7eL^$+>Q4QKs%P6`@Z}@?hYp3^* zbFQv)pSra_e){#UB)!Vzol85)ePA5@=fxTYIU7bjA&5sJh>b^=$vX#iwG0#MuC_K@ ztJJse?)vWA{BwljGb_HTCHSovS(iY@~Bn`L%!EMt)j^?4ibPbOnBDNe8;wVMR2s@5Wz=>Bv z@^C_nOmmk_ef_If3GRGjhs0CgYN~g~qz*TWv6`AzK++pCu95H>Q^eKjdo84Md(pjL z{>S(^>q9O3`T(1qvWU#M;4?y8iVu^-YCS%#{SuMuTE|FJFLzO(*qIS z%)+;jl(Dq$DZ}G!uIs;){-%ltr62r4UhF*lbyxg?(3i!Y7xiHVCNzh6-Tw_QD*X#U zGo=#{+e;iPXh;)u{b%ninG{_H{+FHNF)PqWAq**E4jU+^@h6#vt9a*>|Oy9S{ zM&4V=3~hD1UeevV(Oq|K%mPZ;y9qxv** zbBYxF;jD9JkI|O=QM~>KpYR{MoDcu9EVD#a_ZbKz=3L*#|M)RwJH*)CH6)9KnrK7x z1Hh=M4^$Ex!Tb8f%q{^Vs>pi+>KIWJ^aa+Ut4814PT%u})k#WKWfp3C40cxR7xFY1 z7gF-%pV!<*z6~^PF_wv=L}8hh)TBDua6%}ZB7bEVv?A>rDE+xF_Iw(jl#P*s#Ikfv zba>qOrb|s4DyYyQQz9tAwt7-3Af5jn^gkqb{Fg4Q8Vjk7*_H9yjPsQ7b$eeK!#fewp+2t)#4-k~Mt$ z<;}g*en!{YdiE4DN@~Ny(*%hQ(4TL1QfPLIG*h1|g+V0bU~}-|w!FM~q9QEY;;PqE z6`~~L?PHZ>FT8>JKK`tm*4@+xetXv#vKEd@5f()B?r>G&rSIE?MC za;)l-XIGq#I<-2;+pRaIWG+}LQ*%wd8{5;{OfDq;!WsPiW3&=Gu}X`S;TSf7iEH(i z>0kL^!D>sumky1LX_mI`K6kWSv-Z@7+OmXAALD?jAUU>~uwT7#p$J z;crzRB5hxLUrkOk{Jw+6*Lc+YB)OdeC&{vX0sD{!BMVvM1ZcOWS3v9#3=EV20Z38A z3qsHr1Oua6hahj1|Kw)P#EKM!qL&)LFPt{G_kfouAD)iGHb_|Jd(SV87i+1utRHQpaHS@2+$PNCx^2EiTkDQT$rG;64LXSd z(4X%I48t?6aUFPTJ6G0&263fNGYa3(=A)SKu(n%Eon^ldrMmLzoa(ON?v{n}_siZr zWC4l2ouQWFv>yDYZ+}be1Y^_hg zjU_j10BZCk90ivNCz81o!ioLpk8B>e@7FNK_)aJmDpaFGONwG2-nl+W>0B9e4aXOc$6H;erPzY zn>z%&?JU(2zV3{eE6o2ICdmV4H_{lotd)|8W7-A34&0%`%U~9@)Z7Zc(^98bUw7I= z{8F9P)y!Za=qu?MQdF|Agsju!-7ey#V`{VG*McAMFGz&iT)KY9EQF2^#6dc_;(bg7K@6AW|gAhttnhZHO>K~ zXE>ZA+X5xXpXQpdyl4E@<&597+DGoTwRhehJYBtKya-b!{cE1Pk%Nf*q60dD_E~R6 zN|cGZe|h?;L&1-yb8+`pb{4F6^S%D0R-oK4Ld;w}A+=rwBxqoRUYbJ^)}t!{T8s6; zMb+75x5p7tqoFBp19p4(vm@1BU2I)*)N*3fR1I~kfKHUrQ=8OD0*VPi0iZjTdBSC9 zh|;AOmBuGuJb65$=Zvi)Y<{MB;Yr$_6GKvdmKS_8zLXc;`-ag6eu*+r%+FSen$eOS z94Tb*P7B>P!BryB(@CbJbp5bz@;-)9t?FLO1xq#ag|@kcuUq+eKfimK=z*^`V5BJS zxTL!Fw>E=1j3w@No|O}XwPPxmJNZiBax%4)Pn|jQ?RNaxbDIN(c34HBFeH#5P8nQc z_wX`|w3!%SOExy_55h5GBE7l(zHZE4PH8g8K<_+LM)vidgYK7XBV#hhH?>)8BKL!# z79{S5(;&5FS)!v%xCy^yZQ~vS?zWcYPOb~UTSx`Vta#_OrnO5Qdz&G0l&V%eA(HMpwAmxo?x?V_x|_d>K$K_4 zJJd%YETPj*px+iC<-MN~za$l1ks$%y=fSZw(q*z<&^@DTi1r74^z{8EK3p4>+j}`? zi?ck1>G;qaqCEz*sH7o0`_yM=&Jim( z5EFvZ;AZ!^3gD+S@uQ(^Gc}rs>G5sY+~J<>5!RsS`L5@kve}5@(ze_0RJ}Hp?I4WA zi3#p_J9-7|+iL0{t3jKWPS74lgJYw(Q@tPSNli|FXw!P*t90d37i zA4BGrwsXL-9V{q>rrKS|BmV@FBeoE2Dh1wBNqX5e*W|~NYB9tgVGfKd{<>0KsJ=#N zuidAa5697Ua`%o$qP*`uoA{u+9D@5A$lZ8^jb?(61hx%JznLU|xWwam+t%LSg0Yq+ z3D71J)31*09}_K9B;Uw=zN0w6O5xyIOGW;3c_wUs_?9F7?fV>pC`=7N(ILwo|av#7+tIqazw&xWa;ferYWX2?l<~fm+)fu3m zqcdP2csR4hOd(twdpLr!2cjjcmdPp7P!lLMUg2QGhDNAogM{vpX+&StQ%mI~aaCb!`YIe-jEkjFM7#o4bfO757i1n34mL`B@Kind?A87q z*Y-HZ0RkjT_0K}4|H|m&^bkOfVu2fKXCrW=8>1_MB(_MA4N9>tbJ1IOh&+F_P-gn) zjDmvKlQHRs@2F||if+1#85{YSDcmEwIlwjU76KNEncx2pg3V|*HUQo{Mi&9gXZd`U zH}h83oGduZIlN3@$3W|m4IQUUxXN@*VI0u+e6cv`k$$qa?9R1QH>)khcVg?e_RhIx zFlX3Qcs~nID{XIuB)GOrnPS=jWgXqg-yi&6zP!5TRIp=nGfgrh9WS03eh{-8coTau zFXwsdLqRE4)Y=2EglP?6fgFU7N%69QD5PURcLU8uw7tb-1C!dKv)*Z{&O1+43#@R( zi?d;8Gu12h%3O53AE%yXeJiH1Yj}W;n=@7#C+NW$G)yeNP5Ur-A;p0?|0DR^-18A; zL%Bn3`1{}hr+@=&L^Otm3|VO8!Om^`FrM7k1vtHt(?Y=2y69TUrI9}v@{R+;XoCH| zD*zzow@gz%iK39_TFc?!Y8U1EmIgE^hbn`F?lB*&6(aeE5P~)VCE!dLi?oLL^0wFJ zq2I|PBNW;l%t8Vhu%vV#K&bQm23TsikwESSe#G{|D&^}Cwwtn;Y={CUE@BXRzZC%l z$|T_5<;5f0@f_f4{pG4BKU)D2F9kQtA{+$Vi#PmNTZ>F6MOToE5bZs6*)p&d&C$@u zt@!oMtOVqtzsn*LAmF{*er2`c2(u!P0YvO6jv3g_Ej(~$6-sIG2kNsr`NJ>@p<`*8 zl!YYB&=S(|3A}6J_QT@Lb^8-tU7vs2mMLA>=_G`2e`K z1gY)1Z7;rAkp|b8Nt~8k+(B->l-*JBD$n6w$}vi1C19gff>wBl7s{sg$MzY?X1ovwns z7vP`o{efBsXu&O*qbUhSm={5q!?JbWL;jY>97pPQxnH_@$=_Z)anpKX)z=qikabUZ zQM2Ce*}mb~=XNz0d`sn8KY#W(*;0M%Jl~A#2(ysdHUKe?;lx{*{fy=ThB`%5TdMgN zPEhajbd1Fz&z`k{0V1!<1J~@5IHc&X@EwTxJ{T;tpg;tJJr|SW_CB})wT9?-nIVXi?uyaTLQ4f>{4ab#77!NRf)alG+`yTEA#zWt8uO+bG zA7~f!MS#-Fi|3Jj@yiYXnl%q}>04egoHe=WAhTnB(D0ej@YpZE% zuY2+jQrti@ivBDIJlAj5*0SeZB^X~Aq;Ee^n)!ZZ;lN0J$B(dGe(OW-yK6>8l!=8M zE8gGO{<-o`+z^0A6WKUPQ8rl*moy^k5mumYyvw})bCreLowgo8>c%|&C`R+RPm5Y1 zKL2qTRwW-CGfj}#4@|um^lN-!?S4_+P7SfSPxrHJ;D{nNh$|j(*uWk%{YV8;^qxmt z{Sw3wB@KBXG4sRxAdbj32S^O9A?Umftf%k~E)jpE&lU3z{@4u!rvW1y`rTS*VgI>{ z@2w1mgOr5=tU?SNQ?k^;J%QxBn4tpx3kr}dManD*PhIh;C9ewB zH7t-T6o@OOfbuHRs#~JM+kCnAWZQK(8pBJ-gBL*0x|4eVBSHys+L}h;pk{C@M}IFD z;R;BAdW>86pb290^-~t(07LC(@(&MWbp+Mj7{X2<*#5Fe&iu^E<-fZ;$(RgM0^$1Qv^RiI(Q(NmFej4TMqYu#FYaZv>mu5 zymWAecst6;(|f|O_b{*#2RY?T1JnkRbCktG21Nz`oAYP0Kz;{ENd9UT`f*&D7Q|K` z&_cFyx_AQiMSn37U|0TR3sAsB{Jkwu{`>1;SYRZ8M>e0bd^`ZW{l!f1CV7^)FJGW- zlt0^pJoJZQ{1xCcV5SOMZ=X zMB1y7G)wMF@Xf8*Z-1bOTF{V*FVA3TU@?%D-add4Z2$uLR;F%i0RvB7H@S2x-_R`Q z!Mv_RglvZQBiDs@cB;vzO{9pq2*!xadckN3<(#|7twh*mItn|RodLA@NTHPZb>^;~MX<#aN?CVY;&2Gm5LSVu6m$!rGK=J$Yyj|WNvFTQu?$z z_ZpunV2qYxTD1U=>2d-`or`7W?>#~%3&Q57x^IGJDMOoz#;aN>;x<7| z%(5LAX{?8xshw%}@2WE=Q75;SH|C+6|AXtU01F#xfr>X4u!ji3m~qPOn^QYqUt*>l ztch`o5WZhP`8*^&6p{D~ueR@@L9*juj*2w5-(jhk*=1eRZz2{%{Pc57q2xg6hGDt9 z>|Lx*g@cb$?|ze3xpU~93WIVNB=SlSVe(U`X&1$F+2{<7w`ajOf@oY9TSKY!v}pe8AZmhF_qm6m1y1eo8C`jW7|g?~T6 zB}8t7?V_jQGN~Z6;rQDNCnV&pTQ8hVxsOP4x3DnnP+T@9lAxCFiXYp;+VU+x-aqP@ zZ{`n=^Uv~#M(K@m8u3UgM2iLN)T6S9$X<@hFzk{&a0(7*TuwR7iY9LmKR4>#JYqKZ z^?cY~O^;$PjMxuv6b9!hzb+-}rk1vjb!E-V-kXDJRh88dyA|!bRiiAr%>mOQN(d!d z1Ny!H2CX;nQ~Ga!eJCOwFmwE?7yQ5T$@dFjdSU<{Df0#*dY{>hMRQMlcC6Cg@65rp zI^EE2D0{ruf8ny`p~JzR`SwY%0xxL!gmrmH2ZebW2XC>nDj;B36Oo`PGg=R`B|3pI zAv65ut{TkWxzA_K3+Xey>b5npSwBgGb%1o|3D7TJff_hWxuP@7Zv#uYu_DvE>&R==2#vk!AxKN{?*@7OIEb5A;cVC?RnoQVGhjPgJ2dWr!G)8Rac35IEf zqzQ3P-8wsgG#kzl$NouviIV~A=SiU@5?9eLuL#1Nb<`n(F-yPYWqlB?b?_;6lv4@112%6sW(d)E*rjNI}4XnS)42S z#;;Io&dDbH;Q!dsh~oZw9I?yu-+;lI-Um+9ewlw%Rauig{evE1D!$Fta?_&dleEw% z)DhfCumS+Wm<~V+v=WNaII||=s#AN*Fuq+Q_O-RYBxh|DztjiJ`2EHUikgA@1(?r1 zQoO-;G$2|pV5zRU^n=8hPZ297Y=Mc6mt3}5GzX%!Zy{M|rtlxB8%V{<8U&t?^yTgy^J|{`%h|w$`eA9Y5I+zh%o-E*pb^GE z9KkV|ktEw{emuph=XcPYdrf#L62nKg!Dq_GH zaDoNtHi_$}NuucZ#ZJSCw|h^Nk9ehi`2M_nG}!b)rj<_RiR7v9d*A3H?zn#3uofbo zRo36IZQ3cNnUqvYCy7$uFC5CpXRD2!^Lo~AJYUi@Ofe@=HGe|w|K4;7UY?ShWdv1UhgSIU&Ty7M8-LXy`YW$zH*>BE-=AJSIg$nmhU-EL{ialyQewL z&*#)Xq`$0uVE1rDOz;vX5)lP?k8LdYH%PI}v|?ATf_wq}1?4oB)&+bsB?>R@R?V*n z%8r@edja(%@IsqLKyEFo1Tp}8^e_J=-9VmNq5Rba1rY?E;{%@kAb`$e!O$6v6@4VN z9oL!!d4n7hdf7B)brK)Q@|Xd_bAw5K9YpK`c(4aBaCk3q!#pj3w1qqHfI#%0&U1s!(rIFIQRg_uqZuSO%dip zlN%hq&k-L%O;pUny*UTut+v`9sDo(~9Z!DFZScJRjpV``DMSPhp0%4tf@X6jF)Kb1 zujdglD!AmwdqkN%1w6_l$54pQ-{u;)c=C`9ye9-XrOi5kbhHB4+KpZidU%q*0Wf$s zSn)oXiZnXuAa~kv{Ta{}3Ns*uTUgWvvO#OQp~YxJ6!#1Hr!N3<0ES#arascajs*Vk z%q>Jt>u=K%VMbzz1lV;DOc7RtDH4)Xss+=@AjbNe%X#SGE_lxo#Kw7CmKP@pO%Zf? z+Z=x3fIn&hb<7X|hM-JUho=)wDFBHnGs<7n3_Mw|6Ck1YU7xa%GK+ZxawCO36fn<# z6UTelpgD;FVH+)bYz?a@zDjtJBo15As~J41z?6rlEU_yXs#MM8by=*wPPzaJ5@#DsLwc;3qYbKF%37(VLUBfp zI}`NTR*u8VX1cPwp2uo9=e!gsR@sdzMTJUoY`{a{D73qnYP%(Cz`>{Y=o#*7Vn@j^ zylW~uF@I&$>4Q>JJMMlN4vRGB@`ID)MunP=Ba(QWII;!#tgP7oh-I3%B9T%uSj0Xz zoL8GNn>l}7)hliLmf_p`Reo;HH{IG0$V)O&LOO_hzzT*Lou;GZOzC?$x?}hikm%|N zd0~ZrobUIXdI73lo*p}0c||SYPRt(jj!_rt+yv8#Cfm{l8|bh@nb2&RFMXs-cx1*z zTJ|%Hw@*J?W%#IH>BpLY%yZ>U?9e9MmGct(su^}{KZOqBc?_qKLyS3IR zD)O4bME0}EKtVQn?EqBcRCx11yAJ5U&4v@24BI0vH1v8W7YnTOcMCz)qz9p1UzOL2 z9aO${Hn}7l#Z!4qNx{HzZtTw>nf##`qSXz6_LqUFBCb3TCP6Qt!#EH!qHM&ZyiJLf z&DH#T6B4j~<}_^OC19oWj#3_LdH3LuhYs%FVztMx^^`uRY}iY)9e<-$_3j`2r&&cKP8t$y})!5btxW zp(caZ>bZI_#9GsC%RHW4KZpx5cj?dTJ71UKmTY!ss&rRH*kvV_?&UG3#LfP=1@VowNRrH{kFa+>5A_A^%G@sDeS69VzvQda1<$sby|C1#8 z|5=iVr!(;D5U?J{p$>#=4-$g}>WW_lnTmzCJH+|x0D`Oi4OqOqG4Dr4$rN@S*EHBI z1iw9=@hNEWLrn77(O}SV94T=K^;rO0xiqWKF(wWa8(}sgid=n`|2V&b%e3Au$g^cc z7_R8)13#9|LDd&0^f1s)z#CJ+yXTCXn zx8X|0AnO*sK(sQ7kkN&4Eo^+I2|rGB2A^+S)fTam?y~n_dhml*)*J_JLm&T9iv?aY z(@boY_}g(5%QjADY)R_;{rh)P7I%x9g?qGKUGI}OLbGFjMj~t6K7RYv=64Vix(a)X zyaoA?2ernxCIIqD4#zy`gtx%7h{g&w&S!DvqI8YS>s~qcXwOgkP4`N5@t0x|bY#2* zq5;t5Zoa;=N#2glbK=d;inM^4UX9X!sMvg;uc)^(Ra~L#PQ~te0m;hZl!hRr=r?wVL~oxOCZRe_YC}dC#|w$@U`Fw|?bxO4M z)wAjCA3v+gD7U6MN&+P+47t6_;%5iKczCLwaz78v7>h@GDD+k;C_XDtTCiN{6jre| zmIh2^884&nhB@Z|S4T%I=H$xZx^Ie!CGL{5ht`IfB*A9&#EtNIH=lhEY!lruua3Rr zGOw#j1L8F4x{SuE$p=>qhIIIkSo_ z-i2D+IE_MpO`=tim`8juP}7zM&5oe5u^-lSU@>1?2rII zuFIS&J&vr~0HXEKBMz*I*~ZH(hv>nMKy1X$!cQfIFZ89$Q)}xEMX%9QJ+HUz*S++E zn3#R`MM+USRzpCDTj)`;ZJ5 zjb@$O${O$zOU;5A6M56vsx^1(zzdoFmJ=_-3v+)Q8QjM0m_(_w{t;5|1@9kCQl`+J z8h)>8kL2oW#Bf2Ls-6{Ho8n#2x;9WaS^u2H?xZ`>O_#pfDShD?{)2ryjw%ddao4q% zm=Eu>WK*iNE=4-Bq6C1`g`Z2c1dUA{t_E@-_2OK^|NM4v=)j6EH+}2_9kb zGXxBYZ&(AaRa*NdkM@sAg%A9wtnx|P%OB^V6nyl6{ys`!-~W|e`I~&#KO0%E-T>L? z{}-LC|BZCbU%Fra?K>DC>CT&;Fg3V}t3?9%@o$G&!-9sS$4?BF3EicxdF*%i!LAx< zP8=>C%)?%4v3729UBi2bU_IA^f_XdLBVp{5<(V5*MUpNfU>C~E2X}QnADlKNHgRQO zay~Z*Hm2JsdhQiVLbu5q7uFQLlL&0OA!-eLx`uNng{=RT>O3R|o(dy~j8T~06SMW4 zV4L6)7udK#IjDK^zJd!g*xJOBwC-a+$7$?%h0o=M)!6IG{vkg|P65uny+}LAJlJ>qI27ulE+&dQfp?Epn#1hg_y5s zB%te3S|7ZvVS@Wp<00~FHmG~~Q{2h$p1`(SbKgss+PdObFfq>|{~dJ>QQD-F^>;k>937An z9*-+)ykuz>;xIEm3j!5^GrSxME$7;%n2>+8POjCbwULBT_!2C^Jh8(IvM}-f|^{u%k((Vch?03P*{NMqK{mj#CuDZZ3)lWM`C($udSNb;uowl@lRo*jE z8x`xw$JcG4u8h`QzW<-xImnkQrEsFQ2TRMrpyqt$et>ZmaByDxzP)B{X&UkbRLS;l z>w{Dlw8FtnCMRW)?cnn$f!MoPuh4l6nQ2acuGjyvviDfv=H|x{mW>+W!woONLPnC{ z%PDb~MH?>26-H>05mgF^NI!Pn&fNh+V7Y|g41aQvTdUKS=T!98`2FO?q0%RTNYBdy zM-0Q9Q91sNCK)_+psFBE3e(@W2_qlWg@~z*YacOZ#>DG-n|PzmCBF_$o$eBky4rn0 z3Gj{!8yKxOh0Xw>Vge2Jmvv?jaQLPM)8mSKjj?c{HWjwIM_Bp8iy4(<`xss*96I-Do ztFV;Tfu$C(kNUt_xrDu4<;~CTf}3=atfyyN$3)|#e`@FIYO^O#@SWdJW6j}u1cA&h zID(tl!1`wgz|aY3V^JA6zwd}mk9F<~mb`lOJ@P!^gi2XXYTV1)MZ zq)xC%t#b$7R;N|=!l^&!CiLqgQncreAKsF5?U;Zj?bX+xDE?szEep%M3S@FM)93J( z1I6~Q6vdgS261d0rL6jNDVka?m|J(fRBDnAZn%5dEqPY%ABAM#Wm1mn z>z<+M?z|mAs0s<2HFe~{UbYRK#K8c)S&XYPk3lqou+B`gHzikYHI(=kUFrWZHaVi; zy=T;Yca5gJRj^;~qeF56QXFZH3iygKB91i4-1<#vM)P^O3dOud3uHeYvf4+w>UlIm zbqr4#-O!QfHZQ-3PK1OAdpU=|dl*TNYby`nm^E?QP9IM9z7P}sN%whr>`qJGxAkU* zpM^j%sGP)fU*hIFGXi<(KwT_O6b;N4{pCe}+YEs+3z+eQG&k(;GqPr8(K8ch4+B>R z1do2t8Q5Ud-*)s)8=+&<`PZIb#kr5eOv3(+yn}x^53JJ==(GVf;f(-iWrE`wj5&-; zLxHQ65qDA)7E{Fub#5n#Hz>m+c9k_UcR<-rsiN=2=G%J>;#@t4GWZYZefG=LklPBz z{RWU{CqT2B5RHVaUje3UQyzL9xWWGs_Mp{65M(YLgwN0wbkH#FNHEH z-MrX^>~ZVSvM3xfPBnbL`vREwXq;R8!>QWcM$^Om zqj~U!%DDp_pfv?HCC_Og!T>t3jlg>dFeO$Mh*=#j5!fKCJ2cc{UeRZ=IS9+X$=pgR zJ||{nMOr^)sCR$e$99sovir%-vOxYvSG3GVQuX<%K9w^^UEr@rf zU0olG98&)3=DTU?pfV^W2m-Tv*NYGU;t0$ckO%i5GbAV!FtjAZhUF6#Trgd&cPsb) z(`NQSK-RVApIwg9O4?O-X})i~V+T|-c{iY>6@aC{>2RRyARFX?5s=G6Pw4+Gd<1Zg z0b_j`gCh1BcC~cHlrV7z;Wzn%9-t<#U?paJMayACO-ub)x%9GIz=?oJg514C#3)hNC$rqS>F!=k{Jn3KfYgExLFo)r4>H)VvGzf=)4 zv4azcD3zm$^feslMK%!>VG>>Gv{Thf4eQT4o)`5x%ziG~J)-`yE$Mq({<5F@v(4U* z>{1sUTC17EF#p*+e1Jrm-@En_h(*jgVvIL zc(0sDRTFd3ks&5`geki(f@Hgn~WyG?XmEz4$3(2cpK>ug<(T{5SwTK-&i(pSqn z#hBsso!f8^M8nHI2|1yVt$zonnPGIwvO&%?!e(Z;Rc{w&D0_clX#4;comYJu!!Ahc zaI^h+7JZ8+0t>P*phQcKmUn4y=G|x-UW(jtKKa9m^cLC7B}4DZ-FbG=YCgw3pN1ba zZ9Iu;+{m{8y7d%SWy^lG$a8)hcCl`ll5`7MCIr*g2{A~w$pkDTRLX*-99gWAJa7GF z$N1~Yx|2;|Y1{eC`N9lT7Wn2|ftW~q;pO~+nhaZ=I?{|e4ie8B`Cz%fW@n~W=O1(e zZm$;7`XHNDnGz@ueqvnii>C(Sj_(Dr z-7m5VohR!qy?L0wdt`X{=*yN3;yWzz1Wy{HPlqz9=UmbB^-AE1}!rqtR=d8CngpV;o5gQ-r|v)Yr4l-yDw5+fnklXc@Ned zliT(B(ZoX!6~Dl8Vs`Mo=lm$E&NkgTgF9i zLG4Zt_tL>6&|JVLtjKdGOvQ z&b}EOPzEmpx$+g9-Ng3OgEPuod&nkxg31TnNmp6N9`#<#xRDv(g!QldMyR-779OFs zSRIcd7fc1zDc|?K2~ntCGY&956^fGcraDjWy$P|QOKRM=3ieDbT+C6!Q!2U=vqLbkR6d=; zavA;m&RIQU9>c;$KWl1#oxi{p`-Wza``>f5fWDd_e$3quK94|6M~wD!2n2Mm(|F5D z#=gJE2Wcz#D3?hDClY39vId$rUt0{_q=~Vmz2^8c$GIi#bIQnoPBc|nz ztuFAGBGxT7Buv_LhV($U+Ou*Ls47GDR;0eY4Y3~ zFaY2PD3CXsTLORb)(RL{8VGRV)R2_bV>QZZuz~f>Fdz{(317{bT8W7Vm!+ z@Bit^8?XhW2NFMcWG--^j`zK`W$1{)6Ne%$aRO3;=^w02>k`z09KF-FZ?JwfJQ5!n zaVAD+MgFhn8o#Uu-XIe zmg;<6o5-)V04D<)gaqljFct)WHv!niqL1$viEFk5z%Q{lP+@2K1C`b~Km}xmR9L4d zo&v~?r4f}N-&P!&fTay`74k=}oU|#Vc3vA;Yni<#QQbCdm$1sfLL{yh!*ti-K12hk zzw~oxvGghbiqSu)1!%tTc5*U>mVqmqk3m#mq2tW4(vmB#+ak?!l`e~1ig_0j5+{P& zd35uVSx%bSp55=%e!k~M1OEkdSZyLof_RJ#^r_{}Nq!m{PQtK(4tj*4V-eICv|viS z4K>wML0cNgmD`hsW!rP5SYUs+(od!kS?2T=c8_O&Z~NZ&K5hwkxh;M*`1C{%l^cDS z@1H1mEUg2*Z0wteW2*xnzJU2zXz>wlHRW*wL>Kc4#6}YHgpMrtI2@vP-xrL4n|`n5 zr86hkr&)gD+4A9o`%jry<7cM1)8J8yvERk9AU!_==q*5)m63;jOMw%{+3f&XU(`b3 zZUydf0=WWsn&A}YHR>Gjg9OFFkx2;(p+l_+U2DI>xHCQe3dNZ%M`Zv*zs#Jb^tA~% zOJMzVk(Gg8BY)c;v6|>0gSJa;eXimVD;*Ij0Do1O<+>c9ZiRlS8Y2U0 z+C-lnjQcJ3Uf4<~jcl@QpV%A1e&wAhPjjN$z*CwFUjdZ@Uk zCtkqxo=Jvoq{MHqSL{=NyH)bzl&thYgbe)XHH1!whlY-Y0{= zl%r4tmfVc|1B}~wsRM6zSmgwe1x&^4&8+rTz;KCgu5*Zejb(_v!JK&c`EhOX82w^- zO|~&|vwU|zn!TL(TD?T~4G59RO%0*I)>WGBH4q@?~@%fgJ%3 zQKUIhhByq#>ylz|Xd~}XW+aZK*yB1~Et3DDIDgEgUN*Q#M^7U>|Du&(!10`CIx1ne ziny|122mH9yTQ4+L7EMdG}*7YIQd)^Cwu6TE+<{nwCbJJn7o((7R zMOOz@Ma)7?{x_+xW(KLzW_^%6^=&TSfQd4%j&r7G>#KD#4~r`^O9eZtT7!OFQ}r(2 zXnqR){?!L!Jh2_aywu(T%sf_lU&;o;S-3cqwb#1GCvygooKX_FS)#?bEuG9T%k@Z8 zHUAi|rtViS*Y%lNWe!I2fuO#JqOcE4gB|oToNr01!QUwHY>=&uAF=F5UHe!lloZuK z6D3vL8xTJ+O4UUXfIA`d?f{w(>6}Tgq{6pTXE<*TaPdEMhRoRuyyq0!Fj+PT*MgIJ zjSU&cg*EJ{i8G<0(sR`7B2~I}#BCi!N}w7owGq z3BVzR=Ykey8s$^M{H+pd$x>GGcLVJQc0cYCN$E_$r;BfK|9W`tylstps4+{HeGCp^ zWw8Te=(r?;P9faV$eLn$wV(LHkSb{x6-fHk1|_2}^Xuf=P_u;3W_1OxJ3GHd_@ z2pi2k~`J#fDzaRMfTvATvgy3d1p;ar&JHm`MO>AN!;;y?H?%nEa8#&fxG#`0@G)yl^|(- zfr(|HTh*Qg2{Fu*O_U}p8kQ>^y~q16#*pd-diESkNXFjk$@!K0Wd*2A0iZD>?6|-+ zjX1?sd&4BRtiztfCtW%FQ@7OjOwPG0w?39dl-+kZV{6O5>+JX$)35Cc_wR)feSz>F zL*$^Qb5&gE;cTzzZX|BM!i7G+AQZKKw88-aQ`5{p%YaA*UoF zAt977*(J#q9ffKtgd|B0)tF1pJdTh|SbtFk>@+TJ&F{M0#tS~g?)>qctO2hEc zwi8G@RhhphxU1_0DfYAQ#Y(#kJ5O5Gt2yc6H=jn!A8MM^=;gQSK zsItQ7fLs2{ysciB%4XdDn4jO7daF-^;7}JaDTJtqX~bY(hW^Yz6;sM-w2w_rVkn(h zgWW5a-^Drf;BEi*7v`CVTg^EwSzq!s10(>7_~ey+$#L#aOG-rnQ%XagxW^* z>KBFG^*vR8$w1BIHCB;DH|oG&FR1h+zP?%%u=I(G*h_@Dmf=I20W?cqXhSTnh3Qv3 zd2gk_(e&S5)Y|Xg60t-4uioC_raT$m2ZmZ|8RamaHCzDemdy(sx^|M= zZbPIP#|Ef1?)w&+_N)KBJ_oW(nbV6UzF1wV*+G@fb7U82rVZ#}a~yGLYaW8j3@TuT zV7fN7;uhfyXbfrZ2&Xx%1V_-(SuVc3!(iLy1s8Acx^Uy*&STfaS0Amx<$T~=h){Jv zG=VqK%UydA0=Dx_fK82GVgA*!l6L{?RXzNlgz2x`<zJwV^z@dj_Ov0mABKqsmJn~s&6y(J{h6QX_$Hd zAMWV_JW8o2{E2v~jZHQ$*SBC>vu(y}k9$q>i(*%0sqZc|EKBfGVqB)~_nyr9^|;tu zOk*?gSnn({k()XzJ9I(7w{gvxK zYn+L>pgc@4K5ns6>MCBx;vJ)uUy>~pxkUS1UQPB+lu zKvwq~<6SBIDA~<7Jgq2x3e~LnaElOO^7b;~5QR#0ic4laRh|FrLvmSD+!U?&%S2n+ zkt1~WE-zK%+kOYn9hXR7Evs=&bOavAA%v-6qfZ41GId4G0*%zB@l-)rCk8??dM{rp6v>H%aWTgB_FsW3-2mM}fn7K71ONm1cl1 zMMu_Gs%52kdM(MQmV1A&@pO=NmD0yw3yR;UtV_L?aD3()h4#e1QN8_#e(XP#aDRTS z(1&YL?<|KmlV!(8)Wbn%hc^;KF+DWVnUxnRTvU=^uRCF|MPg(fKHs_-g&g@;o8xQlv+gPzahsUB-zxaq+5iMm7ZK#PeF zR2qJ;9T>cdQ+=6kXmjt5TlH$6jxXs5sBBS_^9XHT?pd-aNn7~HVd*%%nclIT*#m@y zXz1W)7aqrsg6>nqE&L_St@@VLweD@;_6hf#JcEbsD}@CH-;{d$)uZYcoz0jPKz_5d z_dk)-{m&l9|L|uGXdG{1JzB(e@&p?7+xsES3gJ<&_mZ}@jx18@>hXXU7>n)9UEA!A zKsvP9wT^xknFlx3%IMn2?RAbcEOsVR8;MG0lF_@~TGbzV8)m#rBH2MEL@8t8lfW!* zN#d+6q!WlYsk5kxR#IA(0xr5H;#60yjS7F3jn~|U(MIu9Et$;w!5dlnI>)8QnAXHP zBt}ae{le>Vhv^Bc_L6G%&F8D+wSRRF82e?@3QkbeeUi&Y>4kG_32khjI&utcJ_-7f zy2P*u_WW^LJn~4d*2!+s`xBSES4??6oIH4;a>zBPaD#=EoMmAHlekoBY?uC#hALjgHlcxZkMQW~%7t;SqQY^vg+Vn;laN&3u0F4$wpthUT73U2vkrb_aH6{* z1vXSEgS6)ZZb=p5JSGeibvQwm_qAVKy|qZcAcTL%6+ zVoxX?PH`Xdf{ggmg_`gIW8TPN70eZO@Nq_;5#zC|D0KotTWH39*bEbPoVuz=f)#%7 zij!vOg*v>6F?zHIY|g`AXNVen2Os|9apJZ9NBvJUR3G^Dc}zHV4y3dD)c6+3lx2nCB@K0* z=Pz#v?ewp`X|l+~7+J}_qp|vsj0FGd)ocD#XH@9l89R8x6o_;8?t2TGfRgI&2 z+q55?N{&2sat32J1k8+wu0!{DVVtJYIz~qtQ*dfU9G~P6lf6B5WNUh{+|E$%?JA#= zTP{RYrQGe9Z>>M7_8ph|odD>M|ITRf6PiGgmt3^vvx8=Z_SLLVJzZLN$P$JltW*+- z=YhmP4_Sd{?LINohu5_m4Y`G_d23jx{Wxpw?)#plezP2vjhScW@0qpK#rVrQ;#HLz zP%FQLYvJ#DluF-Fb;FHnY}T|K`Ia>$ry1y+Dv7}&%x%4cRk6yvCW*=S8AWSi45&Dpl4iWX~LZ{pq|EFkhek963B z3@Cd9SNcH1?7~1k4KU%G8y27?$AI26RTFykXdH0|$u4bh}io-lP&!p-u%eUUh^ecN!QxW}k zKY4+i-SS6D_r)ZDueobHym^=}3<4>6nKq&6AW_9Cz`O9UmS&4jX;k=$c%91wmu@KD zk<+<;PNs3P=uDMfA|Vdfyf=*oTf|U3xKx`g}H;Ff)8ynHwNc;xW|;nXgl2&e6#J0CK)$2Zx#v| zAfCc5WbjVRgY2%v3sD&mHK;E+8`FD}0%pFg?=xFAesW<3^4Ps$jpU3u<&GD=9-n!d zO*ld0&ukb<|D9m#oJ>YtIw8-nn3_j1?&)1L zOsOk#>Wi)FE~T2D`ORlWq?Ic!yB99C0QH2e2_xq@BXX22Pxy8vIh-qY#cM6zjO0DO z_@d?F^W*&Ivh03>__;M-73z_nuQvivmShz?>Vm^0-lma`@|sGkRtnLZyDX$2^PWCVZDBO!sH4x zx_4eaN1ZgY={lMfAZchwcmHx|M@ebUtHtN%I9yB)u1*wM{_J>BXmwLYx!jQszzmA~ z)3q%5rg27mUQx-z)50~fd;H9^Rkzv(2QMIBG^x{xd|~UC9NLz(GPw8Z`AQp;8JRTdaqqVY+Zd4_eO6 z9+nT{An`8U-4JNRkvL0QDK@KePOMH17CgW5&0>Y_cbE8gmGu&L^!gc*L>|D}7}8?| zo0o?xD@0LF)5H7OuP$F1^5Yt=tO+=lHD|ZOv56%PI=-9NFCX#?mAGhszT>kt@d4|x z54IqfXVmLctDoXoMN+g1_hmxy{N=Z%YKv^;#4{e=KBOI1 zbYUBT1Qii>k3#&ZxS;^p7o!YRlULfSL)n3ndSlUy@N*3z%+{4RmX-kRIer6vaH zFJ)^!&sZ;`p|29s{51~KFoQq4#P7!xN2+OZW=0Z_N4C)m)a?Gct1Y3>kU2-rtHjIr zqSuznV4u)avpjzjN?~*3aOq$nWZ9U8736~OOipgxeW%`(;~zU5@B3el>na=`c8oLU zox7WU&3oIXy-g3pjH~EPEY!vbcR+>)A&=n{2DPo-Z=~SPYXgXImk2kmLO-~F*HlrUuE+Wff}QYZOP4KM|o?-}c>oZ;xN~#IVb9_okJ`lbMhD zPaIyeok`k?jkI-8WBI-vxIM6aBIMZ z_$I)s@?D7fmn`+ut97y#h6OL*->AkL}O_C;hc`Fr6xwVfrjt0-byoFUx$F7W2= zfFX8@qgCo~^=)zBtm1epS<6Nr7P5_4vI>!=&c5QvL>`UQboD*`fZ2!0-90R!H1AvZ zsKtw_l_igLS4!SEM{nwL6Xn5N>?9U1#CiCn9+MVrayVB;bOBR5t${D%EAv))?vP~} zHdXVVb@`cp@QP0V-1wOOjS+}=Dzw*dCWhpMHoi1@8#Ukbfga74?FJ3+5(poiK$Iz8;aoBr0mR zs537twC_@a8LI_)LI1=-_&@Qz%4^IG1PSS>Ecp<+RCt43D`v+*6g#a`^KbUl>PCH= zH-CA}=)z=`A90Bt5Q42qDmL>d`{4vRk&fu``y(N4j1w-xHoV(rxP5chFC#aLh*=9f zzSW&n>u-Fr+Uhlrk6_KE00@k^dq6&OoVqvbo6~TZ4y<$`7pSJYSUN zRII(T@aD&Jwo^h}+D|AJ9*4`^1JlUmAvHwRp4~m+kJNLTTwR6Al>r466Q)J+o)K3c zY{H85=C9C5HC{*D_uo-`apjZ2KE436TZy-j1#4O08eZV<^e4N)HatR@bTSdNSK4}pM zaZ3BsThNcbDx`B4`AmhLRAj~6yn$Vh91RPTJmt?Ct*|JwQ@fs3KXcR8-(=tYBTQo` zBWwYE(v%zxUHBFd#ob6D7r+0mhbfQXG9W98%Qo`3HB?nJ`%ZX`Q!B;jcI7SK9^$j8 z4{nQnUwN&`T41|JgG~r#6%&xT?}gy>W&(Sm@eOtyqC)ou5OeITd=2gl(v@BiHmXf) z5VC(Kzz2PjodVV*0*`wIx)%Puz-J{=*7KTO`FMUr@1XSK!FT+bc>y6x_8PHv#_U}b${u&Aqf zvEbsv;@U$CcC90%yB!OPPVb2%#hnsCDJ*(3qi+E zj5LAYT|kGY8RY{P`iKF)IIV+N9GVS72uO1(PWKvmIy@?Wl=yPHqg}~?AjO1B6;Eos zmg(+K4H~O>#PT;KOh&Z2$PWbbj*o>EHe|mr`FI$y-89Kb#4NIhbT1+5*G0bsTxR2IKLE^ z4nWX8>RU_;4GM(FTrZ|V$1ljNj~;U($w_O$XM%&JM|HaX1C68FVyn5Z*O!pkW3)+o zpGbJW6G>3TzDfUV4rN6c{fsH)Y=DbbAPEfj{ZJ zCsOM5?BK5X{b{ceG)juoAW}_JN7%7#zY|hjq+m2(7BZU5(nLDemqRW?PE8a=KMxP_ z9D}#H33M^kg=_uE3agA%4_BHLe<+>|`CP$xoZ7kR5<7}$uv|%6YfCV#R{%Xr|1$40 zU0(eOC$^19QWapu_{gXuC@7PKvi^*zp$qWsc%`ik*j%ayx_x08>SwpD6ZseQByypquvU`j9y$X;y`n4ob^8z|;B zfw1h5T3||5z&4Y}f&Vk#9iI60J3cos83K%wOEaJLUW%6H*q2s>6&G#n)9$(J)-{oF z;iby_6eJwjxi2ZgMlbr4p`a5_x z_fPQdcfvp8yVAgKX`Lj&IrJF>={u-x8I<{`>5@BaT8Ago;$d^Ik)pGBz1ccCgatOzI+7EL4+SVU7(*6ZY&PBSV z5`F+lt$Y7H(YF7Ju-kw6cU;%|Jv8;o(zz9?c7|PMAC} zoxV;lq~s(^UUBstl_qzSJJt*6JmPRMk7$dg^H}>z`BE_yTZK!r_}C+l=Qf};w)=BR z<*tpN6hF>!w&#a&RN@(5BSSivvEZS1?NK=f6_jOPc zrB%4AAQv^}FyghO-VcwnWY9--X7c6&t&IBaiy^MNB;C|!CEvd>L%Oi?=WNTrn@G}J z68k%JN$xX7&3HL%gIq;Ea8!(zT)Q_Ycf4~~o*AukMvd|z3*fI^!EI3`PC_a9y7Vr_q4f{ix8$4b@mq^&DA=q54!Js zHx-%tdcxyru1sWW;iiwteI8O$>F->}FOVA;nEEns8jnyzm~TE#6q$Fs3KZA9aj1#M=??5|0^PD`}IZuU6%uikj^+ui|NX4Ui8v-QVf8O9{` zx8}+9&hexn-xjcV!7ftMjkAA!Cd8kgoNHFgIxVo9|7U(RjP>Z&Z~;HbMRc30-qp8bxe<=+1ZDwbDAT2J9%TeKA5^r11mA7(iyX^OMKg}4sK&?&?ZHp*yToqKGwzfZ`LJfFMFz**OOyY&b<%XEB?&34vx{c48j zBD_#l>}GSX9_TSUi_Dqph}Ri>^@$o}N?QvcGIN*?=?U^Bv+_R)8M4) zAkHunT|tJH0j3$a2O_}Xe-yv;zcA26BUnCN5Hw96%R|2G3HiSGU!}e9BZwcQ=-cAp zv$7CgaPzPp-;>-DqM)cwRw&H5=@*)+<1g%Z+@$}){#?|ew7x?=HFNGByWhTDq~|)? z08eX`j*H$Zr|XI8r^IkB+sdkK4Rs4%dgF)CP>f<-z0BaeQQ^u+e}{dnwi7{ zTeFtm5C^hj2k_?|`GdIJB){la(KW`AVaJ`k=ISTSomTp6{q2jB_PIZtbx+x?+wU-Y z#g~gY2~`p%g^l_XBu*Njp4pfRirhfAS6gaja~Sdi=7WB>zFZC|>*{i=eWs$gPW63c^)fG+a#K}S@;2apqm)il=F!$ZTmISx1QMg{p};PWy*&FGIN|p#mrJ^H$-++Vfk$|DP)+7%DhJpd55sC$?Fs@)3ssG>s>QPf zTbp+TWE`_4BXd zx^L&m8CU(lO?mHc{}0Ike*`K2Z+zvz9Bt>0)@o95X%$VGV!`jZFt3>7th)PIil~U! zwMF)M3Z|qJb0X+Pnf`3MFl84h4hfr+&2>#8vD2UcOV^@;^;0Qcc9de;t3GK)A{@@_ zJCGH&-e98@?_rNe;pQ2??5Xx#5Ee`>S3$X8Lc;Jy%P4F%8Z6uvzVPKu^gBEBslUqW zydzJt)-E`zQgBmGD(Ccw{{8`*_uAI?#<~P5qC2a8Cv&+FRiK z4Sc?;@M-FgKbijeOl~@S%)CEc-}5|l0XPcjuDNa3fW$ExLYsvQ9eK+bd$gQ@f4luB z?t%Vi5^8|w2f;fsm)ltH>D=SwAEX*RBI_u3{={SuQzKRX%Ztgdzsg`j(_0f1r?_15 zl!g_+tY}Eipm(R`-G75+gZHw+#ha}%oUB;0F_Lb^rn<`;Ed!qFW;W`6&m`A4A;-x) zr?g3X=PD4%*Mj0ptM@YkvWUUknU<_&_!eQ`Bx)5DP`38!dxTR?-Zu!cyYp*&^l-*8 z!Vy`K06uOF#raM+lzlyV9SdAtD&KvJs}0y}Z1!<@)fv0koHI`oRxhwR-S!=>QPLL{ zBbP!2$S|=RAj4DrDaemR8zX&ldtiwlW!?b;H#27)aW-7_0CA4lh!n!K#TVG!@IO_V zt;|x;KB@G2bdyS#a5Lr=qoen+4gCJh6BK*CY7)Y}ovT~=K4jQ`dnuVfevtT0;C7B! z;uaix(9{)X4Ui@`g;kFT^|m5kUgJ+`sHqOVjn*3|)SH0l-pzX*5gG`{s~wcSV6M;MYUJV(FGL=I)3Y;=e-*0Jboil z1Y2Xed3UzuEm2CDJs!6hF(dMviId>1&oIDGD2Ud0ypftPn=TiT(?~qmG}NrEmdM*q z>$+9Tnr}cg_U%zDZYwYd*zWj*HFL%sk!%l*$O(d5nl1_GE}Zm}|k` zRnn9g`vX(X;jdVw^;d3(hwW?K><&P4j?ql?+X1~J&Zn36`J8ze^DH^nek687hSBi* za7d1>$7S+(G+Z`}w1^ zWjx7w&KL8tSXxM6glB}(9*;d;&lkt`T8Ld}Ie+d&6$lF~{LEO!V2`FvZpebY>MaE+ zx3?Z&C!IMX4b70QlHZP&d$N&4^Rn!Ea)*Wcvy}r=O_#59ZaTO->EICcrH#q3kN(MR zb3W@yQ7#MtOX-BvuqPzfKENhYMqPWQYKU|F@a4S90{k~kQzUO(ThxUTWCFfkEzD{6s ziv)9^Eo<&+!Db%4nl`h#!2i1K=fjp~l65=Z3nPyjE&dv|sV35)Ju%*9hsyBSzYCQq z|KI;M-Hf9r{Qq_^zz@2KXCo5 zhiP_zJc1uz3g#1&@YKUFpZJwCy0!>+Y3)@Is;xpq8t=p~+Mmm5u73p>-#f>QI&|fQ9Cv4g++rUlPs*J1r-OI{i*tWI_@Y53Q@cSpG zql-sDoDq?^M;ot;{4pDw>xpk|<;mfV4RMUIjzDPa&jxBDzU?H;lWFJ%XR!GbeZUBx z1ySgE=kRR&#g>t3>OnI#QB=l58Q zXM|}%;J9oy3YORFtC468tIZVLzZddiI|gRl3!kPQIvU)&3C9|)uuq#M2Rw2+7zDI- z>NCQAl{UE+ zF@1O$BmiXtc&fFzi%}_lG=#tj+=3`$_!YF6H=W7Qve7t<&*A4r=c73_YUAbZU)2uf{gClIZBlw{-NMuzKU6$l(=Zj7 z*>)N&7MfkzH7M90s2ncjC?uIl2bw8}*Mz?%4@?+OMyVPXiJeqF=%BLrv+svr?$4i> z&baY)sdzKPi$VB`$dbGRW2y5#Tyu=@tf4Bu9lM97*CuK3-0GAQ=O3#wNl$0es}=r| zyTIf1;o&F{M9I_@_yognUj`gvvB>5FJWI!8^t}=zhY;&AV2x;^A;Tm-Q!}+ zg&HS-tT)&~-t_bOr2Wl0xJWgPxk3`DKd`d~PbuXhxZ){*2Wrr(|I><#eUFGJh64fQ zZGT)0X+JawU~OXOXU0!|O^4~O(PZAQj81)a8m7|B29*X+o<(m%3}$xYaGMGFaM`UG zdccvPckLf<`z;QyzH0EoWK&<{S6}g|M?W$um4FbVF2JsLqAq}c4H!OOtWNUP1f0%q z+x@N&lxUM(+ExV7R;cI_?%MdI$M2Z`+AZCKuU<#uoxWA)hc9e2PvUuShUqaB_O=&O z_$b%K*vm`(tXEplg8s&;=WOmdg)cJ_0b5H8!GJSSI0}-ddHZfuY8999(rOiE*Dv{C zwe0pDgVs8k{ntPD?3C4u4%%s;;x<3>Mfo{K=ZWcpix|%t(|9Rd*YsnY-U6y&lMkt5 zoTysk&v6X?EzqOuY$^v)-+D|R!R5O|xz|NGa6D4U5+_&-?N0YPspCrJ4PCKU#uuo4 zGY<@scyLva?AplUouVgxYK5`Ph{B1BtUv+1_OzQWK{S@+^lr9I&J~4svZBqR^O&hW zo6!-*DM|D06Qw!uN-lZNthq4CeVm{w)k<)YiuePf|9{~tISzE}1F;)})AZzrSCKDW zJLw;nW7c4$J&-;{BDyvG7jSQ%25sg;PO>8(`Qo)hOw|2PI0U%&o2eT1LVLW9rff6sOQkNa zFrhb4E&No3W$mD4WJ%N-U84S`bv`l;E^%M>3CU3ifduSaY1m))Xgm)_*L433|Lu&vz3IpNc9H}KLz8#pzIUnLwi0ckvQiul0+^V z&Q0e!D<4*CN>-&VeyXa-w61BKf6nlZi*UCWjGQOr-WpfO<%ObT=(@Z>dbpyP*Ve0$ zW~26X>OHjNe;Xh0c@sjn=^Fa(-cftEen&!dY}BujH}>Co?I4~6g#|m3CuvF*I|&IM zU~6#ff4WivA3;|`mun5z8P&HR-V0124T?2-f#+`r2~W=Iu{GSb3R?pUr7cD)ZXLX* zY_g)MXrV-jLw6NnZYJE&G-zVZp#%f0yCW(#3yiO{L34QI-EYPfFpvnzAawbPIoj@%#{VkHM2GR&`xGpD1Ch9 zhJ$V{Pc??+Q~kfc#AN_nN;L5lk{L%yQN&qPYgDerwNqhOn`6#*jroQt^a|@MTIO^) z1uJ#uIj#`ft+`;+iz4yQ<_#`lqMZXaE8bFeJkm7U-a4*5TO#&D-;$2pOPyOxQ^&87 z6F_Z%-af%(@SGXwni?*>njHJ(o*Qc9fZD2jGA}J{KJnS@=&ChtmvTntv^tdPM1Gom zlM%2~{1tM9kwCRU*9wioTWeWz6eXHs1(NsWbA)P5!EwX3Z8^uII2p`sg~jEoZ;2AdPHJbIaF`PwwyR`Cexy#*>FV@Pi296s@1i94!1=#I zVi&O<1B-jTARh%Wh_g0J-;QY#YqeA?^M_pB4fDS{99!`@>6l-7V#@720yhzZ(pdZh zMgV?+1xKQ-QU*TAp zQVUe53`>OFsemqZtpmw?)gg!8W;M*c&0u_Fj$ft8leYo4N?NZz+%%l=`mLSQxx05J zKLuyVOg{XLAT?0@?~GLP1sZQJg069_Vep&`{asL3UYk=fKf6Ar#J>D=-W9#-%EMCY zk15AqX6Nb0@3<}d^%eK*euejz`e-;*jE<5z<#1UuzS?_A2$!x&+4O;4Na`iuu-DC4 zmr+9X@R(0XkQqx{>4fZpj78u`HE485FxXk7*%fQ~6^GA-mo@2`XSv_#@fKv?G|lu2 zFsFKXr4csPKK3u3{kB|Ld{`EE;Ru_Pb{6KdT0l>QRRnD1C{mZI*0LwQy6+5DT?!>1 z?sR`>5&DMvIrK!m=Pzn@yKKut>j}cciMSTxW7Jh7I0Jujg0kVM)(n0>bliXaU_tyc zwISnq$;fi9ez50ilW!6>3AGneEs60qQ|p5`gVDRid`U(w*NU-{!ic2p?)+Ea@@osMqEW8-M54!4;&V< z5j1T>CpAYZX#UCW#>f$uQgib?{?h53ee`@6;bn!WT`Vau8Pg z2(C?UFUZFBr4ae5%~j+n9VnsVO73C56AXOC$3qj*FkGexYz&IRJ4&uYh4(QtUSJHq zEZn)yeMRDwklEX<)!BH|FvIs?M6CLyRCa6qG0t(Bg}i+edgRcs7K!rrcK@ySPkd`7i z_JwNYu_l0G#;JYccB4hf%lKvR@s^C-;0>>m<{Lir3TUTDif;d?geWu+QR{G|zNAu( zHgzYIHRb>A-nhRYV7}-I1)$Es&sQLJZ)xj;sQek^DLPOvxZW$;08*d2KrNvDrOk0b z{PE9~#(&NG```V$^cogw22;aAgr|`9H>9!QyFUh0!UHQ{jAqiiTJd@~e76F2MUsyF zHShPwLHYknQED{%-?)^|!5SqY?WgVVu=i8NyU_7@%d^FbsginMg_fU@T?}aZR zs-kgDPTHv{w+|EjS4QOL_r8_cyx(cT%VDXo1W}Qkb2(PzK;8FrHtU))KL3 zP@MbAE9;0z3z>k_Ze={6iByfSA}d?aegmWNmlwo92=2f5hJn~l)Q!VRCCP_0OQGeP zirOkndp(w&7?PGEB98&J@Lk=588SgFr_v@5sCLEKz#BJc=ImOr%4c{Xpd)29eYZzyNr+8 z=uw*>FM^vx2Uo5sPc;hLd(vk?Y)^#$hLU%>Q6|T?s_i&mw_5V6Vy##~sX2#r!O4(#}>c<*QT}e{{b3MfFs2&>C%T z-vcLSWUN(sLg#dG@VMTzE|%am56>*{ZwlfnBvVa_AC!Lx{Jtd6OuaUtP*<)|?DNN8 z1oNSTH4V*SKSncotXeJ2jL_mVa_i9(A1=8D|FR?@&p_(9g^$*I%qBd$nlT3gQgX?s z&{LH(tu($myE(C7WS87+tlh5fLbbERMeeJZ7aPCY&rZFeF$c!~L6Iyf7-24>&VrRN zs#LAJN?FBwXZ*FO{@z_QL$oWx$L-h}zgtzyFMYC`zq?IOF2iAJVIj8`9Z^xB?$r+eA+YQ-#aUsBb+8T<)M zIa}~9&7tLp=le=+3Yl-!W~frJZx88k`KA8cZ8IrPwx7r_9*9qd@uH+BNSuvcW<5*c zgy!Mh88RUemObO#^%s&G)t&|JC%M3Kn5gJGMa~lLxmE{383I501Tvao=Y}Xp3 z#++LfbhY~2Op}#c{DrgW9Mzwh1`{FwmXoExr%2X_?pg&*%l9))Y;-9OXxN>aJhZ$f z!AoFqywmPP`bb5T#mqH3(;p?je9m1nf3?owauhlwk3y1uDdq*d2}=b34JNBkK4~Gb z%aF%$ag2ZzPr=z@{?QDYa&fm9#q{LuD>Iv}Wz@OPQ;eTQ-MuD?ba6$v)u?|v(raMU z<&P)o#UZ?mRs?OL2DYpt-XQYlsSX#z%FTtku!A21JH)t3M;A&BXLCooU>0vChnPT~ zYv#Duv#zr+|4!GQZjTPTL#gL_95p;&ChVN4xbC?IS5NOUZstD)nf_>qK>B30#DMMe zx)j{D%x&?pj6bS;iI^+=#&eP%5|0#x)r>@jkrlAOUiwU@yN4}5x)$Ue4t5h2Y+Ji1 z%2u7w<#5Dj^~d)5Er<-l`9gji2c9R93}jb?4+UW6R&vbJ2aE6>*CjV9$l;)d%}o7N%=v`dgkarFpr=4m?Raty!K}7}Vz5YzrN% ztNv8Zrmlw78Dx#7&|(>aZNtb|+a1@hZ9`o^eII5Mg{r_T5G_e%EJN7iBa<7OYoI6+ z%J>72L0$A83XSVD^Z%T^`M>==RSRzHFOcd-a|JFR0Q>6-wTC8Hr65{+__3HU=3gZG zq&P+x5&WcXv;eXo59(pxTsIh;?4}QZ0&YAMfNh14foS)12Rtz^1pD?+L#3p8Kyv98 zcJn2>R223O8S4rmx7#6bRX@M_x6O_!)01SSLJ^P*0kiD6F%8Ieml<0Izt6>ILpA&S zDl{6ePa*zJu!r%Pdhhnm@9SY#D@zarVi^(BMn zp)k3D1tqk(Bcw4!kdZ;K4HIC0HpU3SpK}%=Xc-EV@vvX~DEv!e|LtakN4^p+8nGE=A3$Q1#@_1q%sV zHW7}IoEYpVno{NT#@J2rgr+DT$Qk*77Nf>{*yi*04k)_&Rw|av`#e7&VDapp!{w@m z$Jp#Mkrh6=zZ1+sWb^;AP}oQ09h1V8PuI{uhvoZS!7HZvLucGWgt@`3o^FY?Frolh#+NA{~}VkP8kQe+Bn=i8y-x zcfwqxg9K%&w=b6yLO!piyiwp*M3#n#5`)LIO!oYN0@aDT$lm~m&hz-J#rno<>%SUQu6CGd&LX4pLkOj z9HOzJ@#*uADvb*yd=^OMQ{nM4`;gHDCn8j|vLR^89>>_!D#mEUboUMA4bWIPk_6-^ zB2V&RiBVL`%bxJUqO7zzYevr52QNv<^JurOjy_j-(9S^Ylla@RDUh&a;eT^(n zHQk5p;m0&29knvL^W~Udis9pxIo_A`v(AaD-C3LL*S5N=-XwUcjU0pUyj0FkA=O5m zibu6C&kOLhTevC4LCdMXfco{{r0&U(vS4~5>_{50Y}xmx)`mynguDXr2U-T*xR4%L{e${3<0;CSRZVp`;_`@ymdt9K%IAQSwE` z$t%B1m{{KvCekg?Mxh3#ExJD9`4o-e(K(FNZ`u%a7{yb}yzg3uvYXY@At^m7_d7vh zNc4~~z^Pn>un!`9v(F4@q+(wO0dT$HW2#R4wz`poeI_MOYxQsL84Oc$-|S3~^FFY^ zv-ND_1bxU9*IX+!0L%FpZw3$*xGD{|FC1jI4V~nr34+TrxSWyd<~SRPCpk7=xthH9 zSy>~wYgTSNi$j$z6|aNr!mVLfVGy~q@fyYWeT5#U3kDxTUc2S7$9&jXFE_ZkzP=K{ zPTX=q1kxg!4E7n8EQ6iVIb(2Fa*sLs@OEbeZ9Ct4$cCJe62)^{pJB++o%P$}G|ahF zni2MI#1tYkZ5Vv}Vs1T4K&*sQl%StZzil(^GvT!Q4sYkWCa)-{oPiz8?csVn%UU*< z*%@t+*!pyq!iDDx`^{b=HH9RYd}IMIjD>FeQR=nws3DIUfBBs-{+)=Q)faw#%lM=U zE@@Bpq%5v;0<4|X@M8Z$x0iZV#N?M6!Fh1D&zf#!&y;|hT8?+GdgnVf7_xt7mYIas zM_IzIFpA>pC1G}t4^0f6vbKJFp5G960!U+q znNI!c#$f>(y^DmdRF>({;k?zar8W;Q73X{43o}sIS$5IAbkXF4>6j0xRU%7}1|CoV zmNLwV0L~8kg3$RbTpFU;nNyUtqH-(4Ugt!uh5QCc<~wqn>(-2|)wi}btVn9Vuk@l% z>lc2}%tPnzbgrwKuOiZSg&dI@c+Vvvd@lYnv=mH`WdOC{-_G7XaCnk4!3>horGY~i zdg*8PE&O1%SKNW`-gSSX^KgCJ%J^HU2Oe+AKWWTOf7ABZ6>KZ>7gE4pA}-Sp13d5b zetwqs)m@Oyu`Bhve?(L1X7z(QMa0GxJ75;Xx;@ezDV8HfP zAsKTPJw!ay5>7SL8EJ&aHJmEUOS#!>LJxA{Qx_|e5aWCK3^ZcIYdHr7ZALMnK z&N-LQ=UCpy`*X`OXv56{w2^6E_UI(7QaOOxx^O!2B*H()Eg zCZyjRTj-2%qy#HE#?4`&8Uo!^6~O-CwO|atM8BDt5EJG$lQ3?9+>3!OnMoKmre{{i zDiZ~etznc&044s4KjPR_()G*@x8#P#D}R**KJt`Ap#J6 zL~gOavw?Rmg-N_@XRt)avvp}^@$K7Z&W)ywtf~we+`B^ktTMQ}bN7FM3Cobui$)7! zi}pGan@$N`UjV1xs_j^7o)#yLjH6jjs6#!2&WpC z0IPECB&G*Mtt1biHx_S$k>Y0q;yiYH#WwXi|*T-<{vV-15@=Tx^Mbmc5<5 zrJdc*H*Yq<#K%u0)cEtDB{&<=vX-rfDP>6+nTdw`lG(FV&(_X;Wz3~)<3n*b#C#y$ z8#a|`%&e+N6*ZZ6|hc!enpg@j{JCO|2IEcVha57gB_Mi803w0LpRPO4Lg(;;|oR!q>Q>eHnAjO=G)&g8}tkwklU^@Q^7i-wuKZ*6jp#$QZuzWxs> zuk_d`CR2{@(g(I?1+S4WZ2xZGpAW%2UF%;kJxS%BzwRPYA^qEYEf5Ez&hfmmH09^gdo7^OWZ3s4Xaf2I;3k$ zbrIf*3nVBH66PPrRVZNJz8N4jb2ao)pBu{7eLgsHzZ_(6qrk}{oe>L_! zzdpvKccRMj#Zv}5!ksuS)=Fo~6U$0wTs%bDr9R^%R4p-;X&C6p`tYQmhVD=+ysFT; zFRpr+yeZ~TSnQlcH-RhD5`G=d9yuP|} z&*{^jvNG#t_xIkNiY;C=kxG<(DMfE&p+uO@paRrGLU z1%eFR@+P9EwOF9_?y!EqYZZ)K#fv)fmJ%IUXcV zRicybv}No!^^Or&A=K<`m47(@bfN+NfbK#;)$@mWymwLyi@x{Hb^ImUWNnG{#HSG$W$+? zT_5IO#uxjW)lw?%sGP?>Mr>8AE64{q2H{YpGeT-B?S!TLrqlbqtLegcJyqfxwhx9t z+##^N!-kQL69$#z=Mo1`ZQa>mF|dJUzq&eT4y})Z&zT8=L?ltD#|k%~ZRh(Lp%<>l zQ8NY=%p0Ol<>xU@+Vc#WUWf#BD#9m#I~=r=;fUUf)Uq@*oV-f=&6I@Ef*)=La=>SK^%7e*OV{ zi<0G>dAmEmH0!%Yfy&uS!srcS2z(P~bmM|Y@LsAi(W6n^Lq!>V-tUQ2PCv>Nb|8i7 zeiBO^l*}HnHcQ(gBfs!cx8KT>0hN>D{ewRU*z$E8mwvw)2~rAKH6OKQb*-;CYiv~g z*gu$MFmhy0er}DC%(@pF#TV%D?(v{UObr)6O7(O0_oI$%;Hb4u&@|q>tPe(;sH+FY^Bug)aMxeifaH1Szc$g3{g3ezv zgS&Hr3T*U}qqMJe_}qu^fG@*c`C;;CeN;Oi!T=;6P-($^qoj!WD1SScp^!mJG0Zy50LOBv$vJQIICN_MEZ`^KBUw^A3 zSa;oqh~5KL8E>NMbFDm|R?F=+6&(h}_kZNnA8d0PEd^>-H|aGbq<3W4c41nw=4|p+ z_xtXB=Z$L3i*r`abLj*sa#jPF_CuY#(pAP8YzdkJ{3aQGP>oA%p(qOiplWq9PJYwUJNg;f=ww$BD+@`h{otXx8D2mRaV@z zSY_<8qQtF@H^mB+QiXylVwg;hDZ#`3dk(Ul8G5;?2Vx;-=qxdt=GzT$NqcoJi>6 z77GbFeTD}hI-AT$7_|GUjV&6jj^8r&w16@f4U>F*^=k3+H)*_z1qN56_>b80i;+I+ zZ*B#To;;|(3sYGy%i1R&&5C@``pCcS&MaSnwXu=AUkhye9HjRLsR2I>0#V+Q9vy&) z?`8;p^}|oNIUqrv$6At3kM-7`KR>W_*6Ej7tKtP}Vl5AoC~f=zq?Al#MzkYrd+*?G zV@9~IxPCb(*h_rAEs1kx!=!|drSWfA?_~F_zSqnyRrITil%ot7R)Q649J$IOM!+{k z1I?~l*8anZ3a#OLaYHsoF6ejn`v{PBI|(wR1c{hpTVJCjYKDugWGi@!MJA7ZuUJyX zQM2JaTNbtT+oZ&|2nCDfdA(fPZ~o<7)H_W7hwq&!WQfb zkc8l9+bGyradHUw^!o^OK}$gSrTH21L}ODagn7MM5)_CF&2#lKVe4 ztONjkN#t4NBUnDR0fBq%j)P$}_#U*5{Dt-ya4)7UzEIf_zjPrS7b2qelYkWqcgn$s z|DgdYcb6%lf(G=j@`6yPlXvuwU+Mf{qv+2&AlNeN*oLBODyGAm2%(56iG4iuK|2Aa zuPmxG+HJN9vwD}W9N8bff2#kq+v zF?Hkp@_A=$bg2u*>mNrQNRjdT$dot)bGI8v!?LWv9TGiMW?^j_X^A#Pcin;Ky@F7% zm<=%WwZ8})5UIAPi5PC79YmZMfvfsrH-RdXx`~)nKhTcZpqNs7k+l+E;f%g%!{m|{ zcE*bBifY<$tIF~1_r(bt#;VrFrETmdtU@Xj30anW5tFqD%M9R%nrnhgI@^T~4R+m% z&|s&HM-wXt&BYeSN-VwXZ|j5!h34Hb_9c~0cnGk=FAiYwzc+@RmborV6T{!6Q|GR(MDYQ zt1pjYfo#L73o_U8MxS~(NKb?&H!e?FWTRPlf7YS-ZN25oMTIhHEGT1Jv2FV-+VL(n zEjmEs@hoBa)w$x!#^$V>t>#g=`pgQ|m~~mfYv8p7NW^R)CXc zJ{qLQ(b4nN5pYA6A{^L8V$b2uC~ZVZ2&(9A67v3jJDVpcaU{81&*gS`@eSNJ->WWM z<4#`L`cOS;Yxj|im3(0`uGWk@?Sl=Qn)?&iDa&1W zGOO4FS8?TSMVdpSR^m|tx{5Lq zdJk_t2np6@iN4%8dlm(btJ1xgIiMQZL%h`lCx6F*} zPuCprQMjcvtNX!YRhLToaTxNzz$7VL6ExqYzcHLBjGboDW!+ELDJMQEP<(H5T-{9Z z2F4qhT`8Y*CaC8?*r^IaErM#w&dB-1LEanw40;}&u76)DfLtWZDp}=DRW^}8_f$=< zdao7Ruc^}N^uqB*g^$?98E0rJ(-WKN2nf+;>Z6>YK#lY>sua_d== zGrEUohiPTQ(tBRA%)iPz(nK)2OrJE1l^NoMEa=us(R-a@vrPKsy7QjP7MASnnzB_= z;2VI_Uhof+^!u4fx?;+PU<>TotoRCQHtW>^VrcN88Z93u3bO031&XeqF)-s^I%8|GPOAza9f?{GuL@SfUi!gfvy7zE~d#z z$LF~AH-;AYm0hHXclV$fWn%+7@pmnuLx$B$R(UQBYZ5dz82C!cxQ@Y!{j(fnljvIp zN49zdtn((@a0K1H9BQPbY=rFz1Aj*QpxIXu#2hB0@KufXoFL`n*mG@CzFzRp-Xxe4 z?6fXS^>#xquVc)N)KZPfuY`ioN{$a+T{_cue?nlQ5#5-L&#mKJ1SJtB^|CB5r@j>t zJ&Cc}xz>T!ygfFu_YyxC+EI@0_xx<%NK?5!r3}@x05aIOaVgXfY)Toz@#QvR1o%~T zIv29X7mvW&-hbvX1v;NVGXH5FW(R_!Pf!r#0=?lF^A%*>@`8&Uj*I%l1Ym8Q~o1X z^bl}s{}YV~o`Qvc-7e8L~?JMp16Z!U-30=ZmNzLZN%#tJn`l+(TJa z=LZ#InEl^-xR6u@kK(PQ7ZM;&8cq@mIGyHZvM9Ik&a{SA5%KVay4CdsW}j^q5!KH& zh@KF@8y?d>djH!Q&OyYCZ5mUG;5z>8?C84^L-A3##Y}PO-w&?-A~gN+KK&~FKO34Y zfWKPt->dzfJX=~H9T&R}OEr*xpFZqIhs}C@g!+ql^znlG9wVUi8>O1=Ah2rl%8v5FMmXm()eaFH?b?I0s_s>c>J{$*38HiHK$dGMH&e zGT=K)Y0$q2BQ(rs8h5`~p$`FcNTg#If{2G#(5mTZtSr|XhW9M*OTvG105D>Z_{-By z+2eC&I{CcVqL_3(Yci_HoT;o>(QQn<>?@bkliR)|YW?+((Qif88=evs-GF((_XOVn z|6z#%+%25Pzr{jt_Qz@*Y#Tq28yzTR_P|oHA^vTALFW9y^?l1kg>PN0T4yTSlw;q| zz$~J9`p}69oaEmH1T_%|3^)qf!wkSoY%8@f;amtb-wE>On3Ih`(bJ8djqv9XrRZ$Q z4sfHpz#-hn0iGIH$96-(-I|0On-X4J`{jAbQ8Uviy|n>aFSVi{drs)94mmsGVcq1L zl3uvgb7E_=mh|(_Zu_sqlnXymyVaj7a52 z_n8ZvS&KK~LSgRew!*0S(HkLZ;wrs5SJtdM=X0rAZ#lMt3dw6z3X6nEfzbt26Cw`L zJLE3O_vwwRvN^;+gCu$$1 z$3-y(L!L9r<3bh}d&*w}HXdL8=3~6oG5})3_u_Anac?5v$?PZy6zc_$g(Xm_zDlwEU4RCw42o%t^{~ZN z3%#d5(rfHPffDc(IZm9`rv@XaIW(3XFCN*uBy^|r-a~@jK}1F3No`aIK7{0UjO^iv z^@Vm++xVEhL@&`kc(k~4{Ew_`sp;L;B3GVreYNa4{RKL4!9@&Q)t61>D_H_n{3?WP z@#&Liq6GR8SJGv8dDNMi)I#Fp$q!6K*<9*fOMlMn+7!cHa-57 z*l(xfcNl*WLS^sMi)rXylSQy)NkE*|gzJb*#ibilBQ9{r&U*XIVKoBq_Ey^sIi zo+UASnx_OK(df(@bsV8GWFBDnj35vv`BvQT0SSM%hsu(7BcBVF?UJ(kc%6PJHTvkn z7j`jgj-TWT!BCbHBvhk=uSlBNi6K-R1HqvQ=_xZ%rL~5&eF4%vj~OGw_W50a5k+J@ zL6|hsxF?d0;PVk4psML@Y$B$_WD%KB1bMLq^n%uKleC@rzZJRS3Q73f3E-)A%xrw- z0FaKPNp}2HI`jGT#O1_%Mz+Lo{do^9{c@A1Sr({jOuC1#(gKNhzA$_)j#IUm?1`MYxp2@wlNiyc*xoO>6OOG!sU3^ZM`Qr7* z{)t80qwqb)M|%t!2E9Yc>ZpDHqs*O?cGFh5$%D;SuiXz-rzpT1SRvdb%I5tFd%jCz zKMsH}cr#?qK){9P=%`>3?aJbbE)_GU`x6S<-8J6Y&x-SsD2Z(q-w^GXId~tBH)9~kn%|1Hz z&TEx?P@_%tyC%{5e;4Qq{t%-4_mmY3{7^^-{gWb592tJt4e1bVH?58Kr=g4j=dS&e z@bsUBt^YfZOV99vXXQa@dI#OxmZujD1d{Yy`4G{%{d~xy8ex8-_bl(zAJztE-%C;o(Bde4kmcz3(`;K~Kc2GG zkyE!0{u(JARBOIb&d9e^^>+aiI!Cg4g*72BoG;@%V~yJBm{$<-QRC0|Mfv$qI(+{^x*JiJ+(u$s z6D|`L7@beArTOPqB>TSYj^$Nc)hk~*QL$~?-MMQbLM}C|J9EZk5M+h?e!j3@UF+k= zcO{Y#RxLeCpRY(QBVfzH^P$PapN>pNMg7MoZ6Kl`iZ%B+@G0j^^0o$OHsO-!x1q8N z2kETz=%Fu5a)Ngm)t#+TO4>~RA|zj}Y|!xux&bnIZb-^Ol zo=Si%n@IEop^bthTv0z)!J57Yb4TZ*AF3-#q)`br&8%a*`upn9 zk)n+!wKNIYRh4rrm2aN1d>$zBt4!BPe`F!g+Fy*j9d#$hl&JfsTe1B@N7ACYovn8z z)P<^F8QIb>r%oj}$S_&sqb-W~4W9;}Sey-(REPi%K7%(Cqz3~{jF>xF;f-z~%VQ4g z@R%YS?g4EiJ7*~V`wf>>%CA?glRYyqWU2x|u&5OBM!JNEbk3FFYvs}U57M(J=!R5$ z=X2opyxxg?_02^T#{bAa1o^5+DFC)(ClE#Y@X2goSQ~J)Q6oQmm$WOS^4}o10z(e_ zyaoY<;8+HCJ!Au4l`qO-Duz&sje_6EoZR*o90bc~{_AiE`-x1jWDpa)kurh+_V8`E ziye#X$83M$N1-R|4e%k+c}(U870x4ICg~hw-vR1CER;wK|@`}?We*pf6vMWA+9{UYmN6*r}j2#GM(PTb! zQ&a*rwV&grwa$j zwYrQ2(M|)ykG{2Ue0zR0=am!B{+|6xHi5}a;2B{H*xo^B7pgWJExdogZN19jI{uw@ z;b3FNi07t+A!p}*3KGqD+y9nm|4oVZN165$2~$}L8#08%Q-PKYV^5&6>g%%B$qW3p5Y z>Q7urh;Nz!9Ax}bE%47#4f$8vRVbu85Z(z-b10Y;gZo>Xi8Ly^oBb_;_F-tfLX?w- zPo4PVxH)1QG^Nh0?~@SnGOiRrzp|9L?U`jM=b8_6hqH z9Dm}f{Qh=#*gWB@Tj#!*_taFC8FbMe3O0XEU}2)!v<5E-{OO;wVFG)Q+C{-*2bffR z;fyef{9Oqa9)&ZBtTtjcfv?zDO2n4rjN&?$m_ZuX1uW%x6mp8oc5shXZbD`T})Q>}A3M#ZmoWFn>g^s$I^B9CyE#$R}z^nfZ1MW}Ejd&l)a7xw7uI}&WoJ8A2B z4{o~a#+^Rtw|hmmig~D%jtFy6JWMmLW)n&YIkuNuH*qFIFr9wS`G%o|Hbm#v#qTuZ zkIhS85x4Kye4!WOF+ml6&_^WOOzIW=)y4hdb_EcLar;R@$UvU(A@~3CfjkFN5NRkE zK}hwd8#X1B^ASe^8~TgynZXct`E~#cSbBlrAb$Ny zI26{+zj^;FXMgvWZio6EB*S z$yYIZ)-?4jYB*MGmTAuogAw6iiCm-<+JV?M1R($F5D(Sw*@UKe&rj*Ml}F>f7dU@C z_1^qU!Cs5ms!_}0m(;W@oO7=G?JTy=6*r-AgTM7b|J|67A`fmipN>nyW;ZgCBF30# z`j^|X8#l5CWW8AaHEZvL9%cn6+=_TpW#Q*Gq6bw9+sirIVliFuSyN;C_w84{BwvtJ z&7tH;pFb|(ea=q}M0_Sw`&==VQW&z-Ued@Sg;J%8EZr`L6%>1D>gpG)NVJ1&AvcF- zuLsaxNx(XYL}dHvn6d+Ox?%l5x@d01ET-6XcmxTy4cm7n7j6D0A8mns1)4SplL+EI z*(iPK%i zC!TB6uPx7TZ!o>nzN44+HfB@Tl2qn(Fh}0+?1<%~N^s4K0z~ei307C?AEF_)A$zi~ z#2u7RJ)lO6dZCwTDxDjs&{&~xHqVcn*U_FZ&q}1iTK$Z~=4Z2su{xXCIF%Ksw|cxz z(b%A2-L_JXx#bE8wJ?u1`PCocs1u`#6y@OknsHfW6(=v}s57B-+W130d5>afagMg` zjanhYofE1%MQ@RNsqCGjmx-Vr9!g~=1vqd5DdDRhEnR)G%JrSE`z#&h+=9@so9I``FN~D`SZpwWNfz)5po<2Z@xl~AfNr8WF7mAFIG4p zp*ihEZQ9Sqdp6XF8^5cYcf#tm$c;<2eHr$jiI{TT>7_JmVd24eeYcM!DL3@k2DQn0 zpdOs(-z74GR1DE-PGKc^6*!0B7>`7|JB!R@pfk6 zi!w?d6_->t!x0*B^g9wuet?wTb$Hk|iOKx-{`ku~$4IkIRES=AA-d*5ljsE8^WPTv zA9U(}_({^o{NX}hliw1vwJQ{9bN&1K{esRCCEbU2f8Svc^zvoasZ%aDkIX-EnqOUh z(Y{3*)5aMG=jWn3euB zeSyT#5s)O%=dMlc+ZsM1!o1z=a{BO@r#@e*R_pJm=r0BbwNMbRLdH+c@Y73RZ}{xKyBL*=0z#;+*st+$;jG_Mn!Sh8CCU0=ay2#I}w z)44=0oW=_6%LaE+SjNUd#qV_ayUXpZr8n|F*0~$eqyl`@9-D3zxui_kY^(wW z&?3duL6v3sZ0EQq&%3&vJSIgd99DZ9XgIGm-9Nij`-;vOcgU3RAy9fg^<=xt1_9Sx8&eS%zUJ_KN4xLiJZlMqql`Ls0k zYklB7bLp3Nj?Yec?lvr^aX{;(b{SEFxWYQ7#Nd~1v z7CXXmg^3mrGidhF!Y@pepGc;J=J+3&Ad0{JT|oDx_2ocYw|1zKGxr7*My^m9pJ3r-2jF4~H8Z4sd`HMl9bI0p9TIOf++k2xrXw(&Nh9{55;@XI2t^arS| zeMH8?KC#PFcQ2-#lMm}6&EM^0l=9oPvCd3^ndcVl6JXG0GLy{_$)c#eL!x^wWj-pl zrIqGDDq0p*CI#j!=*23X1{iREQSa|IF3A{v=Rk?_AXNro-k=hSjPKX$Iy`#F)I6+t znRLO=(TY$zZIxeV(%|uBo4nZ*;iD?EXNpro_vs*nRLo$X?4Xp)4shbwS2BW3Fu+0Fcwc?<{yQ0OFoOUvuQ{`--$K40x*?VbNIUc}8` z|8?>}h36S#?egyR&uJ(2An7@+&(#ZV;}Jobm%W4UleB0`ja^JpqeYNQFboNSOtnc6Dtb{n=?@nT=t}Gh=S|N$AH@I&)m$x3WfkJ;# zys{qlhgB-=4YY4w#CK)GxbQd5G(34?72n~{Oywp~_kU+o|KI%oUv$_0k43Qm=5wd$ z;KO&|4JAhWG^qL|xs(&<2N3$S717WD(xVT``sSJOV?(uDUP>%alGDt!*4nY5hW2>~ zSE}b7fH)u@1E9KW+a##|cW@IpqJ6Gm0D=4FQl$Mu%-9X_S*vX>rjyK%c`26+-c zbfqC5t$Tm(u-7 z72PH`eU-UMPr8e9->2yD>z>vs2EEyql{foKSxM0|#%#2DD+g@eh+eGd-d5k@C48eg z$04z6ukv0wU45m#d0*HjdEqgQZGRIkB?=?VQSHt>{rcc1c3|plCUTf2r-PC+qFpw* zK0nD|eylNeE-NLgRH^ELhO}zXg(xiIm$#OT!6d~ZLAD*Yy{GEnMmBOeL;Fgdr%d*< zp8dvULcujleOC)Iuimm>`-}S}R8z2xDO`YoQ@v4mAeXNLcCGjv35Sf#QoFlw2j_F- zY2xqzCwavoda#vp(eew@Qd=J+@JfR0C*Y%het@?5`~vdq4^Eczh;k*;b*rB(TxfLQ z(A!~u0YPo`>7Ala|C8{_z6`$owB_(&4uQ)BgXlg8>AZ>bm$hg@WrqVd<)U-~qo*@0 zO5S?whhr6y1cCAQ37rZ&;5y)D;N7JeJqdUOKM9vHSPrmN2k1z7EyorNag*U(Fm&6J zgNw0$05keWXK7H;=xZiX# zjJw#e(OZ+e2(xG}(nxc5IzO3g)Kqyf&1S{af#hzMiryK4-Gfg*3N{K6ya1yw{Y=b# zprY(3(^Mi>e|E`O!(E(E%-iHW_4U$)B>*&?DaROU32-FiQlj9N|psqGK z@qs(O@42}+J3oJ}U(PdhXNu45-Xru-Qn%wiHa(K)t{ox!K`7UeBtk-yc2UdozRrm- zODldCd*YIWM#MJpw5u`pG%{c^YI>|~!~FU#ACEhgp=hDZ8G1!66EN@#z1a#)ad zJ-yqcl3VDm`n{;QmhO79(CgFt7%%x60bKkG?TaCES=&DB4w`JL68=rouM3$z4Sq=y3RE-%r@61#pjvkuNn+GrE!@sUXv${LDs^0yHyWiCh4$dM+Vq6l} z)x2Jpb!$=Z179gY`=1y>a3(VraatOKGY5AfX!4hIYI}*MzkT_ITX_zYNTA7{pCx?7 zX>d*D>hl6I>1)(fLmFL76%-^wb?IW3OTJ$4qCR?7Ausa0V6#%(&F)zqn_rR8gC9hJ zm{eCrN7v_r0fprlIs$|-r6S1CLp%^%E6Cuf20XGq9nCY+>(?Yyog1@B9W3yAK2I~t zGW(TPn_|YC-KPR$1>iME%>)hq<$Qoh^}pbJ5a217?tooJ`ysG3Z5cu<0a5O7e1FIHYEwct%=nVP#l&FN!`#-x{noV5Jo1{{@Yh)fDj(nWvyE!K=sf2w zd4HU{{vpQ_pO|B(@0_04M+Uj1SjLz-xrH>rhjC%DPwYo+1jzf~djC&_cK#Nh{K%#t zl?TlyGRP6yB9ROkBMsMw4F8bQ3uo;U&rM(RUi$1=$C?VW%g4M6)m-Lntlm|MiNR}u zILe(ky$}b}&J>3?q7MF&V~(r=qo_a}Sq_vlVi|%7Lgnsb6wr2&Zd?2^0yPX&=sctv zQi6P=U8J`}%!0xL(4&dM2HPs&O`KXnL1PKr1lXwr77-WtfQ*?7AhuHW10+l_6O67G z8UlZNqANMF703czMC{AtorN8m<2_rN4<)L{Z`8!fNN=x>`JJuWFp=>c7lQ(yh!Q6a zlkDdzdIF$;@aW2Gi9_i=$Bw^AA_2iM>R z(g{@lY{>t?7|!|*D-T@7|F-+4pQ1A(kbFusk@*1Ta1iG~qgV#@zWW{3_FQp`b~oJ{ z58}FZe;C}lGw9n${8OFAgJnS`dH2%?!I*V9IM+9a^)Vf{wA{FBrk>>~JhG2)K5mVu z59!TlH4QZ^=jL%}m6{IU%Pxdp#)ROZ824v2v)JRZ-rfsb^6L{nZXMC;ou&HpqtdE4 zfH|Jtr^iD-iWnCP_xB@VN}+lVW2Qo99?J7XnzsO#Q_{ivM=kFwafTrpY)*dryFi}t zr%wYFw!t4nI`lj@MLP|?=mZkyU_$2L!Ec?_hJ-VpOZF$>;>!G(qjdMAGJJj9I$niX zUkY{gyaBHrj>;w6z#+~K0%|bC?TtFGT(ZpVj7Io>cQq@!BkTz;EI8!%!>PJHFQ-aDW?nS^u|<_ZC@Xoj>!ac9GhK zW5brGJKxPfxw|;pk!KkqsL#%Jz1YpwRxP?I?%LWk+VcIH&zP~+wX3t%&W(r?(^)GZ zV5K@&pxE4>jv0k>!MNR@V3VK`%Twns4Dw&NZNU*K`vlaUJAp#+NwV`x0ilX=dAcF< z>5jxayY(hot>3h~KKX>kZD`ruFuYZ8ucQ@i|6K`LcyAPly^P4lAPLHmz*Dp|P!HN@ zcps@8*yeyNQ5X1ISJ=7kga|%LwVsyAl|oHKi{-}6mCA~9cL>d6eiV?X zYWyWIM%O@?3DnF1Y>_25pVJ>;!A~)gP;QJOOAhAQ*Bj;Is(CM)zwIwd%({`0*0m%v zc>Ae00eQmbXl<(mG-mSlkWhsA(K{+0f2Xnv=CG<&Onwk#Q!i;BZP5!vwk5o2^G!!@ z&8hIYR4{wVRR_JX2>12bGOON1^HuHHQ(!Ml__vHU@s@!DFfGwUWh*k@gQO~XS#k2p zZwt~%JvJIP-e+{$jzw)bg>>JQ*u+mEG7Cw$e#4cVCDj!Uq$-*c8fxo@nk^HQ? zDuw(Y_^Y~3w&2Utuhtg~ta@{vHaLLKfp;n*)p{eY8=p3xIwQ)FC$)883ferFe#CUeB#&#FRpj{@oI)@4rGUJu-S=br zJ9E~zH^13CR^sBgwVZfM z(D&Elf5!HJiF4_*<%vMO;mac$v#t`z2J25yCnmM=FgKwerCNICD5@`n@4N{D?WOwE z=`)42{;;19-j&EtN5|n+T-EbP*G5-2R$UJJ+$Y5geAOKpcEY+!}X827dQ9=Mn&3uIBygzDt#OP;t&W1yc> z`})&PVwX-`31fU-Ggr!VzU5?`$JkW}2f7|N>E7PL&))RRRrcOIPw~-O?y~{o zbS}_BEqTYujYzh3*&L(gye<9(J>@FWXy&6q1JMM%-0_e-`EGU^FE1x%W?KXl2I*Y) zPFZzk4k4yk!;-m~=5}z4-DDmAruQeKbD23wyVAFAbEI!{8T&+0BW`OF{Xdk*^jDCWAPttU zk}wwPO#$K(gj?3n)6ovvaO$tvLw}>iAzKOTqeLv3S~bd3Tn$W?xMI*hhwS#6`2o=1 z;5~$Sf^RqsbR7Y=vF-Qc$0j1vmIuMYh{k~rTJj9|PJuuGGyf!jXyp7gx0U9fL`oll z5ek(MfOEJyLSgoD8(=c?O8{6biE}VHu@{Uk#fyKs+J2z_sj$5He&6MCT za8`sTn4Av~pnVOUZOuRp`&pz)?XWxr(UFy_>GLt)v5j!kGBv+D$~segb|sprBxqZj?D{pW(<$KA2B6p z;hjXb`{Zysr-#{o?*V4Se#V$%boA-bR=p9!UB$(58wEC4M_-J*t$z8IS5IcutPZ6R ztgN#aP2no?Go(L;SS3^uW@G#9wz@`YpG@Z27M5#hh-X=T-eReC^((0vXmUyT{4wy? zW~??miAQ`3qCLnN6)}&lXIdx6jhALp3@om@#502}-bHwxRI0fv&S)GM4(DlOfF%V# z!FwI-gU8Qn>3PcqY-wNmPVctE+1|uR^)Qe6&1VDzcj~rT%kSV#~fHFLs zL+XByNKt=zT;L2sFwu0tenX}EZIu}gPA6o@bDO+#hobk-KH%k&n;(BJR_v7g<)gp( z*V10oV;Stz$gmpEDqvFq$CZM(oaMMi(ypq#YSYuy*`ECEqiXk^qnEwTNQsC-rBb9-6{IXb{GuA ztV?(u^jebD4xp3@`ws?a^4YH#FHrknQLwRI1h3@e&MmPkL`B^L)8vjF+Dd!J*S5}W z8n3&kq2a%Jc(`xBYVhoe)0-56o<^k#?iCOa3KFsXgLz~waOhu0Js!MzG!2s5>Iy1X z>=giAHl)&|Xvk?#wh@QEk@)kPX8owGAubHImne2mhe_ZEdlSb$`H`x{e?DkR@V5Us z>LGRBMwF@SGk(~ki~W{-qzBmRx_brLxibbC*+TlW2F<{aA@6G$Fyws%FwDcT5Xo;j z2!rC={;=TxE%E)UIk!YGnXs;EwfVP^;guN>?4~Q={zKCc5Ql&H$ed;wYG3m)GQTpWrc!CL;HO2lD}MzxdmIIf{adzMo&&c1p+KSFDL zkJ!EfiO=V2Zsm8&$~C^i5aOF(Lsl&)K9X!njkB5M0JZ zI_IuL`LxEQ5Uv`E-UA4&?llozUN}=v{ONOTKgIm{>7_*G4MOI(dptqBls=!l;6!p8 zH6m9+xXZ@VB-LHaOuWv@M|W!9k*z}YVvSC&ao0!B{;jzBYeEyAL1dN?*``F8?0BeT z9V$_I5UQ;#hNwA9S;lkK#lUT49$~ld_^j}CYZQuKV|fB4{B-RC81YYZr`#EQX~AY} zCp@}OOaiv(J=A2~{B7}hx6s=Fgh+iYxJ*?tn#JjSUwP_Hf$@jWvsn=Y{agXW{EwE8 z8LHR6`x6ijZuBd9o`&s*r@JNK6nivu+}N=q8Gn*$CVeO6k%N_=-`TRU_YrX`N{=tz zv|K1?&KHd-D7%L{ksf@kKT%J74Wj6noJk*JpPqC@Z+)kc<%27Pmuh8EXhvKFtHp zOEVoi4hXJ3yoZ_L_J5vuK!545LI{Pj(@&3sz#gJ>+v52N36j|dEqV8ITMCFN?1Whu!)9SW?^95hEaOvg!`WSo8k?cZJGR@ zuz{A6eE@)s^0V*JJYi^fL6f|Uzf&&Y#U}dXHe?=h{I>oGb)m@; z|K+dSd4B0b-S6|LMMxIZxor=vvpq5O$Q#{2gncL z_4E<1>S6)1GW4diU0p}aIpnbhgm4fguuKxvXx(1(<}k!w5XxH9-r0{f zVvAsA0f7xdpu5;PU#RoPy>t9Sc17-S;_SGazU=w)HKpY*<>D6fK3mI@m0z5q73jjW z9|>hsxzwx!xDvLFtsS>3>AbUqQ(j5@TD;rh)0H?@(2`=6zwiOR6M9IjZ*Z2{UfWli}l0D<*69$@&z;zAd#lvsI}h4Jgz#`Pk-%yi>4* zRscnsO#|e4Y8eF$wdTV1y}#=r+&w83LJu3nSr@bb!5IpdgVFS+dyIA!;&YYRF4Z5_ zpdM*oOJv#M(K&qkeg7AG-x<|Z+O-{|35ZdUUZR46(ng9XAVC?L45BDqh>B7~KtKc` zmCM0%0XQIOt2BqSn8kwn^oBxk;xd7hc?d7OF6k8iDaeQUk5mSrM@ zlXLES-`C#z+SgTOzRS&@-^*)PTPNknH?c94U^qu+11aaE{NwG`)T{<~Okx&CjT70y z;>-6gGy03jpvU7M?Sw>j==-tPEsFVF*)Dv-aOz@`>Q)L#oYk#d-=h-&Ld&TGso0XaW5KqJv5KQBrXhYX=5M73hD>VqPLCLX#s| zG;7j^HWo-M9R-+Z3iK}LyMP23ODe08#FPZpqwg<5uxCj>e(&3}bvX15bhzWrH{f1? z@Q7&)+@AJaNqt^Xq}a@skgSPG|gTw(HQXo{u&^S6@lhi_*O?CAl-SYdM>&;Bl#|u1ZmN zZ$)Vhox^I!{+wfPu0;er5s!A@;@VY9;o@T3#a4h*V&XwiJBYMHrRe5(`&LKbW<5C} z5K!#s2hQ&^6%|z`%C=|DnD89TT|c)S)v4B>g0rxuPBW!I9OhJEjkB0`&sV9O@cE0nxbl)kiVYaGg4YmmKZ0WKg8+*e+R z?6CG53Ip89hgdNHiiB*+3T{~>!7RMs3s@V7CcJVRTuaT`QHvS38#gT0S3eWrK)o-z z<<&F03%9rKPI%luK_g*!z>EwV1qJanFEpzbf8Y^(DoxPWS9(=H~J*e3Rxjs1&mDSVgVLg>NKtP_Vt zR)Ys>f$JJjC2VAAxx}0Viqn@y@9 zTLw4@>(z8I%%9;ArHr9CyoIvo)2fIz?Za=21gq@LWzW29DcGw_FFJAW@)5DUA-Xkx zjI8{xH3al^%<@06hT#3fGC~1OK{s{rGxyQv+`;e!SL9^IzRNagYgV-}Z6CFR2ULyQ zDvw3@xP!)9#CI61ScCLQpwd1H{f3fyjJAGSlZ{BUlf78NUf~$ndNX?6OoY8uLP^WE zwY#862ax;FM^P(*3YrbNhkA9O$!asF;{)pBUdAMI)xnL1DP@mBYgtc|9rrIL86MY( z>HXcCdCTuiA}X?<(ESMoD+IZFP*s2mOoO$^yDMd}wu2t8q$k{rQYp2ar=C&^ct+(2A83^vz_Wl# zQ$Rm<`3h)Cf?Kmwa~^DF1AuEFm@f$6GKD#>2#lb*3g|{{zkwAAz*$7v(59oWUFbYWM`m%Ugr2_d=(#3+(0n28Qr zwPd9d4#O#vi*Zc<;GBS*27l*Pi!w9uF9s2(pTtD)L`+74&eTm(9KZwY$XO-E3E&tF z1eW$6L?JN{Dl-erdlnAmN;FEi;S4pb}+%Ov)K#I;1wDC?6 zKnAvKp`pUu0n96fRz>DR85dx_)j3!s2X6$s=bIG-n4ilGau3Q=x?JX*EM|9rs})6S zyEWqupCQgUA^e))UF88|wNYyVd9)v>VV(q=0(3c;CcOlH{2@9fPGkLZX?M+m=O5?9 z@AWkGmRJqa)q7tXaQ=G7P+L!y%AN*mB6}aPVnNh>2J~b0RDt!N02JOqo0pm0N*!XQ z5O;u7{0)T^QH4T!u$MshS{XA>Wk7gW9KfO5@KkHmA88v!plO*hh>2NvVT^L&4>(LxZ~eY4OZ7=N!*8rT$nB z`XepyTf*ikF?{^kP{SI zr4j+fz)Ei?-9hlR%KHG`K$XA#9aF1r_TxGI2C(@^BFu7v(6? z%e0+z@R1Svk_Bx|KD_LA%)$VxT9x#!4iH=2VQc0TJ7^-xr|%6Zo&^V z1$J<)OYd?%BI#qIV{P!~`19}6%FaL*t_s_j#fNhT<2EJZ+y=cAwNF>Y<9qE!M-8=V zk}G**j@g7dUStFiK7L{Yalwz!p*7vC5;b}!HBCA}SX61D??d%~=SR%JUXFL;igzS0 zho2Vv^=1A~$j=Zt54*`*jD={HDsgrZ#Z>;Q3{%==f6fvtx1A$))hcnvyAx-_)9^k^ zRo^b1I=sLCGR8Zvuar;%?lrLQ3C`$lhrS6@QBRg2Hz$AkgMKh!{%5QNi{N{t>*P)_3 z+#yxV`}fG%+4(XuD9gL|LXH=X{>hK#W!?ZEqYAprx~R*CS7YVr@O`m?$H=FuuPGA? zhSrK~O|K_<96g3~1r~WoagRQedroK`5@Q%JdAlKSSclXeg8e8_x;-Efl5kzq()b>t zsp#9%^Wc|dzjs%T>C4O9)st)mm0_Ei-%#b6^Fg#lN@wKM^Q`z1SFfp1iR*7F>rK;r zf_}|0anhY}AGB>a;JnAu(BxP?T^r#yfES2_4w5iIo6rpHDAXYe;ME4dmBtH6CcSA% zQ7ZjzkhSiNo9}xp_ECAC=cA!v;6BH_FbCoyz!@AB^ygpFZ>{1$H6BBY41k<28Go)a z5)mvsdRFLVXMLoJ&XX1c6kZH`=`=vRoJHVHB-P3iy36$$rjxjNW~|esl~?8`TN%}{ zugz*B!;ZK($^7{h;wL*;1>t|ox()I^5aP(G2w!RcE2N!@jtWBrrJz8M)T7FG`D^$y z&oy6tec)`bx#kPA;IDd|cn|_PKeNK1$w?AOD57-vi;5X8vFh3oY*O=+kiW5?gocYv z3M=oantkHNV&=f=zFlmad;+d=q$TwL>-(e+*ojK&u7sUV134!mg27pYf6tZzgs7F%g=1HrhMrU z!7BRi&U{L`UaO2h+e6@D9;C~~>zD*oL6J54HczdL_8YfHKkZL7Tx-aqf^`1iX8d;4 z86a)?XVNS%Ba5q2v@7#ZwF^#31vMw@`3K+qVm&%f`c&38I7<$zx4-vIVYP2^Eo3<> zoUo;vdFb(o!HXG!Zd%(n#1AwM&!j#StQHbZhZ#|f<_{X>qAf+?C!SnkswX6sh;1m3p zM$#eLn@9Pd825kr@62Q1quE1Ka=7vwRy;dUi5V>*O#Y3?ESMJO{SP?w=*BGgm>0z; zs#c1r&dS0xZmgC*IX0M6sMwJ+VS3e>PbiiB+Qn+IBVE6wF+s2MFV69E8w%hm>PeSX zVzNq!jfLwK3a(T89F2yrUUwA+AI=>>s0CbM~ z(2wdKE39+SUx}67zYBz{f;-JchS~&m!MQZNe+k@bYroYMy#C+5{AW!T(!|n&h|G+M zdK^RW8)>;TpT3{uK_ai=*0o8uNvm?>&{ubBiWy3%lGcTsGy>3VejliwXIs6V^PS9M z-b+M-A9r#L;H3h9m;Sxfi+c#sd~-l!m-0Iy$rJXafKkVVgs}X8uqKOPoT={%`w7L@ z1=UAR7b|eCzxF}t_yI$rv@^K(n7{Dli2W+?VNkjk1D!)&H+nlIGm;K9jXJ;032-@4 zQrnk2W?1^#^-55Lp=?8pjZiCp(xH~4kI^G9<%v^r6dY5^pWz%3M8QU>Gq7R-rxfg^ zPEtPY0uwEE9c6n@wq@^Ay^i|4q=y+O6=G(>*2wlIR`Cibc9j(e^fh?!H}{`0<_^CW zVfl!?vr8X0DD?X+6oPp`U=#$)>m+iRFpMo%0ajAt+)ZBLRi3d_(vFXF!Z)k#Jec$I zk}Rl@4OJTP-~Q;35MvF;2R5@a_VNN63^CA#ex_+eE*NLA`Qi9x3vLA}mdZb~XFfh7 zH1N8*+~@RU(u0OnuX})AxemT z101OF%L%}@xzK2pX1e^gj)%|e`nK_Gw&!w$ywlNx&xCf1v!Z(af*c^z^4g-R^0#kl z;+=0(csTB!ic@{{s&d=29mgei>Io~*A%qv~bgm>*hBq=o+EJ^7PB;VK2$(ykmDC4K z3TtAV+V;*b>GoD5iw@buldQ+UZ8>WK4(;^XI8p(Ea{`w609T56oj6|yUFsTMoE&OM z9W;tcuM1SvI^G{%K2kd}6}Gek{*47xe~xr5ofNA;57iMZ zw=>9mz)Hhwua0M)cs=nY_=#Gzzgf2Q%0@k4#$riy_D2)T-XQu;Nu!2J7S1_tXwH6=I5mOnQD&85XN*C0 zN$4h)=>S=O(xkt*Pn)O@Y>g@%n^EsTAAgg6re9_Mk%Zn)yWIBOPh7JU`jx@E?u1~* zf!1eFBVHSb;I@LSOP+n{EW$qwu9*+%nV_9ogyrL)odkK<>v%6-1rt%qui05T``Wwm}J?f9}V(5_+kucEn&(Lo`4$+Sd=D#>^N-;IP zC41ZIdp*K@V$$450(E8<$w=XZk$9J#;QkVJkbrt9L{uF>o4CUdT02(G=_B zX?-v!rG4v#x43+b*Td*K%*_zp^34hc@$(R}9fa`P3NR4?yOd!8r&CnIZ}1zPhGnSn z$5%|1PJWV6)RnHP@aY{szY}@IW3&DXyge>PEW?rX>SY(*I{XGnD!`LrIJi8v$FX-jN&Ub9A#`wAZQ4_`AO2&8Rn<{JivUFetBpi zZPV*9yVX8W&o|3q z}VrwJi!A-Yx%kZrC>6NkG-Jq!vFcD(L~P=L=bD!S}q`wnfuDH*LLl4;joT~PpcnYVA~hv_s?BNXF@R~$bDT3T-O<uP5qCqXk(9W2T ztaeh2o#8o}=YdO?5)!Fq8n&X>k4yV=1OiJ}Yo;X6WHnfi`*2KQIkL(^!DRZ;Aw9a# z=RlRX>@pm@o-A4ueZShPqR-(jTc`ND^3w`}t84UQiA<41WV&@}>jJmF4{uAB#RW8a9dVrw+X1%eNVFa?V#+>P4i2{?|+be+L$ zOIl+)HC~CsuAqETsbw{5>%K<44}r4Z+`&DBHGC)K8nR%yta@{)fH_KQvw0Xn0=`dW z^uG=>ub>a!Rcc9pZhyIu@?e|Li;RqiJ_MVK#{y88O8MLBypMr>BkDS*Qa~3|$A2@I zeM+afY;wFoQ7h58xITP-wq@p-&yYMah;{6+UO{^@AatQFF z9G}M24$HqT}9G?suHBo5&-ky{7@xtTUBF-hWV zUnNF?X^64<7w&0(i5oNG4X)JMP)ov*bZ>fTbhU?+;W9AYDiZ0VL?>=Aw-2yDSm&UlAp5+_i=$YOo*B-D%cW{p}_acrdh+S2C4I(2%Xdv;| z3fd|vc~3g*)fkYA{r2gqYKq3^x|KbJvPp%3$~~iR2md<%HRs!i?C-UMCH%QXwU00Lgn68sa@15LpMbCXS zVi&&TWa}TkFFoYwG51%SW&`T^2rmykadnB7(`uR+o2fNW;~^K}xoo^#99WcC6rBvW zmtP`&`kvkCyJmFCm%;P@e|94TXM;Ol3cXKbVn9E#3S!A#Wfc~xP)UtmT+HJ%ss37Z z+Nnfp2lhmagQ1kxnqj2n-Dk$b2<5=JFa>2x@7tzMIzW2d3s(WizbecObgK$O=oPeF zke@e1B2%+Q7EOj!l$^je_5W(Goau0Be7MX^0kkucN!}Ld__=V zBo36@U9fyibDB!SG0jN{{E6O+wH1BXN$Ij)zpW3H%8oY4SBD(EEO+~rC|mU|wr>MW zLFN^})g@6#jBO5}j=x4+yhM^CkwG=7oH!4<9vn$<`D7M9oV}_~BgU7ih3TQBq%bqiNB$6-Ox-kaWRtwRv7s%mUadj zQ9yXR=u0*%O)Q=9&_USE{+{zxTJF~E0lkn zvj~`J0cpYa2VJ8IKom+Jq?*>N&v75Jm_nKee-jIk(A+@dp}fUBN}3<`%DI{;ME8&J z(m1BPz%+k8R@x+>YZ>QrUZK#)8P&~A4Td~G>_o8S`+&&P#Y)-a1Q}C_Us8}g7OVX=W(uZEibUz6kUEgifc|u~P#@lG63hKH%_`5exb;X`WyFZU&l3`= zhX*;X*yOcx#GqDV5KR&wW9?ub2VEf0_i*J4a`3e&D^F~i7dS$^{PXe8&2=cU^{PIu zjmQ)(MtFD_r|=*Nxt)iZ} zfdtzT0N{L*=m>JiJ0zwhnela>4iHcGd4Er$#!_7PmB*;0`s$ zg28Lm2DE#HR}a5R5(g5O(^e{;XIAD$C`e!qg2ne_8@hxg)JEPi=(U<>J`9pXhIPbb3r z))sgemQcNgA6f)|1lFf|i3d1C+rFm0&vUcl3c8u9k)-9xy?CJI_zD>P1+6ST^JdKQ zp}7h8rw3qIia5uI@S6^N1Ex`Xr$andJPTEnC2R&mlW%QHfG8I=eN2ecnusKhaRKV7 z#-9fFK;L>9v?#bn2%X3gRw`I;DY`r~sL6cW)lX=;L1tdQx$eU}{m&m8l5r>LsgBt` zNrpi?T-g^7g6f#g->4b^IxndzaV)#uuDmI0IE5+_c|$_1)XW!0(=C1Rb?`d%Lv>|Z zLjWb(e}|^po80&8as`kqiH??A0GkG|#;9lp3sjhaZ_5OU+?BZgixlVr29__~Cgt-Y zH^KFdfG71}L5cwixb{Z8$`?Q?;{^7=%&+-Vm@R;=u$cWDYG@g=amane9^nHZh{J^SlH`hm52~~z zio+^oQgqGnN!-r41^*Ybhx_c-t-VFF*&f_@yu#tbMyd6sB{C%@7%pyzLhrZzFguka zMxx@`O*K3GOGyD}=rs4L_9m6aQJdj`d?N9JtIx!7724w7`tej1{@J0l zdm?T@>fWYmM!o_sS&!cQd}7zFu%o;;Y38%f3E&RY*OF)+5`;#AQa9l!-mSX4pCGUA z+B;J#UVeI&AncYsdL``yHaH;nL&bTcozA=8jX7X1gFKoY;RV5u8;i$+-FOihoS@~} zPj*Gs1ikutn06kHnH{o-Xi-u$=QZ2r&1Iza&dJZ2f9hc5c{PC(z@{EtcfGOhPVl>_ zF4~By67IM^(kfziY@VC7Xymz`eHXJ1&TdPNyv@F)r?&UZuiJ*|Nt?ro@L>uDKA;j! z)IEehFrc`MiQ74B#P#HbV@MhlE6h2z(@pP#=82z*q9uG(TgA&hh$*bEfXfR+#&khS zb=#cqaa1LtWLSew$*7?!_A6n3x3dykzXwOA!&KZ%pk~|6Z`|#v>esGtq9D(6mRPiV zS?z&t0NM`dj2$!lq@637=RmKDI2-ovolKbZzvoaecs92yp*Bm%&75&iS{96uJa5J? z;q;;U^Q5VRq>>!geY61dwU<(R>re6mngrI!5N7=psjiCwPJ&r%-p~pI_fCWNB9x#!qkpnHrZr@=o=`2NJDR#_G}um1vpK+Qy#*TPydI%xd?4SOwZMHTtsG zdfrPv^l59mel9AVLmUxeo~098tPr{W?8N5U{Rv0DJ-4(RkYm&H4dI$aA&;<>?W7TI zBydy6wIM+TG0H}E&#{uA>6~USraT3Z*8>so%q9ciAtVyL3%H^|$iYO|QC9;5Q3-$=NW!&y0wDdO z+7Npio4N8GV`E_+B3nag*~1r3bI+_Xk83iHK|L05$8V_6O)KxcXEy7VNEdGTT&)^J zHcSWc>OQOh^fOMfo?&My@t~*CkT3_DqS=V_{Y}qNpG_mHaH%2SKB$Lzi=%T)%!Ac# zU<&xF96;<6^@53jM)aN- z^;5DQt(@so?;Ap}DL6RLdef)Xpq=sn+2xO8IuJnPvi=cN($!=>YC7rC>Yf-S4Z=*^ zmtH@Iz1sT+{SJ8Pz9aJYcuTKp`wM|`eoyA@5Ui^!XxYgBZ`y7< z-TOs==4w*Hmrw5g?i1Tz+n#5&(HxQ<3A9XSPcc~Q5gtX?(P_xW#aHNrcyWF z{6&E2X$L}=t^FLsrQ*&jzJvD;-q~UPFzFVfb{zxa6P-h)8NH$GxEa2WO~BpUlPn+jKXO(IA zmqoH{U&5yg)ml%kRsGotL_DFtv|b=<3=M~YcVj^L?KMse&rKonGf&VK!=BO-Vh`Ux zR{Q*-M&qfjqxZB*TteTA%9L)pko|b|C<111`rpM(Sc6K%oC*91Li#`6;~Xj7kxRdH=)yk%huDje{Czmg2;Bzb-P^wHzGVc zX_z`h0U#NsCMC9O*IcrjZ{w?y26-nNakKU*t&FD7eySL?Z?TFAB170H>2n7GT*Lh6Dj4A%Ub5Sn>o8R&hxr0r?YQWN(0Piz7gH;gdANU5`Aw zj;C+y-O^0b4qFRUZ@aMNPy#CmI{5qZ<2nJxRJxhq-HPl$o%|%Y@a#6^Cet6pwL<(! zT2A~*hB77;;Z9aMyb*NHf3UDzt5rr`Zfe#W*Rv1e07C`PXCkN_H;Oob2GZ~xJs zTM8=+Z3A2kYWhnR+8wZ``p7})`S}m6L_MAwD1O&2;(hs&N6{Fy#q8DtrsjjXi4DaG zUM#J!55R^67ob!I7{t<8Y0`W~KqN5Fcp${o=;mGvr!4|nkQ+UyiQ9yh)nvW}&bG8k z^S$!SeXzWIi^guXb#LR25@FP%3zq|jfRO;i6r+Qad9&D6q+*3!w_drZC+$rkj)_cS zLUjyoWzS^^=}NkemSydUnQdb zUgNnGh|(EF^ho3%^R^C0PSCNM0M|{N!7g6{7u&UoE^!T{7UCUU6>zp)<9BKx?0L<= z#MX+yQ3?jWJ9l>MtI3yDrOMo}$Tis&7GY$ueX9nm-+CHi3R4mO?=%&rQ1&m<%Dtr= zG;E8<{w6z{xlG$2B|F*o37c-2&TGA4#gM|v_)$T4yT$<_Zb739VbvrL=E;%;9iMCpRMrcVu6m6&tajirG;C{u6TVHRf5qWwNxZfjf-P~l<^3ih z$4#zVuo*JQqUk5XnrZ-@n(i+JVqkm>FG;*dMTzV7Cjxh0z}~VBZ<;T^Vpn^U9Dkjx zcHm&XcyR=ZB?>G9BWOmAEIxzeD-|h5eGBtxmJ&Zl92wwa8`Ji+|7S_?4_63GlQ~nU z9kIw~oPHa~<5 z`UnA%IqMXO`1?}(3*`Kh+a-zxrLNDv!YN3-KX&6lKCDWInDJ>jtl)Nl+R~7v|6JZd zoh{?{HTrk@)AUB%-@M$-JvP9+3Dv)!`2KJ)9s>Xjz(UV@tXJi5tu9PSP_a3X3HN{^ z$tob5nhBxsO27Yrzx7yKAOBxDhW{sq#GBLvJjhKr!HIDDfeqLa^3dga`q|U8_@Vg6 zS_6ggtPHPQrPwci_wQsn8B+PCmd82+hrn`V8i`FNZfH6L0WdB~S{JAV4CTMh6+T7- zQ4N_mS}RMU@GZcwaX4nQ(U0Fs%G8o)XWRo<5P%E=s6so99&WEAi7Kg!)g1Do2ALG5 zn5NA;9Lss&tthI>sWfU}lI}j%~n?@cL&MnOTi5r*zO5N@T zpQ*0OoVjxd*q!1Pa+yE%<8R5usXz3ytSB22G`ByUB3dTodU^bj%Tdfpxb?@YbyNdK zBOvm=A7=`Iqd*tna#K5!02s8F1W19Za|l#7=7`XwlL$cemR*}^!M99tIyy@6#tJKA z<=yB8McdDpx;5&=yoel2unb6v{4h}Xqkg(|5}1sCZQXz!n`_WI6-E!Lzv-yndqcZ8 z*vZS=&)ZY!i~Q+|pWem!Jc|=BDsvwKLvfKLibUdYA`-Pf3_OKkb5Ox_AHh0-;j^JS z+%S8S)?fh*njB0gXXrOs(MPYUjeT-BukpdSdB8kFA%tCkaNdP<+>rrjy|ga{Aef9I zO{3rP{et~zD!-)7ez(qaLq};`cNk7}YW{RoHdEmncwm!3IQVe>>fSe%39bZ=uSM;A z+=jRvb7EH9yAzkIfUfBOO`C~r5PU=p;hO>tbsj!?^(0scOhNJlXF%FebCu-i^ADrL zRZDwrJZcisd3f5Ru50(Bq1k5WM;1;l`&S$&e=#Me=uQYPsLpb-(MSy{LQE`t>+ww0 zO6n6|rEke9x&spSqwlrCm-b(&zl{2PLt~A^6kY^#TNE#NA7JW8jsgX|t!fcBM z6>oel9$-$qd1JoE%4tgLu%4uE+{VySHMj|xAfjH|lv5m*vj<83wH1awSPD0xHgWuM zP;N3z1caZo5Uh5M9C$ewA3#R~bf{|{j@?R4*!ZS!^NNGfL8*phZ11tT4Q+Zv32<3S z&C6|xl}!tNR(>#k&E}~visg-~kNkH8iqL8gfaP}R4`CfJftHdFR@EF9qn=?kJA??C zH;CzWC^VCtpH`P8t0k7uA6b8s17=#QA3%mkehfB{IXV(6ia+ywW<$A>dW87A@=foc zK}p!Ver1m&xnI9ApB+49GZo#!g+dPKfXrRSIS<5L5CUeLNkkxLXpNlqrpX|0{k&Mm zaNXSZ!B6)jk*B0Y5FP`1jw$RkNd$>OLp}XN>QA#(c~$*{#*5F#+DUDRKKa$1_3ZaY zU*^vEAG(HqN+QRD*)B96cn2KhoZlrjvmrHohp9hVJ=I&I|MdKMrMi-eL$6|GRYSHV zX%&rr$Q`>|kGrP^9ffFq2fCOd7|I$ea0a(=rHI(=1s?+K$7Vi;F(~c<8X9TYF&pH= zn=$Mbnz;*oqLywnFG8<2>z((~P%=G3+g|PN=HkX~?(MJkweO{oq${6x@s1}ztqNdA zNa8=719bs+aX@7_ktzo!m=D%yttII0Vj9v25jrw2?KAXkX$#}=xp(6vPQRDETAi?+ z%f}nn$GHpGv&w)anG9l%KOPU?1%E#cuMh(ua!#{{ul_*Im0(||TpQSGgEIPke~N;v zkD`Ht@#mjp#n-3n!87|sW%OiwbJh7?CL8?WZsRS%YN$aX7ytMOs4%@GF7*B*zm|VW zI)dFqkhJSVVG#MAuo*dPyBiIjpjzczRxT*X@u?z2?s~ZMBTg&nBh{zwSN}7~J^2bh zanG>Mc?33l5k7b+akebfo_Xj$-6z)R4!>f(z>jm$(BR!y^1w@F8S21*@X z%pF8zJC;Ud?%JTVP7)Jec>vMgDg~?LBfI4oD$RTX!pWv5no4|LM%)a2uYK-~T1Y(# zdwR3nu=z{ja~FJYktwV{Y0eZ-o2-5CGGKnzZX#O8__71KG0@nswqK{l>wav~-4o&W z)Z=_p8}gI%HabZUft8EqBzNqx*VtN}?$O%Y-@G{8KW&RN=`CE%+RK;kp8rr;skmEL zd2dSQQ%AKDGW#NKSPt2~4y!S2nb&)3HYGpiNL#^VIYJ0UG0Gk~CQdSYEUQeb zjUBCVr3*g6B;y+Kfxpc6w(T1urvoKl(dHV4b=}>5a+&=QgN_aEcp>gMS(nk zR%A@tpivPVOrB#t2A#-A!UB~zQ4(+IkUQ*u6KM&!0IOji;yBJz)efc%X z-R??rMnB<7=|{6|dCAp1q1#lCig7FxyQ&jG@o@D(Ri?>h7?-D$e8|~};$fs{4)#Rh zWAta;7^E7a2&0FykZ8{*;8Z!Bz1d;_2eS?K611_eDiYZ>3gWah_}Y_y6%{MgM)q7_ zfz)Rvbru7ky^3W9)()^9{)Td%;6~nI*>#T5ChD{?k%pse!+WZCJ9Rho+$g@K#*!2%Wfc>jfDKE{34que)ELVlHGVIdu1H z+CYtP?tAf;!!q{Ts1vt+T9X5}foaR=9$f!4^LPX(S+@3jwhhBQEF*RfMPSs-(p7rgZwDo3G;5m>wDZ(shu z#Hw__`ToIp5LX83FF#O~LwNsUJ!s?iBU3p9Tl*J6{F2HTX7vp%XI_n=0cTUn6R;(q ztS>~1JKX`XvOJZQZ?@}PS8h^#QhUo-|9@>wtNxd3>175#m!Rl+sSr;I7S`S7H(_M(87+AX)Io(G= zGsM*)mgE5Z_P>ui?-L{b)rF~)HHkm_gWlrW4_tI80QYZ6e=hrvS${2nJ|npGLe*1#pU0cgBkmjfCq1ldAPKG0nUcrYvvI|Xj82x)EzR2ln} z;t63u2pMn`WC*=jknaCO3VFJVDP;n3{npLT>R2U$JiO+RNOgNF6{cUJkR_}ODVCku zRflDVr><>J1q>BdM3rLPC;wq&z)KRbV&#)OS=D8Q-jBB5AGQWAqB^9{b+uez+*h|7 zS|0auZ2YsR!U^$0!nFrr;HJkaT*2)Mh&;`(js;$taXQ80#vPKXA3q4Fck4i34glvH`LPL zw)InLN%ZOL1G_Q(Sf-!^vNf89MR*cv4Gpc0h*+PF88yOqY5YZ zQ}9CZyYMTb?It`PpMOK;Tkv>wD?qT8;3^Ph$j`;Zn@Wh*G`b?fgM{uJM!LZhiQ-mn zY4}UXF?)m;B*h%pH^l=uRbZD~H|fK)g!C71^66fifMVm4m@(VFoL2NS=ZE*Kndcwl zXG9fL=u5;_3Taq-wQ)dc`Izr~rW&kI8H+V_uxq-1=GMiVJ<(@%7F2|(dHV|9;$i@ygS|T=P~P=epIkaob$2>^$xf%rdjK z*dLcR84;Ja6w{%hBnSS{$54o7fd%Qj$VM2L*hU0Oz%mV5BJnzh@by!DEB2O|yQzCF z|FR?*n^M{xah_&yb6|Rgp= z+1Ea_Q%-lYuk)a2GmSY{QOpjo=kpIy|$1xfro?qA^A z^&nM#=v8v#Zh=ySfElJd?`i^ z9X^8oO^IX* zdQoxA-8i8V`(rZaQ-^VO8ZVykFT7nTx@nN986VBtEWx+iNOZ~|;5kajzmXu>uj53K zkdiYgsu|F5u%Kw0YHJ(YxyM#MyO1a8`nXv85K5jSSx;y=iz#Rd*husogtwg1Vbwb6 zn37$VGFiFsWXP|;`fN;Zmk~oRsmZ~|CFOd=sXZ|#4ll*UAPFRLB5+@N0L%gQwMH%A zZ@s#j0@N-_g(_o|E`1-k@VbXD4m(_cTza$Pq*%sC+q7$(+5yy8h&+yl_r-(3Anw(j zxBHsY@Q0yYwR_ITdo>>vyBwsrrL1h^kubbHrNd-j@{sB4O6Q6Sn`}4PgS>GI2F|)|uIw`)ECWbF zY%qt9Ww!*jhSjJsblyL^I+~ig_{>WW*>c$KahJA5!{ zF*&lPv5}|8DFi4wl0~l^U9mJnbexElrnRvD8H1dAX*}C}_8{HmpH-6#Adtw^;N5{5 zabygZ<_;FP5b%I|F0@(6`|%P8o#0|paXV{{146@?0)kCNVQ;1`INJ}Vy z03KE$*z14f44cRH-~D3dgMjf@>ABf#1T6qg=HobsM>^uvAkOr%X4GmXz2KmP)Kum+k zue07@V<1nESFJTI-uc9vZd6Xk#wlGR7p0u52vFM540&iT-Y~lO{b#u0(WC8b?>6jW zP>4N50q;Iqjf72bL$o0OP2R_b0f19vsGgs22yi$MHDEi;-PB=Pw^pXB+~aX$ZeRBb zPvJ9LnMd!Mo03|#kXJY!trCZL!6eTY6-o|MY>IIQk6@H0(+r$6`L zVws78*5}}q!mY%wpmK!VzygLE?W*;H0z;87j@ydJ2E^LI)`!E$UP50tK0T4jEcV;i zSkLiQCaQllq^tB4+it-GBReE^=AU!3hz~?wS>&0m-OVb{<$Hhe#Z{4>oI9TP(>{%V zw!~g@x_wUi7ID-ZR+wJ6Lh%}QM|djf_7q~+r9Njm_D;$0mA-K1e)k)x_PI)HZ?j!Q8S(^XM)wFSExViP{bVE{?38KsQJD&R_v#y&d-fLO zb6!tY*1N>kC0BqV;Gp_EWb0sw7p#PB9E6*cLIK(JIz#a`9JI!m3X4xcPqAwayZG0VDy_6ZoR@(*?nFYsCi zJ5qmo9&Ffp!NTXBCWlqYXbotD_${A;_t0#_?cA%N zcKD%>kluT_Hcw7)jSZlVe7g?nUT3I4WS!shcm)!y$PLWb->f0*?O+AmV`DZ43KLr$&`UQMG@hXyW z6}&roZ;d7*G{F>RMu)@pZ`*rBo3y${%Ij87z=xy=G^ z$`yjt<934L!pK<)u+ZKE`&-fO0lh;FQy%qrwXXPbDJ7z;51iKpo!(22|EWE#bzKgCqP2pY;%Ad;=96}CW9jbcjWILcN zOR8`Y_^5MpHBaW%)!y9B?)cf=YM(!~BqaIos+pYdOz4SNk5j-7-SR%kv;btGW! zngeH_sA#Xd;_$%k#&BKc=#|DsdF1=fyZ4V;9A62PXJ7xw$_0!5y^4riTKvj%eO8hSvSQkNCAAYsfO5FDbN1pBvL~n4`!{O@M_4~ zSj>mMwoyn)qknxd1bbrh{6;Q7Rum$l(mP3(+eiGa60i=EOW z@j>&LLg?#@Zz0%1yG=mK+zI{(K)285fC%s0B8Yz7itcMwByPYRGuy(z(T3(1rNZxz zFUR^87Aw^#$*`5RChw9yipfAhIwe*UOa*fRsGC#(e(W~Vrh8g}4k%NcK+3@hpbE-Z z>TE15RG*ghJ=)9(X_E#GvuCM78?Cr|B$~^q_*+k)db!dll>*OeUqBf;EU)~5j+w-T zQJV|o5cide5M5yjU^pTtXH=OniZet~-Mly!`8{7yS@97AN|oJi_)%^0A|q zGABMX%?j6{xOI{_p}l`|DbbrELzg3&ndL1i41vAirory?YD6d}8asm<1SK*q959P_ zg~)9X&(%@xg)I7Qcb3ZOqUahS0fmqDI#=x%x*u(+^R1@>0@$;Etpj2uH_!QX!>&dg zj30*0@pqD$`H(Ug{Ta;d9-6D8I{F`Mub=l90VG1*S0f$I_S}*NURnfTe9n zeF_RqMV0)XA<`=FuXt!Tfy(}9l%i$^U zD|^4EZYed3_GNLz2#Fse1LLH@ET#eB7?6PU{sdM+ws#LiD|zr6DhUM9zxiSFa?GRE zt7pI$`oY?OYFY}m+)ksvc@38c(Ix$(NHZUA;FwDLz|J~|r5st@3H4OWfN2|3fL+e9 zG3d17Nuvk?cL2K?jTm-AO0EGB>*>iZ>RoO>S6WhH<$RMz9F?Ey>=gR`Qqa(GTo;yU zBt=o#(3ApOna>1T=S_qYw3~3to?0r1a58{eLMTXom-SK?xUANISR}p`+^&XR9C9KX zkx8J7up|;EYIF9e}J@7M7rTD|GKz_RY;^WFGXfpES^b&u(s{}k`G25<*Hr?ADV+S~bzLcK&|!Mk`vv8z``C8n<*&HS6( z^51*ViE)R8>X*RJw!}t(Yg|MWt=Y%SM@p9=@0Fp(KmaF!+(nN@38Krk(~-WCvjjHE?y4W#C^aC0a_keu@wx%ScRd65a+kf@*8)Q2r4#Z4z}>8t8Zqh?MH%+0UhZw;&Y-`+Owam<(ZZL&kkO7uCa~h0HyCL!b1+ ziT>ddCpV;KLSr`4E5;t{d5(RbsP;lmZrd{?0SA*TlFs8V{?>S z&sxntz@t3Z9aIz?6H-Lk2CKYzMjYqp;!_=?x9zGJ>*|W7@M~pt@2l2bGGiQq>4q#r z=`0+~a;f!AfpfWzQn{DQCBu#++wDBXq~blH#$(<4R6pWl7rqge5=4%obP{`X-TeB& z*~ny5SqjT&z6QCd~=1F;~Nm$i_ZXz9$$Mog-F+fAnnDd#_(10uW8Qk4xFzfoZ$ZajR zgYNA;P^ha=bo%APyD#5m&Uo;Ru&rwj_XE9KXEw{`^|57N>ekdroUm&*dr&?pwtLq$ zMT-ZDr_QN(cxogSpQr#qi^ZF^H=40!0{*@gDHTxTABpc^3M`PejnK9{dkfy`{wrW? zM${vJg{3n&4-Wa6v{}F$3b3D$fl?HPFn{?Uv&6;~VY^Fx76+70M{2F9MA%^K3h^s% z$?vApKv3r+Yb1^(1zFu#z(seA6vxEjB%%wIJ0W^tF}M(@R9z4tYdm}PG>hv<$JXdp z&>xbk9lY3#fo}wl6uN@nLHs#KcedMfolmV@a!UF6=jh9dDW@#1tmxXeVbb;bRdBsV zNX;dI6~Y{ypgG;4go755tpt|PT|d~w3o_?jh^ylSkgC?)KYQi%N~e=6i!NT%I~)3n z?H@AvoN4cO4VxiGdwsWUMdrGV)vEQ7!tisiBYHFr=UF?f?$UdPUS4UEJlpW&3#Pv^e7kpR{Hx3MTb|yIF+XC= zX6wb>pCXiE6q_#c)7}r<9kpBBs?j}#PYRlZ8+obw(AOrtwULo0@7g_keQVveI=ReC zRZecuXZ630>?hE@c97`a*M61^{*pA~tBv6&cMS_0Zb_QAyO->hxUOA!S1&ckY}6*K z2ccOtlsg{V&cb8XPLL-?p`?j`xHpq0WZWmeMM{4|T%fQCm-)*5SY~R9)$=r~<|v^L zTNXTio$uho`S7|swQ0Gd9xqqXBRiv9Gw|luNvJz=6!z0HqtFSD3%Ev=^=(J%OWTu^ z(y7|7x860`s54T$=2rBe=A+meX*v5jyh#P4T{FU`Jex~&YNS+=pfBMv#-KwA^(fCf zi9R@k=hNQOWLF%b?8MWly=|HMX!rJ_a|D9C8&oSVOatOR{|3f@u)tz$N;h4BdKSyd z!VpIu9_f_cH%ild9M?5IMfVUnVv}yj<{j&ImP!Pbf`(=M4|w}OVd=jPOXHs49wK9F zbpt8)~b_$+LBZv!Hlq^p0=`c0NmJlf%;(%16?k&koOMw{MqbUtBsp z&aS2-%p|FmuSmw_eZfb1I6*Kybd`n2tBSxt1Z{#+l&Pj*KXOtb;oSJbOx;~HZQ$69p!0CXk6~{ZFrV9W{g);IG5ltn+Y0gE`03b^e zd6S6)@Scqpa2^VY;Lr%qQ?i;t<0ke$-~RvGnL*aV4c_6|R=-|!3GuXzB+5~B4b!~3 zhs81AxHP?QK4NwJc8FowH5En0>&?O22Ptp85lCcl_cO+)A(^E+0ML`LT*AEW6 z!<~~zuBY&N;W=bre-o^;#5IHeWM_kOD_#TD7`koZ7NQc;VOw?TJZAp7jhkN!Jq{Pd zvGy&^<40Y#&_90b(J?Cpg|zgVnpYM*$e=kmzg<`W{9X5mTODM&0E{abNJ>bi_nk}^ zyIr0c2E{(xF3H@t^3cA0@@~U<)BOa3GNY^Zr+U6^QYrXL%ENjQ??yY$vlPc-;S7N2*}p^UCfz@VIy-FTtNA0C zHrVWCqtkM#A`FB@E1!vf7_te-O^2QOh@_xD0dRY888N{&b5D0QYwe_?!_pagw!#4Z zB=mRPzu@THl>g`hd)(Rh@Zrn2OrKy=)u$7+eH_Unn(1>3*7FU%IuCTi1g~#F-RXhj zx)snOgS$Pp-M1onDsTGleeGAy#-tuE+@SI$6c+})n-AX~Sh zfyyX!Z7M0$-uPitTw1+)RFuq`8=2~dg94>BYzH7KA(7364s0{aX?l&OV4F&s_IDmYFe80K1h29R+>RGNko0|0a)FHc0M{jWzJFewJ9=zV6NY{K|}t zCl^?_>rFm3sCD;Db=sECo>+7myIQ0`3}azR;5${4ITM_7e8-r;9BJjHBfYg_kl8Gz zx7GKU(+7zHk{^*Xo9^tL*6P=@{vk7K@c5Q%S*cIXFWUPyd;O7VVwzDA1O25CLySj9 zqKR#z`14oiVTirjUElYcn99a`d&I7WNNZ-%ENQKDXr(hS%mW+WULR&k#3CzM(%v49 zzK>@cT1`v6Ww-W5VS-Ed!cA|jq!VN!On2|zMi896hw8BWJa6F^3=L%SBUfz^FuXPMWdj8t|_Wm7fZ?CMA;Dyh>YPHYs<#`Xq8q~s9o|Zbc?1eD1N1Lv0TFBdCt3cU& zZ{ddw@3moU;?nr*FAtnczHw0xQN_y;H(ksqmA?UWt{YEg3Dvkj>GyVzD&!{w%ew5$ zOwQiXdS7p4|20i&@>%9br3rg8d9!QbBF<+vT9x@?)$^b&yyP3XnRD8n=F9AwM&}Jw zcby|ykdD-2#!lbAw$3v}c&Nc-b>{v9$Wg!hhQVuA_nse`RIW+1d`C@Q!)#03%5Y`$ zU36^iwC`%`oExXYzGyWoUOD^;|6{n^SS3{-d^*xB5IcX z{#L6C7fnz2-X*U+zeAiLKbRPCBrjU0*ki%bB`WI=FHi`5RMQjd7Vw>ottb@Iy1=}< z0Hc}MUe9mEvUqDZW6|6+o7dDcoTQEWALc*3zD;0Wyz14+{O1o_v$^;6W?j0$PRCK=X#iU6|1~0+O$bZ(_XF#WZ6F)^eaRn-S1vN)c({zKq_)mZI)^p2?hH zD_6VM>kZyEEh?X{$<4m`-eR@5=H;)F-{UJ{m=oX?ZKPBIbzxwOhX;$gSt`_pT-tSp zpYK-gebr;5Myi8X!|j8UeGX62kN7B4>lH;Um$+yq90I$t4fUuWU(_xSPP;R7r(yKd zK;jupG3X$(o{>VcGzj{ zqgT_`N#U{+4ia0q8rmLo8EW*3&Dq^zib5uQiQ^6@@2;Ha;bo@4FNv zp|<7Gl)^88kljF#Baj1f94Y5W7@?}Bx~_#K>bch(^3W-5Tb3KlQmHkl=-#y2_`TD` z9?iMz*g}+@&*E-$u;!16KweTf57Y5w(?b(=%QZH>%+G7CtMJLOll4+aQBJ+oHhLgV zn6s=hawZ)*M~IIl!KfhyZ#%w}KKUDAn12V%@zt+J!Wpop!Z5HA60LCk!I%*TlpajZ zaGCoXir0Fim##~`q|@(EbNtxd!VM|*r?;w_Yb`UDQZXS9zW+y{OYFlpLV=MmQLEBc zF!QUYXnrDk;R!A>a9GN8cs+E?Gb?L&8DqZ7a-EM+RC{>~!d(2&nPty^l;wFBf z8}bV_QVeXdIyy+7$t_Rbk}?Az5SwLyo9Qtsk?f>f=gi!N9j<_ zyNMS-fJ>VrJDt<9vr(w+0Iwx%zagU5W$C|u+`Erfh@%v0>-p#EU zIJGZ46#DNj_?l^|0#h3xl;l#vzKEPGFimc#)tfKZe;;1vdB0dA&Him$y_!_a-gkR9 zYGx8@Yu8ImlAeEV-P!**P%yp!Jzmex4iuvS!Sro`)!YpUJynBPk$V0Z9C1=bP}J5& zRRCXT%P`bXPNfCGkEI|ZA#`~Nr8M40df(raZ+h~bT=w^v;9ot*wc(_FOc_aFwSx$n zKj`PEP}+n4Z-HW<*nGt0y}_+3!r+Gv1u*gWe8lq2FPcr>lm}8!6Kl){`jrVJ`jK&u zg^OI0JJCDkKoYomHo36Tgc@xSu6E@~iK10Wc#InX z-%|qX_qipUBccmg=odHUXfV$fw~7rX4Jdhm5JVyx#QIBM$$n7@&Z40k{p+YM9^yVO z0AqUuc`rqrMCxbmfdtqa5i&Pf7iibHy8seCM!u|~Fj+!180unUY{mpRyAV%i^ooy7 zeDW_LTPB-?ts&t%9eDQmqdsKZGq6MmpM&f$aUzUmE05@GIY**R@WOv+S2j+=B%Rw8EYrK45&Ln`IXa~g6oKi zOD1Dd70mYKPkGn7H%H#@^D=n)9)M6}p1?iRYFBq^oY57%6(-Z4&Dh7{ju6{ecqFqF z5$fdC4Kpr;TLZ5;+g;`6&rY&*kji zW@St`>EN-Qi$m4R#pPCI|fER$1}^A)nAZcku{xq;@6 z|B!&1^oMmx5y+7|1h$uz+6~Xpj+dgxy$aWzOg_1z@t-vEKXd_3B6(7SN^D9Sxtn&Y z$2P2MX(Lsw+hdu0p4*zFXCZT|hf+q*s44F<+ZRii=|GGWlAYMLQ$8hrxObx9iDR^@ z&ewM@jYE_#7UhgDy^N80fJG%?1qR*)SrVBv!9Mq7y*G?}Ym(%?w@=Xv#jABn4aarj zgz3}=TLMzHiP!cl$UUHuaSk$a#F-@akY_9N8K5S8)^x1DYJ1@NCym9c^fpX56uIKW z^c~uXaOBk>hdsxogpPoLd|2PRo*w|jdJjS>QK9_JAZvqE4hyv)a5@GOQ9r$e#>*@g zAFuq5HBQm0l1VMJ=lA>~tLIFOx;VSvj{CA+b|$RM5Fg@>o8(@jXP)iyrNn&s@~K8u zba|8QDOh<~`@^Av=F=~(CMszTYdT%=Hql!lmj=QUXwa7NCS1B7reGgP9Vn#oa~i4p z(pYW@C6k(uD|A$LsYiJ61MKQb_FUX-X`5Fu4ZFb(akzcKS3+E1nUaoCDheD|abG3f zcg@Xext?iPdB$B&)RuBdJXQYCZDJMUA6X(XbH!Mme08F8Sv|o$S*s=6^hK(lm+hlB zx*w~C7j;Ru?^Dy@MpScePV?u7LncUEut2C&!edl0X1kQgaZ8dn)FJn_&foBHt<(A! zR+7aICHG$!M&}L78`IPl@FU)l$T-Um8{ml@x`;Na;S{ zFq!JZT~5Q_w112-5Oi)~mOXfDGDnd+kRX|rr#2(ldLP+>#kbZs%-@6!MjjOsXgc?}_6`|D|+KY57vue(ix1~Ege9Os` zwX{T;6q3v6F)_+5x-`B5gWiVaS-O>7Q+U&2ISje}ZQ%pn>-7328oi~}ezL4tEiq?T zptQscO6j_QdcYj&aOp)@BtFGm;Mn{6lj_|&CqWK2!TKPlQ>p%FVa#fo^k&Vdq!d5t zJ#QyFuHd~pEyfU>`CGD7gV z0`BF%c5(RM`?un+I18e(pNYB+QbUS=7?K|!701XhL7PC2(iF%or7NL}2(j5z9t*N< zI9}|K4*iX;JGkx{sc2oma$uivzcRWH1A`x*-2v$c3fNd^y zomNR#C|Qm*0Yj)FR@x6bfGpza_yPc|fYZlDj zM*9rY5AMKGqAIPH$hFdy=$&KQFf3ff(b>7Z**oF2C)?lug>>2@&m~8rpB?tuL~h?~ z<}D>Pmo^Q4WiO?GDVk*qPrDc11%^%{>8DFW?5~hVEFg(~kk&!@vfX4Y5FX;MgQgQW zRbdZM561Z7WEfJJwG9YV0>kI{FPm(n;`7Ty1!!-IADr7$bd0_cq8g;WJ~l_zkhq&{ zC!Ec@B3NPUG>RNeRk(py5S!t*vBJwS`mI;b+*34(w4G) zny;QiCC!xmp99I72I#L^pk$Zx&%!dggB(MNR2tVXI0M=c3dfJ;b7W;@A0?DMIjb@+ z{)4{v+nh;y_cyPXa0WLp^Uw5j?O(FSUmH*-h7FnbK&6SMQh_-_Gj4r2P0MZ0nupEQ zC27y^?u(Y%5!hlB{_gWM-U5ZVj_^{6lV-$v!xz*nE5HLW34B7{$L zh3sOR6#KUw_SN^@_{`bC$LG0FPA$wkwv}l-79yV&paqvCB|0Yr$SkQXx;|_=Te#s7 zPm&Qb%*e`@y1e;GOna}D_|R`Amuenq1pid#J}F+=OT&!hU7jX0g6SNB1VPWYw7#uLZmz=0L>I9yvYJ%BK0~ZiBk{#OW@D z@k(kX^#S4?&-1zqo?JCHeWWiYl=nmN&2>BRlJ}6;s6!|S_ZUNXvxjXVI{S$=eimg+ zEruIph#VFO9y?#JAgZeFyHPVJLJ#XzyrW|yjE4HwNd7u5V?b8093yuV1CM)W*2`k+ zmhY%?u=D#^d~jVeQ|D=qWpnq311nPBi?3e2Kz!^VeC1z*(xLi}%lK5f2qF#an?SG% zqiJLPdoj8vhoTTB`OZKW~B`pL0=c3B={K{GBEqd=6&xxOi#=RP$}tM7b)J3hMvXoFKLB%t_ScR0)CrZVApc?y=+}Cf%cvNRFrEFRkv6GsRrc-b9UCQ*^_G0L z@bpv}Yj5lDyk_}jX?yTCW5Tp&JO5E#LSQ5zY{ne;E_?W{T+yw( zVfmWIPlX`ta7%f6{58odcP&E&w#ujH3~Bdfgl=!j`WkJ@c{L<`JnML>%h8a-^6E9^ za`)2$Z!1WffYdTJB?Yx1v7eH-o*$uJESU(3EdW~x&|C$YX=XSW3|<`!Gm`H%zc^%= z;HJl`REx`b*|s5huk$oZ(zVmydtvNM2~WG~6uqyrX7_HDWwvILhNu(5e(Q-D6;{#n zl&WoIsGe9|_u6RLZmm!U?`SpKH>o4pCi{FY7~}}nQdv%WD(<|MOmJHoYT>g@zHcUb zbI^T1do~hu8l7&-&+@lvxS!>{1pSy_YoAifiVPt|d!OF^4?l$%L;7nXD5Dl6Fa7cD zxm+e*>%hPhzb+NoiLN8>I*Y}@tNuWrPyuU@a{Uv{>JPfr|JoxZ6y>^m3UBxGzd*d= z=0x*k=uIbF2P^Q0zHJ0r_uq+U|LjfjHykR4SpzPrK%UPPB_jhXvyk4%HMp<)_g9jjj6X!= zzCY3qA*G#kh^lhnEain+srpgefX}g2;9o{7->ij>9`p*OTZ$006*!-%>zTFeK zk+~7xv&0}O3R)xAS-JIQVJy)pRA(`&w2*s3G9Qbe_OLjnKt=p(yYz5c1iA5CQQ4M zUye2L6ERP2M}3l4R9U#8@oVL}G^!|c^!WkhdJDe_+%f)QAn160b%K!7WsC5nlrU2TZ=kgv|%s4=xKHYVT^@q%oHp|8uNwV{+G>! z#BYy2@~b-mExr-qOeR~aRKrO3!~O`8 z{D-^pUvpQ43x8on@&G(%(u^L~uU`JOi-N9%NYK9qHv2k%wl|=-GyabQ9B%GYS-vHNQtwZMcASnvD*DbP zax(K4?KyG8n=Xe89D9v^dAO8-4^7~xf1;7c^hmlYbskr~v>w8Pe%IG?V}jN1iMy#j z9q{qtSQu|&%@g;U6SP`itZBQWEJ#P#h^~`*i>UyV%aXx3#E@;dk$etj#1mABm*Y~{ z9X4^cdzSdyXp$9EXK2W7LDlGt)cB=EAzO{>2!5kNrJbDW@CkK?(nY2QSZ?VP{=IJc zOqVAntM5yb)NuBMCf3m!gV8mQ)ze(Pa95$R`q8JW@M#Y)QBQ0eblEuX%&`saTFxT|f&+`$obK3}?(*b90ePxy zsqYg#-o-5n8C#O|fCEv`LIfWq|~7N#t%$E!QxsMzEPq)8Z) z{5equskggi1=76}%y1v_=75nAuWR%vKjVs*S#wyyz^ zDZ8C$@7TyuyAvZ_`SN#jHEer>*fVt*9{Q7-Jpnnfi_9Hoad*YGuTLOyi%XVx^>Nlt z?9sgXwzOSOm?UT2(9y!enU0Q*ex6&C&wTJ&aM`jY2LvGA{~l+h6=y@B!kU(Z=?r}3 zN5Z8?Z~7^1fFseiCNbq&!_sza%%9ZiHdN<4$*L1~J!lnr2 z7~zub2yZuR`BEM-VhwB`ia^F49bZ}n!lwlM3W;M#4L%wwA?9)Dya&`DGS8nlnz#{q9lI- zjiUr^EIu_!bOB!>T*9r6yic3fKfAzm$!ia9e?MnlNX~~!jS5gG<_ttXGnSHwipg&P zUvnu01BOKkHWpBpGZnUXTxS1ps~7%T8mvZ9xT-FGaiilMGhz}z6&Z8@ZtbSa+hKK< z@B3SvSP^OU#lsiDDi02Ub@F`o_&i|bI8jf*zHkH0m5FKqlY>3}!$Ed+UlW2(TX&w~ zbjd6CPqGgiym{u@Oz&2;-{*-hkV_O=!qu>E(H}AfCgxoMQ{wrvbxY~$e)8pr{PLk} zq0QYc_YpTGyKMf8u9H0WT%2)n+K?Be8TvRH;lIiDK$XOxKcv@~ibB0@QeR*@ z&d3u2d`;QNQ~O4kG)TfAwEg3(*9Cw%g}0UhLT59QXTTjVq3ZK|!>O9x$aFtDqO{vd z*M#Yx9-3=zeQo|>@TzxD(%bglmr%eIku} zJYfvXM`MwnU;O25k@=N(L`m}=3x^;6N%Zydr$6VWzv#AU;#+gOV@1)4WIW#7(cdu` z{|n01Mt)&g@Jsf4Dpc^AT9D>>a;TS=kux zG`s%lV55&PRLl3H8SykyT1gxU_KaomCk25on3ah!8H1_N?n zaWiw^uC^#%w%PU#L=Ts7txhfQ|cA_Q0|Fg;mlzUQ8+7? zFII?oacgx{JryiC*EJjxc0Ls>Fx|9rzjimjuY~dvD#a4JQ_IN=kQkai#+BD z16cw7(P`wTfF5msBPE^1la?O@=x7FA+TldpDUTaj2sele;MyBV-6%e*{2L*;XbkWVEJ-e&0y!5HrXKYHy*UWP{#3iJM{YuX zDqYw9u!W#K4#A-yBlP`@_E1smcp84WjXY9HX$Hc(%2S{z#59uzkT;|+$+hQ5WS5ER zbq!eWX~@VWQZ$Rd#*IF{<7>C~S1sYJO#WFO4hu|jGS=kn%Jx)tu(#=1w>>ppXZHKo z>-pDKODvKeCxhWB*QZ*-If3+e3THSVyjfxu%+UaFbe}V*MzELd!O?wfnK?n=2yvOv z_}v7_B#`EK0&7=W5H0%s*xe@NC>k0+I{mrlNzd*i!_|i_$rK;cagy9SXT8LMAOM9% zD7$wUTZmT0VoT6K)2XdO4Q^*b*m0A20U7lfvPpLB&&+bGU2+b*>MvTPC3sxbb@CFu znt=t&^54RxdEA6>u)|%1H;xzff|nJ9&)Xm>B=uf*Az@^Qf6$8k*<|7La{eXJZBvqP zE2uT=O7;2TD>2eZNk)Xu0_Odj)=L(BHhJ*SQUp|I3e^8R*9@oCDFch<0( z-hYpKeIykS%R9*&)<7)Jwk&b#lTJv2b3?Lj_ciE8s@9!cccpRDo!^7EIW!*$6JM>R zC=3+3z^YKfUy}ei3=+A_Zc>B^@lGqo;xxV03OUxpyni=_`%LWe>3j1md5;1{R<)zK zw$rgtTW-wxfJ`@L%UQ>SI~~t`&z$kqEBADjb8~oqsWo`hZpp}%1cH?@1MbjLWDwyd zRH5Ac^{uuQiAI&gP`koVs)5&i4a%;EyoE`X@mDl7TaPcYk})rmQmc6d+v3IW&vQ=V z%+l@f!ov%|9tQhd18!#jI4p+Hi})+pkd7s?aC1E1=6oV`za!}h+rFK5r0 zE{4^7fW*Fr!Zu-FV-ZZXdJ$!PHKP2dHukEi)bajNHBC$TDGrGxfflc(}RMq`P@E z6IC%a^0VNd;VLpCOipsvX_l2}M|+>FP4{k%`#%==mYSEV1TBiV;%YO*(>( z>q3Pg*H;N+-lo;l3$)7W+n?qi!Q6X>WwEwA;(||_mL=Agoj(kZ6b6%)4=?}CIlH{i zY|iD0+Pt3Fe@jcNe+1A3Fj1}?6B+=EFu@(D*iW~hd(fk-F(Xd`0F1|gxBK)@i?#pX z4rl&PzK`5JEc_pLcld6Be+mZSVJI7m9a}(zCZ8b&4ABf{%B#VDp*95c0hFypYLAu3 zBFq5r25bsV`A?LWe-=rLQGTa$eVsv1v4Y6ghpj!nI`hlW&tW4FOb_^T z(En%5lv(fIfF6z=TT>rG;v0gl?miF)@ZI$11!zLdJ>4NVVwQpGuQmpAR^!c}Lswpj;^ z6unqlr6*p~5p(h!K~V@6w5*f~(e~B%5%ytv4<((>bsH&Hr3 zQ^L|JR72|X-Oi%H$2=L!edbqP{}8{(r#&J=Z>yr2x|kWUEJ;yRgZxARCUOTUZS{DV zd?`sd?@K+t(u^2K;yR(iIQe!pyd2!Wuwq7MMh|T|?G-AIIv3gZnuxP0ld(A(+h1GP z2uUd&u8}@9(i`Un&sx3hrP#3^t(GE)=0WG&pW+8sMfHA=SRLakRdqol<|KEh7T2Kc zeUp8-xTNGM*C*+u*BO&2N2|k^x|a>Tw4Qy)YC)XWE~FcbK3z1O7>HmS`{=?$=SU&r z6Rah6-SF5ZAMo3paDbAx`MXDBg=@)t2|^fttwK=$=flFw#YktEqt#ED~w;H^+UO#m4jhzOJP}Ep{UUYO$-4Hd7}0rSl}Ed?5lo zQ@8P_2nbZKqsH600?LA97Ek99qdWd@s&}{LF+Cz~W832^ijGIdEhvRo|11BJGz($# z8Dpy`a3b-IV8FMdDRt4vPAG+840!Xb`PHJUG-X$kELE06)Nr%2jac-!xZt%;bVWg< zLFQtg?KS&(^!;a<>@=Y<%6|qy9Uly4Gce?)dS7y9TL|a!P~N_iF9ApvGs7Kk@S) zbK5<(6EY{dq6ehj&XUCl`&K4D7oRF43MtXWt7cQ?BybAL(OG_y#b)CwO`CI$df*-J z;jCYEl*VVRT-8^6wgHsFV9ER^B?{tv|4E4w$j?yjDf&PbPl{g+i`v26Q3gBG?LVx9 zWdtC<6~%7N^J^hTthVw|YqO}GcJ@QbIQUZ0L@e|&|21qugcmBp^T26*Gp+~+?{hFc z3s9Hg)_PpVl^AWRC0xRj3M$qm277C3raQhk?)3Tgih5$_D==*qjC9p8uD&Xc{j*ZlN6os3UK5n~ZP zAH|LP&zsF*KrAi`e~EnAibD{Qoe9B__rXM-Dr*4dY142Iip%6N@V(?u6rmoooH(v! zDh`8}1VgWuimQO&yl5s}3_cjx^f#}#D*@s&>9iN4?N^Ie`N{Vr-B@Lr{`vWB*Qkqu zC-w)U%gjD)2=rsmtfW2ZRqaH>PiyOJX)dz+G~L2$%IU?G8XK4I8kr`|9?`z?K$J*R zclB-Pv=frJHc#t{?&ny~4t0y$1jRFZ7fsZNyd!&jPq!0aG6rEBQrqwr;v~eK6`m~D z;H@imH@q8BVD%Nql0tV_DM+WCHmgHF%rjFlxk3INsh|)GNFqs7@KC!~(1i}vgW!$A z3|tBS9x`m&1&(C`L-wY8GYO0AnOHP8(?Fwl(M({nGd@|ceWP?u=LtdJF3dnox`e53 zt+V0XrXnW=>q(Y^&08mbFop^tE}7CfIsm8OqNiLIUg@#w8^LP+&1vJH;0B&Y9^yG1 zMS9?Su0*kU+1hmS~ksA}uk4!or<*(TQaHsqXnl6T2-q;2E^wZ!R*_%Jlp?lC_Ds&m&lB5RJ+Kn}Owv1NIp zfXp;ma)-s*|1j7+{C!@8m3lB?(#r}qVKu|-dxCQEe*0=)&jqVC$5k%9a@zZCc3PnH zko+B*6;f(P6~EaB8XN%hC%Ow714@A|CK8@r= ziKNYM7+%oioh4OzwkkEPvr5e0KJ3`hxFt$+qcSrtU9?aX9;e#CI?sjuqKq5(X>qi| zOBTDg7eUGr3DKZBMV-MC$IQy`Nv0bKc6K_$p_96SdtNxK-D?-F+i}YZ^G+d)s3u z{=u@PbxjKvtC)U0i)z8nXd3P);xGq01Z$||HzhiLO*?saZ{5V=+FzIXzlk!)vvq%Z zan|TGJn(Symbm-U#wOFv5pi$PF{Jb^gpY#dC%iOg zdtka<09<9Y7nx35BtgcQ$;~$>AZJ)|G?L%Up2LNg zuvJwhGk9Kow^RpDI~?i~wug2;sG0B6QRMDq{HiG?G-EJb{j8B_dI-wjF^GI&-Xniv4s^f<9b^*)O8SsmSrjv|qy9>A&rIXaAIAFs z3y;4NfJRSba!2v09$?avXkB!^zPxCyTb`I8_|HDxpPox~>k5f8pf^wuA7<}C6(pcj zmi0qt#{qF%7LsKWc5g`RhmLaC$vdvdbeJl!!gIr(+3!FM!Jp^1TtSiG5x=g8nmzVv zsP*G#PkgR7&sn5y0krf>*CBzBF3ydK5Y_PLLKVtA>gtAtZ;Cexw)ttTf8Bj#pRNIM znn70ak(gOZ{ts@(fr(Ch9fZpT@NAl=ETiO6Lf*xg%f*z;yms~cyXmwyHTpp2GN%n8 z71K(V!RZ_ZJ6B;9GP0Y<6K6z{dO6>T(7Wzed@f292{@jZ0chfJx3W6Yp0Sj5OY~hz7Uy%L5_A_` zlL}p!AJ<=(pGc4h=?-Mq$S?Jqj5`05r1+OP2G|UxP9Rk~igI_=w_e|YS*Kwc%+f-m z_N@5ZPp(!5IaZ}~ZK#xU>!lt0+F5;vfGGakL&7ZnN3*nNa~6Oddy0$c;-=GUhudSH zwVZ8vpmAS+Ot_}8lOpl{<@Wqm=MI*O@vs>&bayZ1p@lHXxtu6a(`Sg5MW9Dfjud4! z(pd4GsIP*KEq!7egm909Mwlv59l4C~JEEKVvNgqP@7uX~PV(Dv#5I0O+>Udi%s`)> zb-89l^p|xWdni#tj}+l*ZsmtUjt0fL;k3g#i3IX^^lQ8JjwN#^pHUCq9yi%a{gR_Q zFcl;*a0|?fy5;fNYkVP*e^cHur8pFyBg<97BYn$=!eyt2@pTqL6D78;X!h_061KOG z1;Ih6J{=)qe!9;n<2o#9gqzcZVqb||F6A8h#l8fN*KVgY2rCl4e$r0B?0MCt6!pCR z%z6o^c*0lY=3H6tWg4DQnr`7aPc3lmhL?(At4m9(Vb?^^RfI&YcKOMEQzM>pNU>V# zi#6?c_>b?ErgfOSREb}?;AO`CjFqxCF5c$ri@k1i)P+IJ6D7d`^^~dv*1H2j-aXAo zc@5%>jO$V)!4)h3I^9=-zquj@{_#Ue9gHlL4+Bs6%B4Umc>;sPZj;K}{_F33(?^+V zx)h`IkS^R}3W*#WsmjEu<;5r6>Q7?h<)DED3r?ZQ^Kd)zp%DSDQ-@EDxkD0koWA_W%FnxY;I7q7exlH^M~5n zoQYEdfoNQwktjr;BARgqGCV)ky+o;tD$kpp@6Db{`@B9L zC(bCB^Nse@w)n7AdCIm9ufVOVqLTAJg3O~)All2Kg6RqVjVO$z#L$14WWmGHpJ*R8 zC_9eG-D#tX%Tx-M+VHHcxUe9CJi3|7Pj7A-8s5PhExY*m;+l-887q3!4={Na|J|gF z=swniOVb65saCxBOpb;>n^Z2^X~$gtz632!uE|T-SyS2BI`nDpWvqoPGD5#i=s$}N!ViMpe&cc z4{k9va5YurZqD>L!cJ>2xyH!WTso}nu*z)r!)UP$88<_;lA$~@QWQ#hSNpw3{3XcJ z^hp?e+C4@B#_qJoq6pedsv&nY`1DgU$H|qZ0+QaDt4JYj?^l#6R9tU0mMpmWoN$=0 z_!t&D6|W|JnT3TzQB*lV_|szJ;pQ~R098;(IrZSG%tyLcK&s7w$Wy8x@cKqrZyQF( zeglZ4WJWv*tNG{1)()03!v4f)P3`e5vz>+Ml3Pp{Z@i5aSr#>VIx@?TXjv{l=y!N! z?kYm}e)iS5>L<>U-+2ZiPDtwu{&Uz+zeDfK?OgG_SW||dZdGAIeAmj$jw{O3?FYhM z%*a0yuWC@WzAD^d1kx*Wp3OcUc7 zg_=SbwSZq;nRwys)qZzoqr;Ym3uty1R#r}zEzFU4_jQo66$ox9?049Y&-YCf)Z0Nbf=?=?BfJd!28rFq2%MugVX@hllBaMBW2xF4`N@9q^?TmDqi<=szc8mb z*l~Q%W|!N$52#qqy;L(d2FMb%!c3T#AG&dT-GM?vnf=MOZM2$_hYA(mQw_MorT8LV zbr{mUvg!CYLhflDLwf;Zq2^&)>M3-1_C^c)LgtO#?zFb`A zXt{;86mMFnSDH@$f`lU#M|W*|@4I}%N41c%5u&=A|6vRN*KFYlIxX%EH+Hl>%&vl^ zhD-YGW*k+OEC@|^dvSD{rjg$M1vZ+9--U3q`cBE5=xWkUI@fhL*1!|YXsI%F#+=Lm zgOT1fuQKnnsciia(zg8CYm=`_?`{@fH<`dDkc@v6(fe5gB2R4G_fO#eFDpAJRScn0 zYL9$)G3+qObc~g~zh8;fUZTc3nDctb>0;G5bh%HW{5 z>{U4014Jq4fG_OTMqn#mrOx7Me2g-k>SwX1dBIGITcS?V`fmPS=R}#)y3oM5S_(aYq z#K{_!pjpV@_>qumC;!??jM!3Is)edxD;949#r6Bvc8n9CyR7HNjSf?Kyz5G}(S#Y&b?Q#npSP92c zZ)9yNSeT#cWmX`iF6et5B+plLWgU!v%R9z3?LLT&C<*T{_`n%?74e?x*kXu9#Ek=XvDOp#t7L z+Ps~wEIX=q(w%r9OUu|K%7CpFiKvlW>f6S992*RXVjKO_I*h{fi%xnUOt+6bqt`H; zsI*hDVyo#<<%^TVClRE29TbHy_6jnwU|2M35YCn<8rlbe^WVg%x&iAAfJbPpq0 zwG0&t>U6gjUl*f3&x+gptXFTd`#Tn<3)w?ODgdRxO(0Gh8c1EA=|`?q)wy~hUiI#^ z6D^~AqS}*gAKTs>s25WkuyIBg8qdH2>IcD?Sg7#a0m{G`R&|b)JB*R%%z>EYG*}r-9r?5rg#MSzF;Oklbbo$XNNaHPES3@}5wu@oUFg*?YPh_is_M zc@+P8+{o;%id9rW>17r3@`6(Y({TX3C%cEo3B4#Lsq~F7(?X~nD~~itnFF7AF^VPP zz)l|}&U_<5mtuX1p-Hmg)A| z!QPVBo|`)B(B|Fe=6(gn=-eMi`W%Tt@+j57IjM)H(C!HhMJ5``Y)9HJLnb;W z-OkUt(s4O&0AI&U1CtTZSwoIoB3Mhq3dV)yWaCJ6%caTa;TJ&dSm8)btkNd$s>53 z=_1i(*eVwhX_F;Avi3=&idA+F{ba*c_pFx99v|_4bnA#oX4swBQx|0(A2>5hjQ@`y zm?DMzX3&ImyOYA|v~O)~EgMxbGE$K4E{qmC>U(tV(u_bWEy5)CTBMteiXpv)Q~-cw z)mtY#S+V|RGFapCQraXismC!uAi*(k-zVBehXxA4zfI}nhJx#=0p<)`SH^Znc+1az zJq&$)iCFq`jPTx66)CnXB7mss3%~>oyD)Z;kp&y>he;EDu)OIO! zBG(@kCMA^W3T9;kZQ=p5mn2lxf}_!u3!&F&)oMHj+I_73bIk0op8o=3Tot90c@(hG zwQwYr;EfdiTEM!!wFL05eqb7Tx096w0I{DJ`AOlGbtE{@QnO$Gl8|hw4X0-W>Aeh# zhz>|f;R*KS|A)PIkB4$?`-ewJh$-2Gn2J&%MN)P{vP-2MLQF;3C6$E8B?`&DP?XU| zDm2-b-DDpssgUi=P?YVA7#A~ht>0nY&wao5v(|b(zxDp!_kBL^AI~2vExF8jotxu4 zj_>h3z6Xm!>g^ooan?Ejz?$C~Z@7%+<*z7T%&L#>GRzWu^(yJ}nYQMYX73)nj#+wk zm16On=1^d4Smm^|L*WGHmH*=Qjo%IGq(CF3bCx|AaDfN6oY-Zjnpk8 zibDxmKo7VO(0lztDDhs|U(^lF`TXhG%4`agqLk zm&#(t%Z#_ZKY#AmvV+37&0O)o2I!}`>7P_`>`x?H%4kYO{6PE|KT~5cGEPI^dXN~7 zh;r=*_F0&1p4msLVcV6a8ak+XRM{(S?l~xBW?A!;KNO~c^pN@rkNR0JBvs9R{Z50) z19KMB1|j4#9=J9DkqAQ!DFv8f8jcH5SvWWu|EY}VDF$pwE9!OP%lHP$%@9MTSVq1N zCD^^)jPin4GTRy^3@u2%_pERG-r)Kw`K6Vj(FaMspYZ<3X?z5&(BR1fALj5IMKR_o z-NMJIZ75<^`q`G1uq?t@Wb@R6bos*AMumO;NBFqbf8`Kz5?KD+6(qJl3(%fob$=&R zh8cOZqxj}C4WG%$V5JiV@5iRL2Chpoiz+PNs%C#fImud^{FiTs5k~)lN8C$fj*z?J zvDjfc8C&k)zfcZ*5Z%dCss`HTHK;ShU(?s3-xs%vDEB7r`n=}zxWj3Yyfty_Y&P$D zsveV&c}bFQ4&Z8`|CD61o1&2V{Kq{w@}O2&76NWujTp#KVTu-m6%{mEFk6ka90G;Dclt`wRPL6i@A6o zdO9LyDNy#@C{(lP|&c%y33!cDTNAj>r4QeSNjhX?=kmd1@E# zG#|5Gi_h5b!D#9B!5zxW@Q)WRM$`opw*mXRCipUhDIsv7XM1hJbaOcUXgag7mMB+& zzru)L84zU3vWu883j1Z%KK7`hu~!2? zS`j@w&UE}K<9YT#L*w$D31|8u^c*+sXdSh#*7(X{5XU}0r;&p7pnO7O5zRAEO(s=t zaky8um7m=G=D3d!Qw{`zrqMX}FvDA?(QxILA}25Fg7%^-Cp#SFIr49%gMz-U+m&Rh zd`6^9H{aG)V3~zJsA#SuWkKj}$9zMnh)d{Y5ey z|KqeU0$+s({)YZ?Cc+?J(>L*!uNTjL6ma@O!<6#*;`UQ<+Q(%r1^C|r8~P{(=F|s> z>!df6=*H~pW7EJ)2oWpo(72fF`q?ktGOg9-v++(7M=W@bxbO0hm_K_vILQ$sP7hn z7OUlWP}uXYV&EwRy3Ou&8#L!dr43{0!xY9@YMJ$)zW0yIw30!YTL~kaU(o#CC1pkl z@WRXth**^iR8?HZA;H~t+^})#D1g3eY&TUw2)?@9XZ{=YtqtfCdc$D9`hfhvJ=#+5 z50jeKHJM92%t4{4PyILgH_w`soUTEpap?f7ucwCH%}kP27v6m#B3 z8l1z8!NeRBSs&CiWcAO^!dHX~vg#UnaUli!WPXw!5?|`n-KpA&)e;wT?U&wM8xUVD zxBXGVSVUWDs zoM9w?@jp?9|Fd=*q620#sO}8WlNP2?T%vPrQgZtaW#S)l6+H?KQ{IHQ}?wiU_}4oQRL5UC~(0rEq`cF_NN|gB%8l@ z@~;|L7!fuB{P8zh*x9xJl@#dzOyB=Z-=8}K{y*D&IjmB4H}A<4ULnzo6h)FcyDflA z)QK;CHk10<<+YBg>!~wyCwDz3DVCdEQJsf+)u=5X%LR9ioFUj0Ic!*6YeR{qh?@Wu zPPoPM z@OOzcA|SjP5aMc#&YjN0kAU!b8(8;Bt~sv=a(;1y6^2AKt@c16N(y49Ru+FcQ7CUif~kZp{ed!`pq;h4!`Ei^nb^FdhPBuh2I)QG z`%?6y!$dMvH>}N2hc7{M$La)pH1&_NlObtHbv}VI*>FqKLk>n2tgMV+pa195=gU0Z1D zB09(-*CT}>Os6%d5mSMujD*OrY;T-8u`c3S_PZ0Wi`>5CDV>bjDQkYp@SWG354e2a zuuj_ad6E>7>9-EqM`T{0a36>cb^^RV$ouY&~41N1xSeig@K$;DTs zU}ZvJVS~8#yihnZDWLUW5MS>j+QJCR3$pHLxRbO$=}MLAmG$Ee0|t+Wq&3B2&XE*!|FI>kr&IE3Z>ScD0BOC!hn3rpNITh0qUL){*bH^%D_4>p>{)+ zkY;2>h4zDPUbzDce{IG|%ev&31hMGYJ~y@V>xb9a`4+_F*EP_Bb+DA{fx>VM_o;j9Qk}k2?HD#i@V}9jl zUUtwqGE@JeHu$+*xtpBBCLGAkR3$zN1QN#4ba+($xU5 zQ&yX6I+iAMO-+Aok+$ejzd+MVFDjKLV?p5nbwg`4}xAEaoY0bDpu+2V(G9YgTb-S{m=d~Fxx)ciX#LaB()N_X1sxT z06Xv)J_`Uhzj-iv0`l<7`bMZs`z0YNhFNq2VznxhSJbw=|-lw@)PK6 z%5Kx@YWQHQeLUxN!G0m-TVK*}7#UjNc4ABCcob|?NE@wqvff*-k+xj_6eyHgGlTuN zcXU_fY4>iiVt-A&{3xHVBuOiVp4i*@3by$mp@>qa(N#__eZ!$dV%u5f;hVMh`5caB zO?&Tg)Vi1>AZRjnqTEA8_UEm*C!xgC?v!tkqJ;Sqlmc}Z0w!{ki8t=7+8S)pUgYH1 zD0eDvJh_AFt1NR~yCx#`OO@==b4QrQt68Ma8eD1q1_x>_4P7tODCT9{t}P~W^mDL^ zzjoG4Y^`IjY<epTMp zDxs0ItnvP=XCoy1w0ur^`Li^Si6>Wd`!XyQZk)b!(sH5p&Yl132FhS0CZYrbUX8-e zLwXtq#S%ijFD>1 z3Uf-pXub1lR!9+fnV;y9%J#``6=^$c8~3Zq6$$%uI1DP>p#%o?vC zL=9_&YCF8>&k#X05ySGrqf4uR=T9#3Ss zu%qDxBhem9;NQf{2h>^>G6mbeY``HNs)K_E~~ZpzI@}KS9`cn zoH|B}?ca*>!CtIsoB0jL54Dtv%R8tH{m*%^6N$*Wd#x)RNYb%snxbnqWqZ7Be%4^5 z#FS@)kqAr1K4z%$3agg=yqwxVxlx)1V*O5X-6Q>^t>lbkHok+8&}8C6O9O6 zSyJB#rE#wTjr!_4xIODhzmrFI3YqS7cBo^b<8(xj{bB3-Nfvz;r~HmDISyqfs^}Lu zTv;KX2-C-^HX;mjzu(0!W(7@y>tVFctcGG1NLn0Z5}aAmIZwUP`g0iaRySKXqY$2XM z--+1w!?-&rE>exXG7Dm(+>vUOZ5B15hT+#Qs}Xrn1t1XWX%mqYktky zu_IY!*cDYe_2!Gb(<%K!G}DTdjVCX}ugDd*xgEDq6!gQL|LH?&loJUPiR73&jC3As zWHk;XHLm*boXAirqc1YTbg>+0);xJbaWz^FD|QK09Uw}1U8Y2Fji1|lN;r+^CV%d8 zI+pm{dDCQKlgo9RgSXxsSd3c~YWVIU^)?yZA;adNeN2B$gvJW0#iY<;mT2v~LhSUS z?wUrYR}uZa^6sy8F=rCJ_9P_Dhy(`h)`AIV~>%3s_F&B4+^wH#gFLQ9kBvGFQG66E+gYP%aGibQ~bTm~) zx>RsmQ0G2Yp|^LgROo8PZN*G*YqOqGVh}n*BdUKjY6&yqhqe!Bh{{YUcZIGJUGg2WaeNNp+Jvx0pZecfNTeal7j2A$t)!1o2(;|^&MJIr$hoLaBX5 zw6(}c!Bx0qC{QxES^Nlp<1xFoqTkE)g?6&M82IZ|`douA6)Mop$sOCoYJABO4|vaj$WF>$PE zzUtA_U@g>zj_}bunR%7t4Uvy(Pp$jn>Ay+OEVCeDXZ4`=kBp7Xs`SD5rJfF(3tc>( zyU*9>mgscY9TYxZ9(H7-@*$;jZ=35a^p{!WfP~q5ggG?XWsb#m(xK9#gUmJcBMSl> zg33pP-KkhTK*4bpP+$6QI0=V(c%#WY7bqk({%?u||8nLJ zvNUdNgMEwo9_Y~aYVp>w`jq#$qN4m&g1K1k)@Omrm-H971Nu0z;5mpduJKYJRaU{( z1k>3|8Z;tU{8_#NLfXIebD!c-HNselH8+(KL5wSvK|cz8l02kzLsB!LxpsBjbP>*O z*p0gijJv>HxTwQ!VQ)VMguh|Ghu9&WVP%VIe)Up(i%C^oK)lDvgUJ$G zDQ&udv6o_E-{GmoE*R=w>ggsya64m{(mu;&^!vl2Tll}F z?-VI8C%0`{0K3D!Ak|`3YXhtXd5zApC~bbMM6%CO zXjuCdFWa)K(d*P6z0fP1e=WyfEzy6&_ee0_YFmV!LlB26;1;bg7t>_j9(@)Nen`R* z^{Tb~C0Nlp5lYxJGsW2ZEa~JDBcocqwOUmAb1*(ONF?;f2CjGqA{)@`_r-5~x1|q* zBIfu`dX`iMplD~ybqr`q2XGIgE=^jH> ztL?UKyOdheT%Wmqu}aJ5!#m@YQeK~QO(@u^6{>>?JHl?rUC{bwQbg95_dBIa^x=Nlf_ z9651B9LN7sa^zphm4C(oC>|35z(q)myAf7*Kh~BZkNOVAF9|m4oGgC7-rzz|pG0?8 z-q`r#H1{KTUH5kdXRqEk7%FvpLU~-lZLAy~U4p$uipgE$)5I9)g^1-D3bB2nOWk!u zh953|Exa^#Tr&Pv{S{Hp9;|^ZLOg?r)jsAPM*SHCMf>hZX=;z|89U7`pN3xoj{_6( zyER=-sqm+9ufb^2k?IO6)0%WmIyH5cCfmtA*C8Ui=5rQH+2Njg#)T3Ywb`Wk@#uq% zXYb&6Ri9=YoqYF4Of?VmPks0_nCdcg3y2r5#A2 z^*C{Wwj8~rvbpTZ4ezJurH=8dzu{6!WQ1J8JD08sN#=lOxOf8gjW5w_vL~MXoH<)d zi!zieMQ<=iMnns913HM}>9R#yQbh&3J{@zsR=no>?wc-V3NfJ(Z&!zgO#V|5rt8$v zwI0f+b{pB>jazi}%PrD&tO;Qr#dj65zoC)OP%B1ceY`k&v#$FHWyR09!lS)?XFd#< zSY3v4qK?7n9 zwi7kq9P5|WO%h%cdBlranqU9LwYcKxnU9ao9JiV}EdP{$-VEk865b2}whFpFK6Z$i z8dtIJxtFsJbbwc34o8d`(yn;Ec#yF7U6a7xW)p!Vo0GYDvAM!bAFwur*K^1RocrT?ki6@e`@E!vb& z^Ezv;cbG?#8sjrPgrCX#6y02ZYft!@2!oc2MT^ZCiI7Qui1Y}tXHZLyAXh%Vkt(I{ z@g%^d)?ZU?`{8A?TAmjQCXS9jh}w2*D=Gckp+#YJ*9GERf54`gLb}#)y?M7UQe&)K zhR$GJhKj`;abjhW6Ymj$-Duc8=Q0TG0!-LVpP)O%f@>rc?30D2HqwMI_MO!WQt;i= z;ac%=+rI5VQB_@PyG+t0T=u<-l}K@w-+gZdCm&pb#iLmLtzaFWrKN93BK6tVde~WI zV?49s6F+?eN6-pYgikAQ_TkoJ<8T7X*RykIyfAv^Q z+%Zeq=(0R86W8yWZX|J%nkDxiX03pGe&DUXAU)5;sVr=2q{lQr4Lj<+M(fy~M6(Yq za^g;J4=swbTzz11mK16Vw!NC=EE#$Dl_NBXtJ9J8Qd+W(T+ggkyFpIAE8Sj`zp^>v zI9}GklL|>R2EhC}3sq#Izy_ET2_*))Q>rOwoL(*P%+BhzV$%7*_?8MOK&m0O%q#;9 zx=FUt$B@nLh6)`Os&2W~=RG#xf2L`vtYtK`bGyYoOGWynD#?tI?6skWS1C1s5E|k! z3*s9B2MttT+FI>uD_ByZwE?oGxFki9+QgfH779s*+K=~N0yT-tF z9(Cf8-%ka+PIF2R{%JVWyFdoP&8Gd6z4Y&2F)M^VPMF(g9Se}E;6va`EcN4g*iFH8 zCIoqnX3vG-;kddC$fUYt;xnoACj6X%PYj8zYzi8~%+8MlW-x)9fP@m+gm&t5Mt>EY zs&HlEx0$M~$k#*}EVY(ogj6$;DPs%=oC3raNcBONaomeAcz{Tok3ox54q=+Y+pq@% z!%;$*x&dfBTcscQv6gz<2VIMBvlQz_ZsVBg4NJ<8Meuc?-QBhp{lAQDspk ztT18tnGHWtK|lisYiaXmN-2yI>T3;jeIxf#HeH5y3y8%(3*d;x5zvh^?&AgFp18DZ z>~<>PcQ5E@{{+!vtIlcI;fqhg_f#sZe#4zo zISd05+a5~PL+HOI=PZ4~VG_+t;G5~uFqFmcuFY0etC6mq;3j^KBiq0!|2sctM0kiW z14-P6hs_sA_F1qh>v+fx!b=S4VUi zD5NGjnRZy?dpwjQErT*h7?&XImRpM!0DV`EGmOTs9$A{qdk;tHPsL$4#Dm1#6+dS( zJT?h4>_nc@<^s{b`YiD~h%vkI;>)tJcu(vZm42Nt71;`X8tcl5-@NARVZwTmW+%kG zl|%5e<|%&R<19>=2}EK4F1I@bZAJ<)>vV<;FABC@wrJYC7q%4cwOfbLJ}9#|MaB|4 z-%*)CZd|fXjRt2q#8vxcw(-%af8fio?J)5%U=nRZ!?A`~0x;dRL$s0VEYeh(4{U<3 zLJqJLDwHk|%PWL7rvrG7+%|-_>I)w?FIWpO{zR}19AQV~M>}Prb#RiKKn5rI>tYTh z!oE=$S`0Gxc05es*F8NDQ{^F-5CZb;8rq4y(SdWm4u=R`h82kPK}O3V_AsNqq@de# zumjhjezN8gw|JIM;5F>Di|Co;IbNdZPfXql0@ji0$&)KSf`)3>y zL=q)_yMy{*)t6}V8@(>S43S2fwlZlvp!7^1>X`Y<%ANlzJsL?*W>!zn3}VV<|bitP#|R(Y#p#+PU_ zO-MqH6bbB0f>SB)0_oeP`rij8g>vBJG{e4@Lmyg43v(PontTEwZgQ4`pi9 zUwcZRvb}(>s4ux!`C3@%o};7<3W<7b|kBUCRIB<+$H9%Y$u4_bGBW?KcdiUeO^W>t4+ zUr{n&w4JqL!@7yQ1hFS$FBrr(_d|i$yjENwsoP02a)UQ zZ&)&smRs{io-OI@@N7JPt%Sef!pHpXu0wHjLdZXz-T&^dcJGKx8xp#SQcFSC361?c zKWHucp)8{Osjxa%n~@V3){jEF`%4tkX36He>sLSDxC&A+de93M7UVGM2lMlQcYm|K z$Dq~qFWT>o45$%Y9iJ_Zv}H~>@%qt%e|sq8ILwF|m7YSB0GSF}(KS+u_4qBx)C~Db z*H=vQu+3}T$2X5B-!yv9zvBDPrhARcTaM*xTG+3=`$ir<<|VA49oGW>Yzg_a9P1*K z?7rX}aCYX?V6~y}s~eAsDoSkC`B$zaYwX`Uv?I>p`;DYsZ|hn)#R41u5XF6pI$`B* zyQ9q|PFv*pBazIDxXb_6v+CaxXZ%w=m}m#{C=2!Uo1OYgSD_Fg78&|l(j}l<97xV z16jla>9#wa8kA3pJxmBWCR{W80K^?RVjL(Zt3nD0V`O&VG$GtjzO&ddm@uv(8PWMd zw$WVlqVtBH{tcgn(m3*aKIK8}s=S`OSCF2b>+)KGSCS z?y_`DG@Ug_;+19bfcfRwqR_wH;)VLQ%0m-P>e}uac?_M!9b=|Zr!3Xm`qm#puP8bAQw{Bb(S@rI)PkiC3!*%u9kiY8Z0{xvrO zb{v>sKz9P(OLUxbn5)T4z1Sn#dIMRmk7v$z+9VDXq}E;jUXqd;7b_~;?S;P zT+B=kbur>jZTKcYMFNtI*2I%CIBnCsT2RnfAphqf4ly2Rk(DlZt%S(w|M7zF#(M5sc`bCc{o(!Z8@ z+3TfQ!D*}QX>a#uZfV?fbZOk6Hn#rZF>qe~Sj(`J z^Lr(kl!3r4IxR~1Cyj8fo37i~DEhKwFyVDf>j68iB%zjC#Lj<6)2W*jb!c2FkvH_- z&_8;oQuL7f`CsqlEU$aN!Ee?IJ0J&9VAwgB4hutYBdQM}ZZ0ehMk;&SK~3&nnfCW5 zg|6y8XEfHvZFEqv@sFkY>+dVm@v9x&xl{=1H&)%{SOwd{Q3ZM>KQB6%f556$G{AGN zs6}DVnhPHtMoQ-+*8O@>aw4lVtZ#6w68VmWk(wQjP}MJmUe65p`C@V83-|fz;x%s4 zI*Gl3%F|*m?^ohUd*+5QkzbreC}cVvIZ|E(kzgH`#4IDPBQMCu*I;`4_<8XM0;V_Z zd)Jm}?fRCpN~b?obLA;(I_ScKl!XUWor zmXe=0?zP_3$}j3~Yt~?l%h`D5^5z_Hmjpuk2~1ng6+H%ZY?z4+*4nk4@bP{zQYBrY zBUA9fMO1By^iEn#S0+Jg{dQefjeC9W{4?g*k}SAHmM^pd76`BCEPfhnL#!i2JFm{S z66KxraxILmc~|!KcxkElSoG9dY5z+a-`6j~8S?}vZzs{!!(91Eu+QSW$J+RKntauI zOG>a==eG1%Lnp@$vd3tK`n*VpI5N^~ zvTO4Wjn7ZJv`_8dtTffP(#XDWU-l(|n^pnd{n^2+t4q`D>LR>jK z7|B&t^|_J3_X>@TBrr&RUg3nG7Acpg*d{nkdAzO;ilZos+1mFC?%dodk} zrmYAj(5>>$X&rSO=?*h7_@uFPl%RG%QFPENjd#zVTYG1sMa}a=tyi*mAQj!Y0uz>kZU7?S zk_$SaqB#Mi>iPas=BVArTzw77sGM(TnTYB0-WET#chxD&)F;{#?>e40<2(9diO`rE z#0i`O+#S3e{ng!&YqwSiuxoVCKckc~y8FvOr3LJ6f%KJkdcvn(33Zn@V@E+)lvZFK zOQmffPR`A8FZ&ZRav=}%uS(Tv3Lo}*{y<21lfLKh zJd|#-9?}>(W8Vkjqi)$Z`FSzOVtr`rxD>mhNie5(W%UnX;TR5-ju4=B6%%`n$^(Bf zhDoU(7ab4+{M0SzMzQ;ZzLfx**_iD$QJ@y#zI-Tp$Jw|g-kFcDhf6J8N&UG#mZQ#< zWho~6AlclVs0-q9DeUNG^=VPrlXvlEwnyI{zhYdEz-7eT*NU#!sH34f9}Q~MTi+x} zVq5!vZ24i=X0om>Mg6&za_1sT>5dNRv~8s&*QL(!HOSi7O>U`0eL0TY6JWUQsq{yP zM3q#R*Cj+!UoX2`%}#fBs+Rpv-CMogroL`hzHx_y2PMoak0iAWnGY?qHR9tLIAKlX zC1=!KGmr>Gj1eXY@JWV3flaJYlky!VZq>I=AI8d}bY$t*`pg&i72}ug(%bfOiTWXJ zy4nfD1CLhn1+1hDeQITcpBI({y)FC`XaR!gHL zpBUPF!Dv-yfgQBUBM3pQJ%NtrMb7x}R7x}P71RMGh!#_^o5PTJuzQ9~X$M7)orhmc zKvm$+MF7!6Vv>{bfPJjOi}1*tBi-G{-l%bZ!|60PrETjgZ@M)xEDzQ0NTeKgl}K-x zoD;$z1pHh}YdMsO@1?{O6u9d+n!!q)`hkO$o_KN8s`lK?SgV6+JC)-)G)JyRH{>=B zom$1;QDqJHNIXREq4!?C9&QXqF(!}Y!od^3%y$?qPu!d}T-FXUFM9#Tj z8{SJpDWrOLo}n_@>A>>Kjxc>UzfI@YU6)U`Lt-AT5xs<&1LMWl)U2*KW#e4G@k3jb zC@4=^2g%(z28}BPvZJw1!(;6*v5$CnkTV)Fx;~+Xa$JWtuFas>iS;uGKoJXY zv0khx%+J3*v03GAjk$oks8*rkqEKPw=|$8n3-Gv5NJ!&lp(qWtJU@KYe0ybX#I~ve zW}9PBCNWmvlll73SocOYh=h7#`w{w>6DKpE$}8Urw>-`uumnPh<_zD z{~a><(IIb%zgh=Mu@#BPlqrF=GJ6bg8+}X_VeEwQDjyK4rZQdGHv_Ygh@*KV$Sp0eDGMEJqxop*+~`EPsxU4y&a zvDP6un=3_O`z1LU&hPl#*nQ9~K-R{*d&RSQ#D>arc$?;fD$h2yo1XSTO(;9~RVJe6 zv@j(}UIH>quJ_@ptOd*?nmDl4x=RQPfG8;Naa<3+g?CJs#UffJrQU5kn z@9~WZb5-YBcwt-WRXlb(|glc$Gx`TjPahkFu&yj{SsIV-4-EOEdb?>r-5X zT{c+H6DosS;V8cNF`Je>-o#Ak?(XdsV5%mYe?B2Ty~8 z!UQ05vE_M}Kmixyjtf(}nji7RIEkcu8q;6!c6TIqIh7RGFY9&-lZah49xJLdKls%a z|F<^NJA5r7>Y2dZ{n5UtXU67>cgxn&bGTo2x9X9LG{xk{sO+HW0sHh_RXDy*p2Fxa z(%(8(jgHJ0&o&nZv^=2|6n!w3o-me=FGff-rgw~lBT_A4C}6&J+l6%zk8^XkG$X~7 zfVCCGzw?Xhz~>S*qJAOL3yE@y{S8yDoGY*TR;kqzPesk}e+)-Ef9h~o&OPb%$Pj~^ z_v_NMzV6xDT1*d$t&2;0{#^6ueTTO=p*)0;QYG20^g1?u-xn#HtI9o9xYke9XV!mj z_w1{Z*+`0TRuDKIyZP&~ppc(lm#Le8!}$jr2$9?$%p{I?D6I6}4nUAjQN`!8$r2`#`L9L`cCSe&SjDUh6MFsEEj|9l*pNEx)HxQc z@%Wgh-2L$<_fNQIxX$VvR@+ijl{;p1aAF_M@!=~X>PdqE&PPGt-| zV)?UO(O8B7;Vss|GQU1!u)d`g*{oqW@agEI-miLgzA^V!iC`y?fn|gq8SEs zgup#Z&8GZ~!Qh8vur++VeB=j#3F|2W{%OMxu%kxE8PdEE7lP-SI|%RqGpPUj0Tb_# z&}%~MdeFi_Y7y?nNYKsB(FNHFSCp6tRZGIRKhmU3+T3h~f|i+FS%T)Bv>1^%6> z{2K%%7X2 z6iQ=QozpjEeA?@E`S~vGnY8@g6Y8O?dqrxON{&3D(vtrLc*_So<{pe^7xR)be$|jy zRct)x7fZ5edlOr+yID9W$CclsT=kWeu;AI-FIT^{NdMsjqvXn{)WCAuv|gt?7`@@f zAjM+;;uk&t4}Ouv@BE^7QUxNwFPi(;ZvAiI5-ofd$pEPackEF=Z1^yzkmk#cb*-}0 z?yPIPc$2n=x6OSiBjUo*-I~5vtKEVX5+9Wa^I3nq(EM`uCyVB&&_bCHWGJ59fNbkVmRhm3T6&~buS2~;>AJ2Zrds*t4v7##B7)q#4-PGa{c=m+@|2LiGKl6vTHeBdbzpJbkv-dY# z#etd>X72gtjjN7tdLFas>PNnV9%-jaZa(Sh>guWXaPyF;6^OWUum`peZ&8rL=rGT6FF{NVkJo2e;zag~?II zzWfzrRjJM8+e^OLAn{NG6IKUS!Jc3Q)Jiuve0FuC10C@YSohR2{D#?-zMi4U#;^HY zXSZ9W`omH@0%(#&!+tQKqHC#*l&?w*w}$v`e0|AfvnD7 zof>|5#^bRuXHFKXOK$(zlOm$|_;#e{?Iube2>T2}{X0-TTNifaVF=A;>qx@fgMQmn zw58)_E!!X5e4lFeWo=W$_X7#5#NNeRi)~VRy2;`MYRTj<;NFo0ohi`J?3ZDZB8siS zXBWwx`2M;iqIQqrM(B^y<&m`Ge4uMyi)P3->C-2L=W^zcLCw&8JufR5y8cBCo%dL5p&GWoNKm$w{;D@}kE91@wPi{2z4s#Hz3HeyAj3esztg&C zpX~H~L%!sQE`h}xZp9=#-yX*m;p)RC^`_FV9tyZzJLuFneu9a&d=1r(3$1yVnhvB3 zWSF`O{;W*F`EpW!c^f5$*llIadd)&9|C}AR%6Gv#ZY$%$MOLj0O|9b)SHipw={gBj zj;nh9FcdP1SE+@wV8l<8B1^CpXdpuak80Fjdhx08$&Ze$T|GDCOmT=B6;!r*h?vMa*bhV=*#-4t5!feK_bHK#_TwEk)1>Q{$BR43 zA{J3PZ(ZfjtGar(?)Q4i0}k_Jcy#hBk$sj)tD*5>&APqL^2`crg^E;UiC;(AYqv|6 zlH6hwop&AmUJ_;`#oGzHHyL5>Zbdhij)O=r_Gvyl0&&;qn)l&Hr4=?=)Bi|7f90FZmAsmG4b^=dXC_U>3T^%ZYQb(cZn2i{=hSs9D2niFW3Tgd-87F z&EsKL$h*62cIF;UPO8>Y56!XB`%V?TAZ2KgWyZ1 zSG<_>&AF7wna4@4pjpf9Fc-q4W?LSRPA{y$#K0ki@#yO_UE11V`p= zQ$2>%tPI|DXqhezijy+Y+t5TmU8xHncMzec5uibJCeShQO9BdO5i#OvBEiW4%{dS~ z&mE;M)h=(6IGWJ#aC>|U-#P0SSG?j;>hq9Z@+zo;n0FgDpez*TEz3r)XE`4wnVzPK z7L&*PlRijBD}2-}OpN+M?!UrFjK<2IX5xntjL-zT;{ZsR+J8Zq9|PcGkLw%*$&yC) zRkWJ3AFHog$%NRT01MpN-r>Xzo{;HsmKx28c9EfsgX^k^Pg4gDXN(yyXzXA>eXG1w{ zD6lP?RJ4Bk@FTZXZqrZTJl@1awK%!~wQRs=!%lLYfK#oo(XVx7K+c}%&b|3wPrXg+ z!bXIbXzp#2V;qdLkKF6`hB8!$t#RVLCjN-;LKrR&ktrv{8JhAf*fu#HSk`mAheUch zbfBG$uQ<%Q`6dB%+|?PZ*lm;i?(zirX<#YQyX5v7tH5u5b4tFiLaCdzlK41}*a0wv zZ2>B55p*ACUn8?*u+E|CHET+A^sc&})vK6G1uHcKiyx~OFKQ@o-lOxjKI+8lxZchl z_~a=9EaMBTmppBrOJ(M_5$85ny@TJj2&rC7^hCb8VIs+N!VThz5c!@Tiehcv+DCnS z23hM<1CD!4k4By3ebK=yoi;a}J2H4_KTa9hefu9w`8Y69yYXBAz6Z(BQ5sojh9|`> zfbW(gOe+GwakivxYJ>A)H1T;rt>q_u1I9+}9*v_5Bmtv8(IfJ#qMG&W(T8Q<`~jUp5DoYg{q#o3oN7&-X++OYmtHf8SVef?O*N$ zk{aw44}|`8GL!)AEYS6xbs8~{<<+UbZ&HUzUfFtPd?wGKAxK6>H#sji{gdjB-hrLH zF*|B;`^}88NY!7%m^kdT+be_Jf5W{f!(-%&^SC)YwiNOiw_H(xRa{IXu_S{K#zNCf zSz+MuG_gKo4L9*T<;%R9-x~z|qcn8GpZ~tlc!kw-Hxn#{seP``+QulXH&Nf9>}s zG_|TEW>KDB>AAE;B7I7R#j)Jtn2y#i%S?dkDJx1yT)o0{yA8D6h~E?@?gRY#mtq zv>WtjiEf2% z&TpM!O zlUj0V3$>)4Lo$rHqRPe^niVvg<%0qqh4uGI?|2k@Dc5uHqEKDj;;lv!ZU5-3{2zkS z+wE;vcJ(D6G(LTL2Tpt_RKYZWP~VDfiX7`{UPdk=!)+Oz0KwQVb$aaMz zwJVD5vU{A>0~f%mkh<*>-nRxjq8qWhKhko;e>oo7z(3)jI-nqri5u~5`1RZwh#VY_ zeB>eTt|MogbvBbzl+uiwRgsz|RMUEf>BzXSznd2wxd}K+u+5ba9b>mAXws*F32V;D zg220M)im5p+5gK62x{3PYk-sryy)QtvMC7&hu-xFk;rtN1y91>5p-7H;$eI5}^v=eAqNL1Uz&$WNut z38~+kC?$}m&X5&|W9~13RBBG?-Sn^1{?Ce>fB&jF6^Y@MooGx8o=(g-dNnI?Dm;GL zixy(|$ngFY(Jto~856(3OA1+yb%6k-5`!9%A@il;#DIZDec7cK-KWVCkjGwKdDx(o8p5@6?AlI_I#hklia-r?WBfo{DMc7Vv{_hT|BNX&J zZ5+IOv(bgzg206~&|B17kl^SGQAOw=r8;LDJ)eWE^5>8ci0~jsQ@sj0Y=Il)H3=ae zBt(=_LJe&mRy~JQh5`oiBxk9Rw=h>HFbApK94PmLJk^r#nfPRP$|>|Ud<2R%G5HU0 z2ytAYXXs{T_8s+^uFTKhRYxS;4w*BY4+b$fv4*GPEYcqA# zw96+G4nw2xH({ zxt7-&JP^-;C}HWs)uLme0JFWDy-3@Z6ZbgDnuH^+HM-HnX!0EOXCho?;frJ zY_Tk)xsP06&Wi>S%#=|-&h>wAZ5QO{AdgPwAY3^9VOO|23^$;~gWf7NC7P;N;<{}$ zX`W|ZH9PiXYBpau^1s-77jP)|wr_ZZ?5XUcn2M4lWfR#=QY4k4nvkYK$dY!VY%UQh zA%qoW5=BWs6^`6%K-1qU^Yqg&BywC9--*6m85|N3vv|GD{{zu$uVlE682wno#il%kMUilhQjr9|H_MJh}RIU3Z%9L@7}vvxfF z)kj?+EnDXhlljf8UiMXw&}+pYXgC4U03Uz#uy(3qfZig|OyBv0Ii_%|Rry)v2QB@z zYKh9<8&t1~ZWh`D8L=bbv(zpA37Cacz541GmG2QRif|X^uzfl^wzhI*oWGH_*z3#7 ziX9JKO!)PPwTXt9@ZGQ-cpK!5c8|r=pB~R$4q3u0eMTG)e}hlUQ{LWPw%@fVV7%bk z!*%hUn+cK}(|;JGTx)}#rb3(M#g|S!%oTNba_{{{;?CKYF=wRPm%BWvofPvMVWGLJ zS58;-{s}*uuRN!1yFNYDJ#Jl_GxH!??Gmli0n_T>t0T9u(p`mY5Oq{z1hC%}nL>_Q z!XYZvZp3N%9z*VNmp!|T4a^;uvgVlLfe-|Y=`oB)B^XF|On)Yor5BT_{XXPyf81_s z*CAEUrsnx3BH8ZOuX!A|6}ryeXij#g)U=E!!@MuUD&XYyU^KZa(5n96hs`-n>%4EL zsAk*Svk%}yUxde>)vT4N$@(Q<=TOHatg46ytn3uu2>$;BTd$^0DGJhI&7~fvII)X= ze0Qyi)IE7*G}3T$NS)l6#^<%3b8HB_?w|30pqVIUVv9=^@pgv2gi0<=F=PYg#TxdL zdue($?Vg*fvt3qa@4`&q%}EY@cJdouFF2>AQpK8sW^MaP$I2NYnArIaVLg*h7|DPv_Udt`z4dF9BSy+uzGY>SG~zj_bd*X>xTt1@I z4T!A;ptZFmy7Cx|A_W-`r>LVN#9ZWCcT+e?6k+O;dLZ=nhghOt8;*D_8KMmSB6)b+ zUor6dMa{4tj=dH3{E_#IdTM{DER^USlw8b}^b}}jHeKs3JX35CGigv8o=%~C0x550 zd}jm{1G_&u6kU*XM0~{F9LHON~h!3q(2bTh{73~*% z16LW&gqDvVwRLRJ-`bE|f0FXf^Cv1Db94Dya(Ty)ccc9z{_@o*b_KtWi()T+FvY6% z#C*Fi#FfbSTNk3w*FE~6|9Z|=OfCA0i6URAV=5F93XQZ7sBS%Rg`L#8HBYz(Wt37% z0^>+W9IzGswF#H0abi1d!(uNDvAO6iIu`4| z{Q$Xwo|g!=%^Be+@*ux1W{fl`gy|z4Y9#2hQJUn30IQZLl)xeFQB9d8$gAFE?#78| zVRD~m56{Ckwb*BDS8~~`v_k3D_suufT_{^-IDFGR{vLWTe;Q^iQVso_g}(!=j_iBV zgx@G)t?(~_6}YH(%T3z?hd+s@1vorBttN z|2>}rK&k3vbUe}F3X!`L=mpv`sT+xHv)U)3|HU75GfoFCIiGC|+6+;-K@LoZX1(qhBZ&E^auccik-z>GlUYY8{}mdvt9N1_`c`s|rZM6q zS$o<`bV;^tt2;ub0!ty=_PZ_;G8=~+}e<(>PIo7Aw zHu3tVLvUX2E#sGAN}u$XMs0{&s7=(=)_n8qXm3)(x8_CAmLRyT6^9mEuHvhe{33Iw z&u!a@of{f`_Y5MWoRd+X~VbT3lC*=`jMKx@)cTeDS1vVE}6yRez08P+YAx5bKtjw z3T}we)ObjuYiWTsU)MvktCKRFkW5 zMBIIF` zUm1VBy?u>`tA$>}P^`btnKvgc=iLdv_B4!Ayi%fRY;VoBjij@A_j*3r2F|gUf0+0x z>;1d$xU_?o)+Z0`F7uJo*b?1Ag3i2|7g}xO7a3gu6(0rlHF}_uUp@b zp3^*9xAw1H=dz;+P?QWP|Yo=41NB2Ak6cOR%-m# zMnV!n?A?byBqbI3Fqzfer15m>BB)$TZGn4#;qXi=?QQQAoMPtn0)Z{gj^ z#Bl^N03%dm{N^viGZfkvP+|TRQoDlLw1dYqI>GXyv$cQ{XDOG(g9AH!3$gCHyBkQvza}!jD6$+mZ1M`V|US4&0TAHXlld?oS*ykXJ(j zq4vU0pQ=H4ip4Dg%`50dReTJpInzdC(A31$@uAMxDH1{wU}%4Gr#iSYKYRI|*q9c7 zA^54w<+w3`2R?flvN-;}GYe^7sXrB6{1@O$?DujPX@Cg$Ea?2E`a;vN-!t0RuekIr zSnDexyWkw2hLxI_!7reUJH&AqS3JUXC;=^<^`FQ;e!xV*yftmHTnWwT8Q}Jv4<#Tw z{;KcxpRXfgkP*=1-=x?2^HhyU0-aR!0SPmb!gnRIdq9tsj^F&QGkrjCANl+R*FZYo zgNyL(K#5>CY@j@7drpX^a~0ZQroW!tNX#z&!;b&wZ}~^vu8*o_M2mwMeBUr7=HzR` z7f4No@Xpqe)sbOiqk&DOr<%mP0@8aWzAtsyhTqGd<IT0~ay|3N-0zPi5mQD3Z4JT!jI&HaT?3NLE-U>{s-{In@Uw<24C)ZZA zuJ+_bzilIV#>%J8H?F?>>FYhlTms?zXb{4e&*m~g3tYjTYsvPnbCBwDdGliOs_%oY zS{`-lhrN3abZ<4yw_UNZrEgQb{zHi=$=_3iI^#vSR5R=V39Jm45aZckq$*q;JKc{i z?8Y)`+z%uT@BXl&G)dXmsd^x4qt(Joi!)C(w4!^4r*FeUbpe|CH$s>Kln^W_0+YU7 zVsM?!ui(S_-BAXhfEqXpAmUc*kI18gQL}fA7#ZR32vdjbLl0nb)3~kR@u-4(G>eudBBzh7FCsMP5Zp6IdynQD{>*8-|>Xp zi2i}JU^0cE$e!Xaj^WtW&LU1?iHppw`*j2NvD+(rWfT49X5Z_zDEJ^@S#nsUT62?1 zVBP9VC#je~G0&^4))1$Kc&THvi8Vp@TkhUGu}bg(D( zQi+<8#&yj{Ri+OM^A1PG9Ddg^kwSUh!B>Ivti6|$D@YR9!qH6Mf$Rdxv3i8<0>osb zi?Eo9XwilCM;av^mCLY1kEd*E%&k|h_rs?j9bbR#wV#sJFZ14R-J-F)ZIISo%Du_X z9r59rVr5JujwX{39kM95LeR5DI(dFn{KD!bDxQf+h9cq4A3OqROgb*9%L@)_!zJx_ za72V>Onl#S;oI4ROy9FT}VxspFFe5o! zN?U8xfgOc|~_kHE1 zZN(LlEy>pX<%2xUpJ=ZP;x$=7oiE$4tO}J{Q`Kj?lCh%r&PMHi|`22UY6zk1cP9dkgcpcV=m4BFK10J}(e18%s+?zGISufg@+d<%J)g?XAxe@(o5)f_8ab zvDqzXcbS><4rwXj1`COv{>_2XY?rE}(~ zZcvjojb4VXKp8ivY+svXUTD}$x-70YL{x`*X<5snt{s6ZGW>Jy)}D=8b2Mg-%`JP6 z&2mcuAiXzqg%5`B(kgQc0QcyyX#9EL%gy$hD9-9|W~V@QLVVe5%M3wK`xEbuQi`&- zwqV96nEi-d{Gj&o0C!GyL#9dczE;<5raRt9x#vFiQRH{IlM$niqw@yNj)gsE_4{Kc zVz>-0xQqJJF>T7_uoYmbJ7Oj&5<@TcW%!9qnNF76tn^TNtq|UzF?XS-`Gf{gwF^@| zrSaw6@!f4~DZH^E2A$~gr@TS=o7`p-SBd=&{8b|e_5#m>cw#L2d}+0R=U6`}GGOpX zX-9|_qnBv&;mDQUt87pEc}nX)c-9|&=8!mJ^0wS9l)+4x-c;H!#uKuFFr@t>-?xJc zZmeje;0E8B=Z;hxS?aj{UMvHQIA+rpW^~pE){p{Hb6j>bp{SS_6*AA5)&RUbvG?7UAL~o+I8%W$z)W@@+A9 zb|1Y~UH0Q@!?IxeX>;4VT{rp`Ej*Gu<#a$ZQuZOLe|7ZLt7?+cKl$Q^|AQ|c6c&QH z;JGDhVI`G^#jMg-_ZQ;WoE5LsWS(z&;rllnsqcA()~3(pzU z_$ZuOF|gcKI>*yaZ1Dme$P+M1(IRpj@(U4LPOGDWYbrYd)TJsxciQXK)>rjbduw@o z@H-mv+AQaol1XpnQI(zxNgJ0C>q5gAAPk6(pCK(qNA^8|VB;w*>Cc4r9YbWkD$IpQ zH1wh~GDzx{t9&Uc=JVyE&d}w(l~P^KydOTR8bj4TpzPV>XL$9Q)6K`iK)B?SKdlPW z`Vc@*#;5`$abW{}yVr_7a>38Spiv6jirP)(!etwA7eGr)+Zs}I`^;2iK&;!UMLN^w zc6YlnqGNWJMjzN>)U-9r!1% zLK=>z&T^DL1`4(W_Foc6 zc`mquA3_)<6t@3f@EZ-d)*zGSjVv-h%@U&T4D${xOVXw39jYp5zY27yz0?+Bc zQ}Z95nF~{W327qX5FvJ1c0kb3bCS~1!dC%Xs;z**{_*(YFWB&HLP%ivH|0_xzCHp9 zunUH%0E;<}#P-Q^6mO=wJdI_J?o`=*Juh*`hpS0zHa3~+zbFmxwD^Yx;gK*UUy20E zfKXX{G+=mxA+On$XTLvMV$Z{f?ytL^rHU;9uY83qapXk@T&ggsM`)2~F)_{%wnfm7 zeuo;WYEaC!E%7Z*9U;bEc?VtYJe}N=y1y&M+A~~?kmTDoU&(OqUdab*35$g`O8r$M z1Z6E)F=sd;X_+!GBag$H$aJ}o9mZUnCtiBogy_k^tOYynP*$bLm1>0S%*jdoeB9}p z^(uXV#TEjxWF{dJ@oT}>(^>cKpUj1mu%%yS&A8_kH^mm7|IHsIu8ZO=H{UY6rck4y?!O(EpH}3dbwN0(|!I!c# zC9dZ{b}aD&8(2ByvS_ctMs6tO?!_n!5E>xYCn$JRWcZ?Yu#A@XMBc%g8g6PwPloGb z8_V-H#N{g2Z;mgFj}Es04E$_laRK}b8YDVxFPm>+`b+s_DsloNCZk$Q78XC(^p&bh zQcT^zT%Z&*9#Xfi$a1}K`S+KCesI;;9$Neitp*34>T1$N;_#GYxFqgPVsMdZ5O(-*YN``9x*Tnjrc5MYGDXEbF%!lT>Wf9j`SENiHz?$35qfm0saCDN=Kg} z8{sd~ff&F9gW(-~QHp2MhQ}lcI@1&|4t2=DYDmyw+uk z(1uQEdkc@pL-A8?R0kJ_1Gh3na0~v)z6iIeETknP|IVH^yo#X1ki$&P@LjtBbjl#k zT=Pkp63i-oi`gPgl9q4|J_-LuaFo#pS(4ue?FQT8HD!7mEsivjHbj~^)9O1DMH?8# zr6JD0{s3#k8^f}}cI{Y!-lfIUl_$`yDF!vR{M;iYyn%f*F0i2Q;u14!KdCoE&sitM zH>x!P`W&i;pAohrv}tk@;65p$M2}_gl&kZV%9!YCeyPjV`x)Mg;;&WlFcaOA5e5rs zHR&U$cS5}C*HJwVtDZQo-0mc|AhkeY@WFGi!2^kf zUZZ;b^d2JDmrbsdlX$b@U5MXZ>-(;c*rUhatkaaWRrhcdi+l1u``E-bK3ukutHJp_ zXCA;7V`^31a^W?Xvn_^#5;k42Q_JDWyze@7MXu>d!->4kh0~8ZSvNbri~j#4NFe`k zfSr_&zjq31;eG@ng|~h9hGM!f=2qew>p?WC7@ZhdbaHa7tLrthxl^=nN6-Wcwt>nt zL>8dH%BboUBiNUGGWVNsrqI*2f;%Bd)kk#kJF)8Gzln>GZ4|br+^DGWRm2^+LYH|2 z`}iWUmVK=KZL8;1my4p?L`U+MXOyZ981eQ}n)Uc9>sUH*BrY3!a$73K-omL0IUW=k zQfTj==W=Jg#imbo2}g|ty8nQEzofHIb?~!b{7Ll=0#Z3&A8Hg?LHjX~CV5yQm3I8y=_O zQt)+ixmXP@InA>TA~mS1VVC<+v2M((#@#x#!|`z@)9$951L@ZSmHKrn7n%<^6cCVA z6Xfq=d@Ct{3&y5}1NlcF4#}{2r~+y5c@PX)WC~$zB;Kd8f1&YjvlzC5^FY#i9;KD* zd`-ZX6Gz;jv)>#!Bo~9uoxF9truKYV1hXRE&!$N^T8e6kfBAMcpI;+o;*>e$J9z%D zjQ?j6Uug`NDdqrif;;zBEHf|$UlBxkc~(2C`0X^WY6V&hX= zz~BDED4}!U-=0ErqDR}PkE+8+YIFsXN16<^&eM@HpR|^g@ZTCmrfY)O} zgKK>Z=sla?Tc6>?yY0QaWHBexw=<7G3nwuK$EK}pq2wNp3|ZYH(R=&)dbaldClk;neLysk=o+e9&l@u_l5qxKB=wm6W$$oMPk@M z=iGz8DSVMOp^T1%?hTOR!B!(RK}XBeJM1|Vfnf?2n@PIW&!WA88+esIJ&^flq9vD-=e81(WLg>ASk7x|x2tUvp^08(O+YxynMdGeK~-(gQm&hWxa-A7YR zT3D11TM$F=$QnRaNv@}i*>Fj;tRgdo;qbV;bJ{(XiFds}J+!ZHd$2a`+p*tMFqTU2 zZK>#hI8hxLuGsFjg1{5$qA--VI0c{Sb1ut>a$I(`HZMMkV=YeRI= zun?qr0N9Cjb?_!xa4K_3KhDVU<{*ui`EX93$XUbKLllI7>T@aBMsS6{{yq9xP6Ys~ za3TIHz-glM7xlx+?_(SD7ua(1I5F|%p|`Q3T2;!Wa_tq7BB~0+`0dB)JlX)sH!8*U1-tF=pP z1cYSZZS!e3?3sz}Kyl2NeW*rgGx7zm4-v?d;^>$#OvZQsA?(%v{qFxeC;xBnlb`t= zlRs!b+1}(gM7A>pGZkax0#;U_|Z){HJZxnk9*Xy6K{qG2bsyO;%1iN8PGm<}Yh{1E@0U2aiTA0*QFEpU7#bBMM>m2gVnC9Z`K+ z>hE)E*{My>ZBO*SLPdGIc!2@sa*;IL|Yl!DQlExy0I3pwr#Ts?!g9(f;xL6i|? zL50F}_Mcy(^>d*cc)DDQ)vU}!K;3j+kpI56l2Ix0h2y^jNJ&LKds=q+h3VFueC^4( zCHbG}*i!K2e{cigSFLH8R-I`Im&Al|S@3|aD}jqpqi&r$UZ1wLm2QvIGj9+41_ zOhLZwL*(|`a-StHfeSC^9Mb4gzGd77)+&mS#$=<{QnnE2E@mseN9?sRV=^%@HCN8bNi zlh}c7*pEq5Evl$>A>rNQfeT4PH%=q_U`^C>xY$AMfLku1?%C ze1gx{{k+xT^A6+;?6Lokc_=avU*(^8ngTcWar{*&IoVFJpd)7DV(FQxX|&krjQA9(9zAu4)(s?w~DaGglXnGk&ZH-t43{atw*utoPNJ zf=xn7Bjvwdoc*m6ujBlkN{fo4?PK#B_bohPm73TY{y^-$rX&GRCNY}yy2kzI;`OMa zR@!EB>q^?h8qx79~9+Jq5{DXquL90YiFMSQr2)P8(WdA*IJ^Jb)30D0aVB&J& z6z*K8x3@)oggWwn!$~6Wj{OX4|2MD6HIDs#jEY*47~=`kn^R#~J!b(3t*%1?F~J4W z=UQA6;7Kvypna>9BurX3Y%gsu?uj*f9dx{44b$5zdXL=VS5?vboT^0@h+A0EnnAFl z`Y!bea>e&E_;H&bV$NgdG7;_cH1esz3?{ z$M5AGg#C~R8r=`k$Nm>5<-H!PuejG6C3~oh^E`T^oOQ`16Qh|Yltvm~E#X1$ewap| zkQ0wT9oUp>{oZcRwLGnnbwBC|VdX)-xXd0wREW>&_k*0ERQDEfvUj?RWgU86 zA3Ef}06v;WfBZF4mzA-}!o|4acc{exj%Jn5BrPi87_RQywCfB7?k7^Kv z8dsp1bZptvqI2LGi~b_G$x0pivbCpSX6N3!N5uro&5ok^a+vOE@JSNK`Ef~dyI!k_T2@J^=J;EE_|25K@Q~T~s7Aw(wuYt~e6_I&s ztrmYKkAt@@Aq(qE>Yz?dqxI-Be{2OhE2ts&FF_4U3FttJq>v6-=yQF2Gn!rcn7!TF zN75QH)U})<9!k7ga&_MMeP|5AXrp(=)N$ty+dbwSzkh6T{n291#bld>?mEv;>Fb+J z(Y^x8-sfST3#@>3<$7Dik8e)W;*7ShYHAXj*>kIi@-COJl5ui5oxdQtw$)yvQ6t3e zL*d)Nb-xidwgtbNOS=Tt=i^wXZFR?M-~5Dm-^lt)QjU~!imWu2YR;9cUFTchU zVn(OA3pgpPp21qU*d6rdXka>3LKf)C*i6WUBgaDG=KM< zZSiPKx9NLb^IL=8)jbXzGgby;j*8%jK!k!l+HSn2LLnTm=p1t(9QV4B=XXvoO4 z(GuDtoMdN02*`#m!c2Q$TxpNhJpTR_b>2kt!(3@}Fpw2Fu>!q`bm|?bcqVv`OXZ}c z?TlkpNGtm6kNk}wFKz~dxSLPI3sx^p4P4z^O?^8_p! z1vr-|lME12I;t#>O-v~$s-&=U*aU05L zrF7EBkE4g$Y&az!3tmbrOD8Heahh_kHB}vo9MTcn1AD>^Ipim|EB!6^>;9q_rG7~@ zr1Ve8JlUql#PeoClX zOnp-BGQ#+XbUIZhHz++JUN*dO)QxlZYn;p6YiC}`Turze1O+9Hb4Ft$1)S&iQtdME z1!e2fjx-S6r+&wJbJaF6Yq(!9yUz}WW_*7t<-esvmDY=DNeT*=YwSI>SpvDE9>?s;Pd$4ci{*+i|vk z3QOS^@{K$E?_rm3XZN}3Kg~X_vi+fz`Z4x7+V@--#eY^lxh?kw`N_W6lJmRWw!LK7 z>A%{LszP`EB=g?EpV{RRZ`HP{Nt_gg=%jx^L(+Sh1*6>$-ZF#?PW~XC$E!$;?r*9f zRdrF!@q~mo>+V@p&i_E`0#P)vX<-CN{p~w=(B9E=&#}Wwwh#cS*pjpaQ$G07wLx% zos$f<)E5goFvF!aAYCCTg1eP!*UnNgyW&raA2-bGq4a(o|JoW(x(BE-wy*KXBDQO_ zao=)IvTvU}`%Aha&B)EGVeZTNcLt(Pnyo3DU#}HDsiG-6`FTB+ZG&Q(DS{6ttT+w* z{I=~(6IKFiXJ)g8d^kbgBPpngb^>+|>gf%`kAD%7Z~8D(uT?Rkh``dnxmbGsHQ7bN zOVn=*^K+mDD4aUGk33iDthvCtw@*bR=-v@={(U+}Ja+`*6TsOfkl1-tzRp-nmyJyZ z*A+YVy;-9)>P+Dq_%EzcS@Wrc4DvJBq6%{J-I9!Kh))`ts4?J8gSrD8TCKMOLJgWm-pW2ae=F*3nA2O#60g;4w> z@Bv|-G(4RrG9X5rLmKYb2e#{@Ahe$%1`AM#LId^%;^c5X@@)vOWZ#~Hrhs>EPR1P@ zApv+K>=yJz*;77>{tU86S~)mNo7DOT#iQX>)5d=;?cJVJ2_Z;iHaZ|mT>Km1yAU*J z%)LQDI;x25GlBfu*+5ZKMVegF23V6hv!kA*|D<9^h7}rye9eLo7+r)3R_0jR(jBJe zYZ`b(QPJ2iuW*r_tr{VI^i$@q@#sp@A0wBU0~m{)V2=sdl)66A4&htGdKaU<%fXLj zhGlB?q*7WIMLb`^T>`pe&Rfn>i@mCP{eie~YPNY)Gje2REMhXYKy^}hE=6BLMMC7n z9@dih+mQ#{{;hBNj|GIVXr%fPS`-=f4rT8ji!qjW-Vt~=XpRo5bnr!J&uM=NS1*76 z68qyMRlHn>BLxpFxcr%|JTk?RV?8QxA2=8^G#O%+Wv{ujFf`)B*t0~5X_pPhRg^VI zM%mI_T2D7YhdsqDg`{Xpm@qhg;yj9a8wc z3y6L)_Ie&4JW1C7M)LKaLEHbv&k%Q>0&Fse$(HU6Trz;SJwy^^zfHb7h=}w!xM}S! zO|>bj{Gsp=4|0Dzz;-(1mVYgfm>zEV_CFP#gxPdl_GSjIQiMy|^5pqJ?gO2JrtE0^ zmyjp6hwnQd6m=hLH0Ph!A%EYvL2)_@0xU|{t3Y}QFbn#-v={p-Rkl~kA8W_g>}MWm z;(8~!_PGnLN1we_QBbi_>=TIrXdw13T`^n|+!m2x3}NcH9ciDcS66HGE7ntXmWXt7 zKDM57Dbr5=!NY#@&ss|!{@S>zlQ4r$ktYaujLu%v=6%=O1)e{QRx2U z^MV)|tDRB%w(%*5p_}>bJ#emY?WzYo8@)ViU^ZTZT|SS&F&4RjsTf}}cMg;-VCg!l zh((8J`J1?o9zR^qsva-+c!_Qxy|Ul>`5yn~F-&s|9*U{QS4`$!N#HgMin5cPo_ti( zGgo9}JllS@$W>d{U!&(~NQI^OmzA>HKi}|J{cw8~@d8l=7sqNCAGxt7nPU>iD(5HE zpFa{5yCs7AakPER;l`&e=2p||*4an~hs$k}U=Gi4;i$%-jBE4Y$#w(43T*Ssr)Tp) zdAZ3xFX-T=5Oj3qtGS^YGVU#xl=gh)yxV5CTQjoke0yAAfAhg%2lQ$B+nM@(5lo3| zIoDq0906V=NaH{)%66AD$Rnt`dh*$V&nYl4z8}S*U|A#%Q7#HKd}VS#hT2tgh~bS zss5ae*|N`ocCIZ20|!wIytPI#436Ysfh%aIjSdQ-Y$qTOw&p^l7!iqAqYEr$yN8I1 zB7RhxI+r~Eu#8>4&i1syYt2>#r+{l01`a*{oF~HIP~L_r2nlv0weHkHJ^oAx zgby#z%HejjZGr@p@l_8LTl)k#d~G(Z`Ya^9S&(Kqu37Tf&vx?_sa@ZslhwW#J=y(q zy|CmtjUiH^DGvffNOWEAnB^sZ+}wd@e9sf+E&ESr^)F!z|M4E-@z=G;tO)l=T0b(6 z{w-}is@PnA>*Vr>cg-y%90%)m%5|UjP`wL-i4S{){`ki6g($0&G`#}-m3S2$C-ceh z__3%!eX<$)M1VGw1?5rRD%hm^Nk_;SC3~1EU#^wkJ=}hN^w#Lts3YlJ>GN0nExvHP zl;D2jl@5Pf#bsJfr6_!$i&`jFEf;Z6mVJQ4E-eucS(?@5o!Co?K4kOU)qBDGrMu5; zTrF?XqC)$k4wu{@dKgkMu%zr=4qf?HSOLRi@>2Oarq(n2Js)*b`vwVr;k~X{zO@eZwE$-yRLO^Z-ov~IU zgu+1QZbcf0Lm=dTvP@3^z3PxniDUq9FOn|=tAIlwki(t)0r^LjrBK2s;Kbs!m(Yny z)fr)24qUh-Igq@onJLASd)|q$a{2Q~xFc&;f3OqqrpUKVviav&A-N6roUt$Sg zWu?f^MylljmAHmfL=_~=kn!uw5i*JGDmT5E4q#RJG1A2Rjl?=#4 zv$)+h&k985XKhy#LVWPCs=*B(ScWV@N6vgCP23%x0Z$-u9Wo%_w;YO0$@d{$GB<SddNTttT_w1He4hC|k28C# ze0wR0CxHDJN2fR6gTHvn!6|OFpTSR%4pF8pQ2;JjdLuI@BEm_-ag17r|%6}nn5eImYNR>Ctb6`8T6 zfXiMzN*xcOi=!i({RJimI@%~~4-!9}T0h2H1hAip_)1TB{2tQh>B{*?=Oy~giRZWF zVBx;(ea6U_SA_8ZkEvCUa)ls= z(s~ZGOwBsrEoQ-gEgDH_c!d5&SlUCM`3|F-PaDy}WgfujmWII7JpLW?<=aibp-{{C zJT|?33iyqFBb36od*@H&NU7Y(A_g8hYVJ1LyeIC*89TE%W%11A}5(H41m@f z2Y(~nBu?`vHRE49O2W+W*NoCpJ@$yuGcdk8?lBI>BdvGvF;bdk3U5Aa&WcAQpRo%C zrL?HA`m>oxYX|C3qb9)kX9d41zY*LGQ(x2DQ@-O~T$VkIZ(HouITAB-RtnFA!1|!o zpnC-dGR=e&ea)`sm2>n2q32k5%n(u&_3mL;&sL|qEdqNK9EFRVJH<12n9#FsY zJnOy)qJ2h4&==Oopp6uI34bcgRPKc*Q1c0N(c>@B;RctK zmu9vO5$8JpKE_LDlbbTPgznua8Um*Lk8noV_J6{t08^+a_)lWP=%3*v$gUE81yY@g zj;BymkuE*ZQT>+FF)0O7s{VX+uvH=*8C8JDH7D`xgO1n5Com^ttvFt(CQm;s+wrti zro}GHK`*MxHzfInXqalpR4~setl3f?Naej~N+J53iUe*JcF4ZnJ)vm7B!C-?&#N$2AbA=%6r#1txvgsZp)$ek;T+y-!)#X z8d|$iGdn-4Mw=k~(i_~XpTQ|~9$?yRvpUFfA+;68)s-Ub@A*uc!mwyv>W$ouN1r|K zjMEt1J$U7f!$zS;d!*Cx3|Qa~R7_(JwJ@;yso=KdG9MkeTGFNUR_112r|17DR$I#M zJ1jGG^m+d?mHiRYIOhZ5Jc++Z8m)+p54 zp;bJJzy1Byj7tR8Xx1qeah+2+`E$N52-f1yYrv(d`>EI}l|Sv+5s)|Jg?JJRMe=+(zO&ppy0^#YR|d;;#6D}RGWlKdb4JMB$NPX;b)^o}pgDfEv(i?qT^DBbp~t$`7)p$g{dYZ8~; zBxM*LD(-XE2uk?H=ao<5^>CpXFG?aj#8$cK{Ro#o%d?5#F?%KeKq7}rKH+)V3JO>) z-NOCgcmBB77xJy2F70f4I?z2cE9de;Dqki!7i_Cs*h}JL%BVX4-}a%$h~j*0LEfUx zpyVkAx8KFcI+wc0t(ogq)3q|Mu30}y>T@>X=Lyfa-9Z-zfL?3bC<{(lM&<_8mlSDA zf{h#X^x*>Fu&H6kTHN_M*Jt;f&C2(bymhT~6AVhiZiLmLr6e$5*h;->Uk7y{7}-L- zY`Edom40Q2bv&@wuAg4g&GoNN9FADqV!$1b}}jViKy&#}s`^z3ma z?=V;@s`|Nkb+o`!nyK5Dk>gO4W+(+|mfT{dsBX|W z^62XN!o+Hkv&%9lA7TK)h09!K=Z=0mT@bPhGZJJls8^MR9??b?i=Uw?zW$iLUD~ym z#Ge#)FV!bF-=%%Y8TgycmCQZfK{XxiaP-=Wsa9YLr4qH%mxUyO}e&J`~)v-1D;W-bY zk@qwIK^u#LAIHE*(@TCM5RefPWcw^C!Ulh;*YYPwWzdmT}eP zJn;~3K{BvCQm&+z*3zRg&DpYP_c0qCGy8(zEtxNMZd7*3PkXnnlZa_Y!bYv)bmXzLbSpO-uHgeLHQVYec;ndrSc@H zy!3&l#zmLduWGKeNTy zT01{A3U~Po6+YN{`}*p5VOjmFrje9faCLr^fopUauR<0B5jt4QsL7USxmG6`7*5~#q$YtEb?{NH#(mAy&hxhJTu%AuP?BK53LO4emecxYT zU5`A`tJfuNeNy&e($BSO=HsoDTMu`vo;uxl*wj|R`*!NtBMK{3G%rvZ0{I&=ajg~GPK|UP_lzzmJ}pgYK1kTMU=Wx5-{0?xH1-vy4JRrD(#!$-q5{R zy1U>}`x$2irCpyqPG;(SMKQB{?mVoGw?C|tDs6;BQzZGptWmw~Y+vWz-a%8%sdqg) zxLx$uXXCc+>#kz_h>!^bmB5X}H-G{KcTJ=h0}4E27_l>7n@PJwoLi}h8Px1MzotN; z`(DxQ16|#l$6X4S-O$|l{OA&)o9Tl6u$t5`LJ;eBVFyRwOl2&%pENJ1tu{F*cH6TZ z1~yNU#=o)bE(gx9mzsC`^EDI285QWGQ6kBKIfnz8c3f<);1tw?6NVYt{NmX^jinDP1#pA}7B-!$dXhWcEA*O0m9S}X^-VRc20Wr8Q7 z#!Y$9ZBa0gy*~Hskh-x@+RCOHjcZjCMqDER^3Y%^LQ%%AK*rO6U^>J)nnI8sBc_h1 z807C*aiPFyhh9w}d0*N_*Ub{~n>RfadZj5JAwDD%Du9D|9&ey4q8?NUerO~!riP}% zCuJNcdzaIeMrmE~*!Z>Tu{qYnU$etnzuoj&)M2qD>^-bR1bACPfg@&|NU&jDY)UOr zrg9-R##FlHe&?8K=rHDG_55RI6UB0a!nUV_BNtLC9jk;(9@~k?H6?Vp;u5;NT?gU?;AtI;kyuR{beO)?jOV#R5sx(y+O zc+U2lRxdAU)~do)+RNPvd@7f-?k!8WoGZUx#m9=&3+d-c)8Adk3Ti6>UhIi@pBa||$d`%l#e^0br~Uh!4rRwCPmh?$si3j~i~T)A}d%Ej0Z=JH1c{X~Uh zr+bF>`P|;`nsKT9Epua8>%8F~cW&Mn13P|wfrM{V(?6AZKL&laaw%phoBU!2B?(kLL&$>qu zq=5?bw%pd)RPLVw)Bi#9#E=r2M*AZO5zq1_%+lL1iYegEOTaoGARVoL=dW4v4qqA+ z;PISIy>w82%gxU+?LS6E)4LC>Jfy!TDnR7^KHf5zqj_-egV%q$f%2rZzWIN(ckSU& zw(H)hMh;D%97-7FP;yK}$dE&P5}!hnCOIVx$|+4V4&g&ciXx_REHOEin2hrwDQBU~ z7=##Rl<_i$wIA!+*S_{z>)U&;^~c`(T6^~gmutp5^SsYNVeiGdu!VeA2!gdq30fUqi5 zY8#hj!f?C&YpCe%4^}Y!ohGi!$7cn^&gAcyS_dW@16vZ%F z5--d(*--iPy$pNzdk-u5uM3^@h?-gHi-L=REBtYkFMfnn17-rt1QS7LnNe(%ZI-t| z9`*^a)~nk+h;LF7*pVtN`?NTWCi#w5e7_(yN5m#jtV8-ma68}gl16(29+g2J=dWpO zP$5k;7xH0Y*e*HL;%KAao?~`G^}+hY`r+yaBFxCbM*f}MXvLI#{0yQY-dr)$$7R=7 zk`34b0iGh!eNnfK53$YrL(|6cnU6L>FT(8Jy0n^)AOdgZ#XyHoJX^+CB(YanbQib&u_Be{);2m5!Wew1HZxg!UUgQ=X+;7VS6n!G7iJp+&m=O4 ze#kW7ve&J;zqzv{ne8vObeZb$t{r{O{Gk50kKhy*}3YsQOUj)fTY7%xRw-Ep(tz3wXLQ5$;ni_)OU-8*sevisvm0r)@1zO+Y; zOzE1F9Z^660-W28JKuF~hPOWkYA<@8lUrq*ilhqqKL*$@6plC}{jWdS83VMQUY%c@jK~vDg7n z?c5GhnWb4UHi;v_AAyPI3Lm{npmGQaGnYq>CxkhC9qN0e=J(;NXZluSZ}>O zu=ehDJHa2q4aT?@FVHjZh6^Nc{sf{8nIQSzV*ssIaA#|6jFw=kY)_vl>u_Zq{6J^& zswORirG?o8mOBkec^K)FjFAZTQ?3bj*C?i-e(Bl;W~^l++fz5U>3rqh`$o^Ex;1%6 zlsqB}!NU*ZR4tPzg=G3EQ9r=s?JC>j%$RNI&LJe^8B`BRVX~`_YbPr;=h;{b>o|yA z?KeG)li;~o$WrI_=Sgs0l6(k)>{E2xHD*E_+o$+M$*0c7Z3?1y7*@Q7Ua2OGx@lU7 z`&j)qb}|^9k8aOtkg~oENWhM|q1Cn_QWHt?RoUdVpz(q%+c)Wb58#syrM^dCd&)nr z&93(URdL1=-D9W776WKa&HeGi{r$?>*9(Kvo0GPAdmHiaC}#8u@f1(lN&6zU8!0@4 zVq2wiQ_)dIe4yK+0$k_BZ%@@m!%S$5#Q^s$E6c7uXU zz*-wiL<}?s7c8T*UK{wQxd(NRynAEP+i5r>6QjzyQ`9Zpvq#}M5E8s=k&pe<3!@8L z;DQj~8z`BGs=yA{8}}H_jik8jf~-`}Y)Zt{;fZgS$IkYMsXbi#azQg34DS=S)w$e- z%Qu%~$NoNCbGBpp_3TbkC zDDyFVYME&bW>N<`fO<7Od^duB5}vG4ozvJOSM|&l=QVGxDPl3y-uWqQ>6zLMepCg5 zZij~s3%4|EC%t6AXuGFE8IG+Qm9OK7TK%r`%P}t`Z*&OjBw5aQrYIOqTluY>OX8X0 zZejD#?H0S}6D`26g%eeuK*$z@D{--Q{WPbE9YMTdW7+JqI^u5{161F-6hENUi zkauoY!5g{h3Ud9NB{n4fIPClnjN!i&_&DBl=9-2hSG!2*rQ)N%c%|HrpK*`bEUm#$ z0uXE(H-cQ;8w{LN=>{-^f5Rei(=|wx&xlV?nP07oAo!Cmo%e2EYEta0Dvm1Rt5=ol zmZOk#Gt{UZ^E}k_1Y$L!VAZ(oP<_i);s!cjvJj^_R&U9u5LR4FIIw8!b?n;6)+pnb ze^euC_&%nEWe?akq_^ETl1iIRGv1Hc-;Z&jF3jzHRXgZ2sOf&)BazRt@Y2JbGxl4< zW&wyi;K#}V#(Evs6^#K0QsvFZAoyE1u~|y%cQo=6azj2F4yZUJ&{0$w2~%=4CyQfr zaH4Zz!SfsY6BaKHgs{$dd%b!cubX5{cjQodqFhhp#6vQ4`QLRGIVc2V%-3X~JS zH%MbF`iMHnZ4Ybp7(d*=0b^Q#4YFYg|4cCz+JX>t+}mzd}?K|BI9i;&$Sh*Fu8 zHhraffK)eI$&2FwUz>;prWh9nD4{Ni4L~Je%2=SoyClvB2`Q6X%beQ*l?@Mm9FcK$ zz}2d@;mt516vk4pks*k^Sg9-VN!n+%d!6TlHhf6uU+aZ?MyyS8V;QHLrML*jk>tXN zWYZyql|UWZuYDS2=mB}!T@_xZ-GILAlpp}FObZ9H^eG?g;s67o5lA$p!&~oSR7aHG z$C?fjyJ=f})-8Wo@p&b42)PjN%6mo#q=vmjQliNr=wg_!MmM zCOwCFi|B`!!yJNeQ>sO2?^u>KlPsJ0p_>ACE#H%(cM)>fHsDeDh6UoFL9e?~BKaE()N|BJpx7^F#8ThV%1apoZPF*2Y4EUlo!lelLp9It zN$4xVN2wx(@yptl4qH8RIjX+r9LwX1T6{bL0)2e^WArb^9Fhq>F!wy4hj;E^8xKyO zs}Auqc5+3PI1Lw}hm#!1z$8=^Ds40*x$HQ#UvlV$yEmEX{Al00RANl0WheT+mZJ+U zl(ot_#2v_kaVoH|Ipi-uNjaRSK*uM_?;LY$ynecmnhx)gDH(OPs);Pkqk5Yr&R zdCHaWYk)D@oU88K2%wcX=rzhw42%4Q~Aw6AQ<5(qWxpVsisKJNTPI6i$T@lP`+J|@soQ!$>gv*G+AE4&+SFScjy8;>k9Xc+E4jtw^q|)S;E$SOTE}`8cP-$!Ddtu+fnIk~vJOc;+ z<2*jFUm4CBBOo)D0UODHH6`QVe%8fMx!Wbd)&0>+f#;Se=ApaB-=})x`MU%jbi5n= zN@DLwW9D++HUJN?$yg_4KQn}r!`;I+heA0OB`52aipyNbFSxl?lNwxpsoAy5zghmh z$HC`UBS*$?K&aPNnj#Fu%}-cb5q%1;86OupQ=(=z!~vyg-IVwJhYs#p)*KtA%kXJ2 z@KX}axTalPr4BG+paF_WXP@Kz&fWJ}7STMRGve9?+Pb@rj0QeC5yYonl3uHAEgmet zoBv}??pC+K9q`-W4iiY#KC~M8aw`f^qY3aEAU<1`ljO8Vj6A=yO$Jvv=Y-uH+M(+A z>Mow7XyOx2|*KO1^OcCXY9tR9OvN-YN9Sg>u=CPt@ z=sI))LS7NQHg{Jw#teSsx7)K48w#voToVFoz~<$=)+LR_G8GvY;vPdE+j+oaEn2RX z_A5i@R{ZtT;Y({)WJ9%--Od{G+F7coY*Zz=5izdE6#^liEoz+SMlg@k2s;WY*(fOB zBGk;R+LmEkz2CQ{>QI+qZN`38nU)eP~D2^!3<1r>5$&a7}7RU%T;~NiuDcfpZr` zzX)QOvk*aL0HpbjIMqVY)T65+rb_p7RE^}Y!PWPD%U$)ynNJJ&3hZHD?G`z#U$I{d zq}WoWQwd2#brup5Vli(G5v6=#$!y87YT?59%zeic-ql$*OqBFjDm@(2kOAT&>lJz! zHwh!gsU}fMxO<_d$z+5ywhJi~f)|{)5=LLp>y5}BRjRD^<;iwbIDK!)T&+>?(cMGU zUu#K_-Zl-Kf7-Y+^DT!^9x$6`2_;g4C)0#%4vL2l&^|u63O|3m?&@^#8=0_1PUK&1 zCqx8SDC5ZjRteaxFSl137eDMXqG>F<&^xMl^t)$z^?IXuhvE3ssW%eK;@SxgFSLte z;E_CRJit9ijZRPI0)@Zn&BD2rv!XYw8F`OENl5$Ga{h_JW{R;#FZSMYMDwmBrP_}y zY{4pX2a)tZ1dX4y3pG=gah18_SE!|7?^BbGlJ>bV>aT0;Lkk73XC= zw7~A2$I~NG2^dxFG4^pzHlWr{*vnW87_>Tz6ofYB315SLaT7<;Z)h%V*k1=3o7$@3 z!rQZ3zO(E>^#8dk1J70P20&W8Kge90O;y1^+vl=1!6H+@jsArc z^E0m1A73@X5hLFwLvY}KuDD@C!0NQ%=x%u6-qW3z!EcctC_c!hLvBwk{Z!$N8(|wi z!k%ZmV3;QWuxYZz***q}}7oMN-FI!Yh;p?P~eM^5)WVxl=U}?*%=_u7% z1a#e}4YgqyIQAM~sVqFZ7F2LEPU5N|Cui^yxH%f>3Yjf^0k=X;`}v>$OS9CF3fA^K zuIaii>Qfc-@oPqL>vAfhdZdl8&B8s{4;i=0_xjb^idCG)RdkKDq{5yZlj-4N^;day zc-Q+FSzN$rB>|jsC>*$M6L0E<8A~KY68l=&l{*FLEzeLNL#2)N4iaxS$^_qmU+Mbu zMhRc&=86K&{hsn>^}uqVGk#RA`r{x-!GsjD*s@#b;h@e0IQKW`sAi;OgfP{+raa<` z>qsrJ-@Ve$+I;Qm`}&hvf^4-YnUZO_w|?K?|2OuAf405s=Xn1)&!C^{_H*6-XD}2X zp_&%)RTKIUKy6&MFNvMyf>i(rXxv!Dj9+voh1{lYIg_f8y7IMs==_G4;ytcOFO24e z0lqLyJtC`#D+f*|O}1xRyV%+1S28nSMH-!^bQu?+sW;qrbSe$qdDCH@()BK$@OwFu zGEEpi%zT9eC==v%e7W=meKq}Cc3XM=i*b1)n0A5F9m|_~ozBKJ&XWn7erz51XaYO1 zj~&dq&Nj>Wm3|@i8Z*a^e?F_%TJ3pI`>y_8PG;XOcj=4$=e3R(!~CQ8mvGRLa4Uvn zGB}-ng%l8pMw8dni}Hg#tN6dF-_Fh*ANM(SrnR$s+(Vv*3Lg%?Wu#OH@i#|ah<$qY z+beb?1ryPZ*r?Cj;y;(Z61QPbFfx#n&|`5@v}mlF(Nv}pR8^>5qp z1mCRp*^D?W)#@5E{^Hw{ncrm?vwFB>q&t4Ro>{%ASbB~f#2$cDS=u>-B(j*?2+OYp ztN7L{xsl~M!?Ljo&_f^7t9CPxW@Ui*N(>GAiCh_}k;XFPwqSLK&}CR_q6I}cd-hb8 zY-5UsdsjPdYC3%VgeiS(5!m#WEQWJ)8gy_3#1hRwsI3awhD$t0ZhNMFQtp?En6s<0 zJG=cs{?xkD_e%7f);-=0eipc_3C2~%_K~Vn?=x7;CB_WC4JmzjQ5i_~qWyy=Wa;al zWt}X9Drz0XA9&c_?v%FP-&GD$eU5=Ilwe4)#bMN5P8`z9?*ZF_y1d)a1+)#Z&CePj zY8I*TUh^MNK4JDMOdzVb(|+Zh<6*WbC?~CgVoM%T?jxS5Lo5c+{T$XcpH$s1Vkj5- zlOqq;ykBoR=$PHN+gd~>2xq!kn4WHK@4B1lV#zDzrrm(+;?D6iBQ>|Uc2BU(% z+8j2zwVfBUok!x^;2(FK1c`pb8)a2yp@E|B)rXJT8{iumXU!;Uw;V?k;xI?+%-*Ci z{f~MK?4MyG?uUff!wf<7#Dr$t57j?6VSWkNZyj9o6FQzF#04UVCVwQ`Hss9DfBQKh zKP}|vv+#3s__$Rv0X5Eclo3VH|F@eoOMPTCeTh;-u6$%;LCBG+@~P literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/Aocoda-RC-H743Dual_top.jpg b/libraries/AP_HAL_ChibiOS/hwdef/Aocoda-RC-H743Dual/Aocoda-RC-H743Dual_top.jpg new file mode 100755 index 0000000000000000000000000000000000000000..673b031aa291c255897618ebe2b0b7ec4ef61c4c GIT binary patch literal 290142 zcmeFZc|4T=|1UhUuY)XEr$UsiWGQ5nEG5x~kf~I*kR;0OxMz+W( z!P6$EOi(N=ET{(X54AOgvNQH~y@f(qSfCD|P$(`GJ1Yx{9h|X%<1{Pl-_P6UsB?n< zIN$!`oDhl)Jb_c0sB^;q?R@(>6iehw6sja)YaC^S+QGuI{qxTUD?9724^D0YG(Vrf_WAakY~Q|p7x>}h;^f-C;(zV2)qoP> zV!O>=%gVABwL^%7RfuJ)1%&~UvI9+QE90LJmL05Y>>NNO9$s)kg&+{0m30RYmYoeO zmn8(ej$#vH7v6K|ILFR&*Esiji)cJZ%I1d;EAr9f= z=Qyu<@7$~LfJ@{=Qg%rrx7^|L6w&K}tA`7BBVHLtujORL*Lg}>NB-N22C zU#{;Zwd;_C^pEG2nHpq~Yt)w%Or<^O7c}qZ%x@-w@}ALNN}(?Lo^79>uw^#=58cL$xHON)5??;1jD|CVt3p^y*^AKAi`r+ zTPPKmEmTw^)M!Ke)yYuaLOrZ3+Cp_mqL?kOhyq)vDGH8qX=U>;mIs`x7C@_Q3ICsa z^9wUN4DkYl$Ca)htT9;YJOhoIHsE(riX)>{k$2Ekk)2+Uv9s+!4dg=M{YV&$z`=e% zjV)WKuxy4MMJ#qYfgk^=o_nbF*tD{euZ)gW1*NT!;y8Z#!AuI8mT=%pL-;RXySp(A zy?Ez#r`oDDYFP;3K6T`po|U2q-My>*h6(!KbZGHXvw2%V6l3M9EtO8wwiCjD=p0Ss3!E&r=Ow6?#3v+-0}b9L6qA!Eh#eTtpk_*=8=$V1ZJZ-0rJqJntfeuOIz#8m>tiy>M@^Qju}_*vFl zujKDJd8F2UszkBdLw!R04r|BQ7n6%|i}J694R6s;hw>=B`VS8S8Bil7V}EdCWVcX@ z;!azrJagT3OIU80@hX<)v4tvio!UY%bs8OQwosh%&=+BYV_T>Zwe~I4*;L>8EQ%@N zkFogTIHEz_Z+41X@Ve;zoaX|<2 zlPzBstgoUO;=^rrQ4g@>$6Kg!1zOsjq2UYu*7h9U!=FE->ba&N>>|a)$0)ohLc&l2 z+7mqMl@`(!7uTlLd2Ic)+sKVh)9ON_-M(+#TxuoyzL_O8#QRj-5E#F6woSoi_An4R z7(enI`eZXTvH_~9YgqUrqwZBG*0K;Hub{^d^o=?_aiH+`tNF;+i$6LHkyJS6>>c@l zPFf-N1Ofk;$(8d_Q_v%o*Vwv}j}%5?yVA;9vxaV#(R1gw$COtyV^BytmK+UH?A5uT z#;bU=+lA&_!b3zJHrq|bL)c=HYWfPRtX15hQM_T4VE<@xlf|#46 zB181a#r~yYNxft44S`Q}k|4fpHB|+p1gkFx1IbC>hS#+WG5euLM~GaQ$ql036zRfI zp7|$FTKKf2e^0*bk8AEBrtK@cpD$5mz!kHrS^3l+PSjhLXDOECw3aMbKb%%f^@@J; zvF9EsVp60((D-F~|wpHx9YeKbSa+BZ>eC&;u(`5AmiM0FU( zR61~^o(oeXWG9fgb@;~*5f=J!`aXbHzp#=FnVC8R(hNF`Av&YZ-E}VvnKdqdVlh~h zEzjvf4D2zxboYdY+VsIIK1odRV0L(J3L0}K4@V-q{S_}J*irIgZ_5qb>lm=M)K!#_ zux3el@TK%UP^;nYVTu!OD2*X`ZMw^-g-9_bvX4)G(`vC(t0}a-9Jz%`wPKe19L+LZ z{U94U^YSISFQ4HIG&%$|4kjVZ7#UyeLn2$S4)AzM|K?^(1;V5C$39;@bWYcDa`Y*^ z@}CUYnRTct|MfNe^SfGufyHl0|r7h6`mSiXlGJ<-bUo%*!rZc;kK;Wo}n{w>E*T)x_$VguGtbcaK=bHF3uR zIuBfCMNwR;pg?wg%aX(A`xx%8uh^fiJAbl1;=#uEd&@^&qL(wPNn=toAbz$`H=!`c zeQ@;53+rRzO?aWwAm(XmQr4HpcTktCF2DFIKmV=5vry^u#ey|XM1TTZY6^no?pHWF z-RT*JV_WS^Uf^FN_J;C7iNp=sByfn(9?qZLOWq(-Uj*N!&c^xb;ldGNidQJ(K$XD9 zkja7@W0_?t#~+zKEzfc`x!I^B7m^pc$YJ>uAP{E|ew17C-C(`!hjU@=%|buw;9&fv zKS9PQ{L2pTav(A)eDcdjV)IA`9|w-lG-X5LE>`y!UKnbeAys%iSRYZK?#rTdw~gHm zEgPS3DZPAprba$>^`*7J8wqHX@Oey$m3|dCh!xa$zLp;#?{(&19*mGFrJsGi9tM}* zQ}>168K3Q0spL4c(jeT@upDoNx;Za8*o%KonDs;W0;#vMIa|BOIF0Nhk&chOzhh@Z zSL^TjIJ~OwUm+k4fFYgF^rq-W(=bZrrT z?fv<2$JKdbwnD?O{DL(z@`KRg1^CHyH>__;s~KLW#}=@|xa_ghqcLBGn+Ym+;u|#k z^`6X|`!4EQ;}|kOW>k$@NR-R`Zf&bmxfPU^hUMhYbxd9X3ax%o#6O zp0v2~*3FOKH$XA;ceSGp{p;Q;+ow;yEg65-f6|2tIf@G-QZA{(`f?Xx3o6l(f?1rI zBJwPZd4|i`I>0r!n4m|+%a>xlc&N_!H$LWS>X18lmz%rF)oaXhd}o_(R5Ni@YC7wY z=CiTkOFgxF3f#ml2)ys&f7)k43Rl8LK-}`*dpPGY{|4m-G=LH&wosK9)4a_-u7o<7 zHS!AsO(i=ItJo)82e{V+GS3A~fXL#srv8c}YWqIG&Tox*BZFKSn$}07Hf-Au)T8Mt z=sJ8I)W{8yr@PPy53$fq7Dder&x6IMf4*QP*^kpLR97a?RDzN;(Ad^E=IW zEP`(0CBXF*1C0R{$e9$1$HY&iof_0P%6HQ_ct1HP$VD!KNLKbe0^BMc^+$XL$B?~A zxA327S<(p))}eGajOiW@(9S!XapA+wWBQ|S5|xGKlk)nigH~WYBJE2}rOV8)KC4?x z!ldz(e=M3l_h@zw_m`#>=e!`uKK0n!cd*|cFO!3M=C1#2 z6Oo_cm;HI~v!&^hjMKH3IFm$rKYhxHW5QX_ZNAHZm3QNth?N_Fcx02xuu;f?V7; zrmdcm&6uJ)pLcToBG_lH$bQ|#L9w&*1E_D>pgM*=Y4(s=cyE@x%q?pXy+<#2 z;Og7fyAOCZ@C!B+w7aiDN~e#Jd}0?b=i}bW(t}6YgnGg!iFKGT{N5TW)JWi(A6^X@ z9?Ok&_VeB?<@Z^hYw?cm&FGi>L_s*Ly~&Q9R`71Z$O+Kl)hiR()=VzgA2+e`Dq zPA#%S0Bk5$mazVKTNb54tBaN9OUa73N(qVkIoaJZDOaBPlYWu6F;m%F-j(ODv&&OG z(Z;KBrwI#r3~^JyI75Mb5^?2f*>ApS70vi-FL!t1YUQeTOj;e|j<=CmdOl2bHpJwW z05xw%^m)h6`-g*f^nMK8V;~-T1?z_qzD?kcQ(Gul zMYQ7an`R^TVpz|*tS;_eroyVT6+YQWf}zB^`JRwQBo~q>m(Z->BlbbJj@AZDSKk`a zDmrcQo-*{nlfG|g<-Qmfj?I_{oqmc-&n8r2^jv*5Vb&BuLm-9wQa8vtQIk`|(%Zq< zck_n~b-90jh|zIcSZ&-T`qymxAh-xJ+aa}l*O+v@uuZ_`!(0>x~U{R z?ifDIuq*g_|`Dj^Xo-<~i>(+C^OyIhKyWtNT zdF9>T{MBB5#~(gth?&$`{6RPJH>bUarKYkTO|lP)+flM&3sXV$Qp4q>_Av2M%KJ-$ z;d1+bT(*@pzCZW}0##cC;6zjmL#WxbthU;<=r=~pjV7i9{dlM<@5jzrm7!m>h1#LD z`M?kppGC1xfOS1FBj}lkjV4^UtW=M_#|(sCj%^9dt(uilH~p|%w8CuKWisHR^ap|b zDBe_$DXiwtZ4d(#+EwA!74xZ1x0b|$sgx!<-zUqT7QyWF8~zfW=WTWm?uisZj)YixWC2t zD&=Rb7sJ4@2p!cFV_;;>-*KwEvU#ddUV!pk=d6m_dd(> z)?6Lx3ZfX-BLdz}HbIrac@rp$lE)D8Y8RvF@O#PD6#d%t{W)2BoYwMJanQ}|Gn;Yo z4~JJT8Dic-RPpwu1h6+}83n;-6t_^~R-kbGN6yySspnqL^6bX$La!K7r8VFCw{ zyQS@FZ|(j#nZUkag5HocR(a^lmm?U!Cdp6&>k7wrieV`p2@Fvma#UNwgAK{Z$CRw; z6#AUOUP{fCQ{H@nIq!Kpu6{Mwx8z$;+0*gY&(P;fJg+wehSqDa{4T?Rsc-z;^X4{# z)qQ+@eGatpmz%xGG`+w3Kz^9HFbeeq*S)f2Nqyx7AB{qIk5byFx|`^Fu`8ii7BBnr z!}=z@rN`f%bdD&V{mjaX9i6GFI?t=^=)k5X$hyh*|AL)+Rw@?Z1<22Kn>xFAlS)QL zNhOKZlr2=8KKAfDUX_xWCh&{kgw<;8s{2TlzpEBZceoaL1$Ff}Jr>~tY=-?690Yz} zV`hFIR^3-hAtuzS-!7V7;qSh~>Y5|qnSJZWl606+rWJz_#sZ=kRt9^f8DtVeIN?N^ z#gH0t>M)$)Ef}QEIcLM8cH!>wWwjs8s)Z+=*u(Wa+0RAVLi;ckI!k(fbaQ+!q6x=> zRxIb#?@a9vK^b*Y&D;vbFT|K{2CZtO^@?c{V-8Oq^q`=N#L6s&^bB1QY1{C#bHE?2 zhM!HFpFdZ=!g2EBL+|>oj{2o%s+Gxxdh+)#JSXfTbY_i7A!t`Pds^?qH5f+;Z^Vn1 zy2Pj;d+Mr()WWw=Aty~H0oU|RL2`+LE-%qNSyI5G`-qjK$LC#!rw5B4^F2&V_lmst z=?wnMPY$T-allg|1&1Er>)u_iv&2h9cdFL#-j8{^!hH<)wA!eG}IOM`@C zZLuMT@89ioj-6+7Ls#GrfaEb$wFsKnoad1*#EKVP@oB~W;pgE~)8@nj*i!#e(U{hs z`24hz)F>BhyUvs6@yfs5n+}&wQ8bCRo&3G?CMxDSqhvmyf#1g*k%9 z*}{}zG~q3loJpkEdL`f}XI6GLdQ(VkphFP<{$Il+pVC_8ZAPm)NY z04om)8CD{6V_|tTXsuIX5uRB7vFKOPnVi1#`@lWaAM|*1vM;hU|GQDS92fnsT=YhBKKnd7+C_@7hQ(1 zzwh>N&P_n92FGGt^nHp-OD2=RL^9E&uiVK=qjvU0>I zVUT>3axF78ySkd0i%7S-9%%GcjL~e3G`Z3tl~G+;B15_3?I07VxCk_;zedd z6t_^u-+DM#3yejqSir%#EY6VN7MZ1Gz;k;)72K{De}7qSeC=>X)!6Z+P-&<7sX1Kl zAas;SxxvYJZrPqi7uW1&?oTDYK7c}i{>Y2|&It(bH7ZMPlH*a$5TTbSsK9dZ*KtmS zZ5N{TrwaEbi*i4Uk(<>H`sRmw%YH7>FHq@S7z-(s*X3_1LAz zAk%e&q zgo?*hCK^^IEbXciR!PRl&c|`d2!3tlB)>78!l@1qW>Fjnf6P~wM7K~*bz3MTj_~xK z&b-1(vy1V^-m;83G+|cekQed0HP!e^fn2Ovm7v~@@6*KaO=J~&i}Xjw3kACOAM!vf zXx?L4vt&psh^#@4yC4_Qs-){r5TVxVorj-_TZw}RmK`O`XcNm4;3K?b5JwEd}iRxG$&9K}^cM;J)%qQ9@_OG!H>$~U$8{NbO9qqgj_Sx1ewP%K)1GH`h~ zic20N7uO6>KzRYPx!a0!Jp$JS=-#Zz46Ow|Bxja8S}S#@q&@yp>taTH$aYJD#h`*I zKfDI4!&$S1`aBv8KBwgL3Wy7S6n<~7u?Xs%F(~9gYwo$A!?u&f)w|{hn<^$$m^?6L zlv$RI?!d0RpQRE8zc2t{57*m5{Sd@$=*^Qh)y9Yy0S>9d8zQtVl#ITs%s{MGpZjo! zX3RmE*5>8iLC@2_FO)NLu-~WkfdEdj*;}YL8aCp8GbtIHhQHL*@H()z-cd2B4_X}x zkta0deC|9rwJ9x${4RiXm>Iw`r}e>K3xbx8PMv@^WjY#n;zW`#2?atuXez7C{ zt?5Q*-uV1fe6|}E7~Fa`x73zj~3CAe1!JP(ZaK-Uj~H{YM`c2Q0NPE$Fb^XEV5sI6>PrIzO6tum6o|pz(&2>&)Hd1t`>@Hx4`3^x z=I#;VltA_jF?#YqA46{HvHruLg7!aoiDA}CuN`Vj-?Ke5>@-x|#g;H@gz&rrmb(*d z$$X=(h2ciJsia^>%GRqc*V>IYoQSZT!klX8Dj9U zckX9I@m+=fADOqOCm5H@swO+@qq;B5vqJ{5d#U@frfP|-{VdJZ*lf+O0Q2pQaO7V9z@LTXUepy(TT`; zJ*kC`BP-e38_H~5lHW`MUx%9fFo@b4iVeYfp~p$nRSf9>`UOk68q(o&<<}O9_1?1- zhV#r(xn$*#^X$PAxpI7}I{Q~W;Gih0&K(I8NHf%^2a#V81+e62xU$p?%IwtFjPK*k z(d!oHeJ?-+M^Tn#PiX<$85YwoF+1L(Y^KB+Qfa_x_=1&~;RaHp3{m(Q`HFgDpy-e9 zX%;heViF3e%Tpu4o6k+}B}C|*ERo*3S1DHF8gn$n3T*T(v zkftd$Rl?qDDal6#Q*O#79^c)=k@BCEL;qQ+^nd%c01kj5?3^%X4m@qicO}>pHgcaf z%UQ*pPHWS>>zMPbt(iN+|2D17eRT~HIL0i+?+*@QmLMWX6Syzfa8hCbQOpsSRUTAb z<~w`sL-NV^KGV2ANll5(sx4n$Ysj6feRtEdpqWIurL)-XOi7i&T%_8xny-ik?8<5p zbh93!=e4V(wsAgon&{nC<`njwF~G99#5U)<dCfgiTA$2qGt=aG zCnpc7j}a|kQ)-pfkbyk@OZ~y;gs5O+5p_kH?)O{vHx%M5WRGWdc(Y+NRG!egC&3s8 zM(8&t7TM9uI5!o7vm9pV5ysj>^4zo!a~G}b_WmGmDlK^YC4W8xP|EP_?T+t3mLm_= zvEf)Y^}=<_*fWtbUJh1eW3Z_l^E_)x@|w)?FRcx`>n|MxZ4FQehmEN-b}Ewf4cI9% z-#n${q(71T zQw*L6$Y$^|Uui{bcUZ5d8c0xIj7MC#O(_|hEFn8&?&ySuo^vv1JGW3@ujuZ#lMwBF zCc|~}=8*%Y-i8>`peRfSjVVBQ8hvJ&6$qxCqC8z$Cez;P#WlLzv#$5f8yoZcS6a$l zXy}UJ>z{HzlMmH~eU__Q6#W~(x4V=7Q=9j-1Vq3LkbU{!Adm;HBp@$T76!581l($j z`e+sMIS=sQ-z0WahzxE!?YHkBgWo$517@1b6T0m1{pAd7xrZO3r{gqPKSoG~$h8=> zmU;}9V%j~%d#dl++RBBd3-boJ`|-WW^9}+_Kbl~fuk0vDT=So)2A>NxX6^L>F8{D< zHJGT52zJ?jop}DVbJzGvjhEvnVZMo&N`eoYHw30V0`8NazFgrUu%y#m&qfUToG@Xe z)tYlIkKSo6cuc5Hc{BN+b%HpCLQ#(hs$`}iqVoYxK#@zzps}0VJw)8Ku)&I;{o#Oj zwjjx|1z(oOQWXblRReO4D{Y}NX~X#2F(C%_)sNO^`-tfOzIqUsL%3$%{P~GhMuaDD zi}b)p8|^P9=^Mx{!VgJe5dj8C6^I!Ikz*ZMs|T*Finr+26Y}l$)4Nz|lNGM(c^)j0 z&A+$-_Ms0T9KnH#vPXyN2dkE_URho37KoE4(`UP);3QU{o4d@X#Ftd5yiMr?Sm!~; z;pr=;=5-15C&zu|Jvl3XXtFeIGa{P+x+?Dz`q|*4bcr}esOem80EcC@Jl(Ms-YRe z2f9Cx{{YSHpf@3}kDU$>|Es;8nHA~2?ncyr$jj)c^t5;|zF{C=-#@jMO(8^UK6ZrB zweKY!SCaLn&Hq~ar4eMsx$5)Z*CSkN*r{AZ*W(Z{hfomup!5ofRyCS%+pBwOyBN_Y zQk;fE*Z0@UAw334tM`A=Ha(Nx{Aqu@R$Ha9gu7B8Yni*gPWa^(icN-KJ!uCttQysV z*7HhZCcFyCk~sl68$GA5kl^b??S*wYM1Tp5>#v9KazX`;MwK0{nZkV)G6u){%w{gD z+GnkBtCA8<|3@i9 zvv{?Dh%OVqr_K@S+B2Szv<;;LH!-{9M3ym{u39XisyA((R!Pr`*59A+YVFd_({Jgj zaxN@nGy>u(J3(91ysHd0{0fx$G?E5{4EeVUX~N&-&ff1J5S@t5S*3r0!H3kw8pu-J z=}%UC*T_a|a5T;nYWyI}I#9nGT;+;q8=rgsrz_8GZ9a_;zi4GY+N~02=_$@S_{=mA zg?v(`;1G1;PGEC>x{k*<&8rHI>Rc!Nn5%&-*6F=Cuw4;E0v>shnT}_Ni+B0CN@AjY z`PJqvmo5C&ugQj{C>)l2kr z7Q*YP#>o&Jrp3{%`xP0AA9E+_v;&sPsH0T|>#GwXV7HT#ouNNaF9BA3vmR?ZpZMnj z&OfQb-;7>*+>g)Z(7|I{D8B=AOd6Lp^1xQ86Cxli&WUg}(+!zv9l}u4kq@MP=dqV0cyS^j z*oK;c8>?c7txf%WL$yS>_t1~KY@Wor3`jMmRYeQZ`&2*1MqQE_$vJ~szM~Ak`)6Hn zhDh$)a}Oey%kHFO(|$lrdWFn9zYCaAd#R9(MaE&=vx-f?#yR|9-t$x&pf$SnSD7IL z3CgW^0U`URoK8vd-jhJ60cor~hZbE}H{TL|jw5Iv0GcCN>>B~lO^~#-XF6C{yy)&L z-Idx-RKnao;tK+7zzPI)r)H7WVk(M?Fo$j+q;izD-L^kb<$D@152hUq})gkVkQ2D`Lyi2N9jsUO(0 zdXD-#YyCC>SH}}B|zg^RhAg}n*hDQvVgV9Bt5(0f5tH;|;DUVet}K)qFZ@DVCDg9H@_V8Pr-4pVJmAp=q27 z5H7a7%KiCR=sx1dc@zU=m+-oXMiBT%+z`vOZScID6F~p?bWOgE6fzF+4X;MyhBg>7 zK9sfd)D?!1dwV|!NU)>%c>d$rqWj@10lWdyXB(ihSq_7k!XTSfqkpvU@dLn_lTR!l zQb98u6Io8cEE4)X_>E^YSlek__7=p$uqJ%#hBbH_>{4czIH}{UylBR$-z#X>F^4i) zEOe|h`Befgb?iil0S{IZEfkK1+0?dU-XVMf?PWPjMj^rmYkO*0FhIOWhui6`T@SQf`wN@lNbuKJilskPYtWV zMZ?+K?uj>^hLya-1UwUB%F!yB`T7|8PULI-0XS=>gVxVDJf(No_wG4Ai#vaKrG?Z? z=58eBE6MYBY8ZaTv?VY^)({@knFRQN;*v#Sun9G;&wi{#`=eM~Xr-Sw3Dr8{X1=Rm>c{wucZO-!Y4`gI-%p&FmykC- zZ=}4R?V!BiaS;~JTGEUk@Yn>JOHEZ3{FrJ!MGEy)d#W$wAKP+2@Wzw%&s7dJtjRR{9#EV>MU4x} zy!MuQ%Sy|ba&E(NF?=Y6fg54Lm!^oje%&oOIdJdTS(y`qBfdLqFDGW2N~~N_fOJWe zbLxK&;gW~JPKp6HXv^FJw)Ky-g53+;&$;0DQtGSj$*-B`Bo~!0N#=KZsCb{rUko#o zv5LHPwHeHPk}cb06loE#9C-!fV&F%^#B1uQLTA^~Zf7}ve4rS6XK`HKA--LcW$^#- zfd8du2frnu;z@rT4WbU^<$XKl3g!6+BJ*SZUu7lEkC~XtPK9D4f)4}iBQVZV6!sub6v0MWA$q5`1=cT$t^p&;-19Kyg}h(d;cBh{Le+xzAUzD zbY$rgTXGN&iUIbb!p{HdLB>fGU-Xg@HQXw~>vp{eQmy;y2Z$1v+9;hQdM4KvP5J4WGL z8mF*2!0uFKqbLW;*AKE1mL1+V4{~;VsCvTIu6g5!Lr@q`>IL{3C4=@D?gr~mNBYxn zyvV+>1)K=>X19cecfi!+)4hhtV`uF{>Ss##mtJ(ROXcwkcpK1})w6`(0X5DOt5j}{ zPZ1Ya-hAdusP-Sm?N-)2$?dWDic>G;z2}vu4-$JNQH=A@&@yLB)N|E+2q|=x-8CEEt>AaH+(YWBrzk^jcqxq`kwy=;ppa;(ROiJlR1xkJ zGnOjcyI!|L(fMZ7#fpT(d-;}d+JjgAnvoxC1Kake0p0s|wsB4aBcEQlkCz0`C-L37 zU|_?`DQ|8I#aphNk@4)Csc7w~+@`O~?Gcx(PAP`62M`$20P~g1U=SKtYcNdR%fmPT zKqT17iCTtmMNym@(_fo?^op$)a1B%)-_y+HdGFEG-D9*5FVVit=U6u=3R|(!{F7?a zjFE6L(4j2)-5og<^2Qlv z#s~X4siew^5kJIzn;#mv>HWQmub3@VIfRlBI&O~v?9v(6`r-mDfLR8)sE;GXXD(AF9{xMP%?pvRtrF!DSMZ3rjil_}bI4 z=*|&W)tQ0Y)6cK%O8QEEZG!n^8z|Vo4dJ2ntaF&M<+|c;3axDs?=15saJ&Ttm(^B& zlvVdn%v^Gkrp+6eNYTE@wpyU>MT79Vi1b>g3V(CMh}3hA<{WS|72nJ-iQzC8b603! zeKO~uzGwli`Y@kW73e0J1{%Sx-4E)OD3jrDWpr%oD4X*-!(zhmCc9I)bP72WF|Lj=6h-qg#-YG1ii!O&|1 zGY^`wMM#r6u#+G5$xW(hGuEZ@1T>7B`+6&mWeerl?^wm)2*p|xZ)~APXK0teVx6E{ zLH3Yj@X5Y=FM`^2^Z-20(-yVVcbcR3?5=odzIVJq0khZhqDJI>l|RQEz%J$NB36FY z#6aKG{&m|a3Q{aG+mmqy(=ZI;(F99=isOLD@9M=VlNnT>lLHkTl(@C-97or&r5cz2qH{_lLtBJQIgk~PBq_Ppw41R3%>%N)t zfjDtD6)oE(kByG<)Rx;m?TYCrBn%AkKqDJu977zUNtaf5I9pH^BYmHGm^R@L_R3$* z?Nf{V)!9=OtWkcq3H~}{!ZXiWq zX-nh5a`QumS*1~nMPz6sg9cGnnlVwj<}R6NO6_@5C$|j^hiZ+}Yp0jw<2pN6Kg%Vb z)tE)`vHS#F&boVS)oTP)53N+6>4=n;`yYp+e(&Ggd&8G+=lKseE6P0bB6+QH;B!Xqs@HHyMh?RYWaLW&6hu@0f1uvlMiz5<3Hhk?rR0s-QpV-MD#M z&^z88XzL*eQ&KA_Axl6rYnQ+BOj-k0#2f4{N^tGC1QI)5!T&<5on zafS5`1>TtGRru6pz$hi1W z&`!=5oATZB*X8SpGr4HF4dRp^XuG0=MPQ#-{-#ZV$KoGM5%@>j^X5MKJ`dVc7N*7X z==F#|9_S06k{<%2wBc0jbXp|B6O0|KwV7u6oThX~mLK6C%6>O*qwMAGx(iXfzgxhJ zbs&-B)D9vCC{?^h#%a<(5o`FNu6KBl9n1Y982r?lD*{?F+OvjrQI^z*FO*WnF|ltU zIT3p4tosv{yi{I%?SmR8apifj^?Jx43Fz}i7CXr-5e^-lPmjpCo04#TfUqL@wMnAn z>)w%N@ob#~BMLUs2@EkT!XHt=jKvB+wZ*PyR$r2THyWT@O#d#tO^W6a(yOYWC#>8i3~GlHqqIVlkm6#y;vtb|1q_I z7iYN|CZZZ1T2QB>Cu%(T;aXBAX&P*PoYK5dyA@F+#S8N}n@Ym!^w(0LSz#vwC@p zuI)>|wRU~ane$>Dnm2aDolaUEUNB`yenlmg% zO>1>L(t|(jZ$o3X8&QA}jBeq;E%EZ|y)91HX6I!)Bf5K)-wkQQQ9RlzK)JW0$8)7#7~hX6 zBgEzOM=p%(nRhu#jcX~ge6P%GJKD=l)-w@#9(tDF4+51VtcU^s!Nq=OhL|}mmSWlZ zSkY>*7MtBpaMw;8o!1!o=#cw??Lh0y?xa#zj{f%Dw4xUm$ed9SISEU-=iG$b!C)V* za4*_HZ%G$>203f3jQxBcelbOL<@T+6tbsWi5{8LlR!%DB`&L<+ks%_*J>fC-8X-!q z6)TE$A&in5?amZCRfbre8x%7i-lecRS|#)HUpu&MlO9PY#k*O;ii!*=3s!*CVW$5kMQ))479H%{NN$4__KEz)qnCt9-3 z?9-SxLVfw-=ZORmJxQ?6Fkm-fLH>jH5+30y(i%Jj>nA34n7WaON+C_G@)_v*3GtOGraVIxtIOLTE>0jmxshC zMhY2cwon@7=1DTOH%|$X1xub@<$`WtU~R7!Ocn9rvM=EwwmfffZ6?-UnEjh|T6&>P z>gBH_-7$Ol%-th;=C2|f+q^H}2Y~Tc;<4Adc}5mUU}nKcGI%3BwQ$w3 z(|a|?{90`Ur%Hq9@eaYGgnq9PI>P^sn#b6g0s6mFS+N+7`aNTI!RSb-2l=jnZ@v+V zcFBhp%q8dCuDx8aXhaV7YR5?%$h%;K?%9i* z!?o&D^!?bw`!77azYt}PPR{vkn8)7GY87cW15DJ?2b8dHG<8%T{6OUfDeTt zqmDEX_A?)#8CSC!adg4o*zGT4Rv5Bx^ZiB-B6$S;aB>e-JqFSBx1630M^JNqIg{?X z&e5ujIu?R-a-WgzC&_PLzWq@a`Ed6>OJWK=1@{$zvuwhQ`c6k=kjN4&N0_(EO{0X( zn1z^z)Edv|09NBd*vFlykScY-qg?jlnFgVs(xG@fgB3W*Nq;$7I-KDSwthH~5nS1e z;YWm=RS%B}w&C9?HHptvyv_acjHTn-BaE+iTB3#rCJ%w!t$`T8=##ZWT2L$zb?*hM zc~wvW6BJC=10L5(BUqf1MhhzsD6ys9Lb2e0r7;v&8{o}jiZs(6h6P;?URaWqU!AEg zAJl>bADf#{PfFoK`kHqJ9Nrme{rCjyhszvBimyP624O?`>VciY1R3(MMXvEQI%ZNO zX685-fkL z{@pakkY$Ty4A?^-@)G{$I^Cs7H!9C?x7GiwUvUdnlcoZnTYXSTl*W=vu#^+spyUR@ z0n0}ZG->H{kkI$K9?2uRhs-xEm;m+B{ubL;K8( z*Jq^%;=2Pknz7M#8Vj-#!%h-o_Z@7%epp@h_}+M^OX8@tgv@ci!Y?5v`3t2JjjtS! zJ@oDhPSmr{iQ-vh*E|0Gj=fAP3Q{6c&S$|oAmK80c1+*U-B&`t#@N@N{yU)8^&|4+ zomz#v)ZIvX4_)OU9@A6OCWJ7J@r- zZn$#eZe5JNo+A9cUBkRu+CJ3APlW|uqF({`3Eb-*IXtcJ$PZW0 zF9x$vh_UjO_U|;SuTeSjj+NhLF;c4Nzp+}iL*itH`F^$?M~ll4?iwKV30Q|7fbSW? zvq#ZB!CnFH9F!f5-nht04~d@}bb5Ryxt(R8XmMtZ&24ElpfJC%mFFE{+zVD~XY358 z84nojgx6@#;UDA|M(2lv6<^8Uwa8savkOlD-ciY`Y;8-rMN4`0$lzP(==BqE_-jDW z3{nXx5;=q)msN#7=g*G;Po#YOJOieWqh8fxZm+F4C3Aar8plOWD#=Xqjj}Iuc6~UC zLL!Mb(WB-KfWb6aq8VC%?;5>?ZJHDRSX1^-$bUUMx9?fEhPj+@=WMd&wa{adparp3 zh44NGOB98HJ=u+VvZ+5`Psd^()*qwPz2?mlugkY^_PHim7U1`(@8lb&?}g)oudg&L zJ18Ok&LA)y7^*dJiOxe!()b11o$7kJz1?viU)ehMyiY!%T|vyup_n}S^nFX(qn|`i z2z;eb1|Dz1Q7qJXM*QzjZw@yhd#Nw#5~9aO5*4F8^3o?IK#wcX=tVY`|Cfk>}p45?64GhM<9aT!Kxu z;wK64B?ds^>6H=8R2L!EKpo#hVqu8BBu(bNa6i_W-m>Czry((^l|S|qd`ac>J02GK z2VHnN)Cj)sb6q_aL$S0R*=Yges6nlE*ch!YDcjm7=1Av<^q=GA{SJ94ZpmLBb+Sh1 zU=Bp=WMln7m>ot0Vu2P@)t6>~_PJ^)gs7E>;bv0!J_zmVA>|oEV}MG_;0!A-vcH@}@Bjl&3C08W;H%icOC=xDwUTYyJDWrzPsE_R%Dv|Sp}L1{LyO}l zA0);Tt+LQj|8#Amx%J{I%jM& zmPc$FviIIH^4UUt2}SB`AR|FFgls(>&%lF{Bpg3y09&?JLDy~U*Ql9_@P3s4r}D1E z^|SI?hmT5X``L(TyTm7q?g=dZ*>@J&{EXIPM-^a{(3eZRcrCxP1Q5|IODC%?9W>pV z|4ql2v!rXO7m3pM2uXjfgVO3?E*ji@VdJbb5Rq#3MV_7$?;6`;wf9F{(U%S4Bjse) zkx>V4cG<2_gBWNX9Duj1vp~a+H(;hO4lB#ygTyKCaq^~lp6={?tdIA6M@dFZzn4h& zN;mA{LkkC(JZ2nAR0378*gCVjJ{J@@O;CD4>aE1)jATKO@Rq zGHDA`(KiM6+m?-oS6_zI8rJWzRK4rCb?61FC@Xixcyk&I>@)h@kilsz(T{b0#ylvZ z?JL!byG3$t_A64er>EumrRnID?d{PmK-=qyYE^^Ojc0D9P}^dO$O9O0PZEMQ>G=@l zu8oa5(fas3eq(f__zm(tSS{_y84ll1)iijU8Y!3&Li1vLiL}!d3-Q?Ab|cF5F!d{* zCGXzYy}4&+huj$+tF2GeJ`rn3uBj%qBDcGe^Z@6svO3W-aOC5;wf4n43ks?`iY0_( z97WI`Td+j(XRO-b32CIs_V8b~%$D={&C2%1D~y}T;&a-M%pDBdEzf+5S3H6FBhUSe z4NCt;rV*G4#NLneDB?7UpAkr3h+?gm_32lB%s;P?70Nx=!~Y|w#58PQryw7X>@&&j zGzKty;qt5t@3l+npiX*hb5{oGcDq7v8bw)RO=&2TN9_6SiQUh3MjBB>Uj6#Dh$N>X zX%+}z6KEz_=ycR|D1gl7ZI^6c0qjU+=<;wJ33?w(81B)>G&x*oy^FF!KW1s=rQ{f*9u}i>^PfyXc#0>s+z+j%t5Wb-}0d z^s_3R+mCqt4_TVcy^4^K=iU|tE^iZ*zlxV6xYqBjVuk;*zX##g{%n#Iu^XsgMd2W2 z{}D?(!qMi8zURj^Zi~0z_OdPy`dO=@)f{J*e^RT4if0Z{PQG$Y-SxsG@A?`0faE;AeWm$K0mvtc(a!A>*+4@o%A( z+`7l&N?^aY*I5$D^ckY8(2!=I5E^iAGJon^EKjS6SlLefP&snd=+kV7r~E4R1V?%u zOEmMU13O|DH87y9#(wCb2fp0l-G`sovQ#$Djta)sLiEL4uSeYeJLwZwcd4YG zVvc|l`&AbE4VIiRwX>!+nmoi&Ksf~V{*)@6P;b6(TxM%$hXm4`7K@)?cUhMq_YAZ% z6kHf+(Q0d+P){KU+H~bC+4{|5oWx(4d~(p1eI~r76DP@e2rh+u0M4j|V(&o}aG9U@ z@~TjdECjz+|KjJi74Bel%>0)9YmXUA!?hfJd@53K>&T$DAy8RKw)oPO9G zFeBf!r+1?5s4}R_kRSQY^1EF}RAz6cHnm?VcQ4*qeaEWjYfXaTyy!i#3-anMVxf8g z43M4)zr(u5^oI@upH~iKFJ1A{?v({X%PZQX4--F1di(Y3Qav>kzL*Fdp4}T4cs>GP&1h z7&B!B)G$Dvki1&FlV#-UiP(!a8TvKp5F|tJuY8ha{s~nk`%J#;k*e-peXa~Ru%2Ki zWB^-SDju0hcLk9y$&n1eX)eu)TLSs#y+S@u=xw}}zjl^RoIlC+io&rpa*Vho_j{AW z_czJ34c!1gf3lM`kbJD88(Zeu)?q5P%$B%YW_S^Ed5??ZHS{l;vbJj9o}ZOacuhEn zC2yeOZ1L@Cq|c9!UM zED6iVL4`I5582f5(oz@WQJwx9TlPNgHUWDnsbgm6GUB36y?xP)zzw_FjHuR~FR=Fz zAMErC4mmY(+x*bPM#qZHtM{`>7BiNg|5e`d@9G?jM~fjv0!x}cgZweg;d_&ZmWVPO z(sQTVnbqMgLEe7qA=&(%cJY5qU!XVM1f861)0WWNvPhAGan6nAVp_1}J-=5xnYUTG z(5D=`<{%%km;bn>*5=+%-EK48akNJ@>dT28y~dz$<5wbBKRGaaqRU7gmc90>Ci8OF zBkDRyuI+kduD5p{fn?Xzb~jo6*{tT~QKH=3Q_KZoXYt6fR*)!$n?SX+<+F6xsI^q4 zA>H7ecfNbop-Zu`?o^w5Xj!9Kzteh~b~m{;5G?T=Mo<*vHTa_QEPoo)aADHDLGn$D zzxC}7rNK+nM=Tg`R_0DGNhfT9k~L55RW9vzkXJ`GSF5fG^k$NEyZ(Xg>7AX82=h^? zVR}`*pENFwVUAK=!>LddZKg#QQEeHh*`u{!k!by}>$tfDFU^DX_^;Wkvr}1LF{EP+ zT@+=s+mB*me`vNo+ucqV>-uw*clF|bQrdR@x7S;65b$FTK<6p*!z>%BK5x_ZWmkdV z{3SsfyWHjOq|)N$vxql@lJ-^J85{s7h~NK#RRo0ksfl@xPVs$5^JevBFWzv_b!Q0i zhe%Yl^63i3+TRvx+<_kH4QyZ9iIL{C6RKQ^NWgFD$5t5Q{7|t30S!=w4!t4j_~Wwz z6J}Z}AN`a}X|i+kpr7}5+OU7weBzKbxn%}2$MmDsp;iha{s}LmD*P|mLfk!wdo^7( zM}SSx!@XB@URXXWqwwFJ=s(lrq6=W4ysPKQs2`(b|9ZLFm) zd?IcJ?h3$0iiq7iyMrMA%OW0MnZ}Yf&6}7+s}8FH$spvIb57tvy6`SggmL*&tIY?u zF{k?*ds^kMs@m@@E4>$ryo~h5lA0;rMEKZ0u=aEmpp!zpO*)@`M{e!*D%isBx3!+Q zT}$c^6guN{%LUYn?=Y1U{j&~kq5{qYVwZt9mUz7G6d5amwuQVX#S+F;fm`P@m!=fT zN{04yKD0StcsyqI#O(fko<4tF8#}BMVJwH?MQ@L;v-6}DKj$17^i^IptN{3UQt-nn zPwtuyxk@)jWF0Ibt-JT3nXKnL06Per-E8JzuzKeRMw|dw*Ve-)@5s z*~RS$3Gnw|90TxEqiBJiv!YC2Xua0%GQWh4oH|*PFk?R4uJFOo9Ck zw?8(82Tt}moGX@{nkPI|208D&&;EfWgEBZkiMSZWNz%tq0JF9Q1j}MK7ZVx)s!GD zvan$M)Y~JeQ@u7fkTiKw){%*c&LAK8fs^hE_tx5>=rf9;a{um*{IA~?o3lau?DpkyF)_K?bKlkUvd}A!tFSPhn%uGa$#RsK;0<%AEPbPDseeLuwHBohI zWzO+@t$cs#WxDp&Z%ZM2UKo!QT6H057jSWfpsh>%vf{{W`f`h8VO4|%^YvpVV~O0~1`@!k7;2=@MR+P#Hz(=~kh7h*Haddwk(?WtHH8wLA6oiA4@aUv89MD3zC& zHBL?#;$p2$V2NkYfcUWUZ+1MC;BFDYk)ZqG!u^oY6+Kh|)@|y%e921Gt(OPr5(3Hd zd;O`|Ah5p&-w!qDA00+J<;XM{tAoK?2cWh_0z7AM@M^uJ{z!86 z_z&wz{pm54o-U2#3G?F#S-D>C-2hv75A1g_q~FEJ;PgUR8j9TWuDvG@Wgpml^O@G3 ztleH-d@{`%qwmL_V-QKxrBSOr6#N(g`QeS@N{9^^N~v z@2++0XNbH(@aGr{Espygx1rSTxZRB|vbo?Rcdkdv3g20WDF5r!$% z$F3tYS3X+%R*^Y62*6%Ex9p!uron)sBjoB z8(OXO-RajZ!o~cj>|BCtp*W+A{ie=`*4JWmp&#w{!QQP(y)84VO87#D;@QAysr}1% z>VHya&2Zz%RQO6UFh*67QY(QQBU9CiLqOU#!{xz~hg6DG(=6QmJiD^Lrt+iB)r|#O zzaEK;653(CQ*#h;3CmWf;*_4^xdMZFq}=ckDXVEN7x$kQq)sw)w{3#~T9x|j)-u9>cEU7!`N zea(rkJRp8!(7EzXta95S1x0vO*K@tIVerLKmSjDc)#pH{!U`mEq|hEvYxeXaL9juo zCDq^d)<^uRfbNw|y+6)1ofBoZ&F4zu8=UqZy?-j@Dtt5#2#O-#0-)n~-7>9u}tGZ!9c9_kVcQufT2SDYF%MY-DA0ZdrC_aS3G~ka`xS+NkBo`o79<2RxfGtaE(8FbkU>^ed4_i-mT7?*5XTEOAb=N|dPv3B&hFiPfa}G5OX{yCe^ShdA*vtA~ zEUBodiT)@VgCl5sYjXRedw427Y%M~6lOq6xEE-N=dJ#0+X;N}4<}`$*dhdlC%O2y1q=d9)aIPR5>Ft>^Y!8_)4N%` zR2efezSZ;3Y+c=#(j;@`%LD5Ve~*j`9XtxF_&R?4(pXlxh;paVN#Ob-0hjess2t z;mH&uO(Z#v@UM?6bM`0zD|{DOiCjHN39%z?W1=3`G~m5+-ErBK`61GW`A@49II}$mZXmK&-l*d20Up4vDl|wVhdqZj?VuF0Oc3V)`o_qsiKXLr zm{($pChox10}bJOi=Wn5NAt|3Yu~fxfcl=)7ThB$l^SXllY|SPRfL&MY1F`og z;~4uxona8w3x4&L8_98UO6wyV=ciEp{+pdyj;tf;${RUB?cGl2#MG0H{;~k&EFAM` zvKl+?37(UD-r+A&QNWJ+2L?za$B-;BrHkw$0|Q9=Din|bIjqT`LV9tEI2l%D$!@RX z1%=s)j{6VUdVQ?af&3Kzw@=6woqi_St4p(w7uJ zS2JP9B^`Od65rK*nSaJ3^{UAP5JSsh@Brso7*YoAjV$>7Y)E+|zYpo;y~6{`5At=9 z1`;EMtwm*&X+C#bd)A@m=MN5+#T*rX*m2rVPA)v=mkvyM0Sg_qVhQt80$8HP@Rg%Hi-Sld2cB>YXy|x;;PMwT;AFuyl2HlClX1<@(ddL}7_Yq=z@8 zxzJjJYQ;w&#S-dieYZv&2WOKeog(>Pzm^%8zBy>0u4I*PM%3B(-X2>2nalscF5pY7 zRs%k8eqc+yLmSlX{^%H_0rnWYwP4a%qtQ6qWIsDwG4YF5>#<7_y`^$_VRH~K*dW|~eW3xiArTEZyFU78y(4$AMIX3E+iIk4EHQ3HirkPpIX-vP@jF>1 z1Z0JG;-QoDaSk6iiaeT-8dHOX_>Q)k@l?4qU=D9@I7pj+qd)PY?WA5R@!oYh(NAwv zm3k(DTM99?|E$3kc3s11D4(e&MY&+XH6#5LQK0kj z&4MMg%vfL-A<0RyyXay#S{K8vVyGBx>7S+Ci+~T+8)%*@HLXXJCW?b|4Ug~gg5R!r zVCyc34DwR0Qac_zoM7Ez{~Ff=fPX^*bYyy!n<;}OT6iPxAxXLp4RrZCecA599@;M3 zGe-3>&ZV=>u7Qb+z!C|FiuM*WEFXkzMM$CfXS~jN z=9?Q^4Q#0iEp8LtB`?%@mvt*tHXQn4Qg}G+Q1qtdwdDaMId=Ms(y9s*4b->C89nTb zI;C7RvSe`1%W~)ZOOlzVwx`o^6|cfVXM@M%t-FoXt974U($>{I0b>`lGYte;hrqXo zp_S>y#D8ECrWw%mMMWvBpj%~4@%F8E2eDe*YA>kP@^G;&`P^>T&pcL})70s){PW;b znpon%^e(gvEpqv02`%Tj=DS_P$BWe7Q%wr}T*S1sHqOjn?9z)t$fMuR85ZFgMG!9& zq^b4-t`w-O(LqblWIxfBnoy#e0!C|6eJjEB0TwmkS8JG#q^Wj~WsMu>PjK144!GZO zPbRe%fLkDV7OrIg_c!b%mT0Yly^kc>HQVNd`{MUawij5BFX`C*#N|yA5h>2z?(S;q zj+Nmart{UhaUR^dx;3F#!@sK>1QgboDuGgreh5y5M-l|fPooVf2%)CKwH5wuV>Z@$ zkK2~c8z0umSI*@Tm8BB!sBs{bv<@wR!(thGo1KYtLBx{gMk82q5)DIgrty*WpT;70 z)_un>{$?zmd7++dbtdBFNkjpVKZUR8(r+-84?1DJbSmhGrUv)gJ<|M{P;R%ktFR+8f7&e$EDExOY5*+vrAVIcJYOr8u|1o1 z_hUluX$3=%7b_husV)JJXZI(@e{@&c9tFNv?xhDGuMasohXqrS|({^!Y+$ zv?g2rS#{;$UIxuBR!r{bQR~8?uM+laOZ>+oyD%XdWw&nJ0YBJ_-PgO`gQ|;%;0rwoRnv&sRuf2R4*LU8sQtTi5;H=Bt9)*63NwiA967?~AdYF1Zkz+Rt z5%OVdQF1DRyeivgQ(hUPF^-jaCO9E}w3+ZKj(@W{Zg#ZfJMSi*d1FGU*&EUiXim?r z;6ynV1x7V@Im#s{oq{kU-;ReoFtqqwJXK5zXVgHROfj?;N}P3*o*D~+m(CzDyv+Q^ zL)SE0a`+^Vg{}SA+j2zLQX)ar8ux7-(z(Im=b9RH6x{y2M65X2 zTuHL(5R&%0u|Z1qXusZ3FL=a4)nH-adXeg{xfrv+mLEKNoU_rdUvV#JUE$Nf)@#^Gc;uOduetI2)W_Uu`~|`kPg2NSE( zMZ+!{4_nML+6Z}hEMagl`~@IY8WcHgAau@YQ;sc;dawAMBL=xN+m-igGHdw`53H{& zd=33kSWlF_-FxSljhxGoYt46ZMVVt~fef{0;FHbP>5}5sLZvGaMVbOPi0Q4L3e0|g zN;Q*66bVi}Xho@FNh;B+ETL=6{hU#&DFIsd)M@(f2*)p@zS9DYZD%TS4LYA3e7Yy{ zo`Z?a!#s;_*jxnmT+4$4df`J>n`ZQJhABG_NuHR7j$&gmhcUev*bv%}MrdoIs;J0) zU#o~eTCjjUZSBzPv3&gcxCt!&clK7?eiL^&7~&$9coHl>*heG;0|%b>4Ri_=FnUMG z?xMw4#S~=^u6eEahM1X+l)sKINZYRw9pHEHn1A-owygX$-ca~j1cndH5Mi2Tj!VE- zXtP9slvHKasse@W*sL9^-@}M@&$rf(Xv_b6``pMk`nV~xV^yW_RaS6g=LV1gZX*OA z`I~6^TWNL_$r6%c_<=#>aRv$S`M<)CbM&-k=21m&fuFW>^%ZRupUU&*9^5@P%D?;N z)A<(1gO{59Z7y*xfFS^hH49W2ie};EN%oHB@GoisS?+7aW>}flNSsDV`!O4K3Z?E^ z^`Gl)8>>@U;uCNMzJH~h861$2BCG%mV5dhv)(akLAT?6w!#h?mTN7(hmUbiL@ch(} zjVTW!5usVASY@e@9O_`-x^D!;b&gDB%qXxtqb!jdjSbrD42b!vn)K)}P3j1>9F;f7?ec^+En^PjTK_Pr@o_pTaz&o_4AaoL}eiO=V* z9J==?43r0IK-XyFX3!~GRkH*9JB4WwOEEt-YCH&h>G%E&TEWR;^79Whdq6iH0vD28 z4d_q^k`zN8d{gcihlDJ%h|;tWQ(*NkJ&7+$$*#=Qibq#A4a_N4;C`2qCeMF;{oVO; z*$zkcIAXenrSx}zEPZwf(y6KD3m|DI$xUwfF#m6z& z^+A(GS@*dvLWC+gYF}(999&Y*PzN{~m@xwFVIL83faTWjU9R@Lro9En?;);Z-1jC)l=oa=*FJB*Z!*(C_l1ajoU-Qw163fxSbF5lnW*T9j~RH z+&thd$Glj3awS)xAOm5CdvqJg+7D9C|G=2%F%#1?D}nQjZ|sjOnSwxr5#py|&`6~G zk4AIulE8!Gt9Pp^Uj6Cv^ycj@nh+L|^L_mol&Ap+r&MKn6@(Z(H4qU%yrzS*!+IC} zKFZuUUl|c#{^+xf&LmL;yZY_>pYx+Va+w-j5E8sOnLY&oww+nvHjZV9(=A&4*VO}& zrsZ^lPlA6^$I1(Jrbfh3XGzhKsDh|WP4)#Vss&485PWilUbQkw0oaC!fn1C=}U$pdBt;e#XBO~`0c6@zN4!Z|I+#S_u1?JNf{W!3l8b( zbj9t|CvYMm%-`zzv1wDE85IYCaL+uKf$p{Cp(*-`e*W(!LJ|SeRif69ws=Fw*W=5_ z)C`7Q$@NmE{RQ8p3v1qJ)Fc`-_;o*Hro&jH|CMO@A6~h)0csz9mEZx8B)4Kn-YW7} z@SjvKGYY0Kh+^#Ww)1%E()IbtSF$&EuU)vLbB`;AeXMvPhqD(0b;{sz4F+g~=A8z$Xn;x40G)nWe4J3Gk{2f0(gu^?9x#E|!Kr1Lk~ z?~r%mcQv;*92w}0YMB;R6LtDtr=f0{zUxlE)(B5fugvZIv}Yz9Dyr}WPVDsdf#XEtdjpi{MRBI5!#+kA@UD-jqRRSK6M>_=-$tzk z9*q~&B#fmo9*p$8p@3foK6>Y8vEK$1ee}FkO{hL>7x!_$r0&DGg0p&_jN9OQZeY3` zK-3f-gLGGW+MqyFjhyCVDUjI)*nNvtwp%Nnom{#D2#LcH#fgm$Q6o+Wn98Gq2vNv%;Yk?;H2dNqs^qFpptD za+HS!BGa%H%y(?rm9LLx@<9QcCM_hPFbm{zJ&k2QKgbR@4M?)NB`Ad+O-46Zb1S!t zZdn1-NlpPk0ZUNpn>PZ}K@iuopodd>p9!?(((+pY0-Dt2@s==_vZq~cRRZa17u0Z7 z#O&Qmu0c*Ol4et!fB=+Z67NMwl!mR*>HLG zQ`OM2QD66Wc9yg&Up`;`_}Kuo zKY9A+D-Dx-6iGkx{qY-7e(9GN()kWc$X_(*Z@3R-C&^8!#s&;L5O1x z+n!Ef5;5>$&EUgEK0X3jxZNzL-AGV8p9|$@+GB~Jm4Z#7BZWOT+>I~AujKgeD%)9C z@B%8couHRHr+p5ROF!87u9C6w(#bQ_bIAfyPGgA@3FP-tL=>!nD^Rts9RV64sZc>M z9C6$$>IWL>9xi>ON5uK;S;1$IcEpG&1vteU+($y1v1A846Nx2Cp-)lAdrFq@LYe{= zt)$_J9N##ebuU5JrL$EP@$?@Z3%T-t;4CRqvKYI{Ko9dBRmB@$$Qh>=BLedlnj6HJ zR=p&}*FqOo5?xQr+Kt;qGKpTdef>LlPf?2@ZSi(gIhF``$=2+$2K~TIs&)&%iqLPH zO4?K`=8IdpbmxPO;|ELCQ+OU%_BV#k?r5Gj0GJXFKrX`rIXqy&E@8>9(h)5<;U!r; zkPT9f_q}hG2cDQkXWGuS*n?A+4AHM*!Z>nIF>_AJ{tk8Zf^X^fKSKBn^Hqm6*gIsjonGdgTeAA1vGU< z??(NFY|JqvpcNu6#o^1RnhR4GA^~Dg0p*FyjfDNbjHABAct*tg=p33?J1JxBxa&+} z6T4NDilBM^PS{!xlZ;xG0aZQtt8Z?kF#_msOBSt!WnBh~T&l0{_qR}oBM*?L@EI^B zh!ugI*tv5MOU|DDk`~4}X4~%VT7Wu7!agrJbjDuyW;oxY0}}FbGNl>vcvZK}UeBM$ zSkJ)vVSi0SPDtoj)hdyxNh%&=oyvm3;0FSqbYiSmR2E$R-1MEFnkV}F++93c^Dp(@ zzY4zpU;eT5!Jj{boEGXM&kj?lTiem83z!a!rFrINN4gE9Rf>z5k!7u+ayT*Mao1aqLk3mNlr3xiE2vEO6-WUOpM6N+HZU?yw?*tp8*2kTu+cZO&=ws0 z*-5A%8hr3jln-+)@W8@nDgkV8@)#UCtxPpuHKcDK$9~UX3bo_>LY_=fH=7z1-x|v- z1_#=@-!Ib2i@w<^og^Q%uv5ai+W9DpX7yv5=H1$o3Yu`?$F@HD$K#^Il5%*$c^Yw< zJmE_MFs#e)hA~U5mb1qXsP2U`q=pUT4L=zc1-`l75POz38Q;8Gm3B4#jFZ(Ho|7@B zDXB)5M6aihYpc{owjdv1w;LwE;mf=mUx}IWs0XH9OPty3U#3!U*HlKG`vh<03}B$e zVL_z|xeQrhwaP`c0$wbAlN$D|x3_ZpR;@v@s~EP{+oQjw0UvO>NR1<_%{-6o4}^fL z9#I5BvG)8nAl2^#YHF~g{ng%(!?c9Yx@7lLF{>=%4aNmllANXG1 zs+l0mQS3ZyQmR>5Tx6a<))U^px|VLz`$V|v^g8Nf|5*eH#S#qQ?D6ylJHmk-<%^HT zWi@9&F>TxSye&`ALP4oCkNxrwRt1$F#+b~-T)fqFB-vf1$|uAT^&EiCPCz7pDUbGi zUVC7$l~It3PcbdMY9gD%y&;>zd<00C;5~pOE`5})#CX8YTqC&lJ>9OG+B>9oO0>Q` zrq29%l11uxnlGHsHoQ=eMz@9ig`qj<+))Z0(dMg8JvSHO|wuMZ0>2e*k~zBNzf z<3~(puXZdwE`T2lpOEBmc{0n{@ekx{*)K36UCMPyreyY^$%!>r#cx8U`kfj3VrMK` z-zkyRh|^+$3oSx=I^yBJ!Sz1Ze7PTwkDuE#F*1=LMM=n|b4-w+zaZ^V@#;yYC)#RM ztsM0na}2U02j_MS)M--U&41BdADp&KpO;CtkmE{o@%j`^%B#M{{(Grm9?X@3Y0$!a z$L&qJ&_l72J05p4#oh51;#^jkZrDZa0bj0_X&RjX8b`#ow|TQv{M0!5<~YtCHRibs zZ>(mj+Ad!E4wqayi(Ooz*Bs%V(o+CC#+3c3PN3Ls=?SVGP)aI)r?wyInUOhn)1Vu7 z^cKp62XToL1`1?BXT7vIB>AJ*`@@hS{ju8??)j9!;JzwHs;CLY%f~|4Sh#?mVJUoW z^MZB;SAW}CCl~A-gJ3}*_wz>sM>p)7n@7S@S)iS@F^qhA<0W}JE)RwT zfVhI(P4G4gOjr7G2mXpG&>(}ZWmkwi`}HfoyrjlMc^B%|$1_587~f0JjhZ%gd42nY z_;rr(76IwcuUWD440sy{Ozz^E(n{r>6NX)Cxt`0YpZl!T(Esx+;?+MeAuPEN6iKxb zggWy*@#Va&V@0zZDU^u)m|gqIi^iWqaOZ2c7yo0MJ?+9aF`&+`p}=`*^2~Lb$zfIg zE|&Tbs{iKSoahmPGpMjZtlBUY0@tq$mlwyq*P?5^bN5Z2SbTqESaHOc2{rGal}?;0 z_n0|YemUXPi^fe90vy~4P^Y-g_|}gFr8*^5p$#Y8w66b5HP9UFY5vi9B&9%AE`?kj zS`E`q)3|=*z5vm%v6r{hY97gwRC^>pO*8Tq$gfpzrFz}HD*Ph6kC*$qQ}UJ~;mQ&2 zKgGZ>gdxeZ@YvskioRF_I15g{l}np$Lhke9f5&@sSR>a`Qw6B~pPV@Hb_eaeNDTc$ z3-Qg~mG;MZnA?3|TS&7ri?TQ6Av!(XR9k#vN^9tKmGtaF?{eqD)K>)Q!I~Yw*376P zo1OB5=2ZJjrt<#Bd)t=InJOijE@(D?=PkoFgQ(BVds_`5L7-I(5uhz@&Ym;O^UC>f z96}=8h&c4G*>$#-4nu|v$@(~)0_n5wfXzdoJtDNO3vfoJguzxTYfbNK`Ae%GDlC`L zy)jbM(4QBG;RNwKG-af*XTNvK<>`EDDY6`n95F?H`o`Hua0!l9LArsG&5f3I=|m{) zim$J(&F-4GF!()XW@`o<@we&0eSLAp4t4@7gdUD6dvkq|C7cuT+2-Pr==Gc+A*n#_ zw-K9)Ng9*k@ngg`_=Yjl7E267df-T#?WF9&Jk~wXIqO&L_-lpA@92|xeII{T3W_P* zy;zSvZ4QV0t0(QxPHN#0n-WChcmRllGN$q?d!24qqoRAZR#w8 z{J6QkYn(EnS2LUs6Fyl$TB98PQ$Wne66iZ)_q#P1L{4Ikpw*c2k`0+VvaUj5Q{+pB z>I9GMIOD@zkQeTPCw*=Aioh{(^+3qOVVFlt@N=;lW)?{)4xL zaZ>U(v^o0%z=2r|tmW_#KS9A1r6zZ|0YIZ2H|LDi(s`n#doq4!TRi0}=h-nw_eb58fp6M^n_?ypMqFtiVK z9Xe*UsxniLnYlS^fMhvU*L^+Xk2-*A3Lm?susfFXEtK~YxcvW@z4mviR${?M7H4M) zzAA3_jted65(KVD@*sXX*y=m*gIUtXfPB+R5b-s?v`Mv!0V6l)ot3d@HaI#gKa@G7 z(g&CJ>1nVFASyU$HGSd9FPim^0OosLiQx+^eBcb?VQ5jhRC6|J1u5f}`eZex3#WCu z=&q@y^p3NB0u`ZpC*&&p{pd)R6#kJyA4|}J%x|(PCm=Rw=$Hf})WAYuF!)*JB^*h1 z%?=(ad*(f#e54y1iIsmWC+c+9>kyA%$H7e?kOaJAatVs&Bi=Sma%3dX6`#_4+JP6+ z437X)MY{D?gP%~kB>5x3=ti*0P+$tW+u1RG*itL}Yt>1}_}^Sv|CbXY_|6)*cb#7! za{(}M^m<1hyE0$Ll_gTki0`l1{h$zIz;cVEPBynK&v=;~GiFy73jx|%Mjud};Oqm^ z@&FO+XJE_L+hshkl9N!LZgiar)h<&ypmNag!KVH@qUAMpy+^w8@yx~`@WH}0AHV0^qleBSx_XXSUze=hw^uuccaqdy zsU9K!B($4rwR(GW)A_7yrxHs9#dwyorwZ($xSY=hnnTZ#esWf-p%bDltl0UBF3Fum*j}ZZWLobT<5ZU5AhMLL8^bvUc+|h_ax5|;xsbh4F z9cR?IZ=X|$`8J{c<@xTc1mooOq{Y0e%Hr&i;u&SmKEB%2O%A^%(@<}~R9P+h(k}nw z=L+kNeOwfQ@!o-Dz!itVvu2~p{p)l4f`aJGnG3(Q_c<7QOD>^KA{pb{i>E~`k>n3R zmr33%;;-vwWZFnC$~vQm|KsJLeeo|}@ZZD|z{@wY0PV|WrdPb_?S?q2Yl7Z2I*MZ7 z66;#vp1wtCXef_(j&QI1n&vxo|9qm<8Dslz=aP!>>AqKaf3G`+?8|W$=&38|^L`jB zf8A(2_2S(ZjR_gyZ-**C0Q1GZB@Ojulo;gfpJb}XmswUT)7|ouCSRJ^ZuG(Vv!!o=d&s$?o)?d1k$`T2KEPt1N?^~@&E7&|AB+l^DUX6LtQ>q zw92zDO8abx)wRL#KQ4rvOB^RG`J27cDwcK~9xZ;q&W3fS8aDIM;L{!C3lGkl&#>ZV zAZW2?AZM-FIiN?A>mc$MKMBTe{_p7Xg29Qv9o`^~ z$yaAV2@VOqO)KZf4HT7kY`v4jmM!U+nF|}KdSwyEG@PqG-l4pdge@*_z!^e=NJ7{U!7))=Mo9okT1165(FW-bkCo*fZIE`bvj+g?Pb(qg5bC0=DRSTeT_@F9 z_*`S^g9lQH@6Q^59U7JixdS0PkR`DI!POYnO2rQlNo8ZE4Cokq^4!v?FRCS%KCa6t z{h)Lb`GX8}HkW~VQQtUFBxsMs=%AI^IMCGhjEb*!9N|EQwv`Tr%c?0|{k2G!tmw1* zxA@c4cdAJHua=nA-6y;*0sBT`tN1TaiBVwV{ct2CwK6_8u$jnh)34_z(-K?g`ShNZ zr>Ru$&X3pJAH$}wGsCB6;sDEWlqKYP6$}@648%*Ey?|a{9?%*Kgd&BHI}OZ2#qtC3 z7R{p`&PJ7qEb7JTO_kTtiI1cQwcszuU_)%+mNtS=@^q3*hWt{fq`yDr^E6 z6U`jXAWB$+PR8*9g(2D(4d#fKS<4A??@yOBQ z=<9tbpaPO)Ma9S0Dbtb-v8%Wa z6bSNx7`P8jE0f|jY6>|s9o^H!YI|Rzp^dZSYj5Jdpxe zavn&&!y9$gNI+!1MNKqt&3(%qkf5oiYIQO$rMsB+*)I2rZVk+J?yV!`=si+mi2^W^ zP=xsgZa<5aD%utS_@pt@!kT??4O;ex+nJB4rifG9t3vg|-l-!PYNU(-bSI zOqiIQtWKgXeu&tVzXNl~$e`kGi}BwaffVns=@NJ=UcwzbOHMmp+&=Jp zQ+h&Wx@vwd-~FwVo)0$5)w40q&T(=3Dwt_D9A#R4RDzyLu3JrEc|f{DiKj}+TrGQy zlCnn!aj(F5<}4xAgqfBG;WA?L#gARH+|G+~1m^eX5(G#D{^fY^Q2&-Im z@{hRTE>m&g_j+Xsj*O26ir_->1)L$wA$EpF5Bxfa^-v^rI&XqX`C=T75@J93c4DVA z_k7(z`&;FL&6X2gQv2Z`d>R8}^}l%_eojB3JZj}P{nSiO%lb2{paG(ulSwJm>bh#D zf^27W?oB9#weY4}r}FIxvo*;kBUI=laQaUH#2mkm1>AO?$bVpwF~HHfinfMMQQjf1 z4rRPC@7KH-)<4B}Da)TOBxx4?yzye!DOu&MX3m~d%sreg0?iKbgSt)~u5ZIrJ$vBI zRRL2nAYv&_RbISswXTVDi*)`NVJgg5MZy(k)EbWgemt>ensyc&j;zA2_)!pX(_(&V zl2ECxz3bJ=3Rh@k3vM4sDEMvvo(Q{S{e89q)wCMTK6kOu=FX@{O6K#!bOw6S^37!#< zz*uGMXe>GU)^vFvOH7=R3ZZgXzEFJ*uxYzjRlF4G5h*muwtU~IOPclFuZfm{3s?13 zMh6I1STY_#GyIIbgCzlvCSH71kUrS%YEfQYp(9&Wuxn5az1SU8jl-W%49KHL3rZnX z;lL5!Rl(_QP^4j3qG!Bu4hHdQ?fCMA=xln#V2wyX$@I~xdvIi3QgH6*+XD-6qd&L) zPp3uXzw)mC53d+mu+}f|8~5=t$Q8FQ|G)-}izkl#TR8qE&$X}Rg0jX6{p1%hI(_jI=*xEfuq%8+^S+6;pLT!B(ltLWVn z1Hs{^yo7D(3YOe|c2{x061leyloO!i*p*HBZcC}wFXv92+SD-t5ijmU@r&gZHR#}u zDDdpxIDJ7dkfpdDh2Nf0fni-OAr!#5iA#d*G$pb?zSw5=XodSt$M{_D2U7U_Ld>ES zC5MH8g>w2(Tz1?K>0;Sj?FU2B5i}7l*1~`4rgO2un!ZSnyUyuGO0Nv#-top9SA3MP zqyFR0g{AmER%@b|LtvLB?%`eeNdNjp8zE*B7J~i0%-9G;#^4~8kxW_OXYTZ8f0U2) zAEwXe2zIo0Czon3WjELs=Ml)&i+{Z+6w)mtPXyca=(8-ZkD@s`|34ZyVEqtZ{tw#T z1RCo1{~I15WoeRqow625vK2CILXu=Brm`o7kSSwEe6#P05L2n_CfUk1b|GYm>|?9! zGt~HGmY&P^`};l5@44^)ea`=R?sIoeoH~s@*XO#f_xgIjUhR3pmGlD)sk%tNi1o(p zqx~tz?^XWA;rCOMp**sMq6@aaWwlT5wX#$qhHLo3B-v=99_)=I@{H8E)7m@2A!m)% zluBlr_BZx@+By!Zt8<@}p&sJO9BUu@RZv;OkHKY;)XQq$S+#Ab_S1h~FrjUCa5a-| zo7;kCb7ve8d=x%~@wbaO%DeEW02iWfd7JTxI0yub?1V_j6k%#V60%wgeJUCStN2Mc0iC5$CVR-@{kj-UDiN zC~2k8!UmZk7|fSz%%$`MU~G69s?!%*^UPkg1IamM`u@CU>DQh^?25N14(Ww(;vWbx z#96(5#nTmvp+DS2*CNGJwc+_T(!s}<^B?p7H{y-Y&zL}mCdcTZaE~#D5L%47;Wp&{q6QIjHQvEH^I7) z?YXpI=;!#wZ&cy5y&ZBqo@I=_?`IGno-n{}V%Kwr@Z@)hila$Y3n*bzemUoFMspWI zIp1#o9Za-%*TjLN;(tw$*mkKq1dB zXGqRejNe6O2MgUtFa%ig;k12_qWED;GuV$y&jVndpKVJ2kyF_jjGM&hEQ)}FyXFlFFco6aJaSuKBH7rRlVK&)s3To|r<49PkOL@E4R zW&POi;a1w$l&0gIEaiuwPuT1IUvWYF$KN47b1_7j6svn!EEIjZ7^DeQCCciPPSoUk z{gAfiBfmte1^Df4oPs58lwH+6Wb6j<};|$pk zNVtE0_JR0W3E;OjS-c>)N_M6ZKo^|=#)CeqdTs3^!I9){v){r<5XIBQe)chU(L#~F zKmLb?y)u|F=5{CstWf7!JRoHt(B9NqS3u^}k;~G%sFM`Ygyse7lLMX(FY^;5#6lM` z?)az;kX)2I0R6<*@FqME8X0wO1;ioPAfLWmC~Uv?x{Nt3TVeH7*xG>y#uENNy6hyB zKJDS^Ku~;xRygN~2~GkK(3!?^Sigq=;?fBaK8N+|E$W?rvu5W~ZGigqDXw<-I3AO7 z{UGna;nFOcHM5-LMu1Lk($s4xHnBfT6qfBV{0tMaS>ZbNMiSPoLhB>q_mxH7++CW!)_FCT|XfH*FIrtO8Ub%g}YUKsWV z715YB@<7JHKy8(SE_SO!0;iBaT9T6!2k@hK7GF7ZgszR*K*vrau=i)p#zZ>ofg;Ep z3VL`yUa7D9cimQ)o!n$~YF5T;1M(vdx6qT*&>`eX8&!hVz%17DqhqlF1E>ol`iI7{ z)o1!5zxM{13WmN6#mAsFp$Q%nxUHtnF(57^MXG4vWqs5! zSrqr)kfMQEi9?x4wLLTC>b*-{Mo03RCnep`&|wrqSODPFEmWgyQ122~j+SGxtVfbY zp_W;z0*?y(zQvV$rnKPDlh=0jGti~zf4*ROB`c@}aT{A@9T}e@zU**2y!9GhG z8)5Oqf`Nxgu8tfeGlQkgFooD^jq2)$7^j_sG-;{%tw|qOy<7V)$+~vUxH2JM^8m^t9#3 zAOaw)$#M9qkrhvhb6XWKrFd_z_5BR}vVOFg0{pt`bbep4cQ)Ri z=iUL$`1D5N*GQW7PEOvykHXNczi2SwHt!$Ke4yfEN{2UF#Xqz=P4xrT>OeL7RvsA7 z+IaGYVnm%b6_m1{G4lgd1uOpTjtMA;XgB}KnDSxPXriF8HKX;A8 zQ`XSaaUytqWg2+94-D6-?KeY6P`j7tXIo363Iv4<5n;IS%7K-5UNaD1-a8=0a3=I6b6)JL}{|-Yl z*KTnvq@+H9kk_0xJUmQ|nyro&RFXM7V`T{#tJ$mpANfxF_22!CgoA#7*>5eg1OiRN z7QZMv0;2H$GS`DCQ$<*C4Y27rW2!1yI~?qT_wJrILk)`NHZs>!e8}r8( zj5uzDday%>UpD*&{ttlg(8rpCbpI3c9oB+U+v?Y+SrXU2er{+?R`S7cmaG8!ZnmKk z_j``jWGUmW%-?JO>m@Tm!X2)PBon*~AtJy@Ce+`0Gh$*0kdpScU&?)FoM(Vd#`9Cj;Psq$FHFn zizYoAS_>V)>UI)k#vt8LoD5|Ob~ggd9+@UI@4gv*jF6T#0}!vT-j#p+I_LlF#*M37 zuRzMmMp^%#wSWroP12+VK~y=KnQ8{={fiCU8zktIEbD4AptxzehujV*Ct8Bna~j`u znB+E1SI9y9fem6oe>d=7F@m%=-PNh>4eKLPs8lg9K?2Wpd&6k8U(oKdG4hNubeXvB zHM`aF1E<1Jpc+2%k>5~Zn7(pcJkePllvdtM6>cJv_5D!I@Yd-_osK53uQls`F$|ow zvWOTTR*3r5$_(!MI?9Lmp)j_Y$3T4}a>weSzyR{D^_f8u2;$0zQjN-TG4Dhlo*tb` z7Q`KG#A$Buh3s%6bmIDI@;ZpnQ9^S@@v2*@DFv8)#VGK-!<^>sPs&T)KOaE=?# z?lSHkW~YO$102%lrX6POVz5=a@A3>}T3@)bQiS#qWpR#d5+}A9{$OW6liWj0X3bXE z$VkxK*_>2tAqd?Wy5J`)OiO>O;pTP_Tc{W_d1~%N;%ykq`QL#HD-lWl=m5De({ZQl zi(`BaQBC7Yv%lE)hY?zHaTfuT5*08hwS!W;Sp=BZAcGK zo*cf>kCQi#WRwazCr%oDtHq*kqp^% zYi`+qji>A0MwJ7(N$oj~ptKSGMb?QSfwl*(Ev@FNhw7tUlU}ro$~Wc67*a2I&HMvE zRHhd)BLnvYqQ4fAnO|z7Ro1WqFS{iY;!17;ZJ^zx2oekuv4&pE#UolCaK^V6lzMHw zU8D)$`{CqJu;82g@?od^Q+PY6w(lW<&w|_m7|kI4Q`Q)U;)_v_PMOmFgVhfY@p9c+ z={?N;4FR3hqA9~6S;Q)*TyI$s2HnlE<^JK3CGO}Mh8NULTpeU_kI<1zh)P9<0CFzq zp~h2}55t;$d!4ei_6!D3Otv5h9B2HyyAP;JGA8^{t%0ov?5|KwBs%2onD@62pF4Rl zq4g^JPJ*iZbCAU+MT+QS@#xNA=98_~>a>g7_9NSyzcz3&I7L}Pztd5rKpl;=vQ>yZ z4^Dr^a*m#ZT|^{hy*bFufpoY6?^TOgorw%O)5HJ4Z<=2m#(Jsz`#m@tld88;X$_Ey zPw5+vIw^nIyg=)E-#qH!>15)fG>JfhPEXTKt!{ld25W{7+>9Qm<;~ zK2-631xy$ZOW*DV->wIO@e=sId_32$``|o3nr;ClP!4qeT!KMRCDn~6_#DqJ#!tbM zkLFQ{L);7|cm$9;x=&iru;971uNz+>Vz|#XWw%k%b!b2K=tJ*E*5~6pE?W2<0{i@ddkf4eMy{+E;JT32phWWr z23tzo9B&ApE&5q`qSaYjD^a)8`?x6LXp)|fTDy3i);|gPdZ_qcI%XY-9Fx~iCQOZ^ z%F+x^3t7*eFe7u~?|)$c|JbCBckeNy6)@`?_Cs7IRhi$={1~EH1i6Dhb%j=>W9+Za z#!zd1r+cqioHc)#ed7;|wQsX72GCnimdK?jRd&Su#LRI)0J5#yk8>+qiR*1%KQ|dKuX;HyKbRO z3uf^?B_$xoH)ku0wAbH2xPij$!X>SniQkrgkIeDm*6>ZqsPf^0Kq`6;)#h1}7isvm ze^u{@r*7+oApgFTH5ukL0td#=*xuV590sZ`+^j1ATBG|F6hz8%6ce|Bd&1cr55N_EOh$x&urR`eXOIeXLwA_J~TG692 zboF1o@;`TlA`j*NoeVt@dUd0aM_m%e1%NIfN+pjMLB9}?j9KHUL*89ARzEL**e^4C z_Bcb#h**g9?9N}oyY)p`Twazu4tZS*x_8pj-0P4WlM_Q^@SD)ELnK!aeyTQ-IG43H z?Usf0MI*LZ!ycdRj!rn~PIdAW%OgplvT)ji6n0jN0%+30&u;CD1C7iwfEOZGY(LVM7@D? z6e-o!pQCE^$Uzs*r{js2PboepE=>L7|5>p}a!1cOF@1IhuF_`rtQ6k($zV;<_yi|1 z`XZy~_aJc*6fCNlIlqvR__t=Qs)*ax<@V>P@HP|SXL3=*G4DG!_I^KtynlJ{x}v0; z@N@X666-jg+%S?1e4Gp3!!W`i*{1Do`z4xdg62)=xGaUZvQ0_?zr`(N~dY@!S9 z$n{Bw-b_?N&PeOF6)@>Oxj9p6#|Go1()a545k91LK8N>>{T-y0sB%H)Eun|AJ*sE> zkNQ-aI@{OAw72(;smqO6e4LSu7rbltG!(XE3d8$>X--|}7wRjV>^-DXBas-n&0AJo zSe5N_mJuJ!>4z`JHxr<%ps_&;t%HA8>0lhnksSP~s(De^?A^HGZu04UpGG|Ysgr?N z;s3Mttdlx82RzKAfWGlT+EFN$l5XiSlh|&5A#FH)pOJ$}tBiwP!l|)z{?^ugFO1fm zdJJHA_UQvGDKEqxoQzk45LM_=d-^|7gn4;3x3RY$Z@gqwH=kJ#x?VD4X!+2rM=o;6!AmH1zBH{o^wLRnj6kJDpHT#L=6!c z;vlEsc%DT&#(d(VuZHO}rK`4@#SWJly9?%Sja`XOmQ%}Nvw81bezH@-dS9IARj#G! zNIhNW893Z_QO7a6f$+xj9(By#zA@}%$&2`Navr%r_z}kbTA0Q`_3jY;-`9N7TVVd#%kk6LQONNFzf|zc{YYavxU~M_)o|FslX}iyp+vDBvrY z%8X=)pyojAhoBD5loIIYJadHKfksaImT7dws?C+-ix&mMR98mMD&>x{)1!Vzv;3ct zCIH6XJFks2Mz^c1V-iVTiBSlFpHZ%MjTdC zrsIrL6n_?X2-Si1yn-rS76gQ2#`tm`1?HOY-Wq7Skuac@EQ$Se-R^8t`v5BSJ?Hk_ zP(2dOgc+wV!U733_j3xWnXub~#rIj}(0oGgi9x52yYF_SI`Foc)aiLq{;<%Y}Wda|Dzz{&N_EMh%GAfdb zqr?m%;#ZGDYnr&}!sO;{oftX)>&AZSMmWpgmWP#|^M3aU9{K!_>h`}Y0sr0aTr+@C z9K;$5ozy{Adn}wO_W;PV18tiV0xZ+ixjbgPFk;*27yZ%S2Oq(UZwdl*-49e5Lb)`Q zm*Z*gfWDY1KI3By#iCPt-j#_3i;dT*-?%~em?s<$&8>u~e>iSIuP!xL{;aCeprid%Q2f8wDeUhwBlt^VF8^eGy{CWl@V3&|G6zPs4M`|glZ*IAA*KHq=D-~ZJf`dj}Q^sad@4%YxZYyeZ_;^4Zbql49Z z6BAusBYV%aH}|-cUmljv02Wb9ZaA+Q^_SCO05yi2P}0LSq%2ye#o{AcRGxiIx_`3UnNI|A+WE&!O|03%UG3@HahrrrrQJ2sGbYH29-~7a@vhyzPUF#{bQ%Y=$0+hiW4E|pL zy7U-d?%}G0pRt3m8@f_DyAHGeSo(K{4@ClrZV-vmcj|@~(-NfEI?q>L4HDF$v_)_2 zs5$w*2CFM$5zU&UqsjP*{)CbPd0MB073X}Q(RwR-Y2Mlnw;g= zWLNQ}v5%c~+U(@|^yh#)e5(Mye1s{a8aEB`zxe~(kjDbhEEZIY!k*!qg!E+JFz!$d zJ5>2GSuL5k7eY_QsuNW8jGcKd`NjsiW3@EyB9e3pl#CYkTA=d593exbX@?MQ7r-D} zcs?GbVo^KdU%i`Fg%kl+i474R_}=SHdC?o&>P8b?^M* zbb>&Gx}$yZ!?+{Y9PX)gIjqtFyZ1_g<#m0({H(XAX&DU`WE8!cJCvg!kq%1gIFE^<9{5 zo8v82*1cXgFwdc%t=UuTug9ggAl9|nC%Jh>YSImAY1%exMR4D?-&g$3Q}O z%ttFcr|ahr9I*l8u2xSTC!G~NI1EU0f2&i$!1g5b3BV=4F*Rwa>1cz)&Z?_xWxrmc zINH6rf-|c;d$cI={+>2J5|v|m<<}pWfytaUi^G$|h;{ixIE@Fi)n|CV%EQYA18TJ&a-%DnNJ!-F{P(1TJ5V_ z*Q2gBFD<@V8mkZx1)87jix&FX}F??79 z;etZ11DGI-tShzk8&ku&F6!sH6&mgRD#})DF6+5pUM6IG_C07E%s26Lb~Bk|u$dRYBfB?8ln)|EvvhXcMvV_0UIz%?sR4 zA7SeL-zie502xJGb1gkVI+!`>bNcq`<|K4(4~6KYK&RU_7r=L8KlR3 z8(h=0J>)h)%e0jDuB*#^^jBfVE=E2*-Ir@36?9-x<;xebq!@yj5M4OS^ycr7$9SC} z##wFpX?*{+ovF5m;^;px8Ji+}lPF+$m^uuB(2t`4%BH%{wWkN}tE3=SeV6TvwUDkT z{#U}R2T$UZUOKvOU5VNidDu6Lme|=NKr7u@7{18@dy1+~O9BPPJ}FNe9CEnpnrcXC zC_9$nya#r9xT@-SlB&I^os-!~-N&+icbkm3)>Ih+kt{w6^BKs|GW2yK+ok#XEBg*$ zmZm0GpHtz{MC*;E{_D5Sb9f}T2psQPx7}JjTKo1Bd_st7#*hGAuwcv_i(3sm@)%`0 zu|d|Z7^hk>bnK_e}kqw`xwT1Q^;r)g3yoBxVK@ zO^n_qB?L+#TUooPY4zG;fhva0)&1j!`KF9(-Dr(#E%i0!GP$}3KA9Xa`{9j~2m99n zC^V)M^!G4JfnQd@^=jKkM%Fpcek@Km|59uxGej&!&#T#g9s2|c&q+9byH=7R$aN;M zj@_SiFpHT(`cbem?ba9%^8Dl@Z~xw;rB=N@ut{R{Ct0Rf@$h$q?w%RCqgS-W=_>hE@qG2t?`sSc6&L^7ONRT z(=_`X_Po~wP8Khw8nn4zd{D;&n@4=!sCU7$fuxQk_W_CyFn`k z9zH&szIt|U(Wmat2x>H~2GOQ+dn2TZWs@NraaibV=J9>^<;cE%Oy!*$a}bJ!GX#j_ zafbcyvC8SFASaQE+F|su4WH}+XU^u`&>&4&gr+(k;`*fB_2He^7= zz&mO3ce@0wMs=aqvL?Z zF*k!w`p;G;=-s5`&0Z{{tT#;w)bO9r^K?=nv^;Ril%M!KcBHDc+Jb|l;$1|?y)#{v zv~-39FejYS%)E5k0F|_oMZXMab(}`(WZ#(LJ&Tw6?~g^KeKv}6&RIAsV!f%n9y2o< ztpp3QaSRnf&h90RF0*3N!HD6WLHzFn^(dMJ*m5JFQh*vIc8uYp16`@rt;@_~i^o>I zvF7>b#_sCu?`)Ww68)k5-_fUMOYGJPapx;T0AQwe{r+02QdyNcfyQ5{Us*$QLUre!wsgi&0Wc$6x20B`GRK9-=JbB2uwoA1# z#gZ@0>WSnbH>KU*`kKM=cWmX{^`qr~z_}2TAFlN$??~-$6b2&PI`{g^W z8sIpOvf2rJHZ#QdIzzHVwPY%~1yq}L^T2`o7gP}m(ry9R!68w(RZ0y3UjOMMA_fcTZ z5wJ`cz5Kth81MeJ7>nc8vw7_XzaQS|dGoCFK08w+%n;}ItHW$ZL~(zr zeI10F^Fl=6D>xHgVl|7ruIi=jpD^>enK5=m=3=n3pO=Oq)?~w|SLAjA5*VaAeUPFm zLok*GXJ#_Ys1CDStH!eqXm04r;a9bE#kTr;UK#dwDWY@Hd#?5l7{#z1^iMg%@tJE4 z)Sk^)dtOjLm(_y#`aY%a{1;U{v*I%ZTk@l=-2rnR}$&I7>ik(R#M^=C-ZqF5lmcC zdY_=SGB+2Z6qvimr zojB#0eS7;k+%(SRM(i#0J|@Oa@COXy&cZQ8f-XLM$wLB*f28+ z2nR5mRt;_&!eV(A&Ii-PzT{?D9*y*L?)|K7^CO5M45q2_=mEG9WaU1>EOK-Q^)|%^ z1@C(z^v*-8;nncgynA46gGP_KJmez&`J8yN_OdL>I+sGVAsCOk+<&1v6PFL5$n>g=Yq`8W#3f zGDh_T4#5RuQ?w6p6rFfhbo_KsJ2IvQ*+~2gcbHlo<>uwh)wFFeTwQPprl9NP;pAz= z5tkI@tB&e1ivS%|K-~&N)DhI&S?%}+ZcJaB6O4j-xN)b#Tcj-&y4U>0!QbI)aniex z(qH{18YztDIrefM!=d^cR2znv16^}j{8!s>78Qs}C%UWqB=n$v{vL+YtfmJ2q_d*+ zzmfo*g1;h9uS3VoTKmRi0lOU@umyk5x(2m?BFc7Tlt#UcMWpv|uJ`RXM-J7S zJ+7c_?Ur{x=_zcM_3dKNB9hz>h#+T2R&yz_a{)*pJ-<@S8k%ppCa{+fR5T$Gn}x1y zL1rEJFmI3*pe)*4;NB>a&#r)kPI%Em_R)7-lB?qUE^iGX(KTFm->ILh%AfER;B9x; zvOXc+jc8&rwO4<>z?;|ng560a7aOHUkYmYyLyv+C z!+@Fv&>i<|;u`pGOP~BwsxSKeTE7gXn zz%a%EgdpHeTZfd9457Z(>2lST&N)-(Mjd#|`0}cT@hdNX54SZF_JygbsmYe;%eMm6 zI>Zf_eCjbIXY|;4`!86BQcpZO)?_Hqt0n)oec-Q@ z4EbuWmnPR8I(K!-=$7-Boy#UZq`y9c5CYa8I6v}3d^w3B#M3rSd4kzA7!E*6FrVBR zZ^cQ}J1CDw4Mw$gEy}42Ar5=W9u?%AtbpyPjYsWVed4wf3d~5${(bX*_CdN5EN=c; z0B?__?WZ)vQr6otiQ!mps&cEBTTMdx-QjAA=Wv+3ge6#I_40tr9N(4Bl4uCBHmM_z#X0Owfumw zLa4qO8am-l3pr6b4LleJc5Sz}M(ScX%?T+BS;fMk6L?xc1Wn{Ultq1s5o$`&tQ~Yd zR^Ny&d*(i}`>p;C&cLWa-3vtt@_9jVo9hrS#~w{xtr4YkWKNHk8E{29G39N`E3Wv+ z@Ve4l)sLNf2Ja<|!mXHfB=TEArCIB$;!NMF*jx|N{5WBW~P-g$vZ(PoG9 zKK3Vv)L~`7QHOF}2J%^vzz}YM6*^+Yz}K4?cJt4;1DKl?Z-y6)D;=+F%n&tI%#&{F zjb>%Xrd9#jKD(%^cG24hNH9D(5k;{;0Y%B3Y5{SK)iGVE8Xbrh9bZn3KQXXwP0}g( zmJzJ6Yqr+|opquQt@Ak1CGMV>AZz7S6ds?yD=`|YnTP3XsovHvyXju&sq?xnExpRd zw|IEV_v34)Q~VFDFJ3!)ZO_3ZuMOf{Izz0RuEemQUa!fE3`9l~;IcUvg9a<&?RjG5 zJA3y#o;@0y(DLcvJ~dRamHvrOmLiZL%X=zo=UWrMelC6P=1 zz@+rGS<~BQE3S0qrOe*Q*+YSx5tW5Mf+7aZhtS`m-L?8B3i!OyXdZN?f$N=Ub|Kr| zbr~jToaYiMgBbfk5_A(l8^Z9Fk+ImbbHrWHlF5afWt-t|!zsNI1$z0Fy2_oKs!s%8 zq}e90?N#iolfB9{hTM%O_Yg)=GaWI`Lv;ov*lW~Zbw^(ZOq$t*4fj*-1~Jq2ygo%s z#`NF{A@!zA!xqAx#mwCg-`M`Bk&gA2dh+PeV;;WxXZ-(U(mSvhQJ8f$fMtfUrUAzn zB7B-+fsC+r5`jL<_?0*;s#o@A;JtP2Z;M}#(<+My_#O6^{jQdIRe`I#W#R*(AXq^P z*7FPA9dLN}wf9N=&_>-HVJMR0QP&1aFGbK#&)>V771TstO~2W+4D{%yxAX6|G@FUk7b0QW|o-v;?0N|nw;y%4U?#C zXO84JZYGiH-U4LaXuxuWv0=tds3NWDRQJ`r`N@A?k&nkhU=xIu%GmP*9rb=w5y0SU62FPXwaCq_=MMc~}Fg%2rHWAY}xl$e@Pt2SxX!@$LF1NLWOP`2 z<(o;&eT2@M6qF-c$Cm_{s}6F2=6=RwUUrT>zgjo?$*)O)fR*xgB*&cH2LMEC)D(;K}@HRZf7(aGz z?n0*Ws>KW`>Q%~ev;M(=t|^D`RJ1Zo@On#9X`PFZuhx6wN^>0%u%gGY5V&b%`L}9H z->g%#bmdIF=Lznlbo+oMczU3>!rmBkc+8TKG5rzPg(mg*VaD`tPl^)wQKiR?-8U7Cm(0dNfy1`XvbqLwj<3eZuoM+_I*hw z<2gY1%cmy=SRGo%91~(+{HQ7$wY9Ztemg$eB>u>#UxaPvx|Uq}r@{Zf1vuV8j{Kkc z{m)p_KBOBuA(nBzO&n*KxBWLTP7<8?=OEzc4xgJ|ji)3~>x#f1ptMgNd+8k?-w%~2 z&N0)B3>n-czklHIU@Um68WdY120SU%xAe zQE(QiPbW0)_+FYng6IWYOkTPC%u{*Cw4u^te9@3HC{p#s)$c_Q#%MrE9Y z1Y?iOF|cmIUN9#Dx~*&?RqCGUcO52LRO%?%M9C=g&)fU&3kl)9QB`Qh0a=WAk<{@XiO>nNnZBrX_ZrB7n%d?h zl-Q;37#S7tF)-i+e#9elH|W!Zp4xg2|1KTF{EG@?+db(f7~EbtFsn?7Y!y{>Ime<6 zTmSqR?48Tn*8I)~OiUDR)I@)JMHTk$yF^Ef%=j<*2PROo=Z;|pQ$!eIA#^iL3TLW4 zHL@AO_j6LRCVOEhd~v}+=;R+5#^wvMyn`VoHp3^q(Y_9H(4Jt&cnfWNbVNne&tIxP zs@3&g<^O?|9wY#aSJ2HzYYMh=)+xq&tgOV`6anils05QUNfd7|N(YR^uG+!M5(|U$ z8MBt!l9VdatciO}aK6LMNl!PwqixBt%2LUa{NLD7{p%}sz)~B6irtOq;`KUqO7#Ua z|7cVf6mHLD^@St)*`<`8_h-HYD>w0_<#)cmp^1s)Q9DX2JR$u2Q|3 z@58OBZiT|$Hs)dzSC6yZj11DZyun_nE#k_DviXm}J1nrPoRbhT5VQdIveD0Aa9zUh zYs|P!i#iU(_Z)f~&@h%;izvUr)_JlJNjak$Z%vW{i%THD0v+tqE)M9a!Xp*0;yhjr z+7(}VyW-~~>Rx{2he1eCq36BrZyA2B_c?5=gOW7_T9hJ;b3y0eAvp|aPq&jK@Z{JW z-7MCg-{1j`LnZWm(8f0t#9pYw3NM0H7$PG0r`t}^h$mInPmbQhx#bG-2E)5Ythv5FuH2preZHyU+JCQ-xKKzqEO7;YEmvI{}$yrl6+v z`mSKozRxGc8h@%ny1_Kl5u__|j5vc_jit=%XB6T+>^-;Z=RqM&daOQKz;nwip}|E> z!|ojdtdBKA}pTkRbY%hZoEUpXRbOa=_>t9hUZmSTw3$9DY=QYuw*wMInX;|Fg zc|*ehT0ZXekCZ;nQg5HL_eGz(S*Kk7Yb*g53O=n3R8_}RS4XMo1`v{(+eE{|afg>I zvP>1t%iLL=U(jbb4zy=H!RNHF zIPf)-HHzB(%j{8&Frg4*J$>Gr=i1P*%EKx*KPzZoyR_L`+I%spy*vDXuA9vJ?t|zs zq$grjmj;Tj;g(1bL`2RGtLaCe35yhV)V)5oxbElvW*LrN$cp7zzUXERmn77t%SVW% zJ0B!|MvX7Ccz#n&Kq&@1`V`;=#8cIdu9Dnh>vh_VZbcdjIK_I!8cY@#o=DWXnDAR6 zKKFNecl^+y5F!d#ye14V5ifM$43S#e6vR&nq6KH!QxzUL>wX=d?94O0U0w5tQFioQ zlnakyDw>14-B{>exY`WhOJJ&Cm7(Z71`4`4LlX7`j1qO`ug7oGF5_b)qS9>pm>aXz zMev#QmPz#)L<<@YnHl^w{$omX(7PgQPjufCG>3_x7s16q=))O=CU_7BJUPc6&k*9G ziBQqa!C6p1i1i;>*HD1U6-!lVLVn};Ob|OkrNM&$OG^2`?kfZt(6#VQmqC$m8q)eS zij{{*lqxhoLve8Zjj7i3HN%8yua5)9%#6ZTahcM#R~z$oTI)zTmrN!I)5Drr<5S1M z_j|Y|{bNu$nZP*?&Dl~W(wbJ*oXpXl9H~d|I$n~I7(3ar>x^>fU0ayfX6-DJAtg&! zW{rZ`7?gwuQcz>k!k7v|TQ&UaDU6(_z|!#^3{~eGZ7Z1L5YOXeC&TzT+0&M4Fpz{R z;TeL7jiCPtrmwWAv9sTsM|}j!L?(h&y&*^0+8w|h_P_PiS!yjE#z z^(}QRKjOTs5izX)FP`@)g6yK`8cRm}S z{q+0{<$}yF>d%@;#@tH~8n!|l7NRk6I|m^hFiO``YH4E7BPx$=RbAOTpm1<9)iA+D zsoFYCO~Y;BwAGtTkIiKtFWR+GZbksOHjhc<7`y19?BTJR9`T`+2ze zz^ae%6l=x)lY4nxx!WQ8Sz&ihW8SW^)$U`%%vjQks$-esq5LNQqn!UL#+-u|zdq3A>;e3Mc$4^M{ z;bH<}d1Oi${If#O2iJGR6~3AUdgd7_rfvV#DRJVA1Yboh>_b!gTI6dOUPBwX8+ixh zdYS~t(X`}=WpUmuo`BSGk*~+R-MLGSDy;~G%T#zPg(o#- zEugcL`6Nda#(Hsq9g$N9_GCaOyNa)mA zDsZB>ZzHsHa7<(Ml`tdZ($s<1E3y&7N!D_ST)`_3z~ABI399wcMoDPoc6NDbKs0 z$5EH?O|Qp>V}WP}3MX$!eek`FpAj(hGydGPX`+Mm=64d^Fsmr!RVRJDnltLz@dbn7 zxmut5Ko=Fx;^v|NE$u$K6*h>{x5_)hf`1`8hhGp6TeO(gCj{Q~_pR0{ew*9H5%=S+ zh^N*Zvc)lS#hHpS2DdyN-!!4du!YXM-Ukd8I!o} zoS7ay&EO{!_jxqPQL3JhSGByn_pwH&#||fO*v}fb1~JsS9TDv;b@PD|ME{;1>Y=-!JtvJ*Fusz>E3MWUD%*aJIf% z6cHAlvV4_*?_Yc7EG4{Vt;ll*@tQzEa{);y6j-P;FcLZ%(|e(=ldE-svpx26ZPJIz z6I?SiM!zK-cCOm@sz@+wN~+Bmb-XjIg%>9b);I|GqzYCVBp86bDd3b#)-|dt9aCgo z8LnUxc3^ned{y#Yw?;ZI*H(!&$pB9V?Vqa%XlFLrzi~>B^nR0J_qrW>YBuFT_O*U< zm&Y{bPj9|RIW*0@1sUO<` zr6vG#LRS5K-f$II^INs}A5hWCC1{-+hWfE+qFJ#=VU0oC#FYQVq)E>n@gp8Cb~kwS z8jEV|*iVpM*lFssD24!voVPNb$LdFk)d`Tjq__aXej?ZM5#sHn>tdnq+qGBbon7mr`?o%>r}=iw_d(i3F!v4K<{{!L zg1S6owkm`!!CX0gF&HENKGrmiTC6E`3W(Teo@`2b)v0gZs7$Xs#ZAv=|MCY0(0RWd z9oqiDXksIOU_aY5akZFr+C7kMlhYdHpeDNA6b5BNK}TuE?k#255KBI77>6`mxEHfW z`uqV?Kb^LX)_m8;rFXA*Q2~Y$S#ldmxuy!8(w;@HiacKwf07s$5HTFsqCsVwHwY5= z`nBl@M`54bl>u*1EX+^kc%)DV0GPmvgtd%=3vYz?ss}?`5p@=b2-a?h{kpJCO>45L zW3tpBeIX|jSp7uHi+i8dwM@X{oCQIa3654U09NsazK_0{LEiaJskyQ4x8|4 zUwlt`AEkgzEx3Ji4#1aBPNmV@&OAu2*@dHdZ7UFaK(-2J2;ylHl%R)LKDq{$4T_hV zD)9nt&NbHjGqIwZz(3_Z?dQAEx64qz^)K}mzNA8--9s>3(xjuIv$x!!QQ3L!^dSF7 z2JCXFKR97{EhHrX)plBy)(RFh2F#sQ0Vda&Li&p#1uT*4Yt~D}&l3z_KKQ16`W!n* zs<0t^lcNo-7kc59HwKwB)g`Jxz<~*Yvgy){b2$cOR9D7WNY;rbk#y^RaR-N2Tx%UcZpK_iZeOLJ zFh&2S?*YPqz_zkR6~TppPHoa+s0#J0j3Q6=cAd&sC4XQ?-Mw$~Tr+&Wf8tW;zR|~&GUqe|x*6Tj6PR?`LdRtYZ;^XeXK&i^6 zNi=Zpc5n0bjg79p*b8IT?i3W1zY`#3#YR?T^;(MZ};|1lesIMWAddeNSNG*fDsAgQWn@*0A7~?Ru~qAkk|w+6i$uk1@mbOlJ~f zY~p7VMX=iSjy#}+CecH181%X6R-H0Ws6Qr*$w)jVV|~l+Dd8!}69MTg&!o2#AlV#J zuKd(%Z@K|A-kbuVul5%QWJMkQNw1CSsc%~e;(I!LNJ6iy@Z-Sl!>@d8gGmgrMf(3m z-J8He+4p_JBSe<$A%PwGe(&>rp3nQfpSMq;!^|B272sL48&FI{;4i=a*2wdBZ&OV&%NNHXH+wn*sAK1Oh;*zGDS;5XK%ZAFToG-qL=j z>&npQ9|=(I%M_4KV92yI!HlPv zcqIN5&lW58{zs6%Q-*=%DC&ZV-iG^pfVI7j(G_zsb8$?wMI92x8yqg_pb9(`%&k3$ z%UZTm*${bs*PSGBSCldjSfmkmsL_J(g;WW(h8Zn#jK>^qZ-4IXsCBKhk#Df%?&G*+ zgQ3TJ{8t^P--d&5KJcU?tvOPzz>uI}V=GgEIk~|)ZMZA`ds3|Ar3|Ogj4PwJ4tNSt zn_h39$DR5Q7Mb;!CTyIGSTluh%3XnJm6!v^HLf;kd}AN!^Gl--%o+5%8}mC|5mSxg znbKwe+&;*|t`8KRetVz=UGlL&#QdDkbB113NcqXMBO}_arW^N3d{JJPcF{x_M*%2d zMi_e^@&OVDwDD*+JdSQ1ZE8s?yg^Mb?SJ)n=xb=>lXGzgQsixqoA3<^;%dm77@pJhjbM3aV^En~8j9~K(JcA+z^)f42?2}+4KLRL-mWuj;{+yw3$7%bCz>u}eep!~R-1bxol z!Lok&_+K5`oqD6hCpKxLkWxS0d@B%lSjuHx<&|e;rEoyOelaOm_|8^RgUu)89?y!e zCE*pUiHQ8<7Ma@Pi>FR-^cdd{U-7JE^4;Z`zrE$UJDYI=5s7BzJ~K^bDvagDEa3+g zR6zqF^XEM`#wUFvD9as31xD?|NPouZKf_anZ-RN2s5k_0TDjS1sxX{0c!OEKXVG~u}8}7TwPBhGgqzFy=0^KQ3N|M zkD6FoFE*A^VmOyIhD&jD327!N55LY7RX>MiB>%j&p5GxuMKpMf_rdt24;BzcQOFdP#}q=(Fxf#qB^-75ZFWp~ zIn)1%9Pt42@V;5Qcn#dwgI!50Q-qJ-cYc)$zrR|UjgM+kq%7=wI?i8z74mFGSn2&vqs7IEN6YS(V_!*_B& z-H_jMzqs#i+CHos;Fn#CsRHPJ{fWXNk)6nhGOw>qpWyeq`)|K*IVpWXCalcXbmv~mcx*M=hgMP^7BFG4`h2dVvbbYtSF{xZEuCn#mC-s_i zJkq?~dnj7)>%rnuOL^}cF@?+WCvcC!NBs5UpvEdJEuXp+X3h)RLEJzij%!3OpclD5 zUW(NKV+sLO@9t;~S_W^8OHvZdkX5{sP$*oi%GhEN$kLu zpZWUj^UuZgB5F}RKJJ2_cZfXKY}+?fQP)mxNB_-_|5cs9Nd>(s04eVY$`4jJ@ZE1M zVL9Yyh*CS){6~JHo(+NCgi^q=U#N>T|G|9&>d2@7$MkIHP&+eh^y6K+pPhZu0iTzx zIs@jO#g5~=ZL=TE8^#9M3Blh2CKc-)cSf+_%_%p_XlBXb@G#l zi*r+B$NN;1UvJ($Q5CvbO$Bw@>`C!QU;6yt9RK|M2vD#!3_CijB?Mkm)CCqFR|I*N|zg_G33%^$kBzIeAa?5)YF@5U*<9qq^4fTxpGS^PyN5u^>R zNZ5_O?YrdGsxiUV$287^G$j?~gj8?sLKEUopqh!sG>qJ)`jN zJA_l~y}#NjDr+wcB1%B|@Oy*f(6*NJyD5w2yaZ?DuNSk$N}-Dw*tmdofSZbFI>8+c zSix7GOi<_2c`o$TR7mxk;#8XpY1@h};L|P73bjeyNWIfg_X_T01T3sjUKxh((=MuS>igs3`7MflvHg_p#?T#3Xw zLKi4QCq_Z(qBG-!EgZsVZ44&JFj5i}N1XS~Z_%4^{+?zl|2)mgBW>FV-91(-Hp1WMuzRJD?uiJiqe@RiIBF%$a z(Hm{tm()-Et5iX)F0z0$j#31))s?MH>zM(7le{_zP^IU#4jV=ou_h1I)HTE?hq>Cy z{ShO?Ya<_dl!rHAN$hhLvZ0t^4XpdotWFFK9D1&1gX#$(%>1$O>OMo%^ZQb6AG!=) zsNIRF$k#+&tOE+>Z;Dy0>x;iH!IvCaE!h>znajE2jX^LYdWPdQI-&>OwFEu!)r|++M_tER`GrS zbN>87-G}onR7}T8@EFQ*yz+0$KNGeJp_wECoh9EAreSY=lc``3V~`=er>s;r`zyU} zZ8GkTX{7p96a}Q6=>{=WiPdKF{>= z|56-$YEkLd&IfW;DY`G5CIfiUBYjmtUfu8mTEU(A zMT9l-I5GyOdW!tASi=mfk=w%tKj7!M=3v+1G_lNQzTCOK6D`jhy>#qlPqP}(2D_-J}zd~RCQEg!$eg=%ZA)H z8qRLDX{M!nJ5(jFW(03Jb@JS)eMD9Tmq<`VzM}cbb;_KRj6QQM#(hrr7u$==2Cn)Y z@){spV^V+!0V~D2CKsYDpIj^Oz>ao;vRurn*;fM)LaPSH zaqCfmnaW0VtUDUs$yl^xkYWN8l>{0IN~J`H-oWYIoHshO#Eulib|1vQhm?daH zjhPhM3*1szwHG25ln9^pmPR4 z*-8c|k9%_+4wm-<`rDQmOGwIb)e+3?InD zi;WUvc2NZI4t5;}JkG~W2Dkk5OpQ--cI6FBGuV69^PyuBVFb&tBn>@7gk;BT!tI%M zqbZMG;UB9xjW`w8R`tvm9do?&yvNm6{tvB4fd_A1pw{sdLjUHImLl&#C$$C;6Ndmk z4?BvD3dHfj;kJ{u0q5iw^~T@fj6&VYN&!Ny&g$Yj-rX__j!j~)A)BQQr;a7NHpxNz{rAZ+rG5kz39V|LU`R z^K`>`eHOX|Co-fO2j*WfVxY%4M#af(wugY7|azr1@j+T?&l~4Oz3c!(VfN zF)7yQ^Qsp2WPVT3>|6~*(0SDN%qF$dK!ckTdH#81s~ovZ&R@an%mMSO zHb%f_kFtf}Su|q;8et=8qJGh=v}ddbv?D3bg_6xl0Q@CYguVqK+dAt-En87bZM$i@_2)UzIDe! z5!MWx;D4QUB77Y?%LR>O*AGw_wjjE%lr8oN2NHetdl6xHlJ)izVs_~~s81{L4Ia0}1HGrBHsV0E*5H z>Y(b6wF`8|_F28$LT~U&cXjRDWA*N06n&GehiG|- zR>k0OP4rpEEo_ieLqlE=tih_vp8^?NL}}>9=DA|op}8R6f|2Ay?DjSdwRF0*_cOJ1 z9m=1YPgWdC3I{^)Uq=8n{_BoH5h{=2(y)JHS*L?8!d>;5*e2YDDHqUv_AS=+)2~FY zQcCZ9;Q)PLLH0OVG4+ksk9T)YMhP0OSpTiNhp~V!wEiQ~w2Eo^#XJe|UskVnjSj4k z-Td*1dAi~v0QC_~;_qS?I`8HAy?KWY^ajpaTv_57tV4MvFiT@}XA2AI5(fe#Q7>*M zpiZ3v=M|Wy3tos~7aM|lEXv6oNf6p;1u8Gj08|+)-SP7Ufq*nXzC4U#PqRS!D(VtP z0(?zy#k-@E9`ltlpThc6cAY96q1P|53N`Ar=AvvmS`fFeXV;EZ=vl9O+t4$hE$l># z+C3U8EzzoYNyg*o4iso2Ft(1O4*jkDI54HXVEwm-$n}3p**Xtgh$N79-Z1ms5{xuz z`tXO{=pln<5-iz~3ZKAGXe0APT$w)i?pWpQ7&ELHQOwc~dg9IK^a{B0cEPh6f5S6; zV3ybuX?_#D|2{Yi4G=$cwk)fmPN5cLeK7M zRh76CA_mlX6xdGn+mY?zUfg_7ZZSZ01t)+KHCFb`S|!>5ZV9{2_4>G!gii5?gw~Ek zwWc%AQ!_&}u=x}kiNdhN4S_?DE4e&cdGl<5Oz6e!;l~PXxzAp;2{!USc;|FrqtLt5 z0*^bsQ}6$8LBnBT(DapCI13_5Vz8QK(=EH4I5+t2X1uB$(ey(=h%h-^cvrQ_ui?Fe zwqT#l5#BEn+R+S~fLksaPcHifQ6zol>2K|wgDDSQn7oO13KB`54UiYO<6*ec%!c4h zP-zXiOpnlTL(7f&bvX=cn&QG2xP-M{*Dsi9E8mxOgB5I}<6%1bA*JfH1|_`E?^#Jj zikwG^+_|HvEeSHm_Ps-GMDdoRZ2w;j+41{%S(P%Ci6MDYn<|zEWEpSYc9u7tw<+2h zr1fL!n!K|upR%Bu_*QrhA27t8M7Cs6YFPNDEg#w!HCA^H&Q#$uIAxA zor&VEe@X%R5Ka+r1f8*kbAcuTRv70J1xKOXMOT7cF5`sQ=a5FM>|D69Sd0dfzjL;# z_i2r>op@z+8Y<-eiA6pExiK?u5XRJQglNwJ`ap#GT5|@=W!{^)yq~|-c|9Zl$}6O#E}?Ra+WzV zK;!&ICDuv=F$Ma3ilUoD?eRrfG%qk%Xr=LHvG$6m%`QPhs56hq9EgySi(1> zfLMxftu5WKQZ{*%t2KRGTy~*pLe9lL>viy?zd>};k|C^!rNK%b=mm>iRL(X4!$}4u zds{3CYgUFPXavUvu_9M?AZ$(hP8FO9$B4yeQy%=A%2favXUm zGPe68Kfx2Ke+O2}y$f)~tC;HmZ!!6tx!n1*KwEeJ5BPm79yY`J7u1Ep-T#kWf|+^{F; zV3pr#r*9`bJWm|Ye6NyK+1C8tYKOkv&UdZ*K)#IJMS}GJ+AZKTkhMO9HlRKU+c*Z@ z9L=$5^zA+Ot`2uam==1OJxtHVPsTsFpj#`gGO6Hjjz1 z!=C#xOppflLWJVzL{Ka{0~Li^GXr9m(85zLxCH+|x!J(j``P%X73F`JEIMah_4%xP zHFEbf&JX0pWH_Nc=HuOga$IH1KF5OZk7SQzT`6pL5 zWt}aTEjFW{fB-c*N+y8ubRUJ|0n%B0@;6G6JOd$u9dxAw%_PPl(Ea^*KL%85S}ndC z_N9w6>BaP-HjaYlge zi%t>SEJ53b0+hb3X^2K7wje-0hVMCmgP8 z+o_H@zU9?vy4$MwN#JYWKUItToz_iP*7%QnsIioF<*u%11CW%t95%*uL_(k|CzyLx3kMr%^pv`OcyWf$fA^-n~k_#JnaHhg%=KI7_R(#ZQM z;pa573lVttl z`rf;xdQ-`nxHkz(Pxrr)RrbGja;X^=W+($-LfTM0ouI&d0q7A)ai9RLkih4gY1T>% zw>+1vzErn8;be)i;|8(Jqps^lLIAn@Ll0FGG!QWLm$0<*&0ZXd%0{f%FEfWx?lMu8 zIo?0}QoZO^W|(u9XG}?mrN->HkP4&aE)@F8FqeQ=5(rtI;P0Ox`UFe|>*{(TF?t&?||CBD^|=(*)yO3;yO0U>T0sp)4o( zZXT>Z|Bkila69jldE?c5UH1F)m6d;Vy!A*DSz!m$xF04#nKXJWvNT(_iBTC}uB7iU zG~XoIo_EIX(#Ja8TiW-oJtr=?!`WhArnD!}!@{6)!-pY-Y&eFVwKTrvZ>Vj|$R*P6 zj(+buc>ETHjhQ2S@=*B$>0Pd+WO-S3q1Pd86b9Zn79@@^!x^L0Mq%7dmx;uyOx~u` z=4j&4jAn_$=~fegiJjYYZ=S6wEt3FqUWg)mIEE8ln|DC^1lk2l6j;F_5&0amI_3-{ zuFE64;H!G6V)kzJcH>yKb%jw#m!k1nbC!+DAnEoRr_6DnoiQHu&!;(u8)h5T zE@!yVaj&NIwnTRbzHW_X0}d?q8&G_+y7zz8RKnfIF~Eu8Y$6@wW|X}E`G%X2-yp?1 zAl`P)i4$3d0>xzVj0SUC{oxQC!0t4`$q~ z%ov}YpTXgZxY_8&r{Ow|Qcc+pG_N(bSJvy)H%!pe^@g(sO zzF>KRsIgSZK<$XIhEctL()PUY^a>sFzTiqWkqcOa3vjo}_}J+QDJA)h5U z#&D`eF_V{N3*UTUI&5AnVmWeHhu|~np8BOl&|qZUrc=u2uMe(nBLBx-a6E?p`7U*T zz01BmrWzMi76eryEu?uU|GHIiH?fRx zEGG)`qO8uo0_nsLvOG)jUa;Q# z+`cBfXz1hI=kL7mPx3SXuLALXPlIC!8W^X5_vgt^e|Lay&I40r>54Lt^$q8#pbgj{ zh-*qovDVrh(H>BXDRJgvKMAU}%nNyOd9{y%_7-0Ehuv!3HFvSt@Am?qSEJ zD%>LwKm*2+F}V>);rZmpTFeR}6XVKk9!%JUow2H@?KxkP^3@cc&=YDKPdU%4C?bV> z8u%xz=s#18f}eTnkv{6eWt;?M#<34fMVbpDHqEBPskAqBY5*QryZ7p@^iRISK`oEe zx+C4yGc}T43nWDjP4-YED0Be|FECEt;mIH(od_Y=edtFx#-%t;9zYdy@zbPL?^^Qo zQ;HUt%s)sB-;fxHmWi$ih&A8&lOkJdLGS1isSgwK$=IW4RP4aYvh|DC*Lh{tz1?3x z?L6hwHr^E}V2Zq;j2ls8u+zOD1k!t2< z-_-4LaQH$|jOd48`nTcT>(zWtR?K5UERx0^UaXZuRKgfouA%_&wHbd@0)@WB!*&I| zylm!gfi#n-7w|nKDUSgg{ycIdgyzLfSO#6TPM33K@OF(%*sh`a;$6k$T{kW~KYe>< z$4AwDk)-Pha3vzt2&9lQ4BpOvq=jD!t%^$H`xDi30}T0H4%jUi`VtlNE!K&JV<2$74rTYtDSIwy3)2$xP>cLk6x4 zT?hj@C?$A-24EY&)?C>{vBjRpeAWaq;`Q>3&uG`pRky*%It*f*^%blS1{&W~2Q0jjWC+AGH%Aa^20O6~J1ndr77YOKl+w9; z#&rGW<@j)m=Tp@)!%G>PM;ZntI@EUTKX&-o)0uVrrcu{gAD$J<0i=Q7L0beYnC43E z^ST{S{YioeoYg>CN6^71HdYTN`0E979gZ;GjyD(19Mn@b*`)s}uTRnO*8`k7RPS!S z6&b*7tP{Z###nX?$Cz3#dSde7)epJSG|o2k{l!F+e)%&?|C@6P-7Ow z7qbf7kz^8VO@)}%NCoJLNk9#n%Ru#*I$k)SY1lkx^fyY}yH2>b&`{L)Xr*sh!S-|+ zQ4qKjNfG0>;oA&@+T~d$a3O^5uQeBHsD@e{Zn^Vx*GYf1+X_b?m2|Q;e7IMxppg~! zQ|b9PY5vdeVoiAG#ri?nhzo^A!@(NpSsBoPL#T`C+U&joR%h;Qc30>t(iP3k&w+1D zO!WK^wz1g0HUD&d+ip!hi9QLOJk*#$@x`qgqmxMRA+Qci87`n~cjnl!PvUW`z}Hz| z3g%->ZO48ZdiNfUcFz1}oY3l#9tM@!Nw0U%k^s#-oUp0JB8|8>$-!{_|14;w#haMSDIx_W1eeJ3J{Z`mNP(EWzv z2}J+td9Z`YQ+pB7G1!FO6$wIG=vxFyW^0@wc?0~+*8W&PV4+L*EJoLED#Jf(?23Gd zsZh zW<^!*+oDwZt_t=6pA(YiSE~3f9MBtG)R^s9+(vGj7Xvrk07S>L%;2{kS2brRU#VSj zvsNu;YE%YFujeCa?2~j@Mvwc)MS1g1IlxAx$Og(<9p`EZQ;VNWL#{&?Vf+h_y^7z?QPAPVEZ~ z#t2v4^m}&m;i+Mib{ss;KFl%U{!ylV<^68b4E^Lt3(>e9Pg0>TNoj9s|kB1HXe6e8e zee92Mb3SM^Bo|^%F{m)cx)~DY_yI8}!nwjUjt;lYhD#f((-SWbWabhfnO~3EHs61- zS3UlL0-yL5ysFG%2FJpd4T479mN3{+(Pw~JasSs4m^~{B?U6YT_#}6zzLKhh$c39^ zHOXdbjkLb}a%S4m=Xz+!bzN>kP4U5Gfez4|(GrE(Z>z?;@(sKNsJ-{cDP95WZNsui zMkB5i*hG$;Gzch!hT%yhzJ%No0INZq9Bo$cny7sO{R}r;%K!;9L+zT}M?kOX7C}F< zv`{O)h)6ZCQ%GpdLiK}`g{**hG)uS}yEGKwUIWa|Gthen&IM4HvH;Yd z-7D=j3T>LYVqe)rWb^+ZtzNFo78`(I{bl5sFG$w2w+#X%X^}U$Xu=FZ4gsFz8Ql<& zL48cg1#D;k-HRfzFS_7um7JH3V%#*0z;D!?9_2CU!0N@xxyuRw4@7(dDy#xeaYffK z{Nu;pKr^X$pa-r7aTdVLDqzQTNTm?>UIf^sc2Bd#K4V~WEOJn6h=MdItAMq*5rju` z9`GLrc z0{^*(beYS-0d%p=(?$ffH@)TgbB64KP=A$2K^Ec?<+b85ZYrix*QtQ9?etpE#K?A& zn$Cxp1?_4yp*Z&WUW8Ei8#Pb+joJ)PA{*tZ(>f5rX6AyoXPW%8Pft7p&%er>t>8rM zab$J_R(f9d->B?wWB?*cgOX8D_zw5RK$`^b@7jIZ>zi$kXs>`-j@ITJc;QO{bj}Iu zR#z7mJK!*lF7u0bF9vBVj;W39mRa2b#y$qdUI$d9P#BFk61I=&7#D7qJru6uT42V% z)V0e__kNShEAI^cuhH*G=lI%g^2&>~y^%+8&5_S#zfq(Dhz(;~9&LOUaE|oAz!Pyrz-XK}C-SFp3|CT&__s^OgI9GQzp2-F6Dp0K39El7 zHF$RgG#D?W`Rx8C&@qHS5JZfd~h%FHMt*=VyB98$fLhxt=^8?gGbM zb}D#rE$wr|dkgPn?bc!^h4@YT4%I8vM211LU@`?T938;MU=L2ZB!e6e`9O)fs;;?2 z+IOE$StIsBAqI*j`?5HNMZ4B{~IG zzm<3#d(?hx{V!1wFYZlTIA{pBR@n%S3he=D!zhE&KouVGS+tYX%P(?!*;z21wz0(R z%UOf#X{u+6bC2{L!|el|U3Dwp1;9G74-19EeYub4S$lZ^YQF-Y(L3anlh{YiS0~ z3A&E^$FCuZH+fjg$MhWA3SUn>&U-v-Hm;#1Jmcauo3xci@r88<&)z$b{DCIG5f1}J zfD!B+)1`!NT-o6sd?PD~8Qq@GlW)&z96e!fSNwmz<&RHe*RfOO|7&eJ{&$e@|9G!J z<{C?WiFG98kBQ8jZw!dvBUATwG~$MCNfT9Ppd@J}MBH}3YRdG0CQ4bWu#RvJ6x7O?7X%nfX=2w>_TGQG4`XU%0UQ!i5WG<-}2Y zE^Q+}f@nEd#tA5n!ZK)AoHR=@1{f-PWcy z9w!Hka?4}5yJ)67apu8q)IM}F8g>|h7X1Et1w|4czXrHfU-Qd3VRXSz&Xvh zyt%wGHvB?>djG8(&o_t;KeboW{BSVj)ZSDw|oAN=2ZV(fx&^qRtpX}ZuJdQwIy9ch4GfTPl3vmn4ATcl4T9hZSPzI5Mx~5Bu6rfK7YGz zE$wE62*SP1!w;(m<7@3lg+&jXsJk!YJ{NLZ_L?+*yLqG|6R0!6Z_mKovZ-tabrd&@ z<49;2B_bQ-*?S7KwK0)P?=0k0mxcGCW2g*wDy)N@HDMb-^{48#<1z0bdDAnaM4=yx z!-eTt7ny>((JoCNq@^{})qYLchlc_RdK5B5TDn3o{f(mB0lw%wmNxDnGUWnk zM#Elt`kGCQGekcZ7%Gs-5e6?PGBwD*L}IuQZ%euSTppBALR<3CZ$7d`y5inQ^U$$O zaj{vjU#$hky4Wi~-zkuP)*zw?%pSuGhanrbGf1t13Vgk6b6}T5ra>`~JC1QVs4N{~9K=Nx+bgEp#23U`uZ2L) zFGq=@B4+&_YM>9@|4YAmC>&QT= zgwG9SQejti?Trr-2ljSK?>O|~sqxiPsTX{At`)ZIaCpB)X{B_6jYV3aGGbDlES%AZ zl`JZs=eu;=C#2We$$&Zj#~dOUFN$bbo@TGv~%I( zPKy6Lz15H*HuDwOHy%hAu3TW2pGJyB(2UBaA3G8tB;cNSJKl zIctl0$QyZtXVsvAv~csQG18`nTO|r1U^KL3(n7ieu+!h0$Nfg-bRQM?1) z6={77?3aUI2PgCX;w6B*d$T3sFy|r|QX(=y0#)@RUUchvfRC(m;Kj?t^b?{U=+#HH0Wn{jAREn8>;xVdp zo=x|Z#NH%qfiG?mO($QKQ!kv@ms(`Yvwll__qQEw?OJWw==_twT8DOH88?V2hGY@K zFiG%9Z&30Hhgb)`wppd}FLw%zM<(UB*vP+AWIKWsxh{1R^r@SU;m85MrrB}ck)zZI z42Tu@E8CqgKoSn3!~hGv)@!U&^DrYR-8jTW@8R;*5eHT~t|OvqIJo5Tjp$$Gb_l*^ zJR9^IWi`q41+m?qAVw024aU+wH~?;GAV~n+`9RjOy4pSs9Qq?)hQY2^0-tqiiZv)_ zwHLY&Q3LKhL=6Es_t#KLAUYn@wWDta70fGih6P-BHB|m;ao^=aX`7c{?(4iV=+(0J zz~$dVt%3d&!3pKNz1A0ne;W*1WlrOS0weZ1^>Va>g7V-fyGMt~L!A!nFs6`vzPHg_zcOVQIinRA z%aqVaIX7PO>}6W_3zHM|W@4%o4b3O9aJf$LW1Z~iJU3vsaP^nY&`s#)FY5i3BZ9kCe}YPKG)H0)@NLV~9Ax;Dn0t>ib4h-*(78Dsfw=kXa(%OgCh~;* z*^FR5?c|yp71vwLCh4uSvW#V#PP*_ISqV0-_j|cP^v+;Vf#2?Lf~@%k&g2<(NN(_? z!l0SuRS*?s{6-CdU}a)PJ(Z)gL`BT@q0OOsLjbxZMqz=ykupqd!o&`@Ho4CFp6t%~ zG!b{EZ`QvsJYGHac)dqOe01#1eS3>zFGpRm-pdYy>dQ%Ml~&j?Ru$8$b$GH_7$=2~ zQgG6Yv+gg{of)$W!_(|H*plq-lV6LAy`lHFSuhh|Y6Pz3_G^D%Y#go*umN)y>-UPQ9>J*|CF0em8CS zZ99y2ze7v;k{DiMGX->A|HY%#OwE?us=7yW>e^(d7oeu(wRvN!+TaMm1Z?wC&wKRU{;U>ZmQL0IN-#nBf~3&fhv;nhhN*(tm7Z4^fxxT-eLm6_c)F?2<&ns!423jf3UlZ)o;PliELb^qh6 zT#h&F@Z!>*BB9s`Pq0y?~-({i(B?b+N$w%-e^Y2tSEqiErWH~$MNFU zfr)$q9wLBPr|@%+fBq;W+z$H6=uP$&&K`-8c1dtk$VhQ?d?4ZvJ8iQ5a8O3x4F>u$ z8GHl=X0jy^Ff$^7Yc*3+pkO>g)sb;8V>x~JYVv71RAHyg(z!Kx>BV%4dHIU{U+pbm zIc+14p^>dT+*0fh+8Uk*0>P!RATHo-q)^e}7uXI^y}G#+FsKj}3ez#su&ghcm3QN0 z*Y)wKkgFQA*<$x4q_1{cqR@;hgp8m)7Zr`p)hZ?q{9w1+`TVnbTdu<$&;~oGme3S&Ev}qE#&>05i4+PqnhO6?xoG8UhxqSkl1(MJl zrp(Xfa;?*vC+;EVM=Wmpw zesf69JK0Znl|Y)AOTMw{fC%R^NUU1;5ktG7htO81WiQsW*(yh8mGwxp|Lr3dna6VB zpurcy&;5JqzF)K-9ZZuhKt*&|LMEpvj4PEKX#-?Kd598mR)OIOXV_F;Rm@DGjOGW1 z>g{aVN-15}$<^O_S5tA78^8vh-~>3q%?_o*99u?ZN}V*dooF=HcILWW+~9Hr%?;f! z!r8|AYqbve_fg4Eec+#X^!0`76PdzI%b9tJMN%J?H#5eor#3&|nR-9;UbQvK-)N;| z%jIzkRBACDg0)-gahnOvRGB*Ma7~b~rJ!v=UA`l-HLc|%Y}ltOT1#Blb@@=2Wc${a zqEl6xs0m6EKrliwoCC}edfaVOFM8+kNf)MZ0%oG`*WT&q2YN;7*XCMZe`l;m$pP4R zw%Csa2sR_pgg(+SF<3d}9jzYvKJP#5l{D|U5>Y}Zqr%B~Gz?cVAd#95JcD)_PIosz z%1v^tdKt1vym9k<#}SYVOu*8ONRgB!+d2%v1qgM3m9++Y`N+3*zy;`qE>gs&6Mc*D zVq*evexC1SV;frLc6YHaWw?TPY>*S%aY|sOnC%*F!YxO{eUQB{j^3%=jL7%xcFi&| z4-4I~A=W!f@_^R&izYHoo>!x^VOw%98Q#SPotb23Cc*Z#XG}(J>2t^ObIvD3pq)y> z%lxj3mMsn)c~+LFwc?D7H$@91p&+LyQ@ zUt;dCPx?-7mFZ5kHz(6ZrP2C7(s5dY>FW0%@(-6>r!p+&VHGZjt96j=*_MRv6Lw=_ z!v-xISJR4ej7JpyIm9D!yM9~Tya5m)|9DS(QRjbp&z;TpsF%$*8GNrXco>g)xKm6; z&1%CzY-rXmcR-`CMy2ro;XhsgcNQDMfXSV$VHi8X*O>;56?Gbn+_IM!EAD5SY)L(G z+}rcG^7f+(MYkl{)`C5gGtZa-EkHW>dU2#5)U6LcGJq-X8VaEI57mMw{1t3Sj)8u5 zEzQq)tNPZOSXg7m-}0S6f5r07Z?3Jo^wo+FJ?ZYQ)Xx7dZhbVucR?5tvjCZs zORzE0nh0?<-V~7$(bHg;#QUPl;$|KdhKs>B)%&ngSg(~qt2Bj~!oF4ai4@dm)uQfW z6Wu>N#!p6L4K|NsX-nu8D{?e6gRcbsm~R3KIr|R)HGq=QzCbJcp?4TI?^oz&%T(Pk z2p#|BTK2jG&TkYrJGUTOK^=$)MA;!9zX>tpBFh|veKWpo9UQT%PIQY6RkgV#s&V3d zn!dsn#WbtEA>?*3IN6Z}G~&|`2C%VsFaS!R6^YGV)n2&+GNApCH+5AL5&+XJxpspz z03`f37kO6$o>E98SksuJl*k-mz2jEb$#5`(98pG%Lw9%(UE6Ofi{3Ku%l}-$>Be0b ziiBd7N(5PkT;Bhni1|nG@9%%dQ#jHgEt@MF=RXUK9jSUUWn67u{v5A;x~90U^ud!i zr4Mw~J=2Vj%b#&tCkKLZ35YLHKM6R-DL|v+I)>xOxYD4Q@H5N~y4P)vaS=Y=uUypN z=%Cl*fdvEUThDKI#>%5;%j^C`r7i&0zjxd`WGmr4?ltCCtp#JS<(oP~ukz}cobH9X zZp`=6OsC}X`kkd)`0w1=*xRztY+vg~3d0*S+s!1hC~zLLVUV8D)FqE!r5@}ldk_eh zcOG$VE)B{2vDZrRQBKqgwV+`$K$9|g4AMzK2q32O)I4l4WfX4t*rs_gdWfyK@5ejZ2hJ=PnyX^7}E92SrsSLG7J&HY!k>XW8#Rx<5Mt_30P@YvW=mv{dx^TH`T{ z6yCv&8AORU^vJRF%XN^(2n%NJpYa?+Z9u z_=5y2LBI_#N`kcpXW9$HkAC8qyo52fpMG^DOX3Z~{&;@5F@SH@Xld_$zlR%d_o zc~9#ITna>cQYQ;KjGpiG9Sa;V0Faq#+lmExcfgi_idVfl7SHab-4bp3F7@y{WhaGh z4BetG9jx05(LQ!@ym?tu32+D^I1A>knL*@i(pqf21ADwf)EHrSQJu%vU%EB!sFu|@ zYqSz!v|>70G=GVm0Qhr(Hxc~;3(zNM&~=2Ogh>0M1vo77}4 z+fZGkabIrS>Kc#oFZLNgZvY}%^(DAsfhOSn3jiCX5RV3xb*>F{8dc14R)Od z=_M}CTWvPW2Fc@}%c-F=as@RPd=a4$U^=mp0a6**#d%}K#BfU`#) zcf;rU34dUk4TjfL`pwrU4lXXP$vg0PATsK^hGIBMiE`h~bZqe1MHPV^T857lyacfu z|DQb(=>rOHzBwDc8qd14?n?IE6rSBOTwBnx6;vf(tDJFUVpzX`T)9?H!^M~@1W4nb zguCWV*K@=M0-*)caNJQaY9G*g33z+T zpkjrFleY(3P}_LclBLp)qj4N1SFp<*;9qP$q#qJB z#WG0rjX9&DXctD-lx+IIr~PyvWJo8hJy3J*Ws;X-;P=Ue4rHq-x0Ldu(w7Pgg9mH* z!OK>BO3{aC0}dl$bmHt+wgi5p87))m97^Y2w`V>a4l3;baP`>%f1O!3D zPJ=(oQG~OE9_(7ptfqA{5N84{bz1PvBK&ErB0kZzrq6JRME7-W%jkLEwcDG}Q+G^q zlfn+8rFYF&aSXZxtlq^Hs8s-N;RPV>^(g!ht;8j$naYt#WTm7jgytl1tOik@``^)7 zM?+Zv#eie!PI6YyKvdv4f{^huQ(dsQKvhJY|BNTulk5j-RgIpA_8oU=A<4K~g&v5C z+*aKo`B_fM_g5w*ih8Ts@(UyruHWf<T2uvEL{a($G9o zV?<>(!Gypee14FtVYOy#*P9B*P7g2;G&#N<>gwxpQXM-H0)xPnmW&!$%b@8cDl1 zPEORDj+p__H+)r-BRPpge-i~12qggUoPh({uYRV&z@0Ec5)A+2LPo$%>R#~*Z13a} zxtTKK+O@I-U=$R4M4E?-g&N~Q{1LmP%m_e~GJv^T&6VTE)bWR7xS5m-Bw-js>ui2B z*chP*au=R-0atdsEPxt6O60t#cO$oB8CP04IU&df@EjNP z=6|D(m@AWktSknJeC!a3rNXFe96=8s037GLdpW)Z?aIVF&|=j7>g7xx`OKBEsx8NN z*M7d~`BlU7%!@BH-i5FhEaUp}>|Jnp)>G;j)S0i0^}`Jxrvo>#HY;@{k_!Q6@WSb2 zKbb3`iz?bvR|nf`d4Q;_K!zxl*2GC>Mzal~%+bwqg3K3yJ}<7nz75+{;d1hS5clTc zP{!@w@JK>p>?$!?N`+KNA(Iv=NxLYfk|arzY-27<_7D}7GD@h>WG6Cq?J6XsS?t+n z#JHH5tM_z2&;7i=`*+{(dmQia9Pjb`5gnLo`7Y=8JU{2>{G3)R!C$V3p6kt`Fkr3@ zL3)BAfiQ0}ikhRQ^>^-dI&zS!c-5LkkQ}m6d)B6GY~}Y;#r4hWfTZ!@Jj8!N=EKlg z1iJ3v1HWf-yTRe^_K^gM)Jeh!Vt7?(t56NXRAwG4-7&hat;Mrj}d;s*59TO{bK z)peUKO5XLodZmB&DfHy?3wVvz*8Q!Xo=^RCZt0ozU%&OvOI_`0%|Xikhlzt0^xT%N zaBOkOywV-SxeK8<-TV-z`DoS2d_rw1ba$3{F5mt8fp)T1z}XA!_xD+RU#orTZTAVc ztA(`5sO@6^Jg|eo#4Vb4%ig=v-RS(~3V>RFAgSB`fF8vjH%efx-(fADT4G1o&%P-9 z{<!*iQ0TAD_=@w} z;L=}r<4ph7`n=0I6Vw=nyb&p!DlM>NPso#YXQ4>loNrV9^ItYI`koo_St&b5pXDKo z1)Jf{DuU(T>C9px=O{gfP^QwTyX+i?7Ve9TPKXTKld2-ShGl~vDPAovEWPma7S1Cs zbj|GDXQIP2bS21dfjf#d{!;%|Z7jG@bh{BLMxq^U9X%dd^^aReI5OqAFHhu^MFlOp ztm?Dq{Lz(*0*Hr)p8W6S5&z2`TKvEHf1(6(ah^aH21%A$pis+TTJA557%*AIZF^nw z*HOmt#m?_bQ%@%HO=8>v2frUd17`&4;eT;!+BsgrL}lPk*?K!5oIsOWUORFIfFDFY z&u@30fXIE_*?1-DQpy+S?mZvh2T|recXMmUNSP_r#gyf6H(SI7I(NNpZfFrh{hCej zF~v@Xjn}_B=0Euf85m^`&9^W7-#Xk2mc}9YYxX=(t{EmN#g`K-MSWj_PAzEx1wTYl z<+R`IO3!(AYN#M@^L4I9fcB*&%r!bV`9PeV(rx~H_R|14J<*lRkEv2-{Z&aA%`Ziv%r{0)~h?P81UcW<=v*}~QT(Vu@5a{~*VR+JC+-N;VHhw`_q;Gb++6Kjo`14Z_x&+xF7BnrlH5u_x`R-}0B0 zPqH7mh?*_j?VeqA^zg?WA$Hm!TQl&V4N#3#K^C6}&reCy!nwq<8mb2H^_;i>)|D%XnVkDwoUsB_q}zm05+<71J717GQgQ-T=>HaP(RR9O-lVd*4fjoG@V5`f_!FBXLcdHH@GVV zPT=v1pvRO3L`u7$>UGg=OhJ5>c{kGwox0__Fp&D0p5}!*P_+Nz9*2V|tQkho7Z^+v za~eE{jf@C{w}pr$zd?*Zd%+g0Q6c)_LORBOQT|d9Mdb%#a2Q`@cOVoCC~9--;O=yNS@t zqaQzUX141!^xYPwdA*~tQs@ViGj19l0egZkJl{OTPErFGg zY{%b){5ZK2D2gV@r3+Njrf`kJ%dS~C^;Sd z)&lj7U^$}TmIV|0=0AE(L;%i6-3P9YaLIB8CjO66YbSDcP7pl05(P>fynwJ?$M&2^ zyX8M}n^*PSd}%VZ^5JrHygDDY;WFesiS9_YGw>g%sJT5a6HVf85Ntv5zMPR}iXLYhoID;IovUMB*t+r>_vF2oTzE;;b5+5^ zULTibTLn5`nTjZ_)G3mM9>TJP;ce^~cN3^P@Xa9@;)S7Z9A!ogMVyPopKmqZcHXAp zOL0*At}fl(=VjmZWnTKZ)8)Ehaqkvm6sB0FQ}~29bVG0!#?=fWlis5u{B~IGK9qKX zJRQQ6MPy1j8sFQZ?9X;mpV^VnSn}qu2csY_hH}bE`>ewC_MV$=7YDa26+WXi&{0Do z&le5lTlj17LZh0~7jdJ)o-ZU!>MoPRhPH|>ilZwZ`36Jf-%k8@LqgvCmC%9h*px}q1)ewK=^ ze!KdYR!iD)H@}p>IKM5;Ti&+(Q2{fWiFMPb_FuCT=oZs3A}OE1@jwLfe$dQS!N4AU zr_*F0<=}sns9c}5KIQvdWAt&-yR!g%l zIG+sYz0kM#_s+HJnitCMCj0QgS*a~Y3X#z?Zc9B$4*CTId)aYGH!e5w?)#X;7>sL0 z9?W}u(`)TAQCH#DQnrFlXh%R-LM0-VfE=-@&zs zV6|>h7r@thU5uC#d^onetyq<&VkuUgJ>%F2tM1{gqT;yM*$pN=P0GzA9Q7gCy$f{Bp7xYIzC3AC#xM!t6ap2Sj9 zb{HrrEq{|TxywDv{oLxk4)^+d5_J;pi0F(t@m&Ol!YIn}ZnU0V7N=LG%1X;cr^;#L zj~|@q8rYTe&3sov&E43Y$r~r9-z}T%z%p8EZ=q?efVd0Z;4q zE`HX%;_}a=R<$d-zZYZI5#|j#XqArH@WJJ;Jyfkq-jBvJw;5V<{GvJzpX9$KTj%r? zt6xv^U4m4`p1=MvSyS-ByAqrw;**Ow-T&l@j46>#zypD-dYCmZknLMSEaW(sV|r~3 zYVFmRcc>mq9+;~g|8{LdaS+b>u*{yVTYHT}1U?-TQ0$wH1)E^f*20(BWe+?8b~nc; znqNK^;;Gqq;@tI>w}LG-3!pMgoDof!BAFAw2N-JsbtYOHv{XnH$PFR2TaYuvWn?+- zKt+aN|2KhqK8Zwn;oc&a)tJ@(=uL6TH>=UcP&tbOS9U_6kctti9!y|Mo-`D`TN&k8 zk+5O(MWT7ukpU@xtLd={LQ|t}ZDC+|?`LrO-tq7x1HIfHaOT{T{Kq8I$pW@|^`(7vL)@Ec$Z)>x}IjdaSRs$$?1H zlFogc?#3%4%T+E+{y4bkz}{xvkv{%S@r)O7#v5H&`D+T7X zg&2yUjy=ev6D69`=q!)gG3`3z>R#K`417srx!&~2ju6HNc9d#RTG!sQ)-_9M7&v{k zS-RZ&CJuiXl2)R##o&egD6Y)k$?HaUeCN$5tV7jmH#VIl4F8$4XEOv^fr&!V31p%k zi9oKw)}Lwm%!%9RqCT?w6i1zk6P9Es3b zK-ZeWqgzLKPuqOEbpwc}Nzu2P&4*R3FTZ}3vi-z@X9v=)dcT}=F%tQK)TUf7gdJUL zYN6R|bamGVcL6!~`C%fPOKPXnJ~(N?xw9Zpc({n zVs{FYC2_X`M6y-1pJff**LH<5UPbO!8%B4bY>=Dg}EEcF6;r1 z#-b|vGmf`SRSr$7F0}dJe)*|?zevs!(X|T~;h2*mw8daUuh2cIb1NyD@JiWmki1hA z;Rmx2)U=nk7Oe2KF^i6R%q;Tv+;21gb6yfB*JW0U9o}>AmWb9ZN!s`2m<2W;jlM=o zQxdtV^)snN5rL)jo0nN$MunT7=bVvqJq&L0o>39nsC)=<0rKDRz79A{1qA6AU3Z1l zOO#eGUb|_-0OO5-WMfTEI1xL z?v`{t`K|x5VG=mn4UU8YyijUhdZ*5`W4=B-5vl!7;DG0y2l8_{`caUNM}WIT8FeiA-K&@^D}G+iO1T#2l35pUj94JuIJI2>n<3m54u#}3qC7gL z`9&Cw44s4$Pr2`O0foMser7(VB$nYvD_BS@L1wH(iYSiWJN3vywcDup(L$3=HT);X zT~EDJND8|uVJ^QL(IIhVROU$#yYLMp)TkAi)ud<9(Uo4K!@XXe5cCr{v>KwEkrbej z^_I4KNW-b}&Dtry&gb~9bIm-z^R3!=98N><6b`%ae30sMjnq1Vvhto&nKYi~<67~B-rmj?d~u}q(?1-v$HWrrNGNMH ztViVZ1iRU^5>=1*eNA0vCvGTz`&n__p|j$|i6v{z?p=RJc;^)hNU(bwedISuxTND3 z9g5$fDxNtZ^!biJ47{E23cQ~G0JZ|Vf0l?R*}3tJe!p|S(&d?pCV%s|b)!+SP+C9J z>T>A)v$sM5Z+Pt_?FLkjFnN~&WGvyGO1f|h8c07;wU^~-*yOnX0i_`O$L~_Z({D=p zU)xFbW*-U_p9EN@;~yg6Vwb?s2o!0c55J8o^QR^-GL1!wvQYmvrEgPj|2nzH`h}Fo z@c8=0ub%)3>8{q+Q-X(su~-^rh<&3Lj?D-Z{OS><>NV~dz6izVUpQ_u=a~~-Wqx~C z%FLDAliiKyw0s8coL=ayC99Y;`SSPFKO|VTAa2wZKl8deYLIZ#;`g-;sp*Sb-LCZb zq}+J;l@F>>M2aHzi&XTH2<>(J&u_D?P4QEnIez^5kvE~OS)mRZ7naLsZ;SpIf=~5O zYLbBiAs#mKS@M=Dv>i^RNv|8G*J+-dtZD`SY!6)%``}W>C7by5ogD-ESI&eTd~>qz zcKQLt#DkwEOhQf*!@+l_*4ZSALieTB@hn7!@u=&@o_z1kFB2{>n5nPQ{LL5N~GxTuQ6{byH5Cn5394nG13Hat9>FRver#=Oo!+mA8*m=!O zH_u7nd{_CEi}&g)P0fLMRD_&d)V#VC=QDAsdE?m%i)9sZeMni^s5#ugZG-+|BCQbS>9@r32P5Uw5XHB07qk~-U z9Sh_rCS}Q4)YNFR*NrXSuDykIwzwpHUdZ`HISxDA=KBXLfAjTF-F9SOyZLr~1HEyU!`L|M_VL!kd!ELJ+FKnyn!7+kTP{|303ebB z*aza2ClQVcO!bo%s5%3F3bko)vWZJ#pAgO=;C2qiV9UtFD(>CpIIrn#n|Y1C(o4E( z%;TO0NZu*{g`eI8JEc()=KyGZ+3}o(4(SL5HZ_tfv^mVN zxbGJbY`8;euU_GHr=RII8@0cPzlVf`7rM2DcT$)~XQtCtEL2hJgWQJn)!fu5w^pOJ zN)F#rYCqcjX68|5LOCsu$ZV(0S~k}a=H@z(sp;UOL}oE$d|EoYS#Hocs<$kO?%tR0T9;iR^4Z<{sUk>{=v-e~r$PU#PtzATe=glQeh9}-2PEWrCK>GJw2ytib zYz4gcSNPp`lDxo{+uT5cAoG0BMZzMKP+ulLT;%^k%KxRYf$Y8;Pm^mV7oE_b!S~!* zU?m#h+Eai$_UcmE{#{_tk!oH}ip=&vj(44{402ai7BAIa=R>OfmG9!6 z^}FnNS<*YDo~nGsp})8QwY^L5EV0!*~#io=us@4HHAJ)CI zND5fiy)7>biBY|E#Y9W%^r8jy$T=*X$ov4ksKTw_eJ`QC2iqKveep%qPwjoWiy3m= zq3h}7dh2zcm983o+;0Y&-K!wMMMxuYd`V-=dTF3*EqQEn0cWNW3OT0pk2JnMe}8k< zlV9&#$)%$@_mj8wYVMgaTAO@R^3?P91>${)0C=%2%DB3i^qeq-ygUD*iAq;cGmtvJFWtO-oI z|D&1F`}{RzQxu?+A^~N!R}`jR_+?S9PJ&|(t+7~F_Vx$9=;+%+lM|P&y`zEq7~MY( zNX zeoE_A#VWLx4ZJymDdBIxRqQzvm=q+A*cU{(^Er=Mc*8)0v3&j+6wiWIx--wvV6yM? z#;1+X-P6}$-;>|(l{l8NXZhz9b@V_h{GIKeBAf6}|Kk3cD4;wZsuuY|HV)v$o9zB} zjUS(7-tDo49h~#*eTa7rn{GfH^lIThA@ZF=%)9?%_NC24pf1hPY9_$5yVykrBB52P zZ0a(Sqkq9bI%DUzoVHb=7VnvcdHWje&CfB<)6E_Uhks$g_9zK$zle+fhhze6LX~%?^|CRwv!$7L{rVp#ryhT=Ly;01JGF0{IlfgoX06w7 z3%4TK1BLAn0=@t|K-;WIiHICelKQJUb)2aC3JD7yk0!K;&bf zAyD&LZ6=a<#xCsjulZ zPR!@Nwnwajj5@9b#hdrM*zLcfc~EnryTYez%TL3$gW_YyC`XanUczK_5W-iVq6roJ zNH3;mQ(;ZIkkz<;%?9Wy@^YQ9Dt)$riU*PNU^sPA^X}I3^l~{pd&{RA8}e!`*GakH zUa2+Wkk!-EUIN(<*kK{x6ad%>Smcj8(vkX7m_mWS_sda&heGa@SxR{sQD(%)BUU z0e&aQQjrx!MvmGKn*5K>eD}D`0=bD=y3{mL47IOIUvsPiyls?nPI1q22Tjthmy&w1k?C=4XtmDO0)Ga^nc*2xIp#>vlPkcXtbGFj@s3w ztK6;ss~Ban8HH<%Y#lkB^`=7Ue>YAVm5XxV2= zho_9n&%CBzvrN&6i~l8;Ki{S~tP-iUyVing(?=^@xWwa}_?dWpFS4a)MsV1-S-n21 z2dXi<(mI#Qnul#nWPkP_{9}!2-QXAqRe>l^Pr4C>z+%QTzaNFdUwH75T2avxgCG6c`M;QC=XL3i9>8C;n0HJ+V>ha zr-Di5z@oGBx5pOm=DYb@GY8T*;SK7_Rot_`HeK{H?K9cf9i0Bn;c(82lc^Yf^8*cwt(<7F_;zq@;hz8{rZ*3dxuXRr~7c>thiK~gcV=hOdFwJ7&O=KvjgU+E= z0EZ3L;`yQP*e%f3#Lc8RZepo_q9b=3FYV>0GoHRLoZhrIT#>fk5B(Fi>TM4=r={I{ z-4rLz1oLx|`idk__FxhOika-yMJ&<{OuMb*k%wg~z2q{h;@d#U(Xu~>HESPw>X4&1 zKKzq@*OZ(W7bsGt2?OIDb`qCe z?bEkd^^E4$?~{BtB(v#?g!m*lFaHKF>An%(MVP-@x^-%(CF1qLKF3j2+K*vJlh|t? zM!KWgrr4#NMn8qOeNtgpUOeSUvgt?ZY$K=u{DZ|zG%)xx9w79u8^j_B)HOIN?B)hg zltqt!s3FRqsp4+V^~kc+PU;#>*gLT2ZsLUL0w(p$cEZc~8VbevItsyKq!uF0P>5=q z47zjJ6R}k$9BWeB6kgW9>~M7}P2o^$`{j&eR;RYeOA(PfVVgv1he_>Y6g%t-iQ{Ki z!|3ejrN#-wa#1|nxG9G@c6P+NB4uIe#*dtRUsFlHg1>hsrC$M;M--2Sxf<-q>pOK*Kv zME~5#s;GTSivcg{--ckSg@+dwTqAVzc?URAjT1|TyRvUTM&IkkczXKEh7D*)w|)Oq z>9T3^OTp4@5}#$Zyy*w2klUYH6B(1@-nEu9Rj?J4Zex@@(j zS#4zEy#UU!@OAY56^I;hG{X*dx3VvP*>*z9%oyB7{2H_*xJ~yoh@~$nrbZ%5d~FSC zEY`JM)3vFjmr2D%dycCc1#JGT5^!u;jp)`IHQo16-$P4aOzpLh#{$7|Bha$wmmsre z_~)oFAMrq9NQx@G+0-Yr2E06DWaKn?{U6m;6_5JmRQP*-9^D}JYLnF!Q+u#7|D9@s z^R`$7kJ?(j1*JB1S)>u`ydu`hJPsBsj#s@Xa@TqHVJkPSE!%2o!}4@MkYV!o{!Uln zUQT^Z?NYG2<=&Cxq^K^Bq`5>k3xfR`DcC{rKh5xlZ^#;7u1&-MxjH~PvzhHl+E4%D zwVphnYn)a5++4EA%yRGgaT%tF#d%2$dqViMP!y@<0KO?XpLZT9EfVDG&d&Y|uJHd6 zj-HIeWZ=jQ`-_|B(1-05ARL2mfeMo z1#j(N=ee6)CVH2SJ^T~OB?z{Uy#U@w{V>eXUO-P*9TbPi`d@tzQaP2gC$Zb!8LkTx z3aw-ag45j1x1U}JWW=S+zSJwG8;-u3Rq0S3F8X->^5IoFdI35aHH2Gqu4rj42sYqz z0MOC~U*ImOfXcD)`Vr}c>KKgbGm&sVb7qsoIu+vYsc)!ZT zin}e#YH;0f*BHttN7`6CA1^q7k{&aL=bQ_AgBN>l`aI4@Ix~{E#qVAjdiExZSTxZ^ z=xoWvE>SGDtd_x_eU41(Bl{IW@W@M`%7-N}BRBxpv!=AC>vJdKtK6AHdH3{{oQJO$ zZl2TXxzD~&(|41pyKv~bXK0l8R;`4mlyCun^I-^7VTzhGdfKs?!>=I{XkxFzCqK3g z-$z%?YPjJ?(%t)EYXbT`lOj&NZC++Pb`92+T`p34he4R$cKr7srkqpT$KOR;&oDV; z<|pq>E#!B6qt0t)8~65#3l!3@#b6L_s;@yqIo+qeRIMu;@o~%A8+f^&zdOG1^{D*z z=k@QO_DA8Sw}{WkgXf+IJ0X(TuS@6br}NkPA#>iGX-c_$A0k+>5ds7!cw|?w-8Plr zjwVLsPS^cUh9nJ)BJ(MMLn3r`V3Of%2?4Q}DtpmcgPUn^UnjE4z)KCwx)9-~YxjB& zJN(MJ9q%+N7cEhw8Hw;Bl+e360`*}|2CXHH1#EdIavN+fUq97ee&BKx?7`{5L`^8ZUdPPmi`(CUE?6sjo)mI`;%)p+#PL;AV#J z&*0o?Ri2fwh_VdpLBvM|z8qR(ms=d!%=bos{=GcjVWxs~gMN(0oduG66<5ewSuPBr z>_i6yze${+)Nponf@i6Ps(+r8!3XFVR`T;kLZEB^GHhm$RH1|haG`yw7Y8qllmCnR zy%8am|3}T-|2LV&|G$1Gf(C)%G6(YS3FI`wU#z*7oVZ4uOgvcJR+U zvn|aJa+@8=U_Sl>7{-mlr1W8TW;kG-5b7Hz#!^KEwog!lM#}06k57J<-;;MkD>K#A zHuqd(oLEWSDLZcFef+r0)P8hYQAE&*0kr3u+Snpb-cgX&tJ8oNLtW}N99TYymucCY z`Mjq|!c1$^?iGh7mZ| z-p9bAN@YKv4~9h$>lgnIf-!L|!sNEh?mCtuOnhLEMOVFS;oXIu_ShQS3ox5uVq`fq z&f{q<%|F+kV;^ZwWaX+pVz?$_o*Jv<4;+o0%#2-jDq>~9vHdTF^*3R_nu+~#$EiFE zcha2ZBn|rs+d1A3TMYYX5s$otLkb_)Kf`T~5NNRwg$uGhwtd~d6&f@13@(lP+j4%| zl%$3HzP~Q(9**KeR)+frAhn<^Sy{cH2#x9Wic9^q6l4IiO^$CI>FRHyx&&RelkXb7 ze&JwKpw^y(iGvbnC0x2lFeMpC3BI<$31QL4q*;mRKE0FVMY>~lyYAuV+`MIPzZP9(zLkbuOXJ@K55MO@sWp5W{&z zXpTJ;wd7)w5cG*@LXkib-?_Sg9cQrg_wm4Ok&kotm%UDTr2jMB_R&w37j|7^tM0tm znsh&PK;v$vfA?>orgs0qh7z$3S`?iL16hzdHXpLp!SLkztMYQtVb*;gq(~%8~yCZ4r-O_?M10|Ju|=&<~d{ zKx%C$M*awo&M_FJ^7V!-2<2#NZ~VrRu_Fzp>=^JQCEYXLF3ihvu%WK~nQGrv?U;Af z{Jlz@z>j~K@{_>XH4*JB1(`|*Hcga#9hK^pc2rY2&XozxYIJ$#f7snp<9(yo6T`tB~ND5s9aOL)tzc3%2fYkmy5IU+~6?0nP;*0 zUXP?<|GM#(6l&0x?xsyXQ#pd2p?o;rzKQ~9ENyIn?WK7N6X?t|(n8>)|MB=nR!5O+ zR6}rZrPIN#o>MKn0vJXEi))GT)h@!HZsvocIQ8CtDq_KRaX9D&E8_XVWB?7qyeT!N zb`AIl(~^{Uwg+|DiJ{3)zB%O65z5}HRSwg>zL>`1zu+2Bd<|Uv{qSJdu*I(9&P#!Q!lHXr9)G4JGzOZ*- zxTg6N5D{d=M{VZW5A}4^sEt0mI)u0ZVMc&v18vNb4}jP~ixuRJXbk(4_+btboqE_~ z#KQ~k==jdycFw65b?tc3_1f|Hg>FlS_Rxl|RyztGBFtC>kob6R95h`3)ob-c7P9oh z*)uNBEs-F-6zr1Sl6wxT&zWT=b==){b;A{p-;Ow45bNGD0_Zyz2x4}8QFjuaqI_cb zK~#)B*~K;QgPL&8p`rBaNoT9EH>l3FuK?Lu+?{EM(+p181}$o-pHNC&5=J7si+&O+ z!CO!*YD3}=0?!leWqKvdt&c1vD(aM#Djzp}@=L#++UXYNdp%LrM6#6Q(~+YzR{%At zWULk8Sn2CRwn|Qm?KRrWH+L_3=g0OeyKeLHV#vFIYcsso_miJ%)-)U(TY7Ng@`R_i zQ3SAq1WG4kO3z;h(2}%^Si!RlJOr(qq0>+z5O5`<_(xEFBSYDU2EnBToni+2XaR?~q`lLHsDI#OctO^tY}{6|v-d z_1UAdCn=n!(LXl{-Vh^G3212dF@O)FS|JsZj9~j-W-_A$%Y0vuHPBWjppz!eBdYD3 z>N3~dl5$S&^M@xtC*KhtGr!zGiBw z-=o)K?n{c)y^Sya6LsWEERzgINoz_JpFi%1SdqLP zS{_w&uoA}{z*o5Xn_65pwy}32dS`DFHOnC0c;u7orIv{FofnHfev|kR{Pgm=r3Q0A<^ z9ema6@}(*LO{x-Z4_`b^N-;k8sYK~&KwW58<;69i3ZH{5eh!mO7Cy6(g|)m7GxsOe z6V<9$U!bUcG55{=G5k6>yF~AbgQeQf*d(ip*<(j>I3~1wzzc}tJP5)w<4_tH>e?{iTN44LkqlrId$!LZ=NU0bzo zpG->Lz3JIHOX#7wvV-SIx?8OVf4dE`nwP39T{csFIVBUU^7ye7V(ccv;>V%eac|z4 z71Yq$*Wm{H-xgHm!&w^>K~KYvJHO#Z!8_g`8`&VYiUwcx1_(?obj8V}Oj zEZX=wdK3`7{_UqBL^xW;CeSr@kShHFCwnn^@`+$Q`nZ=MGHjZ2<6L!R$=8xaB?$va z>ArNA2!8X$XM-6^v&JC%RV$!dofq{QWPTRbJnDCGk!1w%OCOk5xpr6Ele2KD-d12_F$ARIerP zI~Fm>F^KS0yWF+as_%in{?p_&Z{L2NU0`r%=5;K#!a|2^(@||m-rZq-k{y3|#F0yg z@yc#1G2^H7==U_dbl$skE=8Mp#dOJHEVK%M5izt39;*ZfMU{S$DC*z3^A#txi6|l1 z_NMLf*r-%I@nq5QJ-^sJD~cMvRyGyx`uO9I+}&us=YsM7yAGX{4Q*|RWASW!CupXX zu)G#_|32IZhf~~FyC)vkt@Ra)tUb+nN5sZ74?GsVzPDd(~na=5Wn*Io$R#o~nN zhs`gORJz|@^{&e;5Q>0KJpm%=$x0*y89kBu7k4ObPFPQ?Z~6Bh{tM9fe}cI5&wJwQ z8R*tQ>~K9_6!!5~6)fH8y|9k|hdjLv;^yu!mzKzlh9e`eZcZ*|COg zV6J!R`x6CfFg$Da%qO7F*eU>l^ZN7zL`9_8U3R13Se{h}r{aln$Qq>959!Afi>-w* zWe8tCz(BAZ=5)=L`EnSN;{=vY%Y_2uO8R6JwMz?Y=%x!(s!}m&N7zCu$Qplfw0yt6 zI6M0`kvX;h>bv$E2-LU2bz%WGFZi<$++vlxJp5=r_fIW=7ZU<`0~S89DwuWxb*qE6 z8E04{`PPRjbv}d=i#+e(aC)CVzJC!bWwz->*dA!o^6%FI!^$DiaA~rZa z^P;NqjSioB&#N3_+}d+Qcz^N6OVgq)OSXv&_o_>S0Z+!(W1pPY6>zQNkh5Ol7KB#) zbBotcO)UC_ULM*yq*ayr>8K0FqLmVvKS}7CoKZVY3s0Y87e3V!R6|^h>7P8YiXMxw zH09jwyV}8_FMi~eU3W@5{=Li8^kDaWC*Im60uL!;+$h+gR#|{$%LrglOKJa zVmbv64@hjaludfD!-}%|uw538+zkicU3jo~4B9pvt#Se>;-i~QQ|pnKcm-Qe)|fL( zC-L~M!;`@Y{X1eD6qV1Ni|2*aIvk6g^%IQE{>5Fh2I6B!Kai_ekadIw2y*}*?pQV& z&Z^KOZ>rY+a+#L(?b=|gzSm$$72hfoQCzq-mNEJ~^}TiF`=nU4S+6#)f1&~z&`d`c z))KmgBvAYS*(?P-t2&NNi|y!YOt?+^Exy0l^!me@LZc^}Z}r{+mATi3^8&cEp%UY6;m)`J-XmhacehS7QZ$9!9?g@(yussX5&B26#8U zBp`N}LWStOLKO3PAU@XD;Ku8O62yx+5*OsT=c4Jk6n)hLFTajS&xFd+58Rtk6q&lK zXdg%Ug_Lzbx_9+VO%@u*-SOvW0jKriLH8XtQYuyVS~gs_EC^`Qx*WJ9=!qqi9}8+Rp3!7OoJ6b>$Koe&c_jh6h*_n zh=ttSH5s6AJTx(DY28fZhakT#v+djHuXF_WsI?@%>=aRGQcKcDYQHij!x9sa8GyOk z!uQjjBd6_VHxk3>JdGh_&MPd$Vi~O7R5~+%zTErHuSKZ!GqRqSOde)LZyTE?j5!g< zTs*6;e^PI`=Q&{Ca*Er!0t5TeaE4gYA(%paV94gR8ZOa_K;MKms|~a;x-g=oMX2CP z`YeP#90blKXv;gu9uz3~S)m`ixreH@d}6v6Uzlnc1!~$o6&tcEoGg;Nr)itU6Fa6iz9GS03o_HRiOLrN>R& z^&Hcjgt=q*O-kzyc_*$}F-YIXg`RKX*r8k|gRia+0%FE&7T~ z1^3{Ba>ix={JC-wDIksA=c=;y6Bk|bEfjW-VGV~7G1bm#s^IE^N|{Yc zAty1c_>{2d_${Tw6k@JMJJ3up-wogNLOg#yuD z-QvOmZbbZS+oh>@r17k85jA!FX)@Z2Z|<@U55a?k^yZ6RYVTn9pP?4UO_afmvPi^04)wqDn^0IPE?ZZvA$-A{Q?j%U8?34TcG-E*p5=T-s zSLGmE~a*U&s2)9++Q2pq<;L^`W*#Q4{tr?8MoR0$MX0Y6M=a* z?<)8a+Kyec4Cl4P}Dwt&n{#-a+vhFAgX^phx(YXjt!F4xxc2g0>tjDl_rv z9C|QTB5c?Yd300ZuF+ai)Aj6)DTjXAKk4{m1_r?vd2dNshjg0X250Q}G2zC8BBamY zCBdrKG2<9wjX{8&>N;Wxxw9W(fBZE1@MtIRA*#v?3K-~S1qo)oQ<~=-=MIW@5;^DX z1y8&hh`dA7M4?7&E+-X}`T(iQSm9&(=#>g=FR7BjIe)h*h057SkZacSS`o)39RB&T z@&uAGoRdU~fIbhx#dCw0loWr*JGDn`No8^4dt76p%?-$)6)(oJo83O129-bZ214ry zWG(nwRxPtOI-`tvxqEO7zYXQiz2YRN!qUeNhgz{2BAPe=Gr4w)vEv9c;kAB$D%2zK zt|WWdJaZvM&nY{wT@R%VZSMnB#!#4WZsP2&ZFFH`pgk5-No%n~H+f)(rJyI!yFTh1 zsPlZ8K+Sh_*#N)Hv-nE0cA-haRNlI^=ZO`SV^ z4VoDf_nXUV&ao(&1V3_z7JoS~#>AT$=uwEf8#>zNRbRuJDIe&HWbaJW3--tgvS_Zy zua$424z%XwPt4c^c-%`%$s3*oc%W<>cxSyZ9@!iywk!E!L_fWjXQoC-2 zDAH-DoLGc{qc#&J&|$|LYbKBEZ!;iQMl0|6zURaGEkAGOZHvyp-y*W*2tPWo5DN?N z9iMn%s}s>1);u_7Gw@Kc`3#n942@27BXs4mS|D{0M3pCR;zq{wdM^4rJvBUWtwQkQ zN%>Lh3o)a$=XNGqDY0i5oRjoU-Tl=Mx{ySMj7xe?*H+oz=DBNY)yzPo0IvMsUz5O< zNF4Q;Z}mbzScgnN^O}_5yg`^v7GdH;Jh(QF-1BkS0y9sG?qeibTZ?YxlJZGGO!!~i zb-T^ma;mu_&d?$flfv^21diMRK)6l5(s$}Exvb(N{S9=GX-fl9B6)vOc z3A3SgzvTwK;BIxiNuwRX->;?sjmWk&E;*T~GnOqIdGO(iu|HZZ*<1&t2=rgAnaEfa zyYl}c@6E%Z?En5@Ldu#bSuzz;mL?@C%TyAQwA*4Tl`SNRGR;|p>>(5}B}!Q)dm&?A zlk8i}49T9E(l{|Q*YEARx9|PEuKT#}<2ml*c%I+!{8QI8oipcoem?Kddw;)PGs1MF zW_C3?VAY{vK=pP^A6&>cT>0B@`+4!lyHm%yKoW=$6je^!*mb{v;@DA~IzIYj;{G-Sz} z__>^iIaY1AYpSNdzG}6%3gwIX$S*85%VT|Sqt>c@F(!#^xLY5tT5rfuzHaw-zs9-# zT)YD5MY!Tx(7{yg@t_3zfVh{vg{fpS7Nq{NL#eY&!L47nRr&CR!no=xjR7G()u!fW zkJemVDGsR!+BnRQ(xhuW zKu(YS%9aHhH}?f@?pPsn^lmPg$}wNXrK!aG|IS7e9LSd&!7v|HTq1I7%lCJ?%_bdUa?Hb? z2@-DvVZdSTXN0wRg0#5V^(PE3M!_wWxvdn&NkDIs4hM97K{GVYb=d9Jy!rd0Sj%>e z?3onptkbGk(%C96Sqprhu6^9FkHZyQR>IHWX zPHUN2yV*NA2-WGhrmKIDU;BLNgy8tt|DbiHd^h}d5>nX#)&M_)Eb$VoPzSo5%5a*& z7G`nqSo_?3rO=aFf#5k7YUy@ZBd~>@@*Kg~48h7@HsS0QfTZC4C zVR-q}&i0=k>HbK^`YY_}29_l?#_zfKTb3pAtykXq1~)5utq|Ujwc?_W=-qU~S6!PCe1# z2s5LuY?XIiT1ijUf6Tl(6mwAh+S#_pG=IQNelGq7oF@--2Qp*6q(nHF+oOdGx7X^) zcDwpZrLD~LtwrWULX*i*jN$H`a`)=yR3{ClwpWrT=eet$!POUM0IVn7JK+1N$wlrYUc~N-mU@4mL-T26)L-cB%7(oc~JAs%pmhrO201^uRPH29OY~GOV zgn=eAyS6(*q@gL#P_(dYt%ZWG>d%+2jD1(l9KevZpt+cM3Pfmx^z&h+#S%t~%#pZ_ zcjs2gx`$=K=R3+pY|u!mSqXzvUo|7TXPdW@srt8~{l^rXo?c!M@$-7G(;Pk)iiUB; z?iCbYwiNiHSq8KJ^xB2#Vm?UWUS)hO}W>OdWN2{ZslzK})CJO!Lbna&}Mh zbhV1U{Fpwo>ye=>&rf6kGz#ST_><8NrvK0CN~9o##0aiQh)r&DN|NKO9r{ zrS8LLejiiW$QAeR>CF$nX0J(N3348nS*O=B4O!pU_754YYwMVkQ*%w4xDdx5Z6ZsZ zA=;FzX_}P~$y(L0sV9vs1H5Gw+u*vzc(JlPmWX{VrV4c`3@m|C_a` zw`g(nsCOS@J?3!KQcxjMom}N`ILF#Lr#bGpk*dt8ZUOCnrT*k1zX*=MX3M^S7^7mj(qq4WjGKs6TO22U!*fMX zz-H5yT}1LmFTj73j^jYj=HCy5@v*=&iM@nIKnA)TJovPj9tLti0P*_gV0;R7B>!;u zvvXF^pTq>{khO2#W`@2N7zEt>kajTrp_lc-)S*aw}x9 z+~{;3qO;}PK`m|cNd@v;c!BYxey-2d;wE^_jR-Wvv|(85zkq{aKEp%&@po~q z_aYe|2LN*aiPP$f;Lk!ll%^_0D5F?vKA98A!Ypnir2q9Z9^@$Izd>dr$5Z~ByxM_{ zDs>ip%TDb&g%r{nA_i5dH%)sgTT3u}(Ld?m&{+IQ^Y-|X&NcG^&*ZQa|Mwo~E&MW@ z*pVd$glntpurSbO2^%T^4y%9J@?QCykEe)t8f>@qEgGiQbqv~0j2U)}l&Z3(Bymp^ ztXSWUzOVBN=m=-SR!KbKHc$b>1w60^GY~{UXY&NMlH3tNr&cWur0WADjv%LQzpe}D`N<6M}BYzrf=r*1tH z70rr0<>qA(+Ht#7dZng9<7JJg{PO7$ne&b+n6v+0EfP#5_K{ZZ!S?TFnW9f=8)b*< zTF)^_LEfV4oBX=36otBm`Gm+Gdi!b3Zjrcin;dxnRG5Tr1tSr_EM=*1J`$zb0A5jp z4ZQOzn0EJ~w_LNGwjZk`ncuzCVXf^J_h#|33J2U#4m0(hfix@;8|u7e;Oh%qN|Em;Y@yErz6ESL!yeEw`%68j|iru#&U)_O=i4ZqFGE= zGpH4d>9yJ2=`^bFMB>J;tn_e6b6006v9@^LqV1NJPXnDR1FIVLIvzi6w zA;2GZmD+!L*gLtCw9>sy*^8E+9p?BxxN0#PgyrLv6P}ODj(paUl8h6%RBHv-2P3q% z7#_q4gz$JF!;wx7CulG;hb?QTl68+WhC=9a4Zq)9cw%3OJ$xl>@E zj66xMr3MfsQ4VANB!d*Gr;`f2-~01c&1$vSwCtF1=h-J0T`9xALj1&mP5!)OS~pOgoO$GmWcp0Yl;pO2~#?uQK9iy?m~1SW_jl)zQgt#X*U&g( z`MGtZ)dY!Qv->{7SV7<2#%+5{0~Y*kGhMe`j0-^4?1*S37EW}YgrPonIK#_6M?w_h z0)=;es6}~!(v$F|)|icGXfq~CG{O@Swn&A3(@R<-S!lLRrHGDCgXAq!7Yfw&oNQ$L zD{&V>SA#8w&G2E%=7Yuhjm9yOSauKd z@lT#VyY@;RU)h;2)b9qthscwUvzSXss5jlso24$Y7{B+)t zCE4WPXMb+tV&OU5?zKKCEB|aX2*wh-DRb^P85|?76yj*LrAx~#KqOSlkF^r*TiVJU zpi2BEhfstFw`ux{CmFkY`-fahv{)y;9`~5RG@Xk+piwCE4mwr(DbJy0 zg@aot7|JCKsx3H7X0JnN%H(>`Oq7j#HVW2Y)@D-*Zw8ikDE0gnZuV&m`aWsBV@q!y z_EYq$=_BJeUVp>9Au+rx*pf@NfWQxc3RhpeLKW)VZ0j)Mg-`VCUQfK+?)>{qkPJO# zXpekBkX*3$iCr^mGe!dm5D@Z%j~tL&zJdD*mn$6z8pl+ zZ>MV*{X?mwxI-l#v%hY*mipby_5Q0w^@IPaLvl6nEp!3_OgnnXCs5zf@ zgCMW+jtVzPV+zn|o5>5N%eyz7Vh=qO-hsEJ|13IhFG8aMy5b`kZS#1D(^^5J!39kk z1Ux(;B&`6lN^6npXs`q9vK7;q6PN?`*Q;j^MB#sOAux(V2}xl6A3SkK=}=5Ig7eC$ z?fC^6Q2uN1dU-^6QPxQ)NbLxvydb07irH^1#W^upPhum-b;Jx=BWiP=gS-9%Z3n@)jOeXXWC--;UGxQE4|=2xY# z3D)(Fw=ekGd%!aiK;M9y^3#H|&-#Sm56c=L1t(8uGh*vyNkMEQ<`n%^QjSwcVd3wW zt`ZHbJn~RP=;f8CE6_bdEd}QyF-2&IyGxJF{_m? z&5kZ~|1^=xRS}s9r(L+P+F&*4m^6G|R3#=XMUEL*Mv^QXAd9%{oV?Y&zo?Wy{&cf& zh~lqPx=wwMcllfT3T{}YY+k(k52gKO{s6)MdN_sxK0b{ewQzKHd9Jp}?q7iObN)=w z@NOJ^wm&efXkNltziiwgW}nn9le7zO1pQah0`M&)_PR{2=oa(^Eh^k*EF5<=*`T#9 zg}*x|)_^h8vIu;MVq^)CtZ~{$ygD0sdQlR1ZcW2D53Lj*;t9S_TG75G{Q;dDys%W4LO%vv!4W@J*;Rb`^lEWat8Py zZWxSf^aKmxDYJD|f3{Han3YHn(mxjaDFk(dIjTFr@`y!sngHs@{8c(rcv#_O8X7wy z9-@A((I`ebpHY~(vHhS(M1XqUnv~0>XLyn%Rjt!F2jIQL4PZH&X1KhNA-RO-9KlY_ zi&6gW!~f5qw(p~a;8vDlm`N7J1-J-)AVKFV?~b|eb;K7D4UNyc!_$dEnaN~Tg{61 z(OlV?-R0jXfAOBG$zDBwBR?OuL?#P*Rz`5Bvc>ctJejT-A+FqHKaAN&X!~V0w~F*x zczP)w64q^Ki@&PhsFXNDp-oX24jI>wmV}&0i(bV!el!GFE-K+r9mS!Wil<9QsIpGP zO+7bT@YQ#YM@Bnu*{yWEJ7UwVq2{05S^3MO8GIek8is#2U%gQWuvM6ovsIK;1U}bc zVT_>tpp8X3YSXUUAmaQnE#l?F{c&fnHa)v13U%4a?0${!@V@-|sLsaG?Ao-1wXQmv zS#6IUL(MP!j;_E}H5u}KfkV;r8DYvI(+g0iogen#EP>7+d5qLJgPe|WB&i{k`5!%i z`Uy}kfkaru%8L|QHx<-trICS(3rVsZ;~R+!gz5f0;mw(feRp3P_vGNl$}-aJWs=Zu z=9P@q=A+5)5i|nFB0v$(kEz4u^g|T~#!jIJ|33{YZ{w>*F5}T%w|<$U0UjBI>u7E| z-uKq$3o~iHNBTWD2oq(VKv>XKbARMQ=B~ zbnmp*ph4HIT2~7tXJ=#U zA{6Ge#x(6g@TyN`1=o&h8f|4Cqn_yB?N3rU?hwo}RWjU$i!7d?dzX{&xAL~Hj5A2JdF9Jui(4&^_* z_E?kW(dy5;&quM>MsdYfak6kut>|{~N@N9EI{YB!{)ZuT~~_o zO3k9(#QWW(2%pkK+Xd{VdsTn}`9D$+J(De-8cRC9q7)}(G>fo36^c4_c5++^`YL>Y)b!4yg>lL~S@ zNoP{ru77^lEOCFN>WPC_si*v!mAhLv;9@}1`Rivuvl`g~d>|Xf8`j@5@PQvYgB#t8 z5kjWw!Efp?8b$2Zq06V$5&r3-0T!v$rqEsxh0)4kGKQeja}y^zFuAkUG410->Eo}x zt=9qx4HA2u&pdlaQ+OT9DSIv^{&z_a{7_GwxIhb2k&X@3)Ai80H80DG_IYije(!O} ztH2Qv&(FNqo>~41fWq4`?ibA5*=5dIYKs{_i@{`mZc3slh<#%7{YR-xeDkJK7S zGWXO+k_(oSj(mxzH1jTs^uF-j>C3mLK|93_4`5!NT>#rJ7>+b;1_yZB4}ho42Z@K)3e5@qUYcH-`wbF=St)x}=7_C zuyGZ~>?QyzS~=Lw)xy6Q1(F$HbX7&>@I1qGpsCWGk3y z*2BF*Usv5>yRLtcPOblLJE&UHP#XNUL~+GV!)=QELPLz%;4Fe7eQBeLS$=WHT+5Cj zXo9d>W4x|FGvjcC)b+P-d3bKFxQ7#lZTlxjAG)PLr!%Y}8rd=gzNEk-M)AFyA06ux zU*Aut@UcudX?o>Vy&o(8#-leP8#~;oN^6dIz3-`@GWn?YA(2MYvjoFkOId~n7r~*L zWUf(Ezb&`COb6<*E^$j#yckjmUOFwr2FsQpA4kJHUi$vQbB5W@J`{UA=Ct1{<0~x1 zt2+)1H0k1*Y!AlqC6T_lOX>6 zyo;r*mYJ6?b?E6AKF#@9A9>3!XHKjXueJy*mjQCAQmiP7t1iI=67*l?G@I`>$qjA# z+;`_u^pUq=t$IQX3aZvKojn{i;Kf~C$vjQR`zIa4OZiq?`1e;#>Z}|ZxMNqTIYhT2 zH_JH$d^RYAjy+y>FSin5xV#1+^u1i*z~XN54JnsR7OW&<+kbyFo-Sd>Sg`#3GDc%B zE%14{oxUF(TW3Ukh*UQJ8Rmrn>*6dQL8+sB9Z5KgD@^J9;fa!j>&C&(4{2W2BNx(0L$)gPwXGs!kn-9&M^Jrja&6~{2fFqF0($keuc^I zvrQXfg^N_i^gXA}i?gN8xT1}mR8VuvAwFJ)a0Vp~@#2MD<89nNl36JQtRCI$=@&uf z4Vy0*+`M+<#?HH$^KXHk7$6hc;Z`1mBg;4B)(|(L2y-t=nCedm`%wt=09czJ;`xoP z&TB_Qx60kb*6qJAmdJKw&a!1im(Kgf*6;6r=?>)NdJ%`Xeoy9oBM;mv3$MnFbAu>v zRJZZbp`Q+hrZ`MKpq*Ufg6nHF;#NUL`C&OPV?L<0A8VtJn>mNS`0EdzyYG@o;{boN zZ{&UoZYw|(!m7{D7%lB04pIcUTYTe|k(I0TX^8Yh;`elxInmT{N&n-g8;zr{AL(d! z?Uj+yhgPp>Ct%H>p!)*2t0kCTT%k(HwX+bRsK9s&emj>A7h~&An@^WUHTdoAd#OH) z39ZLGd-QGtJ_48#eid{S{(Q&DBzTVCLPcr$FVTQ1x77X!%vrw=WxsB_?fm*miT73w zdn{+~SX7_Ozt1TAqu~G7^9mkI#>93mA19h9;gX_<#tlbcs}$C@RdF&;l;2phTV8cb z239HD_l(h1hcB{hh;9A?asUsiFhQrv;khk1es7IEIZ5;%q+vDmckf7Jg!gKV;U)eU zai@09nH1hfky+dL%9cC+1=EQwT#3#d*#s3DK1^Y!>us5}6VuakQ@W4DMS@KGPl)4F zlnqjIxfrB!8sYW!BV%iptM}?oC-X0uT~Ob%?&M_U>j(Ge_&Kf#ASKSku4R@@QDQ4s zyy!h+w%SgxZv7%b?X5};PN?yXi?i>V+n;-4E7e6m%&)ohXd6FIhQY~6Od)0ll9>Df zon`9?Da!3!{;6!Kd1Nei*Yi_eAMQZ)!f|>ZXgJa3u66-g z6t5Bnc*EtbHT`#!()I`DM$F6>ys=uV_}>43!mjJRdsPRlGIz?5L23FwMk*_D`NeEW z;hHHrNqS1QI84v8Kx;^jktJb2G(pQbGpH3)FC`;jas=6#xpLK+@07JT+7LbhL;xz8 zyh{#*%c!ekrWFCh5U;lLIa^rRCD+0k{u)wX<{G|MmX>uR=ivC(F+ox@_911>@76G) zL3i2dVY}lnf+7Bp3?mq7O9_K}M*n35BVQ92!Gjoz!bVgO^tkQO#ua$kyWzV0k5T`D zPglmAw~tDyS{F9gwSZSungcJpudUz=#T%@!tM|kx<+4Lu=!W z=2;`pEw&bWo|WENz1I7zXs1$pWVjRGoX#+gokOKzmewmnukj@=<@yxk*Iz#S-?b;H z|1nDRkH_?X`rmxN0H6kZ`o~HH@Mhn=3W21O?j1I?KKWNepr3^SS}(8VaujtB5nR82 zs^;TK7$}}BoDEo}`^s5n_4)o>yz0)sVzc4$AjyD%Od~^>TQQGc^eiD4We(&2@>#}z z#q2cz%rG!oXU3T43NveAHLQ`lv4TdQe zf2%_Or+f3?Uq^XDMK=S-b}iFk*oQ4&_|0`lm$~)zMW(O~(>$f{qGyJg@-xQ4D;a~f zHShAJ4hNZR`B|~S$S(7q33;OFo{$=lw~L!|(#vi$sKb~F(rVNLz*vKC?#uGt=;Eu@ zJmChRaqK|aDHDf_?`xzUw+`;8x#9YImb==5se2xUL@IwfV0MuuT_h)mHuVsM(*`GX zI*KO9Dy~-ZP2Yas!tGZ07JEPeLK*~%D#Lq4mn@XTeD5}zj~uzL);u& zxASm+__fjKaIc0Ki9e@a3Sc^iMrQJDAPRztDs;38#DFhisq3J6(!#Oc_4-eP7J5L6+4Im0a>&6cQu+ zot!cXErJC_+4X51Y&TlzMveRLnSw!jh8x-1eAjvG!fxZQsas)Z6PnyAkDJ!=Ao!b> zqqA(e`=D~VOW*{ivbDSP1em+VETTs6{Of>2E*Eg)1i0g0E-J4=kc_@0< zp089TU4`NI@@=jpAbov?*;r;v&z!hPSp$uBiM6bx+Y&YL39B8qN1oAtYAYgsNr1<% za2>iD;(2RsJ5djfWvYx&0@LWyDt`ZVMoiB^aon6=QYbjM|MBbJ|9(n z*0ga2g$NpKS@L#REDIjJhb{lAC=nCMHcfYi`2IIpxNkiET*-r68{2CAc#`+^h_&yG zt<&B=Hra5oGw|9y0p$1@o|6anu4CUJT!pu+MB7K80VspmcFtfYQ{Z#h3zU(pz0G5z zLu~a4`wiU{TawF<6JdZMJ=K5o~#G-{f7bA_a6N^tj7%8bTlLOB$Ha>v8ErzSKTo?oNyKR%5FUHQ9XmeBO$^lh=8*c)zycrNGn~QFARg(zDBP4j4zcZO#%4B6j~;?kAYO z#MUO^RQ}r(^=@YUf)G6S>wXaRYTU7dVSuzRn(Y{Y`EA1b3K!xY$zu@1SRL# zx~M{tL}mxc(0@z*0wJh0TPmpv$2cqAS2Z&1=s$PY=WyGMcV>jd^RDCR5lQ(w0s(1I-{_NT5pf@t*^5-_NqyENKybB6m;1MimEVmWL&w-Y& z#6EfH07_h{E61R*O04x<*}}F9UB}-(x^2E&&r)0-P=XHK_$+39%ikEY4Ibg2DHX~W z;nxC@N?q;$mDd#82PY z=TKN>{xCH9jh!7F0BBxunH4DPjMyA?D5bjjVeGRlgZR%&ujX*rOf2~5x3yawGZ(by3(<>K7)#F7ej#Pn0 zg0St5Qcu^{a`*N>mNY5Nok`?DBYU_)cY!^*1AxlN{b6*$={B03E8P#p)9YSjx1>() zm(n)Ru#MU(ShBlXYuK5udBtuEmBfJrxqC{;-rpP#q!K*WOZa=3d`NYdvK}#|D=|E5 zea0Xqgw1ygZ^anR(%_`K^ISQ3{V8_+k?V5qM?4d`CQkou)X47;+PxcDIEJ-F-%N6x zC3o$U9;K03spsM~kJLsc7pDME=8`v{%6d%y+Td17u;c%rxb$!~s@{DY-*2cW|NqR@ zvVRIf_7VkfBS0Hi)w8r`!rp*^f57%k??bU>rN#L@b76On4y_I>s@#&+&_phL>cjg? zbK`2D0y!1Rh2lmZlJCQjo2?XQZ@x+4Y8tb3u`CE}U*28zARg?1&N|g_td}X z)q#|jSTiSyGEOC~Lg>QjkgE)Z@ru9ra+#P4oVXs2@v>^YfdZo_82bJXbeu^~d75r* z?C9u}9ws4wGVrj#(?}^XQ~jw+|IeyKYTq#E_IkEddk^apCz0*u1yG%sm1VZfgz7xy zkHvw7)D2cPTJFkcNiBgn7jOB-`rWo|>&+3=!!(l65KGoP6c=tUX(F^HEZ6Rf;GC%u zQJkOy$G-(m{%P(mU%Nf6g4`C$YQovnM#ZYcps3dtcU?XQi=>(q-a6IftGI8O2$Vh! z$p}l2MJ*C&G`hauA3V)AJe;ajia7Fj|AhOy5C6QL*FY7iyp5x!lU5Yk+G6C`BB(TN zV5+xl$?vYGoJG9vPs=;%{Z;Yj{dcY0rD?TakS(9Qblc9g=wu6Hgmp1dM#U&vtXSZk zw>qzatE-Vi16P}VCk682hFX?MY(dUjHs8`g8{2-=qu!pEDgE%pyU1UsI<&+k`d#v@ z)=C)=5*%_byOlQZ#OS-W|F<41--0%*6wK^3bHRVejRFs8(Wz@{u@NxIX_OiA@NBOz zSIG1(Goey@zuu54BZrc$pPWrO>)L89*tu|hQ9Iy zLd!uU!OUh8H5n-%m^$VR_vG8OsqNF(EUQ_&`|FrZlhc>iwrp2X-FZ;{)*cQ3!$_s= zLMj!(IBq!`%hlkCJnFdJKpH=X({{N@#|E# zl=UpUW@lkB_PPEN=ZXw)A`rS6w?aV?&Clpxu&J*Tbqd=j zL-d&bsMpAE)vD;-Y>zp_@0g-C_lpHFUaUF#0(5qKCbT);_#*i0F1UX-5agXDfZ4iC zfg|4WDi+_75TPfN#y-LzzM*scj^}sH>ECF#6+Kipxmig%{^twRE#7*&@^bkVp7$)f zSby^iofbdNkpV{vY ze2W?umK9mtMjnsl3Qb*~$1j^QA?pnVF$B%-jZdIyN_*{Es7+9~B2bQr4MBgw+kXc= zn!c-N4rX&b*fMZ(RV0~X+}f7ifAAc=LLP6rhl}+v(p_`ZXMnw>HJgGa;@6m$s?6g9XTG{5OXZ@B3keI&mN zZy)V=t$FgCbsIx>^Ym_fEr(LA?> zK$T}%uh}vS!*<>U(`f$5u2GaC_U%)&p)PJF+ExuWx&3>-ZR zp+#d>dQbc?Xv=i6*~=(O|4?j_Kk>-0z+9>Y)xt`S1Y<}zN8GE4&Oe;cfWy$yKQPNmMgj!vKqYv z9Aq^NKwH0>$Q;7`Gkok_&^!EapaL!%sDrF&;XDBNnth(>6IH%(s$@s->&f-xD=!O2 z?2gW_ZxxFEUKPrNjs5I9aR5`ajt%({fU*7=6SV>wbOPN#tctxkdX^Q?Eki|hNOb7I zjvDzK%jBz9&}6dizj0dBx}$WiU%e>Iy)7-TNq*s7sr%Mb;(Mzi_kR&&a`2sFY?=IJ z{niCo&6A`>Gl%nd_Ccd1sPeQOLqW~n-;V&2Y0tPZTau5vI+HGrDqBtudNP_T_xC*f zJ)hy|rikqIrwjSWYZG?rKhm?l`kq^Lsg1~^k+(NFr z1L&HxEQDd$8jNFDW;<5)lsK4wF1X5fpUBE5eDXA znceUYjgZP$o923>Br&d0}Uoj%`Zm7TG)-q_$wi?2+*+=I=>&puJ0{5`hL zTrgW25YITS5JdQK;-4zgeWxLAi5nwuoC0 zPbQDAM}>vJ1cu?J!d|nx#$M@t51nZlMh3O|z+Y2y%ja2q=O%w)S1ZYV+RVq{x%|7+ zPMZdP?qc_V@I#PN$wP2}TehONhgu=z|j&Ciz_L8F^jF0Tvf(wATC#LN)BS{jmQ#QsS25P>OZ3We$ z&&apM60ZKb-7)+A5uaAiTJ>XN?ox+Wj(x3J&OHi1AveH~4V57oZ?YWmlUnLj%7&gF zmp^)}v>&Q{H8`I4L8Q&5dApTT@mH(2rFCr?XF1<>P6*P^uAA4RFx)I>K8l2AGo-DW zV#Ef0OfRAm-T}X*NK8?m8L)karNPow4#j~TJ;TdrSqG!yhIUIHNSi=6h2fKq{5*^K z`z!B)FS2sPS9Yl$jj!($V-_a$d|2IJhEjQ|lfBv&e^M45$ z$RPbc<+>>D4eHcAum9B~1_(@}cY`EMx#a{$Up@h8^{>)>ml=PG<4B1&t z^~=_jZ(~c(9oC={ zcMZG7^|YP!AVKTP%r~4yazapXwe*)3^%$bN6W?NPDkYYRhGnuKY4swwf`pn?a$(fk z4qxQR5ix*HmnwU4K+KsE`s*_Fq!Ps84$%DQY_Vc;Cpkh-kx^ft=sND!(=jx;KjM3oe1dfThh~!*_Av{k`79jj**YBnlPXgTa9;SM zzX-Na7*0{_7nuja{eEo)*0>q}IMe*oBCrJbL7ka;fwtP{q8?D+>3uBaaWzByJ71nj2kKsv|1d^-*puXkR{OK z&jlZg%^oTbq`Q17jjlW$bmE9HKVLuPO)GkZ9E6)YP7nk!7q;N);F}ZJYlOMy@C*x1 zI1vjm#}P8V+nfi{#xw5VtMOt49nN#&%4#}Qe7r=&(q5r6<#I>Xr9$f`=WBQ`%7#Zz zy0R#L2?S9vu>X^Y@iFh*Z)6)hJyOqc_>+WQAU~E)daz+K8r7bxrIa z)E2Tq;Ljpg_03pa@V=#kgi}o8q)c1Fp5hW_P`c0FuRDIbzIMtkCe1!oPNZRMJ*w{E zUPbkJ(N;z+sX`rF0Cjzy!EI#h2zE}jEg#I@>8~8#RK4`MqEunJrVHtx=bGyb2XjJg z$lT~=`w)AdzeI*kd<*695E{s+YB?ymJbVTSM29JPay=!Ug6?*xO~eOKXc^pHC0)NY zaAt)_kWIMRp3$m%^`|f_NcU{&!`T)i7NV0jaUavj zFVQ>oXM^m_@E`cT`ETgVzmR*PeO=!M-6yO~7>KFlKfXn(mwlZ(?9+6N2)Vy-74;C~ zfzrli{i%Tpp>X7uS(JLznLV5haLom+U&}7|Lr$v3nF5j{>YQ!-$bezH`iLhAOmP^f z(y<6kOZGY(SJ;;#t!M3_&mz(FZ;T9EhRph7He)}{?0LL7O2}sVrK(Tl(6Q^UF`f0b ztwD(%b)-NA6^460Cg~-bZ(7nuj+LPb)L=ydn3h_+?B8(fN0y!{GuxT{gK6RBDnU0V z*6yP2Rvk3iaDQBQd8TFx-&Tlh2Ah9mw!Z{W@;$&q2`tM)a~+YF&bMa$XxI%=8pY0S zdTnu~ec_F==KO0%Z`f?9)w#Tq`|Qugw9^#Fr~p#_FT(NVp_!Eyf~MDc*87~Z>H7FJ z@r95@oSVG6y>sNMpI_GV%ijkao$no7VW#R=XssF2*34_b(UlmX?ALk`DyIB*5Axr2 zU2GzM3udhhum;I$gcqpo$3-R>mhC@YIP#tOBi&79HsNUdwO7&-M!NSSUTi5YZskoh z;+y5gca7CjLrU_#5CkIv6CDPdd}FXh z+aMJjJ3srl9*(Xm#mJ(n#gCF*K0=b)scN*9}{rc!o)C6qr-r z{5XI!TVVavWNL}#2jyUjqeq0S$IM2Ca3yYy)(u=%e*L|g!&!nm3OQ;NaNgvgg5J~77WM#C*O zcaQ4|XS;MSOs_Xq-?TR3_@=fxv6>ZoghDeT)#l8&s|6VK6_nihY33CMa+H&HjcDNd zWoXdF*~gP?YiDmH`QXz|+q7SLw8-nAFvGv@d-3K4#0O)B`aMSts&#imY6HN>}!W>q0PSvUbX-vVs6u zHlYD{A@^~cE6t;e}&hEr#;v0nx8q!1!v!&FsR51WW11|3=R+ll-)?zG9%Tp z1#0-kz;MgZxKW;DkGmTrXdn5J7?Trp0QJ7M@pCbMZ&;1YJ z4rGukz^xW+w&G+zCVna=9vOkX2)tL?FntTMrVa*uY!^HlX#sKDOXp4;qtt?X;JNq^ zyo13AS3IsG9ydt*H2--hYGm}}0(>FSjl#yLz0M=)vK-4I@+&MbnTY=06N0mG>%c9+ zpazl^C6Oh$=t~yDyc+e2Su%2zxu-mR@1l{?`blJ#M(+0LH3l9X28kUkTmitor_fjxE znDjTF{_ASN{N+CZHT}Qw|CndMkP8GXio+J1KrNWw8t7@jy%T3|^jXp&)=}Q|RAB-a z=YxnlU4b{3pz?a+PF#1`ODp|^e#OAU4hkQRMYr6A6z^Y|VUV39h6TA# znF2a=U^g8^SgNO|YGx$+@WjYjZM@rhe93K{1%u0e-0zwn@BDr)KJLm@JjaPg#t(9y z;~2(i$j{GFXoM{bEYS9J@Zp_J(Ful-D6)#Sg6)5&WOTl{dJD{X#Ae`fNLb>%AFI8fYWVQV=I82BIJHp>>z zz-|dBqx!UD9kcgc8e5rr;$LR3>QHk_A2=Rse{?K0BT#Udx!uuSg5RL}6hQwCp_GC(AqLAq6Tbjm&vLxQcp!@>d5J`=4a>gdi2V5)f$AU7qUnk0AJUfDyOHVSJ5i z7ki#)CE=wePT1DJE%VeP%byxJe>{|~c!NJ($3ghR!)4kRXpO!0(TgPq-#tk%VLCqe zy|s;v&lJXsjTb-kR4yov&AQPjGnuDc+`nyKLgxPOH z3vV+OPcW{{+1{$o$n8eeTc+`8WW14-%8ZdX=(%a}acZ+fFwM#Y^+2|)7>Z0rZJ`Sa+_f1$7R0Fj&j{O@TjSmukf71nu7J@KvPETH=Z@WI&GpYp_Dj3+u`jEF z3lXO-_EFf(&Bzr{DGl(o7`6iAcvAXTm-txU#O9OT51iwQ+Gk#yl9j#M&K!#5)whm2 zV#b3Mz2#B+Im-g64#=fAQu=&Y{>{R;Gi5MgWHfx9roA<0CNWLpSw=*)q#nj~UP`D-b+peF zor?kh3+?ZR)jz1N9?|Pb0*RHtuUd9k;51a;O@MjS1DJD2B}iHUE|TI5f~Zpsk_s}jxX`2#nujTkz0uwYR#FzfJ#&HZYa^InPIxdKP zFv~Z|Jh#)m5L@hWvR?kjukzti2i^l4cznn&pjRvufF!V7u@MfXT$|WHDFmz@3>~S( z%K3_$b?I%IPqEaUcerNu>jEQYa!=^x`p?jD}!N+n>}XAv_% zy(gnOzbe2YSW?4?>zKizdVa%{RYSg(CT5-Q-SV-l@=@Q7y?g7H%Mku* zbaBplatH>+LiG-q(?27$c5!r@c-?IO80#|{m&&$4Uynp7IPdrHkC;h+Rs6R3wrJTO zJnlsnnr9n%i}FPxYkFo!iNs|o1viRn0W6W54R-sI>dK{=^I>{+cZc1im)6<>MZ?gB z=TWVZmqwapG@d-Z;pvZvfBDB|ve19eRc-qR#wqpFMD^h~pJPYYdNb#5*xw#tc4wd!aJ9c{dPYpCe~&uTuFHZ1VZF|HU`OMgjp z1Ztsg*_uqjYO<6s-mph+eS(b}r}&|AqMB=%ZOCR%bq|qKJ7ctsm5x;oElsg@ za*{h(#+(=fSvJ=EV4(+kfS_~nh5m#&>6)MKTAjyOM$i={vFod3^j$k3ts6(772w|) zKZLbNhXjFz3_*!OdRPFpv#I{hZlCzrNd?E=9Q%H{%9`U20`WTA3@(rh0(EUSkeAc0 z2#yxz1JM({&&$4za5~c|alXbv-sR=V9uF;&W)?kENwdGd=I0i@(0k3BuO42=k>?E* zAe^4bbbw|>DxySnyH-+DSOy`aj^Me|9;clCR()r9h^VHxY9Z! zIZVP>51_O47?CnXdU9VGrQ^pBZ`WG9NjCdQToPyDg!t)p%4- zIR?bZift$zSujZS2*$6Qo{n!Ubjs?UthWilbt!+_cTPRvn{{-6>Y7!Lwy1KCqqc%82Wl4*`~os}a9J159cv`RH)1bT>!tX$TTf|D-5VuWqL68Fhg}!CiHw z4D4p9qe+aMdMKPcxHVs&g89(Csnc4fz3%2%H` zP|w&l|KdHSk@x}MgnCf@wgwp+q|Wh+*CptEYy1<7J;6^NTuoe3IoGHb_I2E!&FNN<@ETSZ(ZM+2c*mZ!Z8Zl1zgONY z=0l(k>@x=4&Oj-bcQXM{Adm%(ag(6`(Pv|Gw}CV;=@AZq|1U^002Kboa50)gYn>(l z&}JSdi)T30+~u(TSW`PFY@&dj&#~vkc3f);b^nYE^lLy9&;H%C16lA0D!bk37^`yA zW6L-S-=Y#tqaA3s%TGMAw*!(X{j+>^!uWc!#_Pt2@ef}QY1|MP4z%Q2J`PNrEcO`T z_qjj|rb-!}jY4}v4Frg4KpYLD?*!L<0h>{5nwL0#-9bJGOwhSlSydg~tgVxXKk@R3 z5$BDLuQ$7na&UZtPJRPWz#t)fbDAlnLI;jt#1r=Dgc$8vBYKC|o$2V`1fG*Q;}*Ay z>}^Y~s10;J<`y_>a>m+6J-S zW26mfybX2Iw5S)PvCe?^b`=jvjz{Hd?^oIFHhb<`^@{uFS@H2hMj={1Hany7 zAc2%kC{=I#E>BwRu9yB|)_hFtslEP-_uj;vL9tp{qFz5+Z=cy~czm1n4)z89O10V~ zpFxO}Kmt&y zODg#3Xlq<$fA7Q?eLE1N84mO&R;)hC+ewL9ha=(QiQAaG5G7=x;CoL0DnWVI=~Shh zt|y|^oM+)xt zjCiBn7v8$(R9-66EnWb<3G%JdI<7q`3zWbjPhYkizPOM-CJ7nhS67SH@v%U2K0pzAg9Er&j~O-w5?obBV!DoHJb7DD6})dE zi&W?im5h$I?@?`SypgRCh7~l~`dab&{Zp@*Lo{)wv>C%M#NQ_UtHu30IsK<@>@OSA ztRg?Yt=xIjSU;LGcq^e8*gr4{2-q70U);uS%wBM}w?M+Ti~eiujXlXlBGQO%INh$T7fdMu9)0Xob_if=i*COG~2PQvW^LOS~; zM4lp+K4Xbvfu{rmWMA4S>MyS#r~uG~iz(PoUSondLVbEl>#O%yLYgQxacXZOooH%Z zd&QQ&Ei$ySuRQl%Bgd$IkylRDy>y8YS9_c-=gT+>^@hMGpxy2Q6)B51g-vNS4FqKP z;r*2)|6L)sT94`3@O!R}9?arjtv;7&m!&SE5xryfZ1Q6XIm*3baZKQMMZ`f3A3<=N z)z*d=W7@)B7=}JXK75^0NYt9`NIr};?kiOIm~lDXq>$aqt(r?fxIO1{%_wK6p_2jb zSNEtQnR^3(zGu7~GI(u-RQ z%M(cguj=@qhEm)I^#$2U0oWLW#0*MBCu*(mUg6g{NlT1;?<6s_q#LJ{){!_ZA;w6c z8j`KC_1K6BL8|_XfZ))#u+Hg{o&m36l)-GFm~gX?cCnc>FuQEs_lgngQ}5Kwa~Pk3*E9 zd5GZ`ZV98`FxBATJTE5>8vkH|PiWYQ>CuB$;-j*36Y+r75QI%4)a*-?hGwu#70{Zp z28_7dV2_dBLsVaA!H01UbTt6B9Rn(K|F@cPBl{4|d@4U@yq)489h}bNs`{XHdHco4 zo_jtG5JiMI=EII9Mnlv>fT*^LfKC&sr-`uAvltZVJ?=y5Gf+V_f$U}KpKA*Xi7K6T-F`Eqq35wi`P+OawyX?u~d4S@+Ft~I#Saj;?% z`Y6D24AOqMXniHvkX)$f)EAB-$7<$JRSgyvI7zYx6khv+M2Pa_lZ@zhP!|DyutpyR z<@CXzGe{+n$UXsZdx=y7by!!i4ODVKqbjX+JhbThdPuSlnh(Ck@SB)6PA6xlu>1M; z$()@(9DD0YWXe(o$|j$NV)Ms?M^VFoh?KedXeov3k^Vv0!xVsdgf&7VyDWSQ?TLDo z+n0F)D#Wk7R`6}F|Ansj=W>{Xa2R{XB!C(wP%o)D&@WWhJ%<@)JyE&zH<#?XZ;O0= zW_}9e{?W{;lFL)2>}+;^YbW}`f2c<%4qyaXz`rOKBQMxIowTgBiJhOY<}{m!;fi;m z949><-Lj9iU)yi%Dz%u7b8OAN|Jdl{+U&Xon>P&29PBgqPKtlvZhOdNRqPjzIuH69P%LEBBj9p9 zMKay%K!7F!*jF99ArCY|SQYhq#|jcwu4KxXQjOU>7irr8!shC`7`*`6Rx{VykG+~g z0?f0NaEUM9`i>P`pAF7KblLEo%HQKG0F2;hXRyQ|V>83lL^Bm$1A|x-Y64w2z`Xm7 z0SL9imJls{1C;gO0#gvZDcQDpQ1|EOh99jS&|J9H^!9K;NSNKj-QQF>rd{vJA2Ss> zsa`iW#7=K_4VAly%W10wYMxIigi7F!lb;BAT^DM0Oos7c_L_`zoj zII!WoFkgu!s0DtY9ZPz{y=cOa08uNdJa6X0*dty$LCTqjIZw=+pC2;jkqvjoxv5!KH#}%V6`y62NqHQH`&b;%X$Qu8bgN+vtJ-9o6 z&vguhhF6w*wzvI@`~9nV8JabY(DTV=no|9eDQaAn<$sjktFZJp22U#J++Kbi^210* z%+2}aZ>?!m1#zJY@HX%)G4y7EGmla9;WDL8J-sYylKiFSTM=5{v9LB&&b7PzLlt71 z`?dE4^&Bf}|6(yfgnMTL*k#E;B*2~o*z_c51oAPXs{^A5M07mRqr}P8=zCiH$W~~l zU(npo54}O=w~ycMU;J^aLMx5(B%$WG7{?7I-tezk>8!J_1v*gw-h}4@xtoWi+I531 zK{Zw9o>@Z*dJL3fg+m^jj2cI4+D^W(tWMDNB8KIi;l6&5epJ=O+PAP0ygT9&*vE|o zPKcE6bmSv7IQr^PtvGG#!~p)H!BFb%(Rfqb;X?O>5jUle?uO-!NeyT7Q#N~*{;hp5 z(6Lz^5&_Oc!)GD~7~?a-E)*Ht;l7+ME*VKA=t#YenP1)(d7;m7 zO`SlY_`lHW&Kn|0G*=*4%aXWw2y3{_{Bj1q7n-Jg8Yl@NMo2l4J2f# zN4-CGD1)!>H%c~yVb;4O)p>!oD^{#>IQT%5^aX{yp&dJomYz6xDchO2Y#e1Mvj^n3 zSY>RE8Kkhj%-n^!2~nENelwqYQAg$7u9ckGtJ9SvzqR1q$I0CwPkfZ{Z;XU+UjJ~o zGqrmjEOe<8tuns+5lR4dXrx9l@kp14cK#oj?aEK)QJVOj*a_)%N!BGTL{6ECM+lT=9A2_tXmS^nQRWWiCjW&jfn zkaHDh6YXd3oGgBP)qRy1OG(+8`20cv=#oAgZ~*J#nNE zM#ni824<{v+d3`Tmvr93sGTW)Kg^K%k&pS}NoWH?2dk1-d zOe}G7;uUq&T(JeWGu(_KjVtjq$E)(Y<#m||)$fZlTAqIVQdwi+ns&6RwZm`Fr}FP@ zgSzKnHy484?6-;6)gWK?N=`sl8_>Imha`!A><5U)#xl>6404_=2&c(fNtoptG$(aQ zC|9(p0Ab4sVtNrUQw;oDGP@BS9j++%iHwrQCP%-mYz22^z>o%@$ zBVAgF0L`V(=(J5Q7bt-b{__cw*hi!97K&Xc{HS`mX_z+7hwS6|wwhlv!1uD}jzm{3 z+*#J9mb?@0I0T?f8&I6gAj+fXOM0f0>RV^3C-MViRCaU+1zhFp*FCf4(vce3JcMLD z!X_GOXeKN_#9{%s>XvAbzVXfP1LyS#ZaEG=f@ilwQ9!Q^`5Pb&d;hs+_Rrt{3tE;n z0a(|A&C4GKoRLpon0DgJvDl4i0d2 zHHw#FZ&;d`+I4rt8*ue*5*d$)PkP)3nA7P)Z5CrHmX#H?{ghhTiL%bO4#Pz42fGs; zAZ_lg#?zmHp?@gur@i3FZLM|m8>qn%MS2UsIZ(22@)cHkpmaAsEZsC@E zeT0s}MYOlX%3^p)PLj4|@K$-tGod;Q7lE$+!g>vnDv+hf2*{1Nm8tk7$l>RQ=w|iT z=4z|madJa`jV{Z*ste%*i8g#+#j>niFL5HrP$OgHGgzkdPcUhynzUM!PQ2Dqv=ryW zKALP%O3m%k{4VRa`p!lwoY&hWpJ$Hv`^n%tfTQZo1Tr>)%sj)YCXiAI<-iRiVlOlj z#cH{ze?wT+ReobPSLhsjdH8I_n&o$cxZ<2<;da3e<;BZKEnVFG8>LvAxf3T4{uLwm zVjrL?xfYHVhTLHo7sL0#1zLFC7^N1D|KN;~fgKHP+nF;?9 zpsCx;YH@yVa|1K*gq1O2SnkjgV5HlvCKHFUQu!gpaAEWJz+Ry=GdAxTs$9nx2ll?| zZ=+p{TtY1#UMD(*!#I9!+xQ?m1DdP;Pw7o&1EAOm;`+I@c^2RYm4<$)uCg{G3;&tY z1>J4Klm@oWfeaQ7w8r_f_GR2dl`8)a5SShR-OuF{XgY90gvbCQp_2@*lYr*A9t7{# z?)y~=6D$%JkDeTL@l3aDSZVD$k}tK-o)Uv6RjXU@{s_-(&lY;>#o=MjN#7$RI zoNsaixQ{1)KHCfbSR|dd7xjC@AMFHQ0xG~7C+Wz%QNv1OdKGy~twja-YD`|FLSwS; zl8vh>WLO0jwLlcOt~nE-}qZ`%!o$hI>0X-|`CN40xQ_M2S|?9K|^ z$ywAf1oQiwLg?BA)SWZL+VH1lF?Ox6?;a!oeC~$`Yy9jjHs1&+<};ba(Jg~4So@0c zKP&&?EszzC>dsX62j?wi!0NQ;cg*hDw969mtX*y82n^narUUMr4lYp2?nBZq1QA%O zsf3ENOnFu%fz+cegBiqCAe#X{86788tCBSegB zWjDeE^t%CQzQ0mpP>0yN@51*%A>Jm5GJJjC*j@C{Z9$>=y_{pgO2W>+ksnkqQZA zCtB(v3$L8iNemKCG?~wKz2T<2`(cCF@)A?ITNLW4#6zSyG<*L&ROQmJ4}A)Tz(fhb z99}dP@~f$wFmhOD`@EIeoMPE?GhW{t7phtVB73GjMG%gFv~j{t29WYpW5?~hjN|!| z-Lb2;g~m_!R_OhdY(fMyF!QJJ@UdyYv^my2`i_19wje>V`pR(FTc**sB2~X1z2!U$ z*6%WwTL+I$**fwy?oko58kT+`p=yr6jP;_syBC1(wS5uOiz~s-m(rvufy9b6?CM7h zGQxxvPzYVhXQOwnvh&kEHN1 z1woLo*Fv6M+dI!?r`&rcy>4kCTsJ?oIq9dY5SeF&7{DRzX_)M0?wbY>$;@?Nzzpa~ z7KC8w{ji}nE_>F7ijQzLN}3q>Y3*P6^~TwVBN01Kv|vC+qp<*>tMlGjWAg$%0W$H7 zeL(1jfFtIo4^rxu`U*Z7BJhPgIF4aYrN3Ym2Fqn-wYx?TznE02=x|0qF*>%A(OOr9 zpBiHGeW1D*le@=CDP^Nk$+@oQWt8c7JjvsBQ`iA~nOv05Y)gs9^YbCVz$rR`v ziqunQT!J@`M!6Wi)dwYnh8kN-X#&iBDg|AQb~)cbuJ1%n@{Oj&o53nu3nU`A6>R96 zqa(7aH{l4j$*~fEW8>3gBq7p#`D)OKqx)CTM&Df44;IRhkl#P=9CWjyJs(HN*ih%t zg(#|5B~$DK!Bt?4zm6BiUkG8#F+Ho}20wpMc^>#GY|+6aKPm6v&5FfSKVQtZJXbZk zhsr(ncj>(Tm-vOsY{y?;R6>9S1MB|}0SR^xFneZD!_O${_5QH34OTCp&@26G7756f zp$oGcJ1eewspX*eYbN!Fe73p&^lekr$j^#H^|+ZVHaD<)LCEA4G;abT9X%?uK6AWx ztp;9KM@h%HGI~4i57aCRfWZ4I*dotBl+?J{f5G-xT zDi2({y>jGKfqn>O*SusyeX!+`sJ7qg0YVuQCQW5--`)o?Ix{B6FFx6&X>GkD?+`*} zifnO9ZP5*NO3AGW5U^FX z`u87;9<5x*SR_|sfYLrV?xDq+x+H(DQtEyULl5Qcy4*Eky8@JWaPXBdORlef)L}$6 z6N^DDgAG`+CX{4XQpmf;4GD8oVT;4Q?x}W)+Kl^qYH^xpQubLqYm>ky5=e{c!($Y# z1#7TZmwSS+TWn`HR>E~?T=c=>EH7G`>&FtG(7j<#q?liw_nGeC;ZaD4KOnz)8PttQ zLs#*`k0>?^Rg7~XKK1$t>S7jDh<0l2Kkpn=*+;TLYfMqhvyDZae-zUZ!Um{uw}+*6 z!%e(q3Jap%QO1lu!NVUJ8D;ifsT*NkgLG=+kigVgm-quuJ~_x*ROP@mrCJ}3d;G)q2edKP?}R@OT+6ySK}>@I_>H816_Ikqp4s3aabvI4kw z8yEuNCNQ|dHUO^Dd{^<@U?84@sgVSfl*3?`npn-Qid2PC8{M7DWqCWcnqb3Rwi5Dx zU9+RO2H6;Iv$J(QbmF9Fr;0@2*rkXGi9&MxRr!Ric>>P5qFdA;(9IAqG=GvN{s#_J zcKCUK#Zh+m>|_&4M5_}}yN21DI4-C=zj~0sjfpVfT|XDi>1(xp&%~DXzDLWa3s!yPR{?Kh(uV+Sk`)^m{|#;N-xoJx>4~e%+pr-$h&GL_Q*{Ut zF{VPXS^|=e6CkW*oMrg#?9kiE+x?P{{7Cf?-16}U|8`l`wL7LqFMWIj`r8n?R)Bpyqiy9m%ejDbO#h-pCz zX`;tGjNx86T%ixNlWCD@?{(m=sG3?`bg2K-_VSxm%gu48J8YG1F5gc|NJO&vMsa6FNwj`5`KJ8-H{ym8$0QQgea5ydrU9tN zdSE5|@-4rEW(pr+U$ACq0o;FeKt+C58lY#r{WNKg`MRNI@XKE7<+IBEQ|SY< z$Ioy&x9>q8Hs#KK$T!@WgwT%z5)McNP|Plja#J6^MG|Pik1VyAz8+@Uzf$j`tQb|) zgca&fTA0<`?HxCwXgB5RHgH9vAERkvxJ|yaGiG2nG#Ua|>c<_1G<)Y2IIMsv4<2MM zrpZZ^CWq5bp&2tmc#Sd?vxlY_TUhIJH{0;mu2;U-ibq?#Tz^TJ2#Jz^K3?2i{5_t8K%Megwqf&i z0N2DEj%Ii0zXNbI$AU2Bf8=1een3o_!@!wz1fv1I_=s5zXc5Im=dU*YS41vb3{9vN z&&Z5Nu?3oAypn#2za}QW%X?uJRWI>>w?Nz1DEMezFUad?;uLy(=2#rUr@7>GZ%MvU zlb4mQe7_iT4Hy@Il(Ppb?t>Fw#miy3bnN-3qVZSS!%z`HDmndAeL1)J+TD&|ev(ve zV}5vcd2fx}-HOWG%z`rj&`2b!TK+Z~zHsZ+J4rd!o*2~naZno&a~1M~Hul&cVe1(* z^96cX3m7utz=%IYs6?>@^RZ0j-|B4hEcTvq3224U zi8Q|&*;hl24oCq5;+-`snp5%*<5j`&_C0??+{?s&$HKdpn1YHY!EBug@xMefjsd|{ z$#5r{b-LZGR7%-4)iMWX!%sPB&ax>l4}@Mh04eM3MHpfpfkLQ%*$VUj%?6p30iXv# z7@@<1;IYJz08s=}5B!YHzks&=YfR(!7FOC{y6XRnh~Z|=lq(5r7@b;28e~E>Uf?0i z>NBpCQk_!SaZ=teCuq-^Q3smqTUh0HZ@iUsI%M37p*KWFMoJ7YINTgYa!8X)|LqHCB{qvlK|pC{}3xNKo$~dyQ1d} z0hSjLOQ0r}gAC(usM#J_EWqN$=mUv!49IEh(DF1;aTjoZdGG2Pjwu4s*I^G}f61~k zTtNsgW5~Lc`l+r^|8cLk)J@y2N+AW{2-g^0jVO6{bQ*V-y<27DC72#<=%?_pcdVzf z7s1kB2M9+I|D%UpKolH}C`>2&0ILLY#fgO^d0mx@q6cq^)PCrvHtoe>j=DUcBHO zygx|QPvUd;9hM8L67u>C0($}@>TN`^{k_>VKBsMc`vx4$&7OD)~_OmClcLhMpvIxvvh`-qjL+T>VEg)1sC&0s3M)-RdS6X04=DCDKox_s4 zi{1;E<80vkQiFF!GXmJdC;_(cSUCSc?NOb?)st_F-l@lBRXgmxFcunPp9|H*`^nxJ zn*V!ElO0=`cKHPf%{yy9QGVAaXJ+F>LFLd;rB%%9vIqrrg_5J>3)W`BA)Ad1IMC0J zWr~4(NP{lHd2HcG)3GdDfTZwtUk_8ar^@d4j5f9coy#e9*l0GUKFZD`_TC<8JTw4e70*v zcYHWB%}|UN`_vQhZfxAtD?q0AxUuRvS=sZFCO-u4o(WuL^3n>B+?nt_wlHmP$gW9C z-~H->+OH1v@2kDEBK6%*d)?jgUa`SQy`qFzM-SI#u5~*TjQ&C<*sGbChGY8p0^%8+ zX5!ZMJ6!Q^R3q#bg;2Mk;`65*jcQiPZN8X2xDc~~zBxoI1s<3f_z=!<6Zq3VfvY(^ z9q}3k1t96gEg!*;FyE{gL>~ZSx`p~Fh$^#T#fk%*zioHz{>6(3B-IeLep+CD z4&bYuiDutN1ACysA0qwobzt+*7#Aj(NZ1f?fWq&Z<-|=0Wch*cQ~hQhoXbWEyFRpV zJ}GuJKJ~S`Nw`Mev2786Z{wJ6xadK^-`@+&JcCU}MpzdV%6x%`Xe#s}nsF;O!buW} zk&}TRDtk-4edZP*dM6PJ70W+cyLl|_O-l50DZLcc*^aIGx?D3lOhFYkFT)?mlslC) z@dx2H>x`ghFprWKKxHL6@rZ!I7VFp&lPSJNH%{YR#FJtdoP0*3?~(ZqhBiGxjGg zn|*O^ZLtqDdHcXn+U4hEzF|pSMQ?U7m`ypr8iSDrD_x1{P@!=c_W=g*spLDO7BPXw zAH}&WsxR5_Vei>X3Js*hMZW6%+Gw%T&$tOS6hdX-)3{NW%Y7Kx5V<*!e_HiDYnVBA z=k7wuHLmd2)uyt1J2UTHYr3l3Vw>o*1`PfQa2vBZH1#ZUm}uF@^a}C_poz3qN6a1j zt$lO7V#C(9`G#G7WQ9?@_`$j5)W`SiE*(eQ4Pe-@`|HG6fG2NB65w9E91?{68;;$Y z6_4N~YQlS5q7IpCH&t*=IJw&|AZfb^b888h+i{GlKs?I(BdkNE)o!8pwV5X_Qhl}# z1@qEN_dMtj2b>6HIIo^=q(P>~5n*N4h^D;u|*u?#h_Tw$eR~%~i zWL~E$t!-&{tam02EiVE4aeFOhBp8wS1D`bJ#I=-r;xh8$hewS|r>DIieS3i1YBOWUxG|AsH z;fvoQpH2hde-=zJolWP+l-({8etJMNn6|$v5B)ZQ%#!ru+`2*QC2HvN*k+l0f1a0Q zVm*1A{0q6+eY>NH&clk=mu2qh58^2g2^Yvwds*3cus`(1;);b5ntVCkbVt$of!(f? zS}Oqk`3yMdnSkOlA6@L5`iS)6kpyN>i1;P;SP%KrvyRA%+xI8>9NBZ+#Y;5T#{a3N zH;?tT*)8k+3}LYPGfoF-!3+FvW(d-CvasSg>cR4xsTaL7B+Nb+{l2-FS6XeZ+2}c> zc=NSU+wLT7o!@c=vW5rv3N*Nv(Ctg}N5CwWu|Z5k8s){WVg|>OUf`mfxcgQmzE&2_ z>ZEqHa)wurwn^8Vn-_iPtXG?&T7L^Yzia|qOQSf{LxXx`3IgK^hJzuH zNcX|xJgTJSVbb2y==_;u7?lCx;{3t{uwHD)cS&>_Wbzy9Z|~= zyobP)71#{ci?gzQ*#b;^Q27yl03eoU_rYNosf=@};#g6m%N3~yemvaOwU9rUl+}RH-M3u#@%Xcvvnu&eT0>YWtHE1^dGo59Ql9JxDzC|!FT05a~1CLLCrz-E0PZ`+@hN7TD{D!#XQ zx;;*<^_1(L=P~tGyc+i)!<0>Eo^8*;F2@Jqhq3gML49GSI2HX+??NakHvtz@juUzj ztCqfk_*7nd$V>z?^9nCt)fr`ZPw6(R1V7cy<^>Vw?ZoigG~`0Vq{SoT_HgwentUT9 z9CTDGKi@&+xlv};#MfX8>E`)|lU}?f8h$$p#6B3PZrK0^1*Ztul{7D)fNhc7aPnyy zSM+rzl4jfxU>yA3cH~^2t#@jYc0-VFZJMAwSx!f-tk(6o{~pxI^6xjho1|o?a^7Dt z^mzA+dg9BM=E4fyy=PPx+dk~zQS7n#fn!Q@fjb-pE<01?DkxSqr2M!sGoed+`!XHa zm9MK4rx_Z}XG@Qd>$yGdlyBQ5W;=iBc;b{YAs;8K$MF_`W(VU#(6))DWjJB4At~!+ zd0&r+kn{tH6S0@|K(u0vVGP*diGqdtM`u4URbV@k4IJhX*fU~EITEa$`~Gx+@yjoq zzeM-de>N|<{*@PH&jRHJ5%yqz8SANmX*Xv*4us++#6MK`nzuApyW_LR32FP2A?}N+ za_$4d2S?$V%d{v^g9`;XhBjL~}3Bv!I*^Dtr-C zUigjHf_x(4yz5dTcZ18o+LH#+EsMm8>4hLNZWu+sM0?kQ7gy`57LS<645;pEI^x*z zwb*d$9nGY6sjVT7BYGU@hzSseh#ad^R&O=&7-9>Aqms!hPC75#t_Fn470VVY`W1GXgl zS)}%ze&4+HRE;1H!e&L5M1Zv>>76u-HZiIju}QRN;c}oER>;YF@SSmla0g%Gr6=hI z9DXBGWiN#)0k`$)6RP6m`TGpx@Lg0qwpJx@C_{#pn&MmF)%Rh?0w=8?Mq=yjkNi?-%Cwi;rM9P1f;sj|M7E`% z(?(BQUJ{=Btuyb#(ELRxCd|L1GRW@9fop^M96bwV4{HLIhOkmw6k2YM1=mfFC0E|o z2tb29-_U^rkdpue1^_W(c`T??K6bSb_3Os$l11NQk=3Z|wTWNyc4T3FG577*5 z(~lRGCGz*2+4lh+g~CDBg+`)-u~R zu=HbaUou0-s65y$R!-MZA<0YoxXT?*%jjw1!zls@bQ9lF8)AwQC(8)jY^4xGLn;ni z&KtT^CjEu8oAoMB;qZFWSeaEBRy1F#eYeXV8|$kNopsiYnKCQjp?TpPh8r`qpM5M` zq)(pamlKd%LNtNpC*vl&rW3@Go_k(!XfW=x(f{ z-%D7el%@;mIJ9HLu_e><)|D15c4ojWjxo)o?CXt6Nk&L7(?g&5HovBl}x#I6vX(phcL_ z@i>SgjU0Z&jyV_$He4ZyDJ11Do>k)Lgk1fHOUcpmd#H_*4LF|g1OB8XzVEXd-X+5g zK>;@kZ|yafZm;%|jk>JVx}~l2rEAjNv;R$F+J*|lX_G*O8*;{N8-^n(YgkP*$FKD4 zsnO;M@g$#-?Y!KXu}*f{5jk!(r?q7Y>tYB-wxXb^b45holr z=^{aJ>?v>+0Hw9P4x4+`A21k3LnKhFKsAJ5MI2Min6wY{1V>dXw&tG@Hy>2&S$sVd zge`G23=lTnL)QB|a_*KQt3r-{5K8t1>HP?$-~=2YR~bc2ogQiw!YWB0!)3;4mnEme1urwqW@Ao^X%6nH#+M zW879@4xcks^QXBz5|2t9>WXu`^xnhLM0Lx07VrQuCSiD&*Ty} zEN=PeQW?#9<%*A#NKAT|Pw4LPp3sX|92y%hO%(nVs`U*-ej&y&ZE{1FT8^bw6`~!z z(_4#!)K*u2c14*MO{a9Ws}%oCOM4_7s*sLgEkUq;fMEr3B(P*U0wYg)@|)cWN?Bv3 zQL{tPiUPD&L_m1H79cLciMQB=!GA+&82=4%XXdZ(m_gTrg*q~CwptpC=Q!X>57q~uFwsx$$>zX;YG2(g-|KXX-J)@lom&1_^7)O_pw z@2gJW(7G4R=S41sW{etV2`cx)v$bzuKh7K`1?hW7&SFsI}zsXciT~* zxbRQSOT_%r$D>(eL9B$Q#~Az=V+8e%2jhSg87NX9$(H!VRT{ySHANF0N&}?GDHO~= zz@Z3<+0xniyf!nH9H&}!EnklUGp5>oz;rjhZZyQam#3zk*e!o zoc+@K!sj7PqbltaPm6yv_OVsR4+4OQN&;ib@f1o0e@@bLTZu79X~uDHlA+txsw(Pm zWa^{LkG&hW((>w((j}zDbW`+CJ*{%;a*MCE*lBfgNnjdpAH|biV#U3ZGV6vB`#LT?W=kG%ntMVXcO>iLb$(wei$6-gYiyAGT$FxHHi z&@^4O0c0hP80vki#^qRSHD*yUm!Sc%2fl?etO*R8o2YYn%{T|g-r(!|lafxSU$s5= zMQlYg%xUx5nk^1=Pe6`Hbn?bfPs0TmFzRG|q8}};v84WJ)nHxYJ|Lu}0H6Dm_F8b# zTtvI(xX=Eu(F~~*Eaz~alLv%;5GILKb2y|P)n)}9!n9_pNa2JQWR3%s?_lADDe=K2 zNy=s7JqN`yO&y;lQB6B9?w_#vhFx#r{X2pmBxIY_D3-+&K|-)G{7P9}w7|%$U&B2e zOXQmLF3VL5$L1qR`tNSqs=$0-?K<3e1$oO>93<2+kKk>XNWiCvi45Ql@D&KkxmXP( zAV&OWC&#TMyY__}Oeei0JvIq09)l^D=x#(otJC<=KoT;}NDgYEETWE+z8(#Ax|Alb zX(kuLw>S2r#~n@^Y5ONr_(VW>X~z&F%m5)Pd9rOGBD&7F5KNSee{VLYUd#yUn@h3Y z#mmzaL3bu9yB&F(*|I29vKNK{u)YdH1X_yK4>)t{ynvEe`f%)+_%p5AOpz<$bd&wR zV-(Lsr21_soH0HuKYQ!S7(Qd%cLX%%*}z_{8a7fuDS-;*lVX$(Z7p$M4KAuOUa@%H z%)wDK6WynjnLqLRwQ7aC4yT>4UiJw_DhOJO04za?#pC}D@FrtCy8Z2F#Mrunh*o@b z_n!3cwl!btsGcd$mybCpJo&VoCOsRV?+{xsA#dk9P^^2kYWR*@P5I}r`LXM-XCqH5 z+%+^7;K#7p{K1w-QG98~H;ic%0OXT^W?Inv!&+OdE%)aL@dxf7qa1N=R}pG77kw3Z zn#1oDe6m%PYRZsW2R1my3Q|Qb76k{8&kn2s9*imWbba`~(b2XWVY3PoKDg{N7YAQm z8cIbRNiu)D?>&0+?XH}7e%|Hq+uT5m7Vc>857ozx9oJ?8;uhqk33=K{S7Jnm3q?1KwFesMq8wo0%}QY*5a|OJ*+0XL{5~1xlBCy{Oej6Rl(p)usB>FKw)NPCoBpWM}Jh+C4Ar zu*P>2q794-g36t02G^Yyx~(qPzk2_rwl?j37TM&aN8k;I*I8ij=;|MK`dQ#0n@~d3 zO$rly*#uNftv07|MUbZ{5BMu~|0>BB(DNLI(}c zVU7m)pP_MrUi-SeZ$;O5x8C-|5{Qr7BkdDElsz{k0cr zqz$x+%P3QOW78gBd7$vCZaR7IZ|^w+WFb!KzmL3us?faqASuUX`~>n(6#%~AV)3LJ zJk>S>0V$*|qNbEe%PWVCWT7$;(eum^^y?x&^VL`semWV;c`){;xO=?jyEtX82ux!y zo@(wJji+8(4#x@_xKKZA57k|#Mv__6S{a$AwbtvaYs3~;j13|#pPUIXi(P(j`6Ka| z%3D@2s~bVJuo}x@@n+H=K;mR2N*Y=1P;X;BySGKiFd-oHsA{oo=a})a(y-y~QaVAw z{P@#vN#p*X_>eEb7`-kfgJ!icvXhb~#%Af!1mm?sVzO@PZk{V%+;mg*-9=Uwd8~6b zHitcSRT9QptMrXA;vqb!&5-Kd3%SqttQ-mpx;c38W{M7{gZ_yd+#n28V;bGiC&8b`(F&vUQ@d&I?+Stf?;pyUc5x(IWWujJm9cKITEa?< zA8~RCJ)fLU=VU%Zcq4gOlL!E$3rDL$hsfrDvsaZZkk>p>ugAtc!8=%^J#Alyg3q(~ zZ$N`xRucQ)AiYDP(1XO4J4hk?qTL{%vq*M?;4FSPz)Bp0>{xAv9)H2k$HUO+cA)+1 z=eu}XmofzQ^+(!9eBRhsLaf0)@ix5!p7;8D-AisggYn$hz}@?hQ&eU*F({M-hOZ=~ zE(&r4?6V`nseV=rkzKyfp?1nv@zJ<^b6@HJ`AG5tOZ3&Hx{QE_-L27gGv2<6jp*<_ z{LXE&i1g^c6cJF(gS4p`PS7gNx7mn?I{79&D%!y5gVUU3K!w|{^x&WNeI{n`;Hb-- z{x+LHdj`x`ZqY9|p!n;VrS&{>-nxv#p^pyVnO@;+oywJuPhYZ^mEG!V`WPoib#V7d z19%5SF(~V8`1S#+48c)M19FenL5TsBV78OjVU=^Up@lQgcsx{lBpr0W5h*8eCb)PE zDIP&}Kmudm=*(h|zj8r`1&89Np-To=rrk3@cq(Jmw>vm_*o2N7vide6D@Ip&tXUU8 z4yqF&#k)CXzPjFj$K&hs>Qkj{J^qjy`WU!SQaz^=eB>|Kj8&{b&aVX-&FTTk%k96# zs?3$0AIwmm{>F8$;re_bHSucEnBfBgU@4L;M5xmOmSNbeh!7rdd&zE<{6Dv|#OKLwkR z(9yC5z>&TT9mO{QSeBkN*X4RBu-K_N2g(ZJocJ|;Fsp~G)7$m6VoT2R)wikP9yTdH zAlSYetdI-P=9OkBSJNsJ+i?*Z5SlzPv6Y&oP+9&t;uJ@2%1TZ5f$;m`QnIK|`#U5y z1mlq$2J&=Ml*Uk<_)M>Wm(dYw$rte#q3>_oE*RD=JU`v|r?WxxQ?n|pA&d>z?SoE7x`=Wmrktb zty8qlXU94_gJi=_bA|C^j)P*QIzuY{1G?i8tCChuLMQqaG7i@T))BPyuWDLNb15D9 zlao@ekj(w-X#C3K7Is?If4ZYo*L7L^+rXv;2P{L%n{ispF+`D%z7_B%k8FC@1SF*r zCCsHzKb*28e42NaUDP9G3pb`86MO(Z0SaKGSP_&HZ7G9p#W>&pGqDLR@kNakYD7MA zv=k#Hs{8ZUFR6!I*Wr(D_4tXXVoU=vrv{}SD0cIQjH%}lMB%zJ}QDx$P!*jHw0LOWSW}QoBo;LZ=O;ZLSKQ;tY}wu>zoR)@4Q7DyvgB8ngD>&sFVTfRUEhLv>O^`Mc|q zjs1M(y7ooi>jShSf;YIkjX^dLLgZzf^8-m&q>R*1$wp|=)qYCJuaRT5KVw`z=>yH| zp>|fUK7RUCkkrFKOcUbzn{8&g-l8%)h`YeD%`lKbWvuRP-l}mf8QDPvYpZ2N_-J3D ze17Lg$Pn$1d>lXrrjP3z=G!J+_b(VB3f!A}CNga8pRFr4=8o@rm8D)kj3H$p_ddvo zxsZ~s-lG4)Q_w!e#i%vSl&=5e&ZF8#ghk8$g7MG?_`$ZI4-1Vzd(vu5-MY+8x}RY% z{MK}jP0s3_+32#Qu>D*LGA+C;MQ=K2OZ^9W#DDGaaQ#tYNKVi2E%Ra;ed`69J=9YL zD$?7qL7DHL&gmxmAWUO*whM3zWPBn5(y?P*NuMMPjnnc2e1Yq3(1x>1dU~EYp z_!`cy&=ldq`4MNYhsO?)ZBNYf-x*}fN;`RjOX5ZdVM7SnuEaQy2q=B3cT%hC7I3DH z!w;_J!G93ti8327jVcVM&=~-ywp!f$c>8kjc4Q89=2SZQ%CLh#=I&ocKUYG#F@o#N zYD}XHes&)y#4ul2flP6(o)@;QhX)LV8*ot6^KRcx?Ac)sS6eGF@>2JLJ zaWnN{#`~$D`z+uGzNj_b_EJTw`t1D+_L#6r{P!e`Zv~0--)JnndV~R2@%(cYbDfOq zhJ&{O3?WV49Y()t`_&&IiTIfSm9rWM*zJRV*devr+H}^u`R`=&{Iu`M=JH}*``-YT z?Bw8%fF4KDo zK}tccyugiiu{xt7F>4f`Q}Btu`9V8@`jw0!xu_V3 zp(Me0v>>5k)F9L1-0&jcG5!mdb-z{5EFRJfM^0s8*jUm6sMBtJ@^(4zM5|J~{@&wyHQI{n( zGi^j+SuteU-O)?S6sfNxn{5-UeQZ$UKUs~CAWmgSd?ha|3u7APEBW*b4Z1Lb&|k2t zpURP2zeSuzokjnG;ZudNkSOMeDDw=MEy}=854mbh*21Y3+R|UvSY7>(&?nyt4)l&? zuq@-qy3E*ZEGyXpxl`K&4aJqn9Yx2H_K)CDUc%KQ{u{GdfOT?*TX)NY#k-UFwNZ%- zQKyX)!)W+C_GT$fJ1an)cR{nT=S9JX=Mk}CQy0QDzI{fh-W_ugfw#4{;~%q*Fkjbe z1VuF%o$R|?haltlrVJBu+)hYkCs|pW?g74c{(RZ<)3RW>eb9HnePTdu?-3Z!Lrgc) zQo}B{8$;968JDZXt)hz=7Q4dEz3Rg7C2rl)pyyJ2pGQ7p-#VOKV-<(z1~ZT%WRp@7 zkc;$ulp4vfd^@3C%*qVqi45@)FHpf8djy0i?EXc2>EDwq*;Sw$@t<^CaFFscg)0x_ zJ-4zu3U8-AwFn70db#~vB?nhcO)7_}@Xtr(8aCG7J9F7{f#C-5phjKPEnr(snI9{V zkyHEZD#~xDYcsEBYZ||sn{TktU+cOrx-aSLsGa;t_-OTFFa0EBwP6DBOd})fxdsRp z)avj>5v$Uu_{H58<_BTBlTFp+t9Ji>Xt>ahAicy>Ed)W8m}(9nvL(a@mLR}$`CA_j zAR~pkxh=k;7Y|E~mwdZ&r1UHgckY|=^4d`SQ}7r#)xj5%_eezCuu7oNJnvw5 zyHQ7I8(40uy^w#4q>4)E*nKX~p>QDgo69(Z}0-)&`mIHaScy-@H zN*kw{=>fN(JTguqC~Mf|_UfsZ&U0na)mu8|db5f$-ij^BIl+EvpSs|0lomG^edq?` zfX=7PqZt{gv+6Xd{W=wT&w$|WEo}b<-5D0D4-xk2TZiShRwZ@xZ{hwgsezERO?3eQIVqPtPreA zzqn8*oX(fEs%#e>mQB3pxohbE!6YH4PLS|Ckil?}PdZ<7tn-t>UekMCgVtQrn+!33 z7QcGGkrwhcQ5fN_yhhvuW&JWgx(;XWl^dUX6t~wtL;Qr310SYKNe=#o;u#i!==EsB zgrScDfS$rUT7X7~Tugy88mTb2UGCJ}ihSJwRvB4H2Od5E4V2E@* z)os`gsV(RxYKFvHZD63>7%AzlcR|C)S75oBsa1ahg-6&NVK9TQ=v(L?7^-hIC7iA^ zRq?330m!c{*fvU@4xTO`xKxknrRcmrllA#t{@7z9t?a5gbLx1DD}P-I(f)^a@geeL ztcB?8vrh&RLoG?d|K_U?VJ6RZq4;={R@>iof^&3 zfCyGp;?p&0WJ|s5P~Kh#ubNvqlP)eNNr2tG9R3zJ;X6{z+LK4yjq~^VfI>l7x13Sd zlDU>TSKHmYZ}tYZZTc4^9O7a>yzlL5?|CMc83k~~prQ;`DN{y-)dg9R43(NUkDryR z8~S<0zv#AstWm&V+Ve=|kC)E3Nj(pHjF3f;0JzX|G5ujq9>awBK`x^1qq98`Y13|Ig~W zlQiT1@36XJs390e8lsU%m!1U+&Qrj?h5P3KF^;$lX(Y1l#<6CtnB8_He)L~3Oye`m z>I3Aa3TEl{V+5us4FYMQLSQR)V>gI_`vhII|3eaR_+PIV1m3;_rt>1+L!GW7BLU*& z%E}Q+rvN#Rcs2r#stW%Mzrf;N;I9BOo^p%^~Qncs1{JRhA$) z9WR?*Fe4ctmY_UhRQ?lq{`S9Oa^(USx(1ZB0p0Fju!WRr!2Lc6=)M8tIv&ywXIVFs zarFIbzDyNSMh0OW>`<t>Pc{Ctb4F2HP!QHW*IkL9ErT+`+Rsx`IC9Z@ZxbTZ+FTl|2@3(@j=l?bT z%R!L73j*HXSo~t%JaYT)fa;b%ZvHrH4_NA#mx78|ovz?^-%~U}0Q=vGbN}14>A?Pi zw>krdR0A0x#heC_YEh#GKKh+6AL?xXHO~r+_}mXwms6ilL{6U&*O^XusIezsUs_jZ zd6vlH1rZO2KLmCuM;+~13SP)SUAsNfJ+*UyVV9@s{HG=%@EXs(J@@y1L=~Pf+Wl|_ zWR$muGRZ`4FC!yr_eLDf>(Rr?ocVi|UuPqjKqF_eZ9>yrDy$^`^R?4&1xc4-0w`}aUIApz=UDO zECGqDY2BATlp2sV>Z4ejZ{T@vTPXAhQsW$2u9OQ*3q`%tV%x%TLdXe-?xOCSu-4rRSbxt}skc|c` z(Vc9-h}Q{{n)Zlt>%Vg^vEa5y($Spa3pp~OgCo05XFtKXYol$f{g82pa&T(cXc!j1 z1rz56nbPiC+O;Fg5)*K_*i!^j1eUJue``tB_2K!9CtoVKe)VR^m@|Jb6PgoaB*FX% zn6KfhA3#$kz{4N=ZB&-h6&yB3V9xTlUB9{}A_SlF9lO!HOwo6Lyf1nIB?L zDr7Z08dz9KWeJEeKhy=#n#uTP%m|Vczv=)o&YAazXzqDJ2%6##&FP`eHxWs4pOdY* zeGlz=E$4S?KWG|*R8?$dMw~*UpI(5o0U|De5h&5RZ+wv@4;2;4RYkq~`AYpxPqB!y zO5?477u{p5tC}!{qkluY-v?o4bZ~-kfTuA5xvw6u)?KfE;Bskktt)h*LL<$fqw_Fn zUyvPqr8|gyPF*x8gT%#<0?8IfPxZ=TcS-oWh^p%9Cs*jmwz2OqUB~@uydH|VBaU2p z595&p>g?3s4K-#3f>gKt0JGP~0CkxFxctH-sp5L@=4IZf@JoY7#$S3rd!_GUc5Tz> zx?A!mlV=rdB*2V=faCxzc^4hnv&M@Ekc&nbouEEV&60#%$b3G!ja5Zt)di<`BYDFW zGtvHQ1DT&%UmRt)Rb50E(QphY9hzNA zveqTdM~lY}9{}oWEw|ZvV7+iVlsPj6<6{NM>R^=;>-RFw597UhAM0_`O}>&a`y>>H z9>gjBGM7F1@aj2^G_}qMCI9gn)xB(s@K1saaksXtJm#vMQI)JSD0LEXm{B$c9* z&N>RlRZAzmx_7~^|=5E zZGRK|SUu-(pLl3pW3aOMX@zT)ltZRhuxbP)7XJu1PEUdcX7EkDQh>?l$EFaN7=N=a z2$`-&)xP-td1%pQO!=rouV#&wkI1*sQ)Jd0smiruO1xM@W%+! z$5i-Eay`;%=-+I+5l9rS^Lz9F$!8n@Pvb9tN;Lc#ll1kvjJOKeMOiiPk|SJ}eGMdWrR8il18K%${_x-)A#?eKdW(;4SZ%ZM?@jN42l< zd6jSY`cKH&|3JgoY(4*t<)8N-E*BvWqWMwWmcBZq%*A{KBI333t2hGhe-Ty#rmQF6 z(Tju5FErq(SMXy}7Ig`pzp9}`T-jFAOE39QlfZ-vGCj{e8XB{^vLgos83$eg6Tbk3 zZ_Lx4;bn}tn{OdnJU_};(Uc-{1D@1fd|vXc#OLQ7iba)Ry_s` z$5*%YhCQlyXmkuRrs+3r`tJfdltDK(hTdD>bI@(mJsMI1a9J**1WeOo+HWS0(NXYD z3_&n1WSK!iB&fCBq4S@&h4qCQ^ zCZ{n8#0s5AmPj8%DX0b;RVPtkVv=7lWx9IWKN!xaZQl1f06a#}^8Tqf_;!QfAFgSS z$U{`CX1IW7weXQ@Nt0BcTdFuyPx4iT(DTFVpzBT&WWW!S#@pfLm}s|1kAaz;Qs>3= zOA;&7ukhu$@fHsz=F6TN%H6G-q3*_41G17RhRBO1kSAa59hqr?^VXT)e~^(;C_nf> z%}Z9KK|?ESrw#f+&7DE30jLzZL;#+oVMY^@A3iPCbAzJozJdWhOA`_{(`+zY6VmTpZ|i9m4P{B zo9W#aMu8f0SV$sE?(s=U)uL3AX@ackuOQu4uiEz%Ig-a;umiYa{53&Hw|e6>vkrY| zF5Q=*x-87lrpC8*EZ5nQC*@`?mR468q&`u+8d5ELU3l;58?{;5T?Jf=ScZhnw0c?j)_c7@kZ`r5LPll&O|5ixw z#*+xxSa^A2o1u3*62t-#0f=ZKAL?AF+Mwj_sN0*4?GcV9lN-o#WlgI)dC>`G&6*!5 z&v#{;!w|B6N@iM-w38*(3T4eHW0 zkw^~cbKy^+oCyHUNU-LTKNmoxzBLH`3w8#SOsQ6Wf5BSpf`QmN&sX{>bl=zxOoD`O zSr)#Vsg^|^Xii1mtWK)oxhuhONnk5!kgY@3{}kL3(^w)SQb#joi1U#qsy=lo=;?Xu zZr+y@vzL=JoZszx>SnT5$I{FoFRNa46_BeFzzY}b0uKBwRi<(V87=O3x0v>#-PX_1 zMJ;Jnt?u}>{bqM=q_TG>{p21vvBhUB`TmTA0#gelh>3XUB%w*%2t?XpMARLpr!Tq& z^ZG0Kf+cuA_I2cr3fm2;E?-Fa<4xzleMdki%30j%x(rc|#&iVWHkp{K0a!hbQF9Lt zyJEn(l-=%^bSF2Jec@Li5z=xfJ;R-60>Z?ctNze~v_E*_8(^U5M zDArA^IOu(Y^B7&kl3>1KDF+c;EBn`cBUy$+l@^2*%Hm=jBGAuI9}^%Xf24hc7e*?g zW55$$fo|;d4KG-Y5-sXuokAAikyA1WWC`n>W`M7)|9LH#^Wy1VKjdR@h|gL<+P}#j z6n0voF%(We6NCg~&Ok;!ux|)Spi2M4D^C_uFT%yel`1 zjd7$8c@I5Br22YLbm@Ey>%lb~Wap{`y_$BqM-X#Wp+3(aN zEXCu3J}MmpjDd{cR`S2I7$1C}Wa&8Qz`39TBfpBd|&T;>1q$|*WVIviJk>%@<= zv$(I*tC=Gd*7(a8UMNjo+7Yc;BVN?ke_= zLwOtkqx@=6ZR4Z1&dAD#i1a^;fSTS{*D7t z!Usfo{Htdo&Y<$ar`o)Er1afG`*(xa((M`+OLIyM!(KT10yi{bHRIbhX=?%JV#q?7 zTFe90Z}{ImRee%M?;haqo$ges#&>&@ z5xeG6Q;NeYR4fDTc44i5B%9LRhVjY^bbjzQS22y^YXG3Hy1BTVH|C|6fStz2%5bGP z;rMS8Vu|i)iq?lpzbNx@-#RSiYvUe2bD52E2%oAx250fu(M{2vHACyzgnC|vN#FFq zl4Z{P;di|OdEJLD8WerADW2t$;5_i_u@UA!^Nb z_52L={<}%*!RvG$EvARfv%TFu9^RTU>?gKRTl-9�hGocFDqPh*Te?r`m!bv=?Nt zkIvf;I8Io)70z=fzq9qc8xXSa+L@i94yIiUxv!b-uAl!%+#RHU9ttEem72H3u->_U z9*MruLu1{%_b2e_2R%34cd20dl90_QX_#o6hr2&7zo-CuTgZ*(8dJ^FAHMM!H zDzR`vuJ8sev|d^8V#D{3R@ZU~E2hXPLMt&s1`aJ#%UfLeXs#IorPEk3uYozeyqCEV zU#ilNABcH=+PUb!G1>4iZdpl|HHMUrr}~IfIDuuc1!w=MRFjbs^gr6W_Gl>Awm+fB zsFBDfOhOcr(k?knyMxobnvJ3;6NO}F9COIb;}pBFg(4kHwnRzO&lXxa$Oj(*ZZ&i72&~4u~?x1IDKgiKHnu%3JjoYe-wz!Hi!I<7wr-wID-&e)+WbUIUs+#G4 z=-O5Co5cPyJrO?b>NN!sY*SAU+H zsMpXSZ;alvTvVu$<@bu~Yc7Y3fNFjo*88N_ak94qp%RzcL{N3qqQ3fAlN?-G7A0M2 zQ_jH~edIk#{h+p>>(LH_bqGw^kyHq4Iq|`=(fF*I1<@TL8!l0DFl}mZZzJ~OVpLd!$01B3qBXqn z7#wl*Wz+9vg&;zwSW0(+ZC0O0qtwj*Sp1TV&}?KDRvhDxm*EaA>aoz4OuE#x+g&nDHWdHv|#O{m_OT6gZ$_~D=4wv=ua!AA7i6*ei95l9#+8@qHph0Y?W zNc8xgG2th@4Fsn%Yzyd(ZMe79?~}8q><(XAn*6R|kKD=yUrGm3K|G5b>mHbF#wx|F zI3~oPMP|;K&U8EUgp+#S71zSu&L(HyWW}#8u>T=^=kou(v89+Jyagn+?`M+Qx1r<{ z>Si_*&d_{#a3qDP%?zRWH16Ympcs1pNFCI^Cb89%CHO6lx1)(Ib;;>ro|Dcg?uJa0 zTXh?ZWU(!y7;7AR)iPM{Y;*S?U5z(l!xzUVc>QONRfi}(CT+vQBSgXtd_o--1q#e| zryb_^KP>17_1P}pQCpKE*J^P*`>u_H?xlRf7>Ns(f*fGBfHPmbomf4e z#&)L*+E|8Z*1Bvcod_agB55lEdj}4QavV^jCwezE7MNsx!1%j$E0xHhqSWT)VZa?< zrt)B2UtGWN5O>1#kmnRZaoUkT*OJZXqz|@PT&UeidG|hI+N}-8KxVZ@011a9f!L3Z z0X$tuzx+;+dNG@Ed^^xD&$coKJ;o+^TUiVx=_{F*ajteL6EF zO`M=6G3*Mcx@uKJ6=tBwIf9{PI1w}*#<3>R*p!BKE_dP#7P2LlI<=9-cyWh~+kuN- z&Z%xqoi(eTJ!>pmS1=VFPW6CCstW-N>n+pNsuIA^$B+U4iEbxRtw83NsRmuaUs$UA z+{;mtXF~_=#`Uu8asnd=CU#2Mg~Tq}fSYtFUJ!HuzGDb7po-KgFq~qfO09b$@Z?yc z=DYVJ_lh}Xr@b8I2Ng%3a$SO7uy5te;G9do8LbSEtUNPj&jns_aXBAJY|y2=8da0% z8MZPo3YD}BS3->1@0@h|h3nzw3>6b!2jBFWhZ`FF=o?fMZ>Td^;K6MNAtYAj@pxj- zXb=2Cal=}X)mTZ>b^pO{B!MMeArGQ+g^sjUjx_V_*HWSv$#?nd99zjKrrdxisp42S zv8(Ed0x?`eo|s^IjiGJ3qS5SB^)!p3@dV4kJ9pXs2`y*c^urT>p=q6EY+a1+Go2Z_@Htd}erL$wk~#a5fOW`uRHZO`X!`-EEUbLBl=JaGADP|0^jj1QWt zNR^9yLh1c|uVjkD7R}+f47LLNX%>SYCVb34)8b$;nvAO=q+*{8x@Rd51>T$rDert@ zXFC-yWR{lRK;?Z;4!fX}dAk&i4B&y}mw27kAlSCb>hTPw)%w!t%9+NMuV#KIE zthPj3AOik1?cqm4Dcs(^IC#imMBNv1rI;z==lRfm&f7xpD|1_2z`3eJBrg}fi36*u z>y~(4Ym0(@n5)B2r`ilPP}tsawRvY2m_#vz=Rt`Wk>NTiRkRWBopS$p>dm&zgN~-+ z;$FQJ^Q?`x^^b3o^Wj8JUh-*LIP~8cLYY6VUjK;SYcn&jORSB-*3+12y@Er=5Cl*q zi9gxznR_+%D!cAnZPVKW35zaWOmRQpw7fBZfM6M$rTs6T6eGA?=fF1#cOVpB@PrD%}C{Ly8^=JG#Y+!K=N*op*j8uR9 zn`amdVmSEmueL*c($eSJk|Rf@R>X(U#*jTK!GTZ>z>}R>C_uwpz=v(H5u{EapPO2} zZJojKvzds92ktgIv7l;{bc@y_3*S5j_chPiPblpoDK;O**9`1O)q%lk#=~KVQzbqJ z_pJ>E2_Hag3?!)U99HBQ#E_iM6j4C$%#fygb3UP#nnuClj5%Wf6@Ks&rV}Pi9^{tO zh7q;_WZDFSIQBe9@}Xa;`I$_Ke$~I=s-b=LeKVdO+>#7jO`OD0)B_wIgmpvzy@qYk z*Cj4@T5pT+9`Ct^fx-IbP2&%)=hymt$ldPJ?fKE`-z*saKZo$^RsZWAm#?w@8tZ?@ zZQ$#?{=Yh}p&ynMy#@AXBT*(CsgLk^Os*A~6hsT0(~RhCWt)a~W~|F7@<05{Zl|xE z-4^eya1?vFKu1`G#Lr0suYDo{8~3UMsyKTpho;MZtM8K-+$G;G7$cY`yuYrF;%}$D zTLKPkR$o9t*gxSP+OU(6EPwV(8-FG8C-}n%H3G=S_%jIV`6B#Tcmh24a;TsBBMP$r z0%{AIQ~9S}wF|@?80o}uclHBCH(6#OR8#Yv*!t(b}MeEghlPAHgA2i27#zcka zC|B3Kx_xP9EQWd--go%b2U7 zs&CG-p# zs5>0m6#EHfP<*RCLz6vJh*TzG{50>Vge=D$Hy-~CvGc&E@$JbLpFx+v~FPJ+^0s5^Vt2Z^p4|Jegb`2hg`4GDP-bPqua|-U<9@ zpB5Q4bW_y)Yutr))0c4t$4bXo)QvxAcV>@!Jy^JlV-0ktA}c7Sc!8HNT$DD}J&-wO zGZ7Fps^Bm>puSh?ySF}UPmerjt%kcv__(>@8tfGu-#JsHOO_4K(F z^a;IiH*eLBU58Dix`OJ$N|`6rD~G;GUZyK!ly_oYc?0u}nPjD#PWHK5TeNnpoQT}c`R%F@I)EgF*si2J zA61?Zb&2ib?3kd)qW!4pO0GV2rY*|Kf^5~%5!0pA+s+8E9{!8qo~)efB9sS%%%M(4A5DBE6Ds@ zl==1b&xwKT6C{`pw=iAQ62w7wQAmTb?p1xOo$?4?kuU0tLS_ USB (primary mavlink, usually USB) + - SERIAL1 -> UART1 (RC input) + - SERIAL2 -> UART2 (GPS) + - SERIAL3 -> UART3 (VTX) + - SERIAL4 -> UART4 + - SERIAL5 -> not available + - SERIAL6 -> UART6 (ESC Telemetry) + - SERIAL7 -> UART7 + - SERIAL8 -> UART8 + +## RC Input + +RC input is configured on SERIAL1 (USART1), which is available on the Rx1, Tx1. PPM receivers are *not* supported as this input does not have a timer resource available. + +*Note* It is recommend to use CRSF/ELRS. + +With recommended option: + +- Set SERIAL1_PROTOCOL Date: Mon, 27 Nov 2023 10:49:45 -0600 Subject: [PATCH 425/499] Tools: Add Aocoda-RC-H743Dual target --- Tools/bootloaders/Aocoda-RC-H743Dual_bl.bin | Bin 0 -> 16020 bytes Tools/bootloaders/Aocoda-RC-H743Dual_bl.hex | 1004 +++++++++++++++++++ 2 files changed, 1004 insertions(+) create mode 100755 Tools/bootloaders/Aocoda-RC-H743Dual_bl.bin create mode 100644 Tools/bootloaders/Aocoda-RC-H743Dual_bl.hex diff --git a/Tools/bootloaders/Aocoda-RC-H743Dual_bl.bin b/Tools/bootloaders/Aocoda-RC-H743Dual_bl.bin new file mode 100755 index 0000000000000000000000000000000000000000..d806e3b8f53b95d4d672595b1a50bd970144e027 GIT binary patch literal 16020 zcmd6O3v^S*wf4+8N7nHJEL(0cwh4MbYGVSzhF~5IvSf~p1+jyZmO#=g+v(*9lAydA z(&qk%M-m5UV*<@}47sI{2T2;h4(g2qt|%tGNt3h^j#~ps<2DaroZK8^gN`5Q{NG42 z7jpaGzyH71UF&+S(d@HlX3w6z_w1S3GbTyI^cRkZpZ*=GefHm1kI{Ougoq)e%SZ+D zh=RrZb-T1(!xZWB$IC-tAVwm%3n2JNm8qn+ijDVuPq~9Jm#w4kR^9Oxf4ep~^65-K}OV{noNyI`}iUsX}f;`B0cB4mD$G<~2C< z8z7j+#DYYKD1JqHkee8;cPCYI^Ec-RNeTMVe4iXE++B%2UJSlW3Tb5mQ(@9jhQxl|MTe|Cc$HX8l ze%?`fpLO_jPQr=QiYKczb(eygbH3xZK28|BgFcx z%BsO1-EXX*%0J?Z@t(QVDjQp@GF@PG*8{2tRPP?QtZ;pCTfO|_HqJzp7eK*UnIrN4xiHC zgU*y=Bb-T#yr(U85p$<{&eWlvGjys3bBAikV0owdC2(H?mjzrFa9O}9z$w6G1D6e4 zHgG8p-uNsea&{tej z%ivS0&*r?;^TUpTcXb^Dw-m3U{Q0D`0%_^_jgQcIC)9@?7&>KIVC*-gUkHs+8p|0S z0y@NcLaik>(utOK8a#@NDm_IM*0mBEALF?i&KgCXrkRyfImms z*f(o4M(h8Svp$&(-4P}Ec4cTI+0B`C2j1!@>0%&H!h9-zUCqK=x^;L*7-A3I3qL_x??4J(ZQxoKwOosK5^7E;w|1i95geZ59+|ZJ$ zr1GhSVt`E1A}P^I&?>L^AWUYw7>t+vBE)#Qcv&xz{M|vw`39m)A7;1((aFP4sCM{~ z*~5Z#xP^btF43EQ(QoH&b=+D?lzGD>|EthjlEB7mWaGbCijVq_L)V3;LZ@0}Vsr{- z;A;;3Y37f(VQRB0t2YXB2H=w{uD7I{rAgk&uDjd^z|o??I}gQq+A#RNLyUvr%SF)p zj-kW-MAR-VJCv>P`VE6i4y9L$eLDUbd8cF1CC8yRFZwntirjoC)AiT#q<6r9CnlFggXxDR-Bd2On~lPyaei?hq}0}hEkLzJ6`X|rbDP(hS`7_K^hfPZJ;N$#;F`4WXLzdxJ= z$u1ha_YmE!>)Wg=4zrPc=Q6{6c91AXh8Xn8LGtZ4B`;)k)RBF9^306xl-;y=eDK=} z&u6}BEUQsX3w1l~l3>xjBFrVq>%%@N94>)OR}ASIFN8l(vwX~Yh>|_Tg^BfUvv5E_ z?|M+*FnIVN>ywZ5`RYNT33CapzPPI1fXeFaiPighlyUTItlnKi=VSbS9>Z-1zxNFN zC5HJZhS_{j_evIYw0cM{31*>D00)0k=Sgj0rnw`k{(9}w{RfXiYxf;2snqu+C$zRY z*3(-t8np*8N_|yX+u}uoFCMIrlKX{ZqI{{2S@TLcEdp?rTBb%NM+W)VK6Vo z)w)q%Ok>|Vs73A{#X5_5T&(FJHDySW7DDE44!!hwl61=#Y{t;7jvb@zF;=P zY-{fmlz7VtNq2eux$Dy;T70&Z7G`v(En_QQfxK^oFS1DE*H9^6I$XZRA%yf;)u<`Q z>us+Z9EPtLjbddB8$c`n24Xq_TlM+{39WxvI(@2?A1IxgG@?_8axQvz?!}N79-LV9 zeomt1as7Jo6IE~1BF8mT%k!$9#MkmFMYCZaKvJM3(XT~XG@nAr@m9M-Y_}cJElrWA zWR*?Q#~$AGOUZW3T}}e5@7P%UhNWbx;TEdAKVC6I%DSwTy_Y$|I%S7N8ivuzBfiVxZ! z2$r;y0ISQ|kbbS2TzuLPREfy+k+fuoI>lDpLad@iT(c3d76}9>s~OnNcynbljsnC$ z?wshNCA>u}^ZF;r6I^c(qzX5tUElDMBQ0w&w-Kf!S6{Y3RP?s)^St+0*FwF+rwofi321BR4J z$NNQ2*XJYq9Qgr@^vBj`h!#1-%4{#>PAI#+tg-B~)=RD8jK|d}?z15+GDjo%e+r2` zg=_e}P5frZAA(w>5V-e3#MFLH-Aqj*VWu0-m9rkn%jCl51DhKLf5y@b%PLt|yuL>XiiNLxrmX6sqVL7&+CDP`ia z9gcCq43#ceVHd6T0V2=^)9pq@U8OJgBWx%ZLm3X~b4Bnrp_h`Ic5v%tgU^W*F{%g6K z5aTK}I5+q+U398& zgCOy4V%0rF`nPaScY$=gmn%+lagCt0lTjegQst{?vP-zM%TXW+{YweA>w{iW&&uE@ zG~uwf-3{A+*FeOt(utTN$9I&ekERwoR4Z{kYK-OE9yPYaF&IZphx$S`XXPKl82~#> z#!rc#-ylfFmPYk9+iPufs%a8u)*?1d=+7eS6iTN)LX<~GS^rzq+o~Ccc@M0E$4c4_ zergsZ0p1{6BUbAps9|GzV7`V-Wm0(|%34l+genherb&zf1$C;KBt}JxR0kTdOXn3g zZz@a*HL4p;#A=?#cTb*{)Xk)CnKlwS-aDz7@8K&QtM!&mt2ObeBrS3z8tgQ4B)Cw&`vomA}^FJ(z*+}SPg78v=C%X>Xz z@V3jdu==*2^I`?@W8K*-n^1>WsFC%(*=+#rM?sreKUHjRDM#p3P!-Cb`icEB`8&=R zJc~D4Vfp*q^={=DRhGR)u-%E*(I@KM?a^IRrvr7oesDTfkfvC8FJ_C{P@QJ8tHPaH z#DU(nsNQO-(4l%cSGKk=JunX8S=#yax*>`Ox*c z0%m>NO-`Bf=E`F}$?I=ay*4&Gh}Fj+=#ELP7yay(-)P$f+chd~-JBpXGyK`nc>dlf z(9yzLAo`JV-ks887Tt!s8P1op4qHRQ9sxQ-N7DK_4Bf!|1OB+3O} zvIQ+nu`?hjeAqk5szvU_3}cux;a!*|yt09Jp69Ig3tZ7o2T|VknY-V>ZoVQouA3Gv z3UW9J?(~tuR@hquSGSt8>|6cm>feOlxVUixQFi;@xM<(-LTHz|$wmwJhK{HWHsEo_vKycX2TJ6i|sH*vL)!0>sRyg{?$2X zXIOVr(0++?>~w4xTz}|JSN&?vx_>pXc7R{j%LeS@SwC$3cmesz-buHAzIuK52xQ25 z8z19_X>u$4#*fsv1Zhlyyw&Pu);y_rPgv;R#@DZ=ple+(6dFSDS<2?bThYfMAKqLq zZ&9~Zo1w?l7AAAnKPmik5LlZ4N{lio{9}-d(LM$Kw%AP4q$FNRrzu?&`)8Uj1Uc+# zvkn!yn!|;zCd8IH)q&VZ2u30vVr`75|3)w;$s}=Tb#df%)cRuN)ho3w9vrK+H<+8K z^}CT~)H*uy&*7{qIxdu^Nz7t#W{QoV_lvt)zICOPSybEtRz@#>k$MIHAFbTcPs1e8 zh_#>rX**I$!fr|7&B3GvXIj&z&F)SwEJ9p}SLV)|C0dGRCI05leSFk$J@a}IvSC@%?QHuAK`cFK#6$-}%3)@&k?rko!VjmpZ2pgBSKgCYfzpG8QgWq?_2iZz zW*eVsEFQ$ZtA`GF^jNX9$Z2gT%-a1dn}`DT|7Yb!_@yStt^oGrSUp*p=rZ{8vr)6Aa~`K!Hr;_=`}E{W zr#fZ&36zexMiF2Kmn`+Zd zTI9|EE060ziwvMl^wWf1M3k>gcuTQ832o-JIOJ^T!02|m1(do1>{J(*4-a`I1#@K1 zUG2`6o`c?|2f#yY4>L|O$y*#GRMO7NR`;Fm$5A>-8w~TZ!M{h|hqK(B@>X}Md#T&( zzQg^Tyfvpeu6?X3nYp?0m(Y1iK}jIR%ub=>q?8-n6RGkUBGd1W2)Qph`0j`E1Zjpe z5KfsPoTk{fvsE?km=|l3>d$ha#k49VMSr@M?>Ep*ZcxJdJ<*dTQFnzqyY@gfRbB_R z7e}1ANz#5tQs-lN`4hh_&B0pKGIAlDGBZw91=aqeYD~|nKM9;rW!p%4rBSL;4I6&$ zND58EDb|KHQ-!2Y1VWypa#_ywiTQ!)pvs*tfc@>(EYd8AuZY+AUorW=105Xi<*hhJ z9YNgN<%E3x09_dT6PH>&O*jW^l!FQTZb?ozB47)nHG~(IPbg65|1}*78r(V?MFp zpr3wAw`#yXVA4ppnrDAi=5uk6(VbPsq77Z(;~ikxTzp$4ji_mR!$Ct-xo+es*mzej zKPw-rMck&=dPre+kSgl%8qeN7A$gNjxp>?u&V>ES2(iT5ilJL$J0Yc9i{u9~b1Y>S z!kK-^$puo0R1&C!%=)7KaH4K7s|>vpbIvPnL{!jX;Md5XBmpMF*qp+AWp@|M_TttF zdoM@}@&!VW7U(OoF{i!d{4`y+u7dQPKs})Xb%7%RFV0^Ju^*no&SC!M!#YXC{*Asu zloKjFphaF$oq5Fa+tyXYAidp7W?Q|ym76W7bRm5$)XL5Nse^Xs;5=c(*_9RnpC+hW zUVm6j++*++T4YHgDlNhnurptL-#(e6)AX@@d+IbkM67JD{;i()eqIb6#wuCZ#&-4b zJ-yJaMf7i3ru7Af!{6M`7lVJjUso^zs}xlxUdKQanKO?pK6Lq@}snJ^XiMng=jP+964PIs|@m;M_PL<2;Q)kQw=`E$Ozi8wo&D%E7 zWs#VVsKI^RHV3=48w%w%=;vh4Hu^pei~*umOBxDhtR#`_xbCM0sMe{vcUyA#2ha!4<9rBtqTbNvlPE8U%Hn)#GIsVk|n1CdIGV>z>{ z@0X%A+FR-B#iBn0GzQuXu|D{&GqOXmb7#<+^`+}#R2ZfMxfXd-OF};mg~n>I5*jNJ z+sA08=Qjs%T6Eim*qkAV7GVW|ufhyU&lmlvu+6VD#M6p78FL^c*fu+cpg-_s8ifwi z^Gp0XX%T8|(k3s}B0tgCIKuRW<|&6?D0h3|V<<2k1?h5yw3sq9pI$gQ50`q2-W zhF5D^q+LU=xNWq^R!8sOyCa>Bkk29^EIK5h-Hg;j6{pvu6-3Y zS(qJB<-Jiun`w?|wh}IsbcoJRmLJXgI3(b%Zz!beU+>JV$h!q6ipjaIl0Y_WOXZ6K zr*YqOJvgVD-u+^qkX9@U{dts~9E#o6$){D~ouKIS!y#DV%x#XPDsLK$-K=Smb5SNO zlf{gvN4``nvr|AZyn6%U(no_O(&2EHnJiDkxDXRxZeR)D2EVw}x<0=p7nal&rPz(& zv{pD8G+{m%Ai1x89k&^-Oz%3?ik&3ZYD0Tj9%)6?pRn8Qp4P!I2~^w3it*T6<*l0{ z=swI_m$y1^UD+Th%UhkYlq<8!r&^tZz6Y&ty^B$>fdcNnSCLkyYO0P=VE1|z+zLiV z@23`cR!H+CJN?J*dyVh~TI7PZ*MZ$@td#E3BEQvGREn0dnUdsca0s0YVt4W0@(%S* z&SYb}vHLRx{BJt(6yc840{ww>|F)+V#d zQemmYsn{{M)9m`q^=I<1>M1<8%~8VchRo5(W0&(P*`4VY8{^{t*7H5z=$Z94#{IQ7 zuikdpR4&f@xyK>1U3fRZ-U^H*#-HBRsdgL8=LzjV-l-C^}Zh;I5mMwP2f^#QGNEa4%|H7fwZdUR23o~ zC)KVgA*@V8Q++V6Pw13yBuq8FIRUYNNf$u_9FJ8gKrA31dy%pLYW$@OSJk zJvP?=>TVtPF|UsnxjuClp=VM;tX*oO8_>5z!;2}Qo1(Yyv+13;Uw1w;h4OjPkR=z^9XU1 zg|_2NZX$Bk&m^Ujh#9-Se`F^o8{&Pt48#hJWj-x~JKIThb_w{+7y6u;wD{+a6Dsi_ ztv#WN$w;XePNm9_jOlH)$yQ%yuo`Qx^IWGGl14&I4x11QCneUwXg!nRe#{oT)u|Zx z{k6$f$ODwKN>W{Y*ykR1;(GzpKUo0CgM3~WXkw-2FvpCbZ`xm{wjYD8?LLD0mPYKW zwi-?)=sV9-Bls#|>lC|BV9`0$sZNu8(iu5@c;iq7y-rS2_@oD~=L&UwrACaI?h5=$ zD7ghMGIB9uik%JL6iDj#eU}dN13Nr`FA|9q%nyEVtI)rK&UG%K>#DodyzEpbF~1Fq zF3hIiM(c?$+iN_v*YAGAxb>NByG1&!AyDJ&2FFd=j`O^e;x^kXy`wgfd`Z{0iK~G{ z{5UH1Jw;d?!Fhg5O~vf%op;k2w}N)bWG5)EXZI4iz9kd>q>^0oASwMfeQJdXD&BJR9=kb{I@=C1d^?F1OATJ^iE~xG@Wy;6F7i{F$ zgshka3E7s=RV$2x#4ZH!J2@?Yojca~ivOYvvZe3I6W655Mz;%RWhQebZ+0So)nk-9 z-4omFg6iKXW;<2! z$Mf~@JwFz^{s;@p#h!}scUE2{HF6a>;yYwB_Jvwxo3;ffAnY+WQY$|!Tv+>*6?=-c8{b3RWFW}u zpsX~zob^{py^si#@jad!q zOr#5sj9ePDpFe45RDO%~h|P&H8CB7Ql%C2~XgcKdR9^6pn2l%k*)cg`zj*v3yexsY z>^UPpyV!PWU*C9+oeXo_*nc+0<-zuK>@=9I_|hk#{p=EY!%OyJ$Alo0DxD3lP|YZP z);hBc)J(cQVK&CmbE|y+;;hat)VH2bN_tzJjoTmG!9kkz0w0qmzwskgL>w{{Y%2dl z_+TI9kEsT-8Ml4B^d~ht+1L6;pD+E>?nZepZt?F>g{L7W-`>7tv8n9Mej)v0cXnB7 zS);qg{Z5$e{V?uoLAuZLn&*1^b%VYY_to-2^jQ^+tT{$zWS;4QSKqDI1zFCl5@+6< zyKtvxlC1E{Zv%=(HjmEL>AIMYd|;HVRi4qqLRwcBEY+warT59!L2pf3z&U8BaSraS z>2uG5b=AY)=eE7(vEm-}wOT8p>uDj@NAoxOV)SYd2S1yL!VYkx|1ICYayNA0Cb5xx z8@?$exvxBC^*lT%_L?&@FiXe+QaJ8R-BT&U`T-04Lj6Xe?@3tsS;W)lVdvUZPUn7z zl~ilpE&tr{@o6P#BBMySH75pACU8nR&kZV>t)NDf-}zcE+Gi$*1o#u|PcHhZ!TXwj zcG#7}xOD1LvscW)v7hfEh_PxBDf%j48iVc8wSZZK7<=gGOu&2$o*g~M@m)d;o)LWo zur3DYN7n#Oioup>Az*zB&WnCc`7SXAUl;ZA_WqZBz51~pe;$1maJxG}hyj(F1_vJ#LJ80LOd$adaBsc#jW9`*aUMr=poz1MUre&EyR`Ph}Ek zlEVw92$S8SOC^V(0eBWtzzy0hOlBs`TT(!#<+1%xfkSD;j)xS)aU*BvNlemO^VNdK!YC^XaE?{gm4iz`gjks`J_Ti^4H&Ko@7^Q))Kmq-gr6 zm*oATFD;FjpLU2LcJtLN&quUqC4N`B3&I%+pB|^SeK9-)-4ejdff%(f!WiY#qMx1g zABwU_AyIyGl*v*v;4Lb|3G>``%u`a=ce`9PdrZaMs(f$0U~0H78I@$N!@;dOrUI8~i zG;~5vY0I7juCdPXo{4Up4RDS<;XdIpmTmIjl|${6fO8FB8;v~C&hBT&NuSCKTIxK+ zWSo>K@2@kKeOjmQvHqyIjhzppk$Sv&`sz$cJ9;7`@UpG^bnLI=I@!$XNQM?XJ4wZs0E%FPz&e;~D$Ta_9Z%XFNeY(`;IXf5U z2X;zF`|atur;8=FJ7MpacQ~A}Sjhf0_M7Z;?8W=*(8Aj6i1+_9Z7V3XJGxJ?-rfz{ zq?OX;$Y6B;n(vq0Rko^Ze_c3i@N;{FV)_6-BA8DyEg4yqE2Wr+u7qoJ<*di)6n=>5 z=7ig^hUt(%iz$|9r2823gnpTxEQk_StHOd*w#Tq$OT*y~8QSvD;{Pn&Xynkbu~;)W{qPfOW+AUWqPA{9lXCz==_VvBnk7hNKlKvAowb_7BOpTl%8XHOJNcvH@qReyr!ycNlasV zp|K}{jm4Ll#`N=Z4)i7I{~2rF1j#-#_q49x&fl&Ih0i;1!YdpK#k6%rSO3xL&oria zY4Pb(td|eM1=4)zD-ZhmPT9?63!tyh!*MxJ2;ttRW%HVCEy9A`Ipc#ycL!cqcepz| zIc1v>Y335MfyshG2TT*Na^;CO>RPb|UjdSavjtw4t*Fnb?LIV#+Sr>E0%9cE2ZgxKlmOT9=2f+vaiBrQ)s&b#Q00 z&}F}%-M^rsQ*AJ%z&ADEG}&OX3~F^2MUT^S{JT@_iIw)CR5Y`CqIqT|;8_`%k?$jF z=0j{RkFuCY94-NTJOSSZ_^kx&1$-m{ZwGuZ0UrQ-AOW8Qye|Rw0N#^;M*%;paTmAW z&-&0JjT%vYI5ZyT{zgkY-q(m--Ra5|`cgp)OkD}IF03T8_T7I3N-W{HT?I24h~akE@N9*vk| z_fyeG=P}p^qn*vMxIFoKAbGQHiCkQ{)`D1MW&LLSXGc6DJx)b>}gvT76f1 z_Z^L#O2qV`C)7=fX@i5k#dTo-Bp_lVB;q;q5mV4+vHusSQ;1{i{{^_K;7)Z5{`X)D z;z3*R!W0ljv4wQ6vn!h2KBy7<;3qguY#`mMyVse3GXZA;&XmAmHjs7a?bYkfS65>; z5cYk1Acc&l;I;!7%YoYt+#cZe z0Jq1$tQI+9Hiz2cGQ=IHrN+f(UkxNP2+eTN#vp3tK{E`_Gjo^&d9#+fpaFS@FxpjF z$!?jO-AgLZ;GQj~7VpO#&9!B&X3sMyg&hz29>{Soa^ndQqMX&JxtiHH zg^icM>Z|pmU95GECsQfmMncp)5%CRQ=^gHst7li9sheGiGDfQ?$2}eOckl_?%h_CE zJx#B?aY-|*V`crsdV29OdZwOU2xmN3zw++<${eIKb*#SwsGo=SoRYu1wLkwKhC&sv zr>en*x-+$QOHSS7$}@LQuFUzto@$)SgN89y26#ZMi1zE#^~z)MqTkr-JPf#yi)gTtQX(p!EmLn zaSiCM8KZmpKk7OSe%QQS7+eo;)L`15By?p~?nLb%YP<0@zS6iBZPzxHoAH%exf5SO zeEn4?bm=RN_n_>art7F9XJal zm^|>NavoRKh@B!a>3aC}cu8Be-$8@fxwuQPUBJ6zU<%nAX)s8t}h!>`h4N19v}M?YU>&Lu9I>s&skT)Egam@L98X`I6G5 zQ_%wRDfV}7CJ{eIvJ*QA-i-hALmDgN6LqE<<9!+Mt)QHt$NFVwI!X~ln1ugbLV6x) zBa#z!rept;%sB~1$?>9O0gX6-x+%m!byFyz!W53vO-UkDuiM1q(l=S4giAp~y^eBr zmThDi$wXQYTA9>$#73 z?!M;-fC=$UW52KB57`t=V_*2&%LWh^Poj)oDPtud&3+PP_N&Wc1&J~SUt1P0jkmLt z$XI`7=ay literal 0 HcmV?d00001 diff --git a/Tools/bootloaders/Aocoda-RC-H743Dual_bl.hex b/Tools/bootloaders/Aocoda-RC-H743Dual_bl.hex new file mode 100644 index 00000000000000..ecc103e918efce --- /dev/null +++ b/Tools/bootloaders/Aocoda-RC-H743Dual_bl.hex @@ -0,0 +1,1004 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008BD34000810 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008A5380008D1380008D0 +:10006000FD3800082939000855390008E302000866 +:10007000E3020008E3020008E3020008E3020008CC +:10008000E3020008E3020008E3020008E3020008BC +:10009000E3020008E3020008E302000881390008D7 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008E3020008E3020008E30200086C +:1000E000E5390008E3020008E3020008E302000823 +:1000F000E3020008E3020008E3020008E30200084C +:10010000E3020008E3020008593A0008E30200088D +:10011000E3020008E3020008E3020008E30200082B +:10012000E3020008E3020008E3020008E30200081B +:10013000E3020008E3020008E3020008E30200080B +:10014000E3020008E3020008E3020008E3020008FB +:10015000E3020008E3020008E3020008E3020008EB +:10016000E3020008E3020008E3020008E3020008DB +:10017000E30200083D2E0008E3020008E302000845 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E3020008292E0008E3020008E3020008F9 +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F01F0E2FF8E +:1003500003F006F84FF055301F491B4A91423CBF4D +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE701F0FAFF03F064F800 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E701F0E2BF000600200022002084 +:1003D0000000000808ED00E00000002000060020FA +:1003E000383E0008002200205C220020602200200D +:1003F00034430020E0020008E0020008E0020008A8 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F0FAFAFEE701F003 +:1004300089FA00DFFEE7000038B500F0DBFB01F0D1 +:1004400029FF054601F05CFF0446D0B90F4B9D42E1 +:1004500019D001339D4241F2883512BF0446002570 +:100460000124002001F020FF0CB100F077F800F02B +:1004700073FD00F025FC284600F01EF900F06EF830 +:10048000F9E70025EDE70546EBE700BF010007B0FF +:1004900008B500F0E7FBA0F120035842584108BD21 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B000F7FB03B05DF804FB38B5302383F31188F4 +:1004C000174803680BB101F077FB0023154A4FF47E +:1004D0007A71134801F066FB002383F31188124CF4 +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F0A4FC322363602B78032B07D16368CF +:100510002BB9022000F09AFC4FF47A73636038BD67 +:1005200060220020B90400088023002078220020E7 +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F07BBC022000F06EBC024B0022B7 +:100550005A6070477822002080230020F8B5504B65 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F500339A4280F08880002075 +:1005900000F0BCFB0220FFF7CBFF454B0021D3F856 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000020820000208FFFF010800220020CD +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F0EFFBB14AAC +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F067FA0023AB4A4FF49D +:1006F0007A71A94801F056FA002383F31188009B10 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F089FB24B19C4B1B6842 +:10073000002B00F02682002000F094FA0390039B27 +:10074000002BF2DB012000F06FFB039B213B1F2BF2 +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F051FA91E783 +:100800004FF47A7000F02EFA071EEBDB0220FFF7A0 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F036FA17E004215548F9E704215A4838 +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F05DFA0421059005A800F020FAD4 +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F064FB26B10BF031 +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F02CFA0220FFF73BFE1FFA86F84046B4 +:1008C00000F034FA0446B0B1039940460136A1F174 +:1008D00040025142514100F039FA0028EDD1BA46A8 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0D6F916E725460120FFF719FE244B34 +:100900009B68AB4207D9284600F002FA013040F05C +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:1009400091F9B0F10008FFF64DAF18F003077FF4FE +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F076F90390039A002AFFF69C +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200207C23002060220020B9040008EF +:1009A000802300207822002004220020082200203A +:1009B0000C2200207C220020C820FFF769FD07469A +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F03EFA019AFF217F4800F05FFA4FEADB +:1009F000A803C8F387027C492846019300F05EFAF9 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F0B4F9FA +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F0ADFA8046E7E7384600F058F971 +:100A60000590F2E7CDF81480042105A800F018F9EC +:100A700002E70023642104A8049300F007F900288A +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F06FF90590E6E70023642104A8AC +:100AA000049300F0F3F800287FF49CAE0220FFF7D7 +:100AB000EFFC00283FF496AE049800F05DF9EAE7F9 +:100AC0000220FFF7E5FC00283FF48CAE00F06CF943 +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F067F907460421049004A800F0E0 +:100AF000D7F83946B9E7322000F0B4F8071EFFF600 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F0ECF80421059005A800F083 +:100B4000AFF8F1E74FF47A70FFF7A2FC00283FF40A +:100B500049AE00F019F9002844D00A9B01330BD0AC +:100B600008220AA9002000F0A9F900283AD0202282 +:100B7000FF210AA800F09AF9FFF792FC1C4800F048 +:100B800055FF13B0BDE8F08F002E3FF42BAE0BF0F5 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F074F8074600287FF41CAE0220FFF71F +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883000F033FF059800F0F0F946463C46C7 +:100BD00000F0B8F9A6E506464EE64FF0000901E63A +:100BE000BA467EE637467CE67C22002000220020C2 +:100BF000A0860100704700000F4B70B51B780C46B3 +:100C00000133DBB2012B11D80C4D4FF47A732968F4 +:100C1000A2FB033222460E6A01462846B0478442B0 +:100C200004D1074B002201201A7070BD4FF4FA70F6 +:100C300000F0FCFE0020F8E710220020282600200B +:100C4000B423002070B504464FF47A76412C254633 +:100C500028BF412506FB05F000F0E8FE641BF5D136 +:100C600070BD0000002307B5024601210DF1070009 +:100C70008DF80730FFF7C0FF20B19DF8070003B0E3 +:100C80005DF804FB4FF0FF30F9E700000A4604214D +:100C900008B5FFF7B1FF80F00100C0B2404208BDC7 +:100CA00030B4054C0A46014623682046DD69034BF3 +:100CB000AC4630BC604700BF28260020A08601005B +:100CC00070B5104C0025104E01F0CCF92080306832 +:100CD000238883420CD800252088013801F0BEF912 +:100CE00023880544013BB5F5802F2380F4D370BDE4 +:100CF00001F0B4F9336805440133B5F5003F3360C2 +:100D0000E5D3E8E7B62300208823002001F078BA75 +:100D100000F1006000F500300068704700F10060ED +:100D2000920000F5003001F0F9B90000054B1A6897 +:100D3000054B1B889B1A834202D9104401F08EB9DF +:100D40000020704788230020B623002038B50446D1 +:100D5000074D29B128682044BDE8384001F096B914 +:100D60002868204401F080F90028F3D038BD00BF86 +:100D7000882300200020704700F1FF5000F58F10FD +:100D8000D0F8000870470000064991F8243033B1CC +:100D900000230822086A81F82430FFF7BFBF012032 +:100DA000704700BF8C230020014B1868704700BFBC +:100DB0000010005C194B01380322084470B51D680F +:100DC000174BC5F30B042D0C1E88A6420BD15C6893 +:100DD0000A46013C824213460FD214F9016F4EB10C +:100DE00002F8016BF6E7013A03F10803ECD1814206 +:100DF0000B4602D22C2203F8012B0424094A168840 +:100E0000AE4204D1984284BF967803F8016B013C4E +:100E100002F10402F3D1581A70BD00BF0010005C4B +:100E200014220020503B0008022803D1024B4FF44B +:100E300000229A61704700BF00100258022802D1B8 +:100E4000014B08229A61704700100258022804D111 +:100E5000024A536983F00803536170470010025837 +:100E6000002310B5934203D0CC5CC4540133F9E79E +:100E700010BD0000013810B510F9013F3BB191F9E8 +:100E800000409C4203D11AB10131013AF4E71AB192 +:100E900091F90020981A10BD1046FCE7034602465F +:100EA000D01A12F9011B0029FAD1704702440346F7 +:100EB000934202D003F8011BFAE770472DE9F8438B +:100EC0001F4D14460746884695F8242052BBDFF88C +:100ED00070909CB395F824302BB92022FF2148460E +:100EE0002F62FFF7E3FF95F824004146C0F10802A6 +:100EF00005EB8000A24228BF2246D6B29200FFF73F +:100F0000AFFF95F82430A41B17441E449044E4B26C +:100F1000F6B2082E85F82460DBD1FFF735FF0028F4 +:100F2000D7D108E02B6A03EB82038342CFD0FFF7CF +:100F30002BFF0028CBD10020BDE8F8830120FBE780 +:100F40008C230020024B1A78024B1A70704700BFA6 +:100F5000B42300201022002010B5114C114800F0DD +:100F6000B9F821460F4800F0E1F824684FF47A7090 +:100F7000D4F89020D2F8043843F00203C2F80438C1 +:100F8000FFF760FE0849204600F0DEF9D4F8902013 +:100F9000D2F8043823F00203C2F8043810BD00BFB1 +:100FA0000C3C000828260020143C00087047000074 +:100FB00030B50A44084D91420DD011F8013B58401C +:100FC000082340F30004013B2C4013F0FF0384EAA4 +:100FD0005000F6D1EFE730BD2083B8ED02684368DA +:100FE0001143016003B118477047000013B5406B0F +:100FF00000F58054D4F8A4381A681178042914D163 +:10100000017C022911D11979012312898B401342E5 +:101010000BD101A94C3002F059F8D4F8A44802468B +:10102000019B2179206800F0DFF902B010BD0000BB +:10103000143001F0DBBF00004FF0FF33143001F03B +:10104000D5BF00004C3002F0ADB800004FF0FF33C8 +:101050004C3002F0A7B80000143001F0A9BF000026 +:101060004FF0FF31143001F0A3BF00004C3002F00C +:1010700079B800004FF0FF324C3002F073B8000036 +:101080000020704710B500F58054D4F8A4381A68D1 +:101090001178042917D1017C022914D1597901232F +:1010A00052898B4013420ED1143001F03BFF0246AF +:1010B00048B1D4F8A4484FF4407361792068BDE882 +:1010C000104000F07FB910BD406BFFF7DBBF0000A0 +:1010D000704700007FB5124B0125042604460360CB +:1010E0000023057400F1840243602946C0E90233FD +:1010F0000C4B0290143001934FF44073009601F0B2 +:10110000EDFE094B04F69442294604F14C0002948A +:10111000CDE900634FF4407301F0B4FF04B070BD3B +:10112000603B0008C9100008ED0F00080A68302372 +:1011300083F311880B790B3342F823004B79133377 +:1011400042F823008B7913B10B3342F8230000F5EA +:101150008053C3F8A41802230374002080F311887D +:101160007047000038B5037F044613B190F854303F +:10117000ABB90125201D0221FFF730FF04F1140057 +:101180006FF00101257700F079FC04F14C0084F840 +:1011900054506FF00101BDE8384000F06FBC38BD1D +:1011A00010B5012104460430FFF718FF0023237710 +:1011B00084F8543010BD000038B5044600251430C2 +:1011C00001F0A4FE04F14C00257701F073FF201D0F +:1011D00084F854500121FFF701FF2046BDE8384054 +:1011E000FFF750BF90F8803003F06003202B06D14A +:1011F00090F881200023212A03D81F2A06D8002036 +:101200007047222AFBD1C0E91D3303E0034A42673D +:1012100007228267C3670120704700BF2C2200208D +:1012200037B500F58055D5F8A4381A681178042927 +:101230001AD1017C022917D11979012312898B4017 +:10124000134211D100F14C04204601F0F3FF58B1D4 +:1012500001A9204601F03AFFD5F8A4480246019BB7 +:101260002179206800F0C0F803B030BD01F10B0314 +:10127000F0B550F8236085B004460D46FEB130232A +:1012800083F3118804EB8507301D0821FFF7A6FEC4 +:10129000FB6806F14C005B691B681BB1019001F013 +:1012A00023FF019803A901F011FF024648B1039BF7 +:1012B0002946204600F098F8002383F3118805B0F2 +:1012C000F0BDFB685A691268002AF5D01B8A013B01 +:1012D0001340F1D104F18002EAE70000133138B580 +:1012E00050F82140ECB1302383F3118804F580538A +:1012F000D3F8A4281368527903EB8203DB689B6957 +:101300005D6845B104216018FFF768FE294604F1C5 +:10131000140001F011FE2046FFF7B4FE002383F312 +:10132000118838BD7047000001F0C8B80123402281 +:10133000002110B5044600F8303BFFF7B7FD00234D +:10134000C4E9013310BD000010B53023044683F317 +:1013500011882422416000210C30FFF7A7FD2046B0 +:1013600001F0CEF802230020237080F3118810BD15 +:1013700070B500EB8103054650690E461446DA60ED +:1013800018B110220021FFF791FDA06918B11022B9 +:101390000021FFF78BFD31462846BDE8704001F083 +:1013A000B5B9000083682022002103F0011310B5B5 +:1013B000044683601030FFF779FD2046BDE81040F9 +:1013C00001F030BAF0B4012500EB810447898D406B +:1013D000E4683D43A469458123600023A260636003 +:1013E000F0BC01F04DBA0000F0B4012500EB81041F +:1013F00007898D40E4683D436469058123600023CB +:10140000A2606360F0BC01F0C3BA000070B50223B3 +:1014100000250446242203702946C0F888500C3069 +:1014200040F8045CFFF742FD204684F8705001F05C +:1014300001F963681B6823B129462046BDE8704066 +:10144000184770BD0378052B10B504460AD080F804 +:101450008C300523037043681B680BB10421984747 +:101460000023A36010BD00000178052906D190F883 +:101470008C20436802701B6803B118477047000056 +:1014800070B590F87030044613B1002380F87030C6 +:1014900004F18002204601F0E9F963689B68B3B962 +:1014A00094F8803013F0600535D00021204601F01B +:1014B000DBFC0021204601F0CBFC63681B6813B104 +:1014C000062120469847062384F8703070BD2046D8 +:1014D00098470028E4D0B4F88630A26F9A4288BFBB +:1014E000A36794F98030A56F002B4FF0300380F292 +:1014F0000381002D00F0F280092284F8702083F32C +:10150000118800212046D4E91D23FFF76DFF002339 +:1015100083F31188DAE794F8812003F07F0343EA2C +:10152000022340F20232934200F0C58021D8B3F585 +:10153000807F48D00DD8012B3FD0022B00F0938044 +:10154000002BB2D104F1880262670222A267E3672E +:10155000C1E7B3F5817F00F09B80B3F5407FA4D154 +:1015600094F88230012BA0D1B4F8883043F0020304 +:1015700032E0B3F5006F4DD017D8B3F5A06F31D07E +:10158000A3F5C063012B90D86368204694F88220AD +:101590005E6894F88310B4F88430B047002884D093 +:1015A000436863670368A3671AE0B3F5106F36D02A +:1015B00040F6024293427FF478AF5C4B63670223AC +:1015C000A3670023C3E794F88230012B7FF46DAF4B +:1015D000B4F8883023F00203A4F88830C4E91D551C +:1015E000E56778E7B4F88030B3F5A06F0ED194F8D2 +:1015F0008230204684F88A3001F07AF863681B68EC +:1016000013B1012120469847032323700023C4E926 +:101610001D339CE704F18B0363670123C3E7237841 +:10162000042B10D1302383F311882046FFF7BAFE34 +:1016300085F311880321636884F88B5021701B683F +:101640000BB12046984794F88230002BDED084F806 +:101650008B300423237063681B68002BD6D00221D3 +:1016600020469847D2E794F8843020461D0603F0C0 +:101670000F010AD501F0ECF8012804D002287FF40C +:1016800014AF2B4B9AE72B4B98E701F0D3F8F3E715 +:1016900094F88230002B7FF408AF94F8843013F074 +:1016A0000F01B3D01A06204602D501F0F5FBADE7D5 +:1016B00001F0E6FBAAE794F88230002B7FF4F5AE48 +:1016C00094F8843013F00F01A0D01B06204602D5F9 +:1016D00001F0CAFB9AE701F0BBFB97E7142284F8FC +:1016E000702083F311882B462A4629462046FFF7AF +:1016F00069FE85F31188E9E65DB1152284F8702052 +:1017000083F3118800212046D4E91D23FFF75AFEF8 +:10171000FDE60B2284F8702083F311882B462A46BD +:1017200029462046FFF760FEE3E700BF903B000834 +:10173000883B00088C3B000838B590F870300446B0 +:10174000002B3ED0063BDAB20F2A34D80F2B32D80A +:10175000DFE803F0373131082232313131313131B4 +:1017600031313737856FB0F886309D4214D2C36867 +:101770001B8AB5FBF3F203FB12556DB9302383F3DB +:1017800011882B462A462946FFF72EFE85F311883D +:101790000A2384F870300EE0142384F8703030236C +:1017A00083F31188002320461A461946FFF70AFEE4 +:1017B000002383F3118838BDC36F03B1984700231A +:1017C000E7E70021204601F04FFB0021204601F011 +:1017D0003FFB63681B6813B1062120469847062328 +:1017E000D7E7000010B590F870300446142B29D0CC +:1017F00017D8062B05D001D81BB110BD093B022B11 +:10180000FBD80021204601F02FFB0021204601F0EB +:101810001FFB63681B6813B1062120469847062307 +:1018200019E0152BE9D10B2380F87030302383F3B6 +:10183000118800231A461946FFF7D6FD002383F3CB +:101840001188DAE7C3689B695B68002BD5D1C36F49 +:1018500003B19847002384F87030CEE700238268F4 +:10186000037503691B6899689142FBD25A6803604B +:1018700042601060586070470023826803750369F6 +:101880001B6899689142FBD85A68036042601060F7 +:101890005860704708B50846302383F311880B7DE4 +:1018A000032B05D0042B0DD02BB983F3118808BD71 +:1018B0008B6900221A604FF0FF338361FFF7CEFF80 +:1018C0000023F2E7D1E9003213605A60F3E7000029 +:1018D000FFF7C4BF054BD9680875186802685360E4 +:1018E0001A600122D8600275FEF78CBDB823002073 +:1018F0000C4B30B5DD684B1C87B004460FD02B462F +:10190000094A684600F04EF92046FFF7E3FF009BC6 +:1019100013B1684600F050F9A86907B030BDFFF771 +:10192000D9FFF9E7B823002095180008044B1A687E +:10193000DB6890689B68984294BF00200120704744 +:10194000B8230020084B10B51C68D8682268536083 +:101950001A600122DC602275FFF78EFF01462046E7 +:10196000BDE81040FEF74EBDB823002038B5074C47 +:1019700001230025064907482370656001F098FCA3 +:101980000223237085F3118838BD00BF2026002074 +:10199000983B0008B823002000F044B9034A51687E +:1019A00053685B1A9842FBD8704700BF001000E0F4 +:1019B0008B600223086108468B8270478368A3F11D +:1019C000840243F8142C026943F8442C426943F81A +:1019D000402C094A43F8242CC268A3F1200043F8A4 +:1019E000182C022203F80C2C002203F80B2C034ABB +:1019F00043F8102C704700BF1D040008B8230020D6 +:101A000008B5FFF7DBFFBDE80840FFF761BF000046 +:101A1000024BDB6898610F20FFF75CBFB823002002 +:101A2000302383F31188FFF7F3BF000008B50146A8 +:101A3000302383F311880820FFF75AFF002383F334 +:101A4000118808BD064BDB6839B1426818605A60DE +:101A5000136043600420FFF74BBF4FF0FF30704727 +:101A6000B82300200368984206D01A6802605060CC +:101A700018469961FFF72CBF7047000038B504463F +:101A80000D462068844200D138BD036823605C6045 +:101A90008561FFF71DFFF4E7036810B59C68A2425B +:101AA0000CD85C688A600B604C6021605960996852 +:101AB0008A1A9A604FF0FF33836010BD121B1B68B7 +:101AC000ECE700000A2938BF0A2170B504460D462C +:101AD0000A26601901F0E4FB01F0CCFB041BA542CF +:101AE00003D8751C04462E46F3E70A2E04D90120BC +:101AF000BDE8704001F01CBC70BD0000F8B5144B8F +:101B00000D460A2A4FF00A07D96103F110018260DD +:101B100038BF0A22416019691446016048601861A3 +:101B2000A81801F0ADFB01F0A5FB431B0646A3423C +:101B300006D37C1C28192746354601F0B1FBF2E795 +:101B40000A2F04D90120BDE8F84001F0F1BBF8BD2F +:101B5000B8230020F8B506460D4601F08BFB0F4A6E +:101B6000134653F8107F9F4206D12A46014630465D +:101B7000BDE8F840FFF7C2BFD169BB68441A2C1911 +:101B800028BF2C46A34202D92946FFF79BFF2246D5 +:101B900031460348BDE8F840FFF77EBFB823002078 +:101BA000C8230020C0E90323002310B45DF8044BD0 +:101BB0004361FFF7CFBF000010B5194C236998426D +:101BC0000DD08168D0E9003213605A609A680A44E7 +:101BD0009A60002303604FF0FF33A36110BD0268D9 +:101BE000234643F8102F53600022026022699A4274 +:101BF00003D1BDE8104001F04DBB936881680B44F0 +:101C0000936001F037FB2269E1699268441AA242AD +:101C1000E4D91144BDE81040091AFFF753BF00BFD3 +:101C2000B82300202DE9F047DFF8BC8008F1100749 +:101C30002C4ED8F8105001F01DFBD8F81C40AA68B3 +:101C4000031B9A423ED814444FF00009D5E90032F4 +:101C5000C8F81C4013605A60C5F80090D8F81030DE +:101C6000B34201D101F016FB89F31188D5E90331A4 +:101C700028469847302383F311886B69002BD8D00E +:101C800001F0F8FA6A69A0EB040982464A450DD2D0 +:101C9000022001F04DFB0022D8F81030B34208D1E9 +:101CA00051462846BDE8F047FFF728BF121A2244E4 +:101CB000F2E712EB09092946384638BF4A46FFF7D2 +:101CC000EBFEB5E7D8F81030B34208D01444C8F89A +:101CD0001C00211AA960BDE8F047FFF7F3BEBDE87C +:101CE000F08700BFC8230020B823002000207047E1 +:101CF000FEE70000704700004FF0FF307047000023 +:101D000002290CD0032904D00129074818BF00205C +:101D10007047032A05D8054800EBC2007047044805 +:101D200070470020704700BF703C00083C22002034 +:101D3000243C000870B59AB005460846144601A92F +:101D400000F0C2F801A8FFF7A9F8431C0022C6B2B0 +:101D50005B001046C5E9003423700323023404F805 +:101D6000013C01ABD1B202348E4201D81AB070BD31 +:101D700013F8011B013204F8010C04F8021CF1E70E +:101D800008B5302383F311880348FFF749FA00238D +:101D900083F3118808BD00BF2826002090F880300A +:101DA00003F01F02012A07D190F881200B2A03D1EA +:101DB0000023C0E91D3315E003F06003202B08D198 +:101DC000B0F884302BB990F88120212A03D81F2A3B +:101DD00004D8FFF707BA222AEBD0FAE7034A426792 +:101DE00007228267C3670120704700BF33220020AB +:101DF00007B5052917D8DFE801F0191603191920CE +:101E0000302383F31188104A01210190FFF7B0FAC3 +:101E1000019802210D4AFFF7ABFA0D48FFF7CCF904 +:101E2000002383F3118803B05DF804FB302383F3B0 +:101E300011880748FFF796F9F2E7302383F31188FA +:101E40000348FFF7ADF9EBE7C43B0008E83B0008A7 +:101E50002826002038B50C4D0C4C2A460C4904F1BC +:101E60000800FFF767FF05F1CA0204F110000949F5 +:101E7000FFF760FF05F5CA7204F118000649BDE8D6 +:101E80003840FFF757BF00BF003F00203C22002032 +:101E9000A43B0008AE3B0008B93B000870B50446FF +:101EA00008460D46FEF7FAFFC6B220460134037815 +:101EB0000BB9184670BD32462946FEF7DBFF0028F5 +:101EC000F3D10120F6E700002DE9F04705460C4666 +:101ED000FEF7E4FF2B49C6B22846FFF7DFFF08B143 +:101EE0000B36F6B228492846FFF7D8FF08B110365E +:101EF000F6B2632E0BD8DFF88C80DFF88C90234F7E +:101F0000DFF894A02E7846B92670BDE8F087294600 +:101F10002046BDE8F04701F0FDBD252E2ED1072259 +:101F200041462846FEF7A6FF70B9194B224603F139 +:101F3000100153F8040B8B4242F8040BF9D11B88B3 +:101F4000073512341380DDE7082249462846FEF79C +:101F500091FF98B9A21C0F4B197802320909C95D8B +:101F600002F8041C13F8011B01F00F015345C95D71 +:101F700002F8031CF0D118340835C3E7013504F822 +:101F8000016BBFE7903C0008B93B0008AB3C000880 +:101F9000983C000800E8F11F0CE8F11FBFF34F8FD9 +:101FA000044B1A695107FCD1D3F810215207F8D11C +:101FB000704700BF0020005208B50D4B1B78ABB92D +:101FC000FFF7ECFF0B4BDA68D10704D50A4A5A60D9 +:101FD00002F188325A60D3F80C21D20706D5064A9E +:101FE000C3F8042102F18832C3F8042108BD00BF00 +:101FF0005E410020002000522301674508B5114BC7 +:102000001B78F3B9104B1A69510703D5DA6842F00F +:102010004002DA60D3F81021520705D5D3F80C211D +:1020200042F04002C3F80C21FFF7B8FF064BDA6814 +:1020300042F00102DA60D3F80C2142F00102C3F849 +:102040000C2108BD5E410020002000520F289ABFDD +:1020500000F5806040040020704700004FF400301D +:1020600070470000102070470F2808B50BD8FFF705 +:10207000EDFF00F500330268013204D104308342E1 +:10208000F9D1012008BD0020FCE700000F2838B579 +:1020900005463FD8FFF782FF1F4CFFF78DFF4FF03B +:1020A000FF3307286361C4F814311DD82361FFF79B +:1020B00075FF030243F02403E360E36843F0800309 +:1020C000E36023695A07FCD42846FFF767FFFFF750 +:1020D000BDFF4FF4003100F0F5F82846FFF78EFF02 +:1020E000BDE83840FFF7C0BFC4F81031FFF756FF16 +:1020F000A0F108031B0243F02403C4F80C31D4F808 +:102100000C3143F08003C4F80C31D4F810315B0774 +:10211000FBD4D9E7002038BD002000522DE9F84F4C +:1021200005460C46104645EA0203DE0602D00020B2 +:10213000BDE8F88F20F01F00DFF8BCB0DFF8BCA0CE +:10214000FFF73AFF04EB0008444503D10120FFF7F5 +:1021500055FFEDE720222946204601F0CBFC10B9BF +:1021600020352034F0E72B4605F120021F68791C4A +:10217000DDD104339A42F9D105F178431B481C4E56 +:10218000B3F5801F1B4B38BF184603F1F80332BF6D +:10219000D946D1461E46FFF701FF0760A5EB040CA8 +:1021A000336804F11C0143F002033360231FD9F8A4 +:1021B000007017F00507FAD153F8042F8B424CF842 +:1021C0000320F4D1BFF34F8FFFF7E8FE4FF0FF334A +:1021D0002022214603602846336823F0020333603F +:1021E00001F088FC0028BBD03846B0E7142100522B +:1021F0000C200052142000521020005210210052D6 +:1022000010B5084C237828B11BB9FFF7D5FE012380 +:10221000237010BD002BFCD02070BDE81040FFF7EC +:10222000EDBE00BF5E4100200244074BD2B210B5A4 +:10223000904200D110BD441C00B253F8200041F878 +:10224000040BE0B2F4E700BF504000580E4B30B52D +:102250001C6F240405D41C6F1C671C6F44F40044DD +:102260001C670A4C02442368D2B243F48073236093 +:10227000074B904200D130BD441C51F8045B00B2C2 +:1022800043F82050E0B2F4E70044025800480258F6 +:102290005040005807B5012201A90020FFF7C4FFF4 +:1022A000019803B05DF804FB13B50446FFF7F2FF95 +:1022B000A04205D0012201A900200194FFF7C6FF2A +:1022C00002B010BD0144BFF34F8F064B884204D3C8 +:1022D000BFF34F8FBFF36F8F7047C3F85C0220309E +:1022E000F4E700BF00ED00E0034B1A681AB9034A97 +:1022F000D2F8D0241A607047604100200040025894 +:1023000008B5FFF7F1FF024B1868C0F3806008BD05 +:102310006041002070B5BFF34F8FBFF36F8F1A4A33 +:102320000021C2F85012BFF34F8FBFF36F8F536974 +:1023300043F400335361BFF34F8FBFF36F8FC2F885 +:102340008410BFF34F8FD2F8803043F6E074C3F3AC +:10235000C900C3F34E335B0103EA0406014646EAB3 +:1023600081750139C2F86052F9D2203B13F1200F78 +:10237000F2D1BFF34F8F536943F480335361BFF3FE +:102380004F8FBFF36F8F70BD00ED00E0FEE70000E0 +:10239000214B2248224A70B5904237D3214BC11EAF +:1023A000DA1C121A22F003028B4238BF00220021ED +:1023B000FEF77CFD1C4A0023C2F88430BFF34F8F28 +:1023C000D2F8803043F6E074C3F3C900C3F34E3350 +:1023D0005B0103EA0406014646EA81750139C2F849 +:1023E0006C52F9D2203B13F1200FF2D1BFF34F8F83 +:1023F000BFF36F8FBFF34F8FBFF36F8F0023C2F810 +:102400005032BFF34F8FBFF36F8F70BD53F8041B73 +:1024100040F8041BC0E700BF943E0008344300208E +:10242000344300203443002000ED00E0074BD3F894 +:10243000D81021EA0001C3F8D810D3F8002122EA0D +:102440000002C3F80021D3F800317047004402585D +:1024500070B5D0E9244300224FF0FF359E6804EBAD +:1024600042135101D3F80009002805DAD3F8000916 +:1024700040F08040C3F80009D3F8000B002805DACB +:10248000D3F8000B40F08040C3F8000B0132631812 +:102490009642C3F80859C3F8085BE0D24FF0011325 +:1024A000C4F81C3870BD0000890141F020010161B1 +:1024B00003699B06FCD41220FFF770BA10B50A4CD2 +:1024C0002046FEF733FF094BC4F89030084BC4F8A0 +:1024D0009430084C2046FEF729FF074BC4F8903093 +:1024E000064BC4F8943010BD644100200000084041 +:1024F000E03C00080042002000000440EC3C0008E2 +:1025000070B503780546012B5CD1434BD0F8904061 +:10251000984258D1414B0E216520D3F8D82042F083 +:102520000062C3F8D820D3F8002142F00062C3F85B +:102530000021D3F80021D3F8802042F00062C3F8D4 +:102540008020D3F8802022F00062C3F88020D3F8E6 +:10255000803000F0ADFC324BE360324BC4F8003801 +:102560000023D5F89060C4F8003EC02323604FF4E8 +:102570000413A3633369002BFCDA01230C203361BD +:10258000FFF70CFA3369DB07FCD41220FFF706FAD9 +:102590003369002BFCDA00262846A660FFF758FFB7 +:1025A0006B68C4F81068DB68C4F81468C4F81C6869 +:1025B00083BB1D4BA3614FF0FF336361A36843F0FE +:1025C0000103A36070BD194B9842C9D1134B4FF062 +:1025D0008060D3F8D82042F00072C3F8D820D3F836 +:1025E000002142F00072C3F80021D3F80021D3F893 +:1025F000802042F00072C3F88020D3F8802022F0BF +:102600000072C3F88020D3F88030FFF70FFF0E214F +:102610004D209EE7064BCDE7644100200044025860 +:102620004014004003002002003C30C00042002063 +:10263000083C30C0F8B5D0F89040054600214FF076 +:1026400000662046FFF730FFD5F8941000234FF0C6 +:1026500001128F684FF0FF30C4F83438C4F81C28DA +:1026600004EB431201339F42C2F80069C2F8006BC9 +:10267000C2F80809C2F8080BF2D20B68D5F890200E +:10268000C5F89830636210231361166916F01006BE +:10269000FBD11220FFF782F9D4F8003823F4FE634F +:1026A000C4F80038A36943F4402343F01003A36146 +:1026B0000923C4F81038C4F814380B4BEB604FF002 +:1026C000C043C4F8103B094BC4F8003BC4F8106980 +:1026D000C4F80039D5F8983003F1100243F48013A0 +:1026E000C5F89820A362F8BDBC3C000840800010EB +:1026F000D0F8902090F88A10D2F8003823F4FE63C6 +:1027000043EA0113C2F80038704700002DE9F8438E +:1027100000EB8103D0F890500C468046DA680FFA3F +:1027200081F94801166806F00306731E022B05EBBB +:1027300041134FF0000194BFB604384EC3F8101B8C +:102740004FF0010104F1100398BF06F1805601FA21 +:1027500003F3916998BF06F5004600293AD0578ADD +:1027600004F15801374349016F50D5F81C180B4349 +:102770000021C5F81C382B180127C3F81019A740F1 +:102780005369611E9BB3138A928B9B08012A88BFF1 +:102790005343D8F89820981842EA034301F14002C5 +:1027A0002146C8F89800284605EB82025360FFF7DF +:1027B0007BFE08EB8900C3681B8A43EA84534834D4 +:1027C0001E4364012E51D5F81C381F43C5F81C78F0 +:1027D000BDE8F88305EB4917D7F8001B21F4004149 +:1027E000C7F8001BD5F81C1821EA0303C0E704F161 +:1027F0003F030B4A2846214605EB83035A60FFF747 +:1028000053FE05EB4910D0F8003923F40043C0F81B +:102810000039D5F81C3823EA0707D7E700800010F5 +:1028200000040002D0F894201268C0F89820FFF746 +:102830000FBE00005831D0F8903049015B5813F4B6 +:10284000004004D013F4001F0CBF02200120704789 +:102850004831D0F8903049015B5813F4004004D05F +:1028600013F4001F0CBF02200120704700EB810110 +:10287000CB68196A0B6813604B685360704700009F +:1028800000EB810330B5DD68AA691368D36019B91C +:10289000402B84BF402313606B8A1468D0F89020CB +:1028A0001C4402EB4110013C09B2B4FBF3F4634356 +:1028B000033323F0030343EAC44343F0C043C0F8A7 +:1028C000103B2B6803F00303012B0ED1D2F808381C +:1028D00002EB411013F4807FD0F8003B14BF43F0AB +:1028E000805343F00053C0F8003B02EB4112D2F892 +:1028F000003B43F00443C2F8003B30BD2DE9F041FA +:10290000D0F8906005460C4606EB4113D3F8087BDF +:102910003A07C3F8087B08D5D6F814381B0704D546 +:1029200000EB8103DB685B689847FA071FD5D6F890 +:102930001438DB071BD505EB8403D968CCB98B6948 +:10294000488A5A68B2FBF0F600FB16228AB918686A +:10295000DA6890420DD2121AC3E90024302383F3BF +:10296000118821462846FFF78BFF84F31188BDE8C4 +:10297000F081012303FA04F26B8923EA02036B81DD +:10298000CB68002BF3D021462846BDE8F04118471C +:1029900000EB81034A0170B5DD68D0F890306C69B6 +:1029A0002668E66056BB1A444FF40020C2F81009AE +:1029B0002A6802F00302012A0AB20ED1D3F80808ED +:1029C00003EB421410F4807FD4F8000914BF40F0E8 +:1029D000805040F00050C4F8000903EB4212D2F8D6 +:1029E000000940F00440C2F800090122D3F834087D +:1029F00002FA01F10143C3F8341870BD19B9402E31 +:102A000084BF4020206020681A442E8A8419013C2B +:102A1000B4FBF6F440EAC44040F00050C6E70000C2 +:102A20002DE9F843D0F8906005460C464F0106EBBF +:102A30004113D3F8088918F0010FC3F808891CD096 +:102A4000D6F81038DB0718D500EB8103D3F80CC09B +:102A5000DCF81430D3F800E0DA68964530D2A2EB07 +:102A60000E024FF000091A60C3F80490302383F37C +:102A70001188FFF78DFF89F3118818F0800F1DD0A2 +:102A8000D6F834380126A640334217D005EB84032C +:102A90000134D5F89050D3F80CC0E4B22F44DCF8E0 +:102AA000142005EB0434D2F800E05168714514D3CA +:102AB000D5F8343823EA0606C5F83468BDE8F8834B +:102AC000012303FA01F2038923EA02030381DCF8FC +:102AD0000830002BD1D09847CFE7AEEB0103BCF80C +:102AE0001000834228BF0346D7F8180980B2B3EB21 +:102AF000800FE3D89068A0F1040959F8048FC4F856 +:102B00000080A0EB09089844B8F1040FF5D81844E8 +:102B10000B4490605360C8E72DE9F84FD0F890500F +:102B200004466E69AB691E4016F480586E6103D08E +:102B3000BDE8F84FFEF76ABC002E12DAD5F8003E69 +:102B40009B0705D0D5F8003E23F00303C5F8003EEF +:102B5000D5F80438204623F00103C5F80438FEF701 +:102B600083FC370505D52046FFF772FC2046FEF7AB +:102B700069FCB0040CD5D5F8083813F0060FEB68E3 +:102B800023F470530CBF43F4105343F4A053EB6091 +:102B900031071BD56368DB681BB9AB6923F00803F9 +:102BA000AB612378052B0CD1D5F8003E9A0705D0F0 +:102BB000D5F8003E23F00303C5F8003E2046FEF79B +:102BC00053FC6368DB680BB120469847F30200F1C1 +:102BD000BA80B70226D5D4F8909000274FF0010AAA +:102BE00009EB4712D2F8003B03F44023B3F5802FE2 +:102BF00011D1D2F8003B002B0DDA62890AFA07F3F3 +:102C000022EA0303638104EB8703DB68DB6813B10B +:102C10003946204698470137D4F89430FFB29B6874 +:102C20009F42DDD9F00619D5D4F89000026AC2F3AC +:102C30000A1702F00F0302F4F012B2F5802F00F031 +:102C4000CA80B2F5402F09D104EB8303002200F5BE +:102C50008050DB681B6A974240F0B0803003D5F8A3 +:102C6000185835D5E90303D500212046FFF746FE65 +:102C7000AA0303D501212046FFF740FE6B0303D5CD +:102C800002212046FFF73AFE2F0303D503212046F9 +:102C9000FFF734FEE80203D504212046FFF72EFE9D +:102CA000A90203D505212046FFF728FE6A0203D5B5 +:102CB00006212046FFF722FE2B0203D507212046DE +:102CC000FFF71CFEEF0103D508212046FFF716FE93 +:102CD000700340F1A780E90703D500212046FFF7E4 +:102CE0009FFEAA0703D501212046FFF799FE6B0737 +:102CF00003D502212046FFF793FE2F0703D50321BA +:102D00002046FFF78DFEEE0603D504212046FFF78F +:102D100087FEA80603D505212046FFF781FE690638 +:102D200003D506212046FFF77BFE2A0603D507219F +:102D30002046FFF775FEEB0574D520460821BDE857 +:102D4000F84FFFF76DBED4F890904FF0000B4FF0A6 +:102D5000010AD4F894305FFA8BF79B689F423FF6E4 +:102D600038AF09EB4713D3F8002902F44022B2F53B +:102D7000802F20D1D3F80029002A1CDAD3F80029AB +:102D800042F09042C3F80029D3F80029002AFBDB67 +:102D90003946D4F89000FFF787FB22890AFA07F337 +:102DA00022EA0303238104EB8703DB689B6813B1EA +:102DB0003946204698470BF1010BCAE7910701D12C +:102DC000D0F80080072A02F101029CBF03F8018BB2 +:102DD0004FEA18283FE704EB830300F58050DA68D8 +:102DE000D2F818C0DCF80820DCE9001CA1EB0C0CC0 +:102DF00000218F4208D1DB689B699A683A449A6047 +:102E00005A683A445A6029E711F0030F01D1D0F80B +:102E100000808C4501F1010184BF02F8018B4FEA6B +:102E20001828E6E7BDE8F88F08B50348FFF774FEF9 +:102E3000BDE8084000F07ABB6441002008B50348B3 +:102E4000FFF76AFEBDE8084000F070BB00420020BA +:102E5000D0F8903003EB4111D1F8003B43F400135C +:102E6000C1F8003B70470000D0F8903003EB4111EF +:102E7000D1F8003943F40013C1F80039704700005D +:102E8000D0F8903003EB4111D1F8003B23F400134C +:102E9000C1F8003B70470000D0F8903003EB4111BF +:102EA000D1F8003923F40013C1F80039704700004D +:102EB000090100F16043012203F56143C9B283F8BF +:102EC000001300F01F039A4043099B0003F1604385 +:102ED00003F56143C3F880211A60704730B50433AD +:102EE000039C0172002104FB0325C160C0E9065365 +:102EF000049B0363059BC0E90000C0E90422C0E90C +:102F00000842C0E90A11436330BD00000022416A53 +:102F1000C260C0E90411C0E90A226FF00101FEF7A6 +:102F2000ADBD0000D0E90432934201D1C2680AB9B4 +:102F3000181D704700207047036919600021C2689E +:102F40000132C260C269134482699342036124BFA3 +:102F5000436A0361FEF786BD38B504460D46E36853 +:102F60003BB162690020131D1268A3621344E3623F +:102F700007E0237A33B929462046FEF763FD00288F +:102F8000EDDA38BD6FF00100FBE70000C368C269ED +:102F9000013BC3604369134482699342436124BF88 +:102FA000436A436100238362036B03B11847704790 +:102FB00070B53023044683F31188866A3EB9FFF763 +:102FC000CBFF054618B186F31188284670BDA36A69 +:102FD000E26A13F8015B9342A36202D32046FFF733 +:102FE000D5FF002383F31188EFE700002DE9F84FA8 +:102FF00004460E46174698464FF0300989F311886B +:103000000025AA46D4F828B0BBF1000F09D14146EB +:103010002046FFF7A1FF20B18BF311882846BDE8B9 +:10302000F88FD4E90A12A7EB050B521A934528BF73 +:103030009346BBF1400F1BD9334601F1400251F8D2 +:10304000040B914243F8040BF9D1A36A4036403592 +:103050004033A362D4E90A239A4202D32046FFF701 +:1030600095FF8AF31188BD42D8D289F31188C9E748 +:1030700030465A46FDF7F4FEA36A5E445D445B4465 +:10308000A362E7E710B5029C0433017203FB04213D +:10309000C460C0E906130023C0E90A33039B03633D +:1030A000049BC0E90000C0E90422C0E90842436370 +:1030B00010BD0000026A6FF00101C260426AC0E9FF +:1030C00004220022C0E90A22FEF7D8BCD0E904237A +:1030D0009A4201D1C26822B9184650F8043B0B60ED +:1030E000704700231846FAE7C3680021C26901331C +:1030F000C3604369134482699342436124BF436AB6 +:103100004361FEF7AFBC000038B504460D46E368E6 +:103110003BB1236900201A1DA262E2691344E362F5 +:1031200007E0237A33B929462046FEF78BFC0028B6 +:10313000EDDA38BD6FF00100FBE7000003691960AC +:10314000C268013AC260C269134482699342036152 +:1031500024BF436A036100238362036B03B11847F2 +:103160007047000070B530230D460446114683F3C6 +:103170001188866A2EB9FFF7C7FF10B186F3118850 +:1031800070BDA36A1D70A36AE26A01339342A36211 +:1031900004D3E16920460439FFF7D0FF002080F313 +:1031A0001188EDE72DE9F84F04460D469046994603 +:1031B0004FF0300A8AF311880026B346A76A4FB948 +:1031C00049462046FFF7A0FF20B187F3118830461B +:1031D000BDE8F88FD4E90A073A1AA8EB0607974228 +:1031E00028BF1746402F1BD905F1400355F8042B83 +:1031F0009D4240F8042BF9D1A36A40364033A362C4 +:10320000D4E90A239A4204D3E16920460439FFF73E +:1032100095FF8BF311884645D9D28AF31188CDE703 +:1032200029463A46FDF71CFEA36A3D443E443B4412 +:10323000A362E5E7D0E904239A4217D1C3689BB1A2 +:10324000836A8BB1043B9B1A0ED01360C368013BA9 +:10325000C360C3691A4483699A42026124BF436A06 +:103260000361002383620123184670470023FBE7B4 +:1032700000F086B9014B586A704700BF000C00404F +:10328000034B002258631A610222DA60704700BFC4 +:10329000000C0040014B0022DA607047000C004037 +:1032A000014B5863704700BF000C0040FEE7000070 +:1032B00070B51B4B0025044686B058600E468562EB +:1032C000016300F00BF904F11003A560E562C4E9A5 +:1032D00004334FF0FF33C4E90044C4E90635FFF777 +:1032E000C9FF2B46024604F134012046C4E90823F5 +:1032F00080230C4A2565FEF75BFB01230A4AE06048 +:1033000000920375684672680192B268CDE90223A3 +:10331000064BCDE90435FEF773FB06B070BD00BF68 +:1033200020260020F83C0008FD3C0008AD320008D3 +:10333000024AD36A1843D062704700BFB823002006 +:103340004B6843608B688360CB68C3600B694361E3 +:103350004B6903628B6943620B680360704700002E +:1033600008B53C4B40F2FF713B48D3F888200A4334 +:10337000C3F88820D3F8882022F4FF6222F00702E5 +:10338000C3F88820D3F88820D3F8E0200A43C3F894 +:10339000E020D3F808210A43C3F808212F4AD3F8C4 +:1033A00008311146FFF7CCFF00F5806002F11C01E7 +:1033B000FFF7C6FF00F5806002F13801FFF7C0FF9C +:1033C00000F5806002F15401FFF7BAFF00F580605C +:1033D00002F17001FFF7B4FF00F5806002F18C018B +:1033E000FFF7AEFF00F5806002F1A801FFF7A8FF2C +:1033F00000F5806002F1C401FFF7A2FF00F58060D4 +:1034000002F1E001FFF79CFF00F5806002F1FC0192 +:10341000FFF796FF02F58C7100F58060FFF790FFD3 +:1034200000F076F90E4BD3F8902242F00102C3F877 +:103430009022D3F8942242F00102C3F8942205228C +:10344000C3F898204FF06052C3F89C20054AC3F897 +:10345000A02008BD0044025800000258043D0008A6 +:1034600000ED00E01F00080308B500F025FBFEF7A3 +:103470007DFA0F4BD3F8DC2042F04002C3F8DC2089 +:10348000D3F8042122F04002C3F80421D3F8043118 +:10349000084B1A6842F008021A601A6842F00402E7 +:1034A0001A60FEF721FFBDE80840FEF7D3BC00BF5D +:1034B000004402580018024870470000EFF30983E7 +:1034C000054968334A6B22F001024A6383F3098895 +:1034D000002383F31188704700EF00E0302080F371 +:1034E000118862B60D4B0E4AD96821F4E0610904D7 +:1034F000090C0A430B49DA60D3F8FC2042F08072D1 +:10350000C3F8FC20084AC2F8B01F116841F001015D +:1035100011602022DA7783F82200704700ED00E086 +:103520000003FA0555CEACC5001000E0302310B5FD +:1035300083F311880E4B5B6813F4006314D0F1EE33 +:10354000103AEFF309844FF08073683CE361094B54 +:10355000DB6B236684F30988FEF7E8F910B1064BAC +:10356000A36110BD054BFBE783F31188F9E700BFAA +:1035700000ED00E000EF00E02F0400083204000836 +:10358000114BD3F8E82042F00802C3F8E820D3F842 +:10359000102142F00802C3F810210C4AD3F8103170 +:1035A000D36B43F00803D363C722094B9A624FF0F1 +:1035B000FF32DA6200229A615A63DA605A600122AD +:1035C0005A611A60704700BF004402580010005C46 +:1035D000000C0040094A08B51169D3680B40D9B204 +:1035E0009B076FEA0101116107D5302383F311882E +:1035F000FEF7D2F9002383F3118808BD000C0040C8 +:10360000064BD3F8DC200243C3F8DC20D3F80421B6 +:103610001043C3F80401D3F8043170470044025842 +:103620003A4B4FF0FF31D3F8802062F00042C3F8EC +:103630008020D3F8802002F00042C3F88020D3F825 +:103640008020D3F88420C3F88410D3F8842000228B +:10365000C3F88420D3F88400D86F40F0FF4040F4D2 +:10366000FF0040F4DF4040F07F00D867D86F20F0C3 +:10367000FF4020F4FF0020F4DF4020F07F00D867F7 +:10368000D86FD3F888006FEA40506FEA5050C3F803 +:103690008800D3F88800C0F30A00C3F88800D3F884 +:1036A0008800D3F89000C3F89010D3F89000C3F8C6 +:1036B0009020D3F89000D3F89400C3F89410D3F876 +:1036C0009400C3F89420D3F89400D3F89800C3F87A +:1036D0009810D3F89800C3F89820D3F89800D3F83E +:1036E0008C00C3F88C10D3F88C00C3F88C20D3F86E +:1036F0008C00D3F89C00C3F89C10D3F89C10C3F83E +:103700009C20D3F89C3000F0AFB900BF00440258B1 +:1037100008B50122534BC3F80821534BD3F8F420CA +:1037200042F00202C3F8F420D3F81C2142F0020256 +:10373000C3F81C210222D3F81C314C4BDA605A68C2 +:103740009104FCD54A4A1A6001229A60494ADA601B +:1037500000221A614FF440429A61444B9A699204E4 +:10376000FCD51A6842F480721A603F4B1A6F12F44B +:10377000407F04D04FF480321A6700221A671A681B +:1037800042F001021A60384B1A685007FCD500223B +:103790001A611A6912F03802FBD1012119604FF049 +:1037A000804159605A67344ADA62344A1A611A68A9 +:1037B00042F480321A602C4B1A689103FCD51A68C7 +:1037C00042F480521A601A689204FCD52C4A2D49A2 +:1037D0009A6200225A63196301F57C01DA6301F2EF +:1037E000E71199635A64284A1A64284ADA621A6807 +:1037F00042F0A8521A601C4B1A6802F02852B2F12B +:10380000285FF9D148229A614FF48862DA61402238 +:103810001A621F4ADA641F4A1A651F4A5A651F4A0C +:103820009A6532231E4A1360136803F00F03022BBC +:10383000FAD10D4A136943F003031361136903F0CE +:103840003803182BFAD14FF00050FFF7D9FE4FF094 +:103850008040FFF7D5FE4FF00040BDE80840FFF77D +:10386000CFBE00BF008000510044025800480258FB +:1038700000C000F0020000010000FF010088900875 +:103880001210200063020901470E0508DD0BBF017D +:1038900020000020000001100910E00000010110CC +:1038A000002000524FF0B04208B5D2F8883003F043 +:1038B0000103C2F8883023B1044A13680BB1506881 +:1038C0009847BDE80840FFF731BE00BFB442002072 +:1038D0004FF0B04208B5D2F8883003F00203C2F8C6 +:1038E000883023B1044A93680BB1D0689847BDE88B +:1038F0000840FFF71BBE00BFB44200204FF0B042AB +:1039000008B5D2F8883003F00403C2F8883023B138 +:10391000044A13690BB150699847BDE80840FFF7A6 +:1039200005BE00BFB44200204FF0B04208B5D2F847 +:10393000883003F00803C2F8883023B1044A936941 +:103940000BB1D0699847BDE80840FFF7EFBD00BF55 +:10395000B44200204FF0B04208B5D2F8883003F0EE +:103960001003C2F8883023B1044A136A0BB1506ABD +:103970009847BDE80840FFF7D9BD00BFB44200201A +:103980004FF0B04310B5D3F8884004F47872C3F810 +:103990008820A30604D5124A936A0BB1D06A9847CF +:1039A000600604D50E4A136B0BB1506B9847210685 +:1039B00004D50B4A936B0BB1D06B9847E20504D545 +:1039C000074A136C0BB1506C9847A30504D5044A01 +:1039D000936C0BB1D06C9847BDE81040FFF7A6BDC3 +:1039E000B44200204FF0B04310B5D3F8884004F43F +:1039F0007C42C3F88820620504D5164A136D0BB1CA +:103A0000506D9847230504D5124A936D0BB1D06DC4 +:103A10009847E00404D50F4A136E0BB1506E9847D7 +:103A2000A10404D50B4A936E0BB1D06E9847620483 +:103A300004D5084A136F0BB1506F9847230404D57F +:103A4000044A936F0BB1D06F9847BDE81040FFF761 +:103A50006DBD00BFB442002008B5FFF7BBFDBDE857 +:103A60000840FFF763BD0000062108B50846FFF7D0 +:103A70001FFA06210720FFF71BFA06210820FFF78F +:103A800017FA06210920FFF713FA06210A20FFF78B +:103A90000FFA06211720FFF70BFA06212820FFF75F +:103AA00007FA09217A20FFF703FA07213220BDE83F +:103AB0000840FFF7FDB9000008B5FFF7B1FD00F0C1 +:103AC0000BF8FDF731FCFDF703FBFFF7F5FCBDE854 +:103AD0000840FFF7CDBB00000023054A194601331B +:103AE000102BC2E9001102F10802F8D1704700BFA3 +:103AF000B442002010B501390244904201D10020A7 +:103B000005E0037811F8014FA34201D0181B10BD46 +:103B10000130F2E7034611F8012B03F8012B002ACC +:103B2000F9D1704753544D333248373F3F3F00532C +:103B3000544D3332483733782F3732780053544D51 +:103B40003332483734332F3735332F373530000091 +:103B500001105A000310590001205800032056009C +:103B6000000000004D100008391000087510000812 +:103B7000611000086D100008591000084510000879 +:103B80003110000881100008000000000100000052 +:103B90000000000063300000943B00081024002067 +:103BA000202600204172647550696C6F74002542B4 +:103BB0004F415244252D424C002553455249414C1A +:103BC0002500000002000000000000006D12000847 +:103BD000DD12000840004000D03E0020E03E002002 +:103BE00002000000000000000300000000000000D0 +:103BF000251300080000000010000000F03E002027 +:103C000000000000010000000000000064410020EE +:103C100001010200F11D0008011D00089D1D0008A2 +:103C2000811D0008430000002C3C000809024300ED +:103C3000020100C032090400000102020100052453 +:103C400000100105240100010424020205240600DD +:103C500001070582030800FF09040100020A0000B1 +:103C60000007050102400000070581024000000036 +:103C700012000000783C0008120110010200004010 +:103C80000912415700020102030100000403090464 +:103C900025424F4152442500416F636F64612D52AC +:103CA000432D483734334475616C0030313233343E +:103CB000353637383941424344454600000000005C +:103CC0008114000839170008E5170008400040007B +:103CD0009C4200209C42002001000000AC420020D9 +:103CE000800000004001000008000000000100000A +:103CF00000100000080000006D61696E0069646CCE +:103D0000650000000000802A00000000AAAAAAAAFC +:103D100000000024FFFF00000000000000A00A00D7 +:103D20000000000100000000AAAAAAAA00000001E9 +:103D3000FFFF000000000000000000000000004045 +:103D400000000000AAAAAAAA00000040FFFF00008D +:103D50000000000000000000400000000000000023 +:103D6000AAAAAAAA40000000FFFF0000000000006D +:103D7000000000004000400000000000AAAAAAAA1B +:103D800000004000F7FF00000000000000000000FD +:103D90000000000000000000AAAAAAAA000000007B +:103DA000FFFF000000000000000000000000000015 +:103DB00000000000AAAAAAAA00000000FFFF00005D +:103DC00000000000000000000000000000000000F3 +:103DD000AAAAAAAA00000000FFFF0000000000003D +:103DE000000000000000000000000000AAAAAAAA2B +:103DF00000000000FFFF00000000000000000000C5 +:103E00000000000000000000AAAAAAAA000000000A +:103E1000FFFF0000000000000000000000000000A4 +:103E200000000000AAAAAAAA00000000FFFF0000EC +:103E300000000000000000005A1400000000000014 +:103E400000001A0000000000FF0000000000000059 +:103E5000243B0008830400002F3B000850040000AE +:103E60003D3B00080096000000000800960000009E +:103E700000080000040000008C3C00080000000066 +:103E80000000000000000000000000000000000032 +:043E9000000000002E +:00000001FF From 772dbfb04fe3ff83a5bd6b06362d5e50a7a8cace Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Fri, 5 Nov 2021 13:00:51 -0700 Subject: [PATCH 426/499] AP_GPS: SBF supports yaw from dual antennas Co-authored-by: Andrew Tridgell Co-authored-by: Randy Mackay --- libraries/AP_GPS/AP_GPS.cpp | 8 +-- libraries/AP_GPS/AP_GPS.h | 1 + libraries/AP_GPS/AP_GPS_SBF.cpp | 92 ++++++++++++++++++++++++++++++--- libraries/AP_GPS/AP_GPS_SBF.h | 44 +++++++++++++++- 4 files changed, 133 insertions(+), 12 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 0b984bf1df709e..b947175b0bf620 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -129,18 +129,16 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = { // @Param: _TYPE // @DisplayName: 1st GPS type // @Description: GPS type of 1st GPS - // @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover,24:UnicoreNMEA,25:UnicoreMovingBaselineNMEA + // @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover,24:UnicoreNMEA,25:UnicoreMovingBaselineNMEA,26:SBF-DualAntenna // @RebootRequired: True // @User: Advanced AP_GROUPINFO("_TYPE", 0, AP_GPS, _type[0], HAL_GPS_TYPE_DEFAULT), #if GPS_MAX_RECEIVERS > 1 // @Param: _TYPE2 + // @CopyFieldsFrom: GPS_TYPE // @DisplayName: 2nd GPS type // @Description: GPS type of 2nd GPS - // @Values: 0:None,1:AUTO,2:uBlox,5:NMEA,6:SiRF,7:HIL,8:SwiftNav,9:DroneCAN,10:SBF,11:GSOF,13:ERB,14:MAV,15:NOVA,16:HemisphereNMEA,17:uBlox-MovingBaseline-Base,18:uBlox-MovingBaseline-Rover,19:MSP,20:AllyStar,21:ExternalAHRS,22:DroneCAN-MovingBaseline-Base,23:DroneCAN-MovingBaseline-Rover,24:UnicoreNMEA,25:UnicoreMovingBaselineNMEA - // @RebootRequired: True - // @User: Advanced AP_GROUPINFO("_TYPE2", 1, AP_GPS, _type[1], 0), #endif @@ -645,6 +643,7 @@ void AP_GPS::send_blob_start(uint8_t instance) switch (_type[instance]) { #if AP_GPS_SBF_ENABLED case GPS_TYPE_SBF: + case GPS_TYPE_SBF_DUAL_ANTENNA: #endif //AP_GPS_SBF_ENABLED #if AP_GPS_GSOF_ENABLED case GPS_TYPE_GSOF: @@ -806,6 +805,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) #if AP_GPS_SBF_ENABLED // by default the sbf/trimble gps outputs no data on its port, until configured. case GPS_TYPE_SBF: + case GPS_TYPE_SBF_DUAL_ANTENNA: return new AP_GPS_SBF(*this, state[instance], _port[instance]); #endif //AP_GPS_SBF_ENABLED #if AP_GPS_NOVA_ENABLED diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 4b184dcde0a827..eedc1a0c5a43a4 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -131,6 +131,7 @@ class AP_GPS GPS_TYPE_UAVCAN_RTK_ROVER = 23, GPS_TYPE_UNICORE_NMEA = 24, GPS_TYPE_UNICORE_MOVINGBASE_NMEA = 25, + GPS_TYPE_SBF_DUAL_ANTENNA = 26, #if HAL_SIM_GPS_ENABLED GPS_TYPE_SITL = 100, #endif diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index 3b1d8d70095c96..569d5b6910ec4f 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -68,7 +68,10 @@ AP_GPS_SBF::AP_GPS_SBF(AP_GPS &_gps, AP_GPS::GPS_State &_state, // if we ever parse RTK observations it will always be of type NED, so set it once state.rtk_baseline_coords_type = RTK_BASELINE_COORDINATE_SYSTEM_NED; - if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw)) { + + // yaw available when option bit set or using dual antenna + if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw) || + (get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA)) { state.gps_yaw_configured = true; } } @@ -92,9 +95,9 @@ AP_GPS_SBF::read(void) ret |= parse(temp); } + const uint32_t now = AP_HAL::millis(); if (gps._auto_config != AP_GPS::GPS_AUTO_CONFIG_DISABLE) { if (config_step != Config_State::Complete) { - uint32_t now = AP_HAL::millis(); if (now > _init_blob_time) { if (now > _config_last_ack_time + 2000) { const size_t port_enable_len = strlen(_port_enable); @@ -116,9 +119,20 @@ AP_GPS_SBF::read(void) } break; case Config_State::SSO: - if (asprintf(&config_string, "sso,Stream%d,COM%d,PVTGeodetic+DOP+ReceiverStatus+VelCovGeodetic+BaseVectorGeod,msec100\n", + const char *extra_config; + switch (get_type()) { + case AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA: + extra_config = "+AttCovEuler+AuxAntPositions"; + break; + case AP_GPS::GPS_Type::GPS_TYPE_SBF: + default: + extra_config = ""; + break; + } + if (asprintf(&config_string, "sso,Stream%d,COM%d,PVTGeodetic+DOP+ReceiverStatus+VelCovGeodetic+BaseVectorGeod%s,msec100\n", (int)GPS_SBF_STREAM_NUMBER, - (int)gps._com_port[state.instance]) == -1) { + (int)gps._com_port[state.instance], + extra_config) == -1) { config_string = nullptr; } break; @@ -145,6 +159,17 @@ AP_GPS_SBF::read(void) break; } break; + case Config_State::SGA: + { + const char *targetGA = "none"; + if (get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA) { + targetGA = "MultiAntenna"; + } + if (asprintf(&config_string, "sga, %s\n", targetGA)) { + config_string = nullptr; + } + break; + } case Config_State::Complete: // should never reach here, why search for a config if we have fully configured already INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); @@ -168,7 +193,6 @@ AP_GPS_SBF::read(void) } else if (_has_been_armed && (RxState & SBF_DISK_MOUNTED)) { // since init is done at this point and unmounting should be rate limited, // take over the _init_blob_time variable - uint32_t now = AP_HAL::millis(); if (now > _init_blob_time) { unmount_disk(); _init_blob_time = now + 1000; @@ -177,6 +201,12 @@ AP_GPS_SBF::read(void) } } + // yaw timeout after 300 milliseconds + if ((now - state.gps_yaw_time_ms) > 300) { + state.have_gps_yaw = false; + state.have_gps_yaw_accuracy = false; + } + return ret; } @@ -345,9 +375,12 @@ AP_GPS_SBF::parse(uint8_t temp) _init_blob_index++; if ((gps._sbas_mode == AP_GPS::SBAS_Mode::Disabled) ||_init_blob_index >= ARRAY_SIZE(sbas_on_blob)) { - config_step = Config_State::Complete; + config_step = Config_State::SGA; } break; + case Config_State::SGA: + config_step = Config_State::Complete; + break; case Config_State::Complete: // should never reach here, this implies that we validated a config string when we hadn't sent any INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); @@ -500,6 +533,51 @@ AP_GPS_SBF::process_message(void) } break; } + case AttEulerCov: + { + // yaw accuracy is taken from this message even though we actually calculate the yaw ourself (see AuxAntPositions below) + // this is OK based on the assumption that the calculation methods are similar and that inaccuracy arises from the sensor readings + if (get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA) { + const msg5939 &temp = sbf_msg.data.msg5939u; + + check_new_itow(temp.TOW, sbf_msg.length); + + constexpr double floatDNU = -2e-10f; + constexpr uint8_t errorBits = 0x8F; // Bits 0-1 are aux 1 baseline + // Bits 2-3 are aux 2 baseline + // Bit 7 is attitude not requested +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wfloat-equal" // suppress -Wfloat-equal as it's false positive when testing for DNU values + if (((temp.Error & errorBits) == 0) + && (temp.Cov_HeadHead != floatDNU)) { +#pragma GCC diagnostic pop + state.gps_yaw_accuracy = sqrtf(temp.Cov_HeadHead); + state.have_gps_yaw_accuracy = true; + } else { + state.gps_yaw_accuracy = false; + } + } + break; + } + case AuxAntPositions: + { +#if GPS_MOVING_BASELINE + if (get_type() == AP_GPS::GPS_Type::GPS_TYPE_SBF_DUAL_ANTENNA) { + // calculate yaw using reported antenna positions in earth-frame + // note that this calculation does not correct for the vehicle's roll and pitch meaning it is inaccurate at very high lean angles + const msg5942 &temp = sbf_msg.data.msg5942u; + check_new_itow(temp.TOW, sbf_msg.length); + if (temp.N > 0 && temp.ant1.Error == 0 && temp.ant1.AmbiguityType == 0) { + // valid RTK integer fix + const float rel_heading_deg = degrees(atan2f(temp.ant1.DeltaEast, temp.ant1.DeltaNorth)); + calculate_moving_base_yaw(rel_heading_deg, + Vector3f(temp.ant1.DeltaNorth, temp.ant1.DeltaEast, temp.ant1.DeltaUp).length(), + -temp.ant1.DeltaUp); + } + } +#endif + break; + } case BaseVectorGeod: { #pragma GCC diagnostic push @@ -542,7 +620,7 @@ AP_GPS_SBF::process_message(void) } #endif // GPS_MOVING_BASELINE - } else { + } else if (option_set(AP_GPS::DriverOptions::SBF_UseBaseForYaw)) { state.rtk_baseline_y_mm = 0; state.rtk_baseline_x_mm = 0; state.rtk_baseline_z_mm = 0; diff --git a/libraries/AP_GPS/AP_GPS_SBF.h b/libraries/AP_GPS/AP_GPS_SBF.h index 2d8d47baafc500..e8773cf42cdefc 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.h +++ b/libraries/AP_GPS/AP_GPS_SBF.h @@ -75,6 +75,7 @@ class AP_GPS_SBF : public AP_GPS_Backend SSO, Blob, SBAS, + SGA, Complete }; Config_State config_step; @@ -111,7 +112,9 @@ class AP_GPS_SBF : public AP_GPS_Backend PVTGeodetic = 4007, ReceiverStatus = 4014, BaseVectorGeod = 4028, - VelCovGeodetic = 5908 + VelCovGeodetic = 5908, + AttEulerCov = 5939, + AuxAntPositions = 5942, }; struct PACKED msg4007 // PVTGeodetic @@ -219,12 +222,51 @@ class AP_GPS_SBF : public AP_GPS_Backend float Cov_VuDt; }; + struct PACKED msg5939 // AttEulerCoV + { + uint32_t TOW; // receiver time stamp, 0.001s + uint16_t WNc; // receiver time stamp, 1 week + uint8_t Reserved; // unused + uint8_t Error; // error code. bit 0-1:antenna 1, bit 2-3:antenna2, bit 7: when att not requested + // 00b:no error, 01b:not enough meausurements, 10b:antennas are on one line, 11b:inconsistent with manual anntena pos info + float Cov_HeadHead; // heading estimate variance + float Cov_PitchPitch; // pitch estimate variance + float Cov_RollRoll; // roll estimate variance + float Cov_HeadPitch; // covariance between Euler angle estimates. Always set to Do-No-Use values + float Cov_HeadRoll; + float Cov_PitchRoll; + }; + + struct PACKED AuxAntPositionSubBlock { + uint8_t NrSV; // total number of satellites tracked by the antenna + uint8_t Error; // aux antenna position error code + uint8_t AmbiguityType; // aux antenna positions obtained with 0: fixed ambiguities, 1: float ambiguities + uint8_t AuxAntID; // aux antenna ID: 1 for the first auxiliary antenna, 2 for the second, etc. + double DeltaEast; // position in East direction (relative to main antenna) + double DeltaNorth; // position in North direction (relative to main antenna) + double DeltaUp; // position in Up direction (relative to main antenna) + double EastVel; // velocity in East direction (relative to main antenna) + double NorthVel; // velocity in North direction (relative to main antenna) + double UpVel; // velocity in Up direction (relative to main antenna) + }; + + struct PACKED msg5942 // AuxAntPositions + { + uint32_t TOW; + uint16_t WNc; + uint8_t N; // number of AuxAntPosition sub-blocks in this AuxAntPositions block + uint8_t SBLength; // length of one sub-block in bytes + AuxAntPositionSubBlock ant1; // first aux antennas position + }; + union PACKED msgbuffer { msg4007 msg4007u; msg4001 msg4001u; msg4014 msg4014u; msg4028 msg4028u; msg5908 msg5908u; + msg5939 msg5939u; + msg5942 msg5942u; uint8_t bytes[256]; }; From daf8aeeadc47f4fb339e83123118d93347284c86 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 22 Nov 2023 19:51:22 +0000 Subject: [PATCH 427/499] AP_Param: check dynamic param tables are avalable before adding a param --- libraries/AP_Param/AP_Param.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 9e0ad48b854a40..56d9cbf8ecbf63 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -2999,6 +2999,11 @@ bool AP_Param::load_int32(uint16_t key, uint32_t group_element, int32_t &value) */ bool AP_Param::add_param(uint8_t _key, uint8_t param_num, const char *pname, float default_value) { + if (_var_info_dynamic == nullptr) { + // No dynamic tables available + return false; + } + // check for valid values if (param_num == 0 || param_num > 63 || strlen(pname) > 16) { return false; From 90f7ed34100424b2cb763f8d9e85e01b1b8fd632 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 20 Sep 2023 15:57:40 +0100 Subject: [PATCH 428/499] AP_Generator: Add support for IE V2 protocol --- .../AP_Generator/AP_Generator_IE_2400.cpp | 355 ++++++++++++++++-- libraries/AP_Generator/AP_Generator_IE_2400.h | 67 ++++ .../AP_Generator/AP_Generator_IE_650_800.cpp | 5 + .../AP_Generator/AP_Generator_IE_FuelCell.cpp | 46 ++- .../AP_Generator/AP_Generator_IE_FuelCell.h | 13 +- 5 files changed, 451 insertions(+), 35 deletions(-) diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.cpp b/libraries/AP_Generator/AP_Generator_IE_2400.cpp index d297261d5ff4fa..8a4e01eade5531 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_2400.cpp @@ -18,6 +18,7 @@ #if AP_GENERATOR_IE_2400_ENABLED #include +#include extern const AP_HAL::HAL& hal; @@ -32,21 +33,86 @@ void AP_Generator_IE_2400::init() _frontend._has_fuel_remaining = true; } -// Update fuel cell, expected to be called at 20hz +// Assigns the unit specific measurements once a valid sentence is obtained void AP_Generator_IE_2400::assign_measurements(const uint32_t now) { - // Successfully decoded a new valid sentence + + if (_type == PacketType::V2_INFO) { + // Got info packet + if (_had_info) { + // Not expecting the version to change + return; + } + _had_info = true; + + // Info tells us the protocol version, so lock on straight away + if (_version == ProtocolVersion::DETECTING) { + if (strcmp(_info.Protocol_version, "4") == 0) { + _version = ProtocolVersion::V2; + } else { + // Got a valid info packet, but don't know this protocol version + // Give up + _version = ProtocolVersion::UNKNOWN; + } + } + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "IE Fuel cell detected, PCM: %s, Ver: %s, SN: %s", _info.PCM_number, _info.Software_version, _info.Serial_number); + + return; + } + + // Try and lock onto version + if (_version == ProtocolVersion::DETECTING) { + ProtocolVersion new_version = ProtocolVersion::DETECTING; + switch (_type) { + case PacketType::NONE: + // Should not get a valid packet of type none + _last_version_packet_count = 0; + return; + + case PacketType::LEGACY_DATA: + new_version = ProtocolVersion::LEGACY; + break; + + case PacketType::V2_DATA: + case PacketType::V2_INFO: + new_version = ProtocolVersion::V2; + break; + } + + if (_last_version == new_version) { + _last_version_packet_count++; + } else { + _last_version_packet_count = 0; + } + _last_version = new_version; + + // If received 20 valid packets for a single protocol version then lock on + if (_last_version_packet_count > 20) { + _version = new_version; + gcs().send_text(MAV_SEVERITY_INFO, "Generator: IE using %s protocol", (_version == ProtocolVersion::V2) ? "V2" : "legacy" ); + + } else { + // Don't record any data during version detection + return; + } + } + + if (_type == PacketType::V2_DATA) { + memcpy(&_valid_V2, &_parsed_V2, sizeof(_valid_V2)); + } + // Update internal fuel cell state _pwr_out = _parsed.pwr_out; _spm_pwr = _parsed.spm_pwr; + _battery_pwr = _parsed.battery_pwr; _state = (State)_parsed.state; + _v2_state = (V2_State)_parsed.state; _err_code = _parsed.err_code; + _sub_err_code = _parsed.sub_err_code; - // Scale tank pressure linearly to a value between 0 and 1 - // Min = 5 bar, max = 300 bar, PRESS_GRAD = 1/295. - const float PRESS_GRAD = 0.003389830508f; - _fuel_remaining = constrain_float((_parsed.tank_bar-5)*PRESS_GRAD,0,1); + _fuel_remaining = _fuel_rem; // Update battery voltage _voltage = _parsed.battery_volt; @@ -55,7 +121,7 @@ void AP_Generator_IE_2400::assign_measurements(const uint32_t now) battery is charging. This is aligned with normal AP behaviour. This is the opposite of IE's convention hence *-1 */ if (_parsed.battery_volt > 0) { - _current = -1 * _parsed.battery_pwr / _parsed.battery_volt; + _current = -1 * _battery_pwr / _parsed.battery_volt; } else { _current = 0; } @@ -73,13 +139,44 @@ void AP_Generator_IE_2400::decode_latest_term() _term[_term_offset] = 0; _term_offset = 0; _term_number++; + _type = PacketType::NONE; + + if (_start_char == '<') { + decode_data_packet(); + + } else if (_start_char == '[') { + decode_info_packet(); + + } else { + _sentence_valid = false; + + } +} +void AP_Generator_IE_2400::decode_data_packet() +{ + // Try and decode both protocol versions until locked on + if ((_version == ProtocolVersion::LEGACY) || (_version == ProtocolVersion::DETECTING)) { + decode_legacy_data(); + } + if ((_version == ProtocolVersion::V2) || (_version == ProtocolVersion::DETECTING)) { + decode_v2_data(); + } +} + +void AP_Generator_IE_2400::decode_legacy_data() +{ switch (_term_number) { - case 1: + case 1: { // Float _parsed.tank_bar = strtof(_term, NULL); - break; + // Scale tank pressure linearly to a value between 0 and 1 + // Min = 5 bar, max = 300 bar, PRESS_GRAD = 1/295. + const float PRESS_GRAD = 0.003389830508f; + _fuel_rem = constrain_float((_parsed.tank_bar-5)*PRESS_GRAD,0,1); + break; + } case 2: // Float _parsed.battery_volt = strtof(_term, NULL); @@ -110,6 +207,7 @@ void AP_Generator_IE_2400::decode_latest_term() _parsed.err_code = strtoul(_term, nullptr, 10); // Sentence only declared valid when we have the expected number of terms _sentence_valid = true; + _type = PacketType::LEGACY_DATA; break; default: @@ -119,6 +217,129 @@ void AP_Generator_IE_2400::decode_latest_term() } } +void AP_Generator_IE_2400::decode_v2_data() +{ + switch (_term_number) { + case 1: + _fuel_rem = strtof(_term, NULL) * 0.01; + break; + + case 2: + _parsed_V2.inlet_press = strtof(_term, NULL); + break; + + case 3: + _parsed.battery_volt = strtof(_term, NULL); + break; + + case 4: + _parsed.pwr_out = strtol(_term, nullptr, 10); + break; + + case 5: + _parsed.spm_pwr = strtoul(_term, nullptr, 10); + break; + + case 6: + _parsed_V2.unit_fault = strtoul(_term, nullptr, 10); + break; + + case 7: + _parsed.battery_pwr = strtol(_term, nullptr, 10); + break; + + case 8: + _parsed.state = strtoul(_term, nullptr, 10); + break; + + case 9: + _parsed.err_code = strtoul(_term, nullptr, 10); + break; + + case 10: + _parsed.sub_err_code = strtoul(_term, nullptr, 10); + break; + + case 11: + strncpy(_parsed_V2.info_str, _term, ARRAY_SIZE(_parsed_V2.info_str)); + break; + + case 12: { + // The inverted checksum is sent, un-invert it + uint8_t checksum = ~strtoul(_term, nullptr, 10); + + // Sent checksum only included characters up to the checksum term + // Add on the checksum terms to match our running total + for (uint8_t i = 0; i < ARRAY_SIZE(_term); i++) { + if (_term[i] == 0) { + break; + } + checksum += _term[i]; + } + + _sentence_valid = checksum == _checksum; + _type = PacketType::V2_DATA; + break; + } + + default: + // We have received more terms than, something has gone wrong with telemetry data, mark invalid sentence + _sentence_valid = false; + break; + } +} + + +void AP_Generator_IE_2400::decode_info_packet() +{ + + switch (_term_number) { + case 1: + // PCM software number + strncpy(_info.PCM_number, _term, ARRAY_SIZE(_info.PCM_number)); + break; + + case 2: + // Software version + strncpy(_info.Software_version, _term, ARRAY_SIZE(_info.Software_version)); + break; + + case 3: + // protocol version + strncpy(_info.Protocol_version, _term, ARRAY_SIZE(_info.Protocol_version)); + break; + + case 4: + // Hardware serial number + strncpy(_info.Serial_number, _term, ARRAY_SIZE(_info.Serial_number)); + break; + + case 5: { + // The inverted checksum is sent, un-invert it + uint8_t checksum = ~strtoul(_term, nullptr, 10); + + // Sent checksum only included characters up to the checksum term + // Add on the checksum terms to match our running total + for (uint8_t i = 0; i < ARRAY_SIZE(_term); i++) { + if (_term[i] == 0) { + break; + } + checksum += _term[i]; + } + + _sentence_valid = checksum == _checksum; + _type = PacketType::V2_INFO; + break; + } + + default: + // We have received more terms than, something has gone wrong with telemetry data, mark invalid sentence + _sentence_valid = false; + break; + } + +} + // Check for failsafes AP_BattMonitor::Failsafe AP_Generator_IE_2400::update_failsafes() const { @@ -173,6 +394,11 @@ bool AP_Generator_IE_2400::is_low_error(const uint32_t err_in) const // Check error codes and populate message with error code bool AP_Generator_IE_2400::check_for_err_code(char* msg_txt, uint8_t msg_len) const { + if ((_version == ProtocolVersion::V2) && (strlen(_valid_V2.info_str) > 0)) { + hal.util->snprintf(msg_txt, msg_len, "Fuel cell err %s", _valid_V2.info_str); + return true; + } + // Check if we have received an error code if (!is_critical_error(_err_code) && !is_low_error(_err_code)) { return false; @@ -191,19 +417,106 @@ void AP_Generator_IE_2400::log_write() return; } - AP::logger().WriteStreaming( - "IE24", - "TimeUS,FUEL,SPMPWR,POUT,ERR", - "s%WW-", - "F2---", - "Qfiii", - AP_HAL::micros64(), - _fuel_remaining, - _spm_pwr, - _pwr_out, - _err_code - ); + switch (_version) { + case ProtocolVersion::DETECTING: + case ProtocolVersion::UNKNOWN: + return; + + case ProtocolVersion::LEGACY: + AP::logger().WriteStreaming( + "IE24", + "TimeUS,FUEL,SPMPWR,POUT,ERR", + "s%WW-", + "F2---", + "Qfiii", + AP_HAL::micros64(), + _fuel_remaining, + _spm_pwr, + _pwr_out, + _err_code + ); + break; + + case ProtocolVersion::V2: + AP::logger().WriteStreaming( + "IEFC", + "TimeUS,Tank,Inlet,BattV,OutPwr,SPMPwr,FNo,BPwr,State,F1,F2", + "s%-vWW-W---", + "F----------", + "QfffhHBhBII", + AP_HAL::micros64(), + _fuel_remaining, + _valid_V2.inlet_press, + _voltage, + _pwr_out, + _spm_pwr, + _valid_V2.unit_fault, + _battery_pwr, + uint8_t(_v2_state), + _err_code, + _sub_err_code + ); + break; + } + } #endif // HAL_LOGGING_ENABLED +// Return true is fuel cell is in running state suitable for arming +bool AP_Generator_IE_2400::is_running() const +{ + switch (_version) { + case ProtocolVersion::DETECTING: + case ProtocolVersion::UNKNOWN: + return false; + + case ProtocolVersion::LEGACY: + // Can use the base class method + return AP_Generator_IE_FuelCell::is_running(); + + case ProtocolVersion::V2: + return _v2_state == V2_State::Running; + } + + return false; +} + +// Lookup table for running state. State code is the same for all IE units. +const AP_Generator_IE_2400::Lookup_State_V2 AP_Generator_IE_2400::lookup_state_V2[] = { + { V2_State::FCPM_Off, "FCPM Off"}, + { V2_State::Starting, "Starting"}, + { V2_State::Running, "Running"}, + { V2_State::Stopping, "Stopping"}, + { V2_State::Go_to_Sleep, "Sleep"}, +}; + +// Print msg to user updating on state change +void AP_Generator_IE_2400::update_state_msg() +{ + switch (_version) { + case ProtocolVersion::DETECTING: + case ProtocolVersion::UNKNOWN: + break; + + case ProtocolVersion::LEGACY: + // Can use the base class method + AP_Generator_IE_FuelCell::update_state_msg(); + break; + + case ProtocolVersion::V2: { + // If fuel cell state has changed send gcs message + if (_v2_state != _last_v2_state) { + for (const struct Lookup_State_V2 entry : lookup_state_V2) { + if (_v2_state == entry.option) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Generator: %s", entry.msg_txt); + break; + } + } + _last_v2_state = _v2_state; + } + break; + } + } +} + #endif // AP_GENERATOR_IE_2400_ENABLED diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.h b/libraries/AP_Generator/AP_Generator_IE_2400.h index 65acfa8ef95028..637f95fb1b2813 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.h +++ b/libraries/AP_Generator/AP_Generator_IE_2400.h @@ -23,6 +23,14 @@ class AP_Generator_IE_2400 : public AP_Generator_IE_FuelCell // Process characters received and extract terms for IE 2.4kW void decode_latest_term(void) override; + // Decode a data packet + void decode_data_packet(); + void decode_legacy_data(); + void decode_v2_data(); + + // Decode a info packet + void decode_info_packet(); + // Check if we have received an error code and populate message with error code bool check_for_err_code(char* msg_txt, uint8_t msg_len) const override; @@ -36,6 +44,12 @@ class AP_Generator_IE_2400 : public AP_Generator_IE_FuelCell void log_write(void) override; #endif + // Return true is fuel cell is in running state suitable for arming + bool is_running() const override; + + // Print msg to user updating on state change + void update_state_msg() override; + // IE 2.4kW failsafes enum class ErrorCode { MINOR_INTERNAL = 1, // Minor internal error is to be ignored @@ -53,6 +67,59 @@ class AP_Generator_IE_2400 : public AP_Generator_IE_FuelCell // These measurements are only available on this unit int16_t _pwr_out; // Output power (Watts) uint16_t _spm_pwr; // Stack Power Module (SPM) power draw (Watts) + float _fuel_rem; // fuel remaining 0 to 1 + int16_t _battery_pwr; // Battery charging power + + // Extra data in the V2 packet + struct V2_data { + float inlet_press; + uint8_t unit_fault; // Unit number with issue + char info_str[33]; + }; + V2_data _parsed_V2; + V2_data _valid_V2; + + // Info packet + struct { + char PCM_number[TERM_BUFFER]; + char Software_version[TERM_BUFFER]; + char Protocol_version[TERM_BUFFER]; + char Serial_number[TERM_BUFFER]; + } _info; + bool _had_info; + + enum class ProtocolVersion { + DETECTING = 0, + LEGACY = 1, + V2 = 2, + UNKNOWN = 3, + } _version; + + ProtocolVersion _last_version; + uint8_t _last_version_packet_count; + + enum class PacketType { + NONE = 0, + LEGACY_DATA = 1, + V2_DATA = 2, + V2_INFO = 3, + } _type; + + enum class V2_State { + FCPM_Off = 0, + Starting = 1, + Running = 2, + Stopping = 3, + Go_to_Sleep = 4, + } _v2_state; + V2_State _last_v2_state; + + // State enum to string lookup + struct Lookup_State_V2 { + V2_State option; + const char *msg_txt; + }; + static const Lookup_State_V2 lookup_state_V2[]; }; #endif // AP_GENERATOR_IE_2400_ENABLED diff --git a/libraries/AP_Generator/AP_Generator_IE_650_800.cpp b/libraries/AP_Generator/AP_Generator_IE_650_800.cpp index 8c5b770e1511f1..c0e9aae3a2a95b 100644 --- a/libraries/AP_Generator/AP_Generator_IE_650_800.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_650_800.cpp @@ -59,6 +59,11 @@ void AP_Generator_IE_650_800::decode_latest_term() _term_offset = 0; _term_number++; + if (_start_char != '<') { + _sentence_valid = false; + return; + } + switch (_term_number) { case 1: _parsed.tank_pct = strtof(_term, NULL); diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp index b66d59b8ddcd49..e25a382368033a 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp @@ -77,12 +77,14 @@ void AP_Generator_IE_FuelCell::update() bool AP_Generator_IE_FuelCell::decode(char c) { // Start of a string - if (c == '<') { + if ((c == '<') || (c == '[')) { + _start_char = c; _sentence_valid = false; _data_valid = true; _term_number = 0; _term_offset = 0; _in_string = true; + _checksum = c; return false; } if (!_in_string) { @@ -90,7 +92,8 @@ bool AP_Generator_IE_FuelCell::decode(char c) } // End of a string - if (c == '>') { + const char end_char = (_start_char == '[') ? ']' : '>'; + if (c == end_char) { decode_latest_term(); _in_string = false; @@ -100,11 +103,13 @@ bool AP_Generator_IE_FuelCell::decode(char c) // End of a term in the string if (c == ',') { decode_latest_term(); + _checksum += c; return false; } // Otherwise add the char to the current term _term[_term_offset++] = c; + _checksum += c; // We have overrun the expected sentence if (_term_offset >TERM_BUFFER) { @@ -124,7 +129,7 @@ bool AP_Generator_IE_FuelCell::pre_arm_check(char *failmsg, uint8_t failmsg_len) } // Refuse arming if not in running state - if (_state != State::RUNNING) { + if (!is_running()) { strncpy(failmsg, "Status not running", failmsg_len); return false; } @@ -160,15 +165,7 @@ void AP_Generator_IE_FuelCell::check_status(const uint32_t now) } // If fuel cell state has changed send gcs message - if (_state != _last_state) { - for (const struct Lookup_State entry : lookup_state) { - if (_state == entry.option) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Generator: %s", entry.msg_txt); - break; - } - } - _last_state = _state; - } + update_state_msg(); // Check error codes char msg_txt[32]; @@ -181,15 +178,38 @@ void AP_Generator_IE_FuelCell::check_status(const uint32_t now) bool AP_Generator_IE_FuelCell::check_for_err_code_if_changed(char* msg_txt, uint8_t msg_len) { // Only check if there has been a change in error code - if (_err_code == _last_err_code) { + if ((_err_code == _last_err_code) && (_sub_err_code == _last_sub_err_code)) { return false; } if (check_for_err_code(msg_txt, msg_len)) { _last_err_code = _err_code; + _last_sub_err_code = _sub_err_code; return true; } return false; } + +// Return true is fuel cell is in running state suitable for arming +bool AP_Generator_IE_FuelCell::is_running() const +{ + return _state == State::RUNNING; +} + +// Print msg to user updating on state change +void AP_Generator_IE_FuelCell::update_state_msg() +{ + // If fuel cell state has changed send gcs message + if (_state != _last_state) { + for (const struct Lookup_State entry : lookup_state) { + if (_state == entry.option) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Generator: %s", entry.msg_txt); + break; + } + } + _last_state = _state; + } +} + #endif // AP_GENERATOR_IE_ENABLED diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h index 84395f1125c917..dfa22cd2a91006 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h @@ -49,6 +49,8 @@ class AP_Generator_IE_FuelCell : public AP_Generator_Backend uint32_t _err_code; // The error code from fuel cell uint32_t _last_err_code; // The previous error code from fuel cell + uint32_t _sub_err_code; // The sub error code from fuel cell + uint32_t _last_sub_err_code; // The previous sub error code from fuel cell State _state; // The PSU state State _last_state; // The previous PSU state uint32_t _last_time_ms; // Time we got a reading @@ -66,19 +68,22 @@ class AP_Generator_IE_FuelCell : public AP_Generator_Backend int16_t battery_pwr; uint8_t state; uint32_t err_code; + uint32_t sub_err_code; } _parsed; // Constants - static const uint8_t TERM_BUFFER = 12; // Max length of term we expect + static const uint8_t TERM_BUFFER = 33; // Max length of term we expect static const uint16_t HEALTHY_TIMEOUT_MS = 5000; // Time for driver to be marked un-healthy // Decoding vars + char _start_char; // inital sentence character giving sentence type char _term[TERM_BUFFER]; // Term buffer bool _sentence_valid; // Is current sentence valid bool _data_valid; // Is data within expected limits uint8_t _term_number; // Term index within the current sentence uint8_t _term_offset; // Offset within the _term buffer where the next character should be placed bool _in_string; // True if we should be decoding + uint8_t _checksum; // Basic checksum used by V2 protocol // Assigns the unit specific measurements once a valid sentence is obtained virtual void assign_measurements(const uint32_t now) = 0; @@ -103,5 +108,11 @@ class AP_Generator_IE_FuelCell : public AP_Generator_Backend // Only check the error code if it has changed since we last checked bool check_for_err_code_if_changed(char* msg_txt, uint8_t msg_len); + // Return true is fuel cell is in running state suitable for arming + virtual bool is_running() const; + + // Print msg to user updating on state change + virtual void update_state_msg(); + }; #endif // AP_GENERATOR_IE_ENABLED From c861e1585359289fb533583bd63d3c1c908a9b62 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 26 Sep 2023 02:14:02 +0100 Subject: [PATCH 429/499] AP_Gernerator: IE_2400: lengthen message buffer and print error num --- libraries/AP_Generator/AP_Generator_IE_2400.cpp | 2 +- libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.cpp b/libraries/AP_Generator/AP_Generator_IE_2400.cpp index 8a4e01eade5531..bfb90a4c4ac93f 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_2400.cpp @@ -395,7 +395,7 @@ bool AP_Generator_IE_2400::is_low_error(const uint32_t err_in) const bool AP_Generator_IE_2400::check_for_err_code(char* msg_txt, uint8_t msg_len) const { if ((_version == ProtocolVersion::V2) && (strlen(_valid_V2.info_str) > 0)) { - hal.util->snprintf(msg_txt, msg_len, "Fuel cell err %s", _valid_V2.info_str); + hal.util->snprintf(msg_txt, msg_len, "Fuel cell err %u.%u: %s", (unsigned)_err_code, (unsigned)_sub_err_code, _valid_V2.info_str); return true; } diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp index e25a382368033a..da7991a23fc2a3 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp @@ -168,7 +168,7 @@ void AP_Generator_IE_FuelCell::check_status(const uint32_t now) update_state_msg(); // Check error codes - char msg_txt[32]; + char msg_txt[64]; if (check_for_err_code_if_changed(msg_txt, sizeof(msg_txt))) { GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "%s", msg_txt); } From c91407d66251b223ec5e1ce2891a03b72f9e52e5 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 9 Oct 2023 11:26:49 +0100 Subject: [PATCH 430/499] AP_Generator: IE 2400: only return custom msg if error is critial or low severity --- libraries/AP_Generator/AP_Generator_IE_2400.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.cpp b/libraries/AP_Generator/AP_Generator_IE_2400.cpp index bfb90a4c4ac93f..ac31ff38d58142 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_2400.cpp @@ -394,16 +394,16 @@ bool AP_Generator_IE_2400::is_low_error(const uint32_t err_in) const // Check error codes and populate message with error code bool AP_Generator_IE_2400::check_for_err_code(char* msg_txt, uint8_t msg_len) const { - if ((_version == ProtocolVersion::V2) && (strlen(_valid_V2.info_str) > 0)) { - hal.util->snprintf(msg_txt, msg_len, "Fuel cell err %u.%u: %s", (unsigned)_err_code, (unsigned)_sub_err_code, _valid_V2.info_str); - return true; - } - // Check if we have received an error code if (!is_critical_error(_err_code) && !is_low_error(_err_code)) { return false; } + if ((_version == ProtocolVersion::V2) && (strlen(_valid_V2.info_str) > 0)) { + hal.util->snprintf(msg_txt, msg_len, "Fuel cell err %u.%u: %s", (unsigned)_err_code, (unsigned)_sub_err_code, _valid_V2.info_str); + return true; + } + hal.util->snprintf(msg_txt, msg_len, "Fuel cell err code <%u>", (unsigned)_err_code); return true; } From 36dd720e78a2729230b807f63c5fd0a0171ce772 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 13 Oct 2023 13:53:38 +0100 Subject: [PATCH 431/499] AP_Generator: IE 2400: fix V2 low and critical errors and add warnings --- .../AP_Generator/AP_Generator_IE_2400.cpp | 47 ++++++++++++++++++- libraries/AP_Generator/AP_Generator_IE_2400.h | 3 ++ .../AP_Generator/AP_Generator_IE_FuelCell.cpp | 2 +- .../AP_Generator/AP_Generator_IE_FuelCell.h | 3 ++ 4 files changed, 52 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.cpp b/libraries/AP_Generator/AP_Generator_IE_2400.cpp index ac31ff38d58142..16a57b7932aec6 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_2400.cpp @@ -359,6 +359,12 @@ AP_BattMonitor::Failsafe AP_Generator_IE_2400::update_failsafes() const // Check for error codes that are deemed critical bool AP_Generator_IE_2400::is_critical_error(const uint32_t err_in) const { + // V2 protocol + if (_version == ProtocolVersion::V2) { + return err_in > 30; + } + + // V1 protocol switch ((ErrorCode)err_in) { // Error codes that lead to critical action battery monitor failsafe case ErrorCode::BATTERY_CRITICAL: @@ -375,6 +381,12 @@ bool AP_Generator_IE_2400::is_critical_error(const uint32_t err_in) const // Check for error codes that are deemed severe and would be cause to trigger a battery monitor low failsafe action bool AP_Generator_IE_2400::is_low_error(const uint32_t err_in) const { + // V2 protocol + if (_version == ProtocolVersion::V2) { + return (err_in >= 10) && (err_in <= 30); + } + + // V1 protocol switch ((ErrorCode)err_in) { // Error codes that lead to critical action battery monitor failsafe case ErrorCode::START_DENIED: @@ -382,7 +394,6 @@ bool AP_Generator_IE_2400::is_low_error(const uint32_t err_in) const case ErrorCode::BATTERY_LOW: case ErrorCode::PRESSURE_LOW: case ErrorCode::SPM_LOST: - case ErrorCode::REDUCED_POWER: return true; default: @@ -399,7 +410,7 @@ bool AP_Generator_IE_2400::check_for_err_code(char* msg_txt, uint8_t msg_len) co return false; } - if ((_version == ProtocolVersion::V2) && (strlen(_valid_V2.info_str) > 0)) { + if (_version == ProtocolVersion::V2) { hal.util->snprintf(msg_txt, msg_len, "Fuel cell err %u.%u: %s", (unsigned)_err_code, (unsigned)_sub_err_code, _valid_V2.info_str); return true; } @@ -408,6 +419,38 @@ bool AP_Generator_IE_2400::check_for_err_code(char* msg_txt, uint8_t msg_len) co return true; } +bool AP_Generator_IE_2400::check_for_warning_code(char* msg_txt, uint8_t msg_len) const +{ + if (_err_code == 0) { + // No error nothing to do. + return false; + } + if (is_critical_error(_err_code) || is_low_error(_err_code)) { + // Critical or low error are already reported + return false; + } + + switch (_version) { + case ProtocolVersion::DETECTING: + case ProtocolVersion::UNKNOWN: + break; + + case ProtocolVersion::LEGACY: + if ((ErrorCode)_err_code == ErrorCode::REDUCED_POWER) { + hal.util->snprintf(msg_txt, msg_len, "Fuel cell reduced power <%u>", (unsigned)_err_code); + return true; + } + break; + + case ProtocolVersion::V2: + hal.util->snprintf(msg_txt, msg_len, "Fuel cell warning %u.%u: %s", (unsigned)_err_code, (unsigned)_sub_err_code, _valid_V2.info_str); + return true; + } + + hal.util->snprintf(msg_txt, msg_len, "Fuel cell warning code <%u>", (unsigned)_err_code); + return true; +} + #if HAL_LOGGING_ENABLED // log generator status to the onboard log void AP_Generator_IE_2400::log_write() diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.h b/libraries/AP_Generator/AP_Generator_IE_2400.h index 637f95fb1b2813..c98238f53f7c53 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.h +++ b/libraries/AP_Generator/AP_Generator_IE_2400.h @@ -34,6 +34,9 @@ class AP_Generator_IE_2400 : public AP_Generator_IE_FuelCell // Check if we have received an error code and populate message with error code bool check_for_err_code(char* msg_txt, uint8_t msg_len) const override; + // Check if we have received an warning code and populate message with warning code + bool check_for_warning_code(char* msg_txt, uint8_t msg_len) const override; + // Check for error codes that are deemed critical bool is_critical_error(const uint32_t err_in) const; diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp index da7991a23fc2a3..7febe64e958fcd 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp @@ -182,7 +182,7 @@ bool AP_Generator_IE_FuelCell::check_for_err_code_if_changed(char* msg_txt, uint return false; } - if (check_for_err_code(msg_txt, msg_len)) { + if (check_for_err_code(msg_txt, msg_len) || check_for_warning_code(msg_txt, msg_len)) { _last_err_code = _err_code; _last_sub_err_code = _sub_err_code; return true; diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h index dfa22cd2a91006..d28e578cb4d8ae 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h @@ -105,6 +105,9 @@ class AP_Generator_IE_FuelCell : public AP_Generator_Backend // Check error codes and populate message with error code virtual bool check_for_err_code(char* msg_txt, uint8_t msg_len) const = 0; + // Check if we have received an warning code and populate message with warning code + virtual bool check_for_warning_code(char* msg_txt, uint8_t msg_len) const { return false; } + // Only check the error code if it has changed since we last checked bool check_for_err_code_if_changed(char* msg_txt, uint8_t msg_len); From ab5d28073d46b9750067c4216eba773631ceaee6 Mon Sep 17 00:00:00 2001 From: Gone4Dirt Date: Fri, 13 Oct 2023 21:26:24 +0100 Subject: [PATCH 432/499] SITL: Add V2 telemetry protocol to IE24 fuel cell --- libraries/SITL/SIM_IntelligentEnergy24.cpp | 67 +++++++++++++++++++--- libraries/SITL/SIM_IntelligentEnergy24.h | 3 +- 2 files changed, 62 insertions(+), 8 deletions(-) diff --git a/libraries/SITL/SIM_IntelligentEnergy24.cpp b/libraries/SITL/SIM_IntelligentEnergy24.cpp index 2445df9a863a95..4c87684978f3b1 100644 --- a/libraries/SITL/SIM_IntelligentEnergy24.cpp +++ b/libraries/SITL/SIM_IntelligentEnergy24.cpp @@ -29,13 +29,15 @@ extern const AP_HAL::HAL& hal; using namespace SITL; +#define MAX_TANK_PRESSURE 300 //(bar) + // table of user settable parameters const AP_Param::GroupInfo IntelligentEnergy24::var_info[] = { // @Param: ENABLE // @DisplayName: IntelligentEnergy 2.4kWh FuelCell sim enable/disable // @Description: Allows you to enable (1) or disable (0) the FuelCell simulator - // @Values: 0:Disabled,1:Enabled + // @Values: 0:Disabled,1:V1 Protocol,2:V2 Protocol // @User: Advanced AP_GROUPINFO("ENABLE", 1, IntelligentEnergy24, enabled, 0), @@ -70,9 +72,9 @@ void IntelligentEnergy24::update(const struct sitl_input &input) void IntelligentEnergy24::update_send() { - // just send a chunk of data at 1Hz: + // just send a chunk of data at 2 Hz: const uint32_t now = AP_HAL::millis(); - if (now - last_sent_ms < 500) { + if (now - last_data_sent_ms < 500) { return; } @@ -80,7 +82,7 @@ void IntelligentEnergy24::update_send() float amps = discharge ? -20.0f : 20.0f; // Update pack capacity remaining - bat_capacity_mAh += amps*(now - last_sent_ms)/3600.0f; + bat_capacity_mAh += amps*(now - last_data_sent_ms)/3600.0f; // From capacity remaining approximate voltage by linear interpolation const float min_bat_vol = 42.0f; @@ -90,7 +92,7 @@ void IntelligentEnergy24::update_send() // Simulate tank pressure // Scale tank pressure linearly to a percentage. // Min = 5 bar, max = 300 bar, PRESS_GRAD = 1/295. - const int16_t tank_bar = linear_interpolate(5, 295, bat_capacity_mAh / max_bat_capactiy_mAh, 0, 1); + const int16_t tank_bar = linear_interpolate(5, MAX_TANK_PRESSURE, bat_capacity_mAh / max_bat_capactiy_mAh, 0, 1); battery_voltage = bat_capacity_mAh / max_bat_capactiy_mAh * (max_bat_vol - min_bat_vol) + min_bat_vol; @@ -112,10 +114,13 @@ void IntelligentEnergy24::update_send() state = 2; // Running } - last_sent_ms = now; + last_data_sent_ms = now; char message[128]; - hal.util->snprintf(message, ARRAY_SIZE(message), "<%i,%.1f,%i,%u,%i,%u,%u>\n", + + if (enabled.get() == 1) { + // V1 Protocol + hal.util->snprintf(message, ARRAY_SIZE(message), "<%i,%.1f,%i,%u,%i,%u,%u>\n", tank_bar, battery_voltage, (signed)pwr_out, @@ -124,6 +129,54 @@ void IntelligentEnergy24::update_send() (unsigned)state, (unsigned)err_code); + } else { + // V2 Protocol + + // version message sent at 0.2 Hz + if (now - last_ver_sent_ms > 5e3) { + // PCM software part number, software version number, protocol number, hardware serial number, check-sum + hal.util->snprintf(message, ARRAY_SIZE(message), "[10011867,2.132,4,IE12160A8040015,7]\n"); + + if ((unsigned)write_to_autopilot(message, strlen(message)) != strlen(message)) { + AP_HAL::panic("Failed to write to autopilot: %s", strerror(errno)); + } + last_ver_sent_ms = now; + } + + // data message + memset(&message, 0, sizeof(message)); + int8_t tank_remaining_pct = (float)tank_bar / MAX_TANK_PRESSURE * 100.0; + + hal.util->snprintf(message, ARRAY_SIZE(message), "<%i,%.2f,%.1f,%i,%u,%i,%i,%u,%u,%i,,", // last blank , is for fuel cell to send info string up to 32 char ASCII + tank_remaining_pct, + 0.67f, // inlet pressure (bar) + battery_voltage, + (signed)pwr_out, + (unsigned)spm_pwr, + 0, // unit at fault (0 = no fault) + (signed)battery_pwr, + (unsigned)state, + (unsigned)err_code, + 0); // fault state 2 (0 = no fault) + + // calculate the checksum + uint8_t checksum = 0; + for (uint8_t i = 0; i < ARRAY_SIZE(message); i++) { + if (message[i] == 0) { + break; + } + checksum += message[i]; + } + // checksum is inverted 8-bit + checksum = ~checksum; + + // add the checksum to the end of the message + char data_end[7]; + hal.util->snprintf(data_end, ARRAY_SIZE(data_end), "%u>\n", checksum); + strncat(message, data_end, ARRAY_SIZE(data_end)); + + } + if ((unsigned)write_to_autopilot(message, strlen(message)) != strlen(message)) { AP_HAL::panic("Failed to write to autopilot: %s", strerror(errno)); } diff --git a/libraries/SITL/SIM_IntelligentEnergy24.h b/libraries/SITL/SIM_IntelligentEnergy24.h index eecd0939e27d52..99434758a43dba 100644 --- a/libraries/SITL/SIM_IntelligentEnergy24.h +++ b/libraries/SITL/SIM_IntelligentEnergy24.h @@ -67,7 +67,8 @@ class IntelligentEnergy24 : public IntelligentEnergy { float battery_voltage = 50.4f; float bat_capacity_mAh = 3300; bool discharge = true; // used to switch between battery charging and discharging - uint32_t last_sent_ms; + uint32_t last_data_sent_ms; + uint32_t last_ver_sent_ms; }; From 1355c60dafa66b5cfb6f764e0333a7e590ac65da Mon Sep 17 00:00:00 2001 From: Gone4Dirt Date: Fri, 13 Oct 2023 21:27:34 +0100 Subject: [PATCH 433/499] autotest: Test both telemetry protocols for IE24 fuel cell --- Tools/autotest/arducopter.py | 22 ++++++++++++++-------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index c7898e2b755353..f8afa254b4cec3 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -7678,6 +7678,12 @@ def RichenPower(self): raise NotAchievedException("Did not find expected GEN message") def IE24(self): + '''Test IntelligentEnergy 2.4kWh generator with V1 and V2 telemetry protocols''' + protocol_ver = (1, 2) + for ver in protocol_ver: + self.run_IE24(ver) + + def run_IE24(self, proto_ver): '''Test IntelligentEnergy 2.4kWh generator''' elec_battery_instance = 2 fuel_battery_instance = 1 @@ -7687,14 +7693,14 @@ def IE24(self): "GEN_TYPE": 2, "BATT%u_MONITOR" % (fuel_battery_instance + 1): 18, # fuel-based generator "BATT%u_MONITOR" % (elec_battery_instance + 1): 17, - "SIM_IE24_ENABLE": 1, + "SIM_IE24_ENABLE": proto_ver, "LOG_DISARMED": 1, }) self.customise_SITL_commandline(["--uartF=sim:ie24"]) - self.start_subtest("ensure that BATTERY_STATUS for electrical generator message looks right") - self.start_subsubtest("Checking original voltage (electrical)") + self.start_subtest("Protocol %i: ensure that BATTERY_STATUS for electrical generator message looks right" % proto_ver) + self.start_subsubtest("Protocol %i: Checking original voltage (electrical)" % proto_ver) # ArduPilot spits out essentially uninitialised battery # messages until we read things fromthe battery: self.delay_sim_time(30) @@ -7712,13 +7718,13 @@ def IE24(self): "battery_remaining": original_elec_m.battery_remaining - 1, }, instance=elec_battery_instance) - self.start_subtest("ensure that BATTERY_STATUS for fuel generator message looks right") - self.start_subsubtest("Checking original voltage (fuel)") + self.start_subtest("Protocol %i: ensure that BATTERY_STATUS for fuel generator message looks right" % proto_ver) + self.start_subsubtest("Protocol %i: Checking original voltage (fuel)" % proto_ver) # ArduPilot spits out essentially uninitialised battery # messages until we read things fromthe battery: if original_fuel_m.battery_remaining <= 90: raise NotAchievedException("Bad original percentage (want=>%f got %f" % (90, original_fuel_m.battery_remaining)) - self.start_subsubtest("Ensure percentage is counting down") + self.start_subsubtest("Protocol %i: Ensure percentage is counting down" % proto_ver) self.wait_message_field_values('BATTERY_STATUS', { "battery_remaining": original_fuel_m.battery_remaining - 1, }, instance=fuel_battery_instance) @@ -7728,7 +7734,7 @@ def IE24(self): self.disarm_vehicle() # Test for pre-arm check fail when state is not running - self.start_subtest("If you haven't taken off generator error should cause instant failsafe and disarm") + self.start_subtest("Protocol %i: Without takeoff generator error should cause failsafe and disarm" % proto_ver) self.set_parameter("SIM_IE24_STATE", 8) self.wait_statustext("Status not running", timeout=40) self.try_arm(result=False, @@ -7736,7 +7742,7 @@ def IE24(self): self.set_parameter("SIM_IE24_STATE", 2) # Explicitly set state to running # Test that error code does result in failsafe - self.start_subtest("If you haven't taken off generator error should cause instant failsafe and disarm") + self.start_subtest("Protocol %i: Without taken off generator error should cause failsafe and disarm" % proto_ver) self.change_mode("STABILIZE") self.set_parameter("DISARM_DELAY", 0) self.arm_vehicle() From 3b3c94ea07f7c2d53b70dac35d7549c6c911d491 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 22 Oct 2023 17:55:53 +0100 Subject: [PATCH 434/499] AP_Generator: IE_2400: update low and critial error ranges for V2 protocol --- libraries/AP_Generator/AP_Generator_IE_2400.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.cpp b/libraries/AP_Generator/AP_Generator_IE_2400.cpp index 16a57b7932aec6..84d6a497bfe35a 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_2400.cpp @@ -361,7 +361,7 @@ bool AP_Generator_IE_2400::is_critical_error(const uint32_t err_in) const { // V2 protocol if (_version == ProtocolVersion::V2) { - return err_in > 30; + return err_in >= 30; } // V1 protocol @@ -383,7 +383,7 @@ bool AP_Generator_IE_2400::is_low_error(const uint32_t err_in) const { // V2 protocol if (_version == ProtocolVersion::V2) { - return (err_in >= 10) && (err_in <= 30); + return (err_in > 20) && (err_in < 30); } // V1 protocol From a00b6b6f86e36ae00d79476dcb211d295a9a249d Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 22 Oct 2023 17:56:33 +0100 Subject: [PATCH 435/499] AP_Gernerator: FuelCell: rework error check to give error cleared msg --- .../AP_Generator/AP_Generator_IE_FuelCell.cpp | 24 ++++++++++--------- .../AP_Generator/AP_Generator_IE_FuelCell.h | 2 +- 2 files changed, 14 insertions(+), 12 deletions(-) diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp index 7febe64e958fcd..1385888435f76a 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.cpp @@ -168,27 +168,29 @@ void AP_Generator_IE_FuelCell::check_status(const uint32_t now) update_state_msg(); // Check error codes - char msg_txt[64]; - if (check_for_err_code_if_changed(msg_txt, sizeof(msg_txt))) { - GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "%s", msg_txt); - } + check_for_err_code_if_changed(); } // Check error codes and populate message with error code -bool AP_Generator_IE_FuelCell::check_for_err_code_if_changed(char* msg_txt, uint8_t msg_len) +void AP_Generator_IE_FuelCell::check_for_err_code_if_changed() { // Only check if there has been a change in error code if ((_err_code == _last_err_code) && (_sub_err_code == _last_sub_err_code)) { - return false; + return; } - if (check_for_err_code(msg_txt, msg_len) || check_for_warning_code(msg_txt, msg_len)) { - _last_err_code = _err_code; - _last_sub_err_code = _sub_err_code; - return true; + char msg_txt[64]; + if (check_for_err_code(msg_txt, sizeof(msg_txt)) || check_for_warning_code(msg_txt, sizeof(msg_txt))) { + GCS_SEND_TEXT(MAV_SEVERITY_ALERT, "%s", msg_txt); + + } else if ((_err_code == 0) && (_sub_err_code == 0)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Fuel cell error cleared"); + } - return false; + _last_err_code = _err_code; + _last_sub_err_code = _sub_err_code; + } // Return true is fuel cell is in running state suitable for arming diff --git a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h index d28e578cb4d8ae..8eac8952493019 100644 --- a/libraries/AP_Generator/AP_Generator_IE_FuelCell.h +++ b/libraries/AP_Generator/AP_Generator_IE_FuelCell.h @@ -109,7 +109,7 @@ class AP_Generator_IE_FuelCell : public AP_Generator_Backend virtual bool check_for_warning_code(char* msg_txt, uint8_t msg_len) const { return false; } // Only check the error code if it has changed since we last checked - bool check_for_err_code_if_changed(char* msg_txt, uint8_t msg_len); + void check_for_err_code_if_changed(); // Return true is fuel cell is in running state suitable for arming virtual bool is_running() const; From d626928e0c454569e5dc2d46f0aa1aa6a1065389 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 25 Oct 2023 12:46:49 +0100 Subject: [PATCH 436/499] SITL: SIM IntelligentEnergy24: add error string to V2 protocol --- libraries/SITL/SIM_IntelligentEnergy24.cpp | 23 +++++++++++++++++----- libraries/SITL/SIM_IntelligentEnergy24.h | 2 ++ 2 files changed, 20 insertions(+), 5 deletions(-) diff --git a/libraries/SITL/SIM_IntelligentEnergy24.cpp b/libraries/SITL/SIM_IntelligentEnergy24.cpp index 4c87684978f3b1..7b2456ee6b5838 100644 --- a/libraries/SITL/SIM_IntelligentEnergy24.cpp +++ b/libraries/SITL/SIM_IntelligentEnergy24.cpp @@ -43,13 +43,13 @@ const AP_Param::GroupInfo IntelligentEnergy24::var_info[] = { // @Param: STATE // @DisplayName: Explicitly set state - // @Description: Explicity specify a state for the generator to be in + // @Description: Explicitly specify a state for the generator to be in // @User: Advanced AP_GROUPINFO("STATE", 2, IntelligentEnergy24, set_state, -1), // @Param: ERROR // @DisplayName: Explicitly set error code - // @Description: Explicity specify an error code to send to the generator + // @Description: Explicitly specify an error code to send to the generator // @User: Advanced AP_GROUPINFO("ERROR", 3, IntelligentEnergy24, err_code, 0), @@ -66,7 +66,6 @@ void IntelligentEnergy24::update(const struct sitl_input &input) if (!enabled.get()) { return; } - // gcs().send_text(MAV_SEVERITY_INFO, "fuelcell update"); update_send(); } @@ -147,7 +146,7 @@ void IntelligentEnergy24::update_send() memset(&message, 0, sizeof(message)); int8_t tank_remaining_pct = (float)tank_bar / MAX_TANK_PRESSURE * 100.0; - hal.util->snprintf(message, ARRAY_SIZE(message), "<%i,%.2f,%.1f,%i,%u,%i,%i,%u,%u,%i,,", // last blank , is for fuel cell to send info string up to 32 char ASCII + hal.util->snprintf(message, ARRAY_SIZE(message), "<%i,%.2f,%.1f,%i,%u,%i,%i,%u,%u,%i,%s,", // last blank , is for fuel cell to send info string up to 32 char ASCII tank_remaining_pct, 0.67f, // inlet pressure (bar) battery_voltage, @@ -157,7 +156,8 @@ void IntelligentEnergy24::update_send() (signed)battery_pwr, (unsigned)state, (unsigned)err_code, - 0); // fault state 2 (0 = no fault) + 0, // fault state 2 (0 = no fault) + get_error_string(err_code)); // calculate the checksum uint8_t checksum = 0; @@ -181,3 +181,16 @@ void IntelligentEnergy24::update_send() AP_HAL::panic("Failed to write to autopilot: %s", strerror(errno)); } } + +const char * IntelligentEnergy24::get_error_string(const uint32_t code) +{ + switch (code) { + case 20: + return "THERMAL MNGMT"; + + default: + break; + } + + return ""; +} diff --git a/libraries/SITL/SIM_IntelligentEnergy24.h b/libraries/SITL/SIM_IntelligentEnergy24.h index 99434758a43dba..68d8782937f627 100644 --- a/libraries/SITL/SIM_IntelligentEnergy24.h +++ b/libraries/SITL/SIM_IntelligentEnergy24.h @@ -60,6 +60,8 @@ class IntelligentEnergy24 : public IntelligentEnergy { void update_send(); + const char * get_error_string(const uint32_t code); + AP_Int8 enabled; // enable sim AP_Int8 set_state; AP_Int32 err_code; From d17a1ca7bccb535cc18399edfef42c661974d534 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 23 Nov 2023 14:15:34 +1100 Subject: [PATCH 437/499] AP_CANManager: support CAN_Dn_PROTOCOL2 for an aux 11 bit protocol --- libraries/AP_CANManager/AP_CANDriver.cpp | 8 +++++++ libraries/AP_CANManager/AP_CANDriver.h | 7 ++++++ libraries/AP_CANManager/AP_CANManager.cpp | 27 +++++++++++++++++++++++ libraries/AP_CANManager/AP_CANManager.h | 6 +++++ libraries/AP_CANManager/AP_CANSensor.cpp | 12 +++++++++- libraries/AP_CANManager/AP_CANSensor.h | 4 ++++ 6 files changed, 63 insertions(+), 1 deletion(-) diff --git a/libraries/AP_CANManager/AP_CANDriver.cpp b/libraries/AP_CANManager/AP_CANDriver.cpp index 1f279c12a690de..0ec7ebbceb2a00 100644 --- a/libraries/AP_CANManager/AP_CANDriver.cpp +++ b/libraries/AP_CANManager/AP_CANDriver.cpp @@ -51,6 +51,14 @@ const AP_Param::GroupInfo AP_CANManager::CANDriver_Params::var_info[] = { AP_SUBGROUPPTR(_piccolocan, "PC_", 5, AP_CANManager::CANDriver_Params, AP_PiccoloCAN), #endif + // @Param: PROTOCOL2 + // @DisplayName: Secondary protocol with 11 bit CAN addressing + // @Description: Secondary protocol with 11 bit CAN addressing + // @Values: 0:Disabled,7:USD1,10:Scripting,11:Benewake,12:Scripting2,13:TOFSenseP,14:NanoRadar_NRA24 + // @User: Advanced + // @RebootRequired: True + AP_GROUPINFO("PROTOCOL2", 6, AP_CANManager::CANDriver_Params, _driver_type_11bit, float(AP_CAN::Protocol::None)), + AP_GROUPEND }; #endif diff --git a/libraries/AP_CANManager/AP_CANDriver.h b/libraries/AP_CANManager/AP_CANDriver.h index a950535019f16c..f93e96cec0e7a8 100644 --- a/libraries/AP_CANManager/AP_CANDriver.h +++ b/libraries/AP_CANManager/AP_CANDriver.h @@ -21,6 +21,8 @@ #include class AP_CANManager; +class CANSensor; + class AP_CANDriver { public: @@ -34,4 +36,9 @@ class AP_CANDriver // link protocol drivers with interfaces by adding reference to CANIface virtual bool add_interface(AP_HAL::CANIface* can_iface) = 0; + // add an 11 bit auxillary driver + virtual bool add_11bit_driver(CANSensor *sensor) { return false; } + + // handler for outgoing frames for auxillary drivers + virtual bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) { return false; } }; diff --git a/libraries/AP_CANManager/AP_CANManager.cpp b/libraries/AP_CANManager/AP_CANManager.cpp index 9275ea2ba05edd..20918ede682a67 100644 --- a/libraries/AP_CANManager/AP_CANManager.cpp +++ b/libraries/AP_CANManager/AP_CANManager.cpp @@ -280,6 +280,7 @@ void AP_CANManager::init() } } #endif + /* register a new CAN driver */ @@ -334,6 +335,32 @@ bool AP_CANManager::register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver return false; } +// register a new auxillary sensor driver for 11 bit address frames +bool AP_CANManager::register_11bit_driver(AP_CAN::Protocol dtype, CANSensor *sensor, uint8_t &driver_index) +{ + WITH_SEMAPHORE(_sem); + + for (uint8_t i = 0; i < HAL_NUM_CAN_IFACES; i++) { + uint8_t drv_num = _interfaces[i]._driver_number; + if (drv_num == 0 || drv_num > HAL_MAX_CAN_PROTOCOL_DRIVERS) { + continue; + } + // from 1 based to 0 based + drv_num--; + + if (dtype != (AP_CAN::Protocol)_drv_param[drv_num]._driver_type_11bit.get()) { + continue; + } + if (_drivers[drv_num] != nullptr && + _drivers[drv_num]->add_11bit_driver(sensor)) { + driver_index = drv_num; + return true; + } + } + return false; + +} + // Method used by CAN related library methods to report status and debug info // The result of this method can be accessed via ftp get @SYS/can_log.txt void AP_CANManager::log_text(AP_CANManager::LogLevel loglevel, const char *tag, const char *fmt, ...) diff --git a/libraries/AP_CANManager/AP_CANManager.h b/libraries/AP_CANManager/AP_CANManager.h index 85d4aa31ed31f2..5c352ae5b39231 100644 --- a/libraries/AP_CANManager/AP_CANManager.h +++ b/libraries/AP_CANManager/AP_CANManager.h @@ -34,6 +34,8 @@ #include "AP_CAN.h" +class CANSensor; + class AP_CANManager { public: @@ -63,6 +65,9 @@ class AP_CANManager // register a new driver bool register_driver(AP_CAN::Protocol dtype, AP_CANDriver *driver); + // register a new auxillary sensor driver for 11 bit address frames + bool register_11bit_driver(AP_CAN::Protocol dtype, CANSensor *sensor, uint8_t &driver_index); + // returns number of active CAN Drivers uint8_t get_num_drivers(void) const { @@ -141,6 +146,7 @@ class AP_CANManager private: AP_Int8 _driver_type; + AP_Int8 _driver_type_11bit; AP_CANDriver* _uavcan; AP_CANDriver* _piccolocan; }; diff --git a/libraries/AP_CANManager/AP_CANSensor.cpp b/libraries/AP_CANManager/AP_CANSensor.cpp index 881eb39ce93c8f..025dfd8036e2f8 100644 --- a/libraries/AP_CANManager/AP_CANSensor.cpp +++ b/libraries/AP_CANManager/AP_CANSensor.cpp @@ -40,7 +40,13 @@ void CANSensor::register_driver(AP_CAN::Protocol dtype) { #if HAL_CANMANAGER_ENABLED if (!AP::can().register_driver(dtype, this)) { - debug_can(AP_CANManager::LOG_ERROR, "Failed to register CANSensor %s", _driver_name); + if (AP::can().register_11bit_driver(dtype, this, _driver_index)) { + is_aux_11bit_driver = true; + _can_driver = AP::can().get_driver(_driver_index); + _initialized = true; + } else { + debug_can(AP_CANManager::LOG_ERROR, "Failed to register CANSensor %s", _driver_name); + } } else { debug_can(AP_CANManager::LOG_INFO, "%s: constructed", _driver_name); } @@ -135,6 +141,10 @@ bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_ return false; } + if (is_aux_11bit_driver && _can_driver != nullptr) { + return _can_driver->write_aux_frame(out_frame, timeout_us); + } + bool read_select = false; bool write_select = true; bool ret = _can_iface->select(read_select, write_select, &out_frame, AP_HAL::micros64() + timeout_us); diff --git a/libraries/AP_CANManager/AP_CANSensor.h b/libraries/AP_CANManager/AP_CANSensor.h index a1374821e40e4e..e340b71facdd09 100644 --- a/libraries/AP_CANManager/AP_CANSensor.h +++ b/libraries/AP_CANManager/AP_CANSensor.h @@ -72,6 +72,10 @@ class CANSensor : public AP_CANDriver { const uint16_t _stack_size; bool _initialized; uint8_t _driver_index; + + // this is true when we are setup as an auxillary driver using CAN_Dn_PROTOCOL2 + bool is_aux_11bit_driver; + AP_CANDriver *_can_driver; HAL_EventHandle _event_handle; AP_HAL::CANIface* _can_iface; From ad59f6db01b54dd907bdea95a02891cd1eb698b3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 23 Nov 2023 14:16:08 +1100 Subject: [PATCH 438/499] AP_DroneCAN: support an aux 11 bit protocol with DroneCAN --- libraries/AP_DroneCAN/AP_Canard_iface.cpp | 35 +++++++++++++++++++++++ libraries/AP_DroneCAN/AP_Canard_iface.h | 13 ++++++++- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 16 +++++++++++ libraries/AP_DroneCAN/AP_DroneCAN.h | 7 +++++ 4 files changed, 70 insertions(+), 1 deletion(-) diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index 60980e510f8f9a..86bedca40e680d 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.cpp +++ b/libraries/AP_DroneCAN/AP_Canard_iface.cpp @@ -9,6 +9,7 @@ extern const AP_HAL::HAL& hal; #define LOG_TAG "DroneCANIface" #include +#include #define DEBUG_PKTS 0 @@ -346,6 +347,15 @@ void CanardInterface::processRx() { if (ifaces[i]->receive(rxmsg, timestamp, flags) <= 0) { break; } + + if (!rxmsg.isExtended()) { + // 11 bit frame, see if we have a handler + if (aux_11bit_driver != nullptr) { + aux_11bit_driver->handle_frame(rxmsg); + } + continue; + } + rx_frame.data_len = AP_HAL::CANFrame::dlcToDataLength(rxmsg.dlc); memcpy(rx_frame.data, rxmsg.data, rx_frame.data_len); #if HAL_CANFD_SUPPORTED @@ -434,4 +444,29 @@ bool CanardInterface::add_interface(AP_HAL::CANIface *can_iface) num_ifaces++; return true; } + +// add an 11 bit auxillary driver +bool CanardInterface::add_11bit_driver(CANSensor *sensor) +{ + if (aux_11bit_driver != nullptr) { + // only allow one + return false; + } + aux_11bit_driver = sensor; + return true; +} + +// handler for outgoing frames for auxillary drivers +bool CanardInterface::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) +{ + bool ret = false; + for (uint8_t iface = 0; iface < num_ifaces; iface++) { + if (ifaces[iface] == NULL) { + continue; + } + ret |= ifaces[iface]->send(out_frame, timeout_us, 0) > 0; + } + return ret; +} + #endif // #if HAL_ENABLE_DRONECAN_DRIVERS diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.h b/libraries/AP_DroneCAN/AP_Canard_iface.h index aa7533e6913b3f..ce9b75ee923d79 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.h +++ b/libraries/AP_DroneCAN/AP_Canard_iface.h @@ -5,6 +5,8 @@ #include class AP_DroneCAN; +class CANSensor; + class CanardInterface : public Canard::Interface { friend class AP_DroneCAN; public: @@ -48,6 +50,12 @@ class CanardInterface : public Canard::Interface { bool add_interface(AP_HAL::CANIface *can_drv); + // add an auxillary driver for 11 bit frames + bool add_11bit_driver(CANSensor *sensor); + + // handler for outgoing frames for auxillary drivers + bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us); + #if AP_TEST_DRONECAN_DRIVERS static CanardInterface& get_test_iface() { return test_iface; } static void processTestRx(); @@ -70,5 +78,8 @@ class CanardInterface : public Canard::Interface { HAL_Semaphore _sem_rx; CanardTxTransfer tx_transfer; dronecan_protocol_Stats protocol_stats; + + // auxillary 11 bit CANSensor + CANSensor *aux_11bit_driver; }; -#endif // HAL_ENABLE_DRONECAN_DRIVERS \ No newline at end of file +#endif // HAL_ENABLE_DRONECAN_DRIVERS diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 55d148bf1f90c0..9f34e7f93b10ef 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -1751,4 +1751,20 @@ void AP_DroneCAN::logging(void) #endif // HAL_LOGGING_ENABLED } +// add an 11 bit auxillary driver +bool AP_DroneCAN::add_11bit_driver(CANSensor *sensor) +{ + return canard_iface.add_11bit_driver(sensor); +} + +// handler for outgoing frames for auxillary drivers +bool AP_DroneCAN::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) +{ + if (out_frame.isExtended()) { + // don't allow extended frames to be sent by auxillary driver + return false; + } + return canard_iface.write_aux_frame(out_frame, timeout_us); +} + #endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h index f502e05a39f276..61f0528bc95ff5 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -69,6 +69,7 @@ // fwd-declare callback classes class AP_DroneCAN_DNA_Server; +class CANSensor; class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { friend class AP_DroneCAN_DNA_Server; @@ -85,6 +86,12 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { void init(uint8_t driver_index, bool enable_filters) override; bool add_interface(AP_HAL::CANIface* can_iface) override; + // add an 11 bit auxillary driver + bool add_11bit_driver(CANSensor *sensor) override; + + // handler for outgoing frames for auxillary drivers + bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) override; + uint8_t get_driver_index() const { return _driver_index; } // define string with length structure From d9d5e911101797b543b941588e47661b52fa8176 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Mon, 27 Nov 2023 17:54:31 -0600 Subject: [PATCH 439/499] hwdef: update SDH7V1 readme --- libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V1/README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V1/README.md b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V1/README.md index 41e56176f5b75c..87d7a568536d48 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V1/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/SDMODELH7V1/README.md @@ -139,7 +139,9 @@ FrSky Telemetry is supported using the Tx pin of any UART. You need to set the f The SDH7V1 supports OSD using OSD_TYPE 1 (MAX7456 driver). The defaults are also setup to allow DJI Goggle OSD support on UART1. PWM Output¶ -The KakuteH7 supports up to 8 PWM outputs. Outputs are available via two JST-SH connectors. All 8 outputs support DShot and bi-directional DShot, as well as all PWM types. +## PWM Outputs + +The SDH7V1 supports up to 8 PWM outputs. Outputs are available via two JST-SH connectors. All 8 outputs support DShot and bi-directional DShot, as well as all PWM types. The PWM is in 3 groups: From be668ddc1bf98c23d2d29be344806be0e9200ecc Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Fri, 24 Nov 2023 18:14:55 -0700 Subject: [PATCH 440/499] AP_ExternalAHRS: Clarify public interface design intent * Discussions with Tridge on design intent for these accessors Signed-off-by: Ryan Friedman --- libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h index b35d099c2ff1de..07436b7ae43888 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h @@ -32,16 +32,22 @@ class AP_ExternalAHRS_backend { // Get model/type name virtual const char* get_name() const = 0; - // accessors for AP_AHRS + // Accessors for AP_AHRS + + // If not healthy, none of the other API's can be trusted. + // Example: Serial cable is severed. virtual bool healthy(void) const = 0; + // The communication interface is up and the device has sent valid data. virtual bool initialised(void) const = 0; virtual bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const = 0; virtual void get_filter_status(nav_filter_status &status) const {} virtual void send_status_report(class GCS_MAVLINK &link) const {} - // check for new data + // Check for new data. + // This is used when there's not a separate thread for EAHRS. + // This can also copy interim state protected by locking. virtual void update() = 0; - + protected: AP_ExternalAHRS::state_t &state; uint16_t get_rate(void) const; From a05acfc090ea1605b9b4016a2c2de922164ee30c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 26 Nov 2023 11:44:52 +1100 Subject: [PATCH 441/499] AP_HAL: added last_recv_address() with supplied buffer this prevents a race condition with a static string --- libraries/AP_HAL/utility/Socket.cpp | 20 ++++++++++++++++---- libraries/AP_HAL/utility/Socket.h | 3 +++ 2 files changed, 19 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 0052778928aa46..de60d0d79cff05 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -247,6 +247,7 @@ ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uin ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) { if (!pollin(timeout_ms)) { + errno = EWOULDBLOCK; return -1; } socklen_t len = sizeof(in_addr); @@ -284,6 +285,19 @@ void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const port = ntohs(in_addr.sin_port); } +/* + return the IP address and port of the last received packet, using caller supplied buffer + */ +const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const +{ + const char *ret = inet_ntop(AF_INET, (void*)&in_addr.sin_addr, ip_addr_buf, buflen); + if (ret == nullptr) { + return nullptr; + } + port = ntohs(in_addr.sin_port); + return ret; +} + void SocketAPM::set_broadcast(void) const { int one = 1; @@ -350,13 +364,11 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) return nullptr; } - int newfd = CALL_PREFIX(accept)(fd, nullptr, nullptr); + socklen_t len = sizeof(in_addr); + int newfd = CALL_PREFIX(accept)(fd, (sockaddr *)&in_addr, &len); if (newfd == -1) { return nullptr; } - // turn off nagle for lower latency - int one = 1; - CALL_PREFIX(setsockopt)(newfd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); return new SocketAPM(false, newfd); } diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index 76ac0974c508a7..70e4a1cdea1584 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -57,6 +57,9 @@ class SocketAPM { // return the IP address and port of the last received packet void last_recv_address(const char *&ip_addr, uint16_t &port) const; + // return the IP address and port of the last received packet, using caller supplied buffer + const char *last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const; + // return true if there is pending data for input bool pollin(uint32_t timeout_ms); From c2ea29a198ffbd05b18425647d6060dc6dc32528 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 Nov 2023 09:30:29 +1100 Subject: [PATCH 442/499] waf: added compat/posix lwip headers to path this simplifies the networking code --- Tools/ardupilotwaf/boards.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 04a2e11e7d3011..5f7edf708c972c 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -1144,7 +1144,8 @@ def configure_env(self, cfg, env): ] env.INCLUDES += [ - cfg.srcnode.find_dir('libraries/AP_GyroFFT/CMSIS_5/include').abspath() + cfg.srcnode.find_dir('libraries/AP_GyroFFT/CMSIS_5/include').abspath(), + cfg.srcnode.find_dir('modules/ChibiOS/ext/lwip/src/include/compat/posix').abspath() ] # whitelist of compilers which we should build with -Werror From 0659ab8ef4bb58262d293b726707a2259fd39b81 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 Nov 2023 13:12:06 +1100 Subject: [PATCH 443/499] HAL_ChibiOS: increase max TCP resources --- libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h index 5b8b2aa6f55ef4..9546396ae01115 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h @@ -57,6 +57,10 @@ #define LWIP_STATS_DISPLAY 1 #define ETHARP_STATS 1 #define LWIP_IGMP 1 +#define MEMP_NUM_NETCONN 10 // up to 10 sockets +#define MEMP_NUM_TCP_PCB 10 +#define MEM_LIBC_MALLOC 1 +#define MEMP_MEM_MALLOC 1 #define DHCP_DEBUG LWIP_DBG_ON #ifndef LWIP_IPV6 From f471732aadac4dfef039650157235f71e8a286c2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 28 Nov 2023 09:53:11 +1100 Subject: [PATCH 444/499] HAL_ChibiOS: enable SO_REUSEADDR --- libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h index 9546396ae01115..7002236e2eda90 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h @@ -61,6 +61,8 @@ #define MEMP_NUM_TCP_PCB 10 #define MEM_LIBC_MALLOC 1 #define MEMP_MEM_MALLOC 1 +#define SO_REUSE 1 +#define SO_REUSE_RXTOALL 1 #define DHCP_DEBUG LWIP_DBG_ON #ifndef LWIP_IPV6 From f345d94e916ab902b8234eb720c931b8176610aa Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 27 Nov 2023 14:49:29 +1100 Subject: [PATCH 445/499] GCS_MAVLink: increase max mavlink connections when networking enabled --- libraries/GCS_MAVLink/GCS_MAVLink.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index dd4ab4271a5532..26a30d068d312c 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -3,6 +3,7 @@ #pragma once #include +#include // we have separate helpers disabled to make it possible // to select MAVLink 1.0 in the arduino GUI build @@ -14,8 +15,13 @@ #define MAVLINK_START_UART_SEND(chan, size) comm_send_lock(chan, size) #define MAVLINK_END_UART_SEND(chan, size) comm_send_unlock(chan) +#if AP_NETWORKING_ENABLED +// allow 7 telemetry ports with networking +#define MAVLINK_COMM_NUM_BUFFERS 7 +#else // allow five telemetry ports #define MAVLINK_COMM_NUM_BUFFERS 5 +#endif #define MAVLINK_GET_CHANNEL_BUFFER 1 #define MAVLINK_GET_CHANNEL_STATUS 1 From afe0b849b966c537ed5cbd698f8524abc961db3b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 28 Nov 2023 07:08:00 +1100 Subject: [PATCH 446/499] Tools: test all 4 network port types --- Tools/autotest/vehicle_test_suite.py | 95 ++++++++++++++++++++++++---- 1 file changed, 81 insertions(+), 14 deletions(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index c44aef485f5842..87c881efbda588 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -4268,27 +4268,94 @@ def TestLogDownloadMAVProxyNetwork(self, upload_logs=False): self.set_parameters({ "NET_ENABLED": 1, "NET_DHCP": 0, + "LOG_DARM_RATEMAX": 2, # make small logs + # UDP client "NET_P1_TYPE": 1, "NET_P1_PROTOCOL": 2, - "NET_P1_PORT": 15004, + "NET_P1_PORT": 16001, "NET_P1_IP0": 127, "NET_P1_IP1": 0, "NET_P1_IP2": 0, - "NET_P1_IP3": 1 + "NET_P1_IP3": 1, + # UDP server + "NET_P2_TYPE": 2, + "NET_P2_PROTOCOL": 2, + "NET_P2_PORT": 16002, + "NET_P2_IP0": 0, + "NET_P2_IP1": 0, + "NET_P2_IP2": 0, + "NET_P2_IP3": 0, + # TCP client + "NET_P3_TYPE": 3, + "NET_P3_PROTOCOL": 2, + "NET_P3_PORT": 16003, + "NET_P3_IP0": 127, + "NET_P3_IP1": 0, + "NET_P3_IP2": 0, + "NET_P3_IP3": 1, + # TCP server + "NET_P4_TYPE": 4, + "NET_P4_PROTOCOL": 2, + "NET_P4_PORT": 16004, + "NET_P4_IP0": 0, + "NET_P4_IP1": 0, + "NET_P4_IP2": 0, + "NET_P4_IP3": 0, }) self.reboot_sitl() - filename = "MAVProxy-downloaded-net-log.BIN" - mavproxy = self.start_mavproxy(master=':15004') - self.mavproxy_load_module(mavproxy, 'log') - mavproxy.send("log list\n") - mavproxy.expect("numLogs") - self.wait_heartbeat() - self.wait_heartbeat() - mavproxy.send("set shownoise 0\n") - mavproxy.send("log download latest %s\n" % filename) - mavproxy.expect("Finished downloading", timeout=120) - self.mavproxy_unload_module(mavproxy, 'log') - self.stop_mavproxy(mavproxy) + endpoints = [('UDPClient', ':16001') , + ('UDPServer', 'udpout:127.0.0.1:16002'), + ('TCPClient', 'tcpin:0.0.0.0:16003'), + ('TCPServer', 'tcp:127.0.0.1:16004')] + for name, e in endpoints: + self.progress("Downloading log with %s %s" % (name, e)) + filename = "MAVProxy-downloaded-net-log-%s.BIN" % name + + mavproxy = self.start_mavproxy(master=e) + self.mavproxy_load_module(mavproxy, 'log') + self.wait_heartbeat() + mavproxy.send("log list\n") + mavproxy.expect("numLogs") + mavproxy.send("log download latest %s\n" % filename) + mavproxy.expect("Finished downloading", timeout=120) + self.mavproxy_unload_module(mavproxy, 'log') + self.stop_mavproxy(mavproxy) + + self.set_parameters({ + # multicast UDP client + "NET_P1_TYPE": 1, + "NET_P1_PROTOCOL": 2, + "NET_P1_PORT": 14550, + "NET_P1_IP0": 239, + "NET_P1_IP1": 255, + "NET_P1_IP2": 145, + "NET_P1_IP3": 50, + # Broadcast UDP client + "NET_P2_TYPE": 1, + "NET_P2_PROTOCOL": 2, + "NET_P2_PORT": 16005, + "NET_P2_IP0": 255, + "NET_P2_IP1": 255, + "NET_P2_IP2": 255, + "NET_P2_IP3": 255, + }) + self.reboot_sitl() + endpoints = [('UDPMulticast', 'mcast:') , + ('UDPBroadcast', ':16005')] + for name, e in endpoints: + self.progress("Downloading log with %s %s" % (name, e)) + filename = "MAVProxy-downloaded-net-log-%s.BIN" % name + + mavproxy = self.start_mavproxy(master=e) + self.mavproxy_load_module(mavproxy, 'log') + self.wait_heartbeat() + mavproxy.send("log list\n") + mavproxy.expect("numLogs") + mavproxy.send("log download latest %s\n" % filename) + mavproxy.expect("Finished downloading", timeout=120) + self.mavproxy_unload_module(mavproxy, 'log') + self.stop_mavproxy(mavproxy) + self.context_pop() def TestLogDownloadMAVProxyCAN(self, upload_logs=False): From 7d1f048ca70912812976d2c87cc6bf767f513d07 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 26 Nov 2023 11:46:07 +1100 Subject: [PATCH 447/499] AP_Networking: support UDP server, TCP client and TCP server and implement mavlink packetisation and flow control return --- libraries/AP_Networking/AP_Networking.cpp | 2 +- libraries/AP_Networking/AP_Networking.h | 31 +- .../AP_Networking/AP_Networking_address.cpp | 7 +- .../AP_Networking/AP_Networking_address.h | 5 +- .../AP_Networking/AP_Networking_port.cpp | 317 ++++++++++++++++-- .../AP_Networking/AP_Networking_tests.cpp | 45 +++ 6 files changed, 372 insertions(+), 35 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 7783adf77dac4e..0349145f648ddd 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -63,7 +63,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @Param: TESTS // @DisplayName: Test enable flags // @Description: Enable/Disable networking tests - // @Bitmask: 0:UDP echo test,1:TCP echo test + // @Bitmask: 0:UDP echo test,1:TCP echo test, 2:TCP discard test // @RebootRequired: True // @User: Advanced AP_GROUPINFO("TESTS", 7, AP_Networking, param.tests, 0), diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index c931fc26982461..257a4950c7daf9 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -184,6 +184,9 @@ class AP_Networking enum class NetworkPortType { NONE = 0, UDP_CLIENT = 1, + UDP_SERVER = 2, + TCP_CLIENT = 3, + TCP_SERVER = 4, }; // class for NET_Pn_* parameters @@ -199,6 +202,7 @@ class AP_Networking AP_Networking_IPV4 ip {"0.0.0.0"}; AP_Int32 port; SocketAPM *sock; + SocketAPM *listen_sock; bool is_initialized() override { return true; @@ -207,11 +211,22 @@ class AP_Networking return false; } - void udp_client_init(const uint32_t size_rx, const uint32_t size_tx); + void wait_startup(); + void udp_client_init(void); + void udp_server_init(void); + void tcp_server_init(void); + void tcp_client_init(void); + void udp_client_loop(void); + void udp_server_loop(void); + void tcp_client_loop(void); + void tcp_server_loop(void); + + bool send_receive(void); private: bool init_buffers(const uint32_t size_rx, const uint32_t size_tx); + void thread_create(AP_HAL::MemberProc); uint32_t txspace() override; void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override; @@ -222,10 +237,22 @@ class AP_Networking void _flush() override {} bool _discard_input() override; + enum flow_control get_flow_control(void) override; + + uint32_t bw_in_bytes_per_second() const override { + return 1000000UL; + } + ByteBuffer *readbuffer; ByteBuffer *writebuffer; + char thread_name[10]; uint32_t last_size_tx; uint32_t last_size_rx; + bool packetise; + bool connected; + bool have_received; + bool close_on_recv_error; + HAL_Semaphore sem; }; @@ -236,10 +263,12 @@ class AP_Networking enum { TEST_UDP_CLIENT = (1U<<0), TEST_TCP_CLIENT = (1U<<1), + TEST_TCP_DISCARD = (1U<<2), }; void start_tests(void); void test_UDP_client(void); void test_TCP_client(void); + void test_TCP_discard(void); #endif // AP_NETWORKING_TESTS_ENABLED // ports for registration with serial manager diff --git a/libraries/AP_Networking/AP_Networking_address.cpp b/libraries/AP_Networking/AP_Networking_address.cpp index 5cadbbe6f7a144..28900e387b2673 100644 --- a/libraries/AP_Networking/AP_Networking_address.cpp +++ b/libraries/AP_Networking/AP_Networking_address.cpp @@ -6,6 +6,7 @@ #if AP_NETWORKING_ENABLED +#include #include "AP_Networking.h" const AP_Param::GroupInfo AP_Networking_IPV4::var_info[] = { @@ -68,9 +69,11 @@ void AP_Networking_IPV4::set_default_uint32(uint32_t v) } } -const char* AP_Networking_IPV4::get_str() const +const char* AP_Networking_IPV4::get_str() { - return AP_Networking::convert_ip_to_str(get_uint32()); + const auto ip = ntohl(get_uint32()); + inet_ntop(AF_INET, &ip, strbuf, sizeof(strbuf)); + return strbuf; } #endif // AP_NETWORKING_ENABLED diff --git a/libraries/AP_Networking/AP_Networking_address.h b/libraries/AP_Networking/AP_Networking_address.h index a4a3b6f8b29a8f..f9852948676ec8 100644 --- a/libraries/AP_Networking/AP_Networking_address.h +++ b/libraries/AP_Networking/AP_Networking_address.h @@ -18,12 +18,15 @@ class AP_Networking_IPV4 void set_uint32(uint32_t addr); // return address as a null-terminated string - const char* get_str() const; + const char* get_str(); // set default address from a uint32 void set_default_uint32(uint32_t addr); static const struct AP_Param::GroupInfo var_info[]; + +private: + char strbuf[16]; }; /* diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index e70224cf4b4b7b..23c43df13304fb 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -11,6 +11,8 @@ #include #include #include +#include +#include extern const AP_HAL::HAL& hal; @@ -22,11 +24,15 @@ extern const AP_HAL::HAL& hal; #define AP_NETWORKING_PORT_MIN_RXSIZE 2048 #endif +#ifndef AP_NETWORKING_PORT_STACK_SIZE +#define AP_NETWORKING_PORT_STACK_SIZE 1024 +#endif + const AP_Param::GroupInfo AP_Networking::Port::var_info[] = { // @Param: TYPE // @DisplayName: Port type - // @Description: Port type - // @Values: 0:Disabled, 1:UDP client + // @Description: Port type for network serial port. For the two client types a valid destination IP address must be set. For the two server types either 0.0.0.0 or a local address can be used. + // @Values: 0:Disabled, 1:UDP client, 2:TCP client, 3:TCP server // @RebootRequired: True // @User: Advanced AP_GROUPINFO_FLAGS("TYPE", 1, AP_Networking::Port, type, 0, AP_PARAM_FLAG_ENABLE), @@ -66,45 +72,121 @@ void AP_Networking::ports_init(void) case NetworkPortType::NONE: break; case NetworkPortType::UDP_CLIENT: - p.udp_client_init(AP_NETWORKING_PORT_MIN_RXSIZE, AP_NETWORKING_PORT_MIN_TXSIZE); + p.udp_client_init(); + break; + case NetworkPortType::UDP_SERVER: + p.udp_server_init(); + break; + case NetworkPortType::TCP_SERVER: + p.tcp_server_init(); + break; + case NetworkPortType::TCP_CLIENT: + p.tcp_client_init(); break; } - if (p.sock != nullptr) { + if (p.sock != nullptr || p.listen_sock != nullptr) { AP::serialmanager().register_port(&p); } } } /* - initialise a UDP client + wrapper for thread_create for port functions */ -void AP_Networking::Port::udp_client_init(const uint32_t size_rx, const uint32_t size_tx) +void AP_Networking::Port::thread_create(AP_HAL::MemberProc proc) { - WITH_SEMAPHORE(sem); - if (!init_buffers(size_rx, size_tx)) { + const uint8_t idx = state.idx - AP_SERIALMANAGER_NET_PORT_1; + hal.util->snprintf(thread_name, sizeof(thread_name), "NET_P%u", unsigned(idx)); + + if (!init_buffers(AP_NETWORKING_PORT_MIN_RXSIZE, AP_NETWORKING_PORT_MIN_TXSIZE)) { + AP_BoardConfig::allocation_error("Failed to allocate %s buffers", thread_name); return; } - if (sock != nullptr) { + + if (!hal.scheduler->thread_create(proc, thread_name, AP_NETWORKING_PORT_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_UART, 0)) { + AP_BoardConfig::allocation_error("Failed to allocate %s client thread", thread_name); + } +} + +/* + initialise a UDP client + */ +void AP_Networking::Port::udp_client_init(void) +{ + sock = new SocketAPM(true); + if (sock == nullptr) { return; } + sock->set_blocking(false); + + // setup for packet boundaries if this is mavlink + packetise = (state.protocol == AP_SerialManager::SerialProtocol_MAVLink || + state.protocol == AP_SerialManager::SerialProtocol_MAVLink2); + + thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::Port::udp_client_loop, void)); +} + +/* + initialise a UDP server + */ +void AP_Networking::Port::udp_server_init(void) +{ sock = new SocketAPM(true); if (sock == nullptr) { return; } - if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::Port::udp_client_loop, void), "NET", 2048, AP_HAL::Scheduler::PRIORITY_UART, 0)) { - AP_BoardConfig::allocation_error("Failed to allocate UDP client thread"); + sock->set_blocking(false); + + // setup for packet boundaries if this is mavlink + packetise = (state.protocol == AP_SerialManager::SerialProtocol_MAVLink || + state.protocol == AP_SerialManager::SerialProtocol_MAVLink2); + + thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::Port::udp_server_loop, void)); +} + +/* + initialise a TCP server + */ +void AP_Networking::Port::tcp_server_init(void) +{ + listen_sock = new SocketAPM(false); + if (listen_sock == nullptr) { + return; } + listen_sock->reuseaddress(); + + thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::Port::tcp_server_loop, void)); } /* - update a UDP client + initialise a TCP client */ -void AP_Networking::Port::udp_client_loop(void) +void AP_Networking::Port::tcp_client_init(void) +{ + sock = new SocketAPM(false); + if (sock != nullptr) { + sock->set_blocking(true); + thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::Port::tcp_client_loop, void)); + } +} + +/* + wait for networking stack to be up + */ +void AP_Networking::Port::wait_startup(void) { while (!hal.scheduler->is_system_initialized()) { hal.scheduler->delay(100); } hal.scheduler->delay(1000); +} + +/* + update a UDP client + */ +void AP_Networking::Port::udp_client_loop(void) +{ + wait_startup(); const char *dest = ip.get_str(); if (!sock->connect(dest, port.get())) { @@ -116,31 +198,188 @@ void AP_Networking::Port::udp_client_loop(void) GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP[%u]: connected to %s:%u", (unsigned)state.idx, dest, unsigned(port.get())); + connected = true; + + bool active = false; while (true) { - hal.scheduler->delay_microseconds(500); - WITH_SEMAPHORE(sem); + if (!active) { + hal.scheduler->delay_microseconds(100); + } + active = send_receive(); + } +} - // handle outgoing packets - uint32_t available; - const auto *ptr = writebuffer->readptr(available); - if (ptr != nullptr) { - const auto ret = sock->send(ptr, available); - if (ret > 0) { - writebuffer->advance(ret); +/* + update a UDP server + */ +void AP_Networking::Port::udp_server_loop(void) +{ + wait_startup(); + + const char *addr = ip.get_str(); + if (!sock->bind(addr, port.get())) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "UDP[%u]: Failed to bind to %s:%u", (unsigned)state.idx, addr, unsigned(port.get())); + delete sock; + sock = nullptr; + return; + } + sock->reuseaddress(); + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP[%u]: bound to %s:%u", (unsigned)state.idx, addr, unsigned(port.get())); + + bool active = false; + while (true) { + if (!active) { + hal.scheduler->delay_microseconds(100); + } + active = send_receive(); + } +} + +/* + update a TCP server + */ +void AP_Networking::Port::tcp_server_loop(void) +{ + wait_startup(); + + const char *addr = ip.get_str(); + if (!listen_sock->bind(addr, port.get()) || !listen_sock->listen(1)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP[%u]: Failed to bind to %s:%u", (unsigned)state.idx, addr, unsigned(port.get())); + delete listen_sock; + listen_sock = nullptr; + return; + } + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP[%u]: bound to %s:%u", (unsigned)state.idx, addr, unsigned(port.get())); + + close_on_recv_error = true; + + bool active = false; + while (true) { + if (!active) { + hal.scheduler->delay_microseconds(100); + } + if (sock == nullptr) { + sock = listen_sock->accept(100); + if (sock != nullptr) { + sock->set_blocking(false); + char buf[16]; + uint16_t last_port; + const char *last_addr = listen_sock->last_recv_address(buf, sizeof(buf), last_port); + if (last_addr != nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP[%u]: connection from %s:%u", (unsigned)state.idx, last_addr, unsigned(last_port)); + } + connected = true; + sock->reuseaddress(); } } + if (sock != nullptr) { + active = send_receive(); + } + } +} - // handle incoming packets - const auto space = readbuffer->space(); - if (space > 0) { - const uint32_t n = MIN(350U, space); - uint8_t buf[n]; - const auto ret = sock->recv(buf, n, 0); - if (ret > 0) { - readbuffer->write(buf, ret); +/* + update a TCP client + */ +void AP_Networking::Port::tcp_client_loop(void) +{ + wait_startup(); + + close_on_recv_error = true; + + bool active = false; + while (true) { + if (!active) { + hal.scheduler->delay_microseconds(100); + } + if (sock == nullptr) { + sock = new SocketAPM(false); + if (sock == nullptr) { + continue; + } + sock->set_blocking(true); + connected = false; + } + if (!connected) { + const char *dest = ip.get_str(); + connected = sock->connect(dest, port.get()); + if (connected) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP[%u]: connected to %s:%u", unsigned(state.idx), dest, unsigned(port.get())); + sock->set_blocking(false); + } else { + delete sock; + sock = nullptr; + // don't try and connect too fast + hal.scheduler->delay(100); + } + } + if (sock != nullptr && connected) { + active = send_receive(); + } + } +} + +/* + run one send/receive loop + */ +bool AP_Networking::Port::send_receive(void) +{ + + bool active = false; + WITH_SEMAPHORE(sem); + + // handle incoming packets + const auto space = readbuffer->space(); + if (space > 0) { + const uint32_t n = MIN(300U, space); + uint8_t buf[n]; + const auto ret = sock->recv(buf, n, 0); + if (close_on_recv_error && ret == 0) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP[%u]: closed connection", unsigned(state.idx)); + delete sock; + sock = nullptr; + return false; + } + if (ret > 0) { + readbuffer->write(buf, ret); + active = true; + have_received = true; + } + } + + if (connected) { + // handle outgoing packets + uint32_t available = writebuffer->available(); + available = MIN(300U, available); + if (packetise) { + available = mavlink_packetise(*writebuffer, available); + } + if (available > 0) { + uint8_t buf[available]; + auto n = writebuffer->peekbytes(buf, available); + if (n > 0) { + const auto ret = sock->send(buf, n); + if (ret > 0) { + writebuffer->advance(ret); + active = true; + } + } + } + } else { + if (type == NetworkPortType::UDP_SERVER && have_received) { + // connect the socket to the last receive address if we have one + char buf[16]; + uint16_t last_port; + const char *last_addr = sock->last_recv_address(buf, sizeof(buf), last_port); + if (last_addr != nullptr && port != 0) { + connected = sock->connect(last_addr, last_port); } } } + + return active; } /* @@ -210,4 +449,22 @@ bool AP_Networking::Port::init_buffers(const uint32_t size_rx, const uint32_t si return readbuffer != nullptr && writebuffer != nullptr; } +/* + return flow control state + */ +enum AP_HAL::UARTDriver::flow_control AP_Networking::Port::get_flow_control(void) +{ + const NetworkPortType ptype = (NetworkPortType)type; + switch (ptype) { + case NetworkPortType::TCP_CLIENT: + case NetworkPortType::TCP_SERVER: + return AP_HAL::UARTDriver::FLOW_CONTROL_ENABLE; + case NetworkPortType::UDP_CLIENT: + case NetworkPortType::UDP_SERVER: + case NetworkPortType::NONE: + break; + } + return AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE; +} + #endif // AP_NETWORKING_ENABLED diff --git a/libraries/AP_Networking/AP_Networking_tests.cpp b/libraries/AP_Networking/AP_Networking_tests.cpp index 9370d93a23b407..2fc050d9ddd4a6 100644 --- a/libraries/AP_Networking/AP_Networking_tests.cpp +++ b/libraries/AP_Networking/AP_Networking_tests.cpp @@ -28,6 +28,11 @@ void AP_Networking::start_tests(void) "TCP_client", 8192, AP_HAL::Scheduler::PRIORITY_IO, -1); } + if (param.tests & TEST_TCP_DISCARD) { + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::test_TCP_discard, void), + "TCP_discard", + 8192, AP_HAL::Scheduler::PRIORITY_UART, -1); + } } /* @@ -100,4 +105,44 @@ void AP_Networking::test_TCP_client(void) } } +/* + start TCP discard (throughput) test + */ +void AP_Networking::test_TCP_discard(void) +{ + while (!hal.scheduler->is_system_initialized()) { + hal.scheduler->delay(100); + } + hal.scheduler->delay(1000); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_discard: starting"); + const char *dest = param.test_ipaddr.get_str(); + auto *sock = new SocketAPM(false); + if (sock == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_discard: failed to create socket"); + return; + } + // connect to the discard service, which is port 9 + if (!sock->connect(dest, 9)) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_discard: connect failed"); + return; + } + const uint32_t bufsize = 1024; + uint8_t *buf = (uint8_t*)malloc(bufsize); + for (uint32_t i=0; isend(buf, bufsize); + const uint32_t now = AP_HAL::millis(); + if (now - last_report_ms >= 1000) { + float dt = (now - last_report_ms)*0.001; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Discard throughput %.3f kbyte/sec", (total_sent/dt)*1.0e-3); + total_sent = 0; + last_report_ms = now; + } + } +} + #endif // AP_NETWORKING_ENABLED && AP_NETWORKING_TESTS_ENABLED From 2ee48dea29219a740d714f6eb7707169e698488f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 28 Nov 2023 09:22:54 +1100 Subject: [PATCH 448/499] AP_HAL: support bi-directional UDP broadcast sockets --- libraries/AP_HAL/utility/Socket.cpp | 32 ++++++++++++++++++++++++----- 1 file changed, 27 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index de60d0d79cff05..a5beacca66d054 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -81,6 +81,7 @@ bool SocketAPM::connect(const char *address, uint16_t port) { struct sockaddr_in sockaddr; int ret; + int one = 1; make_sockaddr(address, port, sockaddr); if (datagram && is_multicast_address(sockaddr)) { @@ -92,7 +93,6 @@ bool SocketAPM::connect(const char *address, uint16_t port) return false; } struct sockaddr_in sockaddr_mc = sockaddr; - int one = 1; struct ip_mreq mreq {}; #ifdef FD_CLOEXEC CALL_PREFIX(fcntl)(fd_in, F_SETFD, FD_CLOEXEC); @@ -109,7 +109,7 @@ bool SocketAPM::connect(const char *address, uint16_t port) ret = CALL_PREFIX(bind)(fd_in, (struct sockaddr *)&sockaddr_mc, sizeof(sockaddr)); if (ret == -1) { - goto fail_mc; + goto fail_multi; } mreq.imr_multiaddr.s_addr = sockaddr.sin_addr.s_addr; @@ -117,10 +117,14 @@ bool SocketAPM::connect(const char *address, uint16_t port) ret = CALL_PREFIX(setsockopt)(fd_in, IPPROTO_IP, IP_ADD_MEMBERSHIP, &mreq, sizeof(mreq)); if (ret == -1) { - goto fail_mc; + goto fail_multi; } - } else if (datagram && sockaddr.sin_addr.s_addr == INADDR_BROADCAST) { + } + + if (datagram && sockaddr.sin_addr.s_addr == INADDR_BROADCAST) { + // setup for bi-directional UDP broadcast set_broadcast(); + reuseaddress(); } ret = CALL_PREFIX(connect)(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); @@ -128,9 +132,27 @@ bool SocketAPM::connect(const char *address, uint16_t port) return false; } connected = true; + + if (datagram && sockaddr.sin_addr.s_addr == INADDR_BROADCAST) { + // for bi-directional UDP broadcast we need 2 sockets + struct sockaddr_in send_addr; + socklen_t send_len = sizeof(send_addr); + ret = CALL_PREFIX(getsockname)(fd, (struct sockaddr *)&send_addr, &send_len); + fd_in = CALL_PREFIX(socket)(AF_INET, SOCK_DGRAM, 0); + if (fd_in == -1) { + goto fail_multi; + } + CALL_PREFIX(setsockopt)(fd_in, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); + // 2nd socket needs to be bound to wildcard + send_addr.sin_addr.s_addr = INADDR_ANY; + ret = CALL_PREFIX(bind)(fd_in, (struct sockaddr *)&send_addr, sizeof(send_addr)); + if (ret == -1) { + goto fail_multi; + } + } return true; -fail_mc: +fail_multi: CALL_PREFIX(close)(fd_in); fd_in = -1; return false; From 3965c7e4bf3ed28e2fc8c20031f663317efe78aa Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Sat, 25 Nov 2023 21:23:58 -0700 Subject: [PATCH 449/499] AP_Math: Replace deprecated benchmark function * Been deprecated since 1.2.0 Signed-off-by: Ryan Friedman --- libraries/AP_Math/benchmarks/benchmark_geodesic_grid.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Math/benchmarks/benchmark_geodesic_grid.cpp b/libraries/AP_Math/benchmarks/benchmark_geodesic_grid.cpp index 71da640b0a74af..684a9ec8de4b7e 100644 --- a/libraries/AP_Math/benchmarks/benchmark_geodesic_grid.cpp +++ b/libraries/AP_Math/benchmarks/benchmark_geodesic_grid.cpp @@ -86,7 +86,7 @@ static bool section_triangle(unsigned int section_index, static void BM_GeodesicGridSections(benchmark::State& state) { Vector3f v, a, b, c; - int section = state.range_x(); + int section = state.range(0); section_triangle(section, a, b, c); v = (a + b + c) / 3.0f; From adff2ed5d7d1e23cb63f9aa605c5a851c5cb7efa Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Sat, 25 Nov 2023 20:26:49 -0700 Subject: [PATCH 450/499] Tools: Add g++ 11.4 to whitelist Signed-off-by: Ryan Friedman --- Tools/ardupilotwaf/boards.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 5f7edf708c972c..2d969671e1a6f9 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -799,6 +799,7 @@ def configure_env(self, cfg, env): # whitelist of compilers which we should build with -Werror gcc_whitelist = frozenset([ ('11','3','0'), + ('11','4','0'), ('12','1','0'), ]) @@ -1156,6 +1157,7 @@ def configure_env(self, cfg, env): ('9','3','1'), ('10','2','1'), ('11','3','0'), + ('11','4','0'), ]) if cfg.env.HAL_CANFD_SUPPORTED: From 62dfe0f04b13e563581c903669e6fc07bdc757db Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 15 Nov 2023 21:40:42 +0900 Subject: [PATCH 451/499] AR_PosControl: no min speed when stopping --- libraries/APM_Control/AR_PosControl.cpp | 22 +++++++++++++--------- 1 file changed, 13 insertions(+), 9 deletions(-) diff --git a/libraries/APM_Control/AR_PosControl.cpp b/libraries/APM_Control/AR_PosControl.cpp index 12eee4b7ce4a47..4107082558054b 100644 --- a/libraries/APM_Control/AR_PosControl.cpp +++ b/libraries/APM_Control/AR_PosControl.cpp @@ -141,9 +141,11 @@ void AR_PosControl::update(float dt) } // calculation velocity error + bool stopping = false; if (_vel_desired_valid) { // add target velocity to desired velocity from position error _vel_target += _vel_desired; + stopping = _vel_desired.is_zero(); } // limit velocity to maximum speed @@ -192,19 +194,21 @@ void AR_PosControl::update(float dt) const Vector2f vel_target_FR = AP::ahrs().earth_to_body2D(_vel_target); // desired speed is normally the forward component (only) of the target velocity - // but we do not let it fall below the minimum turn speed unless the vehicle is slowing down - const float abs_des_speed_min = MIN(_vel_target.length(), turn_speed_min); - float des_speed; - if (_reversed != backing_up) { - // if reversed or backing up desired speed will be negative - des_speed = MIN(-abs_des_speed_min, vel_target_FR.x); - } else { - des_speed = MAX(abs_des_speed_min, vel_target_FR.x); + float des_speed = vel_target_FR.x; + if (!stopping) { + // do not let target speed fall below the minimum turn speed unless the vehicle is slowing down + const float abs_des_speed_min = MIN(_vel_target.length(), turn_speed_min); + if (_reversed != backing_up) { + // if reversed or backing up desired speed will be negative + des_speed = MIN(-abs_des_speed_min, vel_target_FR.x); + } else { + des_speed = MAX(abs_des_speed_min, vel_target_FR.x); + } } _desired_speed = _atc.get_desired_speed_accel_limited(des_speed, dt); // calculate turn rate from desired lateral acceleration - _desired_lat_accel = accel_target_FR.y; + _desired_lat_accel = stopping ? 0 : accel_target_FR.y; _desired_turn_rate_rads = _atc.get_turn_rate_from_lat_accel(_desired_lat_accel, _desired_speed); } From d88dfa4428192d92776da60b47bb75b9150b55c6 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 24 Nov 2023 10:10:11 +0900 Subject: [PATCH 452/499] Rover: auto navigates while stopped --- Rover/mode_auto.cpp | 20 +++++++------------- 1 file changed, 7 insertions(+), 13 deletions(-) diff --git a/Rover/mode_auto.cpp b/Rover/mode_auto.cpp index 439f4a014b034e..9f827864ce806d 100644 --- a/Rover/mode_auto.cpp +++ b/Rover/mode_auto.cpp @@ -82,21 +82,15 @@ void ModeAuto::update() switch (_submode) { case SubMode::WP: { - // check if we've reached the destination - if (!g2.wp_nav.reached_destination() || g2.wp_nav.is_fast_waypoint()) { - // update navigation controller - navigate_to_waypoint(); - } else { - // we have reached the destination so stay here - if (rover.is_boat()) { - if (!start_loiter()) { - start_stop(); - } - } else { - start_stop(); - } + // boats loiter once the waypoint is reached + if (rover.is_boat() && g2.wp_nav.reached_destination() && !g2.wp_nav.is_fast_waypoint()) { + start_loiter(); + // update distance to destination _distance_to_destination = rover.current_loc.get_distance(g2.wp_nav.get_destination()); + } else { + // update navigation controller + navigate_to_waypoint(); } break; } From 03c50db07e38ab1ce7db9b92704e38f218bf9050 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 24 Nov 2023 11:03:48 +0900 Subject: [PATCH 453/499] AR_WPNav: pos control updated during pivots --- libraries/AR_WPNav/AR_WPNav.cpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/libraries/AR_WPNav/AR_WPNav.cpp b/libraries/AR_WPNav/AR_WPNav.cpp index afb6f4956cc685..1ab6c817d86fb5 100644 --- a/libraries/AR_WPNav/AR_WPNav.cpp +++ b/libraries/AR_WPNav/AR_WPNav.cpp @@ -505,6 +505,10 @@ void AR_WPNav::update_steering_and_speed(const Location ¤t_loc, float dt) { _cross_track_error = calc_crosstrack_error(current_loc); + // update position controller + _pos_control.set_reversed(_reversed); + _pos_control.update(dt); + // handle pivot turns if (_pivot.active()) { // decelerate to zero @@ -512,14 +516,11 @@ void AR_WPNav::update_steering_and_speed(const Location ¤t_loc, float dt) _desired_heading_cd = _reversed ? wrap_360_cd(oa_wp_bearing_cd() + 18000) : oa_wp_bearing_cd(); _desired_turn_rate_rads = is_zero(_desired_speed_limited) ? _pivot.get_turn_rate_rads(_desired_heading_cd * 0.01, dt) : 0; _desired_lat_accel = 0.0f; - return; + } else { + _desired_speed_limited = _pos_control.get_desired_speed(); + _desired_turn_rate_rads = _pos_control.get_desired_turn_rate_rads(); + _desired_lat_accel = _pos_control.get_desired_lat_accel(); } - - _pos_control.set_reversed(_reversed); - _pos_control.update(dt); - _desired_speed_limited = _pos_control.get_desired_speed(); - _desired_turn_rate_rads = _pos_control.get_desired_turn_rate_rads(); - _desired_lat_accel = _pos_control.get_desired_lat_accel(); } // settor to allow vehicle code to provide turn related param values to this library (should be updated regularly) From 875960a4c6b786ebac54d029dd99818d01936dd8 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 28 Nov 2023 08:16:12 +0900 Subject: [PATCH 454/499] Rover: boats keep navigating at WP if loiter fails --- Rover/mode_auto.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Rover/mode_auto.cpp b/Rover/mode_auto.cpp index 9f827864ce806d..5d2029b8201d25 100644 --- a/Rover/mode_auto.cpp +++ b/Rover/mode_auto.cpp @@ -83,13 +83,13 @@ void ModeAuto::update() case SubMode::WP: { // boats loiter once the waypoint is reached + bool keep_navigating = true; if (rover.is_boat() && g2.wp_nav.reached_destination() && !g2.wp_nav.is_fast_waypoint()) { - start_loiter(); + keep_navigating = !start_loiter(); + } - // update distance to destination - _distance_to_destination = rover.current_loc.get_distance(g2.wp_nav.get_destination()); - } else { - // update navigation controller + // update navigation controller + if (keep_navigating) { navigate_to_waypoint(); } break; From bf9881579c008f0feb8f1093d84bffc704c82726 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Sun, 12 Nov 2023 22:04:22 -0700 Subject: [PATCH 455/499] AP_GPS: GSOF robust config parsing * Refactor checksum to unique function * Clear uart before reading data * Add ack/nack check * Implement output disable before requesting GSOF data * Improve debug message to have line number * Use debug in more code * Stop delaying in configuration Signed-off-by: Ryan Friedman --- libraries/AP_GPS/AP_GPS_GSOF.cpp | 192 +++++++++++++++++++++++++------ libraries/AP_GPS/AP_GPS_GSOF.h | 56 +++++++-- 2 files changed, 205 insertions(+), 43 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 9de37cc4b71f48..389b45dea68ef6 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -35,12 +35,15 @@ extern const AP_HAL::HAL& hal; +// Set this to 1 to enable debug messages #define gsof_DEBUGGING 0 #if gsof_DEBUGGING # define Debug(fmt, args ...) \ do { \ - hal.console->printf("%s:%d: " fmt "\n", \ + hal.console->printf("%u %s:%s:%d: " fmt "\n", \ + AP_HAL::millis(), \ + __FILE__, \ __FUNCTION__, __LINE__, \ ## args); \ hal.scheduler->delay(1); \ @@ -66,10 +69,10 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d has invalid COM port setting of %d", state.instance, com_port); return; } - requestBaud(static_cast(com_port)); - - const uint32_t now = AP_HAL::millis(); - gsofmsg_time = now + 110; + const HW_Baud baud = HW_Baud::BAUD115K; + // Start by disabling output during config + [[maybe_unused]] const auto output_disabled = disableOutput(static_cast(com_port)); + is_baud_configured = requestBaud(static_cast(com_port), baud); } // Process all bytes available from the stream @@ -77,19 +80,27 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, bool AP_GPS_GSOF::read(void) { - const uint32_t now = AP_HAL::millis(); + if (!is_baud_configured) { + // Debug("Baud not configured, not ready to read()"); + return false; + } - if (gsofmsgreq_index < (sizeof(gsofmsgreq))) { + bool gsof_configured = true; + + static_assert(sizeof(gsofmsgreq) != 0, "gsofmsgreq is not empty"); + while (gsofmsgreq_index < (sizeof(gsofmsgreq))) { const auto com_port = gps._com_port[state.instance].get(); if (!validate_com_port(com_port)) { // The user parameter for COM port is not a valid GSOF port return false; } - if (now > gsofmsg_time) { - requestGSOF(gsofmsgreq[gsofmsgreq_index], static_cast(com_port), Output_Rate::FREQ_10_HZ); - gsofmsg_time = now + 110; - gsofmsgreq_index++; - } + + gsof_configured &= requestGSOF(gsofmsgreq[gsofmsgreq_index], static_cast(com_port), Output_Rate::FREQ_10_HZ); + gsofmsgreq_index++; + } + if (!gsof_configured) { + Debug("Failed to requestGSOF()"); + return false; } bool ret = false; @@ -160,46 +171,152 @@ AP_GPS_GSOF::parse(const uint8_t temp) return false; } -void -AP_GPS_GSOF::requestBaud(const HW_Port portindex) +bool +AP_GPS_GSOF::requestBaud(const HW_Port portIndex, const HW_Baud baudRate) { + Debug("Requesting baud on port %u", (uint8_t)portIndex); + // GSOF is supported on the following bauds: + // 2400, 4800, 9600, 19200, 38400, 115200, 230400 + + // This packet is not documented in the API. uint8_t buffer[19] = {0x02,0x00,0x64,0x0d,0x00,0x00,0x00, // application file record 0x03, 0x00, 0x01, 0x00, // file control information block - 0x02, 0x04, static_cast(portindex), 0x07, 0x00,0x00, // serial port baud format + 0x02, 0x04, static_cast(portIndex), static_cast(baudRate), 0x00,0x00, // serial port baud format 0x00,0x03 - }; // checksum - - buffer[4] = packetcount++; + }; - uint8_t checksum = 0; - for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) { - checksum += buffer[a]; - } + populateOutgoingTransNumber(buffer); + populateChecksum(buffer, sizeof(buffer)); - buffer[17] = checksum; - - port->write((const uint8_t*)buffer, sizeof(buffer)); + return requestResponse(buffer, sizeof(buffer)); } -void +bool AP_GPS_GSOF::requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz) { + Debug("Requesting gsof #%u on port %u", messageType, (uint8_t)portIndex); + + // This packet is not documented in the API. uint8_t buffer[21] = {0x02,0x00,0x64,0x0f,0x00,0x00,0x00, // application file record 0x03,0x00,0x01,0x00, // file control information block 0x07,0x06,0x0a,static_cast(portIndex),static_cast(rateHz),0x00,messageType,0x00, // output message record 0x00,0x03 - }; // checksum + }; + + populateOutgoingTransNumber(buffer); + populateChecksum(buffer, sizeof(buffer)); + + return requestResponse(buffer, sizeof(buffer)); +} + +bool +AP_GPS_GSOF::disableOutput(const HW_Port portIndex) { + Debug("Disabling output on on port %u", (uint8_t)portIndex); + switch(portIndex) { + case HW_Port::COM1: + { + constexpr uint8_t cmd[8] = { + STX, + 0x00, + 0x51, + 0x02, + 0x0A, + 0x01, + 0x5E, + ETX + }; + // The checksum is hard-coded. + // No need to calculate it. + return requestResponse(cmd, sizeof(cmd)); + } + + case HW_Port::COM2: + { + constexpr uint8_t cmd[8] = { + STX, + 0x00, + 0x51, + 0x02, + 0x0A, + 0x02, + 0x5F, + ETX + }; + return requestResponse(cmd, sizeof(cmd)); + } + } + return false; +} + +bool +AP_GPS_GSOF::requestResponse(const uint8_t* buf, const uint8_t len) { + if (!port->is_initialized()) { + Debug("Port not initialized"); + return false; + } + + for (int attempt = 0; attempt <= configuration_attempts; attempt++) { + // Clear input buffer before doing configuration + if (!port->discard_input()) { + Debug("Failed to discard input"); + return false; + }; + + port->write((const uint8_t*)buf, len); + + constexpr uint16_t expected_bytes = 1; + // TODO use wait_timeout instead once HAL_SITL has it implemented. + const auto start_wait = AP_HAL::millis(); + auto now = start_wait; + while (now - start_wait <= configuration_wait_time_ms) { + if (port->available() >= expected_bytes) { + break; + } + constexpr uint16_t delay_us = 100; + hal.scheduler->delay_microseconds(delay_us); + now = AP_HAL::millis(); + } + + const auto available_bytes = port->available(); + if (available_bytes != expected_bytes) { + Debug("Didn't get expected bytes, got %u bytes back", available_bytes); + return false; + } + + uint8_t resp_code; + if(port->read(resp_code) && resp_code == ACK) { + Debug("Got ack"); + return true; + } else { + Debug("Didn't get ACK, got 0x%02x", resp_code); + } + } + return false; +} - buffer[4] = packetcount++; +void +AP_GPS_GSOF::populateChecksum(uint8_t* buf, const uint8_t len) +{ + // The buffer is of size len. + // If ETX is not element buf[len-1], the buf/len numbers are wrong. + // Same problem if the len is too small for a valid packet. + if (len <= 3 || buf[len - 1] != ETX) { + return; + } + // The checksum field is at buf[len - 2] uint8_t checksum = 0; - for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) { - checksum += buffer[a]; + const uint8_t payload_size = len - 2; + for (uint8_t i = 1; i < payload_size; i++) { + checksum += buf[i]; } - buffer[19] = checksum; + buf[len -2] = checksum; +} - port->write((const uint8_t*)buffer, sizeof(buffer)); +void +AP_GPS_GSOF::populateOutgoingTransNumber(uint8_t* buf) { + buf[4] = packetOutboundTransNumber++; } double @@ -258,6 +375,7 @@ AP_GPS_GSOF::process_message(void) if (msg.packettype == 0x40) { // GSOF // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 #if gsof_DEBUGGING + //trans_number is functionally the sequence number. const uint8_t trans_number = msg.data[0]; const uint8_t pageidx = msg.data[1]; const uint8_t maxpageidx = msg.data[2]; @@ -359,6 +477,16 @@ AP_GPS_GSOF::process_message(void) return false; } +bool +AP_GPS_GSOF::validate_baud(const uint8_t baud) const { + switch(baud) { + case static_cast(HW_Baud::BAUD230K): + case static_cast(HW_Baud::BAUD115K): + return true; + default: + return false; + } +} bool AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const { switch(com_port) { diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index a55d91c0a9198b..e44b2137a55c86 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -16,6 +16,7 @@ // // Trimble GPS driver for ArduPilot. // Code by Michael Oborne +// Maintained by Ryan Friedman // https://receiverhelp.trimble.com/oem-gnss/index.html#Welcome.html?TocPath=_____1 #pragma once @@ -56,17 +57,35 @@ class AP_GPS_GSOF : public AP_GPS_Backend FREQ_100_HZ = 16, }; + // A subset of the supported baud rates in the GSOF protocol that are useful. + // These values are not documented in the API. + // The matches the GPS_GSOF_BAUD parameter. + enum class HW_Baud { + BAUD115K = 0x07, + BAUD230K = 0x0B, + }; + bool parse(const uint8_t temp) WARN_IF_UNUSED; bool process_message() WARN_IF_UNUSED; - - // Send a request to the GPS to set the baud rate on the specified port. - // Note - these request functions currently ignore the ACK from the device. - // If the device is already sending serial traffic, there is no mechanism to prevent conflict. - // According to the manufacturer, the best approach is to switch to ethernet. - void requestBaud(const HW_Port portIndex); - // Send a request to the GPS to enable a message type on the port at the specified rate. - void requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz); - + // Send a request to the GPS to configure its baud rate on a certain (serial) port. + // Note - these request functions expect an ACK from the device. + // If the device is already sending serial traffic, there is no mechanism to prevent this. + // According to the manufacturer, the best approach is to switch to ethernet. + // Use one port for configuration data and another for stream data to prevent conflict. + // Because there is only one TTL serial interface exposed, the approach here is using retry logic. + bool requestBaud(const HW_Port portIndex, const HW_Baud baudRate) WARN_IF_UNUSED; + // Send a request to the GPS to enable a message type on the port. + bool requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz) WARN_IF_UNUSED; + + bool disableOutput(const HW_Port portIndex) WARN_IF_UNUSED; + + // Generic handler for sending command and checking return code. + // Make sure to disableOutput() before doing configuration. + bool requestResponse(const uint8_t* buf, const uint8_t len) WARN_IF_UNUSED; + + static void populateChecksum(uint8_t* buf, const uint8_t len); + void populateOutgoingTransNumber(uint8_t* buf); + double SwapDouble(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; float SwapFloat(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; uint32_t SwapUint32(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; @@ -102,12 +121,27 @@ class AP_GPS_GSOF : public AP_GPS_Backend uint8_t checksumcalc; } msg; + static const uint8_t STX = 0x02; static const uint8_t ETX = 0x03; - - uint8_t packetcount; + static const uint8_t ACK = 0x06; + static const uint8_t NACK = 0x15; + + // How long to wait from sending configuration data for a response. + // This assumes delay is the same regardless of baud rate. + static const uint8_t configuration_wait_time_ms {5}; + // How many attempts to attempt configuration. + // Raising this makes the initialization more immune to data conflicts with streamed data. + // Raising it too high will trigger the watchdog. + // Lowering this makes the driver quicker to return from initialization calls. + static const uint8_t configuration_attempts {3}; + + // The counter for number of outgoing packets + uint8_t packetOutboundTransNumber; uint32_t gsofmsg_time; uint8_t gsofmsgreq_index; const uint8_t gsofmsgreq[5] = {1,2,8,9,12}; + bool is_baud_configured {false}; + bool is_configured {false}; }; #endif From 5f84cd8f2b2c370078f025731eb4dda99e2136e8 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Mon, 13 Nov 2023 18:11:47 -0700 Subject: [PATCH 456/499] AP_GPS: Move init logic from constructor to class Signed-off-by: Ryan Friedman --- libraries/AP_GPS/AP_GPS_GSOF.cpp | 56 +++++++++++++++++++------------- libraries/AP_GPS/AP_GPS_GSOF.h | 4 +-- 2 files changed, 36 insertions(+), 24 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 389b45dea68ef6..67777bf23cddf4 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -58,21 +58,7 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, { // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_Overview.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257COverview%257C_____0 static_assert(ARRAY_SIZE(gsofmsgreq) <= 10, "The maximum number of outputs allowed with GSOF is 10."); - - msg.state = Msg_Parser::State::STARTTX; - - constexpr uint8_t default_com_port = static_cast(HW_Port::COM2); - gps._com_port[state.instance].set_default(default_com_port); - const auto com_port = gps._com_port[state.instance].get(); - if (!validate_com_port(com_port)) { - // The user parameter for COM port is not a valid GSOF port - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d has invalid COM port setting of %d", state.instance, com_port); - return; - } - const HW_Baud baud = HW_Baud::BAUD115K; - // Start by disabling output during config - [[maybe_unused]] const auto output_disabled = disableOutput(static_cast(com_port)); - is_baud_configured = requestBaud(static_cast(com_port), baud); + static_assert(sizeof(gsofmsgreq) != 0, "gsofmsgreq is not empty"); } // Process all bytes available from the stream @@ -80,22 +66,48 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, bool AP_GPS_GSOF::read(void) { + if (!is_baud_configured) { // Debug("Baud not configured, not ready to read()"); - return false; - } - bool gsof_configured = true; - - static_assert(sizeof(gsofmsgreq) != 0, "gsofmsgreq is not empty"); - while (gsofmsgreq_index < (sizeof(gsofmsgreq))) { + constexpr uint8_t default_com_port = static_cast(HW_Port::COM2); + gps._com_port[state.instance].set_default(default_com_port); const auto com_port = gps._com_port[state.instance].get(); if (!validate_com_port(com_port)) { // The user parameter for COM port is not a valid GSOF port + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d has invalid COM port setting of %d", state.instance, com_port); + return false; + } + const HW_Baud baud = HW_Baud::BAUD115K; + // Start by disabling output during config + if (!disableOutput(static_cast(com_port))) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d cannot disable output on port %d", state.instance, com_port); return false; } - gsof_configured &= requestGSOF(gsofmsgreq[gsofmsgreq_index], static_cast(com_port), Output_Rate::FREQ_10_HZ); + is_baud_configured = requestBaud(static_cast(com_port), baud); + if (!is_baud_configured) { + // Don't try further configuration if the baud request fails. + return false; + } + } + + while (gsofmsgreq_index < sizeof(gsofmsgreq)) { + const auto com_port = gps._com_port[state.instance].get(); + if (!validate_com_port(com_port)) { + // The user parameter for COM port is not a valid GSOF port. + return false; + } + + const auto success = requestGSOF(gsofmsgreq[gsofmsgreq_index], static_cast(com_port), Output_Rate::FREQ_10_HZ); + if (!success) { + // Try again to do the rest of the configuration next time. + return false; + } else { + if (gsofmsgreq_index == sizeof(gsofmsgreq) - 1) { + gsof_configured = true; + } + } gsofmsgreq_index++; } if (!gsof_configured) { diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index e44b2137a55c86..82fcfa6f2a0573 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -108,7 +108,7 @@ class AP_GPS_GSOF : public AP_GPS_Backend ENDTX }; - State state; + State state = State::STARTTX; uint8_t status; uint8_t packettype; @@ -142,6 +142,6 @@ class AP_GPS_GSOF : public AP_GPS_Backend uint8_t gsofmsgreq_index; const uint8_t gsofmsgreq[5] = {1,2,8,9,12}; bool is_baud_configured {false}; - bool is_configured {false}; + bool gsof_configured {false}; }; #endif From d7b5cd32034799cb42d21ec02b7a5157bd63987f Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 14 Nov 2023 17:22:50 -0700 Subject: [PATCH 457/499] AP_GPS: Fix missing GSOF param for SITL Signed-off-by: Ryan Friedman --- libraries/AP_GPS/AP_GPS_GSOF.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 67777bf23cddf4..11dcca752359fd 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -22,7 +22,8 @@ // param set GPS_TYPE 11 // GSOF // param set SERIAL3_PROTOCOL 5 // GPS // - +// Pure SITL usage +// param set SIM_GPS_TYPE 11 // GSOF #define ALLOW_DOUBLE_MATH_FUNCTIONS #include "AP_GPS.h" From 35b52a460495e679e1859559828aa7438f4dbfd0 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 14 Nov 2023 01:11:39 -0700 Subject: [PATCH 458/499] SITL: Implement DCOL parser and bidirectional comms * Implement DCOL command support for GSOF simulator * Only send GSOF when enabled * Publish only at the configured rate * Only build GSOF packets when needed * This saves CPU * Make physics and read loop run at full rate * The logic to rate-limit writes is now pushed to the backend * Indent errors were fixed too Signed-off-by: Ryan Friedman --- libraries/SITL/SIM_GPS.cpp | 656 +++++++++++++++++++++--------- libraries/SITL/SIM_GPS.h | 124 +++++- libraries/SITL/SIM_SerialDevice.h | 2 +- 3 files changed, 584 insertions(+), 198 deletions(-) diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index ac45d68828cdd8..61eeaaecc70616 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -986,198 +986,447 @@ uint32_t GPS_NOVA::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_ } void GPS_GSOF::publish(const GPS_Data *d) -{ - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 - constexpr uint8_t GSOF_POS_TIME_TYPE { 0x01 }; - constexpr uint8_t GSOF_POS_TIME_LEN { 0x0A }; - // TODO magic number until SITL supports GPS bootcount based on GPSN_ENABLE - const uint8_t bootcount = 17; - - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%201 - enum class POS_FLAGS_1 : uint8_t { - NEW_POSITION = 1U << 0, - CLOCK_FIX_CALULATED = 1U << 1, - HORIZ_FROM_THIS_POS = 1U << 2, - HEIGHT_FROM_THIS_POS = 1U << 3, - RESERVED_4 = 1U << 4, - LEAST_SQ_POSITION = 1U << 5, - RESERVED_6 = 1U << 6, - POSITION_L1_PSEUDORANGES = 1U << 7 - }; - const uint8_t pos_flags_1 { - uint8_t(POS_FLAGS_1::NEW_POSITION) | - uint8_t(POS_FLAGS_1::CLOCK_FIX_CALULATED) | - uint8_t(POS_FLAGS_1::HORIZ_FROM_THIS_POS) | - uint8_t(POS_FLAGS_1::HEIGHT_FROM_THIS_POS) | - uint8_t(POS_FLAGS_1::RESERVED_4) | - uint8_t(POS_FLAGS_1::LEAST_SQ_POSITION) | - uint8_t(POS_FLAGS_1::POSITION_L1_PSEUDORANGES) - }; +{ + // This logic is to populate output buffer only with enabled channels. + // It also only sends each channel at the configured rate. + const uint64_t now = AP_HAL::millis(); + uint8_t buf[MAX_PAYLOAD_SIZE] = {}; + uint8_t payload_sz = 0; + uint8_t offset = 0; + if (channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_TIME)] != Output_Rate::OFF){ + const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::POSITION_TIME)]; + const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_TIME)]; + + if (now - last_time > RateToPeriodMs(desired_rate)) { + + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 + constexpr uint8_t GSOF_POS_TIME_LEN { 0x0A }; + // TODO magic number until SITL supports GPS bootcount based on GPSN_ENABLE + const uint8_t bootcount = 17; + + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%201 + enum class POS_FLAGS_1 : uint8_t { + NEW_POSITION = 1U << 0, + CLOCK_FIX_CALULATED = 1U << 1, + HORIZ_FROM_THIS_POS = 1U << 2, + HEIGHT_FROM_THIS_POS = 1U << 3, + RESERVED_4 = 1U << 4, + LEAST_SQ_POSITION = 1U << 5, + RESERVED_6 = 1U << 6, + POSITION_L1_PSEUDORANGES = 1U << 7 + }; + const uint8_t pos_flags_1 { + uint8_t(POS_FLAGS_1::NEW_POSITION) | + uint8_t(POS_FLAGS_1::CLOCK_FIX_CALULATED) | + uint8_t(POS_FLAGS_1::HORIZ_FROM_THIS_POS) | + uint8_t(POS_FLAGS_1::HEIGHT_FROM_THIS_POS) | + uint8_t(POS_FLAGS_1::RESERVED_4) | + uint8_t(POS_FLAGS_1::LEAST_SQ_POSITION) | + uint8_t(POS_FLAGS_1::POSITION_L1_PSEUDORANGES) + }; + + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%202 + enum class POS_FLAGS_2 : uint8_t { + DIFFERENTIAL_POS = 1U << 0, + DIFFERENTIAL_POS_PHASE_RTK = 1U << 1, + POSITION_METHOD_FIXED_PHASE = 1U << 2, + OMNISTAR_ACTIVE = 1U << 3, + DETERMINED_WITH_STATIC_CONSTRAINT = 1U << 4, + NETWORK_RTK = 1U << 5, + DITHERED_RTK = 1U << 6, + BEACON_DGNSS = 1U << 7, + }; + + // Simulate a GPS without RTK in SIM since there is no RTK SIM params. + // This means these flags are unset: + // NETWORK_RTK, DITHERED_RTK, BEACON_DGNSS + uint8_t pos_flags_2 {0}; + if(d->have_lock) { + pos_flags_2 |= uint8_t(POS_FLAGS_2::DIFFERENTIAL_POS); + pos_flags_2 |= uint8_t(POS_FLAGS_2::DIFFERENTIAL_POS_PHASE_RTK); + pos_flags_2 |= uint8_t(POS_FLAGS_2::POSITION_METHOD_FIXED_PHASE); + pos_flags_2 |= uint8_t(POS_FLAGS_2::OMNISTAR_ACTIVE); + pos_flags_2 |= uint8_t(POS_FLAGS_2::DETERMINED_WITH_STATIC_CONSTRAINT); + } - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%202 - enum class POS_FLAGS_2 : uint8_t { - DIFFERENTIAL_POS = 1U << 0, - DIFFERENTIAL_POS_PHASE_RTK = 1U << 1, - POSITION_METHOD_FIXED_PHASE = 1U << 2, - OMNISTAR_ACTIVE = 1U << 3, - DETERMINED_WITH_STATIC_CONSTRAINT = 1U << 4, - NETWORK_RTK = 1U << 5, - DITHERED_RTK = 1U << 6, - BEACON_DGNSS = 1U << 7, - }; + const auto gps_tow = gps_time(); + const struct PACKED gsof_pos_time { + const uint8_t OUTPUT_RECORD_TYPE; + const uint8_t RECORD_LEN; + uint32_t time_week_ms; + uint16_t time_week; + uint8_t num_sats; + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%201 + uint8_t pos_flags_1; + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%202 + uint8_t pos_flags_2; + uint8_t initialized_num; + } pos_time { + uint8_t(Gsof_Msg_Record_Type::POSITION_TIME), + GSOF_POS_TIME_LEN, + htobe32(gps_tow.ms), + htobe16(gps_tow.week), + d->have_lock ? _sitl->gps_numsats[instance] : uint8_t(3), + pos_flags_1, + pos_flags_2, + bootcount + }; + static_assert(sizeof(gsof_pos_time) - (sizeof(gsof_pos_time::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_time::RECORD_LEN)) == GSOF_POS_TIME_LEN); + + payload_sz += sizeof(pos_time); + memcpy(&buf[offset], &pos_time, sizeof(pos_time)); + offset += sizeof(pos_time); + } + } - // Simulate a GPS without RTK in SIM since there is no RTK SIM params. - // This means these flags are unset: - // NETWORK_RTK, DITHERED_RTK, BEACON_DGNSS - uint8_t pos_flags_2 {0}; - if(d->have_lock) { - pos_flags_2 |= uint8_t(POS_FLAGS_2::DIFFERENTIAL_POS); - pos_flags_2 |= uint8_t(POS_FLAGS_2::DIFFERENTIAL_POS_PHASE_RTK); - pos_flags_2 |= uint8_t(POS_FLAGS_2::POSITION_METHOD_FIXED_PHASE); - pos_flags_2 |= uint8_t(POS_FLAGS_2::OMNISTAR_ACTIVE); - pos_flags_2 |= uint8_t(POS_FLAGS_2::DETERMINED_WITH_STATIC_CONSTRAINT); + if (channel_rates[uint8_t(Gsof_Msg_Record_Type::LLH)] != Output_Rate::OFF){ + const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::LLH)]; + const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::LLH)]; + + if (now - last_time > RateToPeriodMs(desired_rate)) { + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_LLH.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____20 + constexpr uint8_t GSOF_POS_LEN = 0x18; + + const struct PACKED gsof_pos { + const uint8_t OUTPUT_RECORD_TYPE; + const uint8_t RECORD_LEN; + uint64_t lat; + uint64_t lng; + uint64_t alt; + } pos { + uint8_t(Gsof_Msg_Record_Type::LLH), + GSOF_POS_LEN, + gsof_pack_double(d->latitude * DEG_TO_RAD_DOUBLE), + gsof_pack_double(d->longitude * DEG_TO_RAD_DOUBLE), + gsof_pack_double(static_cast(d->altitude)) + }; + static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN); + + payload_sz += sizeof(pos); + memcpy(&buf[offset], &pos, sizeof(pos)); + offset += sizeof(pos); + } } - const auto gps_tow = gps_time(); - const struct PACKED gsof_pos_time { - const uint8_t OUTPUT_RECORD_TYPE; - const uint8_t RECORD_LEN; - uint32_t time_week_ms; - uint16_t time_week; - uint8_t num_sats; - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%201 - uint8_t pos_flags_1; - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%202 - uint8_t pos_flags_2; - uint8_t initialized_num; - } pos_time { - GSOF_POS_TIME_TYPE, - GSOF_POS_TIME_LEN, - htobe32(gps_tow.ms), - htobe16(gps_tow.week), - d->have_lock ? _sitl->gps_numsats[instance] : uint8_t(3), - pos_flags_1, - pos_flags_2, - bootcount - }; - static_assert(sizeof(gsof_pos_time) - (sizeof(gsof_pos_time::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_time::RECORD_LEN)) == GSOF_POS_TIME_LEN); - - constexpr uint8_t GSOF_POS_TYPE = 0x02; - constexpr uint8_t GSOF_POS_LEN = 0x18; - - const struct PACKED gsof_pos { - const uint8_t OUTPUT_RECORD_TYPE; - const uint8_t RECORD_LEN; - uint64_t lat; - uint64_t lng; - uint64_t alt; - } pos { - GSOF_POS_TYPE, - GSOF_POS_LEN, - gsof_pack_double(d->latitude * DEG_TO_RAD_DOUBLE), - gsof_pack_double(d->longitude * DEG_TO_RAD_DOUBLE), - gsof_pack_double(static_cast(d->altitude)) - }; - static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN); - - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Velocity.html - constexpr uint8_t GSOF_VEL_TYPE = 0x08; - // use the smaller packet by ignoring local coordinate system - constexpr uint8_t GSOF_VEL_LEN = 0x0D; - - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags - enum class VEL_FIELDS : uint8_t { - VALID = 1U << 0, - CONSECUTIVE_MEASUREMENTS = 1U << 1, - HEADING_VALID = 1U << 2, - RESERVED_3 = 1U << 3, - RESERVED_4 = 1U << 4, - RESERVED_5 = 1U << 5, - RESERVED_6 = 1U << 6, - RESERVED_7 = 1U << 7, - }; - uint8_t vel_flags {0}; - if(d->have_lock) { - vel_flags |= uint8_t(VEL_FIELDS::VALID); - vel_flags |= uint8_t(VEL_FIELDS::CONSECUTIVE_MEASUREMENTS); - vel_flags |= uint8_t(VEL_FIELDS::HEADING_VALID); + if (channel_rates[uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA)] != Output_Rate::OFF){ + const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA)]; + const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA)]; + + if (now - last_time > RateToPeriodMs(desired_rate)) { + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Velocity.html + // use the smaller packet by ignoring local coordinate system + constexpr uint8_t GSOF_VEL_LEN = 0x0D; + + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags + enum class VEL_FIELDS : uint8_t { + VALID = 1U << 0, + CONSECUTIVE_MEASUREMENTS = 1U << 1, + HEADING_VALID = 1U << 2, + RESERVED_3 = 1U << 3, + RESERVED_4 = 1U << 4, + RESERVED_5 = 1U << 5, + RESERVED_6 = 1U << 6, + RESERVED_7 = 1U << 7, + }; + uint8_t vel_flags {0}; + if(d->have_lock) { + vel_flags |= uint8_t(VEL_FIELDS::VALID); + vel_flags |= uint8_t(VEL_FIELDS::CONSECUTIVE_MEASUREMENTS); + vel_flags |= uint8_t(VEL_FIELDS::HEADING_VALID); + } + + const struct PACKED gsof_vel { + const uint8_t OUTPUT_RECORD_TYPE; + const uint8_t RECORD_LEN; + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags + uint8_t flags; + uint32_t horiz_m_p_s; + uint32_t heading_rad; + uint32_t vertical_m_p_s; + } vel { + uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA), + GSOF_VEL_LEN, + vel_flags, + gsof_pack_float(d->speed_2d()), + gsof_pack_float(d->heading()), + // Trimble API has ambiguous direction here. + // Intentionally narrow from double. + gsof_pack_float(static_cast(d->speedD)) + }; + static_assert(sizeof(gsof_vel) - (sizeof(gsof_vel::OUTPUT_RECORD_TYPE) + sizeof(gsof_vel::RECORD_LEN)) == GSOF_VEL_LEN); + + payload_sz += sizeof(vel); + memcpy(&buf[offset], &vel, sizeof(vel)); + offset += sizeof(vel); + } + } + if (channel_rates[uint8_t(Gsof_Msg_Record_Type::PDOP_INFO)] != Output_Rate::OFF){ + const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::PDOP_INFO)]; + const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::PDOP_INFO)]; + + if (now - last_time > RateToPeriodMs(desired_rate)) { + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_PDOP.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____12 + constexpr uint8_t GSOF_DOP_LEN = 0x10; + const struct PACKED gsof_dop { + const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::PDOP_INFO) }; + const uint8_t RECORD_LEN { GSOF_DOP_LEN }; + uint32_t pdop = htobe32(1); + uint32_t hdop = htobe32(1); + uint32_t vdop = htobe32(1); + uint32_t tdop = htobe32(1); + } dop {}; + // Check the payload size calculation in the compiler + constexpr auto dop_size = sizeof(gsof_dop); + static_assert(dop_size == 18); + constexpr auto dop_record_type_size = sizeof(gsof_dop::OUTPUT_RECORD_TYPE); + static_assert(dop_record_type_size == 1); + constexpr auto len_size = sizeof(gsof_dop::RECORD_LEN); + static_assert(len_size == 1); + constexpr auto dop_payload_size = dop_size - (dop_record_type_size + len_size); + static_assert(dop_payload_size == GSOF_DOP_LEN); + + payload_sz += sizeof(dop); + memcpy(&buf[offset], &dop, sizeof(dop)); + offset += sizeof(dop); + } + } + if (channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO)] != Output_Rate::OFF){ + const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO)]; + const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO)]; + if (now - last_time > RateToPeriodMs(desired_rate)) { + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_SIGMA.html + constexpr uint8_t GSOF_POS_SIGMA_LEN = 0x26; + const struct PACKED gsof_pos_sigma { + const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO) }; + const uint8_t RECORD_LEN { GSOF_POS_SIGMA_LEN }; + uint32_t pos_rms = htobe32(0); + uint32_t sigma_e = htobe32(0); + uint32_t sigma_n = htobe32(0); + uint32_t cov_en = htobe32(0); + uint32_t sigma_up = htobe32(0); + uint32_t semi_major_axis = htobe32(0); + uint32_t semi_minor_axis = htobe32(0); + uint32_t orientation = htobe32(0); + uint32_t unit_variance = htobe32(0); + uint16_t n_epocs = htobe32(1); // Always 1 for kinematic. + } pos_sigma {}; + static_assert(sizeof(gsof_pos_sigma) - (sizeof(gsof_pos_sigma::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_sigma::RECORD_LEN)) == GSOF_POS_SIGMA_LEN); + payload_sz += sizeof(pos_sigma); + memcpy(&buf[offset], &pos_sigma, sizeof(pos_sigma)); + offset += sizeof(pos_sigma); + } } - const struct PACKED gsof_vel { - const uint8_t OUTPUT_RECORD_TYPE; - const uint8_t RECORD_LEN; - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags - uint8_t flags; - uint32_t horiz_m_p_s; - uint32_t heading_rad; - uint32_t vertical_m_p_s; - } vel { - GSOF_VEL_TYPE, - GSOF_VEL_LEN, - vel_flags, - gsof_pack_float(d->speed_2d()), - gsof_pack_float(d->heading()), - // Trimble API has ambiguous direction here. - // Intentionally narrow from double. - gsof_pack_float(static_cast(d->speedD)) - }; - static_assert(sizeof(gsof_vel) - (sizeof(gsof_vel::OUTPUT_RECORD_TYPE) + sizeof(gsof_vel::RECORD_LEN)) == GSOF_VEL_LEN); - - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_PDOP.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____12 - constexpr uint8_t GSOF_DOP_TYPE = 0x09; - constexpr uint8_t GSOF_DOP_LEN = 0x10; - const struct PACKED gsof_dop { - const uint8_t OUTPUT_RECORD_TYPE { GSOF_DOP_TYPE }; - const uint8_t RECORD_LEN { GSOF_DOP_LEN }; - uint32_t pdop = htobe32(1); - uint32_t hdop = htobe32(1); - uint32_t vdop = htobe32(1); - uint32_t tdop = htobe32(1); - } dop {}; - // Check the payload size calculation in the compiler - constexpr auto dop_size = sizeof(gsof_dop); - static_assert(dop_size == 18); - constexpr auto dop_record_type_size = sizeof(gsof_dop::OUTPUT_RECORD_TYPE); - static_assert(dop_record_type_size == 1); - constexpr auto len_size = sizeof(gsof_dop::RECORD_LEN); - static_assert(len_size == 1); - constexpr auto dop_payload_size = dop_size - (dop_record_type_size + len_size); - static_assert(dop_payload_size == GSOF_DOP_LEN); - - constexpr uint8_t GSOF_POS_SIGMA_TYPE = 0x0C; - constexpr uint8_t GSOF_POS_SIGMA_LEN = 0x26; - const struct PACKED gsof_pos_sigma { - const uint8_t OUTPUT_RECORD_TYPE { GSOF_POS_SIGMA_TYPE }; - const uint8_t RECORD_LEN { GSOF_POS_SIGMA_LEN }; - uint32_t pos_rms = htobe32(0); - uint32_t sigma_e = htobe32(0); - uint32_t sigma_n = htobe32(0); - uint32_t cov_en = htobe32(0); - uint32_t sigma_up = htobe32(0); - uint32_t semi_major_axis = htobe32(0); - uint32_t semi_minor_axis = htobe32(0); - uint32_t orientation = htobe32(0); - uint32_t unit_variance = htobe32(0); - uint16_t n_epocs = htobe32(1); // Always 1 for kinematic. - } pos_sigma {}; - static_assert(sizeof(gsof_pos_sigma) - (sizeof(gsof_pos_sigma::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_sigma::RECORD_LEN)) == GSOF_POS_SIGMA_LEN); - - // TODO add GSOF49 - const uint8_t payload_sz = sizeof(pos_time) + sizeof(pos) + sizeof(vel) + sizeof(dop) + sizeof(pos_sigma); - uint8_t buf[payload_sz] = {}; - uint8_t offset = 0; - memcpy(&buf[offset], &pos_time, sizeof(pos_time)); - offset += sizeof(pos_time); - memcpy(&buf[offset], &pos, sizeof(pos)); - offset += sizeof(pos); - memcpy(&buf[offset], &vel, sizeof(vel)); - offset += sizeof(vel); - memcpy(&buf[offset], &dop, sizeof(dop)); - offset += sizeof(dop); - memcpy(&buf[offset], &pos_sigma, sizeof(pos_sigma)); - offset += sizeof(pos_sigma); assert(offset == payload_sz); - send_gsof(buf, sizeof(buf)); + + // Don't send empy frames when all channels are disabled; + if (payload_sz > 0) { + send_gsof(buf, payload_sz); + } + +} + +bool DCOL_Parser::dcol_parse(const char data_in) { + bool ret = false; + switch (parse_state) { + case Parse_State::WAITING_ON_STX: + if (data_in == STX) { + reset(); + parse_state = Parse_State::WAITING_ON_STATUS; + } + break; + case Parse_State::WAITING_ON_STATUS: + if (data_in != (uint8_t)Status::OK) { + // Invalid, status should always be OK. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } else { + status = static_cast(data_in); + parse_state = Parse_State::WAITING_ON_PACKET_TYPE; + } + break; + case Parse_State::WAITING_ON_PACKET_TYPE: + if (data_in == (uint8_t)Packet_Type::COMMAND_APPFILE) { + packet_type = Packet_Type::COMMAND_APPFILE; + } else { + // Unsupported command in this simulator. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + parse_state = Parse_State::WAITING_ON_LENGTH; + break; + case Parse_State::WAITING_ON_LENGTH: + expected_payload_length = data_in; + parse_state = Parse_State::WAITING_ON_PACKET_DATA; + break; + case Parse_State::WAITING_ON_PACKET_DATA: + payload[cur_payload_idx] = data_in; + if (++cur_payload_idx == expected_payload_length) { + parse_state = Parse_State::WAITING_ON_CSUM; + } + break; + case Parse_State::WAITING_ON_CSUM: + expected_csum = data_in; + parse_state = Parse_State::WAITING_ON_ETX; + break; + case Parse_State::WAITING_ON_ETX: + if (data_in != ETX) { + reset(); + } + if (!valid_csum()) { + // GSOF driver sent a packet with invalid CSUM. + // In real GSOF driver, the packet is simply ignored with no reply. + // In the SIM, treat this as a coding error. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } else { + ret = parse_payload(); + } + reset(); + break; + } + + return ret; +} + +uint32_t DCOL_Parser::RateToPeriodMs(const Output_Rate rate) { + uint32_t min_period_ms = 0; + switch (rate) { + case Output_Rate::OFF: + min_period_ms = 0; + break; + case Output_Rate::FREQ_10_HZ: + min_period_ms = 100; + break; + case Output_Rate::FREQ_50_HZ: + min_period_ms = 20; + break; + case Output_Rate::FREQ_100_HZ: + min_period_ms = 10; + break; + } + return min_period_ms; +} + + +bool DCOL_Parser::valid_csum() { + uint8_t sum = (uint8_t)status; + sum += (uint8_t)packet_type; + sum += expected_payload_length; + sum += crc_sum_of_bytes(payload, expected_payload_length); + return sum == expected_csum; +} + +bool DCOL_Parser::parse_payload() { + bool success = false; + if (packet_type == Packet_Type::COMMAND_APPFILE) { + success = parse_cmd_appfile(); + } + + return success; +} + +bool DCOL_Parser::parse_cmd_appfile() { + // A file control info block contains: + // * version + // * device type + // * start application file flag + // * factory settings flag + constexpr uint8_t file_control_info_block_sz = 4; + // An appfile header contains: + // * transmisison number + // * page index + // * max page index + constexpr uint8_t appfile_header_sz = 3; + constexpr uint8_t min_cmd_appfile_sz = file_control_info_block_sz + appfile_header_sz; + if (expected_payload_length < min_cmd_appfile_sz) { + return false; + } + + // For now, ignore appfile_trans_num, return success regardless. + // If the driver doesn't send the right value, it's not clear what the behavior is supposed to be. + // Also would need to handle re-sync. + // For now, just store it for debugging. + appfile_trans_num = payload[0]; + + // File control information block parsing: + // https://receiverhelp.trimble.com/oem-gnss/ICD_Subtype_Command64h_FileControlInfo.html + constexpr uint8_t expected_app_file_spec_version = 0x03; + constexpr uint8_t file_ctrl_idx = appfile_header_sz; + if (payload[file_ctrl_idx] != expected_app_file_spec_version) { + // Only version 3 is supported at this time. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + constexpr uint8_t expected_dev_type = 0x00; + if (payload[file_ctrl_idx+1] != expected_dev_type) { + // Only "all" device type is supported. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + constexpr uint8_t expected_start_flag = 0x01; + if (payload[file_ctrl_idx+2] != expected_start_flag) { + // Only "immediate" start type is supported. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + + constexpr uint8_t expected_factory_settings_flag = 0x00; + if (payload[file_ctrl_idx+3] != expected_factory_settings_flag) { + // Factory settings restore before appfile is not supported. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + constexpr uint8_t app_file_records_idx = appfile_header_sz + file_control_info_block_sz; + const uint8_t record_type = payload[app_file_records_idx]; + if (record_type == (uint8_t)Appfile_Record_Type::SERIAL_PORT_BAUD_RATE_FORMAT) { + // Serial port baud/format + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_SerialPort.html + + // Ignore serial port index (COM Port) since there's only one in SITL. + // Ignore baud rate because you can't change baud yet in SITL. + // Ignore parity because it can't be changed in SITL. + // Ignore flow control because it's not yet in SITL. + } else if (record_type == (uint8_t)Appfile_Record_Type::OUTPUT_MESSAGE){ + // Output Message + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html + + + // Ignore record length to save flash. + // Ignore port index since SITL is only one port. + if (payload[app_file_records_idx + 2] == (uint8_t)(Output_Msg_Msg_Type::GSOF)) { + const auto gsof_submessage_type = payload[app_file_records_idx + 6]; + const auto rate = payload[app_file_records_idx + 4]; + if (rate == (uint8_t)Output_Rate::OFF) { + channel_rates[gsof_submessage_type] = static_cast(rate); + } else if (rate == (uint8_t)Output_Rate::FREQ_10_HZ) { + channel_rates[gsof_submessage_type] = static_cast(rate); + } else if (rate == (uint8_t)Output_Rate::FREQ_50_HZ) { + channel_rates[gsof_submessage_type] = static_cast(rate); + } else if (rate == (uint8_t)Output_Rate::FREQ_100_HZ) { + channel_rates[gsof_submessage_type] = static_cast(rate); + } else { + // Unsupported GSOF rate in SITL. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + } else { + // Only some data output protocols are supported in SITL. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + } else { + // Other application file packets are not yet supported. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + return true; +} + +void DCOL_Parser::reset() { + cur_payload_idx = 0; + expected_payload_length = 0; + parse_state = Parse_State::WAITING_ON_STX; + // To be pedantic, one could zero the bytes in the payload, + // but this is skipped because it's extra CPU. + + // Note - appfile_trans_number is intended to persist over parser resets. } @@ -1189,7 +1438,6 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) // * A fixed-length packet trailer (dcol_trailer) // Reference: // https://receiverhelp.trimble.com/oem-gnss/index.html#API_DataCollectorFormatPacketStructure.html?TocPath=API%2520Documentation%257CData%2520collector%2520format%2520packets%257CData%2520collector%2520format%253A%2520packet%2520structure%257C_____0 - const uint8_t STX = 0x02; // status bitfield // https://receiverhelp.trimble.com/oem-gnss/index.html#API_ReceiverStatusByte.html?TocPath=API%2520Documentation%257CData%2520collector%2520format%2520packets%257CData%2520collector%2520format%253A%2520packet%2520structure%257C_____1 const uint8_t STATUS = 0xa8; @@ -1210,8 +1458,8 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) }; ++TRANSMISSION_NUMBER; - // A captured GSOF49 packet from BD940 has LENGTH field set to 0x6d = 109 bytes. - // A captured GSOF49 packet from BD940 has total bytes of 115 bytes. + // A captured GSOF49 packet from BD940 has LENGTH field set to 0x6d = 109 bytes. + // A captured GSOF49 packet from BD940 has total bytes of 115 bytes. // Thus, the following 5 bytes are not counted. // 1) STX // 2) STATUS @@ -1242,7 +1490,6 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) csum += buf[i]; } - constexpr uint8_t ETX = 0x03; const uint8_t dcol_trailer[2] = { csum, ETX @@ -1277,6 +1524,22 @@ uint32_t GPS_GSOF::gsof_pack_float(const float& src) return dst; } +void GPS_GSOF::update_read() { + // Technically, the max command is slightly larger. + // This will only slightly slow the response for packets that big. + char c[MAX_PAYLOAD_SIZE]; + const auto n_read = read_from_autopilot(c, MAX_PAYLOAD_SIZE); + if (n_read > 0) { + for (uint8_t i = 0; i < n_read; i++) { + if (dcol_parse(c[i])) { + constexpr uint8_t response[1] = {(uint8_t)Command_Response::ACK}; + write_to_autopilot((char*)response, sizeof(response)); + } + // TODO handle NACK for failure + } + } +} + /* send MSP GPS data */ @@ -1516,13 +1779,16 @@ void GPS::update() // simulate delayed lock times bool have_lock = (!_sitl->gps_disable[idx] && now_ms >= _sitl->gps_lock_time[idx]*1000UL); - // run at configured GPS rate (default 5Hz) - if ((now_ms - last_update) < (uint32_t)(1000/_sitl->gps_hertz[idx])) { + // Only let physics run and GPS write at configured GPS rate (default 5Hz). + if ((now_ms - last_write_update_ms) < (uint32_t)(1000/_sitl->gps_hertz[instance])) { + // Reading runs every iteration. + // Beware- physics don't update every iteration with this approach. + // Currently, none of the drivers rely on quickly updated physics. backend->update_read(); return; } - last_update = now_ms; + last_write_update_ms = now_ms; d.latitude = latitude; d.longitude = longitude; @@ -1593,9 +1859,9 @@ void GPS::update() void GPS_Backend::update_read() { - // swallow any config bytes - char c; - read_from_autopilot(&c, 1); + // swallow any config bytes + char c; + read_from_autopilot(&c, 1); } /* diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index 235234fd6ad7a0..c9f8c34e415480 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -98,13 +98,132 @@ class GPS_FILE : public GPS_Backend { void publish(const GPS_Data *d) override; }; -class GPS_GSOF : public GPS_Backend { +class DCOL_Parser { + // The DCOL parser is used by Trimble GSOF devices. + // It's used for doing configuration. + // https://receiverhelp.trimble.com/oem-gnss/API_DataCollectorFormatPackets.html +public: + // Feed data in to the DCOL parser. + // If the data reaches a parse state that needs to write ACK/NACK back out, + // the function returns true with a populated data_out value. + // Otherwise, it returns false waiting for more data. + bool dcol_parse(const char data_in); + + static constexpr uint8_t STX = 0x02; + static constexpr uint8_t ETX = 0x03; + + // Receiver status code + enum class Status : uint8_t { + OK = 0x00, + }; + + // https://receiverhelp.trimble.com/oem-gnss/API_DataCollectorFormatPackets.html + enum class Command_Response : uint8_t { + ACK = 0x06, + NACK = 0x15, + }; + + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Frequenc + enum class Output_Rate : uint8_t { + OFF = 0, + FREQ_10_HZ = 1, + FREQ_50_HZ = 15, + FREQ_100_HZ = 16, + }; + + // https://receiverhelp.trimble.com/oem-gnss/ICD_ApplicationFilePackets.html?tocpath=API%20Documentation%7CCommand%20and%20report%20packets%7CApplication%20file%20packets%7C_____0 + enum class Packet_Type : uint8_t { + COMMAND_APPFILE = 0x64, + }; + + // https://receiverhelp.trimble.com/oem-gnss/ICD_Pkt_Command64h_APPFILE.html + enum class Appfile_Record_Type : uint8_t { + SERIAL_PORT_BAUD_RATE_FORMAT = 0x02, + OUTPUT_MESSAGE = 0x07, + }; + + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Output + enum class Output_Msg_Msg_Type : uint8_t { + GSOF = 10, + }; + + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Output2 + enum class Gsof_Msg_Record_Type : uint8_t { + POSITION_TIME = 1, + LLH = 2, + VELOCITY_DATA = 8, + PDOP_INFO = 9, + POSITION_SIGMA_INFO = 12, + }; + +protected: + // https://receiverhelp.trimble.com/oem-gnss/API_DataCollectorFormatPacketStructure.html + static constexpr uint8_t MAX_PAYLOAD_SIZE = 255; + + // GSOF supports this many different packet types. + // Only a fraction are supported by the simulator. + // Waste some RAM and allocate arrays for the whole set. + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Output2 + static constexpr uint8_t MAX_CHANNEL_NUM = 70; + // Rates of dynamically enabled channels. + // Assume factory behavior of no enabled channels. + // Each channel can send data out at its own rate. + Output_Rate channel_rates[MAX_CHANNEL_NUM] = {Output_Rate::OFF}; + + // Last publish time of dynamically enabled channels. + uint32_t last_publish_ms[MAX_CHANNEL_NUM]; + + static uint32_t RateToPeriodMs(const Output_Rate rate); + +private: + + // Internal parser implementation state + enum class Parse_State { + WAITING_ON_STX, + WAITING_ON_STATUS, + WAITING_ON_PACKET_TYPE, + WAITING_ON_LENGTH, + WAITING_ON_PACKET_DATA, + WAITING_ON_CSUM, + WAITING_ON_ETX, + }; + + bool valid_csum(); + bool parse_payload(); + // https://receiverhelp.trimble.com/oem-gnss/ICD_Pkt_Command64h_APPFILE.html + bool parse_cmd_appfile(); + + + // states for currently parsing packet + Status status; + Parse_State parse_state = {Parse_State::WAITING_ON_STX}; + Packet_Type packet_type; + // This is the length in the header. + uint8_t expected_payload_length; + // This is the increasing tally of bytes per packet. + uint8_t cur_payload_idx; + // This is the expected packet checksum in the trailer. + uint8_t expected_csum; + + // The application file record transmission number + uint8_t appfile_trans_num; + + uint8_t payload[MAX_PAYLOAD_SIZE]; + + // Clear all parser state/flags for handling a fresh packet. + void reset(); +}; + +class GPS_GSOF : public GPS_Backend, public DCOL_Parser { public: CLASS_NO_COPY(GPS_GSOF); using GPS_Backend::GPS_Backend; + + // GPS_Backend overrides void publish(const GPS_Data *d) override; + void update_read() override; private: void send_gsof(const uint8_t *buf, const uint16_t size); @@ -235,7 +354,8 @@ class GPS : public SerialDevice { int ext_fifo_fd; - uint32_t last_update; // milliseconds + // The last time GPS data was written [mS] + uint32_t last_write_update_ms; // last 20 samples, allowing for up to 20 samples of delay GPS_Data _gps_history[20]; diff --git a/libraries/SITL/SIM_SerialDevice.h b/libraries/SITL/SIM_SerialDevice.h index 00f58ab93511b1..d04e573506c8ae 100644 --- a/libraries/SITL/SIM_SerialDevice.h +++ b/libraries/SITL/SIM_SerialDevice.h @@ -46,7 +46,7 @@ class SerialDevice { ByteBuffer *to_autopilot; ByteBuffer *from_autopilot; - bool init_sitl_pointer(); + bool init_sitl_pointer() WARN_IF_UNUSED; private: From 8b7652d1db098a2684373afcb458be927fdcda03 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 28 Nov 2023 16:02:37 +1100 Subject: [PATCH 459/499] Revert "AP_GPS: Move init logic from constructor to class" This reverts commit 5f84cd8f2b2c370078f025731eb4dda99e2136e8. --- libraries/AP_GPS/AP_GPS_GSOF.cpp | 56 +++++++++++++------------------- libraries/AP_GPS/AP_GPS_GSOF.h | 4 +-- 2 files changed, 24 insertions(+), 36 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 11dcca752359fd..1effd36754ef27 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -59,7 +59,21 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, { // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_Overview.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257COverview%257C_____0 static_assert(ARRAY_SIZE(gsofmsgreq) <= 10, "The maximum number of outputs allowed with GSOF is 10."); - static_assert(sizeof(gsofmsgreq) != 0, "gsofmsgreq is not empty"); + + msg.state = Msg_Parser::State::STARTTX; + + constexpr uint8_t default_com_port = static_cast(HW_Port::COM2); + gps._com_port[state.instance].set_default(default_com_port); + const auto com_port = gps._com_port[state.instance].get(); + if (!validate_com_port(com_port)) { + // The user parameter for COM port is not a valid GSOF port + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d has invalid COM port setting of %d", state.instance, com_port); + return; + } + const HW_Baud baud = HW_Baud::BAUD115K; + // Start by disabling output during config + [[maybe_unused]] const auto output_disabled = disableOutput(static_cast(com_port)); + is_baud_configured = requestBaud(static_cast(com_port), baud); } // Process all bytes available from the stream @@ -67,48 +81,22 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, bool AP_GPS_GSOF::read(void) { - if (!is_baud_configured) { // Debug("Baud not configured, not ready to read()"); - - constexpr uint8_t default_com_port = static_cast(HW_Port::COM2); - gps._com_port[state.instance].set_default(default_com_port); - const auto com_port = gps._com_port[state.instance].get(); - if (!validate_com_port(com_port)) { - // The user parameter for COM port is not a valid GSOF port - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d has invalid COM port setting of %d", state.instance, com_port); - return false; - } - const HW_Baud baud = HW_Baud::BAUD115K; - // Start by disabling output during config - if (!disableOutput(static_cast(com_port))) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d cannot disable output on port %d", state.instance, com_port); - return false; - } - - is_baud_configured = requestBaud(static_cast(com_port), baud); - if (!is_baud_configured) { - // Don't try further configuration if the baud request fails. - return false; - } + return false; } - while (gsofmsgreq_index < sizeof(gsofmsgreq)) { + bool gsof_configured = true; + + static_assert(sizeof(gsofmsgreq) != 0, "gsofmsgreq is not empty"); + while (gsofmsgreq_index < (sizeof(gsofmsgreq))) { const auto com_port = gps._com_port[state.instance].get(); if (!validate_com_port(com_port)) { - // The user parameter for COM port is not a valid GSOF port. + // The user parameter for COM port is not a valid GSOF port return false; } - const auto success = requestGSOF(gsofmsgreq[gsofmsgreq_index], static_cast(com_port), Output_Rate::FREQ_10_HZ); - if (!success) { - // Try again to do the rest of the configuration next time. - return false; - } else { - if (gsofmsgreq_index == sizeof(gsofmsgreq) - 1) { - gsof_configured = true; - } - } + gsof_configured &= requestGSOF(gsofmsgreq[gsofmsgreq_index], static_cast(com_port), Output_Rate::FREQ_10_HZ); gsofmsgreq_index++; } if (!gsof_configured) { diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index 82fcfa6f2a0573..e44b2137a55c86 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -108,7 +108,7 @@ class AP_GPS_GSOF : public AP_GPS_Backend ENDTX }; - State state = State::STARTTX; + State state; uint8_t status; uint8_t packettype; @@ -142,6 +142,6 @@ class AP_GPS_GSOF : public AP_GPS_Backend uint8_t gsofmsgreq_index; const uint8_t gsofmsgreq[5] = {1,2,8,9,12}; bool is_baud_configured {false}; - bool gsof_configured {false}; + bool is_configured {false}; }; #endif From 2e41cf810cfd0bb47a410ebd13c0d9eb3991590a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 28 Nov 2023 16:02:44 +1100 Subject: [PATCH 460/499] Revert "AP_GPS: GSOF robust config parsing" This reverts commit bf9881579c008f0feb8f1093d84bffc704c82726. --- libraries/AP_GPS/AP_GPS_GSOF.cpp | 192 ++++++------------------------- libraries/AP_GPS/AP_GPS_GSOF.h | 56 ++------- 2 files changed, 43 insertions(+), 205 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index 1effd36754ef27..42616a6af88459 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -36,15 +36,12 @@ extern const AP_HAL::HAL& hal; -// Set this to 1 to enable debug messages #define gsof_DEBUGGING 0 #if gsof_DEBUGGING # define Debug(fmt, args ...) \ do { \ - hal.console->printf("%u %s:%s:%d: " fmt "\n", \ - AP_HAL::millis(), \ - __FILE__, \ + hal.console->printf("%s:%d: " fmt "\n", \ __FUNCTION__, __LINE__, \ ## args); \ hal.scheduler->delay(1); \ @@ -70,10 +67,10 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GSOF instance %d has invalid COM port setting of %d", state.instance, com_port); return; } - const HW_Baud baud = HW_Baud::BAUD115K; - // Start by disabling output during config - [[maybe_unused]] const auto output_disabled = disableOutput(static_cast(com_port)); - is_baud_configured = requestBaud(static_cast(com_port), baud); + requestBaud(static_cast(com_port)); + + const uint32_t now = AP_HAL::millis(); + gsofmsg_time = now + 110; } // Process all bytes available from the stream @@ -81,27 +78,19 @@ AP_GPS_GSOF::AP_GPS_GSOF(AP_GPS &_gps, AP_GPS::GPS_State &_state, bool AP_GPS_GSOF::read(void) { - if (!is_baud_configured) { - // Debug("Baud not configured, not ready to read()"); - return false; - } + const uint32_t now = AP_HAL::millis(); - bool gsof_configured = true; - - static_assert(sizeof(gsofmsgreq) != 0, "gsofmsgreq is not empty"); - while (gsofmsgreq_index < (sizeof(gsofmsgreq))) { + if (gsofmsgreq_index < (sizeof(gsofmsgreq))) { const auto com_port = gps._com_port[state.instance].get(); if (!validate_com_port(com_port)) { // The user parameter for COM port is not a valid GSOF port return false; } - - gsof_configured &= requestGSOF(gsofmsgreq[gsofmsgreq_index], static_cast(com_port), Output_Rate::FREQ_10_HZ); - gsofmsgreq_index++; - } - if (!gsof_configured) { - Debug("Failed to requestGSOF()"); - return false; + if (now > gsofmsg_time) { + requestGSOF(gsofmsgreq[gsofmsgreq_index], static_cast(com_port), Output_Rate::FREQ_10_HZ); + gsofmsg_time = now + 110; + gsofmsgreq_index++; + } } bool ret = false; @@ -172,152 +161,46 @@ AP_GPS_GSOF::parse(const uint8_t temp) return false; } -bool -AP_GPS_GSOF::requestBaud(const HW_Port portIndex, const HW_Baud baudRate) +void +AP_GPS_GSOF::requestBaud(const HW_Port portindex) { - Debug("Requesting baud on port %u", (uint8_t)portIndex); - // GSOF is supported on the following bauds: - // 2400, 4800, 9600, 19200, 38400, 115200, 230400 - - // This packet is not documented in the API. uint8_t buffer[19] = {0x02,0x00,0x64,0x0d,0x00,0x00,0x00, // application file record 0x03, 0x00, 0x01, 0x00, // file control information block - 0x02, 0x04, static_cast(portIndex), static_cast(baudRate), 0x00,0x00, // serial port baud format + 0x02, 0x04, static_cast(portindex), 0x07, 0x00,0x00, // serial port baud format 0x00,0x03 - }; + }; // checksum + + buffer[4] = packetcount++; - populateOutgoingTransNumber(buffer); - populateChecksum(buffer, sizeof(buffer)); + uint8_t checksum = 0; + for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) { + checksum += buffer[a]; + } - return requestResponse(buffer, sizeof(buffer)); + buffer[17] = checksum; + + port->write((const uint8_t*)buffer, sizeof(buffer)); } -bool +void AP_GPS_GSOF::requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz) { - Debug("Requesting gsof #%u on port %u", messageType, (uint8_t)portIndex); - - // This packet is not documented in the API. uint8_t buffer[21] = {0x02,0x00,0x64,0x0f,0x00,0x00,0x00, // application file record 0x03,0x00,0x01,0x00, // file control information block 0x07,0x06,0x0a,static_cast(portIndex),static_cast(rateHz),0x00,messageType,0x00, // output message record 0x00,0x03 - }; - - populateOutgoingTransNumber(buffer); - populateChecksum(buffer, sizeof(buffer)); - - return requestResponse(buffer, sizeof(buffer)); -} - -bool -AP_GPS_GSOF::disableOutput(const HW_Port portIndex) { - Debug("Disabling output on on port %u", (uint8_t)portIndex); - switch(portIndex) { - case HW_Port::COM1: - { - constexpr uint8_t cmd[8] = { - STX, - 0x00, - 0x51, - 0x02, - 0x0A, - 0x01, - 0x5E, - ETX - }; - // The checksum is hard-coded. - // No need to calculate it. - return requestResponse(cmd, sizeof(cmd)); - } - - case HW_Port::COM2: - { - constexpr uint8_t cmd[8] = { - STX, - 0x00, - 0x51, - 0x02, - 0x0A, - 0x02, - 0x5F, - ETX - }; - return requestResponse(cmd, sizeof(cmd)); - } - } - return false; -} - -bool -AP_GPS_GSOF::requestResponse(const uint8_t* buf, const uint8_t len) { - if (!port->is_initialized()) { - Debug("Port not initialized"); - return false; - } - - for (int attempt = 0; attempt <= configuration_attempts; attempt++) { - // Clear input buffer before doing configuration - if (!port->discard_input()) { - Debug("Failed to discard input"); - return false; - }; - - port->write((const uint8_t*)buf, len); - - constexpr uint16_t expected_bytes = 1; - // TODO use wait_timeout instead once HAL_SITL has it implemented. - const auto start_wait = AP_HAL::millis(); - auto now = start_wait; - while (now - start_wait <= configuration_wait_time_ms) { - if (port->available() >= expected_bytes) { - break; - } - constexpr uint16_t delay_us = 100; - hal.scheduler->delay_microseconds(delay_us); - now = AP_HAL::millis(); - } - - const auto available_bytes = port->available(); - if (available_bytes != expected_bytes) { - Debug("Didn't get expected bytes, got %u bytes back", available_bytes); - return false; - } - - uint8_t resp_code; - if(port->read(resp_code) && resp_code == ACK) { - Debug("Got ack"); - return true; - } else { - Debug("Didn't get ACK, got 0x%02x", resp_code); - } - } - return false; -} + }; // checksum -void -AP_GPS_GSOF::populateChecksum(uint8_t* buf, const uint8_t len) -{ - // The buffer is of size len. - // If ETX is not element buf[len-1], the buf/len numbers are wrong. - // Same problem if the len is too small for a valid packet. - if (len <= 3 || buf[len - 1] != ETX) { - return; - } + buffer[4] = packetcount++; - // The checksum field is at buf[len - 2] uint8_t checksum = 0; - const uint8_t payload_size = len - 2; - for (uint8_t i = 1; i < payload_size; i++) { - checksum += buf[i]; + for (uint8_t a = 1; a < (sizeof(buffer) - 1); a++) { + checksum += buffer[a]; } - buf[len -2] = checksum; -} + buffer[19] = checksum; -void -AP_GPS_GSOF::populateOutgoingTransNumber(uint8_t* buf) { - buf[4] = packetOutboundTransNumber++; + port->write((const uint8_t*)buffer, sizeof(buffer)); } double @@ -376,7 +259,6 @@ AP_GPS_GSOF::process_message(void) if (msg.packettype == 0x40) { // GSOF // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 #if gsof_DEBUGGING - //trans_number is functionally the sequence number. const uint8_t trans_number = msg.data[0]; const uint8_t pageidx = msg.data[1]; const uint8_t maxpageidx = msg.data[2]; @@ -478,16 +360,6 @@ AP_GPS_GSOF::process_message(void) return false; } -bool -AP_GPS_GSOF::validate_baud(const uint8_t baud) const { - switch(baud) { - case static_cast(HW_Baud::BAUD230K): - case static_cast(HW_Baud::BAUD115K): - return true; - default: - return false; - } -} bool AP_GPS_GSOF::validate_com_port(const uint8_t com_port) const { switch(com_port) { diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index e44b2137a55c86..a55d91c0a9198b 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -16,7 +16,6 @@ // // Trimble GPS driver for ArduPilot. // Code by Michael Oborne -// Maintained by Ryan Friedman // https://receiverhelp.trimble.com/oem-gnss/index.html#Welcome.html?TocPath=_____1 #pragma once @@ -57,35 +56,17 @@ class AP_GPS_GSOF : public AP_GPS_Backend FREQ_100_HZ = 16, }; - // A subset of the supported baud rates in the GSOF protocol that are useful. - // These values are not documented in the API. - // The matches the GPS_GSOF_BAUD parameter. - enum class HW_Baud { - BAUD115K = 0x07, - BAUD230K = 0x0B, - }; - bool parse(const uint8_t temp) WARN_IF_UNUSED; bool process_message() WARN_IF_UNUSED; - // Send a request to the GPS to configure its baud rate on a certain (serial) port. - // Note - these request functions expect an ACK from the device. - // If the device is already sending serial traffic, there is no mechanism to prevent this. - // According to the manufacturer, the best approach is to switch to ethernet. - // Use one port for configuration data and another for stream data to prevent conflict. - // Because there is only one TTL serial interface exposed, the approach here is using retry logic. - bool requestBaud(const HW_Port portIndex, const HW_Baud baudRate) WARN_IF_UNUSED; - // Send a request to the GPS to enable a message type on the port. - bool requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz) WARN_IF_UNUSED; - - bool disableOutput(const HW_Port portIndex) WARN_IF_UNUSED; - - // Generic handler for sending command and checking return code. - // Make sure to disableOutput() before doing configuration. - bool requestResponse(const uint8_t* buf, const uint8_t len) WARN_IF_UNUSED; - - static void populateChecksum(uint8_t* buf, const uint8_t len); - void populateOutgoingTransNumber(uint8_t* buf); - + + // Send a request to the GPS to set the baud rate on the specified port. + // Note - these request functions currently ignore the ACK from the device. + // If the device is already sending serial traffic, there is no mechanism to prevent conflict. + // According to the manufacturer, the best approach is to switch to ethernet. + void requestBaud(const HW_Port portIndex); + // Send a request to the GPS to enable a message type on the port at the specified rate. + void requestGSOF(const uint8_t messageType, const HW_Port portIndex, const Output_Rate rateHz); + double SwapDouble(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; float SwapFloat(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; uint32_t SwapUint32(const uint8_t* src, const uint32_t pos) const WARN_IF_UNUSED; @@ -121,27 +102,12 @@ class AP_GPS_GSOF : public AP_GPS_Backend uint8_t checksumcalc; } msg; - static const uint8_t STX = 0x02; static const uint8_t ETX = 0x03; - static const uint8_t ACK = 0x06; - static const uint8_t NACK = 0x15; - - // How long to wait from sending configuration data for a response. - // This assumes delay is the same regardless of baud rate. - static const uint8_t configuration_wait_time_ms {5}; - // How many attempts to attempt configuration. - // Raising this makes the initialization more immune to data conflicts with streamed data. - // Raising it too high will trigger the watchdog. - // Lowering this makes the driver quicker to return from initialization calls. - static const uint8_t configuration_attempts {3}; - - // The counter for number of outgoing packets - uint8_t packetOutboundTransNumber; + + uint8_t packetcount; uint32_t gsofmsg_time; uint8_t gsofmsgreq_index; const uint8_t gsofmsgreq[5] = {1,2,8,9,12}; - bool is_baud_configured {false}; - bool is_configured {false}; }; #endif From c16e1a28df2841475261db31eb21a7c473ada8e1 Mon Sep 17 00:00:00 2001 From: jfbblue0922 Date: Tue, 21 Nov 2023 17:43:14 +0900 Subject: [PATCH 461/499] AP_HAL_ChibiOS/hwdef: changed defaults parm in JFB110 board definition Co-authored-by: Randy Mackay --- libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm index 285c4f17142414..4207e693ce825f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/JFB110/defaults.parm @@ -1,6 +1,9 @@ # board setting BRD_VBUS_MIN 4.9 +# setup SERIAL5 to RCIN +SERIAL5_PROTOCOL 23 + # setup SERIAL6 to SBUS OUT SERIAL6_BAUD 100 SERIAL6_PROTOCOL 15 From eb4e3fc36a1c6443f0d1e19ec778e36fcb9c3b5a Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 24 Oct 2023 13:25:53 +0100 Subject: [PATCH 462/499] AP_InertialSensor: init all notch center frequencies --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 49081c29e45bd0..f4de7b9f05f5dd 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -986,7 +986,9 @@ AP_InertialSensor::init(uint16_t loop_rate) if (!notch.params.enabled() && !fft_enabled) { continue; } - notch.calculated_notch_freq_hz[0] = notch.params.center_freq_hz(); + for (uint8_t i = 0; i < ARRAY_SIZE(notch.calculated_notch_freq_hz); i++) { + notch.calculated_notch_freq_hz[i] = notch.params.center_freq_hz(); + } notch.num_calculated_notch_frequencies = 1; notch.num_dynamic_notches = 1; #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) From a61fc423f062b3de82fbb3d199ec0b22f42075cf Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 3 Nov 2023 17:05:23 +0000 Subject: [PATCH 463/499] Filter: allow zero centre frequency to passthrough and disable notch --- libraries/Filter/HarmonicNotchFilter.cpp | 4 ++-- libraries/Filter/NotchFilter.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/Filter/HarmonicNotchFilter.cpp b/libraries/Filter/HarmonicNotchFilter.cpp index 82ae789ba5d97a..3182d4b1647a71 100644 --- a/libraries/Filter/HarmonicNotchFilter.cpp +++ b/libraries/Filter/HarmonicNotchFilter.cpp @@ -217,7 +217,7 @@ void HarmonicNotchFilter::update(float center_freq_hz) // adjust the fundamental center frequency to be in the allowable range const float nyquist_limit = _sample_freq_hz * 0.48f; - center_freq_hz = constrain_float(center_freq_hz, 1.0f, nyquist_limit); + center_freq_hz = constrain_float(center_freq_hz, 0.0f, nyquist_limit); _num_enabled_filters = 0; // update all of the filters using the new center frequency and existing A & Q @@ -278,7 +278,7 @@ void HarmonicNotchFilter::update(uint8_t num_centers, const float center_freq continue; } - const float notch_center = constrain_float(center_freq_hz[center_n] * (harmonic_n+1), 1.0f, nyquist_limit); + const float notch_center = constrain_float(center_freq_hz[center_n] * (harmonic_n+1), 0.0f, nyquist_limit); if (_composite_notches != 2) { // only enable the filter if its center frequency is below the nyquist frequency if (notch_center < nyquist_limit) { diff --git a/libraries/Filter/NotchFilter.cpp b/libraries/Filter/NotchFilter.cpp index 14ce778efa4cf2..fa2c024721be91 100644 --- a/libraries/Filter/NotchFilter.cpp +++ b/libraries/Filter/NotchFilter.cpp @@ -71,7 +71,7 @@ void NotchFilter::init_with_A_and_Q(float sample_freq_hz, float center_freq_h _center_freq_hz * NOTCH_MAX_SLEW_UPPER); } - if ((new_center_freq > 2.0) && (new_center_freq < 0.5 * sample_freq_hz) && (Q > 0.0)) { + if (is_positive(new_center_freq) && (new_center_freq < 0.5 * sample_freq_hz) && (Q > 0.0)) { float omega = 2.0 * M_PI * new_center_freq / sample_freq_hz; float alpha = sinf(omega) / (2 * Q); b0 = 1.0 + alpha*sq(A); From 002f1076d74fd6e0a4779d98c9351fa0168181b8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 7 Nov 2023 17:19:58 +1100 Subject: [PATCH 464/499] Filter: added optional notch debug logging this has helped find multiple bugs --- libraries/Filter/HarmonicNotchFilter.cpp | 31 ++++++++++++++++++++++++ libraries/Filter/NotchFilter.h | 4 +++ 2 files changed, 35 insertions(+) diff --git a/libraries/Filter/HarmonicNotchFilter.cpp b/libraries/Filter/HarmonicNotchFilter.cpp index 3182d4b1647a71..b2d1ad37c419b4 100644 --- a/libraries/Filter/HarmonicNotchFilter.cpp +++ b/libraries/Filter/HarmonicNotchFilter.cpp @@ -20,9 +20,21 @@ #include "HarmonicNotchFilter.h" #include +#include +#include +#include +#include #define HNF_MAX_FILTERS HAL_HNF_MAX_FILTERS // must be even for double-notch filters +/* + optional logging for SITL only of all notch frequencies + */ +#ifndef NOTCH_DEBUG_LOGGING +#define NOTCH_DEBUG_LOGGING 0 +#endif + + // table of user settable parameters const AP_Param::GroupInfo HarmonicNotchFilterParams::var_info[] = { @@ -311,10 +323,29 @@ T HarmonicNotchFilter::apply(const T &sample) return sample; } +#if NOTCH_DEBUG_LOGGING + static int dfd = -1; + if (dfd == -1) { + dfd = ::open("notch.txt", O_WRONLY|O_CREAT|O_TRUNC, 0644); + } +#endif + T output = sample; for (uint8_t i = 0; i < _num_enabled_filters; i++) { +#if NOTCH_DEBUG_LOGGING + if (!_filters[i].initialised) { + ::dprintf(dfd, "------- "); + } else { + ::dprintf(dfd, "%.4f ", _filters[i]._center_freq_hz); + } +#endif output = _filters[i].apply(output); } +#if NOTCH_DEBUG_LOGGING + if (_num_enabled_filters > 0) { + ::dprintf(dfd, "\n"); + } +#endif return output; } diff --git a/libraries/Filter/NotchFilter.h b/libraries/Filter/NotchFilter.h index 476d06d79b3cc2..624929208e1551 100644 --- a/libraries/Filter/NotchFilter.h +++ b/libraries/Filter/NotchFilter.h @@ -26,9 +26,13 @@ #include +template +class HarmonicNotchFilter; + template class NotchFilter { public: + friend class HarmonicNotchFilter; // set parameters void init(float sample_freq_hz, float center_freq_hz, float bandwidth_hz, float attenuation_dB); void init_with_A_and_Q(float sample_freq_hz, float center_freq_hz, float A, float Q); From 0d932e8a544d18661cfdef779db530cf2c10b81b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 7 Nov 2023 17:29:55 +1100 Subject: [PATCH 465/499] Filter: fixed uint8_t bug in total filters and expand_filter_count bug this gets the right number of notches on quadplanes, but is still very bad in fwd flight --- libraries/Filter/HarmonicNotchFilter.cpp | 22 +++++++++------------- libraries/Filter/HarmonicNotchFilter.h | 6 +++--- 2 files changed, 12 insertions(+), 16 deletions(-) diff --git a/libraries/Filter/HarmonicNotchFilter.cpp b/libraries/Filter/HarmonicNotchFilter.cpp index b2d1ad37c419b4..5a35ea5b7416d2 100644 --- a/libraries/Filter/HarmonicNotchFilter.cpp +++ b/libraries/Filter/HarmonicNotchFilter.cpp @@ -189,13 +189,8 @@ void HarmonicNotchFilter::allocate_filters(uint8_t num_notches, uint32_t harm expand the number of filters at runtime, allowing for RPM sources such as lua scripts */ template -void HarmonicNotchFilter::expand_filter_count(uint8_t num_notches) +void HarmonicNotchFilter::expand_filter_count(uint16_t total_notches) { - uint8_t num_filters = _num_harmonics * num_notches * _composite_notches; - if (num_filters <= _num_filters) { - // enough already - return; - } if (_alloc_has_failed) { // we've failed to allocate before, don't try again return; @@ -204,7 +199,7 @@ void HarmonicNotchFilter::expand_filter_count(uint8_t num_notches) note that we rely on the semaphore in AP_InertialSensor_Backend.cpp to make this thread safe */ - auto filters = new NotchFilter[num_filters]; + auto filters = new NotchFilter[total_notches]; if (filters == nullptr) { _alloc_has_failed = true; return; @@ -212,7 +207,7 @@ void HarmonicNotchFilter::expand_filter_count(uint8_t num_notches) memcpy(filters, _filters, sizeof(filters[0])*_num_filters); auto _old_filters = _filters; _filters = filters; - _num_filters = num_filters; + _num_filters = total_notches; delete[] _old_filters; } @@ -273,15 +268,16 @@ void HarmonicNotchFilter::update(uint8_t num_centers, const float center_freq // adjust the frequencies to be in the allowable range const float nyquist_limit = _sample_freq_hz * 0.48f; - if (num_centers > _num_filters) { + uint16_t total_notches = num_centers * _num_harmonics * _composite_notches; + if (total_notches > _num_filters) { // alloc realloc of filters - expand_filter_count(num_centers); + expand_filter_count(total_notches); } _num_enabled_filters = 0; // update all of the filters using the new center frequencies and existing A & Q - for (uint8_t i = 0; i < num_centers * HNF_MAX_HARMONICS && _num_enabled_filters < _num_filters; i++) { + for (uint16_t i = 0; i < num_centers * HNF_MAX_HARMONICS && _num_enabled_filters < _num_filters; i++) { const uint8_t harmonic_n = i / num_centers; const uint8_t center_n = i % num_centers; // the filters are ordered by center and then harmonic so @@ -331,7 +327,7 @@ T HarmonicNotchFilter::apply(const T &sample) #endif T output = sample; - for (uint8_t i = 0; i < _num_enabled_filters; i++) { + for (uint16_t i = 0; i < _num_enabled_filters; i++) { #if NOTCH_DEBUG_LOGGING if (!_filters[i].initialised) { ::dprintf(dfd, "------- "); @@ -359,7 +355,7 @@ void HarmonicNotchFilter::reset() return; } - for (uint8_t i = 0; i < _num_filters; i++) { + for (uint16_t i = 0; i < _num_filters; i++) { _filters[i].reset(); } } diff --git a/libraries/Filter/HarmonicNotchFilter.h b/libraries/Filter/HarmonicNotchFilter.h index 7de4df799df4e7..898857b82e58ec 100644 --- a/libraries/Filter/HarmonicNotchFilter.h +++ b/libraries/Filter/HarmonicNotchFilter.h @@ -32,7 +32,7 @@ class HarmonicNotchFilter { // allocate a bank of notch filters for this harmonic notch filter void allocate_filters(uint8_t num_notches, uint32_t harmonics, uint8_t composite_notches); // expand filter bank with new filters - void expand_filter_count(uint8_t num_notches); + void expand_filter_count(uint16_t total_notches); // initialize the underlying filters using the provided filter parameters void init(float sample_freq_hz, float center_freq_hz, float bandwidth_hz, float attenuation_dB); // update the underlying filters' center frequencies using center_freq_hz as the fundamental @@ -60,11 +60,11 @@ class HarmonicNotchFilter { // number of notches that make up a composite notch uint8_t _composite_notches; // number of allocated filters - uint8_t _num_filters; + uint16_t _num_filters; // pre-calculated number of harmonics uint8_t _num_harmonics; // number of enabled filters - uint8_t _num_enabled_filters; + uint16_t _num_enabled_filters; bool _initialised; // have we failed to expand filters? From 11a5b78a0c68055d0b667753880edd2c15cb19ce Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 28 Nov 2023 22:42:20 +1100 Subject: [PATCH 466/499] waf: correct sitl_periph_gps build --- Tools/ardupilotwaf/boards.py | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 2d969671e1a6f9..e18d3137065f3d 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -878,13 +878,17 @@ def configure_env(self, cfg, env): AP_CAN_SLCAN_ENABLED = 0, HAL_PROXIMITY_ENABLED = 0, AP_SCRIPTING_ENABLED = 0, - HAL_NAVEKF2_AVAILABLE = 0, HAL_NAVEKF3_AVAILABLE = 0, HAL_PWM_COUNT = 32, HAL_WITH_ESC_TELEM = 1, AP_RTC_ENABLED = 0, ) + try: + env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=1') + except ValueError: + pass + env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=0'] class esp32(Board): abstract = True From 2650137e8c429bbac2c576b4fc41d1af99ee5bb8 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 28 Nov 2023 14:33:36 -0800 Subject: [PATCH 467/499] Tools: fix AP_Periph param docs generator --- Tools/autotest/param_metadata/param_parse.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/Tools/autotest/param_metadata/param_parse.py b/Tools/autotest/param_metadata/param_parse.py index 7f5f9c21202dee..fdb1465e29cc4d 100755 --- a/Tools/autotest/param_metadata/param_parse.py +++ b/Tools/autotest/param_metadata/param_parse.py @@ -109,11 +109,12 @@ def lua_applets(): libraries = [] -# AP_Vehicle also has parameters rooted at "", but isn't referenced -# from the vehicle in any way: -ap_vehicle_lib = Library("", reference="VEHICLE") # the "" is tacked onto the front of param name -setattr(ap_vehicle_lib, "Path", os.path.join('..', 'libraries', 'AP_Vehicle', 'AP_Vehicle.cpp')) -libraries.append(ap_vehicle_lib) +if args.vehicle != "AP_Periph": + # AP_Vehicle also has parameters rooted at "", but isn't referenced + # from the vehicle in any way: + ap_vehicle_lib = Library("", reference="VEHICLE") # the "" is tacked onto the front of param name + setattr(ap_vehicle_lib, "Path", os.path.join('..', 'libraries', 'AP_Vehicle', 'AP_Vehicle.cpp')) + libraries.append(ap_vehicle_lib) libraries.append(lua_applets()) From f72dd8cc8916d18245fb2c695d71d4f26d836089 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 28 Nov 2023 13:20:11 -0800 Subject: [PATCH 468/499] AP_Network: mavlink packetise requires mavlink --- libraries/AP_Networking/AP_Networking_port.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index 23c43df13304fb..3cb6a2f3d17dba 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -353,9 +353,11 @@ bool AP_Networking::Port::send_receive(void) // handle outgoing packets uint32_t available = writebuffer->available(); available = MIN(300U, available); +#if HAL_GCS_ENABLED if (packetise) { available = mavlink_packetise(*writebuffer, available); } +#endif if (available > 0) { uint8_t buf[available]; auto n = writebuffer->peekbytes(buf, available); From 7da434d1e04bc6329e387aaf0676ce7f81e02061 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 28 Nov 2023 13:26:02 -0800 Subject: [PATCH 469/499] AP_Periph: fix include order network build error --- Tools/AP_Periph/AP_Periph.h | 1 - Tools/AP_Periph/networking.h | 4 +++- Tools/AP_Periph/networking_passthru.cpp | 2 +- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 376e7245ba0e0d..7459a179eff416 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -26,7 +26,6 @@ #include #include #include -#include #include #include #include diff --git a/Tools/AP_Periph/networking.h b/Tools/AP_Periph/networking.h index d25dc5aa7aaa77..6b7f857fdcde8c 100644 --- a/Tools/AP_Periph/networking.h +++ b/Tools/AP_Periph/networking.h @@ -1,9 +1,11 @@ #pragma once -#include "AP_Periph.h" +#include #ifdef HAL_PERIPH_ENABLE_NETWORKING +#include + #ifndef HAL_PERIPH_NETWORK_NUM_PASSTHRU #define HAL_PERIPH_NETWORK_NUM_PASSTHRU 2 #endif diff --git a/Tools/AP_Periph/networking_passthru.cpp b/Tools/AP_Periph/networking_passthru.cpp index 18ed58bf68bac5..3d2f65a1cad7b7 100644 --- a/Tools/AP_Periph/networking_passthru.cpp +++ b/Tools/AP_Periph/networking_passthru.cpp @@ -13,7 +13,7 @@ along with this program. If not, see . */ -#include "networking.h" +#include "AP_Periph.h" #if defined(HAL_PERIPH_ENABLE_NETWORKING) && HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 From 0a4eb251c654834076a4cd9626d7cb572a3cb0c2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 29 Nov 2023 09:21:29 +1100 Subject: [PATCH 470/499] AP_Periph: disable UART reboot check for non-debug builds this was causing loss of bytes on GPS peripherals as the reboot check swallowed data. The option is really only meant for debug builds to make ./waf AP_Periph --upload work, so disable by default on non-debug builds we could just remove this option where it is in hwdef.dat files, but I know quite a few peripherals are out-of-tree, so this catches the error for those too the symptoms were high GPS delta values --- Tools/AP_Periph/AP_Periph.h | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 7459a179eff416..b0e0839d6f08c9 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -76,6 +76,15 @@ #define HAL_PERIPH_CAN_MIRROR 0 #endif +#if defined(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT) && !defined(HAL_DEBUG_BUILD) && !defined(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_NON_DEBUG) +/* this checking for reboot can lose bytes on GPS modules and other + * serial devices. It is really only relevent on a debug build if you + * really want it for non-debug build then define + * HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_NON_DEBUG in hwdef.dat + */ +#undef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT +#endif + #include "Parameters.h" #if CONFIG_HAL_BOARD == HAL_BOARD_SITL From 568d633dccedd1c99ffae059e348fdfefc5489f3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 28 Nov 2023 21:24:44 +1100 Subject: [PATCH 471/499] SITL: break up GPS backends into separate files --- libraries/SITL/SIM_GPS.cpp | 1562 +------------------------ libraries/SITL/SIM_GPS.h | 263 +---- libraries/SITL/SIM_GPS_FILE.cpp | 67 ++ libraries/SITL/SIM_GPS_FILE.h | 20 + libraries/SITL/SIM_GPS_GSOF.cpp | 569 +++++++++ libraries/SITL/SIM_GPS_GSOF.h | 149 +++ libraries/SITL/SIM_GPS_MSP.cpp | 88 ++ libraries/SITL/SIM_GPS_MSP.h | 20 + libraries/SITL/SIM_GPS_NMEA.cpp | 125 ++ libraries/SITL/SIM_GPS_NMEA.h | 29 + libraries/SITL/SIM_GPS_NOVA.cpp | 177 +++ libraries/SITL/SIM_GPS_NOVA.h | 30 + libraries/SITL/SIM_GPS_SBP.cpp | 122 ++ libraries/SITL/SIM_GPS_SBP.h | 23 + libraries/SITL/SIM_GPS_SBP2.cpp | 121 ++ libraries/SITL/SIM_GPS_SBP2.h | 23 + libraries/SITL/SIM_GPS_SBP_Common.cpp | 34 + libraries/SITL/SIM_GPS_SBP_Common.h | 25 + libraries/SITL/SIM_GPS_UBLOX.cpp | 324 +++++ libraries/SITL/SIM_GPS_UBLOX.h | 23 + libraries/SITL/SIM_config.h | 41 + 21 files changed, 2057 insertions(+), 1778 deletions(-) create mode 100644 libraries/SITL/SIM_GPS_FILE.cpp create mode 100644 libraries/SITL/SIM_GPS_FILE.h create mode 100644 libraries/SITL/SIM_GPS_GSOF.cpp create mode 100644 libraries/SITL/SIM_GPS_GSOF.h create mode 100644 libraries/SITL/SIM_GPS_MSP.cpp create mode 100644 libraries/SITL/SIM_GPS_MSP.h create mode 100644 libraries/SITL/SIM_GPS_NMEA.cpp create mode 100644 libraries/SITL/SIM_GPS_NMEA.h create mode 100644 libraries/SITL/SIM_GPS_NOVA.cpp create mode 100644 libraries/SITL/SIM_GPS_NOVA.h create mode 100644 libraries/SITL/SIM_GPS_SBP.cpp create mode 100644 libraries/SITL/SIM_GPS_SBP.h create mode 100644 libraries/SITL/SIM_GPS_SBP2.cpp create mode 100644 libraries/SITL/SIM_GPS_SBP2.h create mode 100644 libraries/SITL/SIM_GPS_SBP_Common.cpp create mode 100644 libraries/SITL/SIM_GPS_SBP_Common.h create mode 100644 libraries/SITL/SIM_GPS_UBLOX.cpp create mode 100644 libraries/SITL/SIM_GPS_UBLOX.h diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 61eeaaecc70616..9ec9484a4460ee 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -12,13 +12,19 @@ #include -#include #include #include #include #include -#include -#include + +#include "SIM_GPS_FILE.h" +#include "SIM_GPS_GSOF.h" +#include "SIM_GPS_MSP.h" +#include "SIM_GPS_NMEA.h" +#include "SIM_GPS_NOVA.h" +#include "SIM_GPS_SBP2.h" +#include "SIM_GPS_SBP.h" +#include "SIM_GPS_UBLOX.h" // the number of GPS leap seconds - copied from AP_GPS.h #define GPS_LEAPSECONDS_MILLIS 18000ULL @@ -27,13 +33,6 @@ extern const AP_HAL::HAL& hal; using namespace SITL; -struct GPS_TOW { - // Number of weeks since midnight 5-6 January 1980 - uint16_t week; - // Time since start of the GPS week [mS] - uint32_t ms; -}; - // ensure the backend we have allocated matches the one that's configured: GPS_Backend::GPS_Backend(GPS &_front, uint8_t _instance) : front{_front}, @@ -114,7 +113,7 @@ ssize_t GPS::write_to_autopilot(const char *p, size_t size) const /* get timeval using simulation time */ -static void simulation_timeval(struct timeval *tv) +void GPS_Backend::simulation_timeval(struct timeval *tv) { uint64_t now = AP_HAL::micros64(); static uint64_t first_usec; @@ -130,37 +129,10 @@ static void simulation_timeval(struct timeval *tv) tv->tv_usec = new_usec % 1000000ULL; } -/* - send a UBLOX GPS message - */ -void GPS_UBlox::send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size) -{ - const uint8_t PREAMBLE1 = 0xb5; - const uint8_t PREAMBLE2 = 0x62; - const uint8_t CLASS_NAV = 0x1; - uint8_t hdr[6], chk[2]; - hdr[0] = PREAMBLE1; - hdr[1] = PREAMBLE2; - hdr[2] = CLASS_NAV; - hdr[3] = msgid; - hdr[4] = size & 0xFF; - hdr[5] = size >> 8; - chk[0] = chk[1] = hdr[2]; - chk[1] += (chk[0] += hdr[3]); - chk[1] += (chk[0] += hdr[4]); - chk[1] += (chk[0] += hdr[5]); - for (uint16_t i=0; ilongitude * 1.0e7; - pos.latitude = d->latitude * 1.0e7; - pos.altitude_ellipsoid = d->altitude * 1000.0f; - pos.altitude_msl = d->altitude * 1000.0f; - pos.horizontal_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.vertical_accuracy = _sitl->gps_accuracy[instance]*1000; - - status.time = gps_tow.ms; - status.fix_type = d->have_lock?3:0; - status.fix_status = d->have_lock?1:0; - status.differential_status = 0; - status.res = 0; - status.time_to_first_fix = 0; - status.uptime = AP_HAL::millis(); - - velned.time = gps_tow.ms; - velned.ned_north = 100.0f * d->speedN; - velned.ned_east = 100.0f * d->speedE; - velned.ned_down = 100.0f * d->speedD; - velned.speed_2d = norm(d->speedN, d->speedE) * 100; - velned.speed_3d = norm(d->speedN, d->speedE, d->speedD) * 100; - velned.heading_2d = ToDeg(atan2f(d->speedE, d->speedN)) * 100000.0f; - if (velned.heading_2d < 0.0f) { - velned.heading_2d += 360.0f * 100000.0f; - } - velned.speed_accuracy = 40; - velned.heading_accuracy = 4; - - memset(&sol, 0, sizeof(sol)); - sol.fix_type = d->have_lock?3:0; - sol.fix_status = 221; - sol.satellites = d->have_lock ? _sitl->gps_numsats[instance] : 3; - sol.time = gps_tow.ms; - sol.week = gps_tow.week; - - dop.time = gps_tow.ms; - dop.gDOP = 65535; - dop.pDOP = 65535; - dop.tDOP = 65535; - dop.vDOP = 200; - dop.hDOP = 121; - dop.nDOP = 65535; - dop.eDOP = 65535; - - pvt.itow = gps_tow.ms; - pvt.year = 0; - pvt.month = 0; - pvt.day = 0; - pvt.hour = 0; - pvt.min = 0; - pvt.sec = 0; - pvt.valid = 0; // invalid utc date - pvt.t_acc = 0; - pvt.nano = 0; - pvt.fix_type = d->have_lock? 0x3 : 0; - pvt.flags = 0b10000011; // carrsoln=fixed, psm = na, diffsoln and fixok - pvt.flags2 =0; - pvt.num_sv = d->have_lock ? _sitl->gps_numsats[instance] : 3; - pvt.lon = d->longitude * 1.0e7; - pvt.lat = d->latitude * 1.0e7; - pvt.height = d->altitude * 1000.0f; - pvt.h_msl = d->altitude * 1000.0f; - pvt.h_acc = _sitl->gps_accuracy[instance] * 1000; - pvt.v_acc = _sitl->gps_accuracy[instance] * 1000; - pvt.velN = 1000.0f * d->speedN; - pvt.velE = 1000.0f * d->speedE; - pvt.velD = 1000.0f * d->speedD; - pvt.gspeed = norm(d->speedN, d->speedE) * 1000; - pvt.head_mot = ToDeg(atan2f(d->speedE, d->speedN)) * 1.0e5; - pvt.s_acc = 40; - pvt.head_acc = 38 * 1.0e5; - pvt.p_dop = 65535; - memset(pvt.reserved1, '\0', ARRAY_SIZE(pvt.reserved1)); - pvt.headVeh = 0; - memset(pvt.reserved2, '\0', ARRAY_SIZE(pvt.reserved2)); - - if (_sitl->gps_hdg_enabled[instance] > SITL::SIM::GPS_HEADING_NONE) { - const Vector3f ant1_pos = _sitl->gps_pos_offset[instance^1].get(); - const Vector3f ant2_pos = _sitl->gps_pos_offset[instance].get(); - Vector3f rel_antenna_pos = ant2_pos - ant1_pos; - Matrix3f rot; - // project attitude back using gyros to get antenna orientation at time of GPS sample - Vector3f gyro(radians(_sitl->state.rollRate), - radians(_sitl->state.pitchRate), - radians(_sitl->state.yawRate)); - rot.from_euler(radians(_sitl->state.rollDeg), radians(_sitl->state.pitchDeg), radians(d->yaw_deg)); - const float lag = _sitl->gps_delay_ms[instance] * 0.001; - rot.rotate(gyro * (-lag)); - rel_antenna_pos = rot * rel_antenna_pos; - relposned.version = 1; - relposned.iTOW = gps_tow.ms; - relposned.relPosN = rel_antenna_pos.x * 100; - relposned.relPosE = rel_antenna_pos.y * 100; - relposned.relPosD = rel_antenna_pos.z * 100; - relposned.relPosLength = rel_antenna_pos.length() * 100; - relposned.relPosHeading = degrees(Vector2f(rel_antenna_pos.x, rel_antenna_pos.y).angle()) * 1.0e5; - relposned.flags = gnssFixOK | diffSoln | carrSolnFixed | isMoving | relPosValid | relPosHeadingValid; - } - - send_ubx(MSG_POSLLH, (uint8_t*)&pos, sizeof(pos)); - send_ubx(MSG_STATUS, (uint8_t*)&status, sizeof(status)); - send_ubx(MSG_VELNED, (uint8_t*)&velned, sizeof(velned)); - send_ubx(MSG_SOL, (uint8_t*)&sol, sizeof(sol)); - send_ubx(MSG_DOP, (uint8_t*)&dop, sizeof(dop)); - send_ubx(MSG_PVT, (uint8_t*)&pvt, sizeof(pvt)); - if (_sitl->gps_hdg_enabled[instance] > SITL::SIM::GPS_HEADING_NONE) { - send_ubx(MSG_RELPOSNED, (uint8_t*)&relposned, sizeof(relposned)); - } - - if (gps_tow.ms > _next_nav_sv_info_time) { - svinfo.itow = gps_tow.ms; - svinfo.numCh = 32; - svinfo.globalFlags = 4; // u-blox 8/M8 - // fill in the SV's with some data even though firmware does not currently use it - // note that this is not using num_sats as we aren't dynamically creating this to match - for (uint8_t i = 0; i < SV_COUNT; i++) { - svinfo.sv[i].chn = i; - svinfo.sv[i].svid = i; - svinfo.sv[i].flags = (i < _sitl->gps_numsats[instance]) ? 0x7 : 0x6; // sv used, diff correction data, orbit information - svinfo.sv[i].quality = 7; // code and carrier lock and time synchronized - svinfo.sv[i].cno = MAX(20, 30 - i); - svinfo.sv[i].elev = MAX(30, 90 - i); - svinfo.sv[i].azim = i; - // not bothering to fill in prRes - } - send_ubx(MSG_SVINFO, (uint8_t*)&svinfo, sizeof(svinfo)); - _next_nav_sv_info_time = gps_tow.ms + 10000; // 10 second delay - } -} - -/* - formatted print of NMEA message, with checksum appended - */ -void GPS_NMEA::nmea_printf(const char *fmt, ...) -{ - va_list ap; - - va_start(ap, fmt); - char *s = nmea_vaprintf(fmt, ap); - va_end(ap); - if (s != nullptr) { - write_to_autopilot((const char*)s, strlen(s)); - free(s); - } -} - - -/* - send a new GPS NMEA packet - */ -void GPS_NMEA::publish(const GPS_Data *d) -{ - struct timeval tv; - struct tm *tm; - char tstring[20]; - char dstring[20]; - char lat_string[20]; - char lng_string[20]; - - simulation_timeval(&tv); - - tm = gmtime(&tv.tv_sec); - - // format time string - snprintf(tstring, sizeof(tstring), "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + tv.tv_usec*1.0e-6); - - // format date string - snprintf(dstring, sizeof(dstring), "%02u%02u%02u", tm->tm_mday, tm->tm_mon+1, tm->tm_year % 100); - - // format latitude - double deg = fabs(d->latitude); - snprintf(lat_string, sizeof(lat_string), "%02u%08.5f,%c", - (unsigned)deg, - (deg - int(deg))*60, - d->latitude<0?'S':'N'); - - // format longitude - deg = fabs(d->longitude); - snprintf(lng_string, sizeof(lng_string), "%03u%08.5f,%c", - (unsigned)deg, - (deg - int(deg))*60, - d->longitude<0?'W':'E'); - - nmea_printf("$GPGGA,%s,%s,%s,%01d,%02d,%04.1f,%07.2f,M,0.0,M,,", - tstring, - lat_string, - lng_string, - d->have_lock?1:0, - d->have_lock?_sitl->gps_numsats[instance]:3, - 1.2, - d->altitude); - - const float speed_mps = d->speed_2d(); - const float speed_knots = speed_mps * M_PER_SEC_TO_KNOTS; - const auto heading_rad = d->heading(); - - //$GPVTG,133.18,T,120.79,M,0.11,N,0.20,K,A*24 - nmea_printf("$GPVTG,%.2f,T,%.2f,M,%.2f,N,%.2f,K,A", - tstring, - heading_rad, - heading_rad, - speed_knots, - speed_knots * KNOTS_TO_METERS_PER_SECOND * 3.6); - - nmea_printf("$GPRMC,%s,%c,%s,%s,%.2f,%.2f,%s,,", - tstring, - d->have_lock?'A':'V', - lat_string, - lng_string, - speed_knots, - heading_rad, - dstring); - - if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_HDT) { - nmea_printf("$GPHDT,%.2f,T", d->yaw_deg); - } - else if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_THS) { - nmea_printf("$GPTHS,%.2f,%c,T", d->yaw_deg, d->have_lock ? 'A' : 'V'); - } else if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_KSXT) { - // Unicore support - // $KSXT,20211016083433.00,116.31296102,39.95817066,49.4911,223.57,-11.32,330.19,0.024,,1,3,28,27,,,,-0.012,0.021,0.020,,*2D - nmea_printf("$KSXT,%04u%02u%02u%02u%02u%02u.%02u,%.8f,%.8f,%.4f,%.2f,%.2f,%.2f,%.2f,%.3f,%u,%u,%u,%u,,,,%.3f,%.3f,%.3f,,", - tm->tm_year+1900, tm->tm_mon+1, tm->tm_mday, tm->tm_hour, tm->tm_min, tm->tm_sec, unsigned(tv.tv_usec*1.e-4), - d->longitude, d->latitude, - d->altitude, - wrap_360(d->yaw_deg), - d->pitch_deg, - heading_rad, - speed_mps, - d->roll_deg, - d->have_lock?1:0, // 2=rtkfloat 3=rtkfixed, - 3, // fixed rtk yaw solution, - d->have_lock?_sitl->gps_numsats[instance]:3, - d->have_lock?_sitl->gps_numsats[instance]:3, - d->speedE * 3.6, - d->speedN * 3.6, - -d->speedD * 3.6); - } -} - -void GPS_SBP_Common::sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload) -{ - if (len != 0 && payload == 0) { - return; //SBP_NULL_ERROR; - } - - uint8_t preamble = 0x55; - write_to_autopilot((char*)&preamble, 1); - write_to_autopilot((char*)&msg_type, 2); - write_to_autopilot((char*)&sender_id, 2); - write_to_autopilot((char*)&len, 1); - if (len > 0) { - write_to_autopilot((char*)payload, len); - } - - uint16_t crc; - crc = crc16_ccitt((uint8_t*)&(msg_type), 2, 0); - crc = crc16_ccitt((uint8_t*)&(sender_id), 2, crc); - crc = crc16_ccitt(&(len), 1, crc); - crc = crc16_ccitt(payload, len, crc); - write_to_autopilot((char*)&crc, 2); -} - -void GPS_SBP::publish(const GPS_Data *d) -{ - struct sbp_heartbeat_t { - bool sys_error : 1; - bool io_error : 1; - bool nap_error : 1; - uint8_t res : 5; - uint8_t protocol_minor : 8; - uint8_t protocol_major : 8; - uint8_t res2 : 7; - bool ext_antenna : 1; - } hb; // 4 bytes - - struct PACKED sbp_gps_time_t { - uint16_t wn; //< GPS week number - uint32_t tow; //< GPS Time of Week rounded to the nearest ms - int32_t ns; //< Nanosecond remainder of rounded tow - uint8_t flags; //< Status flags (reserved) - } t; - struct PACKED sbp_pos_llh_t { - uint32_t tow; //< GPS Time of Week - double lat; //< Latitude - double lon; //< Longitude - double height; //< Height - uint16_t h_accuracy; //< Horizontal position accuracy estimate - uint16_t v_accuracy; //< Vertical position accuracy estimate - uint8_t n_sats; //< Number of satellites used in solution - uint8_t flags; //< Status flags - } pos; - struct PACKED sbp_vel_ned_t { - uint32_t tow; //< GPS Time of Week - int32_t n; //< Velocity North coordinate - int32_t e; //< Velocity East coordinate - int32_t d; //< Velocity Down coordinate - uint16_t h_accuracy; //< Horizontal velocity accuracy estimate - uint16_t v_accuracy; //< Vertical velocity accuracy estimate - uint8_t n_sats; //< Number of satellites used in solution - uint8_t flags; //< Status flags (reserved) - } velned; - struct PACKED sbp_dops_t { - uint32_t tow; //< GPS Time of Week - uint16_t gdop; //< Geometric Dilution of Precision - uint16_t pdop; //< Position Dilution of Precision - uint16_t tdop; //< Time Dilution of Precision - uint16_t hdop; //< Horizontal Dilution of Precision - uint16_t vdop; //< Vertical Dilution of Precision - uint8_t flags; //< Status flags (reserved) - } dops; - - static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF; - static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0100; - static const uint16_t SBP_DOPS_MSGTYPE = 0x0206; - static const uint16_t SBP_POS_LLH_MSGTYPE = 0x0201; - static const uint16_t SBP_VEL_NED_MSGTYPE = 0x0205; - - const auto gps_tow = gps_time(); - - t.wn = gps_tow.week; - t.tow = gps_tow.ms; - t.ns = 0; - t.flags = 0; - sbp_send_message(SBP_GPS_TIME_MSGTYPE, 0x2222, sizeof(t), (uint8_t*)&t); - - if (!d->have_lock) { - return; - } - - pos.tow = gps_tow.ms; - pos.lon = d->longitude; - pos.lat= d->latitude; - pos.height = d->altitude; - pos.h_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.v_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; - - // Send single point position solution - pos.flags = 0; - sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos); - // Send "pseudo-absolute" RTK position solution - pos.flags = 1; - sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos); - - velned.tow = gps_tow.ms; - velned.n = 1e3 * d->speedN; - velned.e = 1e3 * d->speedE; - velned.d = 1e3 * d->speedD; - velned.h_accuracy = 5e3; - velned.v_accuracy = 5e3; - velned.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; - velned.flags = 0; - sbp_send_message(SBP_VEL_NED_MSGTYPE, 0x2222, sizeof(velned), (uint8_t*)&velned); - - static uint32_t do_every_count = 0; - if (do_every_count % 5 == 0) { - - dops.tow = gps_tow.ms; - dops.gdop = 1; - dops.pdop = 1; - dops.tdop = 1; - dops.hdop = 100; - dops.vdop = 1; - dops.flags = 1; - sbp_send_message(SBP_DOPS_MSGTYPE, 0x2222, sizeof(dops), - (uint8_t*)&dops); - - hb.protocol_major = 0; //Sends protocol version 0 - sbp_send_message(SBP_HEARTBEAT_MSGTYPE, 0x2222, sizeof(hb), - (uint8_t*)&hb); - - } - do_every_count++; -} - - -void GPS_SBP2::publish(const GPS_Data *d) -{ - struct sbp_heartbeat_t { - bool sys_error : 1; - bool io_error : 1; - bool nap_error : 1; - uint8_t res : 5; - uint8_t protocol_minor : 8; - uint8_t protocol_major : 8; - uint8_t res2 : 7; - bool ext_antenna : 1; - } hb; // 4 bytes - - struct PACKED sbp_gps_time_t { - uint16_t wn; //< GPS week number - uint32_t tow; //< GPS Time of Week rounded to the nearest ms - int32_t ns; //< Nanosecond remainder of rounded tow - uint8_t flags; //< Status flags (reserved) - } t; - struct PACKED sbp_pos_llh_t { - uint32_t tow; //< GPS Time of Week - double lat; //< Latitude - double lon; //< Longitude - double height; //< Height - uint16_t h_accuracy; //< Horizontal position accuracy estimate - uint16_t v_accuracy; //< Vertical position accuracy estimate - uint8_t n_sats; //< Number of satellites used in solution - uint8_t flags; //< Status flags - } pos; - struct PACKED sbp_vel_ned_t { - uint32_t tow; //< GPS Time of Week - int32_t n; //< Velocity North coordinate - int32_t e; //< Velocity East coordinate - int32_t d; //< Velocity Down coordinate - uint16_t h_accuracy; //< Horizontal velocity accuracy estimate - uint16_t v_accuracy; //< Vertical velocity accuracy estimate - uint8_t n_sats; //< Number of satellites used in solution - uint8_t flags; //< Status flags (reserved) - } velned; - struct PACKED sbp_dops_t { - uint32_t tow; //< GPS Time of Week - uint16_t gdop; //< Geometric Dilution of Precision - uint16_t pdop; //< Position Dilution of Precision - uint16_t tdop; //< Time Dilution of Precision - uint16_t hdop; //< Horizontal Dilution of Precision - uint16_t vdop; //< Vertical Dilution of Precision - uint8_t flags; //< Status flags (reserved) - } dops; - - static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF; - static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0102; - static const uint16_t SBP_DOPS_MSGTYPE = 0x0208; - static const uint16_t SBP_POS_LLH_MSGTYPE = 0x020A; - static const uint16_t SBP_VEL_NED_MSGTYPE = 0x020E; - - const auto gps_tow = gps_time(); - - t.wn = gps_tow.week; - t.tow = gps_tow.ms; - t.ns = 0; - t.flags = 1; - sbp_send_message(SBP_GPS_TIME_MSGTYPE, 0x2222, sizeof(t), (uint8_t*)&t); - - if (!d->have_lock) { - return; - } - - pos.tow = gps_tow.ms; - pos.lon = d->longitude; - pos.lat= d->latitude; - pos.height = d->altitude; - pos.h_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.v_accuracy = _sitl->gps_accuracy[instance]*1000; - pos.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; - - // Send single point position solution - pos.flags = 1; - sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos); - // Send "pseudo-absolute" RTK position solution - pos.flags = 4; - sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos); - - velned.tow = gps_tow.ms; - velned.n = 1e3 * d->speedN; - velned.e = 1e3 * d->speedE; - velned.d = 1e3 * d->speedD; - velned.h_accuracy = 5e3; - velned.v_accuracy = 5e3; - velned.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; - velned.flags = 1; - sbp_send_message(SBP_VEL_NED_MSGTYPE, 0x2222, sizeof(velned), (uint8_t*)&velned); - - static uint32_t do_every_count = 0; - if (do_every_count % 5 == 0) { - - dops.tow = gps_tow.ms; - dops.gdop = 1; - dops.pdop = 1; - dops.tdop = 1; - dops.hdop = 100; - dops.vdop = 1; - dops.flags = 1; - sbp_send_message(SBP_DOPS_MSGTYPE, 0x2222, sizeof(dops), - (uint8_t*)&dops); - - hb.protocol_major = 2; //Sends protocol version 2.0 - sbp_send_message(SBP_HEARTBEAT_MSGTYPE, 0x2222, sizeof(hb), - (uint8_t*)&hb); - } - do_every_count++; -} - -void GPS_NOVA::publish(const GPS_Data *d) -{ - static struct PACKED nova_header - { - // 0 - uint8_t preamble[3]; - // 3 - uint8_t headerlength; - // 4 - uint16_t messageid; - // 6 - uint8_t messagetype; - //7 - uint8_t portaddr; - //8 - uint16_t messagelength; - //10 - uint16_t sequence; - //12 - uint8_t idletime; - //13 - uint8_t timestatus; - //14 - uint16_t week; - //16 - uint32_t tow; - //20 - uint32_t recvstatus; - // 24 - uint16_t resv; - //26 - uint16_t recvswver; - } header; - - struct PACKED psrdop - { - float gdop; - float pdop; - float hdop; - float htdop; - float tdop; - float cutoff; - uint32_t svcount; - // extra data for individual prns - } psrdop {}; - - struct PACKED bestpos - { - uint32_t solstat; - uint32_t postype; - double lat; - double lng; - double hgt; - float undulation; - uint32_t datumid; - float latsdev; - float lngsdev; - float hgtsdev; - // 4 bytes - uint8_t stnid[4]; - float diffage; - float sol_age; - uint8_t svstracked; - uint8_t svsused; - uint8_t svsl1; - uint8_t svsmultfreq; - uint8_t resv; - uint8_t extsolstat; - uint8_t galbeisigmask; - uint8_t gpsglosigmask; - } bestpos {}; - - struct PACKED bestvel - { - uint32_t solstat; - uint32_t veltype; - float latency; - float age; - double horspd; - double trkgnd; - // + up - double vertspd; - float resv; - } bestvel {}; - - const auto gps_tow = gps_time(); - - header.preamble[0] = 0xaa; - header.preamble[1] = 0x44; - header.preamble[2] = 0x12; - header.headerlength = sizeof(header); - header.week = gps_tow.week; - header.tow = gps_tow.ms; - - header.messageid = 174; - header.messagelength = sizeof(psrdop); - header.sequence += 1; - - psrdop.hdop = 1.20; - psrdop.htdop = 1.20; - nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&psrdop, sizeof(psrdop)); - - - header.messageid = 99; - header.messagelength = sizeof(bestvel); - header.sequence += 1; - - bestvel.horspd = norm(d->speedN, d->speedE); - bestvel.trkgnd = ToDeg(atan2f(d->speedE, d->speedN)); - bestvel.vertspd = -d->speedD; - - nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&bestvel, sizeof(bestvel)); - - - header.messageid = 42; - header.messagelength = sizeof(bestpos); - header.sequence += 1; - - bestpos.lat = d->latitude; - bestpos.lng = d->longitude; - bestpos.hgt = d->altitude; - bestpos.svsused = d->have_lock ? _sitl->gps_numsats[instance] : 3; - bestpos.latsdev=0.2; - bestpos.lngsdev=0.2; - bestpos.hgtsdev=0.2; - bestpos.solstat=0; - bestpos.postype=32; - - nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&bestpos, sizeof(bestpos)); -} - -void GPS_NOVA::nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen) -{ - write_to_autopilot((char*)header, headerlength); -write_to_autopilot((char*)payload, payloadlen); - - uint32_t crc = CalculateBlockCRC32(headerlength, header, (uint32_t)0); - crc = CalculateBlockCRC32(payloadlen, payload, crc); - - write_to_autopilot((char*)&crc, 4); -} - -#define CRC32_POLYNOMIAL 0xEDB88320L -uint32_t GPS_NOVA::CRC32Value(uint32_t icrc) -{ - int i; - uint32_t crc = icrc; - for ( i = 8 ; i > 0; i-- ) - { - if ( crc & 1 ) - crc = ( crc >> 1 ) ^ CRC32_POLYNOMIAL; - else - crc >>= 1; - } - return crc; -} - -uint32_t GPS_NOVA::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc) -{ - while ( length-- != 0 ) - { - crc = ((crc >> 8) & 0x00FFFFFFL) ^ (CRC32Value(((uint32_t) crc ^ *buffer++) & 0xff)); - } - return( crc ); -} - -void GPS_GSOF::publish(const GPS_Data *d) -{ - // This logic is to populate output buffer only with enabled channels. - // It also only sends each channel at the configured rate. - const uint64_t now = AP_HAL::millis(); - uint8_t buf[MAX_PAYLOAD_SIZE] = {}; - uint8_t payload_sz = 0; - uint8_t offset = 0; - if (channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_TIME)] != Output_Rate::OFF){ - const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::POSITION_TIME)]; - const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_TIME)]; - - if (now - last_time > RateToPeriodMs(desired_rate)) { - - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 - constexpr uint8_t GSOF_POS_TIME_LEN { 0x0A }; - // TODO magic number until SITL supports GPS bootcount based on GPSN_ENABLE - const uint8_t bootcount = 17; - - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%201 - enum class POS_FLAGS_1 : uint8_t { - NEW_POSITION = 1U << 0, - CLOCK_FIX_CALULATED = 1U << 1, - HORIZ_FROM_THIS_POS = 1U << 2, - HEIGHT_FROM_THIS_POS = 1U << 3, - RESERVED_4 = 1U << 4, - LEAST_SQ_POSITION = 1U << 5, - RESERVED_6 = 1U << 6, - POSITION_L1_PSEUDORANGES = 1U << 7 - }; - const uint8_t pos_flags_1 { - uint8_t(POS_FLAGS_1::NEW_POSITION) | - uint8_t(POS_FLAGS_1::CLOCK_FIX_CALULATED) | - uint8_t(POS_FLAGS_1::HORIZ_FROM_THIS_POS) | - uint8_t(POS_FLAGS_1::HEIGHT_FROM_THIS_POS) | - uint8_t(POS_FLAGS_1::RESERVED_4) | - uint8_t(POS_FLAGS_1::LEAST_SQ_POSITION) | - uint8_t(POS_FLAGS_1::POSITION_L1_PSEUDORANGES) - }; - - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%202 - enum class POS_FLAGS_2 : uint8_t { - DIFFERENTIAL_POS = 1U << 0, - DIFFERENTIAL_POS_PHASE_RTK = 1U << 1, - POSITION_METHOD_FIXED_PHASE = 1U << 2, - OMNISTAR_ACTIVE = 1U << 3, - DETERMINED_WITH_STATIC_CONSTRAINT = 1U << 4, - NETWORK_RTK = 1U << 5, - DITHERED_RTK = 1U << 6, - BEACON_DGNSS = 1U << 7, - }; - - // Simulate a GPS without RTK in SIM since there is no RTK SIM params. - // This means these flags are unset: - // NETWORK_RTK, DITHERED_RTK, BEACON_DGNSS - uint8_t pos_flags_2 {0}; - if(d->have_lock) { - pos_flags_2 |= uint8_t(POS_FLAGS_2::DIFFERENTIAL_POS); - pos_flags_2 |= uint8_t(POS_FLAGS_2::DIFFERENTIAL_POS_PHASE_RTK); - pos_flags_2 |= uint8_t(POS_FLAGS_2::POSITION_METHOD_FIXED_PHASE); - pos_flags_2 |= uint8_t(POS_FLAGS_2::OMNISTAR_ACTIVE); - pos_flags_2 |= uint8_t(POS_FLAGS_2::DETERMINED_WITH_STATIC_CONSTRAINT); - } - - const auto gps_tow = gps_time(); - const struct PACKED gsof_pos_time { - const uint8_t OUTPUT_RECORD_TYPE; - const uint8_t RECORD_LEN; - uint32_t time_week_ms; - uint16_t time_week; - uint8_t num_sats; - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%201 - uint8_t pos_flags_1; - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%202 - uint8_t pos_flags_2; - uint8_t initialized_num; - } pos_time { - uint8_t(Gsof_Msg_Record_Type::POSITION_TIME), - GSOF_POS_TIME_LEN, - htobe32(gps_tow.ms), - htobe16(gps_tow.week), - d->have_lock ? _sitl->gps_numsats[instance] : uint8_t(3), - pos_flags_1, - pos_flags_2, - bootcount - }; - static_assert(sizeof(gsof_pos_time) - (sizeof(gsof_pos_time::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_time::RECORD_LEN)) == GSOF_POS_TIME_LEN); - - payload_sz += sizeof(pos_time); - memcpy(&buf[offset], &pos_time, sizeof(pos_time)); - offset += sizeof(pos_time); - } - } - - if (channel_rates[uint8_t(Gsof_Msg_Record_Type::LLH)] != Output_Rate::OFF){ - const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::LLH)]; - const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::LLH)]; - - if (now - last_time > RateToPeriodMs(desired_rate)) { - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_LLH.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____20 - constexpr uint8_t GSOF_POS_LEN = 0x18; - - const struct PACKED gsof_pos { - const uint8_t OUTPUT_RECORD_TYPE; - const uint8_t RECORD_LEN; - uint64_t lat; - uint64_t lng; - uint64_t alt; - } pos { - uint8_t(Gsof_Msg_Record_Type::LLH), - GSOF_POS_LEN, - gsof_pack_double(d->latitude * DEG_TO_RAD_DOUBLE), - gsof_pack_double(d->longitude * DEG_TO_RAD_DOUBLE), - gsof_pack_double(static_cast(d->altitude)) - }; - static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN); - - payload_sz += sizeof(pos); - memcpy(&buf[offset], &pos, sizeof(pos)); - offset += sizeof(pos); - } - } - - if (channel_rates[uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA)] != Output_Rate::OFF){ - const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA)]; - const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA)]; - - if (now - last_time > RateToPeriodMs(desired_rate)) { - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Velocity.html - // use the smaller packet by ignoring local coordinate system - constexpr uint8_t GSOF_VEL_LEN = 0x0D; - - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags - enum class VEL_FIELDS : uint8_t { - VALID = 1U << 0, - CONSECUTIVE_MEASUREMENTS = 1U << 1, - HEADING_VALID = 1U << 2, - RESERVED_3 = 1U << 3, - RESERVED_4 = 1U << 4, - RESERVED_5 = 1U << 5, - RESERVED_6 = 1U << 6, - RESERVED_7 = 1U << 7, - }; - uint8_t vel_flags {0}; - if(d->have_lock) { - vel_flags |= uint8_t(VEL_FIELDS::VALID); - vel_flags |= uint8_t(VEL_FIELDS::CONSECUTIVE_MEASUREMENTS); - vel_flags |= uint8_t(VEL_FIELDS::HEADING_VALID); - } - - const struct PACKED gsof_vel { - const uint8_t OUTPUT_RECORD_TYPE; - const uint8_t RECORD_LEN; - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags - uint8_t flags; - uint32_t horiz_m_p_s; - uint32_t heading_rad; - uint32_t vertical_m_p_s; - } vel { - uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA), - GSOF_VEL_LEN, - vel_flags, - gsof_pack_float(d->speed_2d()), - gsof_pack_float(d->heading()), - // Trimble API has ambiguous direction here. - // Intentionally narrow from double. - gsof_pack_float(static_cast(d->speedD)) - }; - static_assert(sizeof(gsof_vel) - (sizeof(gsof_vel::OUTPUT_RECORD_TYPE) + sizeof(gsof_vel::RECORD_LEN)) == GSOF_VEL_LEN); - - payload_sz += sizeof(vel); - memcpy(&buf[offset], &vel, sizeof(vel)); - offset += sizeof(vel); - } - } - if (channel_rates[uint8_t(Gsof_Msg_Record_Type::PDOP_INFO)] != Output_Rate::OFF){ - const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::PDOP_INFO)]; - const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::PDOP_INFO)]; - - if (now - last_time > RateToPeriodMs(desired_rate)) { - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_PDOP.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____12 - constexpr uint8_t GSOF_DOP_LEN = 0x10; - const struct PACKED gsof_dop { - const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::PDOP_INFO) }; - const uint8_t RECORD_LEN { GSOF_DOP_LEN }; - uint32_t pdop = htobe32(1); - uint32_t hdop = htobe32(1); - uint32_t vdop = htobe32(1); - uint32_t tdop = htobe32(1); - } dop {}; - // Check the payload size calculation in the compiler - constexpr auto dop_size = sizeof(gsof_dop); - static_assert(dop_size == 18); - constexpr auto dop_record_type_size = sizeof(gsof_dop::OUTPUT_RECORD_TYPE); - static_assert(dop_record_type_size == 1); - constexpr auto len_size = sizeof(gsof_dop::RECORD_LEN); - static_assert(len_size == 1); - constexpr auto dop_payload_size = dop_size - (dop_record_type_size + len_size); - static_assert(dop_payload_size == GSOF_DOP_LEN); - - payload_sz += sizeof(dop); - memcpy(&buf[offset], &dop, sizeof(dop)); - offset += sizeof(dop); - } - } - if (channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO)] != Output_Rate::OFF){ - const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO)]; - const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO)]; - if (now - last_time > RateToPeriodMs(desired_rate)) { - // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_SIGMA.html - constexpr uint8_t GSOF_POS_SIGMA_LEN = 0x26; - const struct PACKED gsof_pos_sigma { - const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO) }; - const uint8_t RECORD_LEN { GSOF_POS_SIGMA_LEN }; - uint32_t pos_rms = htobe32(0); - uint32_t sigma_e = htobe32(0); - uint32_t sigma_n = htobe32(0); - uint32_t cov_en = htobe32(0); - uint32_t sigma_up = htobe32(0); - uint32_t semi_major_axis = htobe32(0); - uint32_t semi_minor_axis = htobe32(0); - uint32_t orientation = htobe32(0); - uint32_t unit_variance = htobe32(0); - uint16_t n_epocs = htobe32(1); // Always 1 for kinematic. - } pos_sigma {}; - static_assert(sizeof(gsof_pos_sigma) - (sizeof(gsof_pos_sigma::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_sigma::RECORD_LEN)) == GSOF_POS_SIGMA_LEN); - payload_sz += sizeof(pos_sigma); - memcpy(&buf[offset], &pos_sigma, sizeof(pos_sigma)); - offset += sizeof(pos_sigma); - } - } - - assert(offset == payload_sz); - - // Don't send empy frames when all channels are disabled; - if (payload_sz > 0) { - send_gsof(buf, payload_sz); - } - -} - -bool DCOL_Parser::dcol_parse(const char data_in) { - bool ret = false; - switch (parse_state) { - case Parse_State::WAITING_ON_STX: - if (data_in == STX) { - reset(); - parse_state = Parse_State::WAITING_ON_STATUS; - } - break; - case Parse_State::WAITING_ON_STATUS: - if (data_in != (uint8_t)Status::OK) { - // Invalid, status should always be OK. - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } else { - status = static_cast(data_in); - parse_state = Parse_State::WAITING_ON_PACKET_TYPE; - } - break; - case Parse_State::WAITING_ON_PACKET_TYPE: - if (data_in == (uint8_t)Packet_Type::COMMAND_APPFILE) { - packet_type = Packet_Type::COMMAND_APPFILE; - } else { - // Unsupported command in this simulator. - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } - parse_state = Parse_State::WAITING_ON_LENGTH; - break; - case Parse_State::WAITING_ON_LENGTH: - expected_payload_length = data_in; - parse_state = Parse_State::WAITING_ON_PACKET_DATA; - break; - case Parse_State::WAITING_ON_PACKET_DATA: - payload[cur_payload_idx] = data_in; - if (++cur_payload_idx == expected_payload_length) { - parse_state = Parse_State::WAITING_ON_CSUM; - } - break; - case Parse_State::WAITING_ON_CSUM: - expected_csum = data_in; - parse_state = Parse_State::WAITING_ON_ETX; - break; - case Parse_State::WAITING_ON_ETX: - if (data_in != ETX) { - reset(); - } - if (!valid_csum()) { - // GSOF driver sent a packet with invalid CSUM. - // In real GSOF driver, the packet is simply ignored with no reply. - // In the SIM, treat this as a coding error. - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } else { - ret = parse_payload(); - } - reset(); - break; - } - - return ret; -} - -uint32_t DCOL_Parser::RateToPeriodMs(const Output_Rate rate) { - uint32_t min_period_ms = 0; - switch (rate) { - case Output_Rate::OFF: - min_period_ms = 0; - break; - case Output_Rate::FREQ_10_HZ: - min_period_ms = 100; - break; - case Output_Rate::FREQ_50_HZ: - min_period_ms = 20; - break; - case Output_Rate::FREQ_100_HZ: - min_period_ms = 10; - break; - } - return min_period_ms; -} - - -bool DCOL_Parser::valid_csum() { - uint8_t sum = (uint8_t)status; - sum += (uint8_t)packet_type; - sum += expected_payload_length; - sum += crc_sum_of_bytes(payload, expected_payload_length); - return sum == expected_csum; -} - -bool DCOL_Parser::parse_payload() { - bool success = false; - if (packet_type == Packet_Type::COMMAND_APPFILE) { - success = parse_cmd_appfile(); - } - - return success; -} - -bool DCOL_Parser::parse_cmd_appfile() { - // A file control info block contains: - // * version - // * device type - // * start application file flag - // * factory settings flag - constexpr uint8_t file_control_info_block_sz = 4; - // An appfile header contains: - // * transmisison number - // * page index - // * max page index - constexpr uint8_t appfile_header_sz = 3; - constexpr uint8_t min_cmd_appfile_sz = file_control_info_block_sz + appfile_header_sz; - if (expected_payload_length < min_cmd_appfile_sz) { - return false; - } - - // For now, ignore appfile_trans_num, return success regardless. - // If the driver doesn't send the right value, it's not clear what the behavior is supposed to be. - // Also would need to handle re-sync. - // For now, just store it for debugging. - appfile_trans_num = payload[0]; - - // File control information block parsing: - // https://receiverhelp.trimble.com/oem-gnss/ICD_Subtype_Command64h_FileControlInfo.html - constexpr uint8_t expected_app_file_spec_version = 0x03; - constexpr uint8_t file_ctrl_idx = appfile_header_sz; - if (payload[file_ctrl_idx] != expected_app_file_spec_version) { - // Only version 3 is supported at this time. - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } - - constexpr uint8_t expected_dev_type = 0x00; - if (payload[file_ctrl_idx+1] != expected_dev_type) { - // Only "all" device type is supported. - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } - - constexpr uint8_t expected_start_flag = 0x01; - if (payload[file_ctrl_idx+2] != expected_start_flag) { - // Only "immediate" start type is supported. - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } - - - constexpr uint8_t expected_factory_settings_flag = 0x00; - if (payload[file_ctrl_idx+3] != expected_factory_settings_flag) { - // Factory settings restore before appfile is not supported. - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } - - constexpr uint8_t app_file_records_idx = appfile_header_sz + file_control_info_block_sz; - const uint8_t record_type = payload[app_file_records_idx]; - if (record_type == (uint8_t)Appfile_Record_Type::SERIAL_PORT_BAUD_RATE_FORMAT) { - // Serial port baud/format - // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_SerialPort.html - - // Ignore serial port index (COM Port) since there's only one in SITL. - // Ignore baud rate because you can't change baud yet in SITL. - // Ignore parity because it can't be changed in SITL. - // Ignore flow control because it's not yet in SITL. - } else if (record_type == (uint8_t)Appfile_Record_Type::OUTPUT_MESSAGE){ - // Output Message - // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html - - - // Ignore record length to save flash. - // Ignore port index since SITL is only one port. - if (payload[app_file_records_idx + 2] == (uint8_t)(Output_Msg_Msg_Type::GSOF)) { - const auto gsof_submessage_type = payload[app_file_records_idx + 6]; - const auto rate = payload[app_file_records_idx + 4]; - if (rate == (uint8_t)Output_Rate::OFF) { - channel_rates[gsof_submessage_type] = static_cast(rate); - } else if (rate == (uint8_t)Output_Rate::FREQ_10_HZ) { - channel_rates[gsof_submessage_type] = static_cast(rate); - } else if (rate == (uint8_t)Output_Rate::FREQ_50_HZ) { - channel_rates[gsof_submessage_type] = static_cast(rate); - } else if (rate == (uint8_t)Output_Rate::FREQ_100_HZ) { - channel_rates[gsof_submessage_type] = static_cast(rate); - } else { - // Unsupported GSOF rate in SITL. - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } - } else { - // Only some data output protocols are supported in SITL. - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } - - } else { - // Other application file packets are not yet supported. - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } - - return true; -} - -void DCOL_Parser::reset() { - cur_payload_idx = 0; - expected_payload_length = 0; - parse_state = Parse_State::WAITING_ON_STX; - // To be pedantic, one could zero the bytes in the payload, - // but this is skipped because it's extra CPU. - - // Note - appfile_trans_number is intended to persist over parser resets. -} - - -void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) -{ - // All Trimble "Data Collector" packets, including GSOF, are comprised of three fields: - // * A fixed-length packet header (dcol_header) - // * A variable-length data frame (buf) - // * A fixed-length packet trailer (dcol_trailer) - // Reference: // https://receiverhelp.trimble.com/oem-gnss/index.html#API_DataCollectorFormatPacketStructure.html?TocPath=API%2520Documentation%257CData%2520collector%2520format%2520packets%257CData%2520collector%2520format%253A%2520packet%2520structure%257C_____0 - - // status bitfield - // https://receiverhelp.trimble.com/oem-gnss/index.html#API_ReceiverStatusByte.html?TocPath=API%2520Documentation%257CData%2520collector%2520format%2520packets%257CData%2520collector%2520format%253A%2520packet%2520structure%257C_____1 - const uint8_t STATUS = 0xa8; - const uint8_t PACKET_TYPE = 0x40; // Report Packet 40h (GENOUT) - - // Before writing the GSOF data buffer, the GSOF header needs added between the DCOL header and the payload data frame. - // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_GSOF.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____2 - - static uint8_t TRANSMISSION_NUMBER = 0; // Functionally, this is a sequence number - // Most messages, even GSOF49, only take one page. For SIM, assume it. - assert(size < 0xFA); // GPS SIM doesn't yet support paging - constexpr uint8_t PAGE_INDEX = 0; - constexpr uint8_t MAX_PAGE_INDEX = 0; - const uint8_t gsof_header[3] = { - TRANSMISSION_NUMBER, - PAGE_INDEX, - MAX_PAGE_INDEX, - }; - ++TRANSMISSION_NUMBER; - - // A captured GSOF49 packet from BD940 has LENGTH field set to 0x6d = 109 bytes. - // A captured GSOF49 packet from BD940 has total bytes of 115 bytes. - // Thus, the following 5 bytes are not counted. - // 1) STX - // 2) STATUS - // 3) PACKET TYPE - // 4) LENGTH - // 5) CHECKSUM - // 6) ETX - // This aligns with manual's idea of data bytes: - // "Each message begins with a 4-byte header, followed by the bytes of data in each packet. The packet ends with a 2-byte trailer." - // Thus, for this implementation with single-page single-record per DCOL packet, - // the length is simply the sum of data packet size, the gsof_header size. - const uint8_t length = size + sizeof(gsof_header); - const uint8_t dcol_header[4] { - STX, - STATUS, - PACKET_TYPE, - length - }; - - - // Sum bytes (status + type + length + data bytes) and modulo 256 the summation - // Because it's a uint8, use natural overflow - uint8_t csum = STATUS + PACKET_TYPE + length; - for (size_t i = 0; i < ARRAY_SIZE(gsof_header); i++) { - csum += gsof_header[i]; - } - for (size_t i = 0; i < size; i++) { - csum += buf[i]; - } - - const uint8_t dcol_trailer[2] = { - csum, - ETX - }; - - write_to_autopilot((char*)dcol_header, sizeof(dcol_header)); - write_to_autopilot((char*)gsof_header, sizeof(gsof_header)); - write_to_autopilot((char*)buf, size); - write_to_autopilot((char*)dcol_trailer, sizeof(dcol_trailer)); - const uint8_t total_size = sizeof(dcol_header) + sizeof(gsof_header) + size + sizeof(dcol_trailer); - // Validate length based on everything but DCOL h - if(dcol_header[3] != total_size - (sizeof(dcol_header) + sizeof(dcol_trailer))) { - INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); - } -} - -uint64_t GPS_GSOF::gsof_pack_double(const double& src) -{ - uint64_t dst; - static_assert(sizeof(src) == sizeof(dst)); - memcpy(&dst, &src, sizeof(dst)); - dst = htobe64(dst); - return dst; -} - -uint32_t GPS_GSOF::gsof_pack_float(const float& src) -{ - uint32_t dst; - static_assert(sizeof(src) == sizeof(dst)); - memcpy(&dst, &src, sizeof(dst)); - dst = htobe32(dst); - return dst; -} - -void GPS_GSOF::update_read() { - // Technically, the max command is slightly larger. - // This will only slightly slow the response for packets that big. - char c[MAX_PAYLOAD_SIZE]; - const auto n_read = read_from_autopilot(c, MAX_PAYLOAD_SIZE); - if (n_read > 0) { - for (uint8_t i = 0; i < n_read; i++) { - if (dcol_parse(c[i])) { - constexpr uint8_t response[1] = {(uint8_t)Command_Response::ACK}; - write_to_autopilot((char*)response, sizeof(response)); - } - // TODO handle NACK for failure - } - } -} - -/* - send MSP GPS data - */ -void GPS_MSP::publish(const GPS_Data *d) -{ - struct PACKED { - // header - struct PACKED { - uint8_t dollar = '$'; - uint8_t magic = 'X'; - uint8_t code = '<'; - uint8_t flags; - uint16_t cmd = 0x1F03; // GPS - uint16_t size = 52; - } hdr; - uint8_t instance; - uint16_t gps_week; - uint32_t ms_tow; - uint8_t fix_type; - uint8_t satellites_in_view; - uint16_t horizontal_pos_accuracy; // [cm] - uint16_t vertical_pos_accuracy; // [cm] - uint16_t horizontal_vel_accuracy; // [cm/s] - uint16_t hdop; - int32_t longitude; - int32_t latitude; - int32_t msl_altitude; // cm - int32_t ned_vel_north; // cm/s - int32_t ned_vel_east; - int32_t ned_vel_down; - uint16_t ground_course; // deg * 100, 0..36000 - uint16_t true_yaw; // deg * 100, values of 0..36000 are valid. 65535 = no data available - uint16_t year; - uint8_t month; - uint8_t day; - uint8_t hour; - uint8_t min; - uint8_t sec; - - // footer CRC - uint8_t crc; - } msp_gps {}; - - auto t = gps_time(); - struct timeval tv; - simulation_timeval(&tv); - auto *tm = gmtime(&tv.tv_sec); - - msp_gps.gps_week = t.week; - msp_gps.ms_tow = t.ms; - msp_gps.fix_type = d->have_lock?3:0; - msp_gps.satellites_in_view = d->have_lock ? _sitl->gps_numsats[instance] : 3; - msp_gps.horizontal_pos_accuracy = _sitl->gps_accuracy[instance]*100; - msp_gps.vertical_pos_accuracy = _sitl->gps_accuracy[instance]*100; - msp_gps.horizontal_vel_accuracy = 30; - msp_gps.hdop = 100; - msp_gps.longitude = d->longitude * 1.0e7; - msp_gps.latitude = d->latitude * 1.0e7; - msp_gps.msl_altitude = d->altitude * 100; - msp_gps.ned_vel_north = 100 * d->speedN; - msp_gps.ned_vel_east = 100 * d->speedE; - msp_gps.ned_vel_down = 100 * d->speedD; - msp_gps.ground_course = ToDeg(atan2f(d->speedE, d->speedN)) * 100; - msp_gps.true_yaw = wrap_360(d->yaw_deg)*100U; // can send 65535 for no yaw - msp_gps.year = tm->tm_year; - msp_gps.month = tm->tm_mon; - msp_gps.day = tm->tm_mday; - msp_gps.hour = tm->tm_hour; - msp_gps.min = tm->tm_min; - msp_gps.sec = tm->tm_sec; - - // CRC is over packet without first 3 bytes and trailing CRC byte - msp_gps.crc = crc8_dvb_s2_update(0, (uint8_t *)&msp_gps.hdr.flags, sizeof(msp_gps)-4); - - write_to_autopilot((const char *)&msp_gps, sizeof(msp_gps)); -} - -/* - read file data logged from AP_GPS_DEBUG_LOGGING_ENABLED - */ -#if AP_SIM_GPS_FILE_ENABLED -void GPS_FILE::publish(const GPS_Data *d) -{ - static int fd[2] = {-1,-1}; - static uint32_t base_time[2]; - const uint16_t lognum = uint16_t(_sitl->gps_log_num.get()); - if (instance > 1) { - return; - } - if (fd[instance] == -1) { - char fname[] = "gpsN_NNN.log"; - hal.util->snprintf(fname, 13, "gps%u_%03u.log", instance+1, lognum); - fd[instance] = open(fname, O_RDONLY|O_CLOEXEC); - if (fd[instance] == -1) { - return; - } - } - const uint32_t magic = 0x7fe53b04; - struct { - uint32_t magic; - uint32_t time_ms; - uint32_t n; - } header; - uint8_t *buf = nullptr; - while (true) { - if (::read(fd[instance], (void *)&header, sizeof(header)) != sizeof(header) || - header.magic != magic) { - goto rewind_file; - } - if (header.time_ms+base_time[instance] > AP_HAL::millis()) { - // not ready for this data yet - ::lseek(fd[instance], -sizeof(header), SEEK_CUR); - return; - } - buf = new uint8_t[header.n]; - if (buf != nullptr && ::read(fd[instance], buf, header.n) == ssize_t(header.n)) { - write_to_autopilot((const char *)buf, header.n); - delete[] buf; - buf = nullptr; - continue; - } - goto rewind_file; - } - -rewind_file: - ::printf("GPS[%u] rewind\n", unsigned(instance)); - base_time[instance] = AP_HAL::millis(); - ::lseek(fd[instance], 0, SEEK_SET); - delete[] buf; -} -#endif // AP_SIM_GPS_FILE_ENABLED - void GPS::check_backend_allocation() { const Type configured_type = Type(_sitl->gps_type[instance].get()); @@ -1691,33 +165,47 @@ void GPS::check_backend_allocation() // no GPS attached break; +#if AP_SIM_GPS_UBLOX_ENABLED case Type::UBLOX: backend = new GPS_UBlox(*this, instance); break; +#endif +#if AP_SIM_GPS_NMEA_ENABLED case Type::NMEA: backend = new GPS_NMEA(*this, instance); break; +#endif +#if AP_SIM_GPS_SBP_ENABLED case Type::SBP: backend = new GPS_SBP(*this, instance); break; +#endif +#if AP_SIM_GPS_SBP2_ENABLED case Type::SBP2: backend = new GPS_SBP2(*this, instance); break; +#endif +#if AP_SIM_GPS_NOVA_ENABLED case Type::NOVA: backend = new GPS_NOVA(*this, instance); break; +#endif +#if AP_SIM_GPS_MSP_ENABLED case Type::MSP: backend = new GPS_MSP(*this, instance); break; +#endif +#if AP_SIM_GPS_GSOF_ENABLED case Type::GSOF: backend = new GPS_GSOF(*this, instance); break; +#endif #if AP_SIM_GPS_FILE_ENABLED case Type::FILE: diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index c9f8c34e415480..8e6ccad06b1f13 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -23,19 +23,10 @@ param set SERIAL5_PROTOCOL 5 #pragma once -#include - -#ifndef HAL_SIM_GPS_ENABLED -#define HAL_SIM_GPS_ENABLED AP_SIM_ENABLED -#endif +#include "SIM_config.h" #if HAL_SIM_GPS_ENABLED -#ifndef AP_SIM_GPS_FILE_ENABLED -// really need to use AP_FileSystem for this. -#define AP_SIM_GPS_FILE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX) -#endif - #include "SIM_SerialDevice.h" namespace SITL { @@ -87,237 +78,15 @@ class GPS_Backend { class SIM *_sitl; -}; - -class GPS_FILE : public GPS_Backend { -public: - CLASS_NO_COPY(GPS_FILE); - - using GPS_Backend::GPS_Backend; - - void publish(const GPS_Data *d) override; -}; - -class DCOL_Parser { - // The DCOL parser is used by Trimble GSOF devices. - // It's used for doing configuration. - // https://receiverhelp.trimble.com/oem-gnss/API_DataCollectorFormatPackets.html -public: - // Feed data in to the DCOL parser. - // If the data reaches a parse state that needs to write ACK/NACK back out, - // the function returns true with a populated data_out value. - // Otherwise, it returns false waiting for more data. - bool dcol_parse(const char data_in); - - static constexpr uint8_t STX = 0x02; - static constexpr uint8_t ETX = 0x03; - - // Receiver status code - enum class Status : uint8_t { - OK = 0x00, - }; - - // https://receiverhelp.trimble.com/oem-gnss/API_DataCollectorFormatPackets.html - enum class Command_Response : uint8_t { - ACK = 0x06, - NACK = 0x15, + struct GPS_TOW { + // Number of weeks since midnight 5-6 January 1980 + uint16_t week; + // Time since start of the GPS week [mS] + uint32_t ms; }; - // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Frequenc - enum class Output_Rate : uint8_t { - OFF = 0, - FREQ_10_HZ = 1, - FREQ_50_HZ = 15, - FREQ_100_HZ = 16, - }; - - // https://receiverhelp.trimble.com/oem-gnss/ICD_ApplicationFilePackets.html?tocpath=API%20Documentation%7CCommand%20and%20report%20packets%7CApplication%20file%20packets%7C_____0 - enum class Packet_Type : uint8_t { - COMMAND_APPFILE = 0x64, - }; - - // https://receiverhelp.trimble.com/oem-gnss/ICD_Pkt_Command64h_APPFILE.html - enum class Appfile_Record_Type : uint8_t { - SERIAL_PORT_BAUD_RATE_FORMAT = 0x02, - OUTPUT_MESSAGE = 0x07, - }; - - // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Output - enum class Output_Msg_Msg_Type : uint8_t { - GSOF = 10, - }; - - // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Output2 - enum class Gsof_Msg_Record_Type : uint8_t { - POSITION_TIME = 1, - LLH = 2, - VELOCITY_DATA = 8, - PDOP_INFO = 9, - POSITION_SIGMA_INFO = 12, - }; - -protected: - // https://receiverhelp.trimble.com/oem-gnss/API_DataCollectorFormatPacketStructure.html - static constexpr uint8_t MAX_PAYLOAD_SIZE = 255; - - // GSOF supports this many different packet types. - // Only a fraction are supported by the simulator. - // Waste some RAM and allocate arrays for the whole set. - // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Output2 - static constexpr uint8_t MAX_CHANNEL_NUM = 70; - // Rates of dynamically enabled channels. - // Assume factory behavior of no enabled channels. - // Each channel can send data out at its own rate. - Output_Rate channel_rates[MAX_CHANNEL_NUM] = {Output_Rate::OFF}; - - // Last publish time of dynamically enabled channels. - uint32_t last_publish_ms[MAX_CHANNEL_NUM]; - - static uint32_t RateToPeriodMs(const Output_Rate rate); - -private: - - // Internal parser implementation state - enum class Parse_State { - WAITING_ON_STX, - WAITING_ON_STATUS, - WAITING_ON_PACKET_TYPE, - WAITING_ON_LENGTH, - WAITING_ON_PACKET_DATA, - WAITING_ON_CSUM, - WAITING_ON_ETX, - }; - - bool valid_csum(); - bool parse_payload(); - // https://receiverhelp.trimble.com/oem-gnss/ICD_Pkt_Command64h_APPFILE.html - bool parse_cmd_appfile(); - - - // states for currently parsing packet - Status status; - Parse_State parse_state = {Parse_State::WAITING_ON_STX}; - Packet_Type packet_type; - // This is the length in the header. - uint8_t expected_payload_length; - // This is the increasing tally of bytes per packet. - uint8_t cur_payload_idx; - // This is the expected packet checksum in the trailer. - uint8_t expected_csum; - - // The application file record transmission number - uint8_t appfile_trans_num; - - uint8_t payload[MAX_PAYLOAD_SIZE]; - - // Clear all parser state/flags for handling a fresh packet. - void reset(); -}; - -class GPS_GSOF : public GPS_Backend, public DCOL_Parser { -public: - CLASS_NO_COPY(GPS_GSOF); - - using GPS_Backend::GPS_Backend; - - - // GPS_Backend overrides - void publish(const GPS_Data *d) override; - void update_read() override; - -private: - void send_gsof(const uint8_t *buf, const uint16_t size); - - // These packing utilities for GSOF perform a type-safe floating point byteswap. - // They return integer types because returning floating points would involve an extra copy. - uint64_t gsof_pack_double(const double& src) WARN_IF_UNUSED; - uint32_t gsof_pack_float(const float& src) WARN_IF_UNUSED; -}; - -class GPS_NMEA : public GPS_Backend { -public: - CLASS_NO_COPY(GPS_NMEA); - - using GPS_Backend::GPS_Backend; - - void publish(const GPS_Data *d) override; - -private: - - uint8_t nmea_checksum(const char *s); - void nmea_printf(const char *fmt, ...); - void update_nmea(const GPS_Data *d); - -}; - -class GPS_NOVA : public GPS_Backend { -public: - CLASS_NO_COPY(GPS_NOVA); - - using GPS_Backend::GPS_Backend; - - void publish(const GPS_Data *d) override; - - uint32_t device_baud() const override { return 19200; } - -private: - - void nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen); - uint32_t CRC32Value(uint32_t icrc); - uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc); -}; - -class GPS_MSP : public GPS_Backend { -public: - CLASS_NO_COPY(GPS_MSP); - - using GPS_Backend::GPS_Backend; - - void publish(const GPS_Data *d) override; -}; - -class GPS_SBP_Common : public GPS_Backend { -public: - CLASS_NO_COPY(GPS_SBP_Common); - - using GPS_Backend::GPS_Backend; - -protected: - - void sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload); - -}; - -class GPS_SBP : public GPS_SBP_Common { -public: - CLASS_NO_COPY(GPS_SBP); - - using GPS_SBP_Common::GPS_SBP_Common; - - void publish(const GPS_Data *d) override; - -}; - -class GPS_SBP2 : public GPS_SBP_Common { -public: - CLASS_NO_COPY(GPS_SBP2); - - using GPS_SBP_Common::GPS_SBP_Common; - - void publish(const GPS_Data *d) override; - -}; - -class GPS_UBlox : public GPS_Backend { -public: - CLASS_NO_COPY(GPS_UBlox); - - using GPS_Backend::GPS_Backend; - - void publish(const GPS_Data *d) override; - -private: - void send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size); + static GPS_TOW gps_time(); + static void simulation_timeval(struct timeval *tv); }; class GPS : public SerialDevice { @@ -327,16 +96,30 @@ class GPS : public SerialDevice { enum Type { NONE = 0, +#if AP_SIM_GPS_UBLOX_ENABLED UBLOX = 1, +#endif +#if AP_SIM_GPS_NMEA_ENABLED NMEA = 5, +#endif +#if AP_SIM_GPS_SBP_ENABLED SBP = 6, +#endif #if AP_SIM_GPS_FILE_ENABLED FILE = 7, #endif +#if AP_SIM_GPS_NOVA_ENABLED NOVA = 8, +#endif +#if AP_SIM_GPS_SBP2_ENABLED SBP2 = 9, +#endif +#if AP_SIM_GPS_GSOF_ENABLED GSOF = 11, // matches GPS_TYPE +#endif +#if AP_SIM_GPS_MSP_ENABLED MSP = 19, +#endif }; GPS(uint8_t _instance); @@ -352,8 +135,6 @@ class GPS : public SerialDevice { uint8_t instance; - int ext_fifo_fd; - // The last time GPS data was written [mS] uint32_t last_write_update_ms; diff --git a/libraries/SITL/SIM_GPS_FILE.cpp b/libraries/SITL/SIM_GPS_FILE.cpp new file mode 100644 index 00000000000000..e4c096f1eba7c8 --- /dev/null +++ b/libraries/SITL/SIM_GPS_FILE.cpp @@ -0,0 +1,67 @@ +#include "SIM_config.h" + +#if AP_SIM_GPS_FILE_ENABLED + +#include "SIM_GPS_FILE.h" + +#include +#include + +extern const AP_HAL::HAL& hal; + +using namespace SITL; + +/* + read file data logged from AP_GPS_DEBUG_LOGGING_ENABLED + */ +void GPS_FILE::publish(const GPS_Data *d) +{ + static int fd[2] = {-1,-1}; + static uint32_t base_time[2]; + const uint16_t lognum = uint16_t(_sitl->gps_log_num.get()); + if (instance > 1) { + return; + } + if (fd[instance] == -1) { + char fname[] = "gpsN_NNN.log"; + hal.util->snprintf(fname, 13, "gps%u_%03u.log", instance+1, lognum); + fd[instance] = open(fname, O_RDONLY|O_CLOEXEC); + if (fd[instance] == -1) { + return; + } + } + const uint32_t magic = 0x7fe53b04; + struct { + uint32_t magic; + uint32_t time_ms; + uint32_t n; + } header; + uint8_t *buf = nullptr; + while (true) { + if (::read(fd[instance], (void *)&header, sizeof(header)) != sizeof(header) || + header.magic != magic) { + goto rewind_file; + } + if (header.time_ms+base_time[instance] > AP_HAL::millis()) { + // not ready for this data yet + ::lseek(fd[instance], -sizeof(header), SEEK_CUR); + return; + } + buf = new uint8_t[header.n]; + if (buf != nullptr && ::read(fd[instance], buf, header.n) == ssize_t(header.n)) { + write_to_autopilot((const char *)buf, header.n); + delete[] buf; + buf = nullptr; + continue; + } + goto rewind_file; + } + +rewind_file: + ::printf("GPS[%u] rewind\n", unsigned(instance)); + base_time[instance] = AP_HAL::millis(); + ::lseek(fd[instance], 0, SEEK_SET); + delete[] buf; +} + +#endif // AP_SIM_GPS_FILE_ENABLED diff --git a/libraries/SITL/SIM_GPS_FILE.h b/libraries/SITL/SIM_GPS_FILE.h new file mode 100644 index 00000000000000..980f9602adfc94 --- /dev/null +++ b/libraries/SITL/SIM_GPS_FILE.h @@ -0,0 +1,20 @@ +#include "SIM_config.h" + +#if AP_SIM_GPS_FILE_ENABLED + +#include "SIM_GPS.h" + +namespace SITL { + +class GPS_FILE : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_FILE); + + using GPS_Backend::GPS_Backend; + + void publish(const GPS_Data *d) override; +}; + +}; + +#endif // AP_SIM_GPS_FILE_ENABLED diff --git a/libraries/SITL/SIM_GPS_GSOF.cpp b/libraries/SITL/SIM_GPS_GSOF.cpp new file mode 100644 index 00000000000000..477ef5a87a62da --- /dev/null +++ b/libraries/SITL/SIM_GPS_GSOF.cpp @@ -0,0 +1,569 @@ +#include "SIM_config.h" + +#if AP_SIM_GPS_GSOF_ENABLED + +#include "SIM_GPS_GSOF.h" + +#include +#include + +#include + +using namespace SITL; + +void GPS_GSOF::publish(const GPS_Data *d) +{ + // This logic is to populate output buffer only with enabled channels. + // It also only sends each channel at the configured rate. + const uint64_t now = AP_HAL::millis(); + uint8_t buf[MAX_PAYLOAD_SIZE] = {}; + uint8_t payload_sz = 0; + uint8_t offset = 0; + if (channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_TIME)] != Output_Rate::OFF){ + const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::POSITION_TIME)]; + const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_TIME)]; + + if (now - last_time > RateToPeriodMs(desired_rate)) { + + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_TIME.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____25 + constexpr uint8_t GSOF_POS_TIME_LEN { 0x0A }; + // TODO magic number until SITL supports GPS bootcount based on GPSN_ENABLE + const uint8_t bootcount = 17; + + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%201 + enum class POS_FLAGS_1 : uint8_t { + NEW_POSITION = 1U << 0, + CLOCK_FIX_CALULATED = 1U << 1, + HORIZ_FROM_THIS_POS = 1U << 2, + HEIGHT_FROM_THIS_POS = 1U << 3, + RESERVED_4 = 1U << 4, + LEAST_SQ_POSITION = 1U << 5, + RESERVED_6 = 1U << 6, + POSITION_L1_PSEUDORANGES = 1U << 7 + }; + const uint8_t pos_flags_1 { + uint8_t(POS_FLAGS_1::NEW_POSITION) | + uint8_t(POS_FLAGS_1::CLOCK_FIX_CALULATED) | + uint8_t(POS_FLAGS_1::HORIZ_FROM_THIS_POS) | + uint8_t(POS_FLAGS_1::HEIGHT_FROM_THIS_POS) | + uint8_t(POS_FLAGS_1::RESERVED_4) | + uint8_t(POS_FLAGS_1::LEAST_SQ_POSITION) | + uint8_t(POS_FLAGS_1::POSITION_L1_PSEUDORANGES) + }; + + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%202 + enum class POS_FLAGS_2 : uint8_t { + DIFFERENTIAL_POS = 1U << 0, + DIFFERENTIAL_POS_PHASE_RTK = 1U << 1, + POSITION_METHOD_FIXED_PHASE = 1U << 2, + OMNISTAR_ACTIVE = 1U << 3, + DETERMINED_WITH_STATIC_CONSTRAINT = 1U << 4, + NETWORK_RTK = 1U << 5, + DITHERED_RTK = 1U << 6, + BEACON_DGNSS = 1U << 7, + }; + + // Simulate a GPS without RTK in SIM since there is no RTK SIM params. + // This means these flags are unset: + // NETWORK_RTK, DITHERED_RTK, BEACON_DGNSS + uint8_t pos_flags_2 {0}; + if(d->have_lock) { + pos_flags_2 |= uint8_t(POS_FLAGS_2::DIFFERENTIAL_POS); + pos_flags_2 |= uint8_t(POS_FLAGS_2::DIFFERENTIAL_POS_PHASE_RTK); + pos_flags_2 |= uint8_t(POS_FLAGS_2::POSITION_METHOD_FIXED_PHASE); + pos_flags_2 |= uint8_t(POS_FLAGS_2::OMNISTAR_ACTIVE); + pos_flags_2 |= uint8_t(POS_FLAGS_2::DETERMINED_WITH_STATIC_CONSTRAINT); + } + + const auto gps_tow = gps_time(); + const struct PACKED gsof_pos_time { + const uint8_t OUTPUT_RECORD_TYPE; + const uint8_t RECORD_LEN; + uint32_t time_week_ms; + uint16_t time_week; + uint8_t num_sats; + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%201 + uint8_t pos_flags_1; + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Position%20flags%202 + uint8_t pos_flags_2; + uint8_t initialized_num; + } pos_time { + uint8_t(Gsof_Msg_Record_Type::POSITION_TIME), + GSOF_POS_TIME_LEN, + htobe32(gps_tow.ms), + htobe16(gps_tow.week), + d->have_lock ? _sitl->gps_numsats[instance] : uint8_t(3), + pos_flags_1, + pos_flags_2, + bootcount + }; + static_assert(sizeof(gsof_pos_time) - (sizeof(gsof_pos_time::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_time::RECORD_LEN)) == GSOF_POS_TIME_LEN); + + payload_sz += sizeof(pos_time); + memcpy(&buf[offset], &pos_time, sizeof(pos_time)); + offset += sizeof(pos_time); + } + } + + if (channel_rates[uint8_t(Gsof_Msg_Record_Type::LLH)] != Output_Rate::OFF){ + const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::LLH)]; + const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::LLH)]; + + if (now - last_time > RateToPeriodMs(desired_rate)) { + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_LLH.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____20 + constexpr uint8_t GSOF_POS_LEN = 0x18; + + const struct PACKED gsof_pos { + const uint8_t OUTPUT_RECORD_TYPE; + const uint8_t RECORD_LEN; + uint64_t lat; + uint64_t lng; + uint64_t alt; + } pos { + uint8_t(Gsof_Msg_Record_Type::LLH), + GSOF_POS_LEN, + gsof_pack_double(d->latitude * DEG_TO_RAD_DOUBLE), + gsof_pack_double(d->longitude * DEG_TO_RAD_DOUBLE), + gsof_pack_double(static_cast(d->altitude)) + }; + static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN); + + payload_sz += sizeof(pos); + memcpy(&buf[offset], &pos, sizeof(pos)); + offset += sizeof(pos); + } + } + + if (channel_rates[uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA)] != Output_Rate::OFF){ + const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA)]; + const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA)]; + + if (now - last_time > RateToPeriodMs(desired_rate)) { + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Velocity.html + // use the smaller packet by ignoring local coordinate system + constexpr uint8_t GSOF_VEL_LEN = 0x0D; + + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags + enum class VEL_FIELDS : uint8_t { + VALID = 1U << 0, + CONSECUTIVE_MEASUREMENTS = 1U << 1, + HEADING_VALID = 1U << 2, + RESERVED_3 = 1U << 3, + RESERVED_4 = 1U << 4, + RESERVED_5 = 1U << 5, + RESERVED_6 = 1U << 6, + RESERVED_7 = 1U << 7, + }; + uint8_t vel_flags {0}; + if(d->have_lock) { + vel_flags |= uint8_t(VEL_FIELDS::VALID); + vel_flags |= uint8_t(VEL_FIELDS::CONSECUTIVE_MEASUREMENTS); + vel_flags |= uint8_t(VEL_FIELDS::HEADING_VALID); + } + + const struct PACKED gsof_vel { + const uint8_t OUTPUT_RECORD_TYPE; + const uint8_t RECORD_LEN; + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags + uint8_t flags; + uint32_t horiz_m_p_s; + uint32_t heading_rad; + uint32_t vertical_m_p_s; + } vel { + uint8_t(Gsof_Msg_Record_Type::VELOCITY_DATA), + GSOF_VEL_LEN, + vel_flags, + gsof_pack_float(d->speed_2d()), + gsof_pack_float(d->heading()), + // Trimble API has ambiguous direction here. + // Intentionally narrow from double. + gsof_pack_float(static_cast(d->speedD)) + }; + static_assert(sizeof(gsof_vel) - (sizeof(gsof_vel::OUTPUT_RECORD_TYPE) + sizeof(gsof_vel::RECORD_LEN)) == GSOF_VEL_LEN); + + payload_sz += sizeof(vel); + memcpy(&buf[offset], &vel, sizeof(vel)); + offset += sizeof(vel); + } + } + if (channel_rates[uint8_t(Gsof_Msg_Record_Type::PDOP_INFO)] != Output_Rate::OFF){ + const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::PDOP_INFO)]; + const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::PDOP_INFO)]; + + if (now - last_time > RateToPeriodMs(desired_rate)) { + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_PDOP.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____12 + constexpr uint8_t GSOF_DOP_LEN = 0x10; + const struct PACKED gsof_dop { + const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::PDOP_INFO) }; + const uint8_t RECORD_LEN { GSOF_DOP_LEN }; + uint32_t pdop = htobe32(1); + uint32_t hdop = htobe32(1); + uint32_t vdop = htobe32(1); + uint32_t tdop = htobe32(1); + } dop {}; + // Check the payload size calculation in the compiler + constexpr auto dop_size = sizeof(gsof_dop); + static_assert(dop_size == 18); + constexpr auto dop_record_type_size = sizeof(gsof_dop::OUTPUT_RECORD_TYPE); + static_assert(dop_record_type_size == 1); + constexpr auto len_size = sizeof(gsof_dop::RECORD_LEN); + static_assert(len_size == 1); + constexpr auto dop_payload_size = dop_size - (dop_record_type_size + len_size); + static_assert(dop_payload_size == GSOF_DOP_LEN); + + payload_sz += sizeof(dop); + memcpy(&buf[offset], &dop, sizeof(dop)); + offset += sizeof(dop); + } + } + if (channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO)] != Output_Rate::OFF){ + const auto last_time = last_publish_ms[uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO)]; + const auto desired_rate = channel_rates[uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO)]; + if (now - last_time > RateToPeriodMs(desired_rate)) { + // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_SIGMA.html + constexpr uint8_t GSOF_POS_SIGMA_LEN = 0x26; + const struct PACKED gsof_pos_sigma { + const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO) }; + const uint8_t RECORD_LEN { GSOF_POS_SIGMA_LEN }; + uint32_t pos_rms = htobe32(0); + uint32_t sigma_e = htobe32(0); + uint32_t sigma_n = htobe32(0); + uint32_t cov_en = htobe32(0); + uint32_t sigma_up = htobe32(0); + uint32_t semi_major_axis = htobe32(0); + uint32_t semi_minor_axis = htobe32(0); + uint32_t orientation = htobe32(0); + uint32_t unit_variance = htobe32(0); + uint16_t n_epocs = htobe32(1); // Always 1 for kinematic. + } pos_sigma {}; + static_assert(sizeof(gsof_pos_sigma) - (sizeof(gsof_pos_sigma::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_sigma::RECORD_LEN)) == GSOF_POS_SIGMA_LEN); + payload_sz += sizeof(pos_sigma); + memcpy(&buf[offset], &pos_sigma, sizeof(pos_sigma)); + offset += sizeof(pos_sigma); + } + } + + assert(offset == payload_sz); + + // Don't send empy frames when all channels are disabled; + if (payload_sz > 0) { + send_gsof(buf, payload_sz); + } + +} + +bool DCOL_Parser::dcol_parse(const char data_in) { + bool ret = false; + switch (parse_state) { + case Parse_State::WAITING_ON_STX: + if (data_in == STX) { + reset(); + parse_state = Parse_State::WAITING_ON_STATUS; + } + break; + case Parse_State::WAITING_ON_STATUS: + if (data_in != (uint8_t)Status::OK) { + // Invalid, status should always be OK. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } else { + status = static_cast(data_in); + parse_state = Parse_State::WAITING_ON_PACKET_TYPE; + } + break; + case Parse_State::WAITING_ON_PACKET_TYPE: + if (data_in == (uint8_t)Packet_Type::COMMAND_APPFILE) { + packet_type = Packet_Type::COMMAND_APPFILE; + } else { + // Unsupported command in this simulator. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + parse_state = Parse_State::WAITING_ON_LENGTH; + break; + case Parse_State::WAITING_ON_LENGTH: + expected_payload_length = data_in; + parse_state = Parse_State::WAITING_ON_PACKET_DATA; + break; + case Parse_State::WAITING_ON_PACKET_DATA: + payload[cur_payload_idx] = data_in; + if (++cur_payload_idx == expected_payload_length) { + parse_state = Parse_State::WAITING_ON_CSUM; + } + break; + case Parse_State::WAITING_ON_CSUM: + expected_csum = data_in; + parse_state = Parse_State::WAITING_ON_ETX; + break; + case Parse_State::WAITING_ON_ETX: + if (data_in != ETX) { + reset(); + } + if (!valid_csum()) { + // GSOF driver sent a packet with invalid CSUM. + // In real GSOF driver, the packet is simply ignored with no reply. + // In the SIM, treat this as a coding error. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } else { + ret = parse_payload(); + } + reset(); + break; + } + + return ret; +} + +uint32_t DCOL_Parser::RateToPeriodMs(const Output_Rate rate) { + uint32_t min_period_ms = 0; + switch (rate) { + case Output_Rate::OFF: + min_period_ms = 0; + break; + case Output_Rate::FREQ_10_HZ: + min_period_ms = 100; + break; + case Output_Rate::FREQ_50_HZ: + min_period_ms = 20; + break; + case Output_Rate::FREQ_100_HZ: + min_period_ms = 10; + break; + } + return min_period_ms; +} + + +bool DCOL_Parser::valid_csum() { + uint8_t sum = (uint8_t)status; + sum += (uint8_t)packet_type; + sum += expected_payload_length; + sum += crc_sum_of_bytes(payload, expected_payload_length); + return sum == expected_csum; +} + +bool DCOL_Parser::parse_payload() { + bool success = false; + if (packet_type == Packet_Type::COMMAND_APPFILE) { + success = parse_cmd_appfile(); + } + + return success; +} + +bool DCOL_Parser::parse_cmd_appfile() { + // A file control info block contains: + // * version + // * device type + // * start application file flag + // * factory settings flag + constexpr uint8_t file_control_info_block_sz = 4; + // An appfile header contains: + // * transmisison number + // * page index + // * max page index + constexpr uint8_t appfile_header_sz = 3; + constexpr uint8_t min_cmd_appfile_sz = file_control_info_block_sz + appfile_header_sz; + if (expected_payload_length < min_cmd_appfile_sz) { + return false; + } + + // For now, ignore appfile_trans_num, return success regardless. + // If the driver doesn't send the right value, it's not clear what the behavior is supposed to be. + // Also would need to handle re-sync. + // For now, just store it for debugging. + appfile_trans_num = payload[0]; + + // File control information block parsing: + // https://receiverhelp.trimble.com/oem-gnss/ICD_Subtype_Command64h_FileControlInfo.html + constexpr uint8_t expected_app_file_spec_version = 0x03; + constexpr uint8_t file_ctrl_idx = appfile_header_sz; + if (payload[file_ctrl_idx] != expected_app_file_spec_version) { + // Only version 3 is supported at this time. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + constexpr uint8_t expected_dev_type = 0x00; + if (payload[file_ctrl_idx+1] != expected_dev_type) { + // Only "all" device type is supported. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + constexpr uint8_t expected_start_flag = 0x01; + if (payload[file_ctrl_idx+2] != expected_start_flag) { + // Only "immediate" start type is supported. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + + constexpr uint8_t expected_factory_settings_flag = 0x00; + if (payload[file_ctrl_idx+3] != expected_factory_settings_flag) { + // Factory settings restore before appfile is not supported. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + constexpr uint8_t app_file_records_idx = appfile_header_sz + file_control_info_block_sz; + const uint8_t record_type = payload[app_file_records_idx]; + if (record_type == (uint8_t)Appfile_Record_Type::SERIAL_PORT_BAUD_RATE_FORMAT) { + // Serial port baud/format + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_SerialPort.html + + // Ignore serial port index (COM Port) since there's only one in SITL. + // Ignore baud rate because you can't change baud yet in SITL. + // Ignore parity because it can't be changed in SITL. + // Ignore flow control because it's not yet in SITL. + } else if (record_type == (uint8_t)Appfile_Record_Type::OUTPUT_MESSAGE){ + // Output Message + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html + + + // Ignore record length to save flash. + // Ignore port index since SITL is only one port. + if (payload[app_file_records_idx + 2] == (uint8_t)(Output_Msg_Msg_Type::GSOF)) { + const auto gsof_submessage_type = payload[app_file_records_idx + 6]; + const auto rate = payload[app_file_records_idx + 4]; + if (rate == (uint8_t)Output_Rate::OFF) { + channel_rates[gsof_submessage_type] = static_cast(rate); + } else if (rate == (uint8_t)Output_Rate::FREQ_10_HZ) { + channel_rates[gsof_submessage_type] = static_cast(rate); + } else if (rate == (uint8_t)Output_Rate::FREQ_50_HZ) { + channel_rates[gsof_submessage_type] = static_cast(rate); + } else if (rate == (uint8_t)Output_Rate::FREQ_100_HZ) { + channel_rates[gsof_submessage_type] = static_cast(rate); + } else { + // Unsupported GSOF rate in SITL. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + } else { + // Only some data output protocols are supported in SITL. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + } else { + // Other application file packets are not yet supported. + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } + + return true; +} + +void DCOL_Parser::reset() { + cur_payload_idx = 0; + expected_payload_length = 0; + parse_state = Parse_State::WAITING_ON_STX; + // To be pedantic, one could zero the bytes in the payload, + // but this is skipped because it's extra CPU. + + // Note - appfile_trans_number is intended to persist over parser resets. +} + + +void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) +{ + // All Trimble "Data Collector" packets, including GSOF, are comprised of three fields: + // * A fixed-length packet header (dcol_header) + // * A variable-length data frame (buf) + // * A fixed-length packet trailer (dcol_trailer) + // Reference: // https://receiverhelp.trimble.com/oem-gnss/index.html#API_DataCollectorFormatPacketStructure.html?TocPath=API%2520Documentation%257CData%2520collector%2520format%2520packets%257CData%2520collector%2520format%253A%2520packet%2520structure%257C_____0 + + // status bitfield + // https://receiverhelp.trimble.com/oem-gnss/index.html#API_ReceiverStatusByte.html?TocPath=API%2520Documentation%257CData%2520collector%2520format%2520packets%257CData%2520collector%2520format%253A%2520packet%2520structure%257C_____1 + const uint8_t STATUS = 0xa8; + const uint8_t PACKET_TYPE = 0x40; // Report Packet 40h (GENOUT) + + // Before writing the GSOF data buffer, the GSOF header needs added between the DCOL header and the payload data frame. + // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_GSOF.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____2 + + static uint8_t TRANSMISSION_NUMBER = 0; // Functionally, this is a sequence number + // Most messages, even GSOF49, only take one page. For SIM, assume it. + assert(size < 0xFA); // GPS SIM doesn't yet support paging + constexpr uint8_t PAGE_INDEX = 0; + constexpr uint8_t MAX_PAGE_INDEX = 0; + const uint8_t gsof_header[3] = { + TRANSMISSION_NUMBER, + PAGE_INDEX, + MAX_PAGE_INDEX, + }; + ++TRANSMISSION_NUMBER; + + // A captured GSOF49 packet from BD940 has LENGTH field set to 0x6d = 109 bytes. + // A captured GSOF49 packet from BD940 has total bytes of 115 bytes. + // Thus, the following 5 bytes are not counted. + // 1) STX + // 2) STATUS + // 3) PACKET TYPE + // 4) LENGTH + // 5) CHECKSUM + // 6) ETX + // This aligns with manual's idea of data bytes: + // "Each message begins with a 4-byte header, followed by the bytes of data in each packet. The packet ends with a 2-byte trailer." + // Thus, for this implementation with single-page single-record per DCOL packet, + // the length is simply the sum of data packet size, the gsof_header size. + const uint8_t length = size + sizeof(gsof_header); + const uint8_t dcol_header[4] { + STX, + STATUS, + PACKET_TYPE, + length + }; + + + // Sum bytes (status + type + length + data bytes) and modulo 256 the summation + // Because it's a uint8, use natural overflow + uint8_t csum = STATUS + PACKET_TYPE + length; + for (size_t i = 0; i < ARRAY_SIZE(gsof_header); i++) { + csum += gsof_header[i]; + } + for (size_t i = 0; i < size; i++) { + csum += buf[i]; + } + + const uint8_t dcol_trailer[2] = { + csum, + ETX + }; + + write_to_autopilot((char*)dcol_header, sizeof(dcol_header)); + write_to_autopilot((char*)gsof_header, sizeof(gsof_header)); + write_to_autopilot((char*)buf, size); + write_to_autopilot((char*)dcol_trailer, sizeof(dcol_trailer)); + const uint8_t total_size = sizeof(dcol_header) + sizeof(gsof_header) + size + sizeof(dcol_trailer); + // Validate length based on everything but DCOL h + if(dcol_header[3] != total_size - (sizeof(dcol_header) + sizeof(dcol_trailer))) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + } +} + +uint64_t GPS_GSOF::gsof_pack_double(const double& src) +{ + uint64_t dst; + static_assert(sizeof(src) == sizeof(dst)); + memcpy(&dst, &src, sizeof(dst)); + dst = htobe64(dst); + return dst; +} + +uint32_t GPS_GSOF::gsof_pack_float(const float& src) +{ + uint32_t dst; + static_assert(sizeof(src) == sizeof(dst)); + memcpy(&dst, &src, sizeof(dst)); + dst = htobe32(dst); + return dst; +} + +void GPS_GSOF::update_read() { + // Technically, the max command is slightly larger. + // This will only slightly slow the response for packets that big. + char c[MAX_PAYLOAD_SIZE]; + const auto n_read = read_from_autopilot(c, MAX_PAYLOAD_SIZE); + if (n_read > 0) { + for (uint8_t i = 0; i < n_read; i++) { + if (dcol_parse(c[i])) { + constexpr uint8_t response[1] = {(uint8_t)Command_Response::ACK}; + write_to_autopilot((char*)response, sizeof(response)); + } + // TODO handle NACK for failure + } + } +} + +#endif // AP_SIM_GPS_GSOF_ENABLED diff --git a/libraries/SITL/SIM_GPS_GSOF.h b/libraries/SITL/SIM_GPS_GSOF.h new file mode 100644 index 00000000000000..17807815377a31 --- /dev/null +++ b/libraries/SITL/SIM_GPS_GSOF.h @@ -0,0 +1,149 @@ +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_GPS_GSOF_ENABLED + +#include "SIM_GPS.h" + +namespace SITL { + +class DCOL_Parser { + // The DCOL parser is used by Trimble GSOF devices. + // It's used for doing configuration. + // https://receiverhelp.trimble.com/oem-gnss/API_DataCollectorFormatPackets.html +public: + // Feed data in to the DCOL parser. + // If the data reaches a parse state that needs to write ACK/NACK back out, + // the function returns true with a populated data_out value. + // Otherwise, it returns false waiting for more data. + bool dcol_parse(const char data_in); + + static constexpr uint8_t STX = 0x02; + static constexpr uint8_t ETX = 0x03; + + // Receiver status code + enum class Status : uint8_t { + OK = 0x00, + }; + + // https://receiverhelp.trimble.com/oem-gnss/API_DataCollectorFormatPackets.html + enum class Command_Response : uint8_t { + ACK = 0x06, + NACK = 0x15, + }; + + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Frequenc + enum class Output_Rate : uint8_t { + OFF = 0, + FREQ_10_HZ = 1, + FREQ_50_HZ = 15, + FREQ_100_HZ = 16, + }; + + // https://receiverhelp.trimble.com/oem-gnss/ICD_ApplicationFilePackets.html?tocpath=API%20Documentation%7CCommand%20and%20report%20packets%7CApplication%20file%20packets%7C_____0 + enum class Packet_Type : uint8_t { + COMMAND_APPFILE = 0x64, + }; + + // https://receiverhelp.trimble.com/oem-gnss/ICD_Pkt_Command64h_APPFILE.html + enum class Appfile_Record_Type : uint8_t { + SERIAL_PORT_BAUD_RATE_FORMAT = 0x02, + OUTPUT_MESSAGE = 0x07, + }; + + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Output + enum class Output_Msg_Msg_Type : uint8_t { + GSOF = 10, + }; + + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Output2 + enum class Gsof_Msg_Record_Type : uint8_t { + POSITION_TIME = 1, + LLH = 2, + VELOCITY_DATA = 8, + PDOP_INFO = 9, + POSITION_SIGMA_INFO = 12, + }; + +protected: + // https://receiverhelp.trimble.com/oem-gnss/API_DataCollectorFormatPacketStructure.html + static constexpr uint8_t MAX_PAYLOAD_SIZE = 255; + + // GSOF supports this many different packet types. + // Only a fraction are supported by the simulator. + // Waste some RAM and allocate arrays for the whole set. + // https://receiverhelp.trimble.com/oem-gnss/ICD_Command64h_AppFile_Output.html#Output2 + static constexpr uint8_t MAX_CHANNEL_NUM = 70; + // Rates of dynamically enabled channels. + // Assume factory behavior of no enabled channels. + // Each channel can send data out at its own rate. + Output_Rate channel_rates[MAX_CHANNEL_NUM] = {Output_Rate::OFF}; + + // Last publish time of dynamically enabled channels. + uint32_t last_publish_ms[MAX_CHANNEL_NUM]; + + static uint32_t RateToPeriodMs(const Output_Rate rate); + +private: + + // Internal parser implementation state + enum class Parse_State { + WAITING_ON_STX, + WAITING_ON_STATUS, + WAITING_ON_PACKET_TYPE, + WAITING_ON_LENGTH, + WAITING_ON_PACKET_DATA, + WAITING_ON_CSUM, + WAITING_ON_ETX, + }; + + bool valid_csum(); + bool parse_payload(); + // https://receiverhelp.trimble.com/oem-gnss/ICD_Pkt_Command64h_APPFILE.html + bool parse_cmd_appfile(); + + + // states for currently parsing packet + Status status; + Parse_State parse_state = {Parse_State::WAITING_ON_STX}; + Packet_Type packet_type; + // This is the length in the header. + uint8_t expected_payload_length; + // This is the increasing tally of bytes per packet. + uint8_t cur_payload_idx; + // This is the expected packet checksum in the trailer. + uint8_t expected_csum; + + // The application file record transmission number + uint8_t appfile_trans_num; + + uint8_t payload[MAX_PAYLOAD_SIZE]; + + // Clear all parser state/flags for handling a fresh packet. + void reset(); +}; + +class GPS_GSOF : public GPS_Backend, public DCOL_Parser { +public: + CLASS_NO_COPY(GPS_GSOF); + + using GPS_Backend::GPS_Backend; + + + // GPS_Backend overrides + void publish(const GPS_Data *d) override; + void update_read() override; + +private: + void send_gsof(const uint8_t *buf, const uint16_t size); + + // These packing utilities for GSOF perform a type-safe floating point byteswap. + // They return integer types because returning floating points would involve an extra copy. + uint64_t gsof_pack_double(const double& src) WARN_IF_UNUSED; + uint32_t gsof_pack_float(const float& src) WARN_IF_UNUSED; +}; + +}; + +#endif // AP_SIM_GPS_GSOF_ENABLED diff --git a/libraries/SITL/SIM_GPS_MSP.cpp b/libraries/SITL/SIM_GPS_MSP.cpp new file mode 100644 index 00000000000000..1751b5bdbd78f4 --- /dev/null +++ b/libraries/SITL/SIM_GPS_MSP.cpp @@ -0,0 +1,88 @@ +#include "SIM_config.h" + +#if AP_SIM_GPS_MSP_ENABLED + +#include "SIM_GPS_MSP.h" + +#include + +using namespace SITL; + +/* + send MSP GPS data + */ +void GPS_MSP::publish(const GPS_Data *d) +{ + struct PACKED { + // header + struct PACKED { + uint8_t dollar = '$'; + uint8_t magic = 'X'; + uint8_t code = '<'; + uint8_t flags; + uint16_t cmd = 0x1F03; // GPS + uint16_t size = 52; + } hdr; + uint8_t instance; + uint16_t gps_week; + uint32_t ms_tow; + uint8_t fix_type; + uint8_t satellites_in_view; + uint16_t horizontal_pos_accuracy; // [cm] + uint16_t vertical_pos_accuracy; // [cm] + uint16_t horizontal_vel_accuracy; // [cm/s] + uint16_t hdop; + int32_t longitude; + int32_t latitude; + int32_t msl_altitude; // cm + int32_t ned_vel_north; // cm/s + int32_t ned_vel_east; + int32_t ned_vel_down; + uint16_t ground_course; // deg * 100, 0..36000 + uint16_t true_yaw; // deg * 100, values of 0..36000 are valid. 65535 = no data available + uint16_t year; + uint8_t month; + uint8_t day; + uint8_t hour; + uint8_t min; + uint8_t sec; + + // footer CRC + uint8_t crc; + } msp_gps {}; + + auto t = gps_time(); + struct timeval tv; + simulation_timeval(&tv); + auto *tm = gmtime(&tv.tv_sec); + + msp_gps.gps_week = t.week; + msp_gps.ms_tow = t.ms; + msp_gps.fix_type = d->have_lock?3:0; + msp_gps.satellites_in_view = d->have_lock ? _sitl->gps_numsats[instance] : 3; + msp_gps.horizontal_pos_accuracy = _sitl->gps_accuracy[instance]*100; + msp_gps.vertical_pos_accuracy = _sitl->gps_accuracy[instance]*100; + msp_gps.horizontal_vel_accuracy = 30; + msp_gps.hdop = 100; + msp_gps.longitude = d->longitude * 1.0e7; + msp_gps.latitude = d->latitude * 1.0e7; + msp_gps.msl_altitude = d->altitude * 100; + msp_gps.ned_vel_north = 100 * d->speedN; + msp_gps.ned_vel_east = 100 * d->speedE; + msp_gps.ned_vel_down = 100 * d->speedD; + msp_gps.ground_course = ToDeg(atan2f(d->speedE, d->speedN)) * 100; + msp_gps.true_yaw = wrap_360(d->yaw_deg)*100U; // can send 65535 for no yaw + msp_gps.year = tm->tm_year; + msp_gps.month = tm->tm_mon; + msp_gps.day = tm->tm_mday; + msp_gps.hour = tm->tm_hour; + msp_gps.min = tm->tm_min; + msp_gps.sec = tm->tm_sec; + + // CRC is over packet without first 3 bytes and trailing CRC byte + msp_gps.crc = crc8_dvb_s2_update(0, (uint8_t *)&msp_gps.hdr.flags, sizeof(msp_gps)-4); + + write_to_autopilot((const char *)&msp_gps, sizeof(msp_gps)); +} + +#endif // AP_SIM_GPS_MSP_ENABLED diff --git a/libraries/SITL/SIM_GPS_MSP.h b/libraries/SITL/SIM_GPS_MSP.h new file mode 100644 index 00000000000000..ae8ca8fa1a5078 --- /dev/null +++ b/libraries/SITL/SIM_GPS_MSP.h @@ -0,0 +1,20 @@ +#include "SIM_config.h" + +#if AP_SIM_GPS_MSP_ENABLED + +#include "SIM_GPS.h" + +namespace SITL { + +class GPS_MSP : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_MSP); + + using GPS_Backend::GPS_Backend; + + void publish(const GPS_Data *d) override; +}; + +} + +#endif // AP_SIM_GPS_MSP_ENABLED diff --git a/libraries/SITL/SIM_GPS_NMEA.cpp b/libraries/SITL/SIM_GPS_NMEA.cpp new file mode 100644 index 00000000000000..cb15ce32d521fe --- /dev/null +++ b/libraries/SITL/SIM_GPS_NMEA.cpp @@ -0,0 +1,125 @@ +#include "SIM_config.h" + +#if AP_SIM_GPS_NMEA_ENABLED + +#include "SIM_GPS_NMEA.h" + +#include +#include +#include + +extern const AP_HAL::HAL& hal; + +using namespace SITL; + +/* + formatted print of NMEA message, with checksum appended + */ +void GPS_NMEA::nmea_printf(const char *fmt, ...) +{ + va_list ap; + + va_start(ap, fmt); + char *s = nmea_vaprintf(fmt, ap); + va_end(ap); + if (s != nullptr) { + write_to_autopilot((const char*)s, strlen(s)); + free(s); + } +} + + +/* + send a new GPS NMEA packet + */ +void GPS_NMEA::publish(const GPS_Data *d) +{ + struct timeval tv; + struct tm *tm; + char tstring[20]; + char dstring[20]; + char lat_string[20]; + char lng_string[20]; + + simulation_timeval(&tv); + + tm = gmtime(&tv.tv_sec); + + // format time string + hal.util->snprintf(tstring, sizeof(tstring), "%02u%02u%06.3f", tm->tm_hour, tm->tm_min, tm->tm_sec + tv.tv_usec*1.0e-6); + + // format date string + hal.util->snprintf(dstring, sizeof(dstring), "%02u%02u%02u", tm->tm_mday, tm->tm_mon+1, tm->tm_year % 100); + + // format latitude + double deg = fabs(d->latitude); + hal.util->snprintf(lat_string, sizeof(lat_string), "%02u%08.5f,%c", + (unsigned)deg, + (deg - int(deg))*60, + d->latitude<0?'S':'N'); + + // format longitude + deg = fabs(d->longitude); + hal.util->snprintf(lng_string, sizeof(lng_string), "%03u%08.5f,%c", + (unsigned)deg, + (deg - int(deg))*60, + d->longitude<0?'W':'E'); + + nmea_printf("$GPGGA,%s,%s,%s,%01d,%02d,%04.1f,%07.2f,M,0.0,M,,", + tstring, + lat_string, + lng_string, + d->have_lock?1:0, + d->have_lock?_sitl->gps_numsats[instance]:3, + 1.2, + d->altitude); + + const float speed_mps = d->speed_2d(); + const float speed_knots = speed_mps * M_PER_SEC_TO_KNOTS; + const auto heading_rad = d->heading(); + + //$GPVTG,133.18,T,120.79,M,0.11,N,0.20,K,A*24 + nmea_printf("$GPVTG,%.2f,T,%.2f,M,%.2f,N,%.2f,K,A", + tstring, + heading_rad, + heading_rad, + speed_knots, + speed_knots * KNOTS_TO_METERS_PER_SECOND * 3.6); + + nmea_printf("$GPRMC,%s,%c,%s,%s,%.2f,%.2f,%s,,", + tstring, + d->have_lock?'A':'V', + lat_string, + lng_string, + speed_knots, + heading_rad, + dstring); + + if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_HDT) { + nmea_printf("$GPHDT,%.2f,T", d->yaw_deg); + } + else if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_THS) { + nmea_printf("$GPTHS,%.2f,%c,T", d->yaw_deg, d->have_lock ? 'A' : 'V'); + } else if (_sitl->gps_hdg_enabled[instance] == SITL::SIM::GPS_HEADING_KSXT) { + // Unicore support + // $KSXT,20211016083433.00,116.31296102,39.95817066,49.4911,223.57,-11.32,330.19,0.024,,1,3,28,27,,,,-0.012,0.021,0.020,,*2D + nmea_printf("$KSXT,%04u%02u%02u%02u%02u%02u.%02u,%.8f,%.8f,%.4f,%.2f,%.2f,%.2f,%.2f,%.3f,%u,%u,%u,%u,,,,%.3f,%.3f,%.3f,,", + tm->tm_year+1900, tm->tm_mon+1, tm->tm_mday, tm->tm_hour, tm->tm_min, tm->tm_sec, unsigned(tv.tv_usec*1.e-4), + d->longitude, d->latitude, + d->altitude, + wrap_360(d->yaw_deg), + d->pitch_deg, + heading_rad, + speed_mps, + d->roll_deg, + d->have_lock?1:0, // 2=rtkfloat 3=rtkfixed, + 3, // fixed rtk yaw solution, + d->have_lock?_sitl->gps_numsats[instance]:3, + d->have_lock?_sitl->gps_numsats[instance]:3, + d->speedE * 3.6, + d->speedN * 3.6, + -d->speedD * 3.6); + } +} + +#endif // AP_SIM_GPS_NMEA_ENABLED diff --git a/libraries/SITL/SIM_GPS_NMEA.h b/libraries/SITL/SIM_GPS_NMEA.h new file mode 100644 index 00000000000000..471f297857cadd --- /dev/null +++ b/libraries/SITL/SIM_GPS_NMEA.h @@ -0,0 +1,29 @@ +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_GPS_NMEA_ENABLED + +#include "SIM_GPS.h" + +namespace SITL { + +class GPS_NMEA : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_NMEA); + + using GPS_Backend::GPS_Backend; + + void publish(const GPS_Data *d) override; + +private: + + uint8_t nmea_checksum(const char *s); + void nmea_printf(const char *fmt, ...); + void update_nmea(const GPS_Data *d); + +}; + +}; + +#endif // AP_SIM_GPS_NMEA_ENABLED diff --git a/libraries/SITL/SIM_GPS_NOVA.cpp b/libraries/SITL/SIM_GPS_NOVA.cpp new file mode 100644 index 00000000000000..fd6b3da08e50a1 --- /dev/null +++ b/libraries/SITL/SIM_GPS_NOVA.cpp @@ -0,0 +1,177 @@ +#include "SIM_config.h" + +#if AP_SIM_GPS_NOVA_ENABLED + +#include "SIM_GPS_NOVA.h" + +#include + +using namespace SITL; + +void GPS_NOVA::publish(const GPS_Data *d) +{ + static struct PACKED nova_header + { + // 0 + uint8_t preamble[3]; + // 3 + uint8_t headerlength; + // 4 + uint16_t messageid; + // 6 + uint8_t messagetype; + //7 + uint8_t portaddr; + //8 + uint16_t messagelength; + //10 + uint16_t sequence; + //12 + uint8_t idletime; + //13 + uint8_t timestatus; + //14 + uint16_t week; + //16 + uint32_t tow; + //20 + uint32_t recvstatus; + // 24 + uint16_t resv; + //26 + uint16_t recvswver; + } header; + + struct PACKED psrdop + { + float gdop; + float pdop; + float hdop; + float htdop; + float tdop; + float cutoff; + uint32_t svcount; + // extra data for individual prns + } psrdop {}; + + struct PACKED bestpos + { + uint32_t solstat; + uint32_t postype; + double lat; + double lng; + double hgt; + float undulation; + uint32_t datumid; + float latsdev; + float lngsdev; + float hgtsdev; + // 4 bytes + uint8_t stnid[4]; + float diffage; + float sol_age; + uint8_t svstracked; + uint8_t svsused; + uint8_t svsl1; + uint8_t svsmultfreq; + uint8_t resv; + uint8_t extsolstat; + uint8_t galbeisigmask; + uint8_t gpsglosigmask; + } bestpos {}; + + struct PACKED bestvel + { + uint32_t solstat; + uint32_t veltype; + float latency; + float age; + double horspd; + double trkgnd; + // + up + double vertspd; + float resv; + } bestvel {}; + + const auto gps_tow = gps_time(); + + header.preamble[0] = 0xaa; + header.preamble[1] = 0x44; + header.preamble[2] = 0x12; + header.headerlength = sizeof(header); + header.week = gps_tow.week; + header.tow = gps_tow.ms; + + header.messageid = 174; + header.messagelength = sizeof(psrdop); + header.sequence += 1; + + psrdop.hdop = 1.20; + psrdop.htdop = 1.20; + nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&psrdop, sizeof(psrdop)); + + + header.messageid = 99; + header.messagelength = sizeof(bestvel); + header.sequence += 1; + + bestvel.horspd = norm(d->speedN, d->speedE); + bestvel.trkgnd = ToDeg(atan2f(d->speedE, d->speedN)); + bestvel.vertspd = -d->speedD; + + nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&bestvel, sizeof(bestvel)); + + + header.messageid = 42; + header.messagelength = sizeof(bestpos); + header.sequence += 1; + + bestpos.lat = d->latitude; + bestpos.lng = d->longitude; + bestpos.hgt = d->altitude; + bestpos.svsused = d->have_lock ? _sitl->gps_numsats[instance] : 3; + bestpos.latsdev=0.2; + bestpos.lngsdev=0.2; + bestpos.hgtsdev=0.2; + bestpos.solstat=0; + bestpos.postype=32; + + nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&bestpos, sizeof(bestpos)); +} + +void GPS_NOVA::nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen) +{ + write_to_autopilot((char*)header, headerlength); +write_to_autopilot((char*)payload, payloadlen); + + uint32_t crc = CalculateBlockCRC32(headerlength, header, (uint32_t)0); + crc = CalculateBlockCRC32(payloadlen, payload, crc); + + write_to_autopilot((char*)&crc, 4); +} + +#define CRC32_POLYNOMIAL 0xEDB88320L +uint32_t GPS_NOVA::CRC32Value(uint32_t icrc) +{ + int i; + uint32_t crc = icrc; + for ( i = 8 ; i > 0; i-- ) + { + if ( crc & 1 ) + crc = ( crc >> 1 ) ^ CRC32_POLYNOMIAL; + else + crc >>= 1; + } + return crc; +} + +uint32_t GPS_NOVA::CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc) +{ + while ( length-- != 0 ) + { + crc = ((crc >> 8) & 0x00FFFFFFL) ^ (CRC32Value(((uint32_t) crc ^ *buffer++) & 0xff)); + } + return( crc ); +} + +#endif // AP_SIM_GPS_NOVA_ENABLED diff --git a/libraries/SITL/SIM_GPS_NOVA.h b/libraries/SITL/SIM_GPS_NOVA.h new file mode 100644 index 00000000000000..4df22b32d8dc9a --- /dev/null +++ b/libraries/SITL/SIM_GPS_NOVA.h @@ -0,0 +1,30 @@ +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_GPS_NOVA_ENABLED + +#include "SIM_GPS.h" + +namespace SITL { + +class GPS_NOVA : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_NOVA); + + using GPS_Backend::GPS_Backend; + + void publish(const GPS_Data *d) override; + + uint32_t device_baud() const override { return 19200; } + +private: + + void nova_send_message(uint8_t *header, uint8_t headerlength, uint8_t *payload, uint8_t payloadlen); + uint32_t CRC32Value(uint32_t icrc); + uint32_t CalculateBlockCRC32(uint32_t length, uint8_t *buffer, uint32_t crc); +}; + +}; + +#endif // AP_SIM_GPS_NOVA_ENABLED diff --git a/libraries/SITL/SIM_GPS_SBP.cpp b/libraries/SITL/SIM_GPS_SBP.cpp new file mode 100644 index 00000000000000..b3b8e77d890711 --- /dev/null +++ b/libraries/SITL/SIM_GPS_SBP.cpp @@ -0,0 +1,122 @@ +#include "SIM_GPS_SBP.h" + +#if AP_SIM_GPS_SBP_ENABLED + +#include + +using namespace SITL; + +void GPS_SBP::publish(const GPS_Data *d) +{ + struct sbp_heartbeat_t { + bool sys_error : 1; + bool io_error : 1; + bool nap_error : 1; + uint8_t res : 5; + uint8_t protocol_minor : 8; + uint8_t protocol_major : 8; + uint8_t res2 : 7; + bool ext_antenna : 1; + } hb; // 4 bytes + + struct PACKED sbp_gps_time_t { + uint16_t wn; //< GPS week number + uint32_t tow; //< GPS Time of Week rounded to the nearest ms + int32_t ns; //< Nanosecond remainder of rounded tow + uint8_t flags; //< Status flags (reserved) + } t; + struct PACKED sbp_pos_llh_t { + uint32_t tow; //< GPS Time of Week + double lat; //< Latitude + double lon; //< Longitude + double height; //< Height + uint16_t h_accuracy; //< Horizontal position accuracy estimate + uint16_t v_accuracy; //< Vertical position accuracy estimate + uint8_t n_sats; //< Number of satellites used in solution + uint8_t flags; //< Status flags + } pos; + struct PACKED sbp_vel_ned_t { + uint32_t tow; //< GPS Time of Week + int32_t n; //< Velocity North coordinate + int32_t e; //< Velocity East coordinate + int32_t d; //< Velocity Down coordinate + uint16_t h_accuracy; //< Horizontal velocity accuracy estimate + uint16_t v_accuracy; //< Vertical velocity accuracy estimate + uint8_t n_sats; //< Number of satellites used in solution + uint8_t flags; //< Status flags (reserved) + } velned; + struct PACKED sbp_dops_t { + uint32_t tow; //< GPS Time of Week + uint16_t gdop; //< Geometric Dilution of Precision + uint16_t pdop; //< Position Dilution of Precision + uint16_t tdop; //< Time Dilution of Precision + uint16_t hdop; //< Horizontal Dilution of Precision + uint16_t vdop; //< Vertical Dilution of Precision + uint8_t flags; //< Status flags (reserved) + } dops; + + static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF; + static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0100; + static const uint16_t SBP_DOPS_MSGTYPE = 0x0206; + static const uint16_t SBP_POS_LLH_MSGTYPE = 0x0201; + static const uint16_t SBP_VEL_NED_MSGTYPE = 0x0205; + + const auto gps_tow = gps_time(); + + t.wn = gps_tow.week; + t.tow = gps_tow.ms; + t.ns = 0; + t.flags = 0; + sbp_send_message(SBP_GPS_TIME_MSGTYPE, 0x2222, sizeof(t), (uint8_t*)&t); + + if (!d->have_lock) { + return; + } + + pos.tow = gps_tow.ms; + pos.lon = d->longitude; + pos.lat= d->latitude; + pos.height = d->altitude; + pos.h_accuracy = _sitl->gps_accuracy[instance]*1000; + pos.v_accuracy = _sitl->gps_accuracy[instance]*1000; + pos.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; + + // Send single point position solution + pos.flags = 0; + sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos); + // Send "pseudo-absolute" RTK position solution + pos.flags = 1; + sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos); + + velned.tow = gps_tow.ms; + velned.n = 1e3 * d->speedN; + velned.e = 1e3 * d->speedE; + velned.d = 1e3 * d->speedD; + velned.h_accuracy = 5e3; + velned.v_accuracy = 5e3; + velned.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; + velned.flags = 0; + sbp_send_message(SBP_VEL_NED_MSGTYPE, 0x2222, sizeof(velned), (uint8_t*)&velned); + + static uint32_t do_every_count = 0; + if (do_every_count % 5 == 0) { + + dops.tow = gps_tow.ms; + dops.gdop = 1; + dops.pdop = 1; + dops.tdop = 1; + dops.hdop = 100; + dops.vdop = 1; + dops.flags = 1; + sbp_send_message(SBP_DOPS_MSGTYPE, 0x2222, sizeof(dops), + (uint8_t*)&dops); + + hb.protocol_major = 0; //Sends protocol version 0 + sbp_send_message(SBP_HEARTBEAT_MSGTYPE, 0x2222, sizeof(hb), + (uint8_t*)&hb); + + } + do_every_count++; +} + +#endif // AP_SIM_GPS_SBP_ENABLED diff --git a/libraries/SITL/SIM_GPS_SBP.h b/libraries/SITL/SIM_GPS_SBP.h new file mode 100644 index 00000000000000..e0f1f58eab6123 --- /dev/null +++ b/libraries/SITL/SIM_GPS_SBP.h @@ -0,0 +1,23 @@ +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_GPS_SBP_ENABLED + +#include "SIM_GPS_SBP_Common.h" + +namespace SITL { + +class GPS_SBP : public GPS_SBP_Common { +public: + CLASS_NO_COPY(GPS_SBP); + + using GPS_SBP_Common::GPS_SBP_Common; + + void publish(const GPS_Data *d) override; + +}; + +}; + +#endif // AP_SIM_GPS_SBP_ENABLED diff --git a/libraries/SITL/SIM_GPS_SBP2.cpp b/libraries/SITL/SIM_GPS_SBP2.cpp new file mode 100644 index 00000000000000..1596d330af6fae --- /dev/null +++ b/libraries/SITL/SIM_GPS_SBP2.cpp @@ -0,0 +1,121 @@ +#include "SIM_GPS_SBP2.h" + +#if AP_SIM_GPS_SBP2_ENABLED + +#include + +using namespace SITL; + +void GPS_SBP2::publish(const GPS_Data *d) +{ + struct sbp_heartbeat_t { + bool sys_error : 1; + bool io_error : 1; + bool nap_error : 1; + uint8_t res : 5; + uint8_t protocol_minor : 8; + uint8_t protocol_major : 8; + uint8_t res2 : 7; + bool ext_antenna : 1; + } hb; // 4 bytes + + struct PACKED sbp_gps_time_t { + uint16_t wn; //< GPS week number + uint32_t tow; //< GPS Time of Week rounded to the nearest ms + int32_t ns; //< Nanosecond remainder of rounded tow + uint8_t flags; //< Status flags (reserved) + } t; + struct PACKED sbp_pos_llh_t { + uint32_t tow; //< GPS Time of Week + double lat; //< Latitude + double lon; //< Longitude + double height; //< Height + uint16_t h_accuracy; //< Horizontal position accuracy estimate + uint16_t v_accuracy; //< Vertical position accuracy estimate + uint8_t n_sats; //< Number of satellites used in solution + uint8_t flags; //< Status flags + } pos; + struct PACKED sbp_vel_ned_t { + uint32_t tow; //< GPS Time of Week + int32_t n; //< Velocity North coordinate + int32_t e; //< Velocity East coordinate + int32_t d; //< Velocity Down coordinate + uint16_t h_accuracy; //< Horizontal velocity accuracy estimate + uint16_t v_accuracy; //< Vertical velocity accuracy estimate + uint8_t n_sats; //< Number of satellites used in solution + uint8_t flags; //< Status flags (reserved) + } velned; + struct PACKED sbp_dops_t { + uint32_t tow; //< GPS Time of Week + uint16_t gdop; //< Geometric Dilution of Precision + uint16_t pdop; //< Position Dilution of Precision + uint16_t tdop; //< Time Dilution of Precision + uint16_t hdop; //< Horizontal Dilution of Precision + uint16_t vdop; //< Vertical Dilution of Precision + uint8_t flags; //< Status flags (reserved) + } dops; + + static const uint16_t SBP_HEARTBEAT_MSGTYPE = 0xFFFF; + static const uint16_t SBP_GPS_TIME_MSGTYPE = 0x0102; + static const uint16_t SBP_DOPS_MSGTYPE = 0x0208; + static const uint16_t SBP_POS_LLH_MSGTYPE = 0x020A; + static const uint16_t SBP_VEL_NED_MSGTYPE = 0x020E; + + const auto gps_tow = gps_time(); + + t.wn = gps_tow.week; + t.tow = gps_tow.ms; + t.ns = 0; + t.flags = 1; + sbp_send_message(SBP_GPS_TIME_MSGTYPE, 0x2222, sizeof(t), (uint8_t*)&t); + + if (!d->have_lock) { + return; + } + + pos.tow = gps_tow.ms; + pos.lon = d->longitude; + pos.lat= d->latitude; + pos.height = d->altitude; + pos.h_accuracy = _sitl->gps_accuracy[instance]*1000; + pos.v_accuracy = _sitl->gps_accuracy[instance]*1000; + pos.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; + + // Send single point position solution + pos.flags = 1; + sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos); + // Send "pseudo-absolute" RTK position solution + pos.flags = 4; + sbp_send_message(SBP_POS_LLH_MSGTYPE, 0x2222, sizeof(pos), (uint8_t*)&pos); + + velned.tow = gps_tow.ms; + velned.n = 1e3 * d->speedN; + velned.e = 1e3 * d->speedE; + velned.d = 1e3 * d->speedD; + velned.h_accuracy = 5e3; + velned.v_accuracy = 5e3; + velned.n_sats = d->have_lock ? _sitl->gps_numsats[instance] : 3; + velned.flags = 1; + sbp_send_message(SBP_VEL_NED_MSGTYPE, 0x2222, sizeof(velned), (uint8_t*)&velned); + + static uint32_t do_every_count = 0; + if (do_every_count % 5 == 0) { + + dops.tow = gps_tow.ms; + dops.gdop = 1; + dops.pdop = 1; + dops.tdop = 1; + dops.hdop = 100; + dops.vdop = 1; + dops.flags = 1; + sbp_send_message(SBP_DOPS_MSGTYPE, 0x2222, sizeof(dops), + (uint8_t*)&dops); + + hb.protocol_major = 2; //Sends protocol version 2.0 + sbp_send_message(SBP_HEARTBEAT_MSGTYPE, 0x2222, sizeof(hb), + (uint8_t*)&hb); + } + do_every_count++; +} + +#endif // AP_SIM_GPS_SBP2_ENABLED diff --git a/libraries/SITL/SIM_GPS_SBP2.h b/libraries/SITL/SIM_GPS_SBP2.h new file mode 100644 index 00000000000000..580f430feaa977 --- /dev/null +++ b/libraries/SITL/SIM_GPS_SBP2.h @@ -0,0 +1,23 @@ +#pragma once + +#include "SIM_config.h" + +#if AP_SIM_GPS_SBP2_ENABLED + +#include "SIM_GPS_SBP_Common.h" + +namespace SITL { + +class GPS_SBP2 : public GPS_SBP_Common { +public: + CLASS_NO_COPY(GPS_SBP2); + + using GPS_SBP_Common::GPS_SBP_Common; + + void publish(const GPS_Data *d) override; + +}; + +}; + +#endif // AP_SIM_GPS_SBP2_ENABLED diff --git a/libraries/SITL/SIM_GPS_SBP_Common.cpp b/libraries/SITL/SIM_GPS_SBP_Common.cpp new file mode 100644 index 00000000000000..90116d76da97b5 --- /dev/null +++ b/libraries/SITL/SIM_GPS_SBP_Common.cpp @@ -0,0 +1,34 @@ +#include "SIM_config.h" + +#if HAL_SIM_GPS_ENABLED + +#include "SIM_GPS_SBP_Common.h" + +#include + +using namespace SITL; + +void GPS_SBP_Common::sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload) +{ + if (len != 0 && payload == 0) { + return; //SBP_NULL_ERROR; + } + + uint8_t preamble = 0x55; + write_to_autopilot((char*)&preamble, 1); + write_to_autopilot((char*)&msg_type, 2); + write_to_autopilot((char*)&sender_id, 2); + write_to_autopilot((char*)&len, 1); + if (len > 0) { + write_to_autopilot((char*)payload, len); + } + + uint16_t crc; + crc = crc16_ccitt((uint8_t*)&(msg_type), 2, 0); + crc = crc16_ccitt((uint8_t*)&(sender_id), 2, crc); + crc = crc16_ccitt(&(len), 1, crc); + crc = crc16_ccitt(payload, len, crc); + write_to_autopilot((char*)&crc, 2); +} + +#endif diff --git a/libraries/SITL/SIM_GPS_SBP_Common.h b/libraries/SITL/SIM_GPS_SBP_Common.h new file mode 100644 index 00000000000000..5cb13e930f9d28 --- /dev/null +++ b/libraries/SITL/SIM_GPS_SBP_Common.h @@ -0,0 +1,25 @@ +#pragma once + +#include "SIM_config.h" + +#if HAL_SIM_GPS_ENABLED + +#include "SIM_GPS.h" + +namespace SITL { + +class GPS_SBP_Common : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_SBP_Common); + + using GPS_Backend::GPS_Backend; + +protected: + + void sbp_send_message(uint16_t msg_type, uint16_t sender_id, uint8_t len, uint8_t *payload); + +}; + +}; + +#endif diff --git a/libraries/SITL/SIM_GPS_UBLOX.cpp b/libraries/SITL/SIM_GPS_UBLOX.cpp new file mode 100644 index 00000000000000..7bcab4b376b30c --- /dev/null +++ b/libraries/SITL/SIM_GPS_UBLOX.cpp @@ -0,0 +1,324 @@ +#include "SIM_config.h" + +#if AP_SIM_GPS_UBLOX_ENABLED + +#include "SIM_GPS_UBLOX.h" + +#include + +using namespace SITL; + +/* + send a UBLOX GPS message + */ +void GPS_UBlox::send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size) +{ + const uint8_t PREAMBLE1 = 0xb5; + const uint8_t PREAMBLE2 = 0x62; + const uint8_t CLASS_NAV = 0x1; + uint8_t hdr[6], chk[2]; + hdr[0] = PREAMBLE1; + hdr[1] = PREAMBLE2; + hdr[2] = CLASS_NAV; + hdr[3] = msgid; + hdr[4] = size & 0xFF; + hdr[5] = size >> 8; + chk[0] = chk[1] = hdr[2]; + chk[1] += (chk[0] += hdr[3]); + chk[1] += (chk[0] += hdr[4]); + chk[1] += (chk[0] += hdr[5]); + for (uint16_t i=0; ilongitude * 1.0e7; + pos.latitude = d->latitude * 1.0e7; + pos.altitude_ellipsoid = d->altitude * 1000.0f; + pos.altitude_msl = d->altitude * 1000.0f; + pos.horizontal_accuracy = _sitl->gps_accuracy[instance]*1000; + pos.vertical_accuracy = _sitl->gps_accuracy[instance]*1000; + + status.time = gps_tow.ms; + status.fix_type = d->have_lock?3:0; + status.fix_status = d->have_lock?1:0; + status.differential_status = 0; + status.res = 0; + status.time_to_first_fix = 0; + status.uptime = AP_HAL::millis(); + + velned.time = gps_tow.ms; + velned.ned_north = 100.0f * d->speedN; + velned.ned_east = 100.0f * d->speedE; + velned.ned_down = 100.0f * d->speedD; + velned.speed_2d = norm(d->speedN, d->speedE) * 100; + velned.speed_3d = norm(d->speedN, d->speedE, d->speedD) * 100; + velned.heading_2d = ToDeg(atan2f(d->speedE, d->speedN)) * 100000.0f; + if (velned.heading_2d < 0.0f) { + velned.heading_2d += 360.0f * 100000.0f; + } + velned.speed_accuracy = 40; + velned.heading_accuracy = 4; + + memset(&sol, 0, sizeof(sol)); + sol.fix_type = d->have_lock?3:0; + sol.fix_status = 221; + sol.satellites = d->have_lock ? _sitl->gps_numsats[instance] : 3; + sol.time = gps_tow.ms; + sol.week = gps_tow.week; + + dop.time = gps_tow.ms; + dop.gDOP = 65535; + dop.pDOP = 65535; + dop.tDOP = 65535; + dop.vDOP = 200; + dop.hDOP = 121; + dop.nDOP = 65535; + dop.eDOP = 65535; + + pvt.itow = gps_tow.ms; + pvt.year = 0; + pvt.month = 0; + pvt.day = 0; + pvt.hour = 0; + pvt.min = 0; + pvt.sec = 0; + pvt.valid = 0; // invalid utc date + pvt.t_acc = 0; + pvt.nano = 0; + pvt.fix_type = d->have_lock? 0x3 : 0; + pvt.flags = 0b10000011; // carrsoln=fixed, psm = na, diffsoln and fixok + pvt.flags2 =0; + pvt.num_sv = d->have_lock ? _sitl->gps_numsats[instance] : 3; + pvt.lon = d->longitude * 1.0e7; + pvt.lat = d->latitude * 1.0e7; + pvt.height = d->altitude * 1000.0f; + pvt.h_msl = d->altitude * 1000.0f; + pvt.h_acc = _sitl->gps_accuracy[instance] * 1000; + pvt.v_acc = _sitl->gps_accuracy[instance] * 1000; + pvt.velN = 1000.0f * d->speedN; + pvt.velE = 1000.0f * d->speedE; + pvt.velD = 1000.0f * d->speedD; + pvt.gspeed = norm(d->speedN, d->speedE) * 1000; + pvt.head_mot = ToDeg(atan2f(d->speedE, d->speedN)) * 1.0e5; + pvt.s_acc = 40; + pvt.head_acc = 38 * 1.0e5; + pvt.p_dop = 65535; + memset(pvt.reserved1, '\0', ARRAY_SIZE(pvt.reserved1)); + pvt.headVeh = 0; + memset(pvt.reserved2, '\0', ARRAY_SIZE(pvt.reserved2)); + + if (_sitl->gps_hdg_enabled[instance] > SITL::SIM::GPS_HEADING_NONE) { + const Vector3f ant1_pos = _sitl->gps_pos_offset[instance^1].get(); + const Vector3f ant2_pos = _sitl->gps_pos_offset[instance].get(); + Vector3f rel_antenna_pos = ant2_pos - ant1_pos; + Matrix3f rot; + // project attitude back using gyros to get antenna orientation at time of GPS sample + Vector3f gyro(radians(_sitl->state.rollRate), + radians(_sitl->state.pitchRate), + radians(_sitl->state.yawRate)); + rot.from_euler(radians(_sitl->state.rollDeg), radians(_sitl->state.pitchDeg), radians(d->yaw_deg)); + const float lag = _sitl->gps_delay_ms[instance] * 0.001; + rot.rotate(gyro * (-lag)); + rel_antenna_pos = rot * rel_antenna_pos; + relposned.version = 1; + relposned.iTOW = gps_tow.ms; + relposned.relPosN = rel_antenna_pos.x * 100; + relposned.relPosE = rel_antenna_pos.y * 100; + relposned.relPosD = rel_antenna_pos.z * 100; + relposned.relPosLength = rel_antenna_pos.length() * 100; + relposned.relPosHeading = degrees(Vector2f(rel_antenna_pos.x, rel_antenna_pos.y).angle()) * 1.0e5; + relposned.flags = gnssFixOK | diffSoln | carrSolnFixed | isMoving | relPosValid | relPosHeadingValid; + } + + send_ubx(MSG_POSLLH, (uint8_t*)&pos, sizeof(pos)); + send_ubx(MSG_STATUS, (uint8_t*)&status, sizeof(status)); + send_ubx(MSG_VELNED, (uint8_t*)&velned, sizeof(velned)); + send_ubx(MSG_SOL, (uint8_t*)&sol, sizeof(sol)); + send_ubx(MSG_DOP, (uint8_t*)&dop, sizeof(dop)); + send_ubx(MSG_PVT, (uint8_t*)&pvt, sizeof(pvt)); + if (_sitl->gps_hdg_enabled[instance] > SITL::SIM::GPS_HEADING_NONE) { + send_ubx(MSG_RELPOSNED, (uint8_t*)&relposned, sizeof(relposned)); + } + + if (gps_tow.ms > _next_nav_sv_info_time) { + svinfo.itow = gps_tow.ms; + svinfo.numCh = 32; + svinfo.globalFlags = 4; // u-blox 8/M8 + // fill in the SV's with some data even though firmware does not currently use it + // note that this is not using num_sats as we aren't dynamically creating this to match + for (uint8_t i = 0; i < SV_COUNT; i++) { + svinfo.sv[i].chn = i; + svinfo.sv[i].svid = i; + svinfo.sv[i].flags = (i < _sitl->gps_numsats[instance]) ? 0x7 : 0x6; // sv used, diff correction data, orbit information + svinfo.sv[i].quality = 7; // code and carrier lock and time synchronized + svinfo.sv[i].cno = MAX(20, 30 - i); + svinfo.sv[i].elev = MAX(30, 90 - i); + svinfo.sv[i].azim = i; + // not bothering to fill in prRes + } + send_ubx(MSG_SVINFO, (uint8_t*)&svinfo, sizeof(svinfo)); + _next_nav_sv_info_time = gps_tow.ms + 10000; // 10 second delay + } +} + +#endif // AP_SIM_GPS_UBLOX_ENABLED diff --git a/libraries/SITL/SIM_GPS_UBLOX.h b/libraries/SITL/SIM_GPS_UBLOX.h new file mode 100644 index 00000000000000..6ab5d01eea76fc --- /dev/null +++ b/libraries/SITL/SIM_GPS_UBLOX.h @@ -0,0 +1,23 @@ +#include "SIM_config.h" + +#if AP_SIM_GPS_UBLOX_ENABLED + +#include "SIM_GPS.h" + +namespace SITL { + +class GPS_UBlox : public GPS_Backend { +public: + CLASS_NO_COPY(GPS_UBlox); + + using GPS_Backend::GPS_Backend; + + void publish(const GPS_Data *d) override; + +private: + void send_ubx(uint8_t msgid, uint8_t *buf, uint16_t size); +}; + +}; + +#endif // AP_SIM_GPS_UBLOX_ENABLED diff --git a/libraries/SITL/SIM_config.h b/libraries/SITL/SIM_config.h index 726b9032766205..7c760ee4bfa493 100644 --- a/libraries/SITL/SIM_config.h +++ b/libraries/SITL/SIM_config.h @@ -37,3 +37,44 @@ #ifndef AP_SIM_SERIALDEVICE_CORRUPTION_ENABLED #define AP_SIM_SERIALDEVICE_CORRUPTION_ENABLED 0 #endif + +#ifndef HAL_SIM_GPS_ENABLED +#define HAL_SIM_GPS_ENABLED AP_SIM_ENABLED +#endif + +#ifndef AP_SIM_GPS_BACKEND_DEFAULT_ENABLED +#define AP_SIM_GPS_BACKEND_DEFAULT_ENABLED AP_SIM_ENABLED +#endif + +#ifndef AP_SIM_GPS_FILE_ENABLED +// really need to use AP_FileSystem for this. +#define AP_SIM_GPS_FILE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX) +#endif + +#ifndef AP_SIM_GPS_GSOF_ENABLED +#define AP_SIM_GPS_GSOF_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_SIM_GPS_MSP_ENABLED +#define AP_SIM_GPS_MSP_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_SIM_GPS_NMEA_ENABLED +#define AP_SIM_GPS_NMEA_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_SIM_GPS_NOVA_ENABLED +#define AP_SIM_GPS_NOVA_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_SIM_GPS_SBP2_ENABLED +#define AP_SIM_GPS_SBP2_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_SIM_GPS_SBP_ENABLED +#define AP_SIM_GPS_SBP_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_SIM_GPS_UBLOX_ENABLED +#define AP_SIM_GPS_UBLOX_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED +#endif From d992ead5b16b52406786d8f641ceba757e01f8a9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Nov 2023 07:11:02 +1100 Subject: [PATCH 472/499] SITL: rename GSOF to Trimble ... as now it's not just GSOF but also DCOL --- libraries/SITL/{SIM_GPS_GSOF.cpp => SIM_GPS_Trimble.cpp} | 0 libraries/SITL/{SIM_GPS_GSOF.h => SIM_GPS_Trimble.h} | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename libraries/SITL/{SIM_GPS_GSOF.cpp => SIM_GPS_Trimble.cpp} (100%) rename libraries/SITL/{SIM_GPS_GSOF.h => SIM_GPS_Trimble.h} (100%) diff --git a/libraries/SITL/SIM_GPS_GSOF.cpp b/libraries/SITL/SIM_GPS_Trimble.cpp similarity index 100% rename from libraries/SITL/SIM_GPS_GSOF.cpp rename to libraries/SITL/SIM_GPS_Trimble.cpp diff --git a/libraries/SITL/SIM_GPS_GSOF.h b/libraries/SITL/SIM_GPS_Trimble.h similarity index 100% rename from libraries/SITL/SIM_GPS_GSOF.h rename to libraries/SITL/SIM_GPS_Trimble.h From a143d2e4532bcd225063380bf75e14f926a381d9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Nov 2023 07:21:48 +1100 Subject: [PATCH 473/499] SITL: remove trailing whitespace in SITL GPS drivers we've just lost the history for these lines anyway --- libraries/SITL/SIM_GPS_NMEA.cpp | 2 +- libraries/SITL/SIM_GPS_NOVA.cpp | 14 +++---- libraries/SITL/SIM_GPS_Trimble.cpp | 22 +++++------ libraries/SITL/SIM_GPS_UBLOX.cpp | 62 +++++++++++++++--------------- 4 files changed, 50 insertions(+), 50 deletions(-) diff --git a/libraries/SITL/SIM_GPS_NMEA.cpp b/libraries/SITL/SIM_GPS_NMEA.cpp index cb15ce32d521fe..0491cce2ebd829 100644 --- a/libraries/SITL/SIM_GPS_NMEA.cpp +++ b/libraries/SITL/SIM_GPS_NMEA.cpp @@ -73,7 +73,7 @@ void GPS_NMEA::publish(const GPS_Data *d) d->have_lock?_sitl->gps_numsats[instance]:3, 1.2, d->altitude); - + const float speed_mps = d->speed_2d(); const float speed_knots = speed_mps * M_PER_SEC_TO_KNOTS; const auto heading_rad = d->heading(); diff --git a/libraries/SITL/SIM_GPS_NOVA.cpp b/libraries/SITL/SIM_GPS_NOVA.cpp index fd6b3da08e50a1..cd4608b7f0b91d 100644 --- a/libraries/SITL/SIM_GPS_NOVA.cpp +++ b/libraries/SITL/SIM_GPS_NOVA.cpp @@ -92,20 +92,20 @@ void GPS_NOVA::publish(const GPS_Data *d) double vertspd; float resv; } bestvel {}; - + const auto gps_tow = gps_time(); - + header.preamble[0] = 0xaa; header.preamble[1] = 0x44; header.preamble[2] = 0x12; header.headerlength = sizeof(header); header.week = gps_tow.week; header.tow = gps_tow.ms; - + header.messageid = 174; header.messagelength = sizeof(psrdop); header.sequence += 1; - + psrdop.hdop = 1.20; psrdop.htdop = 1.20; nova_send_message((uint8_t*)&header,sizeof(header),(uint8_t*)&psrdop, sizeof(psrdop)); @@ -114,8 +114,8 @@ void GPS_NOVA::publish(const GPS_Data *d) header.messageid = 99; header.messagelength = sizeof(bestvel); header.sequence += 1; - - bestvel.horspd = norm(d->speedN, d->speedE); + + bestvel.horspd = norm(d->speedN, d->speedE); bestvel.trkgnd = ToDeg(atan2f(d->speedE, d->speedN)); bestvel.vertspd = -d->speedD; @@ -125,7 +125,7 @@ void GPS_NOVA::publish(const GPS_Data *d) header.messageid = 42; header.messagelength = sizeof(bestpos); header.sequence += 1; - + bestpos.lat = d->latitude; bestpos.lng = d->longitude; bestpos.hgt = d->altitude; diff --git a/libraries/SITL/SIM_GPS_Trimble.cpp b/libraries/SITL/SIM_GPS_Trimble.cpp index 477ef5a87a62da..e1315f2b4a551e 100644 --- a/libraries/SITL/SIM_GPS_Trimble.cpp +++ b/libraries/SITL/SIM_GPS_Trimble.cpp @@ -12,7 +12,7 @@ using namespace SITL; void GPS_GSOF::publish(const GPS_Data *d) -{ +{ // This logic is to populate output buffer only with enabled channels. // It also only sends each channel at the configured rate. const uint64_t now = AP_HAL::millis(); @@ -98,7 +98,7 @@ void GPS_GSOF::publish(const GPS_Data *d) bootcount }; static_assert(sizeof(gsof_pos_time) - (sizeof(gsof_pos_time::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_time::RECORD_LEN)) == GSOF_POS_TIME_LEN); - + payload_sz += sizeof(pos_time); memcpy(&buf[offset], &pos_time, sizeof(pos_time)); offset += sizeof(pos_time); @@ -126,8 +126,8 @@ void GPS_GSOF::publish(const GPS_Data *d) gsof_pack_double(d->longitude * DEG_TO_RAD_DOUBLE), gsof_pack_double(static_cast(d->altitude)) }; - static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN); - + static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN); + payload_sz += sizeof(pos); memcpy(&buf[offset], &pos, sizeof(pos)); offset += sizeof(pos); @@ -154,7 +154,7 @@ void GPS_GSOF::publish(const GPS_Data *d) RESERVED_6 = 1U << 6, RESERVED_7 = 1U << 7, }; - uint8_t vel_flags {0}; + uint8_t vel_flags {0}; if(d->have_lock) { vel_flags |= uint8_t(VEL_FIELDS::VALID); vel_flags |= uint8_t(VEL_FIELDS::CONSECUTIVE_MEASUREMENTS); @@ -162,7 +162,7 @@ void GPS_GSOF::publish(const GPS_Data *d) } const struct PACKED gsof_vel { - const uint8_t OUTPUT_RECORD_TYPE; + const uint8_t OUTPUT_RECORD_TYPE; const uint8_t RECORD_LEN; // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_Flags.html#Velocity%20flags uint8_t flags; @@ -194,7 +194,7 @@ void GPS_GSOF::publish(const GPS_Data *d) // https://receiverhelp.trimble.com/oem-gnss/index.html#GSOFmessages_PDOP.html?TocPath=Output%2520Messages%257CGSOF%2520Messages%257C_____12 constexpr uint8_t GSOF_DOP_LEN = 0x10; const struct PACKED gsof_dop { - const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::PDOP_INFO) }; + const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::PDOP_INFO) }; const uint8_t RECORD_LEN { GSOF_DOP_LEN }; uint32_t pdop = htobe32(1); uint32_t hdop = htobe32(1); @@ -223,7 +223,7 @@ void GPS_GSOF::publish(const GPS_Data *d) // https://receiverhelp.trimble.com/oem-gnss/GSOFmessages_SIGMA.html constexpr uint8_t GSOF_POS_SIGMA_LEN = 0x26; const struct PACKED gsof_pos_sigma { - const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO) }; + const uint8_t OUTPUT_RECORD_TYPE { uint8_t(Gsof_Msg_Record_Type::POSITION_SIGMA_INFO) }; const uint8_t RECORD_LEN { GSOF_POS_SIGMA_LEN }; uint32_t pos_rms = htobe32(0); uint32_t sigma_e = htobe32(0); @@ -365,7 +365,7 @@ bool DCOL_Parser::parse_cmd_appfile() { if (expected_payload_length < min_cmd_appfile_sz) { return false; } - + // For now, ignore appfile_trans_num, return success regardless. // If the driver doesn't send the right value, it's not clear what the behavior is supposed to be. // Also would need to handle re-sync. @@ -475,7 +475,7 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) static uint8_t TRANSMISSION_NUMBER = 0; // Functionally, this is a sequence number // Most messages, even GSOF49, only take one page. For SIM, assume it. assert(size < 0xFA); // GPS SIM doesn't yet support paging - constexpr uint8_t PAGE_INDEX = 0; + constexpr uint8_t PAGE_INDEX = 0; constexpr uint8_t MAX_PAGE_INDEX = 0; const uint8_t gsof_header[3] = { TRANSMISSION_NUMBER, @@ -496,7 +496,7 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) // This aligns with manual's idea of data bytes: // "Each message begins with a 4-byte header, followed by the bytes of data in each packet. The packet ends with a 2-byte trailer." // Thus, for this implementation with single-page single-record per DCOL packet, - // the length is simply the sum of data packet size, the gsof_header size. + // the length is simply the sum of data packet size, the gsof_header size. const uint8_t length = size + sizeof(gsof_header); const uint8_t dcol_header[4] { STX, diff --git a/libraries/SITL/SIM_GPS_UBLOX.cpp b/libraries/SITL/SIM_GPS_UBLOX.cpp index 7bcab4b376b30c..5d743cbfe9b3a3 100644 --- a/libraries/SITL/SIM_GPS_UBLOX.cpp +++ b/libraries/SITL/SIM_GPS_UBLOX.cpp @@ -99,27 +99,27 @@ void GPS_UBlox::publish(const GPS_Data *d) uint16_t eDOP; } dop {}; struct PACKED ubx_nav_pvt { - uint32_t itow; - uint16_t year; - uint8_t month, day, hour, min, sec; - uint8_t valid; - uint32_t t_acc; - int32_t nano; - uint8_t fix_type; - uint8_t flags; - uint8_t flags2; - uint8_t num_sv; - int32_t lon, lat; - int32_t height, h_msl; - uint32_t h_acc, v_acc; - int32_t velN, velE, velD, gspeed; - int32_t head_mot; - uint32_t s_acc; - uint32_t head_acc; - uint16_t p_dop; - uint8_t reserved1[6]; + uint32_t itow; + uint16_t year; + uint8_t month, day, hour, min, sec; + uint8_t valid; + uint32_t t_acc; + int32_t nano; + uint8_t fix_type; + uint8_t flags; + uint8_t flags2; + uint8_t num_sv; + int32_t lon, lat; + int32_t height, h_msl; + uint32_t h_acc, v_acc; + int32_t velN, velE, velD, gspeed; + int32_t head_mot; + uint32_t s_acc; + uint32_t head_acc; + uint16_t p_dop; + uint8_t reserved1[6]; uint32_t headVeh; - uint8_t reserved2[4]; + uint8_t reserved2[4]; } pvt {}; const uint8_t SV_COUNT = 10; struct PACKED ubx_nav_svinfo { @@ -234,20 +234,20 @@ void GPS_UBlox::publish(const GPS_Data *d) dop.hDOP = 121; dop.nDOP = 65535; dop.eDOP = 65535; - + pvt.itow = gps_tow.ms; - pvt.year = 0; + pvt.year = 0; pvt.month = 0; pvt.day = 0; pvt.hour = 0; pvt.min = 0; - pvt.sec = 0; + pvt.sec = 0; pvt.valid = 0; // invalid utc date - pvt.t_acc = 0; - pvt.nano = 0; + pvt.t_acc = 0; + pvt.nano = 0; pvt.fix_type = d->have_lock? 0x3 : 0; pvt.flags = 0b10000011; // carrsoln=fixed, psm = na, diffsoln and fixok - pvt.flags2 =0; + pvt.flags2 =0; pvt.num_sv = d->have_lock ? _sitl->gps_numsats[instance] : 3; pvt.lon = d->longitude * 1.0e7; pvt.lat = d->latitude * 1.0e7; @@ -258,11 +258,11 @@ void GPS_UBlox::publish(const GPS_Data *d) pvt.velN = 1000.0f * d->speedN; pvt.velE = 1000.0f * d->speedE; pvt.velD = 1000.0f * d->speedD; - pvt.gspeed = norm(d->speedN, d->speedE) * 1000; - pvt.head_mot = ToDeg(atan2f(d->speedE, d->speedN)) * 1.0e5; - pvt.s_acc = 40; - pvt.head_acc = 38 * 1.0e5; - pvt.p_dop = 65535; + pvt.gspeed = norm(d->speedN, d->speedE) * 1000; + pvt.head_mot = ToDeg(atan2f(d->speedE, d->speedN)) * 1.0e5; + pvt.s_acc = 40; + pvt.head_acc = 38 * 1.0e5; + pvt.p_dop = 65535; memset(pvt.reserved1, '\0', ARRAY_SIZE(pvt.reserved1)); pvt.headVeh = 0; memset(pvt.reserved2, '\0', ARRAY_SIZE(pvt.reserved2)); From 97417a1038489b512126f178ae8b6d21ed41f492 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Nov 2023 07:19:24 +1100 Subject: [PATCH 474/499] SITL: rename SITL::GPS_GSOF to SITL::GPS_Trimble --- libraries/SITL/SIM_GPS.cpp | 8 ++++---- libraries/SITL/SIM_GPS.h | 4 ++-- libraries/SITL/SIM_GPS_Trimble.cpp | 16 ++++++++-------- libraries/SITL/SIM_GPS_Trimble.h | 8 ++++---- libraries/SITL/SIM_config.h | 4 ++-- libraries/SITL/SITL.cpp | 2 +- 6 files changed, 21 insertions(+), 21 deletions(-) diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 9ec9484a4460ee..2d8d6dbdb525de 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -18,7 +18,7 @@ #include #include "SIM_GPS_FILE.h" -#include "SIM_GPS_GSOF.h" +#include "SIM_GPS_Trimble.h" #include "SIM_GPS_MSP.h" #include "SIM_GPS_NMEA.h" #include "SIM_GPS_NOVA.h" @@ -201,9 +201,9 @@ void GPS::check_backend_allocation() break; #endif -#if AP_SIM_GPS_GSOF_ENABLED - case Type::GSOF: - backend = new GPS_GSOF(*this, instance); +#if AP_SIM_GPS_TRIMBLE_ENABLED + case Type::TRIMBLE: + backend = new GPS_Trimble(*this, instance); break; #endif diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index 8e6ccad06b1f13..0cbda828ec1d6d 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -114,8 +114,8 @@ class GPS : public SerialDevice { #if AP_SIM_GPS_SBP2_ENABLED SBP2 = 9, #endif -#if AP_SIM_GPS_GSOF_ENABLED - GSOF = 11, // matches GPS_TYPE +#if AP_SIM_GPS_TRIMBLE_ENABLED + TRIMBLE = 11, // matches GPS_TYPE #endif #if AP_SIM_GPS_MSP_ENABLED MSP = 19, diff --git a/libraries/SITL/SIM_GPS_Trimble.cpp b/libraries/SITL/SIM_GPS_Trimble.cpp index e1315f2b4a551e..6c3b41c80cb14f 100644 --- a/libraries/SITL/SIM_GPS_Trimble.cpp +++ b/libraries/SITL/SIM_GPS_Trimble.cpp @@ -1,8 +1,8 @@ #include "SIM_config.h" -#if AP_SIM_GPS_GSOF_ENABLED +#if AP_SIM_GPS_TRIMBLE_ENABLED -#include "SIM_GPS_GSOF.h" +#include "SIM_GPS_Trimble.h" #include #include @@ -11,7 +11,7 @@ using namespace SITL; -void GPS_GSOF::publish(const GPS_Data *d) +void GPS_Trimble::publish(const GPS_Data *d) { // This logic is to populate output buffer only with enabled channels. // It also only sends each channel at the configured rate. @@ -456,7 +456,7 @@ void DCOL_Parser::reset() { } -void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) +void GPS_Trimble::send_gsof(const uint8_t *buf, const uint16_t size) { // All Trimble "Data Collector" packets, including GSOF, are comprised of three fields: // * A fixed-length packet header (dcol_header) @@ -532,7 +532,7 @@ void GPS_GSOF::send_gsof(const uint8_t *buf, const uint16_t size) } } -uint64_t GPS_GSOF::gsof_pack_double(const double& src) +uint64_t GPS_Trimble::gsof_pack_double(const double& src) { uint64_t dst; static_assert(sizeof(src) == sizeof(dst)); @@ -541,7 +541,7 @@ uint64_t GPS_GSOF::gsof_pack_double(const double& src) return dst; } -uint32_t GPS_GSOF::gsof_pack_float(const float& src) +uint32_t GPS_Trimble::gsof_pack_float(const float& src) { uint32_t dst; static_assert(sizeof(src) == sizeof(dst)); @@ -550,7 +550,7 @@ uint32_t GPS_GSOF::gsof_pack_float(const float& src) return dst; } -void GPS_GSOF::update_read() { +void GPS_Trimble::update_read() { // Technically, the max command is slightly larger. // This will only slightly slow the response for packets that big. char c[MAX_PAYLOAD_SIZE]; @@ -566,4 +566,4 @@ void GPS_GSOF::update_read() { } } -#endif // AP_SIM_GPS_GSOF_ENABLED +#endif // AP_SIM_GPS_TRIMBLE_ENABLED diff --git a/libraries/SITL/SIM_GPS_Trimble.h b/libraries/SITL/SIM_GPS_Trimble.h index 17807815377a31..d1c9a41d7eac90 100644 --- a/libraries/SITL/SIM_GPS_Trimble.h +++ b/libraries/SITL/SIM_GPS_Trimble.h @@ -2,7 +2,7 @@ #include "SIM_config.h" -#if AP_SIM_GPS_GSOF_ENABLED +#if AP_SIM_GPS_TRIMBLE_ENABLED #include "SIM_GPS.h" @@ -124,9 +124,9 @@ class DCOL_Parser { void reset(); }; -class GPS_GSOF : public GPS_Backend, public DCOL_Parser { +class GPS_Trimble : public GPS_Backend, public DCOL_Parser { public: - CLASS_NO_COPY(GPS_GSOF); + CLASS_NO_COPY(GPS_Trimble); using GPS_Backend::GPS_Backend; @@ -146,4 +146,4 @@ class GPS_GSOF : public GPS_Backend, public DCOL_Parser { }; -#endif // AP_SIM_GPS_GSOF_ENABLED +#endif // AP_SIM_GPS_TRIMBLE_ENABLED diff --git a/libraries/SITL/SIM_config.h b/libraries/SITL/SIM_config.h index 7c760ee4bfa493..4eb427c0ae3f10 100644 --- a/libraries/SITL/SIM_config.h +++ b/libraries/SITL/SIM_config.h @@ -51,8 +51,8 @@ #define AP_SIM_GPS_FILE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX) #endif -#ifndef AP_SIM_GPS_GSOF_ENABLED -#define AP_SIM_GPS_GSOF_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED +#ifndef AP_SIM_GPS_TRIMBLE_ENABLED +#define AP_SIM_GPS_TRIMBLE_ENABLED AP_SIM_GPS_BACKEND_DEFAULT_ENABLED #endif #ifndef AP_SIM_GPS_MSP_ENABLED diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 9d70ad013aab3e..c516c5acb8b9dd 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -499,7 +499,7 @@ const AP_Param::GroupInfo SIM::var_gps[] = { // @Param: GPS_TYPE // @DisplayName: GPS 1 type // @Description: Sets the type of simulation used for GPS 1 - // @Values: 0:None, 1:UBlox, 5:NMEA, 6:SBP, 7:File, 8:Nova, 9:SBP, 10:GSOF, 19:MSP + // @Values: 0:None, 1:UBlox, 5:NMEA, 6:SBP, 7:File, 8:Nova, 9:SBP, 10:Trimble, 19:MSP // @User: Advanced AP_GROUPINFO("GPS_TYPE", 3, SIM, gps_type[0], GPS::Type::UBLOX), // @Param: GPS_BYTELOSS From 483ef18087672c557ef184732e631115d40a1eab Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 25 Nov 2023 23:38:25 +0000 Subject: [PATCH 475/499] Plane: ignore invalid pilot throttle --- ArduPlane/reverse_thrust.cpp | 8 ++++++++ ArduPlane/servos.cpp | 4 +--- 2 files changed, 9 insertions(+), 3 deletions(-) diff --git a/ArduPlane/reverse_thrust.cpp b/ArduPlane/reverse_thrust.cpp index f64f37b276d6b3..16dc514b547646 100644 --- a/ArduPlane/reverse_thrust.cpp +++ b/ArduPlane/reverse_thrust.cpp @@ -125,6 +125,10 @@ bool Plane::have_reverse_thrust(void) const */ float Plane::get_throttle_input(bool no_deadzone) const { + if (!rc().has_valid_input()) { + // Return 0 if there is no valid input + return 0.0; + } float ret; if (no_deadzone) { ret = channel_throttle->get_control_in_zero_dz(); @@ -143,6 +147,10 @@ float Plane::get_throttle_input(bool no_deadzone) const */ float Plane::get_adjusted_throttle_input(bool no_deadzone) const { + if (!rc().has_valid_input()) { + // Return 0 if there is no valid input + return 0.0; + } if ((plane.channel_throttle->get_type() != RC_Channel::ControlType::RANGE) || (flight_option_enabled(FlightOptions::CENTER_THROTTLE_TRIM)) == 0) { return get_throttle_input(no_deadzone); diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 729e67089e528a..4f2aa9c4864983 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -551,9 +551,7 @@ void Plane::set_servos_controlled(void) control_mode == &mode_fbwa || control_mode == &mode_autotune) { // a manual throttle mode - if (!rc().has_valid_input()) { - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, g.throttle_passthru_stabilize ? 0.0 : MAX(min_throttle,0)); - } else if (g.throttle_passthru_stabilize) { + if (g.throttle_passthru_stabilize) { // manual pass through of throttle while in FBWA or // STABILIZE mode with THR_PASS_STAB set SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true)); From 41f61da0d9668f014553e7208ee1ebf62916742d Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 28 Nov 2023 18:11:21 +0000 Subject: [PATCH 476/499] Plane: Quadplane: add `get_throttle_input` method that behaves the same as Plane::get_throttle_input did --- ArduPlane/quadplane.cpp | 24 +++++++++++++++++++----- ArduPlane/quadplane.h | 3 +++ 2 files changed, 22 insertions(+), 5 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 0a5c724fc82b65..48259c89a4462a 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1219,7 +1219,7 @@ bool QuadPlane::is_flying_vtol(void) const } if (plane.control_mode->is_vtol_man_mode()) { // in manual flight modes only consider aircraft landed when pilot demanded throttle is zero - return is_positive(plane.get_throttle_input()); + return is_positive(get_throttle_input()); } if (in_vtol_mode() && millis() - landing_detect.lower_limit_start_ms > 5000) { // use landing detector @@ -1289,7 +1289,7 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const const auto rudder_in = plane.channel_rudder->get_control_in(); bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && air_mode_active(); if (!manual_air_mode && - !is_positive(plane.get_throttle_input()) && + !is_positive(get_throttle_input()) && (!plane.control_mode->does_auto_throttle() || motors->limit.throttle_lower) && plane.arming.get_rudder_arming_type() == AP_Arming::RudderArming::ARMDISARM && rudder_in < 0 && @@ -1366,7 +1366,7 @@ float QuadPlane::get_pilot_desired_climb_rate_cms(void) const */ void QuadPlane::init_throttle_wait(void) { - if (plane.get_throttle_input() >= 10 || + if (get_throttle_input() >= 10 || plane.is_flying()) { throttle_wait = false; } else { @@ -1920,7 +1920,7 @@ void QuadPlane::update_throttle_suppression(void) consider non-zero throttle to mean that pilot is commanding takeoff unless in a manual thottle mode */ - if (!is_zero(plane.get_throttle_input()) && + if (!is_zero(get_throttle_input()) && (rc().arming_check_throttle() || plane.control_mode->is_vtol_man_throttle() || plane.channel_throttle->norm_input_dz() > 0)) { @@ -4061,7 +4061,7 @@ void QuadPlane::update_throttle_mix(void) if (plane.control_mode->is_vtol_man_throttle()) { // manual throttle - if (!is_positive(plane.get_throttle_input()) && !air_mode_active()) { + if (!is_positive(get_throttle_input()) && !air_mode_active()) { attitude_control->set_throttle_mix_min(); } else { attitude_control->set_throttle_mix_man(); @@ -4729,4 +4729,18 @@ bool QuadPlane::should_disable_TECS() const return false; } +// Get pilot throttle input with deadzone, this will return 50% throttle in failsafe! +// This is a re-implmentation of Plane::get_throttle_input +// Ignoring the no_deadzone case means we don't need to check for valid RC +// This is handled by Plane::control_failsafe setting of control in +float QuadPlane::get_throttle_input() const +{ + float ret = plane.channel_throttle->get_control_in(); + if (plane.reversed_throttle) { + // RC option for reverse throttle has been set + ret = -ret; + } + return ret; +} + #endif // HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index b919be2c445869..ad5e6251af2df8 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -190,6 +190,9 @@ class QuadPlane */ bool should_disable_TECS() const; + // Get pilot throttle input with deadzone, this will return 50% throttle in failsafe! + float get_throttle_input() const; + private: AP_AHRS &ahrs; From 9394a7b26bff477fa4ca5a92701a402ddf47a9e9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Nov 2023 09:16:22 +1100 Subject: [PATCH 477/499] AP_RangeFinder: use boolean uartdriver read method --- .../AP_RangeFinder/AP_RangeFinder_BLPing.cpp | 7 +++---- .../AP_RangeFinder_Benewake.cpp | 10 ++++------ .../AP_RangeFinder/AP_RangeFinder_Lanbao.cpp | 7 +++---- .../AP_RangeFinder_LeddarVu8.cpp | 11 +++++----- .../AP_RangeFinder_LightWareSerial.cpp | 9 +++++---- .../AP_RangeFinder_MaxsonarSerialLV.cpp | 8 +++++--- .../AP_RangeFinder/AP_RangeFinder_NMEA.cpp | 8 +++++--- .../AP_RangeFinder_TeraRanger_Serial.cpp | 10 ++++------ .../AP_RangeFinder_USD1_Serial.cpp | 20 +++++++++---------- .../AP_RangeFinder/AP_RangeFinder_Wasp.cpp | 8 +++++--- 10 files changed, 49 insertions(+), 49 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp index 3cd40aa298e734..e7776e0f955745 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_BLPing.cpp @@ -61,10 +61,9 @@ bool AP_RangeFinder_BLPing::get_reading(float &reading_m) } averageStruct; // read any available lines from the lidar - int16_t nbytes = uart->available(); - while (nbytes-- > 0) { - const int16_t b = uart->read(); - if (b < 0) { + for (auto i=0; i<8192; i++) { + uint8_t b; + if (!uart->read(b)) { break; } if (protocol.parse_byte(b) == PingProtocol::MessageId::DISTANCE_SIMPLE) { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp index ceea2fd16815fa..f04056588ddb06 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Benewake.cpp @@ -59,13 +59,11 @@ bool AP_RangeFinder_Benewake::get_reading(float &reading_m) uint16_t count_out_of_range = 0; // read any available lines from the lidar - int16_t nbytes = uart->available(); - while (nbytes-- > 0) { - int16_t r = uart->read(); - if (r < 0) { - continue; + for (auto j=0; j<8192; j++) { + uint8_t c; + if (!uart->read(c)) { + break; } - uint8_t c = (uint8_t)r; // if buffer is empty and this byte is 0x59, add to buffer if (linebuf_len == 0) { if (c == BENEWAKE_FRAME_HEADER) { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.cpp index d59b030e50e35e..16c37db38f0420 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lanbao.cpp @@ -46,10 +46,9 @@ bool AP_RangeFinder_Lanbao::get_reading(float &reading_m) // format is: [ 0xA5 | 0x5A | distance-MSB-mm | distance-LSB-mm | crc16 ] // read any available lines from the lidar - int16_t nbytes = uart->available(); - while (nbytes-- > 0) { - int16_t b = uart->read(); - if (b == -1) { + for (auto i=0; i<8192; i++) { + uint8_t b; + if (!uart->read(b)) { break; } if (buf_len == 0 && b != 0xA5) { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.cpp index 04e38624e0e428..3d90877d838803 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarVu8.cpp @@ -51,13 +51,12 @@ bool AP_RangeFinder_LeddarVu8::get_reading(float &reading_m) bool latest_dist_valid = false; // read any available characters from the lidar - int16_t nbytes = uart->available(); - while (nbytes-- > 0) { - int16_t r = uart->read(); - if (r < 0) { - continue; + for (auto i=0; i<8192; i++) { + uint8_t b; + if (!uart->read(b)) { + break; } - if (parse_byte((uint8_t)r, latest_dist_valid, latest_dist_cm)) { + if (parse_byte(b, latest_dist_valid, latest_dist_cm)) { if (latest_dist_valid) { sum_cm += latest_dist_cm; count++; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp index 9636b47bf27003..61c2ed9c2d9751 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp @@ -40,10 +40,11 @@ bool AP_RangeFinder_LightWareSerial::get_reading(float &reading_m) const int16_t distance_cm_max = max_distance_cm(); // read any available lines from the lidar - int16_t nbytes = uart->available(); - while (nbytes-- > 0) { - char c = uart->read(); - + for (auto i=0; i<8192; i++) { + uint8_t c; + if (!uart->read(c)) { + break; + } // use legacy protocol if (protocol_state == ProtocolState::UNKNOWN || protocol_state == ProtocolState::LEGACY) { if (c == '\r') { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp index 7f0173947c61df..50abcc6bceae77 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp @@ -42,11 +42,13 @@ bool AP_RangeFinder_MaxsonarSerialLV::get_reading(float &reading_m) } int32_t sum = 0; - int16_t nbytes = uart->available(); uint16_t count = 0; - while (nbytes-- > 0) { - char c = uart->read(); + for (auto i=0; i<8192; i++) { + uint8_t c; + if (!uart->read(c)) { + break; + } if (c == '\r') { linebuf[linebuf_len] = 0; sum += (int)atoi(linebuf); diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp index 61945ca7c3a1f1..bc6a3cf3911581 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_NMEA.cpp @@ -32,9 +32,11 @@ bool AP_RangeFinder_NMEA::get_reading(float &reading_m) // read any available lines from the lidar float sum = 0.0f; uint16_t count = 0; - int16_t nbytes = uart->available(); - while (nbytes-- > 0) { - char c = uart->read(); + for (auto i=0; i<8192; i++) { + uint8_t c; + if (!uart->read(c)) { + break; + } if (decode(c)) { sum += _distance_m; count++; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.cpp index e9a502de79edae..088472b6b8387b 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_TeraRanger_Serial.cpp @@ -54,13 +54,11 @@ bool AP_RangeFinder_TeraRanger_Serial::get_reading(float &reading_m) uint16_t bad_read = 0; // read any available lines from the lidar - int16_t nbytes = uart->available(); - while (nbytes-- > 0) { - int16_t r = uart->read(); - if (r < 0) { - continue; + for (auto i=0; i<8192; i++) { + uint8_t c; + if (!uart->read(c)) { + break; } - uint8_t c = (uint8_t)r; // if buffer is empty and this byte is 0x57, add to buffer if (linebuf_len == 0) { if (c == FRAME_HEADER) { diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.cpp index 04d8c063298734..26328657d11888 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_USD1_Serial.cpp @@ -39,11 +39,11 @@ bool AP_RangeFinder_USD1_Serial::detect_version(void) uint8_t count = 0; // read any available data from USD1_Serial - int16_t nbytes = uart->available(); - - while (nbytes-- > 0) { - uint8_t c = uart->read(); - + for (auto i=0; i<8192; i++) { + uint8_t c; + if (!uart->read(c)) { + break; + } if (((c == USD1_HDR_V0) || (c == USD1_HDR)) && !hdr_found) { byte1 = c; hdr_found = true; @@ -121,11 +121,11 @@ bool AP_RangeFinder_USD1_Serial::get_reading(float &reading_m) uint16_t count = 0; bool hdr_found = false; - int16_t nbytes = uart->available(); - - while (nbytes-- > 0) { - uint8_t c = uart->read(); - + for (auto i=0; i<8192; i++) { + uint8_t c; + if (!uart->read(c)) { + break; + } if ((c == _header) && !hdr_found) { // located header byte _linebuf_len = 0; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp index cda423c79b11a2..5885b2af146254 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Wasp.cpp @@ -86,9 +86,11 @@ bool AP_RangeFinder_Wasp::get_reading(float &reading_m) { // read any available lines from the lidar float sum = 0; uint16_t count = 0; - int16_t nbytes = uart->available(); - while (nbytes-- > 0) { - char c = uart->read(); + for (auto i=0; i<8192; i++) { + uint8_t c; + if (!uart->read(c)) { + break; + } if (c == '\n') { linebuf[linebuf_len] = 0; linebuf_len = 0; From d34e6049c96ce72dbbd20e37cfa45c36300f259b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Nov 2023 13:02:03 +1100 Subject: [PATCH 478/499] AP_Math: rename crc_sum8 to crc_sum8_with_carry the name "sum8" is usually used for "sum all bytes into a uint8_t discarding carry" --- libraries/AP_Math/crc.cpp | 2 +- libraries/AP_Math/crc.h | 6 ++++-- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Math/crc.cpp b/libraries/AP_Math/crc.cpp index 0b283b05153571..985a02c290baa4 100644 --- a/libraries/AP_Math/crc.cpp +++ b/libraries/AP_Math/crc.cpp @@ -481,7 +481,7 @@ uint32_t crc_crc24(const uint8_t *bytes, uint16_t len) } // simple 8 bit checksum used by FPort -uint8_t crc_sum8(const uint8_t *p, uint8_t len) +uint8_t crc_sum8_with_carry(const uint8_t *p, uint8_t len) { uint16_t sum = 0; for (uint8_t i=0; i From 4ede307be2a0814006c8d0b7760126fda9a743c0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 29 Nov 2023 13:02:03 +1100 Subject: [PATCH 479/499] AP_RCProtocol: rename crc_sum8 to crc_sum8_with_carry the name "sum8" is usually used for "sum all bytes into a uint8_t discarding carry" --- libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp | 4 ++-- libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp index 08bc5a06fa7912..c16e2c2b4592a8 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp @@ -179,7 +179,7 @@ void AP_RCProtocol_FPort::decode_downlink(const FPort_Frame &frame) buf[3] = telem_data.packet.appid & 0xFF; buf[4] = telem_data.packet.appid >> 8; memcpy(&buf[5], &telem_data.packet.data, 4); - buf[9] = crc_sum8(&buf[0], 9); + buf[9] = crc_sum8_with_carry(&buf[0], 9); // perform byte stuffing per FPort spec uint8_t len = 0; @@ -307,7 +307,7 @@ void AP_RCProtocol_FPort::_process_byte(uint32_t timestamp_us, uint8_t b) bool AP_RCProtocol_FPort::check_checksum(void) { const uint8_t len = byte_input.buf[1]+2; - return crc_sum8(&byte_input.buf[1], len) == 0x00; + return crc_sum8_with_carry(&byte_input.buf[1], len) == 0x00; } // support byte input diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp index dc9eceb61f8dd2..2631f51d030254 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort2.cpp @@ -179,7 +179,7 @@ void AP_RCProtocol_FPort2::decode_downlink(const FPort2_Frame &frame) // get fresh telem_data in the next call telem_data.available = false; } - buf[9] = crc_sum8(&buf[1], 8); + buf[9] = crc_sum8_with_carry(&buf[1], 8); uart->write(buf, sizeof(buf)); #endif @@ -286,7 +286,7 @@ void AP_RCProtocol_FPort2::_process_byte(uint32_t timestamp_us, uint8_t b) // check checksum byte bool AP_RCProtocol_FPort2::check_checksum(void) { - return crc_sum8(&byte_input.buf[1], byte_input.control_len-1) == 0; + return crc_sum8_with_carry(&byte_input.buf[1], byte_input.control_len-1) == 0; } // support byte input From 46298052b67672eb0dcc9c2a25e6d4d2096665b4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 24 Nov 2023 21:26:19 +0900 Subject: [PATCH 480/499] AP_Scripting: simplify Rover quick tune Only tunes FF. P and I are set as ratio to FF --- .../AP_Scripting/applets/rover-quicktune.lua | 401 ++++++------------ .../AP_Scripting/applets/rover-quicktune.md | 79 ++-- 2 files changed, 152 insertions(+), 328 deletions(-) diff --git a/libraries/AP_Scripting/applets/rover-quicktune.lua b/libraries/AP_Scripting/applets/rover-quicktune.lua index 15e3410a56bcc9..0d09c6f5f921c9 100644 --- a/libraries/AP_Scripting/applets/rover-quicktune.lua +++ b/libraries/AP_Scripting/applets/rover-quicktune.lua @@ -1,6 +1,6 @@ --[[ -Rover QuickTune tunes the steering (aka turn rate), speed and position controller velocity gains for rovers and boats +Rover QuickTune tunes the steering (aka turn rate) and speed controller gains for rovers and boats The script is designed to be used in Circle mode and updates the following parameters @@ -13,9 +13,6 @@ ATC_SPEED_I ATC_SPEED_D CRUISE_SPEED CRUISE_THROTTLE -PSC_VEL_P -PSC_VEL_I -PSC_VEL_D See the accompanying rover-quiktune.md file for instructions on how to use @@ -24,8 +21,9 @@ See the accompanying rover-quiktune.md file for instructions on how to use -- global definitions local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} -local PARAM_TABLE_KEY = 12 +local PARAM_TABLE_KEY = 15 local PARAM_TABLE_PREFIX = "RTUN_" +local PARAM_TABLE_SIZE = 11 -- bind a parameter to a variable function bind_param(name) @@ -41,7 +39,7 @@ function bind_add_param(name, idx, default_value) end -- setup quicktune specific parameters -assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 12), "RTun: could not add param table") +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, PARAM_TABLE_SIZE), "RTun: could not add param table") --[[ // @Param: RTUN_ENABLE @@ -50,72 +48,70 @@ assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 12), "RTun: could no // @Values: 0:Disabled,1:Enabled // @User: Standard --]] -local RTUN_ENABLE = bind_add_param('ENABLE', 1, 1) +local RTUN_ENABLE = bind_add_param('ENABLE', 1, 1) --[[ // @Param: RTUN_AXES // @DisplayName: Rover Quicktune axes // @Description: axes to tune - // @Bitmask: 0:Steering,1:Speed,2:Velocity + // @Bitmask: 0:Steering,1:Speed // @User: Standard --]] -local RTUN_AXES = bind_add_param('AXES', 2, 7) +local RTUN_AXES = bind_add_param('AXES', 2, 3) --[[ - // @Param: RTUN_DOUBLE_TIME - // @DisplayName: Rover Quicktune doubling time - // @Description: Time to double a tuning parameter. Raise this for a slower tune. - // @Range: 5 20 - // @Units: s + // @Param: RTUN_STR_FFRATIO + // @DisplayName: Rover Quicktune Steering Rate FeedForward ratio + // @Description: Ratio between measured response and FF gain. Raise this to get a higher FF gain + // @Range: 0 1.0 // @User: Standard --]] -local RTUN_DOUBLE_TIME = bind_add_param('DOUBLE_TIME', 3, 10) +local RTUN_STR_FFRATIO = bind_add_param('STR_FFRATIO', 3, 0.9) --[[ - // @Param: RTUN_PD_GAINMARG - // @DisplayName: Rover Quicktune P and D gain margin - // @Description: Reduction in P and D gain after oscillation detected. Raise this number to get a more conservative tune - // @Range: 20 90 - // @Units: % + // @Param: RTUN_STR_P_RATIO + // @DisplayName: Rover Quicktune Steering FF to P ratio + // @Description: Ratio between steering FF and P gains. Raise this to get a higher P gain, 0 to leave P unchanged + // @Range: 0 2.0 // @User: Standard --]] -local RTUN_PD_GAINMARG = bind_add_param('PD_GAINMARG', 4, 80) +local RTUN_STR_P_RATIO = bind_add_param('STR_P_RATIO', 4, 0.5) --[[ - // @Param: RTUN_OSC_SMAX - // @DisplayName: Rover Quicktune oscillation rate threshold - // @Description: Threshold for oscillation detection. A lower value will lead to a more conservative tune. - // @Range: 1 10 + // @Param: RTUN_STR_I_RATIO + // @DisplayName: Rover Quicktune Steering FF to I ratio + // @Description: Ratio between steering FF and I gains. Raise this to get a higher I gain, 0 to leave I unchanged + // @Range: 0 2.0 // @User: Standard --]] -local RTUN_OSC_SMAX = bind_add_param('OSC_SMAX', 5, 1) +local RTUN_STR_I_RATIO = bind_add_param('STR_I_RATIO', 5, 0.5) --[[ - // @Param: RTUN_SPD_P_MAX - // @DisplayName: Rover Quicktune Speed P max - // @Description: Maximum value for speed P gain - // @Range: 0.1 10 + // @Param: RTUN_SPD_FFRATIO + // @DisplayName: Rover Quicktune Speed FeedForward (equivalent) ratio + // @Description: Ratio between measured response and CRUISE_THROTTLE value. Raise this to get a higher CRUISE_THROTTLE value + // @Range: 0 1.0 // @User: Standard --]] -local RTUN_SPD_P_MAX = bind_add_param('SPD_P_MAX', 6, 5.0) +local RTUN_SPD_FFRATIO = bind_add_param('SPD_FFRATIO', 6, 1.0) --[[ - // @Param: RTUN_SPD_D_MAX - // @DisplayName: Rover Quicktune Speed D max - // @Description: Maximum value for speed D gain - // @Range: 0.001 1 + // @Param: RTUN_SPD_P_RATIO + // @DisplayName: Rover Quicktune Speed FF to P ratio + // @Description: Ratio between speed FF and P gain. Raise this to get a higher P gain, 0 to leave P unchanged + // @Range: 0 2.0 // @User: Standard --]] -local RTUN_SPD_D_MAX = bind_add_param('SPD_D_MAX', 7, 0.5) +local RTUN_SPD_P_RATIO = bind_add_param('SPD_P_RATIO', 7, 1.0) --[[ - // @Param: RTUN_PI_RATIO - // @DisplayName: Rover Quicktune PI ratio - // @Description: Ratio between P and I gains. Raise this to get a lower I gain, 0 to disable - // @Range: 0.5 1.0 + // @Param: RTUN_SPD_I_RATIO + // @DisplayName: Rover Quicktune Speed FF to I ratio + // @Description: Ratio between speed FF and I gain. Raise this to get a higher I gain, 0 to leave I unchanged + // @Range: 0 2.0 // @User: Standard --]] -local RTUN_PI_RATIO = bind_add_param('PI_RATIO', 8, 1.0) +local RTUN_SPD_I_RATIO = bind_add_param('SPD_I_RATIO', 8, 1.0) --[[ // @Param: RTUN_AUTO_FILTER @@ -133,7 +129,7 @@ local RTUN_AUTO_FILTER = bind_add_param('AUTO_FILTER', 9, 1) // @Units: s // @User: Standard --]] -local RTUN_AUTO_SAVE = bind_add_param('AUTO_SAVE', 10, 0) +local RTUN_AUTO_SAVE = bind_add_param('AUTO_SAVE', 10, 5) --[[ // @Param: RTUN_RC_FUNC @@ -144,16 +140,6 @@ local RTUN_AUTO_SAVE = bind_add_param('AUTO_SAVE', 10, 0) --]] local RTUN_RC_FUNC = bind_add_param('RC_FUNC', 11, 300) ---[[ - // @Param: RTUN_FF_GAINMARG - // @DisplayName: Rover Quicktune Steering Rate FeedForward gain margin - // @Description: Reduction in Steering Turn Rate FF gain from measured outputs and response. Raise this number to get a more conservative tune - // @Range: 0 80 - // @Units: % - // @User: Standard ---]] -local RTUN_FF_GAINMARG = bind_add_param('FF_GAINMARG', 12, 10) - -- other vehicle parameters used by this script local INS_GYRO_FILTER = bind_param("INS_GYRO_FILTER") local GCS_PID_MASK = bind_param("GCS_PID_MASK") @@ -164,7 +150,7 @@ local RCIN_THROTTLE = rc:get_channel(RCMAP_THROTTLE:get()) -- definitions local UPDATE_RATE_HZ = 40 -- this script updates at 40hz -local STAGE_DELAY = 4.0 -- gains increased every 4 seconds +local AXIS_CHANGE_DELAY = 4.0 -- delay of 4 seconds between axis to allow vehicle to settle local PILOT_INPUT_DELAY = 4.0 -- gains are not updated for 4 seconds after pilot releases sticks local FLTD_MUL = 0.5 -- ATC_STR_RAT_FLTD set to 0.5 * INS_GYRO_FILTER local FLTT_MUL = 0.5 -- ATC_STR_RAT_FLTT set to 0.5 * INS_GYRO_FILTER @@ -179,19 +165,12 @@ function get_time() end -- local variables -local axis_names = { "ATC_STR_RAT", "ATC_SPEED", "PSC_VEL" } -- table of axis that may be tuned +local axis_names = { "ATC_STR_RAT", "ATC_SPEED" } -- table of axis that may be tuned local param_suffixes = { "FF", "P", "I", "D", "FLTT", "FLTD", "FLTE" } -- table of parameters that may be tuned local params_extra = {"CRUISE_SPEED", "CRUISE_THROTTLE"} -- table of extra parameters that may be changed -local params_skip = {"PSC_VEL_FLTT"} -- parameters that should be skipped from saving/restoring (because they do not exist) -local stages = { "D", "P", "FF" } -- table of tuning stages -local stage = stages[1] -- current tuning stage -local last_stage_change = get_time() -- time (in seconds) that stage last changed -local last_gain_report = get_time() -- time of last update to user on parameter gain actively being tuned +local last_axis_change = get_time() -- time (in seconds) that axis last changed local last_pilot_input = get_time() -- time pilot last provided RC input local tune_done_time = nil -- time that tuning completed (used for auto save feature) -local slew_parm = nil -- parameter name being slewed towards a target. params are sometimes slewed to reduce impact on controllers -local slew_delta = 0 -- gain change increment to be applied to parameter being actively tuned -local slew_steps = 0 -- max number of times to increment parameter being actively tuned local axes_done = {} -- list of axes that have been tuned local filters_done = {} -- table recording if filters have been set for each axis local gcs_pid_mask_done = {} -- table recording if GCS_PID_MASK has been set for each axis @@ -213,28 +192,15 @@ local param_saved = {} -- table holding backup of each paramete local param_changed = {} -- table holding whether each param's gain has been saved local need_restore = false -- true if any param's gain has been changed --- check for an item within a table --- returns true if found, false if not found -function in_skip_table(pname) - for _, skip_item in ipairs(params_skip) do - if pname == skip_item then - return true - end - end - return false -end - -- initialise params, params_axis and param_changed tables function init_params_tables() -- add parameters to params dictionary for _, axis in ipairs(axis_names) do for _, suffix in ipairs(param_suffixes) do local pname = axis .. "_" .. suffix - if not in_skip_table(pname) then - params[pname] = bind_param(pname) - params_axis[pname] = axis - param_changed[pname] = false - end + params[pname] = bind_param(pname) + params_axis[pname] = axis + param_changed[pname] = false end end @@ -254,7 +220,8 @@ function reset_axes_done() gcs_pid_mask_done[axis] = false end tune_done_time = nil - stage = stages[1] + init_steering_ff() + init_speed_ff() end -- get all current param values into param_saved dictionary @@ -313,8 +280,6 @@ function setup_gcs_pid_mask(axis) GCS_PID_MASK:set(1) elseif axis == "ATC_SPEED" then GCS_PID_MASK:set(2) - elseif axis == "PSC_VEL" then - GCS_PID_MASK:set(64) else gcs:send_text(MAV_SEVERITY.CRITICAL, string.format("RTun: setup_gcs_pid_mask received unhandled aixs %s", axis)) end @@ -352,93 +317,32 @@ function get_slew_rate(axis) if axis == "ATC_SPEED" then return speed_srate end - if axis == "PSC_VEL" then - local velocity_srate = AR_PosControl:get_srate() - return velocity_srate - end gcs:send_text(MAV_SEVERITY.CRITICAL, string.format("RTUN: get_slew_rate unsupported axis:%s", axis)) return 0.0 end --- move to next stage of tune -function advance_stage(axis) +-- move to next axis of tune +function advance_axis(axis) local now_sec = get_time() - if stage == "D" then - stage = "P" - elseif stage == "P" then - stage = "FF" - else - local prev_axis = get_current_axis() - axes_done[axis] = true - gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: %s tuning done", axis)) - stage = "D" - -- check for tune completion - if prev_axis ~= nil and get_current_axis() == nil then - gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: Tuning DONE")) - tune_done_time = now_sec - end - end - last_stage_change = now_sec + local prev_axis = get_current_axis() + axes_done[axis] = true + -- check for tune completion + if prev_axis ~= nil and get_current_axis() == nil then + gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: Tuning DONE")) + tune_done_time = now_sec + end + last_axis_change = now_sec end --- change a gain +-- change a gain, log and update user function adjust_gain(pname, value) - -- sanity check parameter shouldn't be skipped - if in_skip_table(pname) then - gcs:send_text(MAV_SEVERITY.CRITICAL, string.format("RTun: attempted to update skipped param %s", pname)) - return - end local P = params[pname] + local old_value = P:get() need_restore = true param_changed[pname] = true P:set(value) - if string.sub(pname, -2) == "_P" then - -- if we are updating a P value we may also update I - local ffname = string.gsub(pname, "_P", "_FF") - local FF = params[ffname] - if FF:get() > 0 then - -- if we have any FF on an axis then we don't couple I to P, - -- usually we want I = FF for a one sectond time constant for trim - return - end - -- if PI_RATIO is non-zero then update I - local PI_ratio = RTUN_PI_RATIO:get() - if PI_ratio > 0 then - local iname = string.gsub(pname, "_P", "_I") - local I = params[iname] - new_I_gain = value/PI_ratio - I:set(new_I_gain) - param_changed[iname] = true - write_log(iname) - end - end -end - --- return gain multipler for one loop -function get_gain_mul() - return math.exp(math.log(2.0)/(UPDATE_RATE_HZ*RTUN_DOUBLE_TIME:get())) -end - --- setup parameter slewing. slewing some changes over 2 seconds reduces shock to controllers -function setup_slew_gain(pname, gain) - slew_parm = pname - slew_steps = UPDATE_RATE_HZ / 2 - slew_delta = (gain - params[pname]:get()) / slew_steps -end - --- update parameter slewing. slewing some changes over 2 seconds reduces shock to controllers -function update_slew_gain() - if slew_parm ~= nil then - local P = params[slew_parm] - adjust_gain(slew_parm, P:get()+slew_delta) - write_log(slew_parm) - slew_steps = slew_steps - 1 - -- check if slewing is complete - if slew_steps == 0 then - gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: %s %.3f", slew_parm, P:get())) - slew_parm = nil - end - end + write_log(pname) + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.3f -> %.3f", pname, old_value, value)) end -- log parameter, current gain and current slew rate @@ -449,25 +353,6 @@ function write_log(pname) logger:write("RTUN","SRate,Gain,Param", "ffN", slew_rate, param_gain, pname) end --- return gain limits on a parameter, or 0 for no limit -function gain_limit(pname) - if pname == "ATC_SPEED_P" then - return RTUN_SPD_P_MAX:get() - elseif pname == "ATC_SPEED_D" then - return RTUN_SPD_D_MAX:get() - end - return 0.0 -end - --- check if parameter's gain has reached its limit -function reached_limit(pname, gain) - local limit = gain_limit(pname) - if limit > 0.0 and gain >= limit then - return true - end - return false -end - -- initialise steering ff tuning function init_steering_ff() ff_steering_sum = 0 @@ -476,7 +361,9 @@ function init_steering_ff() end -- run steering turn rate controller feedforward calibration -function update_steering_ff(pname) +-- ff_pname is the FF parameter being tuned +-- returns true once the tuning has completed +function update_steering_ff(ff_pname) -- get steering, turn rate, throttle and speed local steering_out, _ = vehicle:get_steering_and_throttle() local turn_rate_rads = ahrs:get_gyro():z() @@ -502,7 +389,7 @@ function update_steering_ff(pname) ff_turn_rate_sum = ff_turn_rate_sum + math.abs(turn_rate_rads) ff_turn_rate_count = ff_turn_rate_count + 1 if (update_user) then - gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: %s %.0f%% complete", pname, complete_pct)) + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: %s %.0f%% complete", ff_pname, complete_pct)) end else if update_user then @@ -516,28 +403,38 @@ function update_steering_ff(pname) -- check for completion of two rotations of turns data and 10 seconds if complete_pct >= 100 then - local old_gain = params[pname]:get() - local new_gain = (ff_steering_sum / ff_turn_rate_sum) * (1.0-(RTUN_FF_GAINMARG:get()*0.01)) - adjust_gain(pname, new_gain) - write_log(pname) - gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.3f -> %.3f", pname, old_gain, new_gain)) - - -- set I gain equal to FF - local iname = string.gsub(pname, "_FF", "_I") - local I = params[iname] - local I_old_gain = I:get() - I:set(new_gain) - param_changed[iname] = true - write_log(iname) - gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.3f -> %.3f", iname, I_old_gain, new_gain)) + local FF_new_gain = (ff_steering_sum / ff_turn_rate_sum) * RTUN_STR_FFRATIO:get() + adjust_gain(ff_pname, FF_new_gain) + + -- set P gain + if RTUN_STR_P_RATIO:get() > 0 then + local pname = string.gsub(ff_pname, "_FF", "_P") + adjust_gain(pname, FF_new_gain * RTUN_STR_P_RATIO:get()) + end + + -- set I gain + if RTUN_STR_I_RATIO:get() > 0 then + local iname = string.gsub(ff_pname, "_FF", "_I") + adjust_gain(iname, FF_new_gain * RTUN_STR_I_RATIO:get()) + end + return true end return false end +-- initialise speed ff tuning +function init_speed_ff() + ff_throttle_sum = 0 + ff_speed_sum = 0 + ff_speed_count = 0 +end + -- run speed controller feedforward calibration -function update_speed_ff(pname) +-- ff_pname is the FF parameter being tuned +-- returns true once the tuning has completed +function update_speed_ff(ff_pname) -- get steering, turn rate, throttle and speed local _, throttle_out = vehicle:get_steering_and_throttle() local velocity_ned = ahrs:get_velocity_NED() @@ -564,13 +461,13 @@ function update_speed_ff(pname) ff_speed_sum = ff_speed_sum + speed ff_speed_count = ff_speed_count + 1 if (update_user) then - gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: %s %.0f%% complete", pname, complete_pct)) + gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: %s %.0f%% complete", ff_pname, complete_pct)) end else if update_user then if not throttle_ok then gcs:send_text(MAV_SEVERITY.WARNING, string.format("RTun: increase throttle (%d < %d)", math.floor(throttle_out * 100), math.floor(SPEED_FF_THROTTLE_MIN * 100))) - elseif not turnrate_ok then + elseif not speed_ok then gcs:send_text(MAV_SEVERITY.WARNING, string.format("RTun: increase speed (%3.1f < %3.1f)", speed, SPEED_FF_SPEED_MIN)) end end @@ -578,26 +475,28 @@ function update_speed_ff(pname) -- check for 10 seconds of data if complete_pct >= 100 then - local cruise_speed_old = params["CRUISE_SPEED"]:get() local cruise_speed_new = ff_speed_sum / ff_speed_count - local cruise_throttle_old = params["CRUISE_THROTTLE"]:get() - local cruise_throttle_new = (ff_throttle_sum / ff_speed_count) * 100 + local cruise_throttle_new = (ff_throttle_sum / ff_speed_count) * 100 * RTUN_SPD_FFRATIO:get() adjust_gain("CRUISE_SPEED", cruise_speed_new) adjust_gain("CRUISE_THROTTLE", cruise_throttle_new) - write_log("CRUISE_SPEED") - write_log("CRUISE_THROTTLE") - gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.2f -> %.2f", "CRUISE_SPEED", cruise_speed_old, cruise_speed_new)) - gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.1f -> %.1f", "CRUISE_THROTTLE", cruise_throttle_old, cruise_throttle_new)) - - -- set I gain equal to FF - local iname = string.gsub(pname, "_FF", "_I") - local I = params[iname] - local I_old_gain = I:get() - local I_new_gain = ff_throttle_sum / ff_speed_sum - I:set(I_new_gain) - param_changed[iname] = true - write_log(iname) - gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusted %s %.3f -> %.3f", iname, I_old_gain, I_new_gain)) + + -- calculate FF equivalent gain (used for setting P and I below) + local speed_ff_equivalent = (ff_throttle_sum / ff_speed_sum) * RTUN_SPD_FFRATIO:get(); + + -- set P gain + if RTUN_SPD_P_RATIO:get() > 0 then + local pname = string.gsub(ff_pname, "_FF", "_P") + local P_new_gain = speed_ff_equivalent * RTUN_SPD_P_RATIO:get() + adjust_gain(pname, P_new_gain) + end + + -- set I gain + if RTUN_SPD_I_RATIO:get() > 0 then + local iname = string.gsub(ff_pname, "_FF", "_I") + local I_new_gain = speed_ff_equivalent * RTUN_SPD_I_RATIO:get() + adjust_gain(iname, I_new_gain) + end + return true end @@ -663,11 +562,8 @@ function update() return end - -- update param gains for params being slewed towards a target - update_slew_gain() - -- return if we have just changed stages to give time for oscillations to subside - if get_time() - last_stage_change < STAGE_DELAY then + if get_time() - last_axis_change < AXIS_CHANGE_DELAY then return end @@ -710,70 +606,21 @@ function update() end -- get parameter currently being tuned - local srate = get_slew_rate(axis) - local pname = axis .. "_" .. stage - local param = params[pname] + local pname = axis .. "_FF" - if stage == "FF" then - -- feedforward tuning - local ff_done - if axis == "ATC_STR_RAT" then - ff_done = update_steering_ff(pname) - elseif axis == "ATC_SPEED" then - ff_done = update_speed_ff(pname) - elseif axis == "PSC_VEL" then - -- position controller feed-forward is not tuned - ff_done = true - else - gcs:send_text(MAV_SEVERITY.CRITICAL, string.format("RTun: unsupported FF tuning %s", pname)) - ff_done = true - end - if ff_done then - gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: %s tuning done", pname)) - advance_stage(axis) - end + -- feedforward tuning + local ff_done + if axis == "ATC_STR_RAT" then + ff_done = update_steering_ff(pname) + elseif axis == "ATC_SPEED" then + ff_done = update_speed_ff(pname) else - local oscillating = srate > RTUN_OSC_SMAX:get() - local limited = reached_limit(pname, param:get()) - if limited or oscillating then - local reduction = (100.0-RTUN_PD_GAINMARG:get())*0.01 - if not oscillating then - reduction = 1.0 - end - local new_gain = param:get() * reduction - local limit = gain_limit(pname) - if limit > 0.0 and new_gain > limit then - gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: %s passed limit (>%.3f)", pname, limit)) - new_gain = limit - end - local old_gain = param_saved[pname] - if new_gain < old_gain and string.sub(pname,-2) == '_D' then - -- we are lowering a D gain from the original gain. Also lower the P gain by the same amount - -- so that we don't trigger P oscillation. We don't drop P by more than a factor of 2 - local ratio = math.max(new_gain / old_gain, 0.5) - local P_name = string.gsub(pname, "_D", "_P") - local old_P = params[P_name]:get() - local new_P = old_P * ratio - gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: adjusting %s %.3f -> %.3f", P_name, old_P, new_P)) - adjust_gain(P_name, new_P) - write_log(P_name) - end - -- slew gain change over 2 seconds to ease impact on controller - setup_slew_gain(pname, new_gain) - gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: %s tuning done %.3f", pname, new_gain)) - advance_stage(axis) - else - local new_gain = param:get()*get_gain_mul() - if new_gain <= 0.0001 then - new_gain = 0.001 - end - adjust_gain(pname, new_gain) - write_log(pname) - if get_time() - last_gain_report > 3 then - last_gain_report = get_time() - gcs:send_text(MAV_SEVERITY.INFO, string.format("RTun: %s %.3f sr:%.2f", pname, new_gain, srate)) - end - end + gcs:send_text(MAV_SEVERITY.CRITICAL, string.format("RTun: unsupported FF tuning %s", pname)) + ff_done = true + end + if ff_done then + gcs:send_text(MAV_SEVERITY.NOTICE, string.format("RTun: %s tuning done", pname)) + advance_axis(axis) end end diff --git a/libraries/AP_Scripting/applets/rover-quicktune.md b/libraries/AP_Scripting/applets/rover-quicktune.md index 21dc1f647e01da..e80f82a4b65a98 100644 --- a/libraries/AP_Scripting/applets/rover-quicktune.md +++ b/libraries/AP_Scripting/applets/rover-quicktune.md @@ -1,6 +1,6 @@ # Rover QuickTune -Rover QuickTune tunes the steering (aka turn rate), speed and position controller velocity gains for rovers and boats +Rover QuickTune tunes the steering (aka turn rate) and speed controller gains for rovers and boats The script is designed to be used in Circle mode and updates the following parameters @@ -15,14 +15,11 @@ ATC_SPEED_I ATC_SPEED_D CRUISE_SPEED CRUISE_THROTTLE -PSC_VEL_P -PSC_VEL_I -PSC_VEL_D # How To Use Install this script in the autopilot's SD card's APM/scripts directory Set SCR_ENABLE to 1 and reboot the autopilot -Set RTUN_ENABLE to 1. +Set RTUN_ENABLE to 1 (default) Set RCx_OPTION = 300 where "x" refers to the transmitter's 2 or 3 position switch use to start/stop/save tuning. E.g. if channel 6 is used set RC6_OPTION = 300 @@ -30,7 +27,7 @@ use to start/stop/save tuning. E.g. if channel 6 is used set RC6_OPTION = 300 If necessary, the RTUN_RC_FUNC parameter can be set to another number (e.g. 302 for scripting3) to avoid RCx_OPTION conflicts with other scripts. -If only a 2-position switch is available set RTUN_AUTO_SAVE to 1 +By default the tune is saved a few seconds after completion. To control saving of the tune manually set RTUN_AUTO_SAVE to 0 Arm the vehicle and switch to Circle mode Optionally set CIRC_SPEED (or WP_SPEED) to about half the vehicle's max speed @@ -40,23 +37,15 @@ Note the above parmaters only take effect when the vehicle is switched into Circ Move the RC switch to the middle position to begin the tuning process. Text messages should appear on the ground station's messages area showing progress -For P and D gain tuning, the relevant gain is slowly raised until the vehicle begins to oscillate after which the gain is reduced and the script moves onto the next gain. - -For FF tuning, the steering or throttle output are compared to the response for at least 10 seconds. +During tuning the steering or throttle output are compared to the response for at least 10 seconds. A message may appear stating the steering, turn rate, throttle or speed are too low in which case the vehicle speed should be increased (Mission Planner's Action tab "Change Speed" button may be used) -or the radius should be reduced. The velocity FF is not tuned (nor does it need to be). +or the radius should be reduced. By default the gains will be tuned in this order: - - ATC_STR_RAT_D - - ATC_STR_RAT_P and I - - ATC_STR_RAT_FF - - ATC_SPEED_D - - ATC_SPEED_P - - CRUISE_SPEED and CRUISE_THROTTLE - - PSC_VEL_D - - PSC_VEL_P and I +- ATC_STR_RAT_FF, then ATC_STR_RAT_P and I are set to ratios of the FF +- CRUISE_SPEED and CRUISE_THROTTLE, then ATC_SPEED_P and I are set to ratios of the FF The script will also adjust filter settings: @@ -67,7 +56,7 @@ Save the tune by raising the RC switch to the high position If the RC switch is moved high (ie. Save Tune) before the tune is completed the tune will pause, and any parameters completed will be saved and the current value of the one being actively tuned will remain active. You can resume tuning by returning the switch again to the middle position. If the RC switch is moved to the low position, the parameter currently being tuned will be reverted but any previously saved parameters will remain. -If you move the switch to the low position at any time in the tune before using the Tune Save switch position, then all parameters will be reverted to their original values. Parameters will also be reverted if you disarm before saving. +If you move the switch to the low position at any time in the tune before gains are saved, then all parameters will be reverted to their original values. Parameters will also be reverted if you disarm before saving. If the pilot gives steering or throttle input during tuning then tuning is paused for 4 seconds. Tuning restarts once the pilot returns to the input to the neutral position. @@ -86,50 +75,38 @@ By default RCx_OPTIONS of 300 (scripting1) is used ## RTUN_AXES -The axes that will be tuned. The default is 7 meaning steering, speed and velocity -This parameter is a bitmask, so set 1 to tune just steering. 2 for speed. 4 for velocity - -## RTUN_DOUBLE_TIME - -How quickly a gain is raised while tuning. This is the number of seconds -for the gain to double. Most users will want to leave this at the default of 10 seconds. - -## RTUN_PD_GAINMARG - -The percentage P and D gain margin to use. Once the oscillation point is found -the gain is reduced by this percentage. The default of 80% is good for most users. +The axes that will be tuned. The default is 3 meaning steering and speed +This parameter is a bitmask, so set 1 to tune just steering. 2 for just speed -## RTUN_FF_GAINMARG +## RTUN_STR_FFRATIO -The percentage FF gain margin to use. Once the output and response are used to calculate -the ideal feed-forward, the value is reduced by this percentage. The default of 20% is good for most users. +Ratio between measured response and FF gain. Raise this to get a higher FF gain +The default of 0.9 is good for most users. -## RTUN_OSC_SMAX +## RTUN_STR_P_RATIO -The Oscillation threshold in Hertz for detecting oscillation -The default of 5Hz is good for most vehicles but on very large vehicles -you may wish to lower this. For a vehicle of 50kg a value of 3 is likely to be good. -For a vehicle of 100kg a value of 1.5 is likely to be good. +Ratio between steering FF and P gains. Raise this to get a higher P gain, 0 to leave P unchanged +The default of 0.2 is good for most users. -You can tell you have this set too high if you still have visible -oscillations after a parameter has completed tuning. In that case -halve this parameter and try again. +## RTUN_STR_I_RATIO -## RTUN_SPD_P_MAX +Ratio between steering FF and I gains. Raise this to get a higher I gain, 0 to leave I unchanged +The default of 0.2 is good for most users. -The speed controller P gain max (aka ATC_SPEED_P) +## RTUN_SPD_FFRATIO -## RTUN_SPD_D_MAX +Ratio between measured response and CRUISE_THROTTLE value. Raise this to get a higher CRUISE_THROTTLE value +The default of 1.0 is good for most users. -The speed controller D gain max (aka ATC_SPEED_D) +## RTUN_SPD_P_RATIO -## RTUN_PI_RATIO +Ratio between speed FF and P gain. Raise this to get a higher P gain, 0 to leave P unchanged +The default of 1.0 is good for most users. -The ratio for P to I. This should normally be 1, but on some large vehicles a value of up to 3 can be -used if the I term in the PID is causing too much phase lag. +## RTUN_SPD_I_RATIO -If RTUN_RP_PI_RATIO is less than 1 then the I value will not be -changed at all when P is changed. +Ratio between speed FF and I gain. Raise this to get a higher I gain, 0 to leave I unchanged +The default of 1.0 is good for most users. ## RTUN_AUTO_FILTER From e58e8b861dbf4430a0123fecd1549954743f2aae Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 28 Nov 2023 14:18:14 +1100 Subject: [PATCH 481/499] AP_Serialmanager: added IMOUT uart type # Conflicts: # libraries/AP_SerialManager/AP_SerialManager.cpp # libraries/AP_SerialManager/AP_SerialManager.h --- libraries/AP_SerialManager/AP_SerialManager.cpp | 14 +++++++++++++- libraries/AP_SerialManager/AP_SerialManager.h | 1 + .../AP_SerialManager/AP_SerialManager_config.h | 10 ++++++++++ 3 files changed, 24 insertions(+), 1 deletion(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 38b8124aaf6fb2..5b961da0722eac 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -24,6 +24,7 @@ #include #include #include +#include #include "AP_SerialManager.h" #include @@ -209,7 +210,7 @@ const AP_Param::GroupInfo AP_SerialManager::var_info[] = { // @Param: 1_PROTOCOL // @DisplayName: Telem1 protocol selection // @Description: Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details. - // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:Gimbal, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:EFI Serial, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency, 44:IRC Tramp, 45:DDS XRCE + // @Values: -1:None, 1:MAVLink1, 2:MAVLink2, 3:Frsky D, 4:Frsky SPort, 5:GPS, 7:Alexmos Gimbal Serial, 8:Gimbal, 9:Rangefinder, 10:FrSky SPort Passthrough (OpenTX), 11:Lidar360, 13:Beacon, 14:Volz servo out, 15:SBus servo out, 16:ESC Telemetry, 17:Devo Telemetry, 18:OpticalFlow, 19:RobotisServo, 20:NMEA Output, 21:WindVane, 22:SLCAN, 23:RCIN, 24:EFI Serial, 25:LTM, 26:RunCam, 27:HottTelem, 28:Scripting, 29:Crossfire VTX, 30:Generator, 31:Winch, 32:MSP, 33:DJI FPV, 34:AirSpeed, 35:ADSB, 36:AHRS, 37:SmartAudio, 38:FETtecOneWire, 39:Torqeedo, 40:AIS, 41:CoDevESC, 42:DisplayPort, 43:MAVLink High Latency, 44:IRC Tramp, 45:DDS XRCE, 46:IMUDATA // @User: Standard // @RebootRequired: True AP_GROUPINFO("1_PROTOCOL", 1, AP_SerialManager, state[1].protocol, DEFAULT_SERIAL1_PROTOCOL), @@ -600,6 +601,17 @@ void AP_SerialManager::init() // Note init is handled by AP_MSP break; #endif + +#if AP_SERIALMANAGER_IMUOUT_ENABLED + case SerialProtocol_IMUOUT: + uart->begin(state[i].baudrate(), + AP_SERIALMANAGER_IMUOUT_BUFSIZE_RX, + AP_SERIALMANAGER_IMUOUT_BUFSIZE_TX); + AP::ins().set_imu_out_uart(uart); + uart->set_unbuffered_writes(true); + break; +#endif + default: uart->begin(state[i].baudrate()); } diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index 01d5d7bbd45640..b548656297f91c 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -79,6 +79,7 @@ class AP_SerialManager { SerialProtocol_MAVLinkHL = 43, SerialProtocol_Tramp = 44, SerialProtocol_DDS_XRCE = 45, + SerialProtocol_IMUOUT = 46, SerialProtocol_NumProtocols // must be the last value }; diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index 7dbf0c16a8a0cd..801b52a163ae0a 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -21,6 +21,7 @@ #include #include +#include #ifdef HAL_UART_NUM_SERIAL_PORTS #if HAL_UART_NUM_SERIAL_PORTS >= 4 @@ -56,6 +57,10 @@ #define AP_SERIALMANAGER_REGISTER_ENABLED BOARD_FLASH_SIZE > 1024 && (AP_NETWORKING_ENABLED || HAL_ENABLE_DRONECAN_DRIVERS) #endif +#ifndef AP_SERIALMANAGER_IMUOUT_ENABLED +#define AP_SERIALMANAGER_IMUOUT_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL) && AP_INERTIALSENSOR_ENABLED +#endif + // serial ports registered by AP_Networking will use IDs starting at 21 for the first port #define AP_SERIALMANAGER_NET_PORT_1 21 // NET_P1_* @@ -127,3 +132,8 @@ #define AP_SERIALMANAGER_MSP_BUFSIZE_RX 128 #define AP_SERIALMANAGER_MSP_BUFSIZE_TX 256 #define AP_SERIALMANAGER_MSP_BAUD 115200 + +// IMU OUT protocol +#define AP_SERIALMANAGER_IMUOUT_BAUD 921600 +#define AP_SERIALMANAGER_IMUOUT_BUFSIZE_RX 128 +#define AP_SERIALMANAGER_IMUOUT_BUFSIZE_TX 2048 From 604559a8440e7a19765aeafe864d583027e55e87 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 28 Nov 2023 14:32:37 +1100 Subject: [PATCH 482/499] AP_OSD: added new serial manager protocol --- libraries/AP_OSD/AP_OSD_ParamSetting.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_OSD/AP_OSD_ParamSetting.cpp b/libraries/AP_OSD/AP_OSD_ParamSetting.cpp index 95476abd8fb440..6c3d7723a67b92 100644 --- a/libraries/AP_OSD/AP_OSD_ParamSetting.cpp +++ b/libraries/AP_OSD/AP_OSD_ParamSetting.cpp @@ -117,7 +117,7 @@ static const char* SERIAL_PROTOCOL_VALUES[] = { "FSKY_TX", "LID360", "", "BEACN", "VOLZ", "SBUS", "ESC_TLM", "DEV_TLM", "OPTFLW", "RBTSRV", "NMEA", "WNDVNE", "SLCAN", "RCIN", "MGSQRT", "LTM", "RUNCAM", "HOT_TLM", "SCRIPT", "CRSF", "GEN", "WNCH", "MSP", "DJI", "AIRSPD", "ADSB", "AHRS", "AUDIO", "FETTEC", "TORQ", - "AIS", "CD_ESC", "MSP_DP", "MAV_HL", "TRAMP", "DDS" + "AIS", "CD_ESC", "MSP_DP", "MAV_HL", "TRAMP", "DDS", "IMUOUT", }; static_assert(AP_SerialManager::SerialProtocol_NumProtocols == ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), "Wrong size SerialProtocol_NumProtocols"); From e04d1bba9ef8ab5a8f148efb5a6f73bf01f34cd8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 Apr 2020 14:33:59 +1100 Subject: [PATCH 483/499] Tools: added IMU decoder script --- Tools/scripts/imu_uart_decode.py | 135 +++++++++++++++++++++++++++++++ 1 file changed, 135 insertions(+) create mode 100755 Tools/scripts/imu_uart_decode.py diff --git a/Tools/scripts/imu_uart_decode.py b/Tools/scripts/imu_uart_decode.py new file mode 100755 index 00000000000000..e9954620cf906e --- /dev/null +++ b/Tools/scripts/imu_uart_decode.py @@ -0,0 +1,135 @@ +#!/usr/bin/env python3 +''' +script to decode IMU data on a UART +''' + +import socket, struct, serial, sys + +import argparse + +parser = argparse.ArgumentParser(description='decode IMU data from ArduPilot') + +parser.add_argument('--set-file', type=str, default=None, help='replace parameter defaults from a file') +parser.add_argument('--tcp', default=None, help='TCP endpoint as IP:port') +parser.add_argument('--device', default=None, help='serial port to read from') +parser.add_argument('--baudrate', default=921600, help='baudrate for serial port') + +args = parser.parse_args() + +if args.tcp is None and args.device is None: + print("Must specicy --tcp or --device") + sys.exit(1) + +if args.tcp is not None: + server_address = args.tcp.split(':') + sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1) + sock.connect((server_address[0], int(server_address[1]))) +else: + port = serial.Serial(args.device, baudrate=args.baudrate) + +def crc16_from_bytes(bytes, initial=0): + # CRC-16-CCITT + # Initial value: 0xFFFF + # Poly: 0x1021 + # Reverse: no + # Output xor: 0 + # Check string: '123456789' + # Check value: 0x29B1 + + try: + if isinstance(bytes, basestring): # Python 2.7 compatibility + bytes = map(ord, bytes) + except NameError: + if isinstance(bytes, str): # This branch will be taken on Python 3 + bytes = map(ord, bytes) + + crc = initial + for byte in bytes: + crc ^= byte << 8 + for bit in range(8): + if crc & 0x8000: + crc = ((crc << 1) ^ 0x1021) & 0xFFFF + else: + crc = (crc << 1) & 0xFFFF + return crc & 0xFFFF + +class Packet(object): + def __init__(self, pkt): + '''parse the packet''' + self.pkt = pkt + self.delta_velocity = [0.0]*3 + self.delta_angle = [0.0]*3 + (self.magic, + self.length, + self.timestamp_us, + self.delta_velocity[0], + self.delta_velocity[1], + self.delta_velocity[2], + self.delta_angle[0], + self.delta_angle[1], + self.delta_angle[2], + self.delta_velocity_dt, + self.delta_angle_dt, + self.counter, + self.crc) = struct.unpack(" Date: Tue, 28 Nov 2023 14:20:19 +1100 Subject: [PATCH 484/499] AP_InertialSensor: added support for writing raw IMU data to a UART this is for supporting external visual odomotry systems which need the IMU data to correctly process image data # Conflicts: # libraries/AP_InertialSensor/AP_InertialSensor.cpp --- .../AP_InertialSensor/AP_InertialSensor.cpp | 49 +++++++++++++++++++ .../AP_InertialSensor/AP_InertialSensor.h | 12 +++++ 2 files changed, 61 insertions(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index f4de7b9f05f5dd..e8bfb60eaed66d 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -1882,6 +1882,11 @@ void AP_InertialSensor::update(void) GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "TCAL finished all IMUs"); } #endif +#if AP_SERIALMANAGER_IMUOUT_ENABLED + if (uart.imu_out_uart) { + send_uart_data(); + } +#endif } /* @@ -2614,6 +2619,50 @@ void AP_InertialSensor::kill_imu(uint8_t imu_idx, bool kill_it) } #endif // AP_INERTIALSENSOR_KILL_IMU_ENABLED +#if AP_SERIALMANAGER_IMUOUT_ENABLED +/* + setup a UART for sending external data + */ +void AP_InertialSensor::set_imu_out_uart(AP_HAL::UARTDriver *_uart) +{ + uart.imu_out_uart = _uart; + uart.counter = 0; +} + +/* + send IMU delta-angle and delta-velocity to a UART + */ +void AP_InertialSensor::send_uart_data(void) +{ + struct { + uint16_t magic = 0x29c4; + uint16_t length; + uint32_t timestamp_us; + Vector3f delta_velocity; + Vector3f delta_angle; + float delta_velocity_dt; + float delta_angle_dt; + uint16_t counter; + uint16_t crc; + } data; + + if (uart.imu_out_uart->txspace() < sizeof(data)) { + // not enough space + return; + } + + data.length = sizeof(data); + data.timestamp_us = AP_HAL::micros(); + + get_delta_angle(get_primary_gyro(), data.delta_angle, data.delta_angle_dt); + get_delta_velocity(get_primary_accel(), data.delta_velocity, data.delta_velocity_dt); + + data.counter = uart.counter++; + data.crc = crc_xmodem((const uint8_t *)&data, sizeof(data)-sizeof(uint16_t)); + + uart.imu_out_uart->write((const uint8_t *)&data, sizeof(data)); +} +#endif // AP_SERIALMANAGER_IMUOUT_ENABLED #if HAL_EXTERNAL_AHRS_ENABLED void AP_InertialSensor::handle_external(const AP_ExternalAHRS::ins_data_message_t &pkt) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 6ab9511cffc3b2..fd085cf7d3bb4d 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -19,6 +19,7 @@ #include #include #include +#include #include "AP_InertialSensor_Params.h" #include "AP_InertialSensor_tempcal.h" @@ -302,6 +303,17 @@ class AP_InertialSensor : AP_AccelCal_Client // for killing an IMU for testing purposes void kill_imu(uint8_t imu_idx, bool kill_it); +#if AP_SERIALMANAGER_IMUOUT_ENABLED + // optional UART for sending IMU data to an external process + void set_imu_out_uart(AP_HAL::UARTDriver *uart); + void send_uart_data(void); + + struct { + uint16_t counter; + AP_HAL::UARTDriver *imu_out_uart; + } uart; +#endif // AP_SERIALMANAGER_IMUOUT_ENABLED + enum IMU_SENSOR_TYPE { IMU_SENSOR_TYPE_ACCEL = 0, IMU_SENSOR_TYPE_GYRO = 1, From 11d0e36e36eac6989308941ba8620bca6d2ac627 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 28 Nov 2023 14:47:51 +1100 Subject: [PATCH 485/499] Tools: added IMUOUT to build options --- Tools/scripts/build_options.py | 1 + Tools/scripts/extract_features.py | 1 + 2 files changed, 2 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 6382ae512eb04e..dfbef411a78224 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -296,6 +296,7 @@ def __init__(self, Feature('Sensors', 'AIRSPEED', 'AP_AIRSPEED_ENABLED', 'Enable Airspeed Sensors', 1, None), # Default to enabled to not annoy Plane users # NOQA: E501 Feature('Sensors', 'BEACON', 'AP_BEACON_ENABLED', 'Enable Beacon', 0, None), Feature('Sensors', 'GPS_MOVING_BASELINE', 'GPS_MOVING_BASELINE', 'Enable GPS Moving Baseline', 0, None), + Feature('Sensors', 'IMU_ON_UART', 'AP_SERIALMANAGER_IMUOUT_ENABLED', 'Enable sending raw IMU data on a serial port', 0, None), # NOQA: E501 Feature('Other', 'GyroFFT', 'HAL_GYROFFT_ENABLED', 'Enable In-Flight Gyro FFT calculations', 0, None), Feature('Other', 'DISPLAY', 'HAL_DISPLAY_ENABLED', 'Enable I2C Displays', 0, None), diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 83a2f0583a18cb..fa2b0378710eb6 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -236,6 +236,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('COMPASS_CAL_ENABLED', 'CompassCalibrator::stop'), ('AP_TUNING_ENABLED', 'AP_Tuning::check_input'), ('AP_DRONECAN_SERIAL_ENABLED', 'AP_DroneCAN_Serial::update'), + ('AP_SERIALMANAGER_IMUOUT_ENABLED', 'AP_InertialSensor::send_uart_data'), ] def progress(self, msg): From 20b56bb4b8e6f2a7983e9b8aa74044e1d6350ba7 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 29 Nov 2023 09:15:57 +0000 Subject: [PATCH 486/499] ChibiOS: update to static networking option --- modules/ChibiOS | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/ChibiOS b/modules/ChibiOS index 3241db7d757922..d8c45abde5fb39 160000 --- a/modules/ChibiOS +++ b/modules/ChibiOS @@ -1 +1 @@ -Subproject commit 3241db7d7579228656bb51435af78d8b7ceda0a4 +Subproject commit d8c45abde5fb398ef9da6fc8fc36992f2ae7b15c From ce824b725d0ad8be598f8297fd8ce32a23e1b06f Mon Sep 17 00:00:00 2001 From: Clyde McQueen Date: Wed, 29 Nov 2023 14:23:52 -0800 Subject: [PATCH 487/499] Sub: copy 4.1 parm defaults --- ArduSub/Parameters.h | 21 +++++++++++++++++++++ Tools/autotest/ardusub.py | 4 +++- 2 files changed, 24 insertions(+), 1 deletion(-) diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index f170667859e8f5..433d002180a984 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -358,6 +358,7 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { AP_Arming::ARMING_CHECK_BATTERY}, { "CIRCLE_RATE", 2.0f}, { "ATC_ACCEL_Y_MAX", 110000.0f}, + { "ATC_RATE_Y_MAX", 180.0f}, { "RC3_TRIM", 1100}, { "COMPASS_OFFS_MAX", 1000}, { "INS_GYR_CAL", 0}, @@ -368,4 +369,24 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { { "RC8_OPTION", 213}, // MOUNT1_PITCH { "MOT_PWM_MIN", 1100}, { "MOT_PWM_MAX", 1900}, + { "PSC_JERK_Z", 50.0f}, + { "WPNAV_SPEED", 100.0f}, + { "PILOT_SPEED_UP", 100.0f}, + { "PSC_VELXY_P", 6.0f}, + { "EK3_SRC1_VELZ", 0}, +#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIGATOR + { "BARO_PROBE_EXT", 0}, + { "BATT_MONITOR", 4}, + { "BATT_CAPACITY", 0}, + { "LEAK1_PIN", 27}, + { "SCHED_LOOP_RATE", 200}, + { "SERVO13_FUNCTION", 59}, // k_rcin9, lights 1 + { "SERVO14_FUNCTION", 60}, // k_rcin10, lights 2 + { "SERVO16_FUNCTION", 7}, // k_mount_tilt + { "SERVO16_REVERSED", 1}, +#else + { "BARO_PROBE_EXT", 768}, + { "SERVO9_FUNCTION", 59}, // k_rcin9, lights 1 + { "SERVO10_FUNCTION", 7}, // k_mount_tilt +#endif }; diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index d1fc238c8263b9..40eb081cfb3825 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -317,12 +317,14 @@ def DiveMission(self): def GripperMission(self): '''Test gripper mission items''' self.load_mission("sub-gripper-mission.txt") - self.change_mode('GUIDED') self.wait_ready_to_arm() self.arm_vehicle() self.change_mode('AUTO') + self.wait_waypoint(1, 2, max_dist=5) self.wait_statustext("Gripper Grabbed", timeout=60) + self.wait_waypoint(1, 4, max_dist=5) self.wait_statustext("Gripper Released", timeout=60) + self.wait_waypoint(1, 6, max_dist=5) self.disarm_vehicle() def SET_POSITION_TARGET_GLOBAL_INT(self): From 2c84799bb5fcc40451f8c47babf2f6cdf240b858 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 29 Nov 2023 13:26:54 +0000 Subject: [PATCH 488/499] Tools: Scripts: Decode devid: add ICM45686 --- Tools/scripts/decode_devid.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/scripts/decode_devid.py b/Tools/scripts/decode_devid.py index 9b8a192e11ed09..04cf8b1738d954 100755 --- a/Tools/scripts/decode_devid.py +++ b/Tools/scripts/decode_devid.py @@ -101,6 +101,7 @@ def num(s): 0x38 : "DEVTYPE_INS_BMI270", 0x39 : "DEVTYPE_INS_BMI085", 0x3A : "DEVTYPE_INS_ICM42670", + 0x3B : "DEVTYPE_INS_ICM45686", } baro_types = { From 2ef560db0b984a64496eff11995d960816e51c04 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 30 Nov 2023 07:43:11 +1100 Subject: [PATCH 489/499] AP_ExternalAHRS: reserve some ExternalAHRS type values --- libraries/AP_ExternalAHRS/AP_ExternalAHRS.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h index 89e2331cb86188..debf2d27fecbe5 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h @@ -49,6 +49,13 @@ class AP_ExternalAHRS { #if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED MicroStrain5 = 2, #endif + // 3 reserved for AdNav + // 4 reserved for CINS + // 5 reserved for InertialLabs + // 6 reserved for Trimble + // 7 reserved for MicroStrain7 + // 8 reserved for SBG + // 9 reserved for EulerNav }; static AP_ExternalAHRS *get_singleton(void) { From 89506846a3b22c21837e18e4fae585f0b888a8c1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 30 Nov 2023 09:23:39 +1100 Subject: [PATCH 490/499] AP_Networking: improve startup wait this ensures we wait till DHCP has completed --- libraries/AP_Networking/AP_Networking.cpp | 20 +++++++++++++++++++ libraries/AP_Networking/AP_Networking.h | 4 +++- .../AP_Networking/AP_Networking_port.cpp | 19 ++++-------------- .../AP_Networking/AP_Networking_tests.cpp | 15 +++----------- 4 files changed, 30 insertions(+), 28 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 0349145f648ddd..401d0116c57761 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -7,6 +7,7 @@ #include "AP_Networking_Backend.h" #include #include +#include extern const AP_HAL::HAL& hal; @@ -256,6 +257,25 @@ uint32_t AP_Networking::get_gateway_active() const return backend?backend->activeSettings.gw:0; } +/* + wait for networking to be active + */ +void AP_Networking::startup_wait(void) const +{ + if (hal.scheduler->in_main_thread()) { + INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); + return; + } + while (!hal.scheduler->is_system_initialized()) { + hal.scheduler->delay(100); + } +#if AP_NETWORKING_BACKEND_CHIBIOS + do { + hal.scheduler->delay(250); + } while (get_ip_active() == 0); +#endif +} + AP_Networking *AP_Networking::singleton; namespace AP diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 257a4950c7daf9..088713da056250 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -144,6 +144,9 @@ class AP_Networking param.gwaddr.set_uint32(gw); } + // wait in a thread for network startup + void startup_wait(void) const; + // helper functions to convert between 32bit IP addresses and null terminated strings and back static uint32_t convert_str_to_ip(const char* ip_str); static const char* convert_ip_to_str(uint32_t ip); @@ -211,7 +214,6 @@ class AP_Networking return false; } - void wait_startup(); void udp_client_init(void); void udp_server_init(void); void tcp_server_init(void); diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index 3cb6a2f3d17dba..2490f5b77d98de 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -170,23 +170,12 @@ void AP_Networking::Port::tcp_client_init(void) } } -/* - wait for networking stack to be up - */ -void AP_Networking::Port::wait_startup(void) -{ - while (!hal.scheduler->is_system_initialized()) { - hal.scheduler->delay(100); - } - hal.scheduler->delay(1000); -} - /* update a UDP client */ void AP_Networking::Port::udp_client_loop(void) { - wait_startup(); + AP::network().startup_wait(); const char *dest = ip.get_str(); if (!sock->connect(dest, port.get())) { @@ -214,7 +203,7 @@ void AP_Networking::Port::udp_client_loop(void) */ void AP_Networking::Port::udp_server_loop(void) { - wait_startup(); + AP::network().startup_wait(); const char *addr = ip.get_str(); if (!sock->bind(addr, port.get())) { @@ -241,7 +230,7 @@ void AP_Networking::Port::udp_server_loop(void) */ void AP_Networking::Port::tcp_server_loop(void) { - wait_startup(); + AP::network().startup_wait(); const char *addr = ip.get_str(); if (!listen_sock->bind(addr, port.get()) || !listen_sock->listen(1)) { @@ -285,7 +274,7 @@ void AP_Networking::Port::tcp_server_loop(void) */ void AP_Networking::Port::tcp_client_loop(void) { - wait_startup(); + AP::network().startup_wait(); close_on_recv_error = true; diff --git a/libraries/AP_Networking/AP_Networking_tests.cpp b/libraries/AP_Networking/AP_Networking_tests.cpp index 2fc050d9ddd4a6..d4c33f980630c6 100644 --- a/libraries/AP_Networking/AP_Networking_tests.cpp +++ b/libraries/AP_Networking/AP_Networking_tests.cpp @@ -40,10 +40,7 @@ void AP_Networking::start_tests(void) */ void AP_Networking::test_UDP_client(void) { - while (!hal.scheduler->is_system_initialized()) { - hal.scheduler->delay(100); - } - hal.scheduler->delay(1000); + startup_wait(); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "UDP_client: starting"); const char *dest = param.test_ipaddr.get_str(); auto *sock = new SocketAPM(true); @@ -75,10 +72,7 @@ void AP_Networking::test_UDP_client(void) */ void AP_Networking::test_TCP_client(void) { - while (!hal.scheduler->is_system_initialized()) { - hal.scheduler->delay(100); - } - hal.scheduler->delay(1000); + startup_wait(); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_client: starting"); const char *dest = param.test_ipaddr.get_str(); auto *sock = new SocketAPM(false); @@ -110,10 +104,7 @@ void AP_Networking::test_TCP_client(void) */ void AP_Networking::test_TCP_discard(void) { - while (!hal.scheduler->is_system_initialized()) { - hal.scheduler->delay(100); - } - hal.scheduler->delay(1000); + startup_wait(); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_discard: starting"); const char *dest = param.test_ipaddr.get_str(); auto *sock = new SocketAPM(false); From 5bc38304515aebc2f57e0980e6841b11e54b85e6 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 29 Nov 2023 10:38:36 -0800 Subject: [PATCH 491/499] autotest: don't set DHCP in SITL/CI because we can't --- Tools/autotest/vehicle_test_suite.py | 1 - 1 file changed, 1 deletion(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 87c881efbda588..e8dd899118a44f 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -4267,7 +4267,6 @@ def TestLogDownloadMAVProxyNetwork(self, upload_logs=False): self.context_push() self.set_parameters({ "NET_ENABLED": 1, - "NET_DHCP": 0, "LOG_DARM_RATEMAX": 2, # make small logs # UDP client "NET_P1_TYPE": 1, From 7f94ae6fe71a7a16432afaead2cd8de7a2ac30c6 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 29 Nov 2023 14:16:31 -0800 Subject: [PATCH 492/499] AP_Networking: only show NET_IP,DHCP,GW,MASK,MAC if it's actually used --- libraries/AP_Networking/AP_Networking.cpp | 8 +++- libraries/AP_Networking/AP_Networking.h | 39 ++++++++++++++++++- .../AP_Networking/AP_Networking_ChibiOS.cpp | 4 -- .../AP_Networking/AP_Networking_Config.h | 25 ++++++++---- 4 files changed, 62 insertions(+), 14 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 401d0116c57761..df2f207e9c5abf 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -32,6 +32,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @User: Advanced AP_GROUPINFO_FLAGS("ENABLED", 1, AP_Networking, param.enabled, 0, AP_PARAM_FLAG_ENABLE), +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED // @Group: IPADDR // @Path: AP_Networking_address.cpp AP_SUBGROUPINFO(param.ipaddr, "IPADDR", 2, AP_Networking, AP_Networking_IPV4), @@ -44,6 +45,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @User: Advanced AP_GROUPINFO("NETMASK", 3, AP_Networking, param.netmask, AP_NETWORKING_DEFAULT_NETMASK), +#if AP_NETWORKING_DHCP_AVAILABLE // @Param: DHCP // @DisplayName: DHCP client // @Description: Enable/Disable DHCP client @@ -51,6 +53,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @RebootRequired: True // @User: Advanced AP_GROUPINFO("DHCP", 4, AP_Networking, param.dhcp, AP_NETWORKING_DEFAULT_DHCP_ENABLE), +#endif // @Group: GWADDR // @Path: AP_Networking_address.cpp @@ -59,6 +62,7 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { // @Group: MACADDR // @Path: AP_Networking_macaddr.cpp AP_SUBGROUPINFO(param.macaddr, "MACADDR", 6, AP_Networking, AP_Networking_MAC), +#endif // AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED #if AP_NETWORKING_TESTS_ENABLED // @Param: TESTS @@ -100,6 +104,7 @@ void AP_Networking::init() return; } +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED // set default MAC Address as lower 3 bytes of the CRC of the UID uint8_t uid[50]; uint8_t uid_len = sizeof(uid); @@ -114,6 +119,7 @@ void AP_Networking::init() param.macaddr.set_default_address_byte(4, crc.bytes[1]); param.macaddr.set_default_address_byte(5, crc.bytes[2]); } +#endif #if AP_NETWORKING_BACKEND_CHIBIOS backend = new AP_Networking_ChibiOS(*this); @@ -151,7 +157,7 @@ void AP_Networking::init() */ void AP_Networking::announce_address_changes() { - auto &as = backend->activeSettings; + const auto &as = backend->activeSettings; if (as.last_change_ms == 0 || as.last_change_ms == announce_ms) { // nothing changed and we've already printed it at least once. Nothing to do. diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 088713da056250..1359b3abe55723 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -54,13 +54,22 @@ class AP_Networking // returns true if DHCP is enabled bool get_dhcp_enabled() const { +#if AP_NETWORKING_DHCP_AVAILABLE return param.dhcp; +#else + // DHCP is not available from our scope but could be enabled/controlled + // by the OS which is the case on Linux builds, including SITL + // TODO: ask the OS if DHCP is enabled + return false; +#endif } // Sets DHCP to be enabled or disabled void set_dhcp_enable(const bool enable) { +#if AP_NETWORKING_DHCP_AVAILABLE param.dhcp.set(enable); +#endif } // returns the 32bit value of the active IP address that is currently in use @@ -69,7 +78,12 @@ class AP_Networking // returns the 32bit value of the user-parameter static IP address uint32_t get_ip_param() const { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED return param.ipaddr.get_uint32(); +#else + // TODO: ask the OS for the IP address + return 0; +#endif } /* @@ -84,7 +98,9 @@ class AP_Networking // sets the user-parameter static IP address from a 32bit value void set_ip_param(const uint32_t ip) { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED param.ipaddr.set_uint32(ip); +#endif } // returns the 32bit value of the active Netmask that is currently in use @@ -93,7 +109,12 @@ class AP_Networking // returns the 32bit value of the of the user-parameter static Netmask uint32_t get_netmask_param() const { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED return convert_netmask_bitcount_to_ip(param.netmask.get()); +#else + // TODO: ask the OS for the Netmask + return 0; +#endif } // returns a null terminated string of the active Netmask address. Example: "192.168.12.13" @@ -114,14 +135,21 @@ class AP_Networking void set_netmask_param(const uint32_t nm) { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED param.netmask.set(convert_netmask_ip_to_bitcount(nm)); +#endif } uint32_t get_gateway_active() const; uint32_t get_gateway_param() const { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED return param.gwaddr.get_uint32(); +#else + // TODO: ask the OS for the Gateway + return 0; +#endif } const char *get_gateway_active_str() @@ -141,7 +169,9 @@ class AP_Networking void set_gateway_param(const uint32_t gw) { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED param.gwaddr.set_uint32(gw); +#endif } // wait in a thread for network startup @@ -166,14 +196,19 @@ class AP_Networking void announce_address_changes(); struct { +#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED AP_Networking_IPV4 ipaddr{AP_NETWORKING_DEFAULT_STATIC_IP_ADDR}; AP_Int8 netmask; // bits to mask. example: (16 == 255.255.0.0) and (24 == 255.255.255.0) AP_Networking_IPV4 gwaddr{AP_NETWORKING_DEFAULT_STATIC_GW_ADDR}; - - AP_Int8 dhcp; AP_Networking_MAC macaddr{AP_NETWORKING_DEFAULT_MAC_ADDR}; +#if AP_NETWORKING_DHCP_AVAILABLE + AP_Int8 dhcp; +#endif +#endif + AP_Int8 enabled; AP_Int32 options; + #if AP_NETWORKING_TESTS_ENABLED AP_Int32 tests; AP_Networking_IPV4 test_ipaddr{AP_NETWORKING_TEST_IP}; diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp index 442efdc454a0ac..692ca988fc1860 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -102,10 +102,6 @@ bool AP_Networking_ChibiOS::init() return false; } -#if !AP_NETWORKING_DHCP_AVAILABLE - frontend.set_dhcp_enable(false); -#endif - lwip_options = new lwipthread_opts; if (frontend.get_dhcp_enabled()) { diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index bfc4af537f226d..5d32334510dc55 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -8,16 +8,24 @@ #define AP_NETWORKING_BACKEND_DEFAULT_ENABLED AP_NETWORKING_ENABLED #endif +#ifndef AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED +// AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED should only be true if we have the ability to +// change the IP address. If not then the IP, GW, NetMask, MAC and DHCP params are hidden. +// This does not mean that the system/OS does not have the ability to set the IP, just that +// we have no control from this scope. For example, Linux systems (including SITL) have +// their own DHCP client running but we have no control over it. +#define AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS) +#endif // --------------------------- // Backends // --------------------------- #ifndef AP_NETWORKING_BACKEND_CHIBIOS -#define AP_NETWORKING_BACKEND_CHIBIOS AP_NETWORKING_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#define AP_NETWORKING_BACKEND_CHIBIOS (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) #endif #ifndef AP_NETWORKING_BACKEND_SITL -#define AP_NETWORKING_BACKEND_SITL AP_NETWORKING_BACKEND_DEFAULT_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_SITL +#define AP_NETWORKING_BACKEND_SITL (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) #endif #define AP_NETWORKING_SOCKETS_ENABLED (HAL_OS_SOCKETS || AP_NETWORKING_BACKEND_CHIBIOS) @@ -25,10 +33,13 @@ // --------------------------- // IP Features // --------------------------- -#if AP_NETWORKING_BACKEND_CHIBIOS -#define AP_NETWORKING_DHCP_AVAILABLE LWIP_DHCP -#else -#define AP_NETWORKING_DHCP_AVAILABLE 1 // for non-ChibiOS, assume it's available +#ifndef AP_NETWORKING_DHCP_AVAILABLE +// AP_NETWORKING_DHCP_AVAILABLE should only be true if, by setting the NET_DHCP parameter, +// we have the ability to turn on/off the DHCP client which effects the assigned IP address. +// Otherwise, param NET_DHCP will be hidden. This does not mean that the system/OS does not +// have DHCP, just that we have no control from this scope. For example, Linux systems +// (including SITL) have their own DHCP client running but we have no control over it. +#define AP_NETWORKING_DHCP_AVAILABLE (AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED || AP_NETWORKING_BACKEND_CHIBIOS) #endif @@ -38,7 +49,7 @@ // Default DHCP #ifndef AP_NETWORKING_DEFAULT_DHCP_ENABLE -#define AP_NETWORKING_DEFAULT_DHCP_ENABLE 1 +#define AP_NETWORKING_DEFAULT_DHCP_ENABLE AP_NETWORKING_DHCP_AVAILABLE #endif // Default Static IP Address: 192.168.13.14 From 63f90462657c58e52101dfb04eaa314c0fe1630e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 3 Dec 2023 09:08:43 +1100 Subject: [PATCH 493/499] AP_Networking: fixed docs for network port types and document broadcast and multicast --- libraries/AP_Networking/AP_Networking_port.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index 2490f5b77d98de..4c0e384ad6ea0b 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -31,8 +31,8 @@ extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_Networking::Port::var_info[] = { // @Param: TYPE // @DisplayName: Port type - // @Description: Port type for network serial port. For the two client types a valid destination IP address must be set. For the two server types either 0.0.0.0 or a local address can be used. - // @Values: 0:Disabled, 1:UDP client, 2:TCP client, 3:TCP server + // @Description: Port type for network serial port. For the two client types a valid destination IP address must be set. For the two server types either 0.0.0.0 or a local address can be used. The UDP client type will use broadcast if the IP is set to 255.255.255.255 and will use UDP multicast if the IP is in the multicast address range. + // @Values: 0:Disabled, 1:UDP client, 2:UDP server, 3:TCP client, 4:TCP server // @RebootRequired: True // @User: Advanced AP_GROUPINFO_FLAGS("TYPE", 1, AP_Networking::Port, type, 0, AP_PARAM_FLAG_ENABLE), @@ -41,7 +41,7 @@ const AP_Param::GroupInfo AP_Networking::Port::var_info[] = { // @DisplayName: protocol // @Description: protocol // @User: Advanced - // @CopyFieldsFrom: SERIAL0_PROTOCOL + // @CopyFieldsFrom: SERIAL1_PROTOCOL AP_GROUPINFO("PROTOCOL", 2, AP_Networking::Port, state.protocol, 0), // @Group: IP From 96ede5524c7a0f67e0ab9686e96fe8a99ba922d0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 2 Dec 2023 18:27:20 +1100 Subject: [PATCH 494/499] .github: clamp empy to version 3 API and syntax hanges make 4 problematic --- .github/workflows/cygwin_build.yml | 2 +- .github/workflows/esp32_build.yml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/cygwin_build.yml b/.github/workflows/cygwin_build.yml index 9ae7ffba31fac7..f836b9c09a923b 100644 --- a/.github/workflows/cygwin_build.yml +++ b/.github/workflows/cygwin_build.yml @@ -189,7 +189,7 @@ jobs: shell: C:\cygwin\bin\bash.exe -eo pipefail '{0}' run: >- ln -sf /usr/bin/python3.7 /usr/bin/python && ln -sf /usr/bin/pip3.7 /usr/bin/pip && - python -m pip install --progress-bar off empy pexpect && + python -m pip install --progress-bar off empy==3.3.4 pexpect && python -m pip install --progress-bar off dronecan --upgrade && cp /usr/bin/ccache /usr/local/bin/ && cd /usr/local/bin && ln -s ccache /usr/local/bin/gcc && diff --git a/.github/workflows/esp32_build.yml b/.github/workflows/esp32_build.yml index c2a438891f7da7..47ada972560a46 100644 --- a/.github/workflows/esp32_build.yml +++ b/.github/workflows/esp32_build.yml @@ -200,7 +200,7 @@ jobs: ./install.sh source ./export.sh cd ../.. - python -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy dronecan + python -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy==3.3.4 dronecan which cmake ./waf configure --board ${{matrix.config}} ./waf plane From 576dc9d05fce73f57ab9d1c2452ae42b0daa2aee Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 3 Dec 2023 11:47:37 +1100 Subject: [PATCH 495/499] Tools: clamp empy to version 3 API and syntax hanges make 4 problematic --- Tools/AP_Periph/wscript | 2 +- Tools/ardupilotwaf/chibios.py | 2 +- Tools/environment_install/install-prereqs-arch.sh | 2 +- Tools/environment_install/install-prereqs-mac.sh | 2 +- Tools/environment_install/install-prereqs-ubuntu.sh | 2 +- .../install-prereqs-windows-andAPMSource.ps1 | 2 +- Tools/environment_install/install-prereqs-windows.ps1 | 2 +- Tools/environment_install/ubuntu-18.04-python3.sh | 2 +- Tools/scripts/configure-ci.sh | 3 +-- 9 files changed, 9 insertions(+), 10 deletions(-) diff --git a/Tools/AP_Periph/wscript b/Tools/AP_Periph/wscript index 8f238ce14b0d50..da728bdcf4e282 100644 --- a/Tools/AP_Periph/wscript +++ b/Tools/AP_Periph/wscript @@ -7,7 +7,7 @@ import sys try: import em except ImportError: - print("you need to install empy with 'python -m pip install empy'") + print("you need to install empy with 'python -m pip install empy==3.3.4'") sys.exit(1) try: diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index 819b3474c540f1..a827af26f777f7 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -114,7 +114,7 @@ def get_full_wsl2_error_msg(self, error_msg): and make sure to add it to your path during the installation. Once installed, run this command in Powershell or Command Prompt to install some packages: - pip.exe install empy pyserial + pip.exe install empy==3.3.4 pyserial **************************************** **************************************** """ % error_msg) diff --git a/Tools/environment_install/install-prereqs-arch.sh b/Tools/environment_install/install-prereqs-arch.sh index 4a1d69b82f9f8f..52b94eca23cd62 100755 --- a/Tools/environment_install/install-prereqs-arch.sh +++ b/Tools/environment_install/install-prereqs-arch.sh @@ -26,7 +26,7 @@ BASE_PKGS="base-devel ccache git gsfonts tk wget gcc" SITL_PKGS="python-pip python-setuptools python-wheel python-wxpython opencv python-numpy python-scipy" PX4_PKGS="lib32-glibc zip zlib ncurses" -PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect argparse matplotlib pyparsing geocoder pyserial empy dronecan" +PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect argparse matplotlib pyparsing geocoder pyserial empy==3.3.4 dronecan" # GNU Tools for ARM Embedded Processors # (see https://launchpad.net/gcc-arm-embedded/) diff --git a/Tools/environment_install/install-prereqs-mac.sh b/Tools/environment_install/install-prereqs-mac.sh index 5471e6f175e6ef..cba654a6de3d7e 100755 --- a/Tools/environment_install/install-prereqs-mac.sh +++ b/Tools/environment_install/install-prereqs-mac.sh @@ -159,7 +159,7 @@ if [[ $DO_AP_STM_ENV -eq 1 ]]; then install_arm_none_eabi_toolchain fi -PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect geocoder flake8 junitparser empy dronecan" +PYTHON_PKGS="future lxml pymavlink MAVProxy pexpect geocoder flake8 junitparser empy==3.3.4 dronecan" # add some Python packages required for commonly-used MAVProxy modules and hex file generation: if [[ $SKIP_AP_EXT_ENV -ne 1 ]]; then PYTHON_PKGS="$PYTHON_PKGS intelhex gnureadline" diff --git a/Tools/environment_install/install-prereqs-ubuntu.sh b/Tools/environment_install/install-prereqs-ubuntu.sh index 6fa833120a0ffe..9a865a52c13f9d 100755 --- a/Tools/environment_install/install-prereqs-ubuntu.sh +++ b/Tools/environment_install/install-prereqs-ubuntu.sh @@ -152,7 +152,7 @@ fi # Lists of packages to install BASE_PKGS="build-essential ccache g++ gawk git make wget valgrind screen" -PYTHON_PKGS="future lxml pymavlink pyserial MAVProxy pexpect geocoder empy ptyprocess dronecan" +PYTHON_PKGS="future lxml pymavlink pyserial MAVProxy pexpect geocoder empy==3.3.4 ptyprocess dronecan" PYTHON_PKGS="$PYTHON_PKGS flake8 junitparser" # add some Python packages required for commonly-used MAVProxy modules and hex file generation: diff --git a/Tools/environment_install/install-prereqs-windows-andAPMSource.ps1 b/Tools/environment_install/install-prereqs-windows-andAPMSource.ps1 index e1bf9465c4f07e..2076ce1f588d6b 100644 --- a/Tools/environment_install/install-prereqs-windows-andAPMSource.ps1 +++ b/Tools/environment_install/install-prereqs-windows-andAPMSource.ps1 @@ -19,7 +19,7 @@ Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i - Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'ln -sf /usr/bin/pip3.7 /usr/bin/pip'" Write-Output "Downloading extra Python packages (5/8)" -Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'pip install empy pyserial pymavlink intelhex dronecan pexpect'" +Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'pip install empy==3.3.4 pyserial pymavlink intelhex dronecan pexpect'" Write-Output "Downloading APM source (6/8)" Copy-Item "APM_install.sh" -Destination "C:\cygwin64\home" diff --git a/Tools/environment_install/install-prereqs-windows.ps1 b/Tools/environment_install/install-prereqs-windows.ps1 index 5529c9f0c11dcb..15bac628949e85 100644 --- a/Tools/environment_install/install-prereqs-windows.ps1 +++ b/Tools/environment_install/install-prereqs-windows.ps1 @@ -19,7 +19,7 @@ Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i - Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'ln -sf /usr/bin/pip3.7 /usr/bin/pip'" Write-Output "Downloading extra Python packages (5/7)" -Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'pip install empy pyserial pymavlink intelhex dronecan pexpect'" +Start-Process -wait -FilePath "C:\cygwin64\bin\bash" -ArgumentList "--login -i -c 'pip install empy==3.3.4 pyserial pymavlink intelhex dronecan pexpect'" Write-Output "Installing ARM GCC Compiler 10-2020-Q4-Major (6/7)" & $PSScriptRoot\gcc-arm-none-eabi-10-2020-q4-major-win32.exe /S /P /R diff --git a/Tools/environment_install/ubuntu-18.04-python3.sh b/Tools/environment_install/ubuntu-18.04-python3.sh index f8e3ca06851594..a82a4138a4c73d 100755 --- a/Tools/environment_install/ubuntu-18.04-python3.sh +++ b/Tools/environment_install/ubuntu-18.04-python3.sh @@ -17,4 +17,4 @@ echo 'export PATH=$HOME/bin:$PATH' >>$HOME/.profile sudo apt install -y python3-wxgtk4.0 python3-opencv python3-matplotlib python3-pip # pip-install python packages (also swiped from install-prereqs-ubuntu.sh): -pip3 install future lxml pymavlink MAVProxy pexpect flake8==3.7.9 requests==2.27.1 monotonic==1.6 geocoder empy configparser==4.0.2 click==7.1.2 decorator==4.4.2 dronecan pygame intelhex empy +pip3 install future lxml pymavlink MAVProxy pexpect flake8==3.7.9 requests==2.27.1 monotonic==1.6 geocoder empy==3.3.4 configparser==4.0.2 click==7.1.2 decorator==4.4.2 dronecan pygame intelhex empy diff --git a/Tools/scripts/configure-ci.sh b/Tools/scripts/configure-ci.sh index e7a4c6a60dd807..a547b729fce176 100755 --- a/Tools/scripts/configure-ci.sh +++ b/Tools/scripts/configure-ci.sh @@ -101,5 +101,4 @@ python -m pip install --progress-bar off --user -U argparse pyserial pexpect fut python -m pip install --progress-bar off --user -U intelhex python -m pip install --progress-bar off --user -U numpy python -m pip install --progress-bar off --user -U edn_format -python -m pip install --progress-bar off --user -U empy - +python -m pip install --progress-bar off --user -U empy==3.3.4 From 0d9c658a1e93af84b1514bb30affd54c94812ef4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 1 Dec 2023 10:17:39 +1100 Subject: [PATCH 496/499] SITL: add missing includes --- libraries/SITL/SIM_GPS_MSP.cpp | 2 ++ libraries/SITL/SIM_GPS_NMEA.cpp | 2 ++ libraries/SITL/SIM_GPS_Trimble.cpp | 1 + 3 files changed, 5 insertions(+) diff --git a/libraries/SITL/SIM_GPS_MSP.cpp b/libraries/SITL/SIM_GPS_MSP.cpp index 1751b5bdbd78f4..125f1b8de2650d 100644 --- a/libraries/SITL/SIM_GPS_MSP.cpp +++ b/libraries/SITL/SIM_GPS_MSP.cpp @@ -6,6 +6,8 @@ #include +#include + using namespace SITL; /* diff --git a/libraries/SITL/SIM_GPS_NMEA.cpp b/libraries/SITL/SIM_GPS_NMEA.cpp index 0491cce2ebd829..161f0ef0f04ff9 100644 --- a/libraries/SITL/SIM_GPS_NMEA.cpp +++ b/libraries/SITL/SIM_GPS_NMEA.cpp @@ -8,6 +8,8 @@ #include #include +#include + extern const AP_HAL::HAL& hal; using namespace SITL; diff --git a/libraries/SITL/SIM_GPS_Trimble.cpp b/libraries/SITL/SIM_GPS_Trimble.cpp index 6c3b41c80cb14f..9ddaf64027d2b2 100644 --- a/libraries/SITL/SIM_GPS_Trimble.cpp +++ b/libraries/SITL/SIM_GPS_Trimble.cpp @@ -6,6 +6,7 @@ #include #include +#include #include From 55b5e1cff1e50ba7128027469e2b96d8ed1b9333 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Dec 2023 08:08:46 +1100 Subject: [PATCH 497/499] AP_Networking: fixed off by one error in cache size calculation this caused some of the memory to be cacheable which led to TCP checksum errors --- libraries/AP_Networking/AP_Networking_ChibiOS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp index 692ca988fc1860..ea5e4f42a6b0e1 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -37,7 +37,7 @@ bool AP_Networking_ChibiOS::allocate_buffers() sizeof(uint32_t)*STM32_MAC_TRANSMIT_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE; // typically == 9240 // ensure that we allocate 32-bit aligned memory, and mark it non-cacheable - uint32_t size = 2; + uint32_t size = 1; uint8_t rasr = 0; // find size closest to power of 2 while (size < total_size) { From c61ee15c1fafba04f0a73eacd17281a5f1ba6fc5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Dec 2023 08:09:22 +1100 Subject: [PATCH 498/499] AP_Vehicle: init networking after serial manager init before serial manager led to not seeing any error messages if net init failed --- libraries/AP_Vehicle/AP_Vehicle.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 0635dc8368cf97..dd0b1576ffb16b 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -313,16 +313,16 @@ void AP_Vehicle::setup() gcs().init(); #endif -#if AP_NETWORKING_ENABLED - networking.init(); -#endif - // initialise serial ports serial_manager.init(); #if HAL_GCS_ENABLED gcs().setup_console(); #endif +#if AP_NETWORKING_ENABLED + networking.init(); +#endif + // Register scheduler_delay_cb, which will run anytime you have // more than 5ms remaining in your call to hal.scheduler->delay hal.scheduler->register_delay_callback(scheduler_delay_callback, 5); From 60ceaec9012a5e86148f2ed77232bb6c252e94ce Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Sat, 2 Dec 2023 19:24:58 +1030 Subject: [PATCH 499/499] Copter: Fix AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED --- ArduCopter/mode_auto.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 99449a2991daea..74bd78a15db915 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -1515,14 +1515,14 @@ bool ModeAuto::set_next_wp(const AP_Mission::Mission_Command& current_cmd, const switch (next_cmd.id) { case MAV_CMD_NAV_WAYPOINT: case MAV_CMD_NAV_LOITER_UNLIM: - case MAV_CMD_NAV_LOITER_TIME: #if AP_MISSION_NAV_PAYLOAD_PLACE_ENABLED - case MAV_CMD_NAV_PAYLOAD_PLACE: { + case MAV_CMD_NAV_PAYLOAD_PLACE: +#endif + case MAV_CMD_NAV_LOITER_TIME: { const Location dest_loc = loc_from_cmd(current_cmd, default_loc); const Location next_dest_loc = loc_from_cmd(next_cmd, dest_loc); return wp_nav->set_wp_destination_next_loc(next_dest_loc); } -#endif case MAV_CMD_NAV_SPLINE_WAYPOINT: { // get spline's location and next location from command and send to wp_nav Location next_dest_loc, next_next_dest_loc;

    XsURuq;HseYYOS6BC z`{B;f3hq2;8WL)E+lph%+sr{s5zzH$NPWTH;X!o`=_gynMCJPWS*cw-S7jk@)idpE z5;Y~06n|sbO-*{?T710-y6Foh9%?86R`&iX#tEnat;dmRH*2HKmWE$e>dOqNKAlpj z_kEi>5chlh*#RN`Zz?8Rnm+7CW}}4uPl5CKe<)h{XW7H@5wKwm=I#LV7giH!QCSk0 zv)@_h>Xft91wxmK|`x_ zGiu}3$JYV}Kx@L;Id+&A4%VmyMI2!7{HNdNG~y8b|NPpN)^g1 zv28T@i&*&&8-9e3gIZ1V_1nT*c5Cy<{N6pZ+=lKAW=d>8l={tpd2!^~-+x2kyg+fw z3IHP-pZ$By!aw}fzW~nTG@x7s{eMV?s2`L*L~}t;=m2mxjwW2WMLj_@{1`1z$3{+) z_V7WvUzTjy6i>S1TzQ*vh|CZLxgZN9$TYadNp?G0eARyoC`zH|#0FaInz^3)-izj4 zUASUbqvV`Or}yps$mz!GC;4Lsf(a&IlL^5M@*pszE`nyYPV~qC#sb(N`+(Dt3}BWB zF$Cd2Yyz&-kAM$px(J%gx0@2}Yk6G)U3}m8cugjr6T5b)G&_UBM?op0L|_of>D99!hrQsfrDxTR$8!<455q@g** zg&@WS7z7(x>9uaOi>=T2{mF!Fzq+BDB67Y>t_qgMNn4Wa>~$XtZwVDw*y#h~S+DCf z!_R`J$iR%=S$edj$uev~3F#~PNEiP8q&(^nEBS(FTTYqbt*3EXCQoiQD|qwhenEtM zmegV#1~YaLEUSao(rBZs2&HX7z#})rhWzqtA`34lxDW*!(^{kZam+D2`ZmA|r)DjQ#Lt{1--i{MjAjhd*`;DYQMUt~q}%p{IGo zbw$Eh83Tf3+bGBpe{y#m!K1xSgczdObTM2DcV5brIy!7D_cFCf+QsDQHuLQ5Rv(q? zH6GVXv3f_f^&mnV#HqFlG9$Y$`_wG#5h~L1=W2`S6K^$ddE@-#kaX60 z1;)~0j2awun55Hh{|Op7wL1trB*AFIx6 z(Ny$#XRBL$Qcl+OLt7p@b1)vf`M5N)G&%GTXk+#JY%$=Oe=<7Z&^V#de|11}E=4{d z?hKdDz4PsYKV=1!W;<@26dUgOUx?~mw&?&!@&7r}_XtG|z%s>`CR4GDAh?vY)aWne zgX6E=LmmC4Irrk#u8SV;eZ=#n%DNTi7%d5oBVs}k9}Jp>jS#3DWfht_n;)E(h;QMx ztjh2(%2EVTygWACBaHl=mo3aM(rk0`3>wZQ2=;4^b|4^s@0z2|C0L2+Kq^Azno+LxD8A`Al+2Qyv`5xv8@?5{q zwpS(kg6A)B+}eXUQdY%Ty3P8E66*)}m>-C)OelfTyv4LhwG1_Hi|~&@3Iv_*3vxU) z@!k26O`Hky^TD%9+(|MfMR{AN4%PDyBam-IZ6d*WKTo*sg(BfV#k);&_apj->z$Uh zNX<;GgqKyzZ>!Ti7YdnOg5kxQz0W}ViZ-{d7Bd$JG-`nQ0@ei(REU()np%!HNk<;{ z(vTQC?HqEL74836MCQi5#Mjg52zI+C9%#P^Kg=*MBb?oY;>V~%?jUsEJ?W@$<@<>G zcx6?haYWF$q;SHq1KO_1WksQ1!U;g|%Y(69ss$D%XB8{1tk96WG_t_FJGp>nh?@~U zR*JOcoG#WZ9e?0_AzLEB`ifZB1JXhRg0=Gv;W1$tW)P@R z3B4RRb1&UQ%0I0Wi&m+WcP$aW3* zt+_=_3CUPE(u)L#Qx<|gb$g1}gT(FJ)0GOHZxX6F z+7I^anHU>5X<2}*he%@tSiQS-X%}W(UlLZN-D;I0G-G!#PpA5r@h-R<-pchHY7|e^ zw)?DMD)O9JVJh)(T=FbA5&@Z9x`6JoV2ZD?cW#4Op^Pwij*M+W%FF@Ij&Kobo6WOR zr+eNq#OUvW{muo8e7OBMUjyrK|J;=)f)?EWZh!xt#N^3g01uGIFe%>r= ze;S#!eR96qH-1Z}u}HJ-$KB3H%xfzR+r(HBPy+!p0{L%7`7D9l$+!b0*7|sP3B=c; z^2b9w?5fJ+&+N?A6lzlbuIhYEgVrtg6aDm9m1W+kdjgg3@h>+EW-9>aphzj3XO1RM znM!^;Iy*{?DxhG^%B#NrIPtxiHg>wt_s1K}%#oAQ5n>(5PnhMfB75fnR&ls2?JG*Q zomSc+)zUUv*Q=j^X+IcyBb(X7dgK|UDUbc0SF&maKH!?n zDSYIWJNaqr(B-7AB%*8TX}Rks6M2aMIoLA~jAcUVazW=ZHzi zd2uc*kR#Vnq#BeoTa!JSj;;rc#7f^V@-zBJN6)l` zs$`e)gq_vvL(T%<@c;YkVEz$i>hJ$&ZjLev^;3mFJx5?12!=KSsH-6m6Dblvaf7ci z^qPF>ORypO(jf5yx4=l<#NN_f86N&eI()vTEle?nK0<%NBCT5n(&+{B2rNW%pli{b zUNDTmydGhy#c6%~L>M@T0n}l-9Zg!bS<`0szLaabJ+J#xAd`z=zGGEEBs{Uycpk)0 zIF;4>GL~4c|3)duWrSg-nmDeQuz)P7c+?3sd zq{ukdGOLOS{CxUD)`QxsWJ2tOav$?JU>{3YJ`-HjP-yseY|KHseRqcRTYXDJfnOTP z$?T|3%H~+duwweYuy;cZ2J*1eP#alb6TV%v{E0OCYalIeOjZZO4)0c3TwJG3-Tscw zSY-*p9&NY}geHGjp?e{e8cesO$qvPUFgZzu<%3brA@Gfw+J0wEo`Dql+4a=y4!GHlNJUhbsYQMzUpc zQyp)A_P3?JMj@@v)6YLANIpGst6r7s6GoN^f!ozW4T`{4Ma7N2OVkSnT;F%r;>zFJ z5WZPNx70pM%oEj%kp6Kw9KkE}k>r}rvH~CZXP?dh`3;l?2D5q17+fISJ{1X=6K=!) zlLA}3k;3Ic372LLx9|@PrHm{=A`zmV!UHRuYKq)a{ynZ~Qa!G^R^O>~lDE@2>A?x#g2{b# zU;K{WGwTSwy~o9b{halT;OdWHw_&(ydzd_L4rWw;`aN1v{Qk7+Fsvz7~x7AyoWjgJ`;(f8hiq%DqFHcBAZ9oVt0cS4NBbpATI2#he*@AU$?#I z_Ec0}UjISdD_>hA`YLAY!9n#6wF{$;Es&24)l{aZD|0eQo3H5IqBZT4~ zoWWJJy&Z>qKM^eTyNr_*P8^wjd~9XSXG6K*8!ZE?7&~^_(ZSr;YwyZv{grp4si>vr zD>eRghYe(i^JE}4T{9tgLmHIp;m+HLr`-efP%anm%I*`3BQnO%FKyWQm4#Tfbd8veX5_ zR5a}*njhSN3(0$l5HqbfT%jYdWIa4mbL8?i(}BY2=ZClYzQbzkS;@NU3r1}}dfH;> z(P`dUm1VHlwx0L*e86WJD!yeU2lT zPy-N#of|{=D(S13gxnoQ=L^CHy4{SfA0;zoCH7_741TD5oHO?#-EQtt*J??j_?h6K zth#jeRTAm$iK^^xi@pKnD<9vfSJj&)StwN+aU8KZP6m9%-x2k}-NQPi%p<4TW-qBd zu^RQgC~NF&f0QM}ahA~aN3W2z^GOIZ6hC~psB_>hqDx!5`->oHNt9Fg^lRaw`##NM zE4S;F@5tV@iq=ew)$|~;CM}kK`M{Zf#6xtdBg!s=o(k_W;VI9vN+Mg2Z2czh&Dg<7 zOJNBE4oAm4FiUbQKEmS87!oQG*%Q{k_uNRWOF;7zcbPEcyx(P+`MutT&n9_#yMJi* z;~672N&`Zz8!F!rV;1{=?1>6fHu=;iv!$#I#Vu?p|7+{Z81MRM@1zXNubk{UzKY7^N@A7k55X^9eZ8YoYr|*3{QhE9D$m2Sx*oF7~5lHRe_1 zLk@^5sg|qQcD&AOJ!h=|mCPeeTU`~h4-Vn3y||`%)c*9AZGevR4~Oi-7QGZ|jUAju z#oYS}`v{T!G;c5k?o@cVb3JG|PDtC4XaH1t&dv)Zq8D2WV+M> z)t30P1!p^A3v|w{@<&*9a$Lgg{DUIrg00B8T(IW{KV%mzIWwr>d&XpfRKRSKSE7Vb zb%0%lQCe!a?oU8i7>n=;k#k|SjpZ>PvdwW9NFa>Zwh{CS_V;ix{#cjV7@Z;Q)uSO; zvO{lB+RfmzkDob{KPuP+4fL5#0?gx>Jv$fj`@-8jv&$%)jM?EQha$x~46UP4twxoX zLq+spWJI~cuTDASn3qEURX$x7y6Laqjz2JH8+xO4~x| z_Sg34h_})59NWG@v-f}-4%h+6i3bwT06wiG%8FK3u1NXHrPrSV*24;I4w@xj+^639 zRX}OT$h%AX{wspYb{B1Y+2zLCis+Yp;Stw^e0;9NSQX_Q-4(od@k2KU=b~TZo+dAf zhpNnq-jA`jMkmd7S(0Xzu(krSPiKJ^0Y8J32LjX~I)){i&Xk3%I~rrsLMfcz{g&;A z3{Jb;NqbB9IzuI~GEvgd=bKC*#wzz_0NGX!>JNc`^nUZcqcSGd|GesWh}6p+@y-w>j=GQt`a1x;EC6=ojeo zu+3tp&{Xw796@xkkx--HNEvplIT}r#XiliNPpT5@g z)t4!(#3jyfW|?&V#o-JeOcxnGAc6{g%57KTtn)LjVdfPsu zN?|Fd^UjWWy4XJ-qZC#s+2zjs@cBfopp{pLxuNEcVIEfI?*?|hhRsw#iy7&w2X8$g^6soLP zZtwC(-uY({o#4NwafT%LA-LaSSUTuJB2@Luu-tQwF?S(mqKk4#WytUt7kl1r`i*2O zX#LGyDW|--X=u2{31i#!)dsUEZ%TWS0&oZI-TK zU=`kFXIctF2sB#IY+K#qG@H@J<;Jgmv=G>@+!jrfl-LVO5uZN>$YORPyGb>HnEB?J zjd8*v77?6Ee+i7kiOXdlTuJ0}i&;vbe$ri@1b8Ptnc;zXZMB7F=TX4o(N1C}#vEV^ z0`4F^GhWwbPuJk4J5%7jZ@|=9Q)Nfa{#8znv>6@F%>c7METSEtw}X$g5Qj4b*Lao- zk1Yeq$#@1y&Ujmxez$}kQ9{r2;K$|K$=iNC+LPTOfoUa&JoWcp-EPp6x4k6(cM8G} z><-VNj}R!nRx77;tck#0F7!*ew+ZeG3IjGd2A3?drRPM&RAek3m>*`fkqjV;K6Gzp z-Lypkn(ZH8`EoH9<9|y6?JIDdP+IpN?jy2FJj<1w!skCN65DpG@w?dMVp`|HQ+@os zvL}6{+P!!OTN?jCBm)$RYoJU1wv$=_*f-zye#MD;yoTPNrkTDcpIgCCgNr)9tz&B| zSCn~#86HeY2MW&%i18xnSVRnXDHfh|;}6?)&}VBzXb%lqHe`ChD9T7~7bF@Mzx1~8 z!SM5;mmkj)lUJe+NBeP?IpD@;Froo;{r6Q%F6e=N%o8 z|F&&)BHx5}E|ewh!*s)2MUASz!yb1;?Uq7oo zMJ$7{F$)?}jbBkuozQKxyu#|5>ugYzRw_9e*H&_80nkhMuy%f7Y9SN3=wG(?CtesE z(C|bGU(#rK5c%0D0e1~^a-7ezf(*W!mS5)*FFHJY))c3*VmppuoPZ&w2u|n|vWs<) z#wNzF)Sky2aPR7}Qc3Uk&UTf`NVPD^xNwSti@$_}Hx1mN?;omUDf~MU%{nDzR#@qy6pveIiNbkC z{L;P%g_(qBh|jZmpFe~Hddu@hppTj|!}lG31jxz%X*9?wFYwo^`aCo4(Xofv9ObZ2 z$zIW0Tf5R8#VxA#Q*Hne+RA=VZhQbVh@BoKiR>ASCO6ATrg_>fKMnly)%%zx?%|Le zei_x`%e4gh?7r6#BzMR=I`G8oxepJ^nmI_# z)I?_>RT@fMaij|{u7Py5cB8Zf(cK3Ln>H*j7oRwc~n!)Cq zm|>WL3Al#iA2r^^I!R-b?l)_c@%Zh&dEkA3>aK1hZOxsBPOo1)!pE!n;RP352-+n4 zQTNf6Ybz>bNS0+ZRx69{0Js#fls!&A)`sh6xO=vVcFXrx=^fu<23=qYpqm?O6bioZy7GN}J{f?=%?brrg)&iD#TmDFh%|Y^%v1Cez&3VC> z2D<*^fr01!3i+Y%xfiPOmP>h z>*zkNeeux3U*}!u+|!a~!6zG$GCq$R+8;m#LGV5xdhI?t!xG27J?xo4x3(HK`*v5+ zs?h(IS?|Q+t-v2IO|7Ioq|v^;hxb$Ex%z@3+Q}Jsx8z$4tn73DmzFRNGgQ0c-#PJA z<6i=lRq?ZZA@J!Pt|Ma;0xVSc@_lgatp5&|NiGD@aaF^)#LK<`S zFOCG=74*pff9H?u{(Z-~ZO^Wfa`wtulBMP~dnHrcegKah#1c~^qgkSBWbv_k#yb{5 zC4v{z%16sf7R3af*}A45-8R%$dldAEn>w0Jb?jB|Y`K$%n%!VTvI}q_Oly|kDB!Rp zh=9>cs4eYoY;0-DN-UX=d}Sa~!Xa*F0*FyKIQWrQnAwqmiRx}rZ3;`Ys-H>OUL0Pr z=qW;1o{uThRjc#U3{uaJnQ&=-CzYnS`x#XbiqYNmz{Usv2?886%ehQbT<~!7)zOy2 zv@6*oL!O=s(=sFHY6rij$N6~2TPpe9J)l$;`08M^gB0N-dVGTsK?_vP7X3sy>LCg?+8if&8fBHN*ra*YrfueyK(fkEX8+!}gIl$>JCrQ`K^eKmLcSv0Od|6M@ zszs(=$-W}-$TpR!o8L&f&0rsFy^rr{5rIFU66D4x66Hmc(=t6QU8ur*)56}=rcS)x zH&c=0gB8F2!RrrDwV2uLTp5-v(+WHW2H6g8bY&3yDFlhIQ|)%c?dFOHKhTQ(7?E4z zpiy94ECHdmE@t*8W`YPp8!pmCbc`_{Eu%Q%ISf&pieFh!)DrZ=3LD}__X;|dEn2L8 zJ=mm;e)E-Z?kGET@WvAlt`oJDm9@mG%Br|?L}Ju|U8l|SRG+KPs=nd?f^AX+RnP`{ zo)80KwbL_^w_@9&_`_(%SS-QY{l4cRL4CJ?-WZXo$=*ZBj)HIHjtcg+re|65(uaUM ztzi=YvwJt1$lJaq%F-Ry#jg05UmI*&vLc51HXjetp})wu*46M+!Yo>p%-+hPi*SbHkwleUXrC8rQQj;5l$kNy^%e~H}>fFp88R^beYQB2l z+m6;d*DP%{=uvAq0*H_dyR1c?1%5j!&le-G-sg3?o`z0YXIn6REK{9QNA-zS85Fe_ zCs(Y*$qqA#=?^pO2{S41zFd|_(`+V7{PwX=6!=-;<&25>*y9#2;k(BhtZnQkBn-2+ zEGMU$x__Hg&>M8A82oSw>`@hDTLMtL;xp5$e1+2=3Msel*j&e6YNGSr*Bo54V;VcQ z3`kp2lMNE~UJ&QJu=QI&X{2E8|9lSV_d!G;geevFo`HY|zXlJHp-89-L*6^~vg$T= z#jqeC(A4=r)9Tgolt-cl^HPMj1o&<>qXm4rjlkLqg8HwwkP^WE0yus3Qjl$v^aSuw zCAhOsC98dix<#8|l1l5e>X2^f=apLj(X3fwW3uZOE?>@olB=MZ`x>|h z=noA$2q$?3p?p8hM|iAE)C11V z2s22RfvGHFi33H{J32E-ZnhoJ{pmf;Ekqk9?DnFhQ?=niVy~_$4X#R;zc7#w-(Qw^ zFtXqw))i`1z|1ZMps6W|Ua%|E&gFZqAYR_$+7*pv)7Nh@9)=%&79-H}RcZW`l(1{c zqf@iE=UZO$F8>mTcZ0h$VV8i-a|-OeEatSpW(NGq1J0r04Eunp%AV384(?#Z>^1*WrMZ*k)0-( zk+WZ_UW?9ibnmou=EV^`q>&?0`bKe=S0I%BDoWCRJXv8^)hGHj( zfNpHaSMrt zW|wAuAG7GlW%B#xZeAx6=1UQw6~N;%fFGD)93Ud8fG1}>{eMS77mq_`Ff@0*^w+{-+m%y$UbVbckjG!nS8Q|gjIUin3Jc&HG`hkJX9@2*<%Z< z6tOugfWw<60OoWHmgzgN#zD?5Pj?290d)t8KftB#Ze!O$3wQp=I&aMm`in!!4pXp2Z;48s=8aAe?G*yL=D zwmWPr>lUFwjZkFnFCX@kdB-f{-0)6ZmA$@#?VV>Gk7k0bAEH8Be%}U>Kxku2QzN)T#q9DbiGuC=Rx1=rb$8&g?HvYdL3&7 z4B)+$fj(N|=;nN|PwCZ#ERM89 zDj?uI2yW#k>bGfEG-xo81m2bgkxBtadlgkOtLV-@{K zMf2F$sBMVMi~VOiy!aDe95{IQDV0C$8%Y_=+dtn>9ty19yNaZ*eZ~i&&)<2G2i@2@ zalp?l910RVpiy#%OF&hAQC<8 z#f4NdWvT=0d-=Myl9xQQ{wy15uyXg^1h}9|lp|O^j1acnM@~;a=6Pf!N0NOXbBQF5 zbELnx^&&@#7SbH5zx48L^_Lyt1^2F)Ula_reB%GD#5Rj(< zzFhMIaAGXO9Bc}xbB(0}Qq{jzTT;M62a<9(TmIN|M`Yj9GzvZ+K)oLlwA~LoDe2=r zNU6EkI&XpMeW!D;?z?0Zuk<%k(oQz02;T+s^OfDA4topZL#+7*h5Ce5kz@@X3)_63&#`?j&mCfh8b33ggMti&4}QOdY?V zInn*CdOBB}6+a}Kgl~<+l&pidWG z#%bO+P}&#VwF!qItsp-%aNS3;`9n9cime;GWq(Cywvw_lGPkZ4kQuX`J zdCS#r35t*1%*?n&^*gmddH2`mw{M1q;d`=8x_jMyIgh)` zIUq=+r|NlCRn_Yr`L7~p*8m@hoCM588*`zjB!#SKwIPxp&*>kIDSFkvn^=1?QoFn1 zg1Ccswe~CS2dGH!(BejD>Hr6Lp=!K!;V%x+K?E)J8NQ^{7z5|lOqzI1jPB!{^UyfC z&EZGk)$pw?VB_BH!|kS~h(N7+EaeC?yy``(Ohj~HarE~J1aj?TAJwU3yGt&@0UhhzKRL&=W6PR zYf3p#&~1>1T54>$&aNc^#8dSEORU>{=msGnSF|QqV9Bip<6Ao8w{**kx3sc)5nhTV)Mt${*Go-|SAmWA1wa$!)eIxkxIpVQ| zK*f`&#?!^EfRW}`J5wDQgM@&xVf1Nul8jB%$=w-t$uDPS<)-@ER#oZ^`!2F~yva60 zCC4k;PtQd~$dR56z}g2}bBq$G=&oF0i|vJ|_Cqy5XgfN>&x zq&mM=jz?I&mGte!w9w9s7Loeoq0Z2qx?kPYf9z7yFXy^1`{rIW-{xsvU}4dJz*JSX z%boOWCIB)ewjA`m1;y(W_f_Nv0CNG!i6K*tC4y$WQP$qutk# zb4}LivfLqc2cvFtjd*e^hf?)586~duG3SvLBg~60*qJZxpFe+Y+mO`P7u`lCCUIU0 zy(Iq!m7v10#h*&zgIZgGyB%Hpc=_2z;YAqMoc!|9hPZL%Z=8t zWKH&2oX&h7Z`^7!_v|z6Rb;g&KpQ$g0X9Mtr$xnbgBOQd`1~*;JiYMHDO%u@t;Mpv z+Gmd{Oy;>13Ucw;=@mpBY;ZRk`zFbf8zN(NUIuX@vGvUvs}%dpw~e;Nti0FO z(W$pfH%<#|I~VQgx@9g@yV!BM>HgF~TZTIL_`^RMfl)CFhm-SZ5M^r`mFLsA6Ea~i zSKC}Q#c9v@`TT_NJSSsWNtjRm&OaEd=cZBg(PzK|YJi1D(D;zUH_TG>=Z*d*l3U%S zkZN0dyh-Ndb05uirF$6)VG8vaSm$T=3uW!H1}xex@E@GWIVotpZsHBdJ%R9lZwVXZ%a$`? z5HZ=@{Pistw41T=y{Lf0H1a$MwkI#I15f0`dS1%#2NQ-Rli0eGA9+8n19&^G58QV; zeHw5EB76b#?hd(KBek-;X9sZ_!NC__xt!H~(^nQ*A+2N&7(sPe51{sOlHb6lR;~nw z_7Vi7l%>sHFkF9!Z-aCQ%{O+XoPL{;1q9*czhi`3_JmQpvK?dFmlB$8Yxub4{Fs&| z)!bMYz5gYCjsHV_$%r2h*Wz*+HWirl??ui){!bJ@0E0lU%2xP2 zGdPSy5l>F{$zz>*Q(sT(U=Zn3b%j@|7O!XZ?$!{Vye>SsXS9EHKc_r;AQY(kmFCuT zCclXg#LBg(t6!b6ypJL8X)@rvFYDPd3Y=vyX%+;$vc`r`>jh&m*ryAU#4Cj5wiDl% z>h?b=_8-%iAS&yW5^d-hGiY->d zPDXR!&A{|@gj$2=;{iVsWI5NZ82pyepBEd97x>fVi5s8=8*+GH{%8$ zGT}bLSzq5o`||5YW#zL#i37p@!LKD9(%wbii!ZZ#j#k@ZhWiOZGjTWFHI}$D!j~G~ zdXsfJ=M*$PVq`Eg*t7;8T0;201MSN_D$DQ4LXzZX!?&C}Y~wSDPK;YM8SgL*v!v&y zfftj`?)drstow5bCk~yYq~4d2+Q7xmtc_o1{9vcID8P5yF*TWSpt1Pwre-udmptj- z7dYwM%)DSD9KAAUGo(>9S=MVGdiIiVaqHv)fNx=7{RFZPOB`d_OgGP{Bcbrxov2Oy zxB!j6ID$*lrCe&aWy)QiF0?ilUlw9F7*ilsycGT^iIG2gl!haa~wpiA;;st3)QGwdqOcc}>%(Th4f6-adG zzE*93(~l*)5nbyz%{9$cZ*7|pokS0S(yKlwYGssaMHnZIry=}gdJ)xPc^}gc{{gCz zC=aJ#CBsl;MrCl(<;+$kQf)@>jhg1F`Yg=YgCB}YNg2PDcs}nCfGbUS{yo)%zYmsC z1-hoLfyN7zn`lc`mBX6(AMuI_B%!67!Nk=yyOqM!sjBtfv)uw)7q`;3OIQE?f;|Vd za#o0rAp$DQBQ=TQw($ifwxwnYci>bW4tz5U9A45V|L7B4=pbz-V#iix@p8Dozxlta z@cvV4(0_#%`k(%Pd@%H1%kz-(vGCyyj1M{2$AEHu1Sz;CpkO*^bLkqGF(a`sAL~I$bZHQ-{$yf=zs4wyG zRO`KKJa7HBNy%~$CVE+S!6K{vGlOm^tR0h#uYlokFaCgQ*a@`oq|4-<3`Ewyjwmtu z&^^^#l3yk`k@!VQkk{ZH2V8_G2EvnocL5?}*+9@05YE>8UE%eO7$Sdj1X>`293M+5 z7v$|;fz*R+Eq2o&0s{a?Dj+pc!ts*?CpA%n*ucw2LmMDL^A|_**fNGC3}`UUQ*2?? z`DMEhx?!iM>?flGCGKGvKaVr_q$?2u-w8VXP(x@Lf;h^yeq%RQ^WQJd{$ty;z!M&* zz|5v$s>H|ImQtjSQ~flX%|a@YjvX=hd{4}b8}HPvI4^f9)H`C?EAauUymXEfbqx3zwK_%ab$MjQH^oF{s zI`@omj$PA!x}V#Jo2wJz3SobMS`U-v(AX`|a*i*0Gk};UgqmP7#$haz2X~;Bp4&+f zKRye3tEU(3zVDxTfARW_q!6WRJrC2P4oP2o&=V>wsh0RP5)VR-`{|?$s7RKjb*WufKNql!_4O8h>q&c+(i!7(O;(Jd1~fD z!9wXHC6oOplT&RD_JCK*RLI^JeKwFBrb)jql zIgkr&dpSWWyS$f+R)h!*gBj*WfM(k%6ueiq8~Bo)n3x(c48-W5n!?m>_xK-YjH)K9 zgyQ-S$UI$_B7C_FKwB;0;A<5~4r??8-5w`?LdLh?YIH)=vRs8oTdnTBrU*-jnNb#eYt{{kn)N`rErZfDW=C=)V-k zR1?^766j5yTVpF`01u_eu5HHn6au=zaB`5W+xHIxmqOf?Q~eb>t;6jTt)v1<>lHaB z&9C3_wEkPNj)I{%+ro!b$j&U$Qp!CHibUQuf+*pRB}-M*3aQyPC-=@+#+yy&;Fc>) z%c9SkSAyl2+91urte#DIYs-!FL8x-vJ^*QG!=q_IG0Xi6H7jymhSpa*IL?-EHuTtK zUa9O>8uP${(@3ilG+RsJ2Wx;Jw{7Gl4R<&NC=`*?lYS8d7t4}D0%T~_ZHvK1JXK9^ z?aMg4J>E4fpWvX)Oo$ZXXzILBD7B8-ttjlR9Zo=sRkO$6R z2`eB8$a{w+&CUQgnk4JDcoCZZedB!-@U4}ykbs-rXJWcKPA1iv)lMY`il1^0|1pwv zYVdt5<~jDY&&nK-r{y!%Huonf7%ad{f@}X83|ypXT>1SsE3JJW)OQk7h;r z8(%94`*Mw!&NH=OWz6zq5iSH6;Y{9EbPPRgre9L=jEAV~djrFJ6r=D90qvpLlKAj1 zIsTuG)mRQ-c;C*%+}cQNb}eyV$dRUXCQf7&MHu6n+`}Fk+-GyqaEgzhhf z2+9@S7fK)Yt;T84=ZKNn)OT{q`Zrf@iq(`~;1$TpJLR(ds_lCdbd94$2O>Fy3n0H= zLAwo=g+!=0+*t{_5)?2>nOK$N@jRq>)$!A#2ab2RckL_!j0SqKbcl>3P{4FKH4en$ z%q~h4yqs}=+8G+8%A0I9V4!-ml_U8cm!}u=HZq-y!puIIsZK5gU8j!hzKU2cRX6uZ zH*@9Y5zQBZUUhf)P7m(42z23i)$xE+htv5F8*-E{s7|Lghu@~80JO%oW&vPiMX(v# zmz{QA(D-ovj$q}XchTD}@LSYc8g$-H$D1M@KztJ23QeRjB8QpT20l zAFSx&FJTqJ-@~={;c>1i6Y0p1cA;+WOO?h?eclDdy*s>+YV$=U`g9I7jG91 zmSsq5@vo|0%FI%p1U+8KU%I9GaKKmdgn=iT!GRqfbriO>!0wp1Y^+Wv#ubFuqzL+5 zdl4$yR^)%yR?++D)>#L=(M#u!l?GgEfxs>WvEJPzL=5a1XIw<^tjmof&g6lP8!^^R zHj?&D$*Zz%+q&lU#`wi>_w%aFKNa%}2(`Mr;#~*{S6Q)UZe_`^>uxY*AmH_cSSnP) zay1gGSL96y_C1(d`Qd=VKBII&&Q+mXU;aT>>w=k`*SZJJtS5t#>{+_iw7Oclez)7@ z&OOzBUSSy$w@e=DmjzwzoqIW97q2SJmH7Ic0|)*dP60khMn}qVR?-M}SO@cAi}qW- z3X>-X)eAsViHiC$bB-xn<;GMirR?veb0}CDbYr2&5KFw9e5$Y_OguzG(vvoMT;dIR z<)qd`&1kxng_FILi%V&A@ZCp->DM?n8@^mHzjUsoKq)Pfha(Kr1D&~5)KZ|w_8YZBtI-{M4Tl6`e^>8HoQ0h91-q&?i^h0E8K_+2qIU< zAFFVj9+h-DD9@$Z|0!^tiyL`{@5-&iM3REA<1;33E^Wr?Ffj&qROZUhGrbK}S=+}0 z=2KMOXX}wOmE@$Y)qp^^y`n-3M1xqOxr_i9qBkKD#tAeFa!VG~EIm*GFqiIjs>`yx zn7x-i*SYs1w`F{J&h_kHnB>1WcCpl$2U)Uo$&}`xGIw8NFP&cfSgQIwtfoDYCqd2|aIyYSkPXYnxK!S5j4YT)erWQ1T8r zC^|lq&fDhZ`6hp6VzE(^=qJvOUa5()4APi8s&uVjyR@sci^#BuC$RK?w9un6aUfS4 z<%S=yrSnqE`qm#zO;zL;`W?REuYpwFc>6k8`9g`fgG4Au-G`_;ndi16-X81_1I+9)1XNL- zSNIB9x^#5ZueIpx`M8R~Zj;95Va4GqL94qSJb0(@B0w;C(h+D)^+mn!f}CD)-DBsI zE}>(g+M@Q~Mr!nft$0~_ckHz7p)0>`D>Ybpx7sOPj9K`~|A8xCkV_=T#^Fz@$r~Gk zsT_;?O513g*%IdSw$b#1QjV-br@ViWbo+_fp!66^!MXdq(u6FK;zH9r2BN{nvNV)M z+t9aWm4vYf z4QCTU7Q$GK;L$9L$~u2?-sMofV7dIjqU{VK|Be$q{F&ya=VauyOT{^s{#)8X1RZek zIA~4)jRtu$E)gyVl>b+C-c|2^d9^KkZL}aN(NwmZv65MwsjF+JUV`xR48I2p!$PShs zZMw;ev^qv|fDB!Xgz5fT2mKfL(5n2Re~WQ$0Wk5ovC(0Auh z=hst9B-Afv!r1M&lNHkB`Z)d=B|&+EMO!yU5DE+gC{PepSYl(}>5_@&%gBDi%S zu8pHLGARNx(+|hqH^vDS++BRIe}hm9YS|>%NRiw#_HzA@1VW)|^n&ijv6Uuz0Y$PMvm;Dzpkqb==U8$%H1n3ww;J#z)X+WTA{s*jK^Cz-xw-*~640)2-IbIsXpoDXo z1_;HFN}r7Xy}e}tYzu!xauK})#HZj)!<}E5Y@TwQ)HJ%L?4Vvpb9c4ft+628X3mG~ z+Yy?F8bO2E{m}%#hRZG>jcAv!$!;gK5B&Yj|Bzq)&mAlOhhC%lwf-Afk+F5P|0ZCH z1Nra@D3Sd;>(YPqSM7He80J(!N{g+rSO&ljo*??hT?CEuri1rcTIY-WL?``jd6oms z44rHoYPSO~*Y!%TMJrwQLFaiN)(!!X(Pr`>L!?^GH&k@8+eUO5qO>SH(OG=_HeL9; zn1V&nuB(?OSNN(AsEYhZdb|3kD)fzspzkt0p--JGXRyeZNmL6KhL-_y7zGJ10sQbd z)J3|9A$I{weF7+eNVC9Rh`kD?*8@!heb34eTM*#|x{>wJZ_P*yI28YL+F24@wiFcU zH#)Q?1`xh1h>{YA-#-QvYWL#&Uwz(FP5Gp??N_!2HzRRIardZjPD-`!!m9+4{0^?>Qx3qN_BGbhrgQt8dQE1{>^It zu@_kRKm&vM2dKQ#-y7g5?viGsa%<*S*1)hHpsRGG#K`dt{uQ$0fKfQ7d~Xo*be7{8vwf~ z3crAG!Zvx6aBRmYawENzdsB=(B4SA-)tjMa9*gT7&H{# z3Ghm+^pzdKpEKvofBG-7lz1G}+J~vdbZCA4iSR)YRCJ7|>Tt6xC4{b*<=vQ+ zJaFjz!xz($uN8%Ad=lx{{!o@F7xNPIsTKZ-AV+~qTiT!^+gFD)L$I*ow|w#P<_&GA z4f~?5r$F=b7cB#E7FY&tBIVFWv;#P_Sz+2DF~Pu~jFDhf!U~G{=V7b^acGd_BE~iQ zk<)263-CJZqtAWs(fclo+NN_(alKw*nUkLHMBJd+0b2m|1>zfRi`JzAlfGc#agUgP zKj)48#fa!3EV@PV|Ne>a=Q4d4f!>DgXH0jll+K&&109*usQ6Kr^`+tosS2aX`g2zr zqs%4j&3R9&EgXgcI_Nxbe9E|>zc>gsz*(QV`H1s32vbB_;5FpF?L87L9Ncq<^8$(` z3?y?~DJWPSn}k>Tet4{%jc)aybyt(AzgRV_)Sz!pv3gL-YnK>q5_QA|Qm$oIf|3rn za%zZ3RIFnY;fdCi+x-9_XL;;8P%=yqkry1MAV6U3Uc$TbvQNf##p^@EvQ+ zWklx`tN&0mDQUf_9eMPfthw3>3f2UbLS6+AZ2Al-!=8{DaGzi4q$^!Mm<-$=q<^__>WU+hj*wclTOn z2ga9}dZa(+Li$v!V8be^+!$aYV@3iL5_ecK(55wa9Mo0QF!oQt z2)7L|8_K;M6--()RgEuRaEy8_51Cy&6^7&2n;0 zJSu|$UiU0yY^1*(`l_6;d(P3TUq%&k8rTRhce4a+6`;4j4xl!84V*fyyh9IBqMJV; zjYm0c%aoMZ5b;priQ_aa=ST^b*UCzJtIG=i41qQh{mT##xp8Ty6?FGeXKEs{YR)`A zEAZlqcZPklJoZWW@0&lLUdK+&?cn@5z!HTRr$$NV0mj+64T{DqHODYJ;ryz5hy5ADv-d(ltd!oDcTE5r2dKk51 zT1+gZe7gqk(V<_4PQ->0yO+sxs~rI`E{{y(6P;1t4)F3{X9mzy$iLxgT0*C%xa8PQ zSGrzGXraJo%;-cot=aQ3RMWJ93ieP2BXk5m1iS(!iBy%cA`n6w=)`PiIf6=u!j~uh zoPIBDu5Yg??6uG+c>YlP(1NoO4KM?#8Ggva8qd*9;k+L@qL!FK~N-WYNG7cA|hRy;|NCHjdN z|EpBy_A~8itB!q;M)|Nl)<->T>rp@zlu2dEN}j4h3N#g zwgo60JJKm<;-GcEwtpo4hyx`@P zsfS>lA%w4-?sXRY{GA2Nu3uV${&F(#^;vh>17$kWm9J-`h4pclabmh+SN^a zRi7J)N?~UhxiO6=~ARejXAOP(Z#B90;cxHl!Nd)gX;`<npaM5_*|8%X(#xcPix% zr(Zm`OS<5pFxgbdr7QaU~KlifI+;A)q^%Igm5w@=&3Q5 z5rzS7`S~0z6yy?*fSXJKo(hHf(?Gt^@CUxrHeds)eIqRGPyZjEcgE5HcPr?>SiHT! z5}*!j4I8x4@bVx2Slbj}R?ht-N}5}9lIsdCuBhj{$ZjGrKu_%XzovG< zdO@vDq*($+kTm-c!(a3Nu=k!(O?~UWFo=LsrFVi93sn#V6^U3VA_5kw5EYRQA_Ac< zMd=*`6x5)g2m+DbiF6U^O=_A*mqaNGNb-Lt`@Cn|arfT$?sM)P=YBe0gb_(ttTpE| zpYkhed?EVfRO!l4QhkBPn!Vh`Dq~eO2YJi%@gENpb%sK2$9Uo!ByN22q4xcAhugL8 zjmPx#FfqmmL%MV@>@b?WMNe<&;pF20XK(C+Ilj|f&6FA=xFUbwCqDj3vd>w>7C*iBw*Eho=&Zc9J~RIbN3=JQt$!sgGM&y?4&}=m*NuS2XFWdlvEQgM#wwUhi=QyirKbkmHo# z)?@Qce3YM0h@Rqj`i;nx{B}oo5$_D0^y^`Js)1}1g0T-IacuK;ARHVF11J){%A}Yf zc&U9xreC5J2x62C0uh|G$$fWUi_M;Nl@G*+Ht1V#-8P`Tkr&#EV{qWXyCZt2ePrQE zs>Fs5K=kQqAC4|@*ttrHtQnmA-g^IsW|Fh6>!Egk_6b@Du7?EC6X|t zHfg=c%}bMM65;zO1XAS|o7=OWq(pg-`}5Y#y*~R9Mcps5@&?$GWq*tumQbB~%+%H!3O z1If+`17vKacTjW#wWUoS+&_Eqe^m4TM6C1Qi3|U)z9MyS|C%d=>IXgt!2qUa1gHJQ zblVi%#w-5ov~{St5%>GW>i7<$;{-sd+03)-Xn=0pzjvqp)r64E9kT7{!A;aL9#8E&g2xiM}|b_BIX_7)dNO+M}!`ct2=ipLd) zfs`*3QyI{9CSaotj-X)70fC|b&DZ@k_C_n^^S;>z(3zR6C#H;&@QK3=l5u|Ack z*^}z5bEQ}puvqya(mw1{*pk^tW1-aO&1(?Jk<9<>{ zir>9!ajT-7tNQ5m`;*e_BV)&-y`f6K3Xib#F%C0&W+bSapUn_x7PGQ4N)?96dwJMH zYyaBEBX6J+8`Ff0`48sU6B4Jh6=LIm;$;8v7f*t@{2!pc0SY-bp!^SxPrI-YFjyCA zI8BuUWaHtLhxNtk%6<}dE;&j%=Dn94{m(kEH-h!}cQg*Gk@Vk~zkBVUP&>Bj!HSv( zu{DPlxFf|F5g%(tJwD|fb-RfIW%5Sr8W&E`YkMYTjXYQ0PRZR!uye0?925GPb$>0u zIpF?|;{nQj0znOMZpk7moI7srcriVeg;UOP75HeL%&gwniFjd=Ec@RbrQNdGQP(q$ zUW(DPoRXUIm|!`;i$xNqF|Zl~gg4e(!@6daO_FxhS^|P(_;hV#RJL(ofLuE2@uZV0 ze&Dov?A=tOE{=9QoQ<7Q10AOllq%Fc`ARt+ml=B;UIHpARLuv9bvlY)TMs^7 zpScT}C?)Qi2FY+h8&_wqfKg)|F=mdv`cUG%`A=C(^u+rp_o~RO}BwDpmP$spwLa z!n2PBDix>0L>W^+6U%JnD1mq4nnN{wo=8W6zUuU)^D{i5p-b~W<-r(u^v|yW?a(SbFguYA_X!?}iOlUUx z(rfrf%@sVrXJO+a2r(p4EUl$UDC)wFb8?9Jj9ld@?-ZQ(gg@KPl|env*Jdx0h=3#X zf%p5;#yiUDO6krq^kEVxsn+{Lyx$*s<1I+$pHx>+h}iK;yom0Sfx$kQ+PRWiGTQjO+*o(#fq!6{Zlb_pms_Ya{2BdXmY>=_D8LIc`V=`h=&6n*n9!p`T7)er zd7Cg?Aw1A5AN9@Wa{#j-*j5}+fs(t+a&c~?pfxGtoa~X$H&~c>-!X+<2R45=%6-FV zh>#v8OX+JxMV=B)Dh#P^q+VV3wDkN>gFLx55w16v zs_0#l;BkQg21Q>j8b!H^kVM;&#+uuQ*1g4Cg09YsW21hRkjgyIjUP(2&X2U===^yw z>uk5&2SovInI|LwUJ0N{SW$g9TKi)QP;G|GR)o%Wa>CrY6S>#BOn%nR%2eJTN zST9wqV<(17UEO+6=lk<6rw8Aj7FfhH*2n&ogJ(YiV(J~n3EEA1jjjz9MYxjYNQQVr zj2c6oEr#SrRF=If+_#Q7_f1F%TjwQL#F_)(eme8{W9%~+iZ_xb@)mRf@o(VV7QIvb zYgk^IImI4$nDx9Pv*VGN_>O1OXhcfH@ z$;mnafFgCJhy)NXp$ZI58bzIRpy&KjYZ8G2nxzqN!221E?+ZayFE^`$ifeSZ{f?zv zD!=tozufC=H`#~&1?&n^K@2K-izolI3ab56*>Mo{6nWcTjabYmFryCT)ADuU>DxY#N zoau+uo7og*j}s%xlXjxWKJ9Rb@CP+vVhaDv`q>D=<*EE|rz~}3q-T*rmHIhR@84bx z9m$uhWHht;`FUD&u=8>Z4yPRf8?f##faDSvjbQ&(iC7NQwYwAN6m~6We7f~-hSB`j zdSY0ZyUu-|6QX@bYcsfy&_AuO##3PLYn1B93KTEBybIIz8;%@w-}^{iI;bPjOZ0$- zz*pWcQz9>!psR>-=gw*NjSnz00UskRlIp69B!|jQ+LZD?Qb;_R%RBo;Fj;E9;%9!A zqhe>=e?YKW08RKjLlR6%wdYS&#l5kH(>fWanld`imJf5qIdXh1+!Q(Paq!i(Z!zcC z&UKgv+%`hqV01y{z+mZM*te#=Fe;}@p(Bl8&p&Ax9w_2I9cU5Z`ur|2&$IWe4r`(g zHXcbJ1DUMRMzDFD=+7H;bU7hcPpSy9a<+$&;2L}^a?C20q-hs-^~ar)qOJQ4y`Kpx ze&=pHi`0P#&w*T4XS*r1@fuWx5s(WvvL&cGJjA}BGry|zo$Jq*)z&`E*px5lN{v1H zt9v=NvcqouC>dqMD{XbwY`7g8G|Cd5CDM<7hIm5M3(gm~xlOcJuFq6_ z`XXt2He;|Bb?ni5Lnn@RvA=GCfykAI%)2SauIXoUyMsLVsCyxo1{r)bxxt4LfEqTl z5L39g-Bc`ATRm{_Sxw{-qNV-NC)BYQ8nF?2mTJ!cO%~4!pG0*)6mzqQLwG`Fho{In zX~mIcFVza(11_U0Zq(vLJp3eS<07bJaB(QuLjNzOFC*KP;G?dBNrxm{oo(BLsJqE|~w*iYgzV<}MV)8p{v7bD?{E z`zJ%rB(^eyQElBzah{65w!h!he`jl3ixWi33Gafh}$ z1ljHH0qF$QN;P)4l^m~9gmxrpz0Azg!;l)4uDF}beosgqmA*MTn3Hkh_p4;W@0ULL zl+(m&nhHa`R#P#r^MZ$+ICB}YVaKQ|C+HnUNHiF?~oOH{~0wbYt2J7fLp4V+mn5sf=oK0M^ z@%Uw{US^Q^(@5;DOqHHy2*z(p2Y(o+3_7Q|D$}3O@D*}CpcG|<>FuE>V+3UZC-d`Ak|4b4R-9S zIe3f&TJt;Zpk2pa7jg?Ns!y>aRy^=`Ra><;B#1(%Ow`~rePk}5J7fZ`)#h#=+v%n6 z9eNSjTVo`9@Wzh>1gyu|F&adwj@4sE+gS|RF{fRkN^V@k7I4dJ6l~ve9=2Krx*8%3 zj^~&iMgg<-UR%laVVLXVE{KtgbJ!_hZKn;_in_Rf9TCPAHNWP9H}Y z0~97+Ygh=}xilE%llR|C{BsSg|J>25Zu2O{E=hOeRHgW$MgVseCmbE?-l2(Ez zAa;Zm{$d)w!@%8NqWt-X*XI9aH{w6jx%j{QS(ZO>3?2~mpUH<9gLd!x7$7)wI*1Vj z)a>wEmp7N`;KY@H7L?cNpa=M`St5^+<%<8AUJ^qFq^Cuw-_P(9c8sssSmfHOA8K+I zl12fGz|Sa7Mh~81jfEF~fH)Jv1l`*AzinnSNmbACj8mM6=z z5IK}gR%{Jv@FEJ9#L(Q5DqRtO$ORDL0Yoii>cNh!!W#LEtJ&n$9R=GY#;dg;TH1~! z$Yb;=^3j4MabIZ%KPX$P83T|(P$C`zQC zn4PmB2Poc2n%TkK_DUTSQW-cW)``NY^V}nKX5wFjUYw6e-Xj$KMMvHj)$9rR0HJ*# zy22}&(Q6pmsE zMZP{nHEeBEYZteViU4MaC7HI>v10NmZ*BDTC6m%y9l==9+=>Lz#H9XWI^;^tW^@`M z*CJ2RKmEtRJx$lZ9sfUZhAF~61CQu`*2dt$5rB`Ts$r)wM0g_&j2I|$olQqzZ$eUJ z0B2tGLy20=$zscSg9P0_-D3QwR_}bM-Nz>s{_EZyX1dM*DiTL=&7=tnkTzEWsA?S$ zYnT!`?kbfuAH<1HGZ?Ehj^9qNd-v^Fx2I;F@C&;Yj<192PT#HMg*bPT{$@uh=QSyw zp|kfTPY_Q9)3y@4M6W>-2*`=xjcoe6%2h#Elu&~YW%GRE_Qin)B(cXWRIl%HwZU!i z6h5;Prujcpn(xW4iCXNk-`T!E%@#CJ#Ivf<*CBO8EahSN?x?_ z-ZIaY7m@OYGF%Y`C-2=ki!?rh1p^X7A+kzpb9p}~O}5~7R9}-J;J@L`zF=|)jqw}LiF_t3kA8h-Gylx878}br1+w^6SO>B3n*JQ=%FWw0k>8Gz2sz*XqcK4% zi5Jea$u=(^UYQ;?DpXMW(Nz&rCc~A-ldA}Q+L34*_PAY>6p(pJIj+{fYTuVHD{DFX zU9c@k__Q|Ql~SP%Yj}W&2nT*3W*^aPqnr9kZMLK3dEZ9s638aH0~fs|mm(824+tMR z!5aTuSCzL9NAV1xiO7)?Hdi)@$R`;75Fe6Rj5HUVB0qZIFD9>P;}0_~o9--KT%W%E z_#$`cOngKv>x1vCzCie9UC`?HI5;LjsA=}oL!yDFxD=Izh<~gngT@juj{(r`59~kM z**X!Q6*BR3W0^lVJLZn!Z{c*&w`r9JRM|-1J|l)-3BkEwm1F^J{w76WHHb@W;-OiO zsnI+`iDwja&%cG^%%S7v!i=EvT9s}2KeKr?Jrc+7>wdP0{EREb3pdHy(qv#OlD9DG z{F(Noh_&ou2htIdhh>J|oL|4@)*pDvymVHIRfy)q7{E|aY7_Mv;qYuBdLT>_z1m{z z=l{ogo*^|dH}tSaRhf7&ao_i&95q+_YB77u)#b<5(!sT@0?(!pd$59!gDw8>J3Q1m zFj*b1t6e+=J6^+utMj|9?lr$u?O^+;v|gcw?FRY5ai%xnk9g}o>;i;KkyWotcb71D z^L^T7xR^L;65Pj!4*M#qnfFS&Rj8+@&2r!?d9P4>_fJn<^|SfKkYX6P`Qa;!F+Co* zlQ$t3UZ?W!TuoeEF>?wn?DBor_eWS=D?5!ny^DDdt2vqljBf@$VCCuI0E}6_bC1!1 z;0jYb6T1)~eTuUF{-du;&eN(_WNEiU#;5l_Zb>y(dh$0hgb^g=IyM^Ua`lZvp8;40 z6?!W-EsTy=#Qj;geG~klJ&@~QYu>%N#%;Yg{sQ?bW6iW-`d*m*UpqYb$Z4&^$vtP z2aqA7`ub>6V9>{kfm%c*E-tZ|C#{R?LC_3uByg)!5 z2vHdtbD)m3Oip&%ADEKoEwpx!*Mpu7YP@+NJ;AoG&Fh-X-l`EV=YI~n{smF)Lo{KH zRmOgyon!M>O+rI!jdmofHqM12T_oGvqR}d!bFpLEsj}%Bfnj&|2|Sq1zxtr?>sh2& zmOt8l;wB9JDIWXKLypdzcvRMN+yAKsw!Jc5oo9`8|(eNVb)oz9*iArZsz z=GDhy`U`L%lprYPz<)BTc?b0f2(6r4?}pfwCR_&5Q7xxl4Ud}tx>MTjA`RESHF06_lIN>pd)&PTfrIwd%6Tsk&ZQ zVK@~V-yz%nj7_0-`w1CKlg=l+k^nvB9~hn{F}JMEc2kr|ti9#X_2-lGL9Ap|>4UP2 z?PaAWk3Jr7Qrh`EZqEE0x10o`!~i@34$bdl8njBf^ocxXF(jmEg+nFveb=qUTjq_BZjl zVYt14nTFMC#1n&BkrL{&6Qxf@)Z7mK(b(jgjBB&Vp6mRx^*>0Zp-~{_?RKiaI^lNx z;06BX2QO_k2Aul3M?QfM{}R@BRSy_-d~qa?kW&m7!TM>Wffe-MEc3tlFf#v3wt3if zu(0|N6k80a^|itT(B8z=mYvB^Bq^%R#i=gTG?(8v$2EG!CQIvfb#IpGmw4Y#7mu>| zcc6ay+R#h%6wy&68|tggHjK1AT+^$Ht8yAE$$~GP(s|xQF?0lA{GD3tkEnmEq9#K? zPxO-mh#T*_gXn+<@x%^EsAFi-%XQBegaF}?Vq|m!DsLg70CsNE_Rt$IoNTSUS6Sm# zemV9++(FhCmiEg=ViVxGupcz?0{TTA7#Y7 zir76SMUSL9G+LQ%Ne1_`|53UaHV3uw;tn9^o6txA-U|IrCE21$slf70aUmMa@RVt0L11?^co3L)RPcD z&?0QzK0R+4bh~2Img;pOd36f%<187fxixnNy-v@>Cg42!U^T<#$(_A4|0dX*D%T!V zl}YM3F~RvU&P6lu7a#v!e#1W>CLZKTACD)OfDNGuwFw|9*y%#vPjH)mKnLoFEh7qd zH|ePrP$pQ;r*wX{eb@f(XFdV5f5Db@y1l@0?;qRoc9sUGN1hS6@_>+~!F~w_fY=Ip zJTxCXhNED>P2!;MfgPzL#&9!btaV1E-#NILw_V(+3Y&kKs%ffH*=C}A+2WCtg4C6L zd!5-H>49cg_!`uFykR$exe1)p@sSRkV?nRumm`f9oa2wz3-b(GvdJeySZgDx9&` zC3(?7hZ+?@lXySX{o{N<$>Jy1ev?D{zhjRpW_&)(G`HuG-brvNO5h{*HGl^7-XIF2 z@q_Ksrt~Q|iuB>?(ABZIa$%oVw<1Y9yB4vp2k#fPzsx)m#TjokJ(5YlO3vf>8`PXj z&;izi>vR!wGmSCxAun=WW$n$BT7~%Z+sOv{XOyl!LW0EA6M~N)Zvhz!&Sm9VJDw}- zXnrf63y!6)dg~(na_F_1<#Jxhwsoe`j#F2@Pa6z8Zv415392w~S>qHn8h_`8-4IZ( zmNx0p59{AfEd4k`uy?l_RQ%ZcRqwj}hu9P>#|Ji>>eE5a?TCpuBIYyQf5-%=wV3UJ zk=JngD#h=su@eh_rrs!=mo=3w=L*+g785NYiKYG&NO#8OA%Tw{t%*0E!v#8ll^SCBEg}XjcnMI zVDI?qI;~7~%+F;q(#k`~vjlhHnyRW?MYyrk!^9)Q_4Tg`A3ZQW^C*Y64f>wR;OeGe zKZC}igeld#T`ksxD$x2G(PY<+nS6uKn>Uet0Hm%sgxSc(reyhPp*seDcYX#YcL3!Ri|at8eeF z(Ew{?DP^N#M!uGUXhU(>ok_^3mU`Y8{(Im>p77X#)pIxQ-n;8}%j#R&!QUsgGHHAe zgZmjJlg3XbYtXI&gSESG5|yKO)XrYv%}`Gy=51i%K)3ACfIugg?>YAr3jyEnsDcf2 zSr<6moP}+OcEtg0+dq?tjXZ5Ez8@AdQ^qGI!_S5P{&GV^{&AONvSMZnKAyn~#yoQ) zGyzf{H@ek0@fyp_eAY|xh`KLK3S7zMM{e!Y=?xTQ9vu6Dr3teD_Yg`oP0(&5VpvZJ zEzoHJSgGF8C-fR!ee&qlW+R7gT;I90oFabo61K0E-8*~sbX-`a)nTeL8UHwJk84%+ z>r>SHr!*1g(1Vc^p}|(wLyk4~HExJIn}1{15z}M_P#wNZ#=Zms5|-<0ZG0dlXH`SR zBsN$(ijT#p77Gt|aXH2N_n#A^eRx)Sc<#iXKRU%RoXRDWX*UtxV2-nkB7 z$y+<@Xka*1zjMq5;?zS-_SP9Z>+|&s^sSh7tA22++gIJ3*}vuSWRSzQ6j1V>bi8ablVCzB7m%AA!nmOekC>lKtXOT_aM_?$z+6=Cz1IuAr z?>ZW(6PxC6Fn7yWk78Y2m38;$)qDD1WH~2l0D0McGxevfR!#2*X|G(P;MyPod5R^5 zD)%{np%G~nZpwyl6HZ-pmEB{{UG~L^D@QWCR`g^J&l6&1Yp4KWuJsjri-Y(Od60IR zn4rh4bh$j?MaJmFzEPcA))>c1L9SF|;9r!rHOAl=0x|9_h;c%=4d19{Y2}96el1V& z`9*Q|Xcd)F_XJr&NynCGlE&ei>`4!PeUG}Y$Q^2WW8L0%On>l~8n(o9dAW$>nqLE4 zJ3v5?d268)P9^RG75z_)R^?SNsnTcAU||2yRzS}+taxC z{N1C;=T@q9bb60Ju`gx{1CxF&Rn+%tsA;l z!SyTo=K02bN99UwEXr8Q(tXOE!GvY+4Um3%Hh>oE-ds4zhbm!D^$jtA(-iVDPG~z` z5k7HB{wjCbbMyN8OH1h*!Z+p0R(_;yt55|(w@xZQgP;v6@<5iAJ@jHp{vu5vyw5EhPEc^wU;2Boy}d z4m1l9ASz20IBpDi^FcKahQ_pXR6pQD)4=i6#xsGXOX`72^l2JkE8al-$A2{J5kPkA z_LfC36oY9)(uGYFUvUGvNjI@Y)4Ia{(}{cEdyVD053S7HC$mVH-5i_u``=A2wStuMRXsg2?C~e@+i`K6+S!`)3j%bCN>nJ=1DTK*BGyS-f(&I zf&PZlq+QO1L*p#oCz^d49K!-Tcw@l=R74U!A-TXG`MgOwd<#f|veS&pVf;RoFwR8>-Z76bQMau3*`c>TN?q#MAX->T9QF@aQw@}NI-)U| zuAu8Nw^fE+9c{f_HAuc&Ssgwt`b$ahHnU!X6$yAR0JkZgsEuS$YlRrlUpJT$@oacF zbteQ9y^tK}z zwxxT#VdKaSmKyrZGQ#I|U_0Os90(2jj{37o=>ru4$PznTSbq1$(v2_-E(X0+Ho9z_ zrUklgej%n^G}0cRJb4_5jkdi$)8j~)5qRkd32-q|_|76S);G0j67H0s9kLoQRVKV^ z%sYMt7q!lrbimuyLb;dQ|nlFc)0)In}cu6jhv>}iv9 z`I5qPZ=;Wn#e4yGd8zl=`)At2W}s$KBq8cGGspq-XlI7;ro$z=x2Y2C<`;!=B$MaD z2Q2pA_H-9HByqpfhxJ9Clci(C#k0JTO>+N@8UGJs##y#NZ3Sq~PG$neR1+eyquxDG zwLyU%Kf~LYp(*dW=`&^K$NM~pS;OoID%gJm+dRS8Xi}mnQ2IJiQMT1jL!5FJ!VXb- z>zS)?Lw*u|uV)rCc*N}D!&&y6v^3Y>%Yu3t)JYRp*pXbs@k=-)8B*y9aW}zq=94GQ z06(7NtY@tvanl32KB>D7&=2llX#@apM}|k6YXeX50Z@d_jZ}IXj!+bKnqt_BiDM{JFi+Q}k;WNgm&?#k zk7?G0@EaNYIQ-N9p6#2OKXA<$3 zZ%94Cwjfzv#b%711^r1-lRo>O8Y4`A=jwfkYZ zK$R~UqSnE`VwrXX7_!Xta^yUL7WfwvBm;UEesmtFxdd04-v&);1ENzXX*E_)WklDN zWEA51!L{oHYWYvbv`odrB*mOtnu&pPKew%ZBmYUa<1C^`=zn2-!Ga{<02C0j0y>kd ztY9mpf-aDEtGz_aHkfFd9yYCvwCnL#GJcwDSM-2I;O2E(*JwI+grYGx(FJjn0{tz+4JH{`%j@=I%8V^*m zMw)48)l`?qitVYUs;+rRlYw=18(3`p(5!e9H(+#-@P9EGmndyL!7jBjcno%bTgVmg zZw8~CAwe-~X+)X~`>klVA6WG5ggz)dbKldfA_??7P}V=0){|QVn2XAQW@um6ap=}Um_Y5Q z3aJy}THAnr=eA{48<4%9tu^P|=i^qgLg?p&!0c8?1boVBsvcS~Pv zuXrb5B;*07F#w7Xqly3q?h@(|Qc_E8#Y~Ex@&nNK?w&1oFW?YP9i9KsTw^`*%1I{h zv8cKl7zR}d(Nq}C7=A6(Q$*EV3qsJvt>>c)@U1UdG3VMUsrHe2zFPl_+~mHK_rIQU z|DR5_aoG@ja*iC8)O2(=Q*1iq(xj2KEv4P;JGl@hHFVeiw~De}pI}Ot_-po84d09w z@1A)iM3?`21w0F|j*`I#90+3q|6X19)V7Axa~3mR9~pEM?qAyGo-ZAip5nj2&ySUi z=H%CY zix1?tOLG0x>xL_1EH35t9e>~-K5238?XNq9oa%b(XAv#P6(=gT15;tRB1bk84LLWW z#ckIi-uqEE>)F`Ttr(dHP38`JE58`b`q7Rvqh=N4~}Q$&UCI>`&kgzsm= zozh%|wGbO8hnh|$NvJ&yF;yv?3Vj!%eyCQ?#qB%6V{+~p`>XeNYRRnV9NsrLLOf2C z=CgAafZ_Bw(5?1t2g9RbyV+8cWd^`U(Gy*)j>55!8K`&lnsFyB)M%n5-C*-dCgVn-W|*rgRF zVqitJ?21aUB4I~oA|_5xD($MhtR=>HM7e~!w)Ok^n;& z%-B~z0m6|^dIb=rvvvFFjKZkgiA@KYF;&K7fmYM`z<=NiKbrmyywa=L9I^j&-r-H%1J7Ai3#x6@C=swxiLCF zl2P!HF<`f}0jl3{40>>=9eJRF8)ZrjEi(2#R8L$YItB-G?BPGUDc31ueqSsN%~2@f z0;+Olh|mQkh9PnA8=$NBBhxm0wbkT|IJc)`W=O`wz4y*W*A0v(B~14}D@#Nze}%$v zAx)a-C|e337Yn-qnd**WlFD&|hWf!GBhtn%9VucQgI(qZ&Ak`8jRdagEno@)AgywQ zzNZY)DE*;d@;2+7wRg2eCMv$xU#J$){*6&0}Pkre}Q4e>R#njEk zHrN-siTA~D9^@8&iUy2V;3_S+!`>Rj7h*zjL)2D@ciIrTL#;; zjZLsU@e47zG;!C$PS+>O%U&+kCiklG#D@d7WLQ4X0S9nw*QEzT&ruDNb(;~T3O^}u zvqE_euT8UC?g+mqynM61A;sfP#Gl9m6^=Dbsb*6cR=xeO*@h2%?F}&Et>eJ}lXBSW zyUjwKQ+)8js(600f_wLrzb%`bK7O3PEtUEADov7`is`^GL4;&TT-TH!(cPogW?AQ1 zS%{xFF&QTj9QQ@#m%{lG>+|xDjy2m)K4#TNbj(DN5=>h4o=UIC7d);@YsnFAhxM*p?;R+SsD`g{V_V-3jly)S(Sh@#)k-wUHQTEuu zlxNBMqB2=D3h3mBzuJ+4dCA|xbmCg{*X=mrA}hIFe`)GSN`CkqyHzIpQY!W9 zV$iYM?M$Jd0kXFhE+B#Q67-&TlcX6{>hc4%c-@Nx`l+33fo#%?hL4S2McqsH|8kZf z#(Rm@^|zg<1(QERWl=5O`{%VMB9fkjxEA9P{Gr(o6ecGPStj(Au-6Y6=l$;E>i_6? zM19A?-CZi7;(n{-{Z@{riJInxv209C_n9PbS!FZEfM0VfW-^}u;JTZn%t#NK1u;~A z(0A{*fiCw`&fTxY%%fs&bTL1B66ti((n$uIsDl5G;A1G2-k+IS`qb))*}1`-jxOEWT5&up(D zKVAVhrLc*U&8)=(j)__ic=1loH@S;W_Dx@Brh#^R^DIW9AruR~xzK@>$QC^JbV9IQwB4fg z!BN$w$-=4666mOJ6CWjmKV9mG7A+K>x?#lh14kgCw$62S0=5KG>t9Uoszw%e`DR-e zt(HMkB zE&^j5poF7ni)8SNoBhQkw_6L@FeZU5==BPSCa;NM7y^%s#Ilxpkn_}oo-?+g zq_dM98bA$n3yjX$e?b3SSYW*cCkGJ-_rWNdCPZfJ&wp=IwXUd?ado? zk07B)2WVU`eS7x*2Q*mCB4|PZ44zUL1$G`#O(`x2(V_50{Df=C#cU*#Gxy);(zEmC z)AG4F&1Q{;z9qEgxd~m-Pd?_vg!uT(>W?A#!z)5U7z6hJ@WzZ1wH(}KUA3rp%i%L_ z;=U32uuEUgM+8;EyOVcY9>D>vuIxf5q;q%|uEsK4SCNDbY+@g?FqnGl@pm4+m%PY- zgtm8yworwn1Y31RlaQ{k2_@0>cyrv2!7=v!DeXVtt!}XlpIyOz_D0&}q4oB(b_9zq z=SNpuJ5PGiwCf)Rzfn1sScY@L5i;-;E8d7*LgCW@hl6l%K%ir>%ef;oePWOC9@Ko< z7m0hzPIqHA^t#NGCyfqTYdqrZS&ja0RlA_SSGB`Nfb_l)L%EOqjE5B-lFyEolmHH_ z^x0w{lk)nBvZwFecxHb4ubobx6!kgAQ=S~%cRd5~BJ3Cl&P1ApPq9%5a@W`+>poG$ zoO%}_h>GEJae*%Cen4ggTv@O=(B2d3$wcI@Wo?`S8)^ev5JUu}%;FfU#Id&M-X zIXq41JcCCU207c_R;mE{l4U)dPL&p(3?NSLA*s_-I-ns{iKCo|t)DDkH1=P-x}Qd* z0$*ER(o(`b%K?B9;+}Bb0$#Rop?gfzyTKXtz8r@$rcBU<8(Z`p&>?BA!j-S?&dRbz zo0QQz*Wh$-l4p>FU2ybTg2T+rfaT2I$0u?pPxEFRyJGz#t^fY6p(aU(HyX939|D3= z1Zy7v!sjyN9>L%tT@Y!;z~(oBEkhyTo-t&G>8ZGRbt;HE91>=X^SS@<3N{}14<805 zgaj-N!J0p{sBTBQ2(tz{yA1Mb?6fw?+r{u5?^T(LU^#$X_|#X)6bgnF2i(HCP-~*Q z>Mjx7`MY+@Kp*G|1Rpkh1Q9Yp^NEJ%ZjzWn$1b&QidSq8HB|;kjr3tOE+lH_`6Sdt z96K?G)#?Y5!qteD)yW;gEH<%85H2^P8bqCttFcbX40vxE|6KK!hptA_uTNs4PRe=e z>xKUyxv2D8gu$}}4lOr#OlAIZHW459nrp~um}X45Kh^Zn)ss1uv}*WL&P0~1jCV$l zn&#Y3z1%6`zP=c)0jdfXT?^DG`^p~>o8K~eKz9HYx6UgFJ5^$z%p4ic{#K(WWrQ() zea_fbysKlx@#P(n7 zGF;OYmwy+QV?|>mfAHu0#bjIA&gjFHV;=+AQDlTT>M=tK?Rbfj6!Fl7R&TG@q7vP} zWdD6OFXa=b(d?@vW#gaqm;T`%{kuG+(k${HmEJ!7vsZIi82g<62IY7KEgO9TP!7d0 znxF`S6S1px+pM7qI*+94_^i%0@dl(@`GDrqNwsycThrCOE@aUJ?YnF#nf{}b_3n4D zv;%z%V4Mjc-rrMh1LsVuKcET9u1k}luC_w3vRd1UT}SeasUvB@vl7XJ?~>T3TCrN* zDQPUh_vFWxrvURnt|l|xFbtUNnL|%e6brLRUl>aiiC3mwd;k6GCsd1E>dYV0^vnl& z6r+!_{LHO@?*`r^=3b$aU%u%TwvN*5@=edW;v?G73jd(gV;B2wxI+QwOesw zA^KU6pz9{mY2?Qxx9l zhj<~hNt=0SuGw%A>fyB#Be}h7mX@qGqHLB|iiG(bz$FenbXAQS&?QiHyUFHhQL6nG>e00xQ2+$rIJF($!>7%(RBJf2n zcHgkDv%d$cIWtfkXLBdi1GZ)B#_{2>lSzB>+fNv05o}c}52ZZJQo3yCg|B$_*?ubU z={{;Nya|8Ns-y-wNMQK*b7o0_>ONj34^dpqo&t7oc9 z3(w7_DXH&R(pMFYpP?5$24@25U3K5=>9`#6C!s!QPS+8bV1}Kr`m|_yf6A^$s=cvg zzih?{FtHco%Db=6E|XaKH6#$;A>hX$qG}}>8!at6)SyIE1Ru!< zC$E}`y)tuS+IHMH4^F*EoD*`=k$f4+3$)8Q?7RitM37E{E0wP_LQiVFIN37UCA)mj z$m>T1dF25zf#lQ2gR9Rp<6FPro2=ofXb~^@p@vyHm$vbZ5 zSS6+Bb%9dz`-vhAdz4$M>@UCYeXXZGSp!b&Ir@;R^}$>^2%TY2Gb)T3>}%5@i)z@6 zd~vw4N1E9;^et+l%dx=joSk#_tPvZ$c}pa|tiXv&--#WVXal!}^WiF zqKBA--;H*6YHN##~Lv)YL;esL4M8PyuBMinl)*Lz{$;w zn%hi@o6jI>nks%ZJ-4l6msh6j=y56N(Q;91`d(j@)fg326zoDFa@5t9K3HkB!?+>9 zyTFU8S9z%Xjs4UwH1=TuL>}t$ZI$Zk-7(7?rD)WQwZ+Z>m{1z5PuYX@dF=FYL&UGuHO!L@QbM!3h*C(4xo0H@dF(v41!e30WYj{q)Y9`74ykSGt zptm*E*`IQ%74(Ju&lSVw?43}B6-^S_kqi5VkoMA(LZ^`~jEVoue&|tYvsQfQC*Wc| zm((!Tbh%#kTJ&N=!Cqi+8Ja@LC*dL)Cut`KX!ZoU_Z2DvDD-<&2Zg%^y|e2I3=R&^X!UmGa&s`g>wnNfNdHdTBPRK=7Cla| zg&8LV;)lU8HsKK>Jdb3$c7E@T=LvAkTE-CwNlzJC z@HklVj{w90&onUus?M4rm0x=8_v%a3RBkndyFc%DmVYjnydtK|Y`)(EL3TFkSF5By zz?+no1EKtqpLS@^+tCe!U#|4W=BBn$ANK-VqF;#@(}mL0(<4F9i6ua;eG?es=CV8G zi8*zy4KL^lw9-nR-#FCRpd9c8@2^8X>tG|nzAyIM*~6lH6G0&yLBV$**+EA23eOs% zMr8&bYyBZo@5kLzzN#x!#O!$tDw%5jm4wFrb?i3`e8!!qme}CDa|j#(Cn8)69MFiC zQ!AS^`IhhH=iOD>%oSe#kzpLTN>V>4YWZAMKY0)HrpWScZ*Z0V9QY^U1;LPr9frsS zY3)OSk=-Vv4;LyHDz)@8PW;p_JD=$9#rx>W)E>j}8?@c(^MoD`?JPXE<4;rS4--BA z0cyE7qflB`T32D!`~3DR1^4RzkG*$~hq8V9Mn@_kP4=OTLdqsZvNyUVB#DX;Q%OWj zDj{PokxjNyaYszqB-v$Oc4IHu?-^lcB>T*Wab-5G)9-zs_gT;HzTfry)>`jpJ)igU zS%0Map3Ka3UFUHg=dt-7->=KoOm9UAi8!wF$(*S}+;zVZSTLDbSPx2TghzQk-N3bk zH%?vljXT><2{x}Wx^P1RQruC0JvTnd^Bw;oW&T6j#1BZ8XcXC!CDLs+AP<{QnU=+v zo5b84xF67dOSw$xP#a0k?FORQl^f^sTo0Z;})D zaJ7<$GiB_JRA5>!+25ewqe=?bt!8;Vdgk`R6;N$DMhkCsItJcSK5L*zTZ_#C=}Fw< z<1uE{R)NwsLt3t-iF@`xrAeew(p}D3{%C*nSPp?-f$E!xE1_{9LuYV>0|Fk;+&(lp z;a(O1;>Iz&5=<^n#Zj=~663L=hJ8zIa*Qq2lYha-U_iN~-muzX3Jt0(^>3uPKhmxw zJ+-(;Bi1L{R}VdYlHPwXxJCDsb823mEPmojf@^dS&zL>L5*KEe3>v7$ZKu5sL3}dbO);&ANR0^Ec^}`xfZypxuFFZn+HAZ!OTX^P~Xa z!<|_VvXO5#Og&y9eSl!cJUH75>HxzvV~*D>a&&!fs_(HX-7KzcpYtQOq=AJGR>SQY z(DRpH+~{UFcGi>*zx?^VpIY-VvN=UBo^kQZ3#yWo?Q{83)6rNn?gEL+cX`gK9ku*|rt>Z@m4UQm zxseFl%n?}+iTPhZ`CJwhQ7j?P!VLvHNFW+2EI^ld0BTYomJhRqiMxOaJG=!s%si(8 zkjs9Hm4;)Wq`UVl50dFN3 zsJcVYD6Q;BcNBpenY@ zcIrVCJ*Al=(W5bw=qW8cl|tBA|L$}_qfdTnnyl&iVPk($O-~+W1NZNE6;1<@b^!w` zJNQY}p+%}Ca&J9EHl~N&%SGuw&b8= z?r-v9{Ns-;FlpLt%o6u|)(-HAUs#G2CAFU_`l`Lwk^;Hn2d0dP8>^2li?qIV!ZZ9@RfLWlW*%(g$UOM*i0ynEtZC4M+yB#%pZd= zAAJC8>Oa5s@7M5e*YaQZH`gYkE{_vHISCoafvoWYI1BnyYamS&%>+f_Z$K9pvP34y zKypBOesaVBNh>JzTC*@(EO87>R6THUe7Ye{7T1xnBlBk;F%$Y{)dza^rXF&LInX>q zk@^|FG|i@E9(aMgXt0m|J=`OoWR&Nw^CEw#vUAV9y-!4+x4n>y4%cqEqjR2TDVt?1 z#pDIWVPJ~w>P;wCh{<1G!8}FLw^=R$&t|l~xLNfK=>#>_7tf(4QFNIm8#!45qFJN{ z#IZTg10303-v9sZ6Bo0C(d2332t-9j-d+tr#z|V#jIX9$x$ADfz3{Dl4j6Yz5xDyr zSAKmlRDO~r1swfyxPjC&n}O~|AOWUsrx*M4>$t<5x_x!b;cuT?CU_;Dba!YV#u!%4SoMP5)hhLunZaYhK{+ ziBi!cx*R?`vWJ6iH=Kc2bT4-jr0Yi)*zjKelzKgQmLcTOF7xz+`iC#oyaG6s6G$w! zj=-|-@Su)QJFgld&D)<|nSkBx*M2tGrhMm(iVBD40Z+mv3}ZzT{s`ErP=V%@N7P^kO6Z3KgB@zMgp*TBp*f}AowP<*Yt)6iHJUM>TTOinh;B?IZ9ng&< zm|r*jLV#YR+h1PsSmEZ#fVUH8@oWOPYyVtO_AZWtgR>dnHPp3?+7@o;V##O=_}4biRdm&8_iUXf}WXh^A!pcL`bJ1iRN2f~O@0 z|KvKjX7dN)y2&ts=F?rj&uB`4C797NoP68XS6q7AU}?8dwHW1PW|%goTm9%hYpnt& zn{LD@2VfKjrRC@c-%Ozd-6d=D1AKDalk+>0l9GJYUf!%sKCLPjJCk_xx|u?PnZ}ua zr@H0-e`K}LwHGWcARu6{V;%)sP9pr|*5LcI1(_*L(rW!OFY-eqRF;OOrK#5{p2~*a zc$!wvyM*}~_xAqpT96U(XYP+?@hZX(+jb4tx}_}Z9y`3-<&d46 zf`QWz=K|*-&Kh*sAt`rhc`(nO=aFHIxa#^Z|J0FA&I10hn0n5d&`4^+72c_{rhF(CD`w0iKXa1!$i?jTS%ka*vX8^rKg{(}j&#SW}6S4C|8h6&g6AU}HqF z&H;2&_$6rZI)*>k0aR!IQ|zKjo|AgtUa%r1cD_kd8RnFt8YZ;^5aO2i&u)|$h*umN-)ncGzywD!%4u< z13=#{H;&_A_4gke!?I<^*NWi$==*AmrsBfTNStdf>6A<`(~&lvmT_OKri-LfJt?n=nmDSFjU zCio;z2Sd#V^5~!j-B>%wsDc; z4)%Vk)RVgs^*2|9{^!enjT}HlOzy;K(8C)v4N!F7@cU>{H_cFsmXzEP<3Lw~J_+Au z#o`ltwy0^zNM_KUku4u_5VPvHoVaP&P@Hhq*G|Thyw!aNCoL)x&vMlyh+I+$+HTr~ zDD3El?+}*m0SK!qTmyR8gRQ?2D(`@e@d65=)r8-Os7cu33baBBLfd*o!;MUBoId+a z-r^DqBBQtaeV;scGr+X^WV(aEGeo_6GFV~nOi*F_F;2edA&_X~h z0^3Lsfg|NlS=idr24AerZ)FBqDBmWldigCmMMeOfoGtI85j=>^p1GDK;}cL%Phx@S zw84GqHzIKWYJB_~;X&9igPNCF2Mf@@08lr#Y(`QX7-JMbZ3sKGRJt}0!zF#AlYJ|7 z)(XS&-VAhfr>+EMISVa&wyIPqDCm3q%>LI_dytem6=j-APS9NQGDs2YmihLfV98ZFXcRD+WQ%`5h&R9I0@>Br*>H=hRa|4F&z*o5G1 zIkyde!0#%J(OQs!{0zs3`}3yL7LYT zSAW-b%30#n6|eY`M`eyli`^sHj60x#$P$jDST=&kPrq6g zOBJo@*tyI4a+~di!OIUroP@zS2=+&?H0;4Zz^PPhq|i9_ObcP#Mg-Moae#(pC;FJjpqnT60&U$aw=)(l8G4n| zO_uCdbGbh=0!|#86#c~{$Bni!HY-JO)x~=RVTN}FZ%jp|` zevrPdLw@2V(sCz%-zS?1{L*ISauR^=#TgfRm&m<%KG?F!wwH@|f$s8Q_{Vo|7BuHD z6;qRb3S)SPyIlpy4s?&i-eK0td-N<_&ww8LpkFQ)EE_J&ctvK=Yahp#?(H_P+mqx2w(bu_gJ@Yl5X4D4dRVc_6lK=q zdHYZGy@?%e)z8}WXSr9hn*j0!3v})HvbgAcPui;}Cw3od z%5f`JSM!pvc{%cBO7>99bX+wMy5B?~%_CtYo)#>85QpJf!Xp=k()J}a50mmag?g1Z z@fiPoaU;R@@rp+;6PCQL6b$Q%@2s9#`$7a&Q!<12c;X;^ou#hwBmDI|srkL*!iKqi zYKcWu6=AWZB7~23QYOqXBiG+E_Bq#vBV`#rLRfs3<0hsl4wa%BsvL5o{Jtd%=eIJG z6!}%jW~fkbkcUs}XPWtbxJUq&ZgVYg6S!e7QDX z@I0Do?szk1vrMs67JJ-@@pw*y9V>6Zx21v^Lk|1bY$ zQGs_Ugr<2>LeS#jbZD+?qGpP-BMLwip0Hnmxfi2;^y(kOA;9$y6IUL`JwY=>deN&h zSSLC#Yhc>XPjR{+#{N0N#(p>MdHa8(v55Un(jB|CKUwR0n9HHrc?n0;`mNGCWXsGz zH&6pacXk9=g9n85K<+|kvI(d#nuAzqtZrj)G3l@Ze~vU7!v)~9moJ8w*1 zh`fJ(=j|C*5#5y~yf8KVNaNG}aSw8KbLtUbQro&87fyLEhltBCWJ54t!9*BK0nn_7 zvOq;8-JGrt0_%Wfj)n>A7^cN?LyjnnrX|$^&vc1BVr7VGa;>)ngiTAjOe6Oq5^PCE zH}fy6ofIc|9p{gdI)2?d?BmCap@HjKb%nD4;LZR~?4b-WU0ap)CMY5~F^P(eHjw!s zW|fs7UQElc!u2)oj0sWhyJqx7)R50gE$bzab9MWVGcP%Cc;k@45gMEE?7banUdJg1 zE1xx;)p6a_>rMO_J+JIA8|#xi!Mvh(!BEvTh@20enLAH2G&)9=&Y~8MuA5f_q41eY zRS9nQbq##FcPR-qa7&%=O1BENlRap}GCfv9)L91r6u7yf{8KHe`BXtr9| z@sJY>yyG%}XUeMrZF4_MaIBPKgI04>uQTgN&bOqG6qQ;0Jd#|j*E8{6@rO6Rnc|nb zXEJ1+-F1;OLP2~RV1sB(2{;2P(aYG;9}B0_Kz3Xx4oE=ulq8jX>=5UJMvu117<^?E z#xF3K90Bm$g01|XwO~-P?CfgC%&)g<1!!3{orK5s(_2!p=U+(jddb>Y+wX9`W$Ra` zRvfA_{SnB{to>(lGymDY`)dMS3inN(1b_ub&trrQWF6g4q>1-s2T%Ab-zLp_u6#Vz zpsMh!ZE@SfPCOQ>AI7YNS?+~KFkn0OJu=)gNf*Z~x`LW3PaN1X1eV7f&_6`8M44nF zOH^&9`3_5dKx1Ks=00YSsiAUsu{XVderSdSgCGQXz!sUNvSX zDV3`)Y>_4*p68W=|6jiG%_t!pNM}RtqHo*jnG||Rt|nHH+QKaUSo(1zuA?vi#~0^gdYuoE0&(U&>oYGHIbp=&>O zZ_%kH-MwPtYTk2%GfYWh5+KlB;8;Ubs!W9>;)dfj%zyymg#T38qv;nzT2t0tix1vE z+H7bNK~uoxH)0E@>F{v)%BXQM(kDX8(4$y}??B2Qv?JjIkKwGmB-wzXri$RErZ2DhA60ByjpSXYb5zMAJvra~9k7u4w5; zy5`>kL-%MGCVEts!>dob(0J5A1w4Do7$oGL?IoA6e%{Le(7o|zU6+aDPfS3tw{W@l zy78q;m#l&ibz4&Zdw=BbdJ?u&0!uWPBOuxbxyMCqbT>gkc*PzTccEVb7$moCOrAGq z$7l>hOPak-7D+G<>~JKZj~IWQR89P7#k2#yLRk&mNeZE?>27gB77cG~ZRkQ5?UMR> za{$$G0ip^30+<;N!~roO#TXptpUc?ifh+z3j^UHU&4NKUa6Ks2A&~fq#la!aW_}19 z)nhbl1(IVG=pyK&t}K%aVRd1~+hL#2lp(zfG~bgS7F61XRF7OnGMvpVU)DUaTE>(E zK7wWVfC=cB%7QZ?@Ql9D#zHf3x1QBbD>$TS_-USsPHTe7Qo6*7N~6%2uevV6E_Q&Q zktM?QHyxe-UAsI1tt>%tj+HP|8+3lc-$JvYg*^Yt$=|~>P-=yVglG?kBYiCS0WspX z8~qweZ0%{f%gBSWkACKlZraftE9vEO46Ld646i4h&V& zz`)V&>lOPejjx-m-EJKF{Ia@Y@6m5}OkX35-xZRRIAY6D=vgsB?B! z&}+fY9$TkA)=4aU?|#gLwqbIrvNFNNhSOUt!S$qm9f0d~B9&l}iUwz}Ea(ScfO07c zp22!h1@4k|u)K3UW0mHt#5JvjgQWJEp<_TBb$(96ov4L8&-FkCH}( zxYeWdHb_YcSdb11R_Q~2WNDRfRj5mvNV)T9XN3Gqv=c$(hN|H!|FkPo0=w5=pw3-hS-D z-aeO-Qmyl*+^Fbe+oh9C9Qf`gs5HAtC4h{M(Yr*Os>AcPkKB6b8tF=#j)^|f&G5K& zv*M~3_Qu7VH}78D{k0`UjOYwndYFCg7=Vu;M_{DO1dcdkeY~^hNX{RYw|&odxdpDK z?oFC8%cBJ-XHSNaTtm?0r#8vWuM{gds&ud1cbG4RUzdeV+@sQ}PCb}6T(pb3XDE#U zroUM#aWy!I^MQ*%u;$B%_%u*xpa84szPz7$!N##NwRQBy%8ylMgMR{5_-F2`5=Has zgrJJWX>ccGFcPp_j|vAkCb2T6@hnFmwv|eZP?7BWc_DViC$zm_^rje-_2zh_s3YUs zQunr36+Qp0(fvOhIYttEe}iQ6L@2PO8}M(0w~LRrD{!+rR*b(J?T=y94D48l?~<^4 z9!rj&sFh-a?&hE+IG*Cz;Q+z(2VI09M5M^jyMs#uA#3Il;@AOt19Rohewq zz4O&hpj5=DjNDWwj{uM92I|)w-2tFUw1}IjeMlkWB!G($M2WNv;0fYqx!0`!|KI(` zbFk=jIc;E)9k#?eU~OHj54%<$oiw&6G+s18h>`=myDc ziO(`eM&}+nrEIY$*^vxCIFOnmMP*||ww=0!*oHtLwh&c-1KdR%<>5TU*?|2WtI9FS z;K(enpF%U)%~;kU>Sm1y!M>PIRQ%ufHw%;TyEk#on;Qw(H+gy)l%sdl?sdoPR>q;I z%b`ihjBFr`Xgrv@`ZH-z*p;MA;@xVrc>Y8Oxj5lo4+6htWoN)cb0h#Z!m+s%!a!i8 zJS);HXTHKdtKaK-t50)B!dcd{n65iV!K|dmzsTh(a-Iu=g6i-8MqEcqLG?xuIW_Gd z>`Yso1&7%)_X>vQQOMm<%HeMOS&0>j0}oa<)?-nU0=Z#H9(AZ<-$pvM@QJi?Z?yzv zs5165X8zux^DA19J!@QfMc>;#ClUl+scm-pu{PWAbS)d=Nb+=Z1NWt`n2Z#AiH@M5ikg;v-U$H{mEgH}ff zic|Iwi0gpkPX-odI{8tj8ZkRLhy6@ilGn0Q=7lfMCE;)Pj^(Bwe|#19CKLFMEh1b~ zvYZ{i$j~S#q2W0GIQ2A)8c`G1C9>X3D;ECnkyR~y}jD(d?{9gn+I{@TY@FU zl67*FiGd)BEl1=ow4x7LOqOacX^@elx)hjh+Y~3}20*h5jwUx$*R)xG+WYRbJ{nNO z*D4(usMH8iexZw1*?W+6dJcEp>g@NMN@AQr})?P?}{V#+!4TwB_#lGcAkt%RXOp^?@MXzqMrE!u_f z>x61JnxO=$GiIU)JlMJQ41LlkKsFALj4VsoEF(yM~w-$f|X5yqpdUkDe|W$?ZmSlNO@oCy&e}3hL^N zHL3Z#%D;RfA9YN*1E9qY2BEpolpiRXEp|i3NeM*x=Ae+*G`tAxHEv3?6%|J)vJGRI zGmZSDC+pBc1=BB&+#gvY4Q5r?G^w|FbuDd;{iGtb`=kWvb*OYM(}L40Ed?gMT)X$+ z%;~uPdJ1vt+y(dH?>ks+nWn=Bw1#Dl$Br0p4YCU}-Mi_N>rW8L>71>=Lee=M4~QbQ zsIi3yl4p}cyI%NQ%dLxd8o5$ud;ji^@hNSSSVOB3&-i;`UxIc$V+^s&4M1E~Zva>Z zYcN#TrX{yoj%44NKhh6H58JLI<3-D=jb6&%-Nl1IbTnJpg;P+ig+OMAYLG?M9;QI` zgsrorv-duRVMHdz-F-E82R|s0uNuoccbfNnAJ^xv3*i+d}YPbHQFNe#}GmC4d>|NG|OnGpW#ngQsZ`wclvv}?3dY|+&S>& zz(P{2nZzA~(`~ZrnnuIQEQ|Efd3(>n8V=!|VbY0;6Dz#?KRy{yGmTc0urrm3-61nf zlfqPE0G01vbRmFs0IgUIk5?gn@BE~Qsx$p&1v%HDJ>M?x_G){8MtN13_Q4ew`RZJX z$gyj9bKCl+Yo1~eZ757j1U;R=IEjEJQ#z_xC z1+01-rsGs)ml4PR%GIK+kr<_ca0BExuQE& zrWZ*u--gA7+PuB*d^dB6kJ5`iXMRi%XjY|_axq2F^<>=f?<=nw8` zSDhMt$BGDn#2}#mEv2v|0Qw~rg$;$1K%*8 zo#JMUlUUOAOcN6crb(k}@ZEC1V*s5WWDvHNOD~T^u#0HGRHo@kmP3h_LM#c`CHK}> zuaL9Vwf%3=W^(=m(ByWaE64}{krFBtsObPtmy|s7=tgxf%Zx(jgQFUCVhu(!+GISV z_uxwYm`2^mjb3V0JaG{c(^y|-NlDO$ZD6og+fralfzZJLd*A49)wJ*Vo+6>v4BjRA zW4W=>Id`6#hfM4@L}e2M0cZnMT@WBIE>h)Wh_5ljG2wsr>VKc{-b6hA*Z)Di!q9w{ zS#M;imh8~umTc{@;p$D<-)TW~34tB)(3KNmPx}iq2*-95}9QvVkhYlX?wNb>S@8hjDD~We7|bh6c_scj4O! zfOwIm%zjpe*`=qUm=b0calUnLObw$zFxF3ljR)nO zS7@3~rqC6rUQ+LNe1>Uf?%Y+y=x3a#O23YPRmNI@F~-1UHXwj0T&@LmZ&0Hnf9981 z)H}&E%A>XO2NI05;`v^A)vRrxz7Q>lWXeY;P>ZdhZ)go>KIpm5b@2vawH-gm*rc=E z0jP)ouA;|aox{?EZ5IhF35&O1Z-L|WJSGz3R*?*B8YwsSeZS+#K;FIR;nh#Z2vHV@ zS?Vv`cWCd14=c3V?JuoNR-a0}yxsI=(t&wHf9|5Kcu{sGxD&7;S;A8AFa#9ACH(z(0sEi zn(y;h?qHqnQ6>m?xP}PPaT?@Q?c)mvtDl?S)7o0nu7r5qCRiJ+Qm~j)zr2EW1%vY6*)r3GQTWG7n2) z!7jQDW0<;}_F6qyl^)XSv=8?6rv$oVce_;p0utH&{2!jKrb7XjC#>J!jCFg-Dy*G! z(>3zEjc3_@SN+HMZ#KRgQ-Nyjyg=2j&7VSsk=7&L2GqDuHZFS&>BRJ>cHf(}kn+F# zNv^g9Xy}smlpN&&FqnD}2$3rw3GfrFBF(-qLI)Z4ts;qWt7kQLG+#x^ES9IVBJ!kY z>QvXoPDa#|J;$C9-2ND`nij?szxW9n^jHq>6Ivml&Y)?t1Zk}n)%@?y9$AZVwSM6` zu=c5rRBUy!-EVbgpXr2RI)Nq_dmKnqR~W(7-orN3m7PH@j59r=c&3 z#G6E>JVy!us2yu?bnuG?_`cd*umVW8|Aa#+p!^!+oX~-VEdQ=eN$n{P z&WY%ay&TQx^jBaB=W=!(V<#AF<tt2s?b? zZi|uU{cBH6wO%8Kl9hfga}I>FK{4umC%6{fNscB!HY1s0Q17J_@a?`tmRAt^cgD1-i2t|n*4G6avK=pyJvJJ8Cv!LkG=z{ysLU~f$aD!DG;`uF2ML*g7czVQOFxUi07 z62VdNi?tM()0w9CFMfA8Tu?n4EG`oZwCWOwtCa9KF5uQ=LD-tHHou1b=ikHusx(+> zrVbqgOza-Eju7P}MSq?&!CeMFz=uRrt7=6_7zm8ORZ}OxeNaYZp4lX$kGJnVv^!i}=zRr5rzaDpLyZ@~1o`+(QU4FV_$~D~6Q64Oh zT+pso4iY3v&yB{w4q4BFW>YFTHn~iY_XmS1FwIS&=WXZM;rn3>+0nUCN4m6DzIe!f z!7`Z7jiv_v@b?gh9Kx=MQ&dy5k4FtHI z(>A@#NxE#i#*G2}JDQ;?tQkdJX9@W-T8C@*!^_P;*pe-7L(A_9-zzBq8p&pQNhgYP zMUzSLqvhgl0#6^%?wYbAUL!k*ux<$Fd?U4xxn~v2Ruo-tT`U1Qe9g2OPIDkQ7R?T9 z(gKiwAb%MlBZ-U7y~Ndbwv(vhZdQtTBY`Qp3J{KwLFiOnG^vpS3fvB01Kr1MvS6z> zS;4OL50BL3H3sBJnMc)gcV?Pxb#AXPlhckL^t%xKGl(~z2y1b3_ql5hYHJ70IV-MO81m_oB6_@6Mp3IJ5ks#_1_d7oQ1j_u}h!{xP1ev z2Mqw1$XrF|Oo_@|U-J61M0Ky<9&e7%Gr(cl#~`aKPI_ zfpr8yH!MjZ9Nr}QvpVT*a1D^HUKW{Eam|{WYD}*ARQbGJ%Jb*JQq$p31?4*Lp-L32 ze$W_#rKdcu1I#U=77Aa|Na^wDB?#cn8BUszNz8u8& zZ`cLSD=~&wUepjTUu05cJP{*kzGmiOnaGwvw&aHF?OXr&#YrI%lauHXZvag{XS>< zhw0N4-^hr)I`;M5r67Z5@U9rBKFx_2jtaatg&ZX`^#R`bQBS8 zM)vwx>iISL*ZW;tBI-JEo7PYb-g$#FGyzVl;GZn@;aV-6HvA|M9bRbBQbirN;UV_T zl$ZD4C=ZRz)I6y!V(M)5U4pkxR=b%f#+jT1s+A+{6sI`mX}^sHhZIUdagU?k!->?) z?(97U61aG8S1&PYpEiGbPLoQa)kiS|8$~bVAZ>fdFfZjDM~bCTJIGOXC*3x&iL?2$ z_08;X$5DEdtO4Mq<>6jOE2(y!0~$2|(_4S%IMWdYsya+#m6~d?-iqMD;sen#aJ8ii%b*53iAfUzFfnfD$8fh6$_QkSJKm096<;*c1aXq<%&ctj$#7bPo%| z^9wEZ;Z2z6%G#uY3HZh7tb5*XM;j??4kG?)*JHXe)WyzfUFG}GeuI0%J-rqMJWwQF z2X1G8kTm!l=uo%@vCMK|^Cl8*xeCxa_j)U>qbdH3-aeplt7LYPia zZ!^ml*xn*>$`D1$5`~k19}LBRCGJ7r_H>>~z+HsnsNJX|;k#n*)AKPkJ;iDoAUaa@ z9Um{d7h84uAs-ubN`t954Bey-4a@Vi5XE8jD+79()EMNcSWonYqNFdMO78h=5j(v% zht#2_4{%VVzkLexM3y8t)wb<|rcMw8^i|t{BX~izagEytKb6Ivw8{DzJH8hEv8p=t@@hdq~R#i^0 zPcSXG9`O0al#jyByv$(aR$5F8yLU-9mrBEP4P@1V)KhMPe;apEN_sNFh!!YXEVMy7>UjH=z2Q-P_ug+jkblz%S1sZHzLhM{|ss9X5>Ch^M-L2Dejl& z?prtcpry=X6@$iCz(T0v2T8fQwEj|(O##xwA+msp2k)l9#B>)zWevul(k?$a>^-(y?NK|6E$QGvZy_k_xU<*S;-r*l7F z;$B3;>a85!aSoohhkK9Dlua^;SXtxA@QGygT<5 z@6ozhdxxju#Bmy6hlc^ujJUdoS1N~NtI^jef#!{%#e@w!_~u<>fL!8-JVDk<(o3sT z9zPB4XdejDh5#0q_Y)KNv-)ZSX&SL56**OfnX4cT*q`c~)k&S@y<=^b9{Xd+XC=GB zC$t51_Xk4snAz<~ESjMNgr^p_}O4m*EGkSNeR~3g7k^G}NM)0)y|( zcJ?{>|8VInK0cj}_^f_V@K1!nYjAfT47N2h#qf2LMRE0xVjB)IJPju*vogC*PcHGN zICvVMOFt}j^nX2}gVcJ|jKHl^EMa-grF^C_r!hHh38WBW8VfNtQXX+4c6QxVa|%_r zo&UkjfX|NSKGSlQt4J>8*VsJew2V5^;0_A=UnRjNpke| z^(g0u(|!h@G+^MrwmVIH^}~SLb$YeBt6ok95E&l(+#?(>J2qK;r)W*FAf6VSF{c;A*VG(@fW%Mn} zAmCOBQ4_*6OiOn}ngp#YE~iyA@n!b>ijk)~!8L-id+(tx%Y9}FIe>8NoE4@S!$R{g zK+u{I1s8&iF$%R1^N6q<)RYfR0rFQA**3EJLN3N*;=pjVM7EQ=PRzG3^Qh5eQ5Csp z|CSQcw@Lq(2&M6K2c@eR2vsUENj}!lR4TuP*u6NX!~)ur)zlM05qs5{IZW zkp|r0bL2S3;i~$Fj2udw@NA`HX}RRvlsiM~HnG_Jr^PxenYl-&ijH%wHH)&Wp~giB zj5}#{gZVG(D*!pg0Mp$?;Mg``r=#7LL6xGRa0mQz$`Z6NVT`rorGnLb%PVQrzHhBr zG3*AYJs$cWINA4=T{X^>c3B_5kTK%0MWo$ZttluinJzm#&G~jq3h9E$L>j9NY zc0~0_pjzkJ6t%tNorS;96-P(^c-c=bM$_|W2#5CLFI}qJb7>Fv7?DgH`;-Tf;~6C< z<(_^?)9qta9<#a9_&`gRL`=lO=4IFoK6exh(kc)-j+wB8b;&Q*7Ymt(VJsy(!a)5B z;BVIq@4IzG?_|Ke?~WEyU+kPo{pJcuyIo?;b@y`hTr=r;!DYybxN|5Y`KS45Jl4VZz1K#2o0Ky=?$2CVzuuIh?yYw%f; zTR0P-M@W}savhY3u3aY$ZD)QN4b8Cj@-Y2C5u@IVh{c4UOI#P3g{o0{3LfuFxCWH_ zEQ{PFYx-{|;0-6Yr4}dtG^`W4^7KqlD+6!?fZSrM4h;PCwyU4|d{iSgygp^XxyBI= z4xlyc>uon5HX=0X8lM$;IV)OSh`Xhk*E7ra1gLq`pFoozqe>=OLc>ks(lT(sn+3_% z=mHs!3xL>aLIuDtRn{}2Zg@BD@QQYRVi&$O9-N7r!SfJ1nCKh_E2y#rv#n_ffW!Nt zLY$X!{-U1v``?J0;A!)o`;^ltchHVBXWRYswsOB1_K;F&-MAzH++xVd+c*nXaM6DK zV@?ih{a$*QTyx5Dsq3{5?9a|(&@_S6JZU*K;Q=I?4o$KI+W~W@C>ldE$fDnDY|?z@ zx81BWaxOV{RKDZF9@6E52qCLzvo9jvA>pE{u8rt0Jg9rnn5Suk(BlC}B#dnwiXXXE z>GS*#r2s8isY`+;hKP-{Y|yZN)eY-skP~y#Iiui;@v<7#*+z8n5UIxAE^Xsa#Wf#O zd*~|(NxkvUx};F|hp8{1yFgePIl>KQ&qT5rcL!=E09~(ZW$%wnhbpCZ6G4pIdPH8) zxP$giG2>lR-)(GcTwGkPBgqvl5Ul1g6&6LU3WXuM1I0I@RAuIKk`wd6Ge7ZH+hY$M zxgg^luV4@ygcdtgIE;mZ#~2`md(%!f;UIm`99wV->~_EpLaW-i9bn;pWP=299>IE& zPIM$v`LU!zPPpnL6s$k+8}Z8#z>z$emq6cTnkEZ;OC5M@C!EM zZkXMxY-dIo9Fy)LDG)EzN$KX1dc=NR7c85=xbdXVphGr7n}=@}@6MhB4c6fM5T75~ zlEz8N8X1{=Xpsk=$L_jZtjE?fLR!7YLN9>?X%B)A!Er>Bfdiu54=Z9qP`yF51x;*$ z+?7HJzzR9sO6<%xrn*)oAd8$x<6HKh_$=jL&L1-+^|R|JE*v1PfjJW30ANjJwC9?; z@$DP|_!0f^5toC#sGmA*6c7ja{~^2{o2j{CQmH}Qa3?K$On^zJ|b2>$?R^(INl=U0o(wt8RA z*ulF-B}x&=`2ZS*36O=U>S~G5N#DDnAMoqgWGKYYLUR&o@V&N3`Y^)<_GMbmo_L69!g9kGTJ613(WHFO zvhgEQaQ-yuVx{u?dWT!GvPG|vmTIjB6QIhVYxPjGfiS8-!PXTD7-#sYQ@Vq3Dw$*R zn6YDaa}QN&@{VC{Uu0Upm)YVO5%nFJ!ngg-A?_&*tYgbLUqRR9)ZU+DD@PKaZgAE( zDlAD_QtRZFaX(C}v_uam>b8G3`Pi=!aA;ZO;Ek)Z_S#(5mx5%bf|XkTav6wCiJ#cX zm3<%@TL^ms+@sU*9H7EC0)uk)?APc;E^$tx!*DOe1v!Hg7hT-3kx3B1?}ZiW?s}L@ zPS%EGoXjqpjq{E+y?*Jdc)*mtCdz)kR*t1kTW&#f&l^b4Z-!^WNsX1&*QJ)!FO-?* znwRd}qa6QHvF<2O`~WxL19-H-1|8gxgT!eWq9}SX%?!jvN{Va}D7T&Fv_q>{)OLvW z6vT{EK4Z9@>~M|%r^89Ua;SDMONEAfR2Hz{?BX2&MxBSmh3o9DG<8dEKV&CZ{w(@^ zT0@Zj8R8RA+!$tM5g1QFUnwddWDYmV*u}PwLFyh%w2-6mBFqe2JFWciH6Wm%801e<)493~0*^M*dU6=WoPM9`Kc7hi6tzBMHF zy})rZ&w360h#IAx9E#9M?1?G}@f6s%{fmuNWHk9+T_t2-~4@^jpGY zO$4DjX1Y^_$yQl(zJXUlW`Q*$YKGZ8cHC#!AZE!_qdqN zqd%)ECKJu}CMBM(8<&gjxTEGLGD*s1*wQqYa%oadum@e%*aE8O$eH#r{txorJshh4 z-y0qgflhwC<#eAp;YEu2nm&hj9Ep_r=qA-QbLJINFn2_lALlb%uqR- zk;cNB^?lxczkBa{@89>g_r3T1T-S3y*Yo`0aII_2TC+au^FF`cuXpoDcK+t~uj)qD zN(_&!)etKS5fpeH&&Pjn*%w!DZke%N2>lyY(b zdAt{hfrSQa!*O|x+%niqB{7W-duAQej9U|DT^PSOETt@d@>5N++vzKv4={)zLrzhp zc#jyKe-iky%N)1RQ|%^dn6YKbo-c8q@-xoJ1S)&1v6uYVVx?lZ_1VTQmC0BF4K_>V zd$Irq%32^3F7XZ+rRn9XdlZ65t41ZyIy@syGQFIdHT^G7OD{YNbg%aJ*SZ+&IjVyi z+A>`MZK;DV8-x+U{nfoeaTn{WiuE6AgdaWKuX$x%`ngq?UF9_L8=qM5Dy5Pu4q1#a zAhjY+1?M8cwTY+o@)1E?djMD3@+0!unRvrh<2Qy)Lx;Bw}CwacRo zMrLGOG@F;`M_P&rpt+nUN82W~>J#)7yhO|%vbJQhIzCy>uBfx^i~D)^z{~gjXRDvz zn@<8R@3Ri$6qapND|)j`h<>zsM`uq4zS&=SS~#R+s9vml<99wKp#Fq%pf{di@^00)VRhXOGu zCJH9iJKz>uc9890(OzcFVi1O}l;=?A%bzMZowPkATCmqndr8RWPv;-;JtRm^A?yn} zSh_Q8RNmE7phbGm&On~P4SSrkNH+J1!esFDdYd7&Tcc0Tm*GjA1mO{Kgq(ufLGW3- z@ERcXzhsLko@Kz0+lv6(5d&E0fALf~%m|b%6>+9t$H~puVP=2G6_dMk)aO9xkv8wP zqhGpnz5lrB5^b7$(e8E0v+5<{n|8`cb6o+VeZ&|X;I(y6|0Fnp6b}p1+lkW1`}}7} z=L^O>ADF}(77 zK^u~JnPJ$2!dZX)D!Gp<`|qgkA!|s6SPoyfA$A4YrP=+Mne&1q(z3J#AX?zBEzbTG zOBgo?jF`-BkjoD6qCVKos{P+Rl`1kg1!>K39-D%TUqvO^jB1kD3{SnnpDdPIw_;>D z5~%6}GxBnD9n|`q*B$9O{-E?VNz--ze#Ad#I)w|B|Jw``0PA&2LK3%S{x^Y^yV&;P zzyZ%xXaz>@EJ9Gth`N!9OFK@F%CtY$P_@5kSUj(55h7?5jaNZNav%bic8ewtAMa$a zDLTL;L+PHyB=^?^Z^f5ySTO4STCG*aL8bN)S7#q=o)h_^WFEW|QcaLxVUXTjB8Y<>WAAEy8|m3|e)UPc-;h2jRaOhuJ64 z6{*f(d&*QH(gDu6hz+}M;SjqiQg>lJw6cGC^R_KBeEqM?6W5Ym2`)Fb@35qg2}2r( z9s}aT{3g6m!(i_rC#*8`deD&`WRl?Zy|;H)Yr{I739G7X)qy1e<6^<-aEqn=f4z4< znSIXTf83VB4*&J{+in}|Flh44vJv%ou$C=au%2H%8h;J66aSW;i(vwH|Lz0K@|1}& z5c}_;6%1jje&2e|F0|P8%e_V)<)U7nl@4qAFMW=wyd*1-mYT_@GPB|>Bf4LXs=`*U zig4l-M;nuwijrrneUTTVl1F<3;~qTwVfnE%UR?0vd3XLf@J%C6Azn@MDq9eyStc@V zPJ{PcnNMb0==A8|%V!s^1f_wexR#$J;5xSO*xWI1F1cb=Iog0BhV6_bZ!KY#-$4vxSFY2IbDw_YBomX`OA z^{s6${3c}9nrNz%L_g6?%Vwsr7lO2<5Fz4T3a`*`&;%j9<->Z;Iw z@=SX83*Q{nMupBJA7!baz?_x9dwRO79EE{?LtW*oL4(sXkr7opHW^c_1mEEl$AK4n z#Q?u8yfDZ;1}W#$i_IRV%i+;8ZXOT{G)F-5vmHpVffZmy^C|2T4O3tRs&Eq}0^20Y zUpvmjS!?|Dd~k2&X&>#p$yRM|SFgPM^!EoO#GYpOCUDH~Wt_habrGD%L=)H~mfdW; zu|mePlJ;Co-}TgL&xUt>2`1=|SaCY(-g|@1(-q%LNv%)6j~n{k2gq~1kB@gaK%PT@ z`3xY>AiEE5+g9~ywU+rl>K!dv_cUuv{$$rWkp_k9Z;I~-ZoFKwA~#%MwbHV+z^5Ms zOQDbI;KJaZ3HYPT0Yt`1rkWI=6krl`bVB*TU>kL>>|-152CJ{}oD?yyHCjcH_P4xy zXRDQqjnLkcmeQOq`6c{G{(Of@XIZ>y*Cn%zQ^&l0T^_~Sm;LqdGM(ma4M z@oOOnGlVzoP5W$^RWlWJ?{@9O2ovAe86`U+1&NuO%?YsW5QP-}vzHy5)+dW=&?Jd_0YVl!gRs zkN?6^q`80%F1dhw1Z4NYPD(z&J4iE{iyYyVg6Xhrzra|K|L)mW$uH|Mr6+!QRG0>a z^e8Yt$7Hx0TsJp}#FVtjET@{Qs)--nZay>_cTNf5-xyDG8+JZC1o z(r0-W)q-Oip7%7r<9F^MCbQ**x3iklGW#v6Z(YvYb?Leb-*`H`_bTlpJkb4qcHr#9 zNzG3UOv*J*&Wc^yq1mT`!+kzrBMgpQ{{#r#uBJ*7CUKU8JuoGG@sq~hfaZ2XiXwO- zWC4V|GaH%qBmD=b)}kUf@enVg(96$-BU25&!<8SYbqhhq6?Z`fPBe4UoD{7`>q07( zK^6)TG4cQ%5!Dl!66x&=aH}hqi{H)U?O?f6g7C`zDF9;)3A4#aN-cEXh@B+L$`RfBX_29Z6cu9FL9D>{9m(Yiq#m5)Z-aB)FkFQG#X%(5w_T#IcRS(G4*rdbrf zOsqfBI{C0;vOWIE+1yvV*M!^M-A`N-X}m&X&Ii;0^!&WhS6(vq8@JH{4S4r>ak^n<9Y9Xam<-1z2?iY+l{Q393^Ux)^h4I!?S|2`3RULx{%T5d+Qg9F9$q-U z6*<-Y^{jj+rd-nBrRCLjsndYe{cG;RqsdPTrive=v3$6&8V1{RsUYgc4ytp~<=vXm zkvoc-SQjRpC@Fl|_CRmLgf#nR{gtPaj+-V$&udKANG3r)14!!t{3wvm(&HEf`bE!Z z?X=~gRkV#o?T(5oQ)Oos8uz#Tq4}#f=ca<@U2`Mnua6Y7riz;=Y#%x%b%L&TC|Vuv~Q;}Yb7J7hW93cwy( zqzAawC~e|g)X#rjnNz7%H)dwgJ&`+T`E8lU_hWc)w~{46v7Yq&hLP2ht?6-hce z*=Aa-cK8*+BB4FSn9@=oPndj0T#l{h2-o=js$a^8U}+C`WAKs5U~tB5=q{dYkU z1{xu>xqLI4!>k{-W%rvmQ+MXL&)de9nfso~b9DTwdw#TI#9Q@f=E3Sme)a^=3TH7j zwmK%=516V`fF`P@DWbnQ*5=K|WLNPAi+C!GbG)l}cgVKKar~zaO4^yOCM<;^W0jMj zbK!0RjBzihVYeFMJ^=V4p}`4@tezHfi!`pn)(QB=gufmtcY1u)1WfE-g#WLHa=wqQ z=bzyR=NC2_jrYuCE&i=vP*>3(Hh_(Td55vjlVknIPN3mTW@(6ZmmSMbD}2wPorfz0 zfTnqD`aeQUq_gOAtMqi{e}fS*)uUwx@IaA3hJriE<7>!x?AiL< zgh=wV$ygd!BJEGY9zEw~KA2zeZ-0bl6rdmgVbS~i1#6_U6UquRVuu((V{9{A6yD%X zXKwPJ1Uen!?qT_-wAp4p3MhH@<@$+JoUPowyc;G8VPrnJHRkWl?SE&)T@OBS18N1XbY=p$(#_36 zvnLl9kP=H~A0ngR@Erl>1uq{Zs#?UrL`38owinAW^U-{7Ri|l9!ket*UDNfkX}Po} z2Tmn;qw0SJ0Vf7!WD{BS6%Ybf^V#J->cJ(UaTqg*@;u z?Ii-!t39qLrbX$Lk)&Vbk8~a`+(`R_Z&{&?3@t_I2? zp8S3Jp9B&zPK14$rQk@w^1!L+r}{(6L%oWE8ZTO9jp2S&wG&g^3e6huHYdgg(n3p8 zst|GXOnt2f4>xGTXwe;9KSPPv0koGJZEfY}97{ zoq#ya{LPR3don?K4%CGZf_zl;BQC7gP57xrd*bku0@=a^BXo=l0vB?W51laD?2+8_We_G5aZaYI-jb)$QaiNAI## z2GS-rz)W-y5ULlO+h1?C_tk6p&v&)cw1(D+?b>ipYArK*xdYHCH$eYr%)$nw(v$|j z%ozjSq#k-LLq>0yYQs7y{>#2anPDw^u6x2fGwovJ2jRyn=)TGV>y37WCT>CQ&*LvH z0WH%cXhVU1cvf*7iUZIGmFJ1b7+Vb<`QrCR>~#$HcL)a_8*pa8DA)iURAc#HqMrQ{K@k%Vd)UCceK*7Bvu}|iz z2 zf^Zh2B<^6+5f~x6&x0&Z)7KI_AW?KRv-+t`lT1hJM+Tw1v4s~Bx9UA95W(!`#6d{XVAAbZPsPxz7{ zKha)$G!Q-%2_9;W`<1YclxJp4qe$nH*TIQ(uU?t2>ln>=^78$Vn{sF)6}E_=e?X@_ z#~)jv|D*rN7w;)%Gu7|8$NWXxHPG4cN5TD?yTj$@ewplW@o^-eB%J7uGM|l+UprJ$ zB9wwZ4woyjeFGxRen^U@7!(&vY?b~jvhirPK08|Q( zziCWu=MolSYB3gptxUy5 zfiBO1Gi^P!lGZd|fts;?uDkH~>s*S7Vrf#|O3_BQq|eU3Bu)8FD|!y{0 zg(ULQR@9S~5K9x``0*ImedK@IbDr`>z7&qdSn7^w<#PMIPp#>CS#vY#ovEqalKX^U z=Y=guWqtoDvKP7Q7x(cOy{1r^G~y(bGIiVazNys8A1S7s3SVfD*m>^95e2t?gZoci zK3J+&VQ=X_>W(=EI$Fs+_?mpiIkD!qY9|-o%F<8pj!f|u3Rjf^&WJST@IRdy$`z!t zAWhECHZ+axs1wTQo|Td833$x^Ybk!a~1IRhmNL>zn? zxMTyZ3E}Fh<59_1$tTNIz(oK58!$kE-8Dm++d~gU#si8$IeJF(uI5o#^%d|As8^c3 zW*CYANK=)Y55&5{XtxH{3Y~1(aIrCWfz}9e;w~(aID=$aIm}19k7V+z^ z<}arr)Lc%(v3$Wk!5a!ukJ)d-mH6hqTC8gy?NyKikM}sP$XEa;p=Bwm1NLCg-9HI+ zo~7tXwn#-9f1#Cb)6xKqDkoywnUaM|$@kVJ_+(Y8)wSDh%UJ*1rRRBRe~{S|P^0L_BXuefY^`n+z7_mcgze10l687y@Crz4CzLLN zt+f5I$0Y7GFeQ6_&gBLbSLt*oF^k9lB=`lBui{E5sdDSt$eVpukKFA`JWoDfwO)18 z;}qdzkz)6~w~cycaOferlqi#xjAp9&laVWU#Pi)=QNRT2-#kl3Q|hhdd)1?3*q2v~;mZ z^C~n4@B@cCx$m6F;OnUuSLi4Pq#o!fYJx`<`W@$N|0Z#A9$%;|@vChg`ds_)m`i}Q zQNar9&8mr3x_p==#`h;7acUrKfp`=ywA+vO(;>PWm^{dCHu}>FG00WQQm;v^Z?4ft zF=D1h-RQ*^89Q(6B!n1BI<=cB$-rh)<&_qa(RIb+7g$ZPPHS8IY$ZK#S^a!516voX z$?tF8M)xf?`fOYuxbw{Rs?e+T!WS7XWEk02P3{@v3KjFx3rjnisnV++_#-bYo>{H- zb@%aPOdQ;A=CxFKg}AAo%c-kX?{v6Nc&Wx33#VvJCfca;pr@6NvCg24p^g6B+Ve?! zazkF#)kwVB!*toBeD!@6^vG0EAUjc+L^Cepyz5A1GJ2%UDTKZgIr-%+d8_7}KhuH& zzE8Ve8Wj3uTI067nE;_msFAT;4i((MkZ@WHY4wBCt(U&HI(;16Uvwz>$DsWeT32@H z!cDE1tA=qSD3`*%!WicSGUI#)Z0j3EtvrydCUTgL&l4u|wrsx#YLXtt!IshrkV@d< zy|ajJ3OS5_N@j>t#XIG1b;^ikdtUj@+Suor61(K?37uup=?7KhmgThHDJTL0lPOH< zaW5`>dqE^1mASor0yBEyWb5^8xa0-5j-?^e8_2)GML;nx-11K7?PD>78ZTwiV#Mc~ zR$(-yi0wvyFPM7bu0Ngxu+h^U^E;E@JPb7Xmc0Ubcl(twLdD69+tUEMY{Qoqdx5ch z&I_L*g(1EAxJpOz^v|Q6dX`#^WnhLy4FcV*yrSgIB{VNqDc5LEYe2%z5SGy9535r+8g&%|AtEjk0hQUXt$hM)@$dw3P*WdC_{OV-8#m16{wQR+_SKx(%o0{z;euUr_#~IJ7f@3|006 z6I&F+9kzF7(x8_3m_>0bP8>Zn*7Lg8J5Ds zXM(g~jV)o@)_4ik0QhrahOFdn@3f|kRo3paf@Ktxy&|B){J8xA=7}Zz65@e7JZDq? zG9c3_1(qik#MzG4h;Xej0~kS8dWC?2O^O5sc-D4afhGzM$y$Im>fwKOaBMyt_?T1D zP>5BykSR)EBzO_mVa$oc*s6a##K=Aib0#Zz3FLv6rk=wCLKAN6hI+^PXcNh=9wy=( z`@6YL^ zH8L;wjPh=V;PA5;TMePOKn@xO%Ha>*ePbymDZ(%%O!u30b;-h6f7`rojXqMl|8U_G zymfWn`w{W`Ph6S7dqy7iS|msc zjhVvDp8Vwq9WuxN{Ib7bv$J<5#F7jAu~lvZjEY8IN48>p4E<378m8FzlvmvqXVNk0 ze^aE84`XSrs~Yd|SO2u-0`KfUWjrA892YwQ=n=?SB8+n5+VS#Di~=H97751ExuZ^+ zoZVv=vQJdAtjFAk&PQL3Y&FfPiYG|VN(0>E9c1(#(rWr=_Aip6gn2)Ol4Q;l`6|Ls zHCWh+t%AxuX!7ocQ%po?q6Pz?3M7OMS?P8DohD~B5g0l*2k3C$ zqY8P{ZD>SB`CAYp$;gxgudJVW?PG07bWw8Im$!+NzU|bFO&6C-b2_nIV+)dC%#}fR z2;0DpNYt1Sk0#6!x$u986y5;#l2os#!y;ExA`S&0b@H0NwQj+@V&weVW9b1dN+*)G z=sRB~ZMpBJBCy1y>~Xmgd@dTPtoW0_hYZ|7R_EeMm}N0~jU1`1+f`(GDNfY(+?tzr z9cB})WzWosU-srtR~{k|-*`swG8k?;LU<=hz<4M7XMN9cPbUe^?hS%ZU9??a8!SuA zcy9du?#c6j4ky8WiczY*=cl;-=7<}avyk%}C=MNNOO_myRawDZ^1lF{?>|A1S4fyhwJ z*g)&GLa?)_k+l2x<0>g6Nb%*JysgE7a&>zyw5`3Wzdmm(E^ow~;t?N$da3*dE}qOu zop9`MW5GTR?ie{HjnoB1CBhgrp8SYWVPUIfdA-|=lY zS&xhtN0V@1iE4Rq_+|fZLf)q0$=2)8{DS$hZT{ zFi6}8q1}HWl+Wg8x8cIz_z8&f3h1CfbIB4WMtD=t>r_`#v`*TQR=-~2ip-nYBUPS$ z;hz4YcDM6?Xdig>O2SIuw$f7IMyo6*u@5Emq}E>1F5)Q783*RLdklHZmN4QcCZD#o z(J&Ruxr3!Ys(#*^p`#k4_;M|z(iLvRXr_HASK@S}4`>eEm0;%vJwbB9|ZT`Uf8;p%yv|g)nL7L5J%_lqF~>D?XiNqkf`zQ~$6( z;9*YP)j7?4U1p>Hsf_=9y&Sy*`1*k`sBsXYzjX$f)Tk{VW}RXQUUrTnNAG9k)55kq zlNP1a)y=)TUg|zt>Q8dh-uvC+4nbXxUW@bq4mBP9zMzCx&8JN4WRYU*IoKZdr&WDw z?SN)~SWUIT0GCK)%n-CVUkZyl4G`m!GP`FW%y>WTNvVQ)db&M76 z|Jp@GZ}z!HW*;HN_AgR30UEU`hIE~#ky<52$BuGrxX*MYG7>4lF}7?@xJ=)&Y1>}a zzB_Z#bYq8~jkIv;AMg||m{TWtAc6FXRt)p6%e6Tw0Zp|u&GzpRwrwtNk~=3LV$kP` z4nKNTZ|vy&KHl_D#%gAYGKtX#K~*T^(NCAY6RbNv6@O3h-App)U5)kQv!$nRWNSX* z$+E>Q4m*%pYUHj6Jf;JbPsonrU|>CKsqp-Q*Jt`1NxlQM-SD#9-n+d z+jOUHd?qK2v&>-J7xWb)G7UY5pT6esXNj*CtK($d%(b5%*_y4oiU8od-#m8|y0My3(!vH>Eu+xnF598{ z$`}l2Ay+pZu6|v7ZMV zV_#lbrGu_@tFhC3@~OShobb>V+xN&gh%?9U1U5xrPq;f7S|SVXeR`fp70TSizmU0f zBOu;rEg&l=l%u#XHWXATmuEYS)!|szW-y{z}53Rm4~3>eibTg zpYRT3<|0X+%+3YpX7Cmt558t3neEm&ahK!CE$pNjAyrN2?Lj1xe@`eRjK}6b&4+aR zcsBmntRfNi@~uY5t(xcLsn5~ z0a8@)^vTU-u0}^=Lz|)Ke(XP5k@hB3*N4kN+ZP=0uN28bBq~k1TsdIYs*Nh5_B}Vb zH17oEcyALg{mjF&8L>x9I$XcSUj1YQdH)a~hPau4ZiG=B4#2Eo4Q{OtI?GHG#e&ec z=_q2xnap>~8tI^ID2wl_TUvHY_28qVWzpO0WQBpqned1>_AnaP2L@X(L-iBZtp1(? zW_-$XS~Ek|XXcxAZHZm(w?celS-}4whuCuJ_N^N`2SUsdms@;8q~iLCm`8X8DStM> zL0&*#%Z_-gVw(*Cz6Dn1Pjcef}pHEfr$T z23`HPm)Yg%nV!Ym=4WS03Zq9>ow$Z=juNQhN=WsT3-h2D{enUG8*y{4$rjX&zBp+I zk7i@R*AF+p?0yFwrg@9N*pxbYOh4PV zJZ@nJbw|ew2!{^@cu$`cInf$+UA*L4aof;a#+&5Jdy==Wx$CIAY&fIhxy9#h-Yxpi zG+gu-YW1Af(*L@1f^WepAl;<>nWm3Riul`OMPl|NQ`$pjyrH86lTMT0JkbL}97R|H zYmQR-Dfqh<9a$;Ud84L$Tl?z_-!0jVU#<`EJ1qy@d^z_|!cH4AAU~vFp1)PNJa{%p zbez+P>wgVSAYBGpZC7{p2t^qm%N~{Y`_Or*3vUrf5pVfWl*h++D};|QFwMs*i}?%o z65>PfASz8hBY)6C$Xw-N%Di_7BY}i&w21WssITx&POE~~;X}n?)C)P%@fs=SC%#$k zCu|!^MC9=gfcjoC$`E0=P{L?(onEx+ya4|y`TZ%`$K_Vp7JS|5DtajMyV`Nj9MNac zFJz8vCbJKup~{qrU``Bo1UxFb7$({Idk24wlGYb`;aJU=OTUk2tG>BxMew|8>Z%-j z_52lJd}d&pVnKN56$UP7h3oNZkV>*FV_b%9ekb`1Tl~7!4k$sMTneaRj=0POsM6hw zbPBp{$lO{+u1{B6rD0aJZ8tyDHvD&ke%o&b5jC=G^AoZ6yZri1_($3AvA5N%9PH%; zLgSYMZaW22^jUBjf%aZZirjJ)KJ0O|zuMD`1GUDH^Xm3B)RLLa6sdZ=+W*r~{UHXbQH)8`t0`>DgizofOo=K}&kHE& zueq1s`uKI5dbCW~b(=Mpw_HfLB}$}t(+d9y4nh_R{|byMpZT>ENib$^xGqxT4Wh*u zj-u`c5qOY>cK!+iWVj_z`Tp;mr#HP=jTYh$Q0LwU@eDN)!mi}Ag`zLLTUB2zN!=d2 zB`909#51NeXXyBiiizpYg`LY!49$6sYH+UnCn$)2fs*_`j|idVBbEGMiJtWrBK1J6 zfK)P;2lNj5)X-N3I3Hz{Sx@L3>QsMIRBHF~tshZAUsllW)Wfiyqf3#)cGx9Y(%0na zRGn)St|a7w+Wgv)(|;Q#$Tw#LO8gacdMr31-QMkhg%O~)-@`It(ThKNkIR`o3rM8kk%7U6ww&2ShB$mv(Dm1yG|~J4pY9)I zVU$wiv@Wp@+Dkldw-$EOZQi)g@Sb8tUT-VwF5F*z3G(MZ{v^16MVbN`Qw5aveoTIY z3b+RXUd?y!-c5-1i%q;}JC)41f|ZJE|Xh+oEz`%GjN zVPFdX_5M9s*s9{{dl4~=fm;+M-EZrvW{-UFF;>5L!?DM-t;vX*B^)iXdGL`mb{VMK zS7T0q_WauzoaL!NZ)!?WNnM>Y*Gx%w z5w^b&mL5?{;cg!8pFg58mC)^m+r%)Nc+vB2c%nH4w#omJRv%obN)Wh#7;>TQHTe6O zODSp^kJk1nvqOvx9Fx?@E#nYg?eSM^T6gf~=dZ*?Y8wfE z?k(O6hR-(z?j7E1oy=clMuCFQJf56&u%DHWr~7*QJ3guQxufN^_J+`A(N!A74Sd}> zvp}bffu0UcCIcf?HMbW%I6w|V3MTJ*1`kkHp4?wC3*hEu>e^j-9-2 zez*I`N~T%xPS_8S2@Sb4($BU|=yI!qOqo;seZz%u@_#g zOqWv?UzZ3DO*q}=$wR-^r-=kiPH$nSm7q6mBUK@MAFnI(OU8*{o99rtNyU{@&{^p8 zaAp#JLTZ0n53#-l6D%|?fEe1+T4FBQ>qPYn^sQ!31wPA>#HYF`+|K366MAGM&mGdi6UYSQFPWIYT$7G~wWa=Gb-ytRqjR{lxoucW|L z*n7#S%4`(?r6Q`V8;KS9eV$6H970%`Im^p}bgn}+R=-x*)uiQt zwf|?0^b9d$Cv7@1FpCJ!_3b;~jrw8nrB7qgLt|vN&gR}MS&AdC;s0F-ckn7u<7(E7 z$uf|o69GY0W7;~#UV|~~jbBW6aM>rmTK4Z;TR|Q;&Dg^@MGEt!itr+7;^@X7`r%_$ zCd*n116#snt$dtCZPS83`c6?280-_)NuW}7;r)b=&(OP(edHc_q3Z6n?PZ5oT)Z*& zU59>f!Nr4n!%GWukezCptR+aJrC>kkfJ%zTAYYbW38v@v7&rQ@Z47ydF_H7jqNok? z8|W7fXtRBlI-$?);okIlW+qU&cP=tXWvN$2T!oteymXPA3ENN;3FypRScku-XL%IQ ze(YB=Hajg=CZ=p4WzO6xYRv!ZO}tG``)mEJp_C3G%n0E^&hW7an*#H3;IqFqC0|%L%!~o z7PcSCK@Y$bTCb%KnJ~(Uk^Q2^dYqUl2PG26KjIQu+T9>F&LlOb%RJa)`yTPI$G4Bk z<`Ak?Likok|01JcKE}Zs?Uor};F9uge-h*#0agm#+>4tr3N3i&VQ{TR4{sYRY$Wns zgi3JMXE8i>+6DBt(`T6)h&CflO)j~i7n4DZ>x z@j+kbXL(6=N}?_J8uaupbB;w$g2R3RHZwxEM;MP*)`IIFZA^&g-J zot3%4dl>Y9xU;D3$3v~k*ITRQlTUsWUtVXrBb&d3&ho)U^dQaY#>*g&KORHok7*(2 zZhxn#@xscNp-nXgJ>~gqU#3%T&e^1Q?cXPUULRL~Q+l_n;Dc(Mq}%1wR%iZRYCnY6 zlBNTZ<>c{8EwFD&{FL!$B zv7<|tDTnaUk3Ax8;Jqcg>nx{z?0+RwV;iYt4CCjfgiyEL4+rhrl#An;zt_tKdU>nd zxbCwxVAtxf>eZZkIJiRY^e#HU4s*a3EpSqxbD*;x*JX=mAMzsG08T3B*a@c|&vU!X zg}uejb3?CuI|4Vt#EMc;CS$$WFTX8^U^u?YX1xfz+=^)oj0 zV%MN5_Jywlsk}qxryGOy7wF+6#L{2fHBCUTkV;W4OWrg3i)U7@CNBHKeA~4n_Q1g@Z))l~}Ku=^WW-);u6hfCu z=W&`+aisCF7Xj*aDB^$qba~tOV2Nk1QQG<@?~mWl*Hp?`ZK+&NeKJ`=V37wpDBYg8 z+>^yYNT(fg}34nNFLu+;i`S?);3_N|G@a zVbQ}jxL&*$f0yt&d79-cCF08${&8*Wt6OI@nR^9gRby#jYAUVB1DPPi)quk#*2NLc z&~F?w>sDQc+}UJqax$(`a@6aI%oeZRCs8}aCGms`*(GJRxKiW7ex!wp=0pBbuM;X& zK;u;_{hjf$KT-#{P*+lw+Wo8>a;*=4!6YAl>pS`NV{4P2Zn8wd`^lQ*GpDUiTd5{` z&b9N(kb$4%o?inx6ImRGN}2*EE5d7rD1v4kXuCA*%5J{vZONy!26Pt`*EZ#+-P!P2>U!91}PArL7FG-P=CZ zx4y=GR%X=&>os<(*K7YITmlju#Tj=kIXbREAD)KvSsp+xNPhIBpKC^aSgUb9htq4-u=_Q9T&qi+Wou^1FC6q zN(a30Q#)$EHf8qyqjvCVp?vMcjOw`vXn6%T==x=iprKW7!`&1(s;EXA}MbPv9^b5zQDn`h_vpLE#aah1hog&|%+& zhW<%VnS2W!XOM=Pakk&_?*g*LhC^g0gY8VgVn~I>yx;&IsE@R3%$73*$bap`|BnqY z5{(E@WjIY1#ch}ulO%%H+ZLowNF4XPcSQdBriPHx_I38cy;gGk+f@A*QE$=s4+gW3 z3~m)qqCb>@?(tw?XA)5Vgz-hR;ckP0DO~a%d>626%;f*p$^Rr0@8sV7XKzt&E{&7L zbw)i0nouM40aEx35&^uwRKxydneDyS1tUajl-%Z|ZEE`iRQbm> zW_lPg3{*!4%hce8gY#1Lb54yw`;OGOF$zdLVah5p`#9{957P5D7mTQ0tuU#Sa`mAo z8uqxi-_af4*5aktuwF;no+ayj>exXS;ZNxmf54uPUrrzBU=*h<;`g8MbAur76S$c7 z5!L1U3GEjYR6C)Ph^o2O@Pw+!D-YLs!7wvxyt5FmYfYS7BXo~L{nVPNaLKEVC`-T3 zU~Ts4CgK5@18nt+I=Cgh3HaM`aNAO*IxiBCwEJc3(6^vnW-+N$T-bs=h6_ir%?_Z~ z*dL5d?}^`iVV(X_FGj8K{#T2YTk?hT2EDu6gp`Mr45jAk!F9{_aB!rLo3Zn?yz;au zxRlJ?=~&pC306ByBBt{aaM5?*A3357{3BR={D#Nx`6-yo!@$F9e22KLJk_z?uTetls{_fW?W=P9P~f@VgL6If zB6PdmAQ|Z#s>k*?FRVkFp~j0#aVc1;#XlY}CB2w&_&GZ+0;{S@YXZZ0u&Kw{5v#7~oV4|7`l3DX`B)}D6&)Tn=`7SI38!p}v|OPhQ2l;y!HIhEuU z&hdIiCvTk-P(Of>A+fVK@L?dMpKXqaG_pubFz=!-WqgmZh1@a^A+GBS=bH@M4t=vy z{@YP5CPTsmJb69+M+z5wv(VOZ1FHT#BVu&FI8}tB)bVxhqLYUM@iFB?yoe0N0&gJtNkU;W!1RwE>=2ull;^Jhm zIk6Dw(Dj6F_zW1t%3bAPKq|KYd1Ipm%cmx$A)`&}hqZ>7$%j?e6K6QpD_>ueyCt*c zSk!50JGm%=!vL|~2i-y9hI104w8>09wm~&{>G0_@o-Xf--nP@RvIjY;neHrg*$+n@ z(!4c-aH1R9^vsj;y12?GqEWA+1v45bpsOBlO74^aK!2&%$Q!j-=N*A-8Pe|jzag46 zw&0fUt|SR}&8LZdNSd>Sup|@uX>;wwYsb0Q}Z>7w$36lw8 zQ z8+HpHtwfX<`D$w$IJ^Xy&-}=#_p|KuxeVR4z7QPuuy!aB-)|~U>9W&M8DxJS+K4Rd0G=P(_JAgxXB}we}23>0f`f{o%yKJ)+izwQ+uRvF1o#~s`x15`bHH9a8Uc{QZ zD%>dM&?%RZ$|6KgrySCymG0#tjUE?t?aNi)m9T$f8`jvBgpanmx34Ca3π zn1FO9g?(6qj-Js$jeNPsI74qEY&jjbPh|vtlg`slJg)fKh0K?fjAQrgUx zI-0=sM~yg;9TibEoT^NdUiS2D6wULf_a|G?@nDsbqT+*77bZP_TXXmE9_uFb^m1L; zGBw|pCoSmIJ4$C3tkCdY*nUsVEi7U7$;J281#4FF4IlY8y=ecUTNZXEP;o_iQLXzB}9xT~6x{6$2QPsfA zMpJ8EK0E5SBBO4$EOtfpr|{M-%TG`5t@dWh3IQtmId}?x5~9lusXNhk3*OWN5se(% z+KIiB)zy>3yJ9ZC`K99)xtgW2#oR|}yIs+3+KBXm&55Zho$Gx{D3M)U-6z6+nBwyo zb*n0&8amx|Cd_H&vP>h(GX^g1x7rRtcV09g@8}=MD7e)(U`m1>tsW8cvyCX%?WrFc$*twb%Ksjl&J1s&QW)2zg6dE^gOs_%|w$weK7eEFIMa?bk1CS zM8rkOoqs;@aXCa-p*LVk*OP$=Y=sd^JrYx3X?a%l@Zvr{;09alElX@2mGD_Bpc!dK zun=$)a9JIVpI|V@`wM^aWSU|~=;4zH=Mo>U>>wqA#CCI-aO0S9A9m7=k*Zqs+8|LO zFG(btEe}H&yODv?v=soZ1WHvBhf(uTx}(Te91XQ< zIeo9;P+Oi;&uBZ|xg-%7yfdCD4@@st6e9$CnIoVc*<7C&OnXX%HPZF#h6szPSO6JRUSV!8cB;w-w~`cJ)`*9 zl$^eIJ$*$Rd?C<>Y{%>VElhb@zFtgu#h39d&h`HU3sh?`s6EKRS34 zJ#w%rn`sJQ3Me-R9RwbO@fi5@US5W=EzGdjY4an-r%CH*>Je9s=+ADlW?5&(2lP#= zxtwC$R=#0z-g80s5itrGV38FtYZN>Tff)1|%QnnpZ9AsHid(Ab11!0z5wE|jd3C&N z>4$KaHBU~-X?|K}Bwc?6${wK?$=;2=i#78QN7SO`p?1d^j!?X@MzB9Kn1-Jg?L2(^ zWq`|#_*Z%v9kq9+8{bB$-kV@lF|;qPIh-#m3mqbcR`+PBx3r-ib` zEoY^%&!Eo483T{*rD0N1T!i9fyy;e-bJ&r7Sm{!$|0KqyT8gRqdVch(B=vnAQBiZbAS!J&LoTvMx z{*ooZlOwbvdK1?i>K&2+-Hz z`>~Pys?g`tG&|TxCU~IZw0=#-%2g|s4)yxwE$Q07zg!Gc5JJnRc;PQ#d^6EEc*S~O za1|lAzvw*pjcWYJ^2nbsJLc>93Xo29ioQQLdC1tf#d7;FEQ`LixH9Ph7Tn}c5X|zqf0en2l z&wv)T0Rr5^MhEJ*Ed)jCY$#xcemuh=Q??I+Xc~JB)fgli*d3>LH|2oDN?|w<8Kww2 z+nM#fXw9`ze5m>1y^SWwtJq;6VFPYA)M!rq+C*Lly1K7D0O47kQ0iZ$M+Yi%)Cc$U z%oY3j`_In$F`TvL=t)*m;!lO1Ce#W&z+iYW0Cdtu{m&2v4o(7!V%k%;ljIIO|3r+> z!<32E5MT9zJ1zo4zhV^I2dFv1ggE1+G2)EbKpV^bL^I5qOM&NVlDs zW`AIWbz1TkclbiEq7D!butGGc641xS65v5xp&}08WBUKukFjLIw&`V|uOTpnlCZdF zTUC*rNS>I!a>tghN#Kf->x`oU38RlO(w41+1$Q6y*~Zj`m_RK=Q|`5Ws~_7eK3EcA@sU zR*;TJwFf6q^8rvsdyYZoA5!<>8PchviDNjDd32l1kFZrz1 z^6We!yZ1{Fj}a1XyS1y~3IUR%wOtHc83jteP7`_{xTY@1wK`l~*3MyBsJBa{Gf`zi6MJ^?SBZ_x%emI*=X4*Hu-ux2)b8P|dn|J<6 zw=roWS#j6BWf~o24k2O>avq4}VqQR~d;!pjk|Vw?5byoWCo`ii zCHv`KAolH8Ui{Img|2Iz@~B8-JKqjfu|1$&1=vG=P)NCcRX-Kh)M>{G!GlNP$In97 z+Y3(-h7x`J^S3^z;hmG{nw0gK7=gl)PAz`$ouI(ix|?x}fmfGN@lVi#J9*N#!SGYP zmVV%mtm@1s9qK>#*VS3Ov>%FWIpctXUB@IrpHx9J71jlgWx@k2xFbCUfSu%ZU{%6w zM={Bul=XNp;+2$F{5&_Fp@nZ5I5%O} zP|>H=pCIS|#O272Miq7IZk5!lFD>}V$Du|={5Ml7^T_-vjrY4rs-y2hHo6Y%fbHLa z?T>|qj_*UA0D)Y^pCKG*n;=0*9IgW5-Y^9Q;NjvA?j)r#4>rf6`>?}Qv`I-Bl$@>x zVIVVo;QEtqL5+pDg={Q%5w-wWql;e*AXjN5eRZk))4%`OarKWKSbuh5{coiV{Dwzl zG#K9zsZj=QuH*$tk9!|cED8-7CtY;idXJ&FQ67Mus_r~Up3HFHJ9{l)Mx#DltgZPS zy&(j5zd;FVETC29%>^++N%ovW=nueH=JWS#QbwZlChYzN~)V%?r=Md{5~pg{h8to&Wskt%`UQZ~o_l zH)%5H7>(&XKhli~fs`V@6w7FKhO_YtVd^CI#tR+IM-88z#PlpXx;lxw(YhlH%{%?d zk+Qg9VdA08kbOt6AgOm20Dix-_i=N{T|t!4%Pj=ypz}LGDU9X#yzMid z!4BF@-V8`6=^)75w~o zK6f5A(?E|E(SZ{3N(h=`Z~=*<41#LKKmOyt)$6Gz@Lm7~k(orLXA+ouY$F85i>yvh z%qQWbO!p|hs8QW(KdWJDXSCntYrM0xUWMCUvC>TkekDay-mP$R!J_vBb0!B;4p9Ji z)yR9U>f;jVDPlM^)8ezfeUEuT(PL|rnddzgoc*pYyxHb!)4s@^2a+!CISq(Gz!&Oh z%!8nh&xGyG`cTH|1w=~jkYiuN=1`Iq?#9ohqU4ijeI6y8z6_~8zUijklJB^=MbKGR zAs?v#4QY~uRa*3@yWl$hAOp=6XdW3T8>h*_R)m3|QGX|oSFfsTQigS!dzOZdMltyu_LYh z>2%MtI~JUWHus-L*7FM)kibUfuK>3#Bo7TpggU(eG0Z$kE`rpsFDo(Ea5a5P7rS`+#?Rpqiw)l`K0?%U}=UlL*3QdjrCW&x+=n5-Zk&|yvn)M>c4}cQ{zY+3PVp zGagI{4V)f*7KApPrQ0!(~uj>mfmKbu|Q33!AZU)miCJ0`u z6zvQ)*JmObBgBNos+8W=T!mjD_W5IXcE2&Ls?Tq8$K!uABqg;kl|CTt}ZeVtJbboJvj*hl+WkqHDliaXJ z;_V_A1ijChsz(Z{GBJR16W&&cNI5ZL5d~4s5j!A*-f`L9mzg`_7D{WIAO+Xu)HMt% zepM)mN{im}>x(%?e%C2JFi=Tgsx8s2;AdlA0dEim|mj$ahm9 z?enE-_2#eOYr8O_dEraVs9+ITfnWaASgGS?>CeY1VXDHaYeuSaE=(H8j&R2}_{Jxs z(1OG+#z`MI>|BUQf=;zE<^(Dj!r3*1n8D#*FSGsIs!H58bEz$|*%t>TOXvDjy}l)f zDt4?0{jCEMaR-jWAn;<_$$!`{=xAj^ zZyB?>IE;5*+VPYzU>8z=oC(Z%9LRyAal}R%qM}bj_1u@6=C6BTVcY||N3cdyt~`^R z8MwPHqkCWPrrx=)cb`8?D~NWmy|a%W@F^7lxz%Xke@qj8@1?cOul(+X7R%L9%NY&> zzRsjIQ)TM62R?v{_Ix7Q<&R0}O^>W{RixiJ_3q?$>9p!n5#3$NN)PL4e-Un-=Vf`J zBEg_@e11;+4~(0>Jy(cLJ&dO_aKHBg_&?}GT}NFkA8W{ik8+Gj=CH_e7oE5!)Tq(_ zIiGCo-cSCO6TyrZ`6$9zeCNep@I_y-rdV4=CMI4FRF=T zFSC71ZX#>%*k~(zin^`VwO&5wOPmpVS#*iFmNL`SUbb3?a z%FR4h$^5)A{7|+I~gH|a^ISWIE`l_^1d7o(oQbO=Fp!(l?Pt3EZYJ1 zly+K?&obLF){En|5zV&hDY z0_d<#8??SAE=X`mruRyY?_pQ@t#>-_j!Qb*C@0A%uT6{FAg9ms8@RUoC%F$15U211 zi*Y?2^3JiPYnOR3re^0!8jr_*j2tX)4tlz$s4GylNPF#4!Z3a9o|}BC-d`!x4;wat zu>nVOV?$m=9wGs%V>*m^zG-u1p!9P`HDR#DL%kt|%{iR1e`I=1tJIFxmo~>{WbZoM z3z_r8j{XVY{=0+A1A{!4z$*~F7Oq~Xtoqj<80(qeuPHw!(Dm=Qi3QvzczTvm?k=Ku zbpnmw8xq<gI_sH{Nac{U-ZMwxj*ttKh*8JFndzY^0WB5xI6RAOQOgCxULp&k2U* zQ(JU|eHv8#catP)*1Q=z*&g^c-u&|`c35_ZzuUwv#cjOI$pkbCG=HouF+o#2mq8H+ z7^ZL0I2NyC4j`G_3EY_*Lg3tNip1v~)L0P)LD|O2`IX&?G(_16WXq+X7SWR-T!q$o zR7~R!Os5bAIR}OZsEk;d^FqTGAA!H$un}bxu_XU2_36z*-u5GEZy+%h?nCV=Z$M+K zY4FK&Ou%{n_u&^3L=9+k^xPbHJU{PUyBfK#{^PUkFI9uuAm<tZIs9IuoKiq?vwW z`1J7w*xT9PbXlAsAd+gfy2Q09*h4i{SrpOfZo7ZKqk; z_HNLm%y!~tHmKBGUnTG6=VgY(lI(@!e(Dd`Z&ApUITU!!xc#Zo%`gFpIr{g<;m~Rr z*V#ywCCL`T=}mc6C6xGjv!eaqT`pWDTt8i3@#=7PL57)ikw}!T;IswqTK_by%nHdR zG}&_$^&zfy43!A|<2BXw{I3^U&fZ2tmT$BhQyRE<^{-_;=@i}qCJ9P2-46aD(VVOqO7 zaqrRU^0b#W0&;vQ=XseXDAu+AMI~kQ)i{1Q;DuIwHxFs-M6{9Dk-E0P>Ga=&6Kcqo zks2<)0TvO2Sd=NiVsZ<-;ePZZfq4`=LK~;WgO;MT_R>>XvVeb?s2%gn`@-g0j(R+;Pxwd|l)f9Hzd!!z@H@xM1m;=QQ!_u(BBV4X4>c4mZ~$#R5~ zBVK;>d=D`Qh3jo7gT}}Nupz*~Je`_AVA{_QskDp|pEiwb5TJbfgla_WZWrpq!@zzE}_WU_mtPG#kPkJOPJK*h_|L9Ia=$HUvvdNIR_YZ8wO*hY9jz(8gm2NuckjfZcN>bHe-?Llk?A2`rJuYwhp*%PU>> zf4dpAo5Z>#w^v)qLek6pn|w<1!r(&wUzBtT{wLryq!3#5n3+fIQ}G)iItAiK3>dT| zym-CUIQJmR3Rs-8B)rTWm=ZPr78yFsE*0TvoEWc zcJSCtv(rMCOy+a@bGK^iEaYzZ@$8xa%8U8N8ZbCVV_w4*pm)HMp$53X^N>r_l6lxj zuQiL30?`wxyi4xH<9!Cn$9{Gm(;FkWy>4w8>ZhCt2-%V?gpmVM0(&fQ{znNQmDt## zw7uUHm}kCo@b~BEM>6ssT?oE^Da0 zZ(G(js;JzTBzy$ACuhOE|91dVcwn&J`9bF>`JK9-J3K-OnL^g8Ae8 znH9e}hu+bWuDekTK`osP$Q%7<>5^;KomF1^26o^zT$$S3OO8C$=u}CQ@y%O{>@R?c z?Kqz@RzF(7=Qyyr&4+K{P)Z^3e!6Nv;)X3L$9Y`h&~(sv(Ygwrr2yuV3H#U)VYH(` z7$QYG{Ki??&lvoR8>}!?A&SYe^+lOKX1||)g3F%sAw}csvewmd~ERK zr(viGHLl6FXF&;7wt3P&uDU%C)DM1XU62Ai?CFQie23@@FMd*+)0d+`ikt>D&fzP@ z${vyX^VXs2T93NNx#3NeaqpK7=ThWfnY{eDcXyj~uF2=8YMPtVSD7HhH8@YX6%a^3 z#6mT+H;S&~l$N=*S|QC>Uu<#1X@9q`J+d#vaDjgJiCtHW;=S83j%V>PkRn8XOO!bY zr-YfyAs3l*>@?MvF|?MILj#$HtX~V2)sqf)VsSfCc3cYG(1<})9#VZZ!FYCHlT+6Q znC~QMB^+8P8>PLa-iwFs*aAYH1FM{^54)J1KxS;73WN5a!w;!Gg}`2IF*nv47(%s4 zYN5L3!FGFG6;Xn6>OcuNK*gzY_^Aq#F2EF+%%i||N*1m3gRj{Cf$^Rr(5(>hiKgX~ z{U!a$-7TU4pzHQx7A@ zY;0^@OW>Z3nCEc?(MK?#Nk)pt6NIN&5NSl+MuhtCK2%t3uq_p&#N?JJ(y-o%(%#K{ zsfKeUj~1lplGnFcTm({qiu1E-J(MR^buqra**+V$=id>sk$l#yvHh#q9zLZ#l=%^= z8W_u>JRphHj352ZXnV#|8J|y(AIBvxO=r!x#F*_QUWxD+kNdJa+QTr)+vMICx$9-0 zj|ZMRh5eS2z%3-ey7m)k)U(7ynh^gB249q!<$H~x*@eLLcKO;R17B1*8SVfkBzrs) z<)J|=DIPdyKY73dYP^M$mk=36JYiSOd*f$nsL9YyNl4uv^fIZi>a0^o8g`I0qJO=s~r{AVZNAb`tZYF=goW=!_MP}s%FNKW?%Idw?&?x zs!`_Q9Rx2}4Hbz3XWk1dTs$CkQajWOrT81|t!ua+p^`REXpbOwK#f{ddK%crczQZv z-OqY6Cc9^Wb8>LsvC!)+SJPvu1CNsoyM~(DC5RDe$~+-}eeawy?&$He@!s)i{q73V zXHVaJv&45C6bPI0V09p2HVR0&Bz!0O@~VwyowiJ76AL=EmJ<+>r0^QuE;y%e(S*|r_v zSmqzz>(TE&^s_d@B&hwK*H%4)+QztRn&EpV#ju|fG`?Yht~esyJU)*|7qP=rTa{#Q znc-STjIFQS^uYg?|Jqkcw}pK zU|3ine@@PQJN;i>$|<|Nj@X*)96y1vQH$i?nETBCp-+u$W~P|S@Ni47y=l+7i5LU^ zdw);jXfS~;^L8-U(lBr=1o+5(l3*#6yY-GBYE_v^hOAPW;)}unO0|vBo_9mrH=Mwk z_0oANFp)Zl6!@kF%Mx8Lz>miTmL%1ixFR*YA`b+ws&q zyzmY0IUX(%>{>rS%xJCvYHYxw$m3$ESicZG|Js42S2qYXaMZ7Wjf`N$x*JKPG79fY zHIPb01u6eNMKkK(R#Wo%KS9Ow<=#iALbPLIKYQo(ga;|C+64b--Pp;8#dIY z+tu#LD9<{yw+3_Ny@z*}UYpnVq`^S2!bX{RG*PW757F?$!*iz*doJ*xz41vj(IwzN z!`Y0&CNtOOhHbsyd#X&f*Snnl_GQ#w-b&MZdAM0aJnd~4hGYqDx0)kTC3lfEz;Az& z39BZ>TnQ#HsLAFUQ%B%T0!tun9PI&(_^rP@w&m_6r33F&vohR0NA6yt!XP*d`2v|| zAP@=x==?(u^9jW#KJU=%B(AA!&Di4Y z>73J}AR+A_j=@|1rQRPo3i_v=MaYK4QBBxs0tbZ2n79+n*!X%pqr?zfPG#1I|IR=1=K_;6U61n-T5XeM*&z18xQLFB32QK zwPOCvXXp$ij{9AWNdC5%I3e)4nyLQ?dT7(P4WRQu&&&Ixt~6%RYNBiJ*lRF3zacma zKkgV>fJVPwJ@pmDHl z&|Wn292he@09U5Fyp5x>wCa9Xw?c%)zm;3<0Gi>yL@|H>3`gTUv~Zcqi=TA@A!JV# zW$H&6$qA&28%#3f47zyt51gst_w=3F@Iu65Nyz=M-nHHyAUiyQwovIKTS0}L&m6|4 z{$}-o>=7%1;0`sLB6v^`mv01K{MPDKy@baf7v*sxK1YV8s~xigr9fZ@R09T z@bgF@zb0_p0w)EYqeBFcnWwSl)o?70GEi+AI{bl}au7wTUJJFijGP!SzLWDJ-|OO< zPU2;uPN@fC7H3cG`O5ot&aE5K>uv@{RJCO zila`n`9?V8O}gFI*m17xfm`Ey-whbmUBv4e@WR@Bgd6 z=l|WmkvbwUPC=xpsGtf9iwcHuENwX6L4egng(jHGs8B!0tepV~cPOPY<`h+8ft!&>H!H4XQIZ=%=YmXvBFb%4|GmQm zPJ}35um=p#Rga1KcZbR3f95a&rz#3WWx&JQ2!86|y~FXb0I7b3-CX)|z##jvW1j)1 z{#3U~r12&3wbHVYyH&Y7|49ed=^i>jsKz(rhlt~f-&4%hL#YRuP^{MB)~vZsyAW;N zO;OToZ5}I2NEn=Zqqc!B5_{+&6^BEGXZ{q(-dmMeq%%~=cJDJt6|vH@XxPn~h{!yg zDc~z*Z@9rBQ*M-fkHB|s2l;q`!0b2}iSt%=Q-*<|;s>MkP8~mf8={xt7cUbkAXErc>u#UmS^2V` zYz`k$^B6di03EOpx?%l|L{d1>myr zAg7hZ%?8OdM=J8L0F|>sg+Wr(%79}8LX8sW_kMu5?sNK@is+^yGHPgwFB>?!jVD3g zJs}l7i-R@oxe9}`G;o_Lke!#tkZb<$Jo`1)4BhGmz!J<~&)o!MNlTP)Vxd;8j>%rn zeHLt0Z7+)}Pmugx+z?xL=G2?WJ$z0rRF<&XY7@ym&j|nv(Fy^nIE^;wpT`CIs{!F1 zrZQyghrH0Z)^=3pcTh4*!o+>k+DKk zUa=#tA~O9>6tB*rvG~c|35K;OF%;mUFXBmMjHuo`2bQ-F@6gU zX_Kk0aM|8T%a1{tn^)5@n$*nU@Se!YP2U0KXVStC&ZHw5Y#x z3s$Sn!ociWxpT~cX?-~Q2j<=n443qfs{DWaA?E#fgOB20Ww!=B$4@m;T!RF4e8}IYxm~r%}ax6ZtbvQ40a& z=_9=pv5gUiiiR4J?3fZY;$;@ zH=K?Nn_`jsR*eKiW;zdf`~dqBPfr8Lxe_46ZOJ6I=5DB9wa1xnx?rx)l4?-tTS`7D z9piH@v>+*It*6aGr=Fg~`>%ro((oWKFrC2O`*a+J=Qxf?K9D(LIg;Ot8BpLCtx z`F6)=x*?V{SQ2WviV%o;1IspD^@x9hxN>t(_b!H87yBPA@w}9_@0yszmCyIpQ|v)$ z&2t;&Z616K0sz?+FyR$cl*bbIZX@_{8!+Ww)G5lU0tU>F{R5)`T5U%X5U?AfL1uzK z1)QIM>i5v4@JLAkDwT)Gn4kdaG7B7)NU&HJs)4@J)4#sFH?j>2Ym)OX0plaw%)VOY z%yTL4)U}L>!gmnkL<^Zeq6FUpVLTpKjteLzR~)s{y;FJt8p*I%ceiBYW|q;cTnq z${aoGIwP_nGr8WSygX*F>2C?CwmEa+Z~t|ZYd2fJd!S??FwZYdhgJt>n-c)2&mKmj7M*VP6ADW5$ncsTX>>YA@aCnadv49-{soN_a5E-np_K~vS0PaBGLfX zP{Y(|8qMbxFz4BqN)wOt&HaHH8139rXBDyg>~y^LWO?OHrFDr4%iPcZF>>aASUy-e zfEf-T@Pp^s4M5{WNs=S0Z&tr#t#Zb|ky2UX*Ap!MN6JgL4$OZ#p?6=s40jgDq5~K(KR%^@4b;Y=;FKygf9F% zpRlU|&Uzpg$1xa_sfSHCyL}QT@bbfw*%61A2DbC*dVLGhFuT10uUkAA+HSzv!YAmv z#%iNxU|arCsnaLcV|YuYcnFpsi%B{UN2crib6(^X4(+RE4^)3F-Z9!%02uMsJdXs8 zk{IdV05rgV5#;3`F9LZc?A-NdfR~?)9V6}Uug81)1{QgAFisa(`fIfa1}Yq-3>+al>_%!Dd#xw)=wX{7ni@wfCyauXO$IV$~|JRa5vncMOVF-)hwsG!Stnr*c^sda!x z*w~*tH0*FIm}BtrM$W`(o@Is9Oe!T*5*5y;zEk$)*f>A2tL`=<^j-n=_A<` zZB2VLHDDx2+|uc(e!SwKP*EZFJTW8q z>=8j_C&uSICJ7hi#3(B#fY_{6l%85Oiw>G^i@Xp+!_SyEvmqVw?gg|zWt21M0P0~B z^yAgMYXE`O4Px*0e%`rb-3)lo|C%u6gj2DoDCQVRn%LPr5zKCePQn$up&`vao*e7ur7boXnPEJTX5%YDtO z`CDG?1;n7XtZR@YX|Z$?3QPN{tWEVEyI&}G@nH!D%*(7hd0c9nwWtc;$aCvXFIW7X1;Q=O$Cfa?U0^7pU~0a&{i!8I^g?TzYKmcsH`qGSLvMvdcKK7@P2?p5Hb>wH z`qat9b9Qxm6%Gw|hlMe$YHzKRG0dr+_SUxGPqEo;{)9@zpS2g6ZcyOn)ML58cnn1p zG>=^FWQWS=7&LU@v?@h%S6z(Vc=~f-=z=nvX|S5p9PSxO11J%_wq&%&*XuKIVu$J& z=U2$tyN}SkZAkGWK1ak9_#E~I|J0Oonu1`JOhi_Ayc>~`ZM;fjufOv&RIlAb+WFf6 zNe{YIqa~#)A;B06a*%AU_17wsljpg;_5hIw%=|e3x^g0vVG${#iP$+FR(K04!WzqC zY_HNt6}2%o?Hz6n30^ib${Zv4DjbiCdgA3HE7ARnCkc@UF883zFyaXY?*>^v^w+py z=GH`J%GhX&(a~n1yZ+<7FXnq^4LKN|kR3LFR834F;vEJ}d-^XBCj^uzqkwDIZ)}f9 zny?30vW>}jddYI?e7&0gnU&l^ql8SWB>T(0(j)Cso;~!sIPX~P_pyONqtPNmgi;)$ z1R{ENF+BeemSo5_o4Jl_j;Xzlwd+|rGkE-DZ*)tsguzQ_^B20KXHmV%Q%zy1BhDn? zt?~1~VSS$?L2icaK408V&QX}5HLEU5T z`Y%&!Ds-R0R%~G~uC1sN+K;O|ca4t2A?khRQls#b1udh)gOV-r#l!7E8aLtt_EguL z_d2(U)L6g$l(YKJAaM2o2S^Oh075tfM$PQ^BDYY0ugp=L(=J)GJrSKN z|B{|)TPC~#SMQh*?66C{MsTyF_mve#frB~2O+ks8-#z~$ZlZRaytv$1gLstZq2gZ}pwBV%?NWez9g(uSfPFe2Dv7G}J3(84=Mx0glsRrI2pNy3AO`1ok1cvsQ1 z`BuAN+e7z>;lWkaTLg|B9WGrjp2EYeX6mF|f#S!6dQ5EqsIu4jW6%sB-7)?jNOu$+ z?pzc2IQUgy?iq(a6vw^;mV}czE;NC-eySSPg~OQP&8T)y(A^T1lm*%9UaiM3EtPrh zZHYWs{D@w5pz+KxGZj>n2j)B{d4UaMqaFL)&F&&u9)5L%IhTGgMEt_1(Xofu2ZaW2 zZ4-EKL;xd%S+s}MafpHj9S3~8xjg2?I5w_+%QK*~BQfI}Ve2vAzr+`X7a6v{#AbDV z^SgYJ-l|a2-KT1MDaP6{_G^g!Uc+!VLmV#`k)>vhZ2*zQTga zJv~RlRnzBA{}@zS;@W`&9=9qS=Lf-C?Hh@45}zZAj`oxEh(6B`x^A`Q92#*iTYS&7 zz8EfUfwMWf-(g^p-M{GDxi8n%sV^RJdWb>+B61U@GEda)yiuNbgX)aqADDpD=4#_8=l0VVY#g$F&>zKU zeciF&`AfF1gw&~A0aQ>FxF}|%UEpyaAby0HtF)+jvLrlzG{L6Q);0OGfvuu%=do^) z5Tz3$6*oi}hN&V?hdeEg{{|^FzGB$t379lju)iiLi8Kk*z(UuVF?r_U{G!l|vF4+D zG>>VOyuV7$l*}Kmf3(vk%J65k+{E?e8bm4_6&>lLo~Od`yJxDi!ZZUM0l}8|fw#+8iQ+?)ZDiHcnoN^@$6tkIii;H7Wb56zKuN(^fU zIPxvztK2)phBrajiZGK9|Aifu*@%yozCM_*61mkP()jV1PfD^XT$d6C)uhsYXw0 zLT>^}gy`R}O6T#yc=`l2(p-(@&=O3RWlrXeYaMsawcdCo>VxQ|A1+@C_Mf|`;<&}Z z`TnUjhqv)g;fG(X(u0Mt1Q`A)=`0<3!)xYz^K$tkt&-^m757jVnNy}64-Bj4ziD4; z)18mJm=sDWrLGq0neJQ-FkR#L*sIBuW_MdgCZc)Tbim1Qq-na&ZAVL)q20%rh@M?{ zT*Rzmj&#+Y;{6R4hJXpwczAVDjTW%4!q5Xmw6>RYbmFy2%K`RxmvZKp54ZKXCbPY& z8Sj_H_V$ETn68($zXMS0F_w+KhZBA&=luNE39wgH6;s%S*=Y%DF}s^lEVJu|F(HfxeD=QO*XrshgA`TV{v�kw&ZD4uk50OR2-pHge42Q3gIvV$x3XO`YQ8>j=fV zfGp>d{4f`>kaNPs6CP-(UO~FjX)W(?1uuC;| zBA;4C-gT%yk9AB4?f$~2*nEFY(4UH63-Ng)mT1R^mmp7iY!G0wm}jv_fj7g6d;1lI zYcO5Ov$6*)XGL!HVjirfGkbiZJ85MgF@m9i<9D@~d2;e#X-9-vYoFmwtH~Xk4fO1l zzK^szUFP>(lh+0kD=C-Jl8`?zx>kQ+uFin;6>MyR9y!YDM(Mbfn?83~vWUDtxV#nj z7Rn387LQ<=g^Z9CQzfjDJwF#6;&&vtIqJwgWYWZy#HK`-brr5JIzNy!yDT${;jYY}E({JEQDc7h(9oUGcUVuSaKUK4= zwB;p>zbYf&?2&)alP}ySNBu8LJqmD2uq$3?#v`C^t&Dq4D7TseWIv-2JDdqx7h|uM z4wz~%5-%H6CN;QyG%mAIzNZ^(D_^9dvrGM=b)$J2AqrxiA+|?2RN_6g+OjU?JH6H_3)N!2@ zCbE--jnW}Yz=O_C#v+$zY@ScAG(XHZ&xaloRrt2&?15C@Ic4*?=d`E&zrkYRKMm&g zN|nwC4akAHvPS8dai(g_P5|~7-d=CtAg7h(<*nPv&#k$YRC48ck(}eYVu{Ue{=2zu z|C&_7-dy#qa7@Q8fUo(@G4L@r?W^AsHj!-GV%&2+DCY?#`N{yj0!&?iJ$jayI?3QPni!FVgdF=O9nf5T+n9N+?2we^sA?@|i4Yk}H zU>YEeM{tsiXT_)_`NPV_;@kuIMKd8E8V|quXn7_%ECTAMsX`GAFuYv{S@oKsNah6(u2 zc-UN35wzxqv3JtqD~{!)*3axq=I`g^Ly`+#rFcec5~w1DPk==5ADB@py<1eN#UVtbRC!DVavG!R;vM746&`RNerw;gwcz}mPw>}Z zn!dy?fr^yZ=Xs|O{ujZ_LjQ&D;ekI%?}yvxK*@z)iCf*U+Z|^-b7F9R$^E&GorE7o zgO@hvzI!+@v(Cdnho`G}*lHXBV7oe0?w6#aTem}esOo1$&)wLE4~n1 z_B+p$$>=Pp&zp_cau^q#?a?-2P;X;L08q}B)y-xNj&K+?EmXcEdBzhX*bs!Amha&0*ham-%;!dZcflB1V3v~L{2hiKZ~3k zb-4g)uQbB>qzT}NIrY;j3K0b&N0HoW2Bv&uRvL+5TW zKmq{;D$VHz$?FkFRy1d1wOxPiQ#Y3O^uU&?hSHa|*}k{U*Neh2;B?}Xo%~lCkahU(IrC%KFge!-+Aa|cjxBPuPj0pDC*e5rd33Wezy?X zn=2Rd#qIG+7A01BlhaSiy%0~mzMtp9FJTlkK@u)v>V-W$vz-9)(gaccZn;o_mO6YQ zNvGIq^5lh+XWw=671Z4_pLsT(R{9PQw6A+n{;%a8{AN7;v&-pK$%oZ4U{n;zx;`zy zAlZsx(eq&aWv$2eL$cELEeSbz5;&*KG?vDwDqsZ<=L62Jv*0T{fSi+xM>8(mSsAzB zCxL`6-&gKyP#*zgetB~SEPPAeIuibo70as$^~k39hLGi>+MNb8uPsdEn%opgca^c% znLO3pnWW3V(7|z}u7&(*utD}j<~7K-TMAI7q%~*`!J9kVoHC7$O&7SnX3n7rHP}g8 zf6>%8&bN=v$mlZ9PjP;b66MzXv{-7Y7G7o>b#kvZHBviTl9;_kMxS=D+SlIygEz6LBjUijK} z;2@9)fsgU!}rnvm%x#l=BAQm1A{wakiELKzD0Eyspm3U^xC zLdc>q1Dp_Xlh!;?JdDkg2q16vRgxJX`LNcYJv+JAH3wy?gJlwRZkrB2j9>29(o+0R zlINJV&09iG*1uX11b9`~X=IrnCkJPjn7Fo^ZF7%9Ls~XINxRZ0D5y18FVUJly1DJ> zyd#xf1c(m4aX=NgQIWh3{RlMN%}uc}kSKzqTUP;Y%@HW>MWyYlSA8+t4(;p?c=hCt zwuJ3z-nwVEU+5mTnh}`$&XERDlaMq3y}ueaN-jv};96x~ZGIKMr?%(k&Df|PAkbGh z#_y-JVNIcW3$76$=dasP{mwYTZh0F?%4Ff{GWNV0DxrADSqYk8PJ1|IvU6V7MEo@U zLN&ugfKza70@{a@!e77+3AfAABu(8JsS0-a@R+Ztj>F*m6KcI!wua3{thuB26{}02 z^7i|Y_Xggj3-#V?3^x|Rfpz?Yd)st7Gp}*y+Yv&n@>T}>tZ-nF`^zt8pKHYpg6qF73Rxam4KD-XZ}~-A%m} z0lNJ3rlDB3 zFBg87gB4m%Yc(3!cz;>K`a{6=lG3HX zK{~+d+Xr%+1R-=7NYszLWVW|`^l%GxYTNiE(fet;&qe>qGfL9sH~nv3dZfF(y9$&! zqjr$=nKVQq99^&8-yn#%GJhr(dDw*EV@=fOH5iCo->4}-iiTb{*^Ny1}yKf9E@9YpV z5l#&8vE~yU?<3l4?ZK>ovg%`CVU?MnX@kbb529P)+s$E5512QPf7#GcZg=@uke7(? zXXVDQ4G}}1-tvvxPqZWQz$o*ru(}Z`TlU96d;lRO-R;87(HXt5&?{f8q6ZDgUPjvr zqpK=5SVu8c_cif8MPX1KGM(#t|rn>bBpZ0s5J(y3XrdUgvqfPCY}C58`ZjMSuC3ho`GjM^49S zd^LbwPvTScN%asMpLFiYJImaV zI+mdKw2&=b(Fq!34iV;L+cyXyKXx=?11Mxpwr1i`1ZAie6C4 ziAQOYZ+NRGQ%^_L^A9~XL)jo>nmANSO@`Eb>sb5rbOy8r9ra(_ zR`?khcfTOdXLGdW&b0Pg_h9=~K|49QBNCyNVA~Eb3iK>#z}YRslq}ay@pQynHROvQD+X+)}6I;HqFz*-VTpFN-d6^U8I4Lmfa>BhtZ5ei_7wg04(FH^u`SzWp)U zH7`_o5b5BZDA=V~<=v?ut{kjZbD_=t?t$kzPj1?=pMYJ4p&0Mcy0cgqp4j8JXJP?) ztYJa{l70obT0J6okB<}P?5S;!bxIEgKYh@B?aohO7vLc5o}-)8F(NR;vBU(dlxl_3 z-FtO-k_u0k)%aM)ZmhS5?@3zy%9Z2W*Ifr{ba$|v8>&n3l;wqnY(c1-(qUQ&xlS4< zC@WtC)99Mu!vgysH`#02yfG4!XW1<&YRl3lf$PUX2P^49XZ_*{WK&(-upco2#mNtVzrAdpKe{+ zzY#BVXn7;+^uUQE7u4nNYu_&hD+-6iTnayX=54q+>rU${oG#!2bcn?YbjYs-8}k%u zY#hXM)4i?+=0bOjOV-l16|$*3pP9YVN@;ix+hoy0^5SDooO?!K3`3BRXC>~;ufbm> zK-yO4DH>0Z*&i?2%A_hW-v5Re6k5xOUt--Mlaz{dAGbUHVWRP!4JDTM{e!g~jvnRp zon^5s_^s<3G-As-4TrP{O^0X#nEF7zz`ui`C+xMv{u ziYU_yeaq(p>lwfq0UVt5!Aww0s*m^adxT*1qiYq0lr|9rKl+Fgr+U<*INC0m z;8|H4`&-l_Vp;LbxkrtUr*xB^rmq2uuaHQW)&Q;@a;eChW`OR`*6Bs>3n^`^JcP+{ zFwGzL))Eh<94-{EObIAPL%yhSUtU0TdKQ-bv?W+r%rmWWw?hw66T;X12##1qE= zC!+V%PUD19GpbDdD@GRbXe5wRq@AiQN=ZDO;+ML8<%?r~*qL8>ob|D|m^XpTLDFnW z1=#ML{_+$!`GV^3Ahn;I7+0sv>`r%VZLB?t3=2M6O&Q1~iT1w&s=H$I`13}!D_ajg z7;tgu3Gk2T?8LH6Ur>sZ_-Mqm6*SOv5#bRvh9bS5`p0@}l-}I9(0nM?T;*e6b)K7@ z|F`6XuYzrQgX?jqcwiEh=mJ_(AZwvUohJLWBu3O7CTAxGzJkyl7Rq@y26fzD=T10| zkBu1z`W>;ZJ3ezj;zU)|^*}aQD8T4A0DT|VU&!kT{B@u?>88-xQ1dqnQt5Hm$c!IZ zm;#MOq;aX`one}QBl{t7=d0yT&2fW&`bKvsn4NCsYCCX|Pq__fxx z!4dHQEjX7v$2AEUd7ZRh%U%|A>XKHl;o>&pNDF?7Jb8KL9&8N*sR4|5#eWk1(B&8- zR}bZ<(fYVf!SZPQWczZ-8pfklbD_GZvt3Kvyi)0e$W^&HZ?04of zL@3d(Gq7l_Q1_l1HwsT{Ff|x0Rofrv-RUSJtLrrCgx^o1n$`X6P#zU*XxqO>GxFPD zBb*!Dz!(NPr1cfYVKhl#3%y-V_KRMczI&}#9T789hxHKtGPd}sQRvl?reuS5y$sk+ zwl)%QMzg~~H{~*jl0WQz;bIKdbAW!c8{-bBZIV?V%kKXY+iL`vx8w&@uP0FxkMhJ^ zKg_?G>HCvI;S)^AAb)}lT=7X}KUNGu1YVjX!h;Y`kSxPVhMuO3GqMO#xIkyeHT!7O zgaPWnO55k!WYw}0->6NuN;o6qU#*st|EdY?_Z!WzC(GnEsyLB09|a&D-Ej_kvtW#p zoDbGHr-J|Pg|xbK#_GVz^IKnhE%tyWcog|Mva#smMM~uo|J2-@V{^BS-gybuHJ03u zPM*IjYQ<2yAZyCdbYw;-&)}g0U_57T1DtGu8x}teAtw*Pt-X==86L>AeIg^ja}Hk6 z=*Uy@+$Sh_BB)jB=%t9(*|Y!132ZfjyF)<91S)_OA`6)sAxh23it()pfpFoFV9Sh| z&C|%Ly10v_dSu>ig9oM*^>4e)C7FrJtDq@$J}uJ^y_x z)fkM>e+doVz?JR+1vx2*8bG7nHHV}4ci*XV#T3x*%&?pcoY>WO8(d#075 z*VA<2?4i9MSM$GOWAQ{PARZI#`2)KK22_aFRFq;{bSj@@+Vo6o3y(OA4tL6Qqew$t z{x{yC=k{6IiY{ZxC@dr=(?u7>*pn-pRHG*j_l8PRT%Z>xI{w#V z^{3_{IC+KG#HK>dNi%40hYm5)rcN(3fbnjfUjjXZ5Gx9Go5b?A?+N%t;bY=Icpozv zZGQ3ji!JR`v7Tm&yWA(c(?;R^J=h^0syQA4JyvYO(0y`n>+O{)N_0bNH%_l_tMFP~ zsh=X}ye#MM_>kFd{~mnu62B!BL#joYF|u5}A5Ukt9*_vIpVj#C-SO@?^XF>6_9kvQ zc3?nP+H*2WdooItYp>^PI}u(Oj0n^Iifco0flaND0*(Tnh}VLb6=uvlyuQ;<%B8^6 zjy%h+Ma5GKi_0R^;LrBkTFj_L3kliT`iz;w;Q0hrrqCP)%-jtz{aSVS?ma}Ly3?sW z%|S~|Vm}p*Q<(GI^T0;xc>_ic^0%%jtwkvi#R}O| z`%~R|-}l*vne*@_uA5bMwaw@rk7YXH{ZPt9yUi$xdf{mM~$y=@_yy5Bv@%*$eSWuU#I=x zs>8Iiw0+dPQ-EKUTl}S(yX%3wYo+iHFuOyh9HBcTU1!(E?TUA==Lb$485pb(SM~8{ z{lMAY1O}ME+;o4 zJRQ!9!*GsZf%0(a2;xhSmBKv0l5MTH899^qSRsUvlhMo#S+V}pBMX|ay<*3&$GCF9 zYaUneedDqT8te=BI}gJ$1K8Iw^=$}G3>dMZ74GZmu#b`(rJ=(2>nwa4ajO27 z;i54b=)C$gyqG%$MHfzK%@+Qg^cKSb&EHi4HTE6K_X{jMc>cgJu331Z9Ze7wjVHU^ zUDX3)l$>6T^6DS#)jY_Ak5BMVgSET0<1GA@arhs2qyyL`avx%PSYHP-)O{5kkVMpH zJLo>p{iiYQC7~e2Q~U;45p!Amt-OC!tzbbx9Iy&DD^Uot1tB~oWQJt&;a6>ah`O`b zP*k7BLaOBIE2E+7;z^$#bGCOJt^nl8%2X;DK^MM5bsnrc2(8YlB&5}uU~}I-@C_^& z3de?tR za;^rfEo-J!AtgHmUW;?R7{ z7=J#fL(F7w@1s=iw(3m22t(#43^5f>Myi4Zu}4H$kPz%3!f*@8w1^jP(if|Fra_H6 zzA3SG#WgGCAWJlxyc-7v>GGPkmpO#iV?4xr@^O%?8nfJe;7yJq^(|b-T$(TgPCs5W zCF#%$bBh-Z)L9q<7f>fK^#}39JeM76a*W*ysR!hOV;TM&)+RSC6*x@X*!vwjcU- z9CuE9yo5HRp9OL>smJqfK^7GWsvQ5o#JsD}Rx9OLVW&AY*UDv5#587VV=D_N)&tDZ zY&pg!;PK^S1=Sap%s=X>l5rP51NPFz9PNlsA5=%xEwxC6bS`Z~4M^9fKHN!V0pK$-`gJ;%=o zK1%~pP-ZdMxNX|dKQ$}6$@AC`3#>XO(}&{-iYGMbz2IsCwJqxOy&!xGP=OVwBUWl?^8nn z>@H7kZM>J_l@6CIS1t&1CTVB*9PZrjMP%EX-+qKTPna;64RIHx*Z<^L=L1t6zdHgp zf#NaDWCMJsM@{~DIcRNk{R~ivhlnjFR97c394r7Q=J?(q;lp_Dc9nn-1cAhuTNn}? zpB3=cC3P_Lh>K1y9X@5LWd|vfiY_$S`xT8h2fi6U>%_xZXPxa-Y3&}XuJmiqr98y9 zc<_nL3#cqS*?VQF62}~clh4-f_7l5d<1Kptx|2T^qPa|U&5XIB(L<&H%<@0IzY8 z2g@+MUf_Jqa~(UJYhBmd$DH@>l2t7Hff$LuslWrB%>Qc%okX|r?k5|ASxFKIT0CxM zJ{HD&fG3@dLv3s7CepQy{=ibp$9I7J$T58}DCcqnfy7adl7jSqc%^Ap_h`h0`CqXy zI66-m)#R`dIsTO>+>Fucv*y@*MAK&W>hEHFWD0p@>p`$`2oM(^h>?IAB7q&K8v#}eeh8z zWNXWzh?FG_59M6j6o>aRV50Tt9(*|mpsMY9sFR+ke;}j)kZU{&NTSge<}{;kb6v_Y zOi#0~AKiO3tN5$N#Ng^25S@q}b+AJ#$S#D6^q)Uh#|xR}j_3@X@!wmO^{XuSM3)jm zt?)#n)XXxBc%^!pb&(JcC*Q|5^7DD$ae_FA*myl>50S!%g-ZiP>xL&H3LrtV0b)n4m6FMEDsk$TgZV3}ev9d$D35SMl09e$dI*@jf~Vjb5dt;B z`Ib2$1r0h6@1r|GvfhbP1qAj?zNKi7BXJUWOH^H0`f;&qmLYGDg!i36BjYVqf`w*tw;owj>8LBi5kQAZmLS; zMY3tm=(#<-2Pi{Z3A)d1&d6x_vYWOqfnDnuj?!j4U*=rGJ_hogT27~fMEy^Y;*b2D zGv2z0KR`f1mm0xeQbEPd|5I<{u^9(hx04tkz#^lDH>oMmgZCk>trKvHQhoKf_2a32 z4U6Y~W!i4qEQ((&69p9hzzRdoxF&y(%wV|n1}cYnoUg1Y{R{?;&TC|FP5LX`k%s|R zQQo%#hI<9PAuim!H0V`fRL~7+X6Sn0Z`>jIn3r4NB6Z%?Mx`o52mG8vUeFyq-SqNP zf|;)!|8>sDhkzVw$yijT^LvnekEME?$gvN>!P>UgC(KWUi?FOA=ptAq_Z%6?n+ z477@wkV`5rI;(adbu#Oa&5UDzl-c-R#b*jvB6v$mOrM&NhAwUePpLxsYK@vYV@VK( z8ZcOHsUFt80hegLsvCCA!u%PA;Eor;5Z?f>2OEPRzQR;kC7=(5WH2q-%a=@yd*7VA zRL0QPRQC3f!dAryTu68qcf3PQm;{^wR!q|!G5q??U^sLu8Z;K)I1V!6X%>hC0!oSJzfHPMP@g)mBX(Y(M4jJU{Z~C-b)oa zl`@$gp=TMEOIL*qNq%sLkssa0`SaT)oDqXPD(8BBATh2D2q#v!bZRt-kuDOx#frPRy!hPS&QnPS&DQrZq?4zd znDGUmT)6?r_|~pOD8UL;u;<+9#gnTsOaol~;e)K3y_P!)eWi}TKZUH%6=r;X|m6?tp`T07BegF8ORCp}z(6b1kD-12Y6_u>&ctB(10waVv^tLY7$Oo6DlS)XnsCK}XZWto0!^ zzn`%t(LNeVazGVzc&u$*#{9gO?@?cwcWDlnYm%$?ma55uafs&A0K{7WzC`3NjRRRv z5T(Ykt=MOXM2F}6cNp1fTihOWQ>6k-cexhoCG$sviUA}q8~;Fh${6V`nkgPGz0 zVQLdy#Fli?Wj~O?EV?-Lab>_QxFQ^?QCa)k=qN6C-W+#nIPwonMe%}&8k-FL^Yqmr zDW*3dcwMm_Nu3S8MOnYX?lhZ)eT zU3D1XFFpiwRhc`s<#?S4F1AiNB;%9@PRtN=sKy@E@VR}4^|q7YQzz+XYQ>j&Z!ZV7 zb^R2jgDi9XeTAz!HvpqI2=gO=AUf#tV(KsI?`F`7OT*&W?jGK}twAd+A5vHN=#cjF(czFR1^mx)` zd}s*f7((y}U7QprgCr7S%T3Hc2gcGu-uoWE->wgKxg7nOEZqCUtUm^J{F(^!HImGc z!ED46N4rK%QH;+R;xiYHLAt{S&0J)oxBqv81u9xtoJ?mLVCoHN*N57;= z-#2r$=~75&I=nwmp;!*arE%LUc|t7N z-h33~QGZC@=>}RYIc(jPE9e7x-NzA@w+wE%KH$YvDYEs_PZKKGm}rDCy{{9Ly`+fU^}Ik z*%HUkP`Jlvc(v0>!re9VZ6!rY|FPiz?r^^sW+Zs z0O}=d&g4q8Uq){WMru0U1Q}DT_%TK5L)}w>kP{pUdrY`H51e#_(apgEJOYix!2k$E zjcQT?blW)^u+b%*??TQGiQCpl7i+$nAKIF6W4p!OQv6|B2+jU)0HVKvx$RLVXEU&g z#uN^^Pyw~GJJj1-rGGGD!`)e}dHc+jV|@XeSHGm1!z=}xk}6EUSDTM~=cl?7t@e5$ zghPdMpcDgqWxqN?z`-bQZt&CI)?mLAT>F!(HbJJDszK*Pt`~zC>^7J!aR3^mX@n$F zF%+3i?8i`*Kd_kG=$gj#bkpo}<^o&y3~x;(H<9Kb3&p)m3OcxsecIprh06drMGs`4o>U?xyh{NkaCy^IO01$n7i20zU<(ys;v0U z8pIXMs-w=LauT#llg>#t+spE5D4fG@J!IkIEB+ZAbEiuqX=R5@5XUd@2R7TOgJ)mZ z%=x#^|D!o>rxs)T3fQs(nCY+jpjY3}kD)m{xcCbVoZb2q#Of8eD1Px(B{TEp0`+#d zJ^(5r#xdXaV?4WP0zgLz^wVvTR2*d@G*DeF;EiB|q@R zRsZJMaDCao4-0Oon#s8VQoe5(nV7|l5a0_~l93d7)F>d9UtnGUElHqbT%8OiqGb|a z@#hp!Oqu+*QsBj)rir;3?~X`)f}cW__e0>wa#SWl4cN$BJpI5buuHzeppX^yH=QpE zPawO(>Eq&zZ&+Fe?yD4o306+x5A63We%Th_G5s*~9~e@NlEXAxi9;;%-38=BvQ;;J zqt!9(G87NS0~})A2n=+)`1dEePyl{Y0#+^y{R2g{)dOlI*ZT(f-ew}Cm`;BSmK>BN zzn;W0be#acz_sJouO@-33>yPvBgGlXQw*zz>JMcB9dqvX;IDr4Td--wv*Ju1{=4D3 zS2(;BD1(eZw39W88BE&*@lxS76^m2w7k`PGNqD#YGBZ!X(yTCQ+ zZIptTa>=A_>lHs}pVWOr1TiL?J4I@W5gbz%pijUnZ6jBMQ3IxQnWoox;uDvHZ5)0v z>esaAn90gpTL0Sn!4>F4F4HD+YK5lgn8?gpzsJNDYysOBc^LESP@O)wKf64z&jeH4 z+&0*MK2XE3(9(zT^pm}O;*l5KIM2*rmg~#Y!ObL8{mPP|P$SKPe&&pwt(EZn+5FwG zUGpyNuv=ySaavr+wY?4@>E~bgS4roM-|5}=0Jl;FG9PTGD`nNYrviDCT^b7cZ(YAU zxCtx}MjcPSZ@FepyBn%lF;ab%%%8!3+v!3T2TD-Wu(uo)4FxnmIy~jZRy@(e zW@!2WMxSFcW$Pygsr+y5evCDN>{hd+MHk9xIeX8Tg0Q);&ivk!xPkli8=r@RPEa+h zAVsA(?kD2Viw|O(h~be-%!qJ=CH{urmZs`s0#zBD8S{VCDI|hA1&L5)pt@zj9=tQD zgBTz1(?fOgm?7K;uuux+0OFTI0CB%c#xb7U>td#YyqNl%*lF}By7y0zl8-e$o*!1al5LIQ(vLz^I z&1hE>CW0@B_TKWJwk$dKAS=SSjTg8CB0DMt_x}gOj!%L^I>OZYlpWn1Q3;V+CMJLX zM2o#e^YkX=a1}4bN#i$5gB8E>-pj{bQQrOml~SZyiJJ|ecct1^F@V71g>@Pe_R z|M~Yi0Bc7`qlfuufcwU}P6X;9ZQTsusdZ3S37d8oh}Yj_$a>tuhnUv7!KQs7kM6U>{twv~(JeSQ8=aW;VNAUNXjJP0M=j$W`m;3$c^F8WJW$Cop}4}XC{_x=_Me8mbRKS+NQ zNA&^M?FAGSL#rOu6c4&)04c+kvG^hYAg=cUtF!GF5w4$rYeqn)@XT{q;tC^S6)Z1X zKg|IZiy+^B_z(>o#NC6XAp@>kmpYh$Hh-wwSmdwNGIC{;E&-NE%lHrMb}sXG0eLqb zgD18iwyIQVsfbMt1313_I~_#T$-1O28mkLtHu_`67i>Iy)ie|+|0~{I41skPy2w92 zum(^!;D0HhO4Avs{Jh{gMn-C6Yr#}lU{Me0Fka#p^Flm;V>i&p!e{^`{w#D*7*S8e ztUmX~(S!rA3>+%0d^_eZ6Ru7mU+OeBgIAFgp5~1CJo^K4r2lIGBLAW=lMfW8J`<<& z{DFORBrvgoQZ!N>D_C@ww;)T&qtBkg7!N=@GT$n%eEavb^X;{mOBiynaU&2jV7`Sw zpiByrvHG;u&P=6e|H~~{*rZEd1b1Lb*<>UanSvYGK83OBr+)<(pNd$0Mu2065BFi# zS8@i|8NhIIfPB3w{UrfJs!|#VhH@Id2AFQV=V(hG!V@KXS=)LIinC4%-?7{jgS~G5 zVJW31z!6EB0lR^N5bM_lH#<>Z6Qg_`JDM^=+vCY&Eelxdudz%T$S?f{^a;K|-iINO zI=^-XyNx=9IjceM0Ry(Qa7s%v&`z>?iLfOIvZ zs5Tp_3@xuz`j^2C;9Kl=I^P5C>2T=vq8>!db~3J)rgj$5_mg98@V_%aPu*e%TbzU* z5)KsuIxh_JoAk}}SI|jsUb^E$w0?)O{4}hWH$3h8`Tl9ndBJ9M-Qa3Jct>LBeLv9B zXj`jQ-~GaVa1#HpuaujK{cIvYX%khp~DTFKQulUHVwx4GXYYECnH4W%p+*1g{r(R;a{Rlv7Y8W5 zP6#tCQ>Jnm@nZ08vklrK1NaFb7aq+0l?`}Ekz6&e4=!?RPs8U-gGhh9hQ_kkJ@I1QX{iS{5fdSJIqOOnC?(|pWbsXc^u=tCk$rbMbA5x;aCr)WK zca6BVR7E$^5=(gykSSe}O)H~dEc~abuk2kzcgxN-*sc!>;e7XI=)zh|9uzp7;OIxV zd-A;sJx=awju%>RN!AWb6!p&FMP|g4I20|LioZL3J2%r2Ay;#KpRXCm%I>VIds1@i zz5S#b{d}aFg$|D7z3FMIA#p5`158z*aRCfUKu<|*(N&NUa@NT}b!~xIs%(56?cRP59se;%K z!uS(2hRERR7K%`j1E_zbLaFIN%2kCSEgOny{nABSSA`7pL%GjCdyJBuRTM0{r?Fr5evoJp6$?kCjwo;QQgVS2 zB5zK%KGd)h2#KU-^s77bpD9bDS>tQSwKbYlYm;}=X{O$vL`4l1Qb38g|0QNS>XY+I zb2%AL*9dObzUjEK7}<22e$1|iUt4HqDLdo|mUQgN9y8Vq7<3v;K3+#bCs6fhEiyH; z&=X$vi}^ZdzM^}=(Zz65!uLu|lrjI_;wqO%*WKizB-sRv!|s61p#V9wLwI0@{93nB z@fr*9!K9fdWe#b-8^Xd|qb)vVNvPj3_K;{a`%LUqc(wPK-4#yQJOCE?hcGUT$Dn5E z9v?n-@uNCkIMl4)gHrS>zTr_ugYM%iQ6owc--;_MqfW=K$)Ejp%aC7cnU~4E&!jV053tYFN`v zzj~u!uj~=>V$$%!E{!>nkKHwQT6EY`_vZa*cmYy_66(k~BwZwu$>l`@09Cyn;zriR zNx#PkPkh`R?<%`8ajk)>;Kl+UYcH2jZ*}WVU2u4kUMHVK1WQ_%95p*>y)(hq0zcG9 zB|}A5i3omhl6A<0CmMI{3FnF_T8%?xzxscll8-P3h2O_svd2#&ZyQ**#=_|RZ}36* z8!M1{3K73(L54d6u3cs7`$0Y3Nd$jO(Vg4OJqhLt!B>)+MZ9l2n#(-4vtvuX^OY?D zOb3hxVpzfa1_18p`oul-%e_qXP%|i=nC0k@rmGz=q=!&?!5ei*?z8>c+tVM5vYu2w zuqld=2oI%!HwK~`M^>5%quZNPZp}}ALWoJt7lD54YrKj-3huKyDR3pN`BbD$j^W0> z14r?a8bco`NkgE!WVslrXrVcMHYj+qNVUO5=;zN?xA#M)6$dMiyI(Uuvi#jbt@y}y zbA^wD_wVwkhqRo zA)ULPgWO=hj9lWPoeUADeuOT5fZ!ypM`aj^5G2yMQYR>f|AnNyt}{R1-nf^AkL~(a z-^zNjLfUWeXi(EeAbYni7SIGjB?g!(H&9Y&rO;DkU+k^N12%KVpahdN_x;M=w<0)x z)mgg*!Fa1TZqUEfK*wpK7|+8-l!d9DhDP1dN#jU1eSk0DWbG>X$OoO z(5;ItK{Y2r2gN?nPR?P=6XP^i9_#E4-o4t>T3_7gePm$Xku;!O@nXu0WNndWvwQIJ zvI#fKmN`w2zKeofvZUY}0NW~E_`P`nRL~;z(9t*R=F8p5CM`35#Q5C~W8}QTR+tp? z7f{cUnwZk`#Wf-#x+=8u&Q+q-o;jv$#fv^=3z>IiLGw*}PMoG&!m$~c6nuLl`AQ`MnpVr#gnzAiLB)k5G@1vL<-RD42NJ^cK4*XDgMIm`d!l!+l&2hSXgv2^&h@Hl@Q1z>*XmClC(q&xv`KdyBI+n*LgU1>Z)1>nxSwMHu zL_ho|NAo&zneYHl{F(R=D^ka5M7h|AD(_f8?eSF~4t!poiC}+AE`NKrQ`yZ=%hxhN zGHBV}#OCz_(Jev&os03PY~23$1bjqzs_r$fP?=YtAGxag+Gp!qGHe;ipY7+h4p;EY z$sS~#I?H?mC~Yu99+w#}KrFSR|3ItXi2FNAfo;U*`HIw_YA?;CD#!1QEYI2%HqX5x zyB|xm)B` zy$dxZ^T!KxjgI)yYKa`Mr^D7PTX@tfJo)Czq6Q8_%f_f3-%U%BaUDXh^2;0bI1DvG#-Zp4tS@gvs;Cx0cj`o(XKEH$a# z_jup~I=1{iIg>r$V4}ZRpq>;x%X=`F{VBYDgxO!?3YL|PkqNM7>?lVQp_mZk zx85ZjLYg}7w`9e4qsqea{X7pfpxXP&>Y-Q%``yAKk|Tm&c%N|m!tab!<9i44VXldf zwkw-Etw^m+{E>CynKlUnDjF*C6h1um__ef(TTjz@g9<8SJ@&ZHtZgLs>Zj z;x@aYf6Xcq|7pGC8=qE8^cos5tda^uMpk(ZCsP8*j&b*=-l!7 zk%96+nbi2yLU;3zGf5E&o;k_in_wJwQ2E&>!A40i+X=fd*ZHIIWgM}1Z=ARV8AmeS zp4-+NK=3I#jearuma@;PO!v&SV^*~-%{&xRT&G{A9cJ#nAh1P~klSFc`c|MU=s71e^^Yj)>&x*-gz=+o9;vEh>$9PpO4prft^a~5)oN88b!|bF5~A_m zszR4Tt;i?LMjq`1xsA$a46?P|yq}iT7^mNhY&oyx6IP2{N&;fkgYLlWRLHW;$sUKc zXci&c@IBsA&+fTpWyej1T(quzM(?>Pox5do?ECkNJgpPg^1i||0qHHc(aYe9fmNzE z0&au2W$$!N_hf(321dy0lSE-a=3N_$^xKBk4jgIWPt=q5Z{n8j)%k&UxH7-O0fKiG zKD=TTO>~dutBWBm==#|B+`G%y@{S}iuGe-TJBa1^&1b0wqQZAa3R19dK|-Yo3+ZiA zMF;hd0wCc&rLpnewTV`8i$#%g(-QaZkj0}D!hR>Gp1;YGvC@fM%qy|GoRq&}*Z=IPZ3L$_zRxg(CIjh~_pU4rG_IQ)TiZGj3B0TD*% z)*YJ_YeBSPVGd@ibl12A${)yjACf*vx>WZ`L=55XS8>;Oi0yGl3@6(|ZEYAG{|0{@ z?}>u6gsDD^WWSOu-$J>b)$&-?^(Pj3K0?W8@(j-! zvX~BVjmVQ|5oRZfv&ML8WiPt7>UZ>{D%Y@nPQFX~BxhTMh@>{pZHMP%QCp$!2C!t1 z$k=TxY<0L*suZxFiaV)J5D$5OKT*s($oJK$ zmxFGhc`vUB?sqc1`Ek$L&w;b-q2oYac)%^Ip_@1L*#P9f#7^$8rXX5mPESzJ^aiR* z7<}U6rcM~9$RxkXx02+x8*4M%mlS1)8@vZ2g5=+STgnnQWyRbh1Epv+t3pR+TC3-< z-Zs+?QI#$oN-@Gz4ck|C`VFG77Q1rm)Ndvgb z-`G6x2>$LT``;f~Xd2+CST3xB(uI0M^dYZo?;~1x{_M$|u5T-1IoI?3=h<*u8O-Me zTOeSJR9?LP1+2~sXw^+Yv9d9<0uwr~b1$)PaGe4QJ7qETY1q{x=w873qc(@#W?w>2 z4(?FfdHsRyZ(TxwtgSxqbziysXo-ewHu;^|63_1lNr_l6fJ^G0#x?Z-!)yg%{wcTn{x0`>)?FM$dL_(g;U9oD_UNzeRHqaElIUE(s zXFy3^rw#tH@+yMKmjMzECEz>4F~ca}JX>g-Ww;OE+z-ZPu3P$@)|m{ zk7dz(it>sd!~uGZOm4ehP9Yvt6uIv8n&mW<*)n0VexdVG%2Z$E?QfXsn~g>H2mi{i z94rC(l~iX_P@p1p3N6I!(aCM~6J+)x#OjWO+C!$K_E1YweZl*p17BXD>iu4w>htsc z@r7G>vHN(!zI}%uSQAqv7$Bh#X^ikA#KHMO{rt$nMv#R+3IC|>7}$g_g&|cV6LU_D z!3P=!PV{_db=orYxgzVt7B&c5IcX=ihf#o^vV)U@kx`-7@sy)vToc2$!~R8LhqU9u zh1y5!xS@O(=@+#XtbKMXkPd%SI-!z47sC-zi(RkB%qX+nbK7SoPih8_G=KNgdl;$#I)qbBr75cQth^x1GsVCd{0*gh1PfoaJP9qd|U zoea~OBs@fGGTW&^+i59Y9$p_H3eL$Pc6%czy1J@(->wFyBj4)$M_XEO6L9D-E*xP@Eo#zre<6|bR@wJd4jFA5l#+5 zEdt`~zeZHpK_-6u5NpGPAVn;Zl*uRFkUU#;S+i8ZoogaQA%JB>nD>0E|IN1Ily)#Y z>_><_kTcK=_kP?nd1%bDQmokGs!EEoleupjua6+=S&Q`tn;KUMQkgOd4{6;%iGrjJ zn=`aK^h#mXtDop6N<^niMSw`&==uZT7>y0SDEiYQ;BW+9`JI?Gu zP5?g5BQE)2iNpq`^;GQoy} zs;)l+Xa#v6kE*Cg37QL;byq)#8CkgTzu0^8a46ruZ+wJoA%qYkOGFY`$~KjsG-3tN2f;=p zjt$4r{7^e=o-|2V z3@?N(1SNPbEopyd2;nf^j$_^XhCyW{$@OHO&_pWTwDYO35D!o;GzX``g_*1cNP(MK z0!=jECc`WCbyQ|lf;PW!r^}gP#dL4$dhybinmN~WHJ*f-au5KHm*W64(MX!HlU-3= zP!h~{Yhqt%fnm!_Bx*qlsWrd;i<@jZk3u4QxB0>NyeNO4BXXR`pa!lnB=sTJVj%r2 z;IGR^nnT$tJQQRun_Z8AhG$>g9mtt!v*Zy3jgqq?6h{4 zpetzk1152Rib(Ya|Nr%T{ry42EucyC0qi^WI}EFmNrqx6^as!}4Bqe-6wPNS+z$$0 zyw>!-@2+lnW#74=?;)quKErt6Cg1}L#Fcn#B!1&E1+zvdv?BxFR`8&oGB#A1sR(y$ zyvEc#`VbY-28hVV<{u@$bPCq`dN$iiE&Uri49E9N=a!O2*Yk%fZ1i*B9bR*W!dt)# z2PP=S@gm+=@prfzE%%4lrODP`#!6|o?%pL^PiO@zpP#uq2mf*#s%8na0?xUUtTvfr zRI4WZQw$eMl|(!MC5z1Phd6wyPKL|1&Sr6|y|rvp6t+CD*eLptTaKOW8*TzILIC$v zj$Z_OhvPHV>Y0I1ffsr=#FY=BiH=o+zDs<;8k1#TLec~rN@RkoKA-f}sDd5a=Y}Q_ z%c>W_w&c9dOghRs=q(9flbk0M*Dhl(lsOqM(@P=r#@~>O zU3xrwi(sA2972tvj4hz9iJ@Lh1fH`}e zRZe3gjl}y|ia{CEZE?W`LD8pf)u(u8>WP0&a_I{8k=MVgLHTw=kV~`+Y?wwk4DXJ6 ziY?P^u^N*nBN~xh&igEbIlEMyk{3wi1>3P+3crX_+JOt-%lP-Y<8mUQFSVjl}?#oilP192n08iWK0vBwygg`g2(NJTxaOItyu>$g*Wsa*!SwT z%T0%U%jFR{c=HT9morQd_;<}6AQ}*yMfVYf>U=&zQ5Ue};i&g<2!WtSHir!>pMIvh zzLPN_D7+?Z@pum9PQYIAuo8>5@}MLtrWxq?BtrT*)4fsXJ#!oN@E^XFOko}^C*d}J zO~Z>FYRd=tlFz*Um3%EfVs$snT7#+f_e5_*z&(%4H&*IW}bf`kAa<9 zacz`%@&taQg8X?#$%iCUe~p2T2G<4ss9RXb3A}OyKjVBw)v7l9X}v=HlHxd4)oO6p zxaHPF9Q-c--%JtIl)^F`-$QnGH_JDmqRXZ=fuSo|AGb2jzgG>ktd|TqQ?J_ zANJCmb^F06ViyKLO&fg=u-b@xXaSTNRWK42oQ+cNJ5urWWF_C74vtUb?fc42RVYb& z@^p=crFwMPpCF&$sb`QQ>eE~l;7B;TAttrAJ&Uv7z>;LeJI7K?J>R#Keu?vilXula zs;J6zz1htN5=xPVmY7STjCo9BCD2hV316hU?sw4h_d0RmW z8(*kV)5{SL;&;;!^vI{`Qv53>8vO$=jnb!U zp!U!LTdc%fm~qW$zWx&J&@-;O!Pf8Y7YI&0Y_M_t`2FpDZ)gfY#eEhM!|`B9fuA)b z*&DVCU>!E%&Rva@yxulH0q=>)>R{@phJQ|2jo%n|Qfz zz19r3s4nZ%=i<~EX7q z7n~Cp(l9UnU7xAuXg_kl%yeJ!w~u;S*9gCS8B)Nd?q)JXnV$f&d`*4}2H3ZZ7Rk+4 z{S3M#@0yDRN4<1;b+DRP$h}S<6VrpyWGTNo-7$ayMuaUhcFe3jZK(U1>w`zT z%X8*+uZ7M=QA(Ta1>Mtl)+7vze)R$Zq-V@`AMvCSM1(H9>}YsCge6Bs2GA*7&eh5L zk1jo^)d;~DB##4140FWt9WxU<=ETy&1G`}|z_#sf1;*th-g6l`l-PnzG~$8s@|aQ6 zA3>GWQ&(<7g0k-Yr>kgkEZfXQ*ur0Ik?KGk<74qk(JcX4 zTL>-Rz8_`jJw3_ct&^JM^{`4@5;YefT6@aqdvvl1`SR#B`~8tp9I?#Ye?lmg02VKj zMZ{DjHWLAZ$URKEpcJ^0w_uwfmzUAep$7{%zTQF|tn_NDh(nv>EmPIm8dcKaj#DRa zqoB%jWupW1h5%Af1WG56>>4MJlTusr2F|9}zq(iC7Z`Fw!KJOATIzMp!617sx`*=g z9h-d!X3>wXh;Bwy`ch13@*7Vet9(e1jEt}3+bE}r{`u^4aky#abd7mVWrjwp0@RTv zB3QYhtGUET|G{9-VJHD}@vWkpizJiin=|)NMmat}O|Mh2y0kogEp+T#%)SWwrpf`I zhFupvJl+)x15Ph264O?MAT1`cGb|HXiuK}94B&C6e9x4(a50Bl3}z;tIUDxthTxgb zP=0SrBcWb<5Kv4)D!_ChMzPJ+{0d_z+mvU8-@-2qm&_#ohA%ob-`O(ci2vdK6^xPG zWTpb0twTU}L5Oj!tQw55Q4^~Dri)F^!ZoVD#`Q$J2Et2(C44(7> zNkw|GP6W}=lcA(ZVJqQzVI4=^&$0c|N4xK1qJ16grgnt@Li<*d6{i=TA0?O*6lhxQ zWGR2DG~BZE$s=P9jgNkBw^g1%ww3$-VX8so#1#hB+CpGgf&N$~ns@5~PV~cpHxyxA%XTBM$+^G`&M~w&*ii}w*Xf4PIElY_^GN{z zX`Ecz727QG45h~3q06_xq`y|PD=lFq_t0!~1V=K)96|b(2+4O701RUK_Y;%@$;JP4 zAM0q)nd!B!@>WBYCn_Mu6^@^X5pwbwSdD`?%J|^LEn}fqxBiaDKaa3Rkkq6g-h~YS zsd`!nrt6JD;mth7U7iQV$6h~OD!hxn(XHTAazO0$lhyj(m+WhR+IbQR37{#Fs)3G% zt><&|_e5{KtCB917R-?poB_`VFOp2_ej>a?breII0YIz6KDbs4B#UU$XCC@>Vj1ss zJa^K?scmGXm=vLo6Jd=`=2cukjL93}t-$l!V{SP00%7#KZFwa9IHW!Z>;zcwIlajO zp45b8v&u+^S6nW=d+dbR2%Ghlj7i2Gn#VK1NyO4-rr_N(zPN|-HEj>p%k;-;cvMH( z47RrZZ2uv5V6&-t5eD1o{7zv){x%Bu`oFxzm z`G_|IZLp};-ts2u_(IovZ*F@(dCUCqwEZE$MSw^fgS27%25UvZm!oRn?YMBfSn-Ti z85DQ!3$=CHjA|QV9^Z0@@*~wEA133+1Av*$fAf$2Z@`%dKRoH1?^A+fDn*{w-0pIu z0?F^-sl+Tiy7X*jMa*;+_h$^R0IYuxVl@8m?!fWNM7XQHxpx8MDotzCx~Kau7+fzj zJLwCOR(NIdoI z$=;oYHJ~jTMR484|Dd3*ZEmx$BB+;7QDm|F8y-|#qmvb-P$60FM@M0&r0V|7o7acxI@*!Y#-`|&&-*!oWLu7}m-n7j zal6Y$jTQLmS<0p_4i#%2K=K2yj!69TFi_!@CP5L1s@N(JtYE73M7&6`=Fe* zP1eCUORQ~W8l`xwzio)UV_&?;aVZm&e3jVQ9)VL^@<3G#_{uQUExG~fQa$qxnrq<- z#YB8G8`9Cy5GyRSrUDn+csbSa}F`J_xx5A~*vt%+Ul>NwyOx}9~BCi<(ic-}Fx zwCJ|5Lp3dGz9_~>?7HO zD5Dqi!!#~@McPrhXZk0uYHs-m{5p8*HK0(1??f*jk)Paiz>`fg)6lZ>c+p(y?+8>V zP0%@trMO(;;M~1C!%IkPc1*&>Cf#8v;YSN)#7c>M%P;#e0*sHHSY`2ukb##LB|K&+ zGB^lzh!3c%kgtzg?%4SS4X571(XH$t$EnNX^63)Kp86_(JcKx*{H|Vl2xPKE>SbT( zNMb9J6VRii*ALd|lMvkBb?4Iu=2H4b&(5Ch1?j(~jjX_h$EG|Fd;0LX#* z)wC=%#eBL&D=QA~Id64eXrIT|2M;ct;?(^0OJ6_uQ2NHcCYHJu(d6daq`g~G377uV@9)3mZoe*VViSneczNqa!im{ey%Iu;9LI|> z2SH<8iLy?^Y-~bN{$ynAls*CF5UkbasiySiJvQI3Lap)xdH+6jxLjB;;LVVQ4+E_& zr43Ce6nvcxGg^B&(#}hoAJOADlQPdqb^3nSlfE zx&j9&5EhfD3oM>cx=4`Sw9$(hb^iIW%)(Gp*TMd6QOS}*qXB~twPkyK%znt6^)nH; zXukbTXFBPdAwLEdum(sG0aT)pRu0ZNO=jE~a+~2>a5-Tn2})(v{f0d;MTbt`OdqM5 zc;ogx@#Y7fv4t1U1u1Q@G@wSfOsSmqg_NTf<4MFgw2+!u206}>Aa+@2uA=r^M*?{W zlJK0hbs1qBR26*nL}n96lEla;ov zOX1c|Y+65aeYFH=#}{qfN=Nuf9^4yZI?KteTrz_0eZAgo8F-$crUWAujo9JqvsH`(AT@ z&6bG7JEiOf4{&XmF)&}vQ#-R9hos(bZx$TmGOniv^fvhzR%BkeIy~O;Py>MZzdk#f zc;|;!c3{$X^NMyUrDehqohrl|F!UmdxC(t!tM zOEEi3;290szA`0V16>KymUeBo zt0H{-mAt-G(Rf?UcJ!9+uCvK@is>3MBleLU)|j-h(8}*AfkNGT68DvUy7}P7$EOcu z6CxiY@ad{sMqrgeySEiCyi?S8HYG##ZRr)goplU?e{?Ob$`dG-pPCHvx~Y#Qc&UoW zWormf8Q(hLx1;onwrdC0xwXByj~2Vfl7|5gp~Q`A9V*8<%aR&7_MVpZ+;v+SCj>4Z z%bLiN0zdDg+tJ6NFXZT(brsa^0=f)VYTpZ+uSriI4u5FSA!^!MBRS-jZg5{#X8#Eu z^(3$lziGxSUTr!@kbg6h=YbPOI4GytNVAe~b3kUBPq(H@EcIcJTXLXT_2JJZ2VdW^ zDNTlHpl*Wi^7F)0_yT$ICVaVREGX|37#$3c?~QBJgrfbBU9qL%NBpSK!5`xn zK1cq<8nlPX7q{%S_!8G%qZxSYCg*E-rzGeYi-0F(-%0XBSUehZ*$K~@Dx4cx5FRwY zWa!qCT6NU5^N{_iHWHfgBBdA zjA8XOU~CNE52*imQ*mXiRKqNONmGFL)wTT?7cj86lYF70{`L~F74R5Gl+Lzq^fmun zDBnCfv&OYh_~0uMKj0!Bq-dJ!D_CEgy#ot9w=?~OOa!kDVEs?OWE)u+;G`va8D4oviyMlJv*sjTFB|g!NjBhj|A5`q@_vNVD>MSm1Y3n1-yh+nHzKRh+@a!%KT(AGo-kf}R8hAF<4vuW@Pp zmC5

  2. Rx0Y{Pz*A(ES-@DWJg0=oUtI7|@s zu@~H=FXQIngE&QF>x!I)v38F`(%~(sXw6>x+o#LF6^c>k&44#hAuXEHgKnE_V~#>q7rk zh^ccE8Jg=ybq#V~IzN#jA=E~NsD1C;eK)oW91nz2liy|^6`yoofywTOusoCmKnfA6 z?o|?;8sVI^##1@YGaAm>on~xFQfx{sFMAAu1kSy)^#3fS0%ft+!|I{-wPk2!fZn7I zv<>qN(u99%t6j3`WUL!aZe+0j+OYAt)p1={hSKb>;yxVbv@aMk&+fCZx`aTh&J9JA zxuF-Eucbh><2L#OFK@5SW?RXpOTrGerlj#-Qmepre8_@#=0BKDCNj39KD-z?8oP=- zLCk@cST+=pT3D!o0@R|H!v{QZ*OG!<+GmSbT;(v_NMdRP4Tj8vzH?dA00LZuP34ZNp+Yw0gH_dn5rrLk>984 z>Zlb;T%>*_Z}rfi`41FjA1Y~-W|$ZZ*Z^k7`(rH|G_wm zD;jPJuc_c<`4ggx*?~f%k>0bRVoPU>P4S`m+&sjBO&dll?~MR85{Zu)_vcs=AGQ=p znm@XbtZ%d|i>pc~?-6(Ro!g149kr1Ajg-KA3H3gQl1EMB@y&9*JY9$z2$tv~xiT6N z?SumlFe1;1(n4wtg#6vP>KZT4sO|WfL93C@%v%9;G((c#?xjQY4x98^IoTK5!<(toJUlT98CW7$S1 z0n{=PZ~+hg5BZc$?rZ16Y$ts68{xY=_sES)*DvhlY?(A8w_rrw56O<*o3EQ4hhdEC znAE2UB(;XcDy?_D_W27614U?Lc(YXI019V|D04;Y^WE_FDDZ|w(}sEQm>GSXKRhI9nE$ugAe z2JqG&1rVT+R1!=d0@(tnp@h4@<=iJcBF!vwKvtb)Sr|3aW z!R7mPkiCqb`4VA)>9uz{I@I`DF`dxd0{R9l%U@-8jaHQ+i58SnoNQAx_&ejWX zM;*E>4{!*B7wm=gIXQ9>cj=TKX^z(E-tDu^K|b)-Ere&^UZdt&HqnD*tQF@iG?DmS zXVk^i>XN(210%jbal{J-N?CQ}8{moVH3yWi_T9>DkM;H&v&+gjFrv#?iOjw%kRZdL zf-7mBFoY;`@+qQ*dy^LI3?4# z?={E8w>{}hi*bBQP<PBL>(((B3|kLhZnkfX2l%q5yR7KpK;jg|zq zYt>kmD62wP9v*?4@HhQ~M!NiI=~sP6`A#YtO^WRwTBF|U1{^}#()7}3r`s9zj*CbM z305`?4kzA$7)rjY#_pVkj<5{-5zo)dpO`0ayoD&#BKs&o;KQ9@X=!t8Vz#=X?5u}H z#cLM4b7Uo0Io(}S_BQ2T+k>b+C3bc_dsf2F{9KFIY7E{ShW}u8H058QD-2Jhslsmg zFHh?5rQZ=#>s(wqYrRVyO{E`^b9%BjE$zqFn9Qdyn6m72C)z3zR=Bj|y(yNGP;w}O zxTOa$_E^K@TH3z7pt$5VL{)FU6AhRbH_OXL_7x0+qIOo$|aYUR2!`_j;MQjE{3WfVMQ^(dOuaGuw#nNX~H$cE5OlE9}*)D zU-i71?7{)G;N#l5+Fr7?!e_p#K`QGZG$SfNInyWGnf5F1thei4G?YJ|H5}*YM6vZI zF`n=BobFT}JJc`A@!Ha~vqW_$4nt<;_(II1qM>)Y#urWmVGEQeXRoUnwZ77PVj!Uj z;l^agy$Dj!O3@8t_PJEEo!gdS?ii*%2oLm*^wf+%zt&;YL;=y8vD*bH7^S#v%jL9V zwca(y%Qfi5gWQt7UTr#8pN6s9#(c9JBlFgy21IZuuJbB=U%jEWT2<$8DN4-fuQrG< zLn-YKJlLa6b%9xRjV4<3rc<0R>?*y7H|Ry)O<%FG>kqEw!z{Y@-%_{>Y_wIqE0n z_#v|~Dg94{ zCUURC2*E+$O42}XeFI9|Yqi3zm-<*Dgk(WW9ML)RKICg%*=yJ7moGz05Y3_GU+8`1 zHAK`^Nwr8iT=B=DhJ^ArNP`pipOaHC+wI{3WMCLAokI@w8venQ2B+jI7AI5Ku zZ{vCQx*PiwW>1-!A~5{oI0J>YemfGw^_Fo5Hsww&ECjgu8=-2NpXL`v#1L;+D;Ode zJ9Jzm?_Ee`6Kx5^MQwYI6N9&qg-{2<69%YB4zoi|yH*nNig7>UC?-)E!aOGZ-&GeD>awZH9AXLy38eQl79 zy^(weFK)smqB%i@&wg{Ss=_X&LC|PVZ=iTIo`URhb?zmWGbyQ}VeJNL%D&dm~R1{W*AAwPmRIPh} z_DFdg<^`D+2TCwei&C9f9ib7S*YaS}c+zHC2-yXGQOKg}ZD{PZaIKhA`bKtI zUS{Pv^=d07-^#JgP@FMIYn}e%?|jRxe-&GLT{WQM9NIKDd#}}cG1?$EBdLiZGB!Z` zS8tm#0`Fe+M|nIE&bi|Ub?%U~OQcm>=6U1qF<}jAp!yVC_^7Wn`+JoRLZQGD{?z=Zd-@6cHtCM*CsqE6reyX;vwsn;uNx_}pNTr!=d+(78># zvqj5~6D%n&465AUPQ);Gc}@s+ZQZn|mp=;}lRO&(^(w+uxspT7owrJZ$MnzxVMEb> zi>27JiGOsR2cOOgYcxcb_gn9oDb0019g`4j&A{b;V<~f^*^F@cY#w%EbKN=VFh*bg zHQ$*@?a&^87IlYpv3*$R&BcV7J>#~TC9>qt$mHXL`>Z=honZfF+;k`Gv+T~zY~CSl zs6FF&S+ie-4`B~*UtZeBAE}M5k`o$sikzwYnLnTyjxvxZO&dz>GdBz6rGXvzLnM?( zWTUlTon3SD9>wTBF*90iiR5eep7FsJ!*oi>!o?g|XYOe~*^EY4Q^A7KbItrIvE3e+J!;t(a`;N3Ke>W%k{s@Vf+|6T}llV9FpIp&@MT%jKuk{l3(kfT( zFIkBa2t&RXO{?#zAebTG_RY0hZ)h$)*%#raWpU;EcLgNQ|1F}bj$onGh-- zw;7%7{e#heED0N1c_h8t2oJ4ik3vu*+LsR`6Nj)xf1;CBUWKrQ7{U5})_N?7KwW3c zG{ifI*VmDqY3P;Wk>N)AVS&QClUi&(oclcV`(3{3&I22R5#U{4wZ|@cE>7~j4ep!V zQkQ?R%rgI5`E&2Id zj1i5KF%ibh2{0bM@JjGMn5<=S z4dIZC?wTHVINbHGF=RBglKEFmW3@FkawD9611ilY6k4upo9rS~CiSE1?RJL-VHe;4PzOuTvX%7;}Ak zj(ci+o1K zK!ju)TXvuNZ6)z-J=RF!nMyJg89FY{DT{Ee1P_A5iZFTAH4L*9`Z5v`+Eqh4+LyFd z4>7ep&MuSKtP7CqP@z?9h8~e<>}0ifvsSuvLO-s~w-lEyy+9L(>=rSeYZ3qxFf|RW zA9fiq3&`2R9AN-OF**ueT@-8sVqcxl;WA+AVagki+>Q^!i}AqwKNK83g-wo*j_E(Z zGFs9BSl0Y0+?magXkQTcn&qG! zk<_QDShF|vREqT#yH7)pSY3nc3FQaNS1G+kIs2_=2_Ua+5)fWVpjEBakwl@TR!Cw@ z&6Q~qPSBn0my14K#rAm3j3w;Pg+Za9UQ>)wOlji?jJ)K` zA^3d!xJKLC%Q=FRuPYJ05|8EKvH>!h*vbS=c4!S}o?zU=<}MQdT6WVxu!tg*%jI>! zBhX`uobecc0XsRtfD;^i%&sGeqkpQlLk_A+YAu%ET7V@sA{C@Mm4og&w(>|~GBR;} z!LG2fKeV@nE;ha@T2Z8gSV`sld0qNq8gMok&^b#a45g0)foNNG(i-Z<81x-a7C6t9 zN2l<)iASK1B;@paJqwALOHz}p(fn}AL!8{Rd~e;*fZz@jFyj+ z+Ym|;7|eMoe)pLbl>p`^yqxOD}L8&FE8_ z8qcQ7B1vQlL_yZ^(?#~4X)zQJ*?r@Bgp{kAhqVD_r&+<~T;nSwQYy8WO!Z+zh~U+Q zY$j{ZtluPjVs?;|uN5U{tu6Gx0>MSNEMFMphtp3l#|@A64)npZ-}zUNIn4y}KUfP* za6I*1w0vVU1FKKi%AVECG+11%J-&hDn<^{rf<|$Ay$gE>G;Mhg=geAUMd?DM&jwAJ zgQu?GQd!?;quPy^Olg;BN}XA3I(f&&%OibFOBM-ti@m-cp|+VDQ)-#vp$UyKV|)y3 zlAmz1w{q@FD`<)XOM`Vbb$BA`m%#1H4zpWl^X+fo`@R|Sqc1USeC27cyJvsiG=jVZ zk;dA)jI)E*=>$u4azd4`Y&lfjkRH2nPzN1$?={~nLpx2GMPNTq^>K1&cARXFSG z<(?*&orOgf`9k)gs7h{e?L;~ng|!?ElpvoHPp|V*LXR5&`c&m~VG@ z;|p+2>U(JA7q>4R>*qX4?LHT-ZPC^(JIZeP>H;jBx@mvLC!mM5pr~)h0>kvm^j~9Z zLygmu)gu?XZuvy zlOE_u+_+RR8P@D2oLh9(3X%1uMraU(_cckz*Cl7%z$bqD15EmyNmE5=s-|^7Fwhjx zhKGqJqo0u6(V3KGs>>84le%!4)+OMZSNa|>S7^RMN*_Vt%OM;n-4F|#o>OgvN6g%x zlfs+1@W$n>oPtDjL?p~6?9oiplsK$_g?$tu@VWME3Ig+0O%z@3 z=x_VfaiIJiXqVpwwK?=BStKxlw~x{JQRq{E*@(i{dB!g1JGpKmBi{8fux7~cz`5bf znu{!TapTu&o84cXn7>qeCe19pRj;hiv+8m)QhX)VQ5X@yl9(-m{q=uhKGbVS-bREST9Q^AnUAF$eukqaW$r5;%5rp;_P zJ*T0#-V)%=g6^-XZ_hhn-w+CY5Vf05*;7!QKm&B_<0u->KnGQua?7w<-5m%iC&ErY zhnSnzhnx9|EC-z-7BROx*PpBOEP{+i3$;!A+5y{QMwWu&M)F_}D2}AvsE0B&ad_P} zk!kHZy=&Fg&*9GL6s;(1J8~$O%#PG3r&=5<=c)pWZ%zB%YIHnf1&v#HiS!%lS}YUR* zNklZmOk@2{M4cn+zyP6Dc9fB)7*_1vyleX)uOcL}KXH%dYx{TtT%l?>`G!$b4wOU-r&r3B>1ef1bM{Mw_v zo6)RFCqr`b2G!`zM|Cl6CoxRDbdkNr*nGn$c)Z6aaV@m3uN5&ZiMU_WJoRuRGx)Vf z3&S-zQ1=xva%<*o%=jc?eShghC0h-LN$8J!GYJK$!T948(k86`RpQEk?e5qGe{?5ud=;}YG! z)lsHZ8JLhGFjg9+jq)q+LS?S>ernNO+Guen$WiCp#u6+9$I6AxEY##)B+K9v5|;J6 z2{LeiOedVu7^qaj|5{XyMN^0HNsXMeWfw_dsfaJieXr$#ER7b#T@J#np2+R}5;yE$ zMA3({+IVD;ys8a0Sy#x5I*lB;3ycIO(5KsJ3D}j8ksrby(x$bcNMN$b!;one$w1$* z>xpoOPir6d^1kA&6Ad<84Xu0~tZ&^s0_!o^>uic@X2^HnN7V`p?iuo{sHtsR;Edy2 zvr925GJm)dtkoW$Tl{m0W}CjL(?Pwm(>0)Y)Eob_&4PMp)aax}w`?NS(#WBzNmM{p z+d6)*Z&fn5NBxlG)Acr;~#a^@VnoH}KtKPj6k!<`q(`q2w9$w3el7Yh#NoVb_QA zu1E95ij~X_7X{EkRkKJbtO@PK&%@8Zi+HN&WTZOQgcKHm>QeAGt{oN~1f%t~7L{BJ zQ_je51}$=t5^;8>h=aztu^|`3w5w5wpilEw_mw_ju zR-*~CF%OC)@u2SCYhGwwwuI{4%PBTDIGTAyeGY$R<0F&bfzg~ONp_|bXU+N&*jbi5 zP+pR$eY^rMM?Ti`gu-QJ4M?y_;iz^;gH|J4u*L#gtJDWR)xZ1UsSsrN$2jegegOM!7H6xIuM(hD#?ncn(%)lci^zYu7E} zW)@uZ{2s62HTbNr7HV9P-BM|8&kTqH{pNhvS`iPl24($D!5f~ge0FZF{7Kq!|EAMr z(CYU;FjS(12?-C8>Pczh~>&?BR2MXO-TI=>4c0bau4r&!d~7 z@Um(}q3~CkXV<2VWN_3zsi1c(SV#YGc~j67#Kx z62W=k}a zl^1{|E(TzH|MBdU!VGiU9Tf6?e)|!JFvJ8c@yB~Oy@#TS1JA6^Q+u3G?}LMFCc)zO z=EhwlvGLAO*YKhbBbqMXx*R3~kzJRWQ)_Z$`B9Hq3AsG(sfF~k!>FA(QE4NJWTfBK z>J{@81)Cw%eIu~I{Mfny<|)TYAwXYgIqlIgWwy{_MW~ntR^mK|>L}54qc$7~mEVqH zo=D^GMg4q)ac%u&Iii#g70F0pCT2?Ov!m^PXW4iMQPUmMtSyD{jT18;wsqtHJ7@6% zMvu1xM^BBVBvvk}FCe&H*?Zv;lt)Hu#y(XW|ceMEf;{tSvWV;re@LVBs7{Kz_O}8%eB=<*1eJV;j4W<^7YAEjO`%~&*15s9n{2#8) zI;xF!Yx|)s{abPqOBo z$;^FcWhQ&=eeK`%v?O{wbP0_PTY7H%H;G0M;^RG1#-Dikiyce+bA~$-^%lRAT=Njg zbb+1n#m~Cr2#(!%!&P?M`z;Y|=bH+mIY%6tD>8?cOhH|EpENjGv0&iU`4Kq8%9Td$ z+^5|J?lrBgsT}MZ5xKMNtIo7Om zMQ{luIOw~89eno-@F6+gaad9$bJXUSZ1F=)JoWKMT@VYFoLSdSzIJ@lvdxVi~W9Nq}KC0k}mFt?z()_pOHZ zK-7}?nc9I+(pEDc$P=&(rOL(t0vwY3mUfQzHU?u$i$1KkYDSz)>PLS0#1 zL3)#D@AW=cC;JmhyGe>6hCeA+vE#aG#P}bY1gZ{8>d}pt3xK_8$8GC&w~fh&tIreX zDj^`wIa`vihvif#10=dLyL>gDD^p!IH&Nls8}6=wG^ft7-GurDHx#EZ78~rO_6cDbOE%j1$LDbL}I))%AMB!vDN}0`qRZrj7RvdMx zidaKsY!Lx{_I_gr%yJf0k>n)gMCR|mDBXbeMz;Ojno%bIAVjv?WP{{xD^V72z zm_@NiriKz|{8^nsbrn>SBAk~s)UEPc!0E-yD2CqDy#+X}NT6~|`1T&dj?8JG6 z`gry@JDkJPiKdOKQq5-AM>GboMZ7RK0_CiU}UHnHQpQw15*MBliZOIDj8_jSVU7MHVLkUrYOln#!b_f(A_hpGs4 zTX#5zu@8xY6VzhZaGmQJ`k2yRLi6L|^Fq@Sv%<5?<~1ly7!G_1#^lC6o^_g25r3YN z&Ji_xs2WnoO%X`d=7Nc#{P2Mb-1dZ5Yj2GPcZT*DFfgkFKjFhO+9qA1H<^y_I+k8BM{ujF@IS zGxd^h=*s#Hlecd`n+(8j$^06$k98^0#lA}7)g2_PCOtanrdu|cSR z!De6l4uO=GrPMB42f;>bg%4B3v>DF=p$M3N0Of{;INL}zYk5J#RuJG;cWFw3i(NyT zj#HSsSNMZfEFq_8mTPKCO*J^T=w%gvGeR8W-Bd=w#8wzCV9K1 zub*#JQ_3DJoc$Wc8+$lF)*=mC(irLn&5_>$b)6DsYonwPuV#g z=^K!cCF!&1B|IvUM$p>UyGJ>Q{GumOd!AQ+6NB38caZ-$5Eg|gy&9Hy#6HxBa(IK~ zmmh8`NIYY#8d=k^+Fek`><&h*i=B-6)Bd=&!{3lQ3+M=6--kvF<}%^i;7H3HD-DM@0ms^juz+{k?#aSZCW=DGaO+$*kHb^O!x4RT#4ISjOp* zMC=ky_$rn^u-2eNF@1g)x$7RBz~=O z4#BZyO%n-yZVQ=$!`N^~CS&YLAf78P)8@1ME%#XG<^q}3j9_Fd$5P!t0OF&c0Lm;2 z0^%}8Q3Vl2joB=q^oH?M>*3Ml+Tk@9&Inc6DeX?uFohUuQRR{%DYcF6j@<1|rB-?L z0~X?%v+Q7xWYiOeW4mGwF{D*G_^MjQ{igj6KG~)gCT;J;YL^i2AQLz)cC)^osa^9T zEtEblv1D}!!rFXzkbb_0SJs3}tDk)(0}J3@=W(@)1URxu=}Bs2 zD-cZw{kYQ*fR|s5g-=^_E?MYPs{X2Xn}25MI=y+1=<(}u!c!OiJO9?$A{LSyv>A+q z*{K57wW2<@oJ1I*e<_V8D!;A`xY)XfwsYZ+IiykygYRTmU3FB<^pnP@XMnK<$M7Ux zn+Z>Oo&PH(J-Hb$@mfyq1ZGcNZ(z`m?cKfD19$Up4tF+-D%rHD{WJ;b!H|?0@EL_{p=X)>o<$J_t4Z!$&uCx0*#Yo zdkVKTAPw?Qf13RxgU@q4Yt~8?a~52w@?DltHUuBq1|uMA5e^sLAbW?6B7)M%FnJs` zEjVioBcpY-E8~WgKcVfg=$bCkno85EN%s2m2{Wofc+dzvSc^gv7ge0Kc|BrQc-oGA z(!y)lwKL9w$e~=I9#mYO!Wj8OZh!>6O^{b8*3=83g}tLCuAagAC-Vc32S=vYp$A*W zXB07y_yA`|Bco65yZZvr@KiAfj_isr&8_vPeQki;Rs)O^?Z^+rao#kWTS7P`6%Xv# zYilh+I@S>jaEkDW);>Hv;<9Y?NnB~zF6-n{RybQye5_u26UW~E$_EkZ85c4seHUUJsfi_Ve8I{tR;C1-LO0zD189Xyc7w)_9jhDY=yo?7zj4Fw@S{mPhZ;zQ}2q>LR9BA2!i9xy+=$NTI82m0iiRjzQO0lK@8U(Y2TwV=n-I&l#0ckh=j|;tVLfei zO^ji0zthPi@o+)l!-9KLeB#n;x*HSOVg=%_u-zrGD7=umlDHtW&N!iZ7>qLnQ?yNe z+apeJQn-v@0Dz>IQXCe2Wg`2Y$;PP%&#JJtjKClKDXCM2z29T&GD~3l6~rHjV6fal zQ-U37k?oD&-^gdKjiIxkSpFO-He0ujVe93)bV^%#r z@dG#k2GBG)Hzv`N^IJO?*;CphwmLiITenlHQkQOJQ&mLwUIk+w!5m|o=W?tk=J480 zE^1LCSa(xPuBSBCf6CRg!V;A@fz+9&a9S{1Sq+Qx(H?A0`6`YNV}~uOb`zA^rv{8* z7);>VJBry+^wkqR2yD%MHW+`)@tbM;Yu>mvIx%WEmpOr+j#9T{)3{1I6__t>^C*%R zJK~~>^PW`Z&M;r4Q9-AqJSh%H80Bq@bS7pRF*N0&7AT-RUR-F%_=xfJQIuEiseACz zo?<-@ww1k0Qx5eawaR^%_1w=(>5XBRpu}}ij)f@agr}%;{UU^!Uw^p~dEH3Ir)c{R z=MW#-NjX8c`nPEVP#ZPQUHhB$jGG~YoN>E=1(__5NRi)Kb%!rLkveAtRccvkII<*& zAg0XF!MIN2fY`QptkwZ8>k|9}~)i&v(|70c4_-`DHhUVID#1Jxqe#(fTVN1=~vx@`fr@yte% z{xYNEk`0ZkGaJh_$&}Z=&-if!DOX*rD^M$Ug5&daY+;UNh9wSwI2R0?>s8fkewAe| z-w1VC*;nFSZWTWB{QBS&rIDT+W{)ZVK1+jTd>Q4O{gGsuYPv<#BJmvd#|b7|r`%u6 zdxTC2jwH(w=cp7V{3#cLD^zO8wVtL`1aJ73a*(FH^_7pZh>&cbQzUT^eP4|eGf7_4 z9hdXo;r>>;L(^ocIM$Pdtll|d5?qPe;9c9#HbLd@3+l7G?&^!jG2`bxPi);G{Nz-I z%uR@gmf5{$G1o)|K%(Q;$F4DbN~aO#2ZB)BSfr2wSx4s_V=4nhg8AbPGRm8V-8sjW zjP2QO@{UOxQn%8tKNcUF!#I9R!LI?=)tWknKRmVTfBw7MJm0awR; zM8PgnrVuoy9fGYO`y04!Oe?YOg_h=K+lOvAM9*k)cG%(JiMhy2FZsQ;u?fFj)5NG> zD#4u1lE-j*0;1zIl+M(c!$Ebcpb(WqH7%yxL9lsrPSmr`JI}5Z zozCdiuC?$5YqP7>f)#y7#lTy6b_79CM2AzL%#wXL+?oS@)z_e=XLPRxyp$Qj1w`O~D&M zleG4@F1NYY^Cu=f_!N-;ITDNI+8n}}i!;sNrdJ*iq&}i%Ml%IJ6W1a`>0vela_zD=`_47a(R5)j^u#(-5YL=#-L_O3$81vb~1WVeIi{MDiXEk98vQ{R_70P zw42H2Oy`9Iaj(V`^h)_X_3LEd{kCtUnHCNuLYe4Fn!iTDO#CoxJt!Pw&HPu+VWC(Y z9pPu77>JeEjzqp4_hj8`f(;~+%;Yo9o{*@-CKN+U*ab(*%Wrt8vLpu@!<;xHvj_3G zlg?XBYe}n`Nd$TB=TgnIcF9a=9utj%qYLB~rLpx^xUUHeEI1KFRRc4+cEU^ebo1>< z-s8?P%_azHe5}y@x7Hhbjt0pC1^@hBtG#9w$_;UzOusSZzjc3k!)?i+Ymzr7zd?5W=u!JebAcjZUEkX8;6jS-X9j*=ls#P56 z?#iqHlfWBmOc_Svmz$>#QN`(iPjug7frViD!hgxYHZQ>}UVuvgGL%5|@6yD#f9C#I z6ZW4JTnkpvV>qTHPK;>a7Y|-AJ*~@CAjeZ15oHK{l<(i!IUEj((4mvNIlOhKEn;cH z7ZJ4X@1M~yUEE&u=I~KEUhJYfUS#*cvCnZ-nPT%5{}+Wsq0H(jl}9 zZ_#rn=O=Iw@AK`b9=3S|HSvw|$v4=whCPzZPrJfwaHFXAu0 zeE+Hc@12Hd<(GefTOubn%d!mbXLC513vK?GJBts{15it!pdvrNe9+2&HjAN~s+x6v ze+rtPE-2Chf7?Z$d(N0@E(g9_aVBoZV~VIiF3$aCc4{KjU+2Jdl`A4&RrOyVlE%OI zaZ5c2p43-fdDH&Q}vN*f{ zg1vfnAsU(ZTEdyRosRi`CjS4gO4=xAVCqlO;&d2yK6vyU#kR}bnN6T6jU-`zc3i`L zhrs}kdn?1e+>tJ3jckjMBMZSl`~F9i=IOgDu`6Y(uufbn#x1;7=74Y0rcq3YJ(sSk z{;|)r`XNJC1*wD{V>^&!pXPM>bGa^`SvaQO*UD0(BfEi`xjM=jKBh6p@VAZr)`bY? z5PQVUMh;9=edLAZ81&Mu9z2IS5I7lAEJy<>4)lou-}?Xm_W#c!He|^i7F~xm7Yg^@ zW&TLpA~BiRvhDu^klT#ieH2e`vI5gO<1YXM5N`e;_bT*qxJGgLEJmnTeWg$Ve5Tgg zBObVuAX5;uV3LM7hm}Z$GU&BW{i<_@Uz3;Vl)pfTx*yEv(5`MlbPtZPK+LoRMC?*) zUm(HPX#ciQnX(sD?V#5V8mYqm#0Aj`2R z{2VP8V{}d+h3ZCmAFvU8zma$Los_57cWXgc|DIpa?yL@PY}%m9?u5zsqSb3|oVO|p zItY&pRw%Qig|>6zNP$04o7kVhR*+ZTLw^whiZ?1zoz81krd~*fP-nXaPWYhIMx|OK zQ!kb^8y*i&6$a{DTU~BpLvQ4&3M2&yf?@GVqcfME zaiC<6`&^dF0N;u{qJ5wW9vkHsQq&6NAkh zNp4k+zP>OP@W^pLFj{ZLE;-S%*0yzunxujIsedM9xuQ|JKKs`&th2`&pQ0Nl6F#p4 z4U(L`%&x?^p)Rx8F>F1Gy97U<)LB(1M7eR)vczLi6#v*ZdFCncAAn!+hOX7OdBwHz zyOW3F5B~seV^>vsC&CN!kd@h-R~r5SINE?^k0x?8Cnu-_E&c)AX!$#Qo0tFJ<74P1 zS@xVrJIy|=)T@69@AS>KN}M!(KTmX4{Ua~L{nzMki<#+P4oUmo;&4m(j*Za8V!THg z2Ahi(>S4VZt~pyS?eKp2FTuIv8W{?hv)vUad$nq9(WDbP5tWWMD9Bn^|=o#=RCjR@i6=!Fc5ln7(H?m@At zCRv7rrUW)u3-3d=L&T`t9qYS;_#eN7;CrQUW>dbcoJp zZdQ6yWNzvinn{r-Gdk&+rkMssvqH@}8D|;(kR+hy4a^j)W8C=_wdxT2g9!&eRzB8{ zMJ|bsXSScelUMAR%f2PZ!b2MyCSJfihR>jKhrZLVnwRA+OMkwo|L6~tr3(26uxR}@ zM^yVJu+VDuTeR{~^M5|-eIXgtj%0|*J=eyaw3UK1hGz=NKi-m6=Fz^DTNCwWvE_nG z^^Tv;l^XZJWtbI^w8Rio?$MDM9nL_3myj>XUO(jXtQ}=)-C)ny%692r*NN{zb69WN zG^AJbT5sE5?H3apkZGsVJI(U(Su~U#mT7cI)|7_Rq?Au8)JOvW7(EqpPNe6ALr;FG zV~}DG!=C(_!|qJIL&JnwKF{_lR)LnL!MZ@%*p+*QGpmO3~#lE})bKm~hbtU&`ob$fe~Y}YlsW&O0DC)Xa6 zS6wLn{-^oN)@s-#F|5W}`zgrov#rlhi@N2GT@jw~C6`dv&j8WSrdC@Ay+6@e^P+wt zU9mSLW^Ig%TGFKyKJm54rBgKA3p8tqmMm-Td>#7qb4?er1eKJo977a%(!Y22Hryvo z{NQJo_S{4a6m~m*dzTqzcu9{(>JPkRUou&ZjrF)zg;?Y2Z=A>qOqye26G%BU92PcO z9}ICsv6#^F_FSa6KiUqq!I$O)39AH0rmr_F1hw`F|}%{??^fNK{1tJjA~PFvYGB80a7 zKL?l&w1`@n7A}@XWUC1hg~CTH-r{nNXpq$D}_`;Wm=&CT5bX2>f(k8;i2IM8aO+_WU+rwuXR5Xeg4 zyfaEZ$BdcfyEy5l1hmi>6O5W7!vdD43W%S>&4W`v%SGCd`PO>}FEjD0`x{0irB<{d z4V&Wv*}gj|xBB!+Cz!xmFs@;UiPAU4;<4)+?~iCZ*;CGmE*8geI*mV_CMxqCh1YhA z)Z8=?>1JK0gtYT<^8u+qDi$NgIaxFXZ3SsffhekRi>PZtR*?|1msr@^UM8C=XHrk* zmODI|-d|(I9zbSR|6W(eXy^4^w7Pj#bo_L;Rn7?80gw$L)lSr&=kEtMUOiZ_N7@3X z4X@Zb6d+_w@Cnu5$Ux3<-AVeWh<{!G`Z|y3g7Mr`L!Yz1KO24G2eCd?5s9_)s0xMs z6ttCVXlm1hMl(St7eq9q6K`#8pv*wVilbJ^h@eg5YJ1rq)8vGGl7AUsQ#7|A%OVbwBYB*B*IMUexlwy~vmQ9Mc1jrcf}eS}g!=qIve>GzFsIWd zjwWfeW~f9nOdFB&=fOUP0uy8jI`D}PvNU%(ig+%Sm0zlNI?y} z^IPhsBRrg->dP%#!rIB`sx}L^itCuzh%Gw;-bDLZv~v<`ehLxDRqwWQvqA^C%mA%h2HAjqmhy)(7A`A6ibHUfEFNj{a%0~*gDAJ)8Xv4;gHANM8Wor&4VO`bd# zMp&qbBHZI?ZJ+2-e&oIyJLJNA*G_;^$pTSZS+W<*TI0k z{x{}KOp6=Y{UHdwYQXtbN<`W6i7_poq^??W5~^~%QP?r!dmb0JLqTaAaa(pCaGivR z-{Er@8#H3$-Hl`2b+hvGsjH-p@dk`Lwpe=7rv$mDQwT=FP`qHP39wbbq)Lnpj_^6G!pU{2~!@ZVY8KbKrGtVl;IUg zMo@-v-b4+?DQc_Czk{?FNLH2r>u<_B1j4w_s5=(~2dCqC*eads3kXY@qdBdhteI2V z)nVze95v@>FHInctfXjioQ*Cv8ooLuWn&a#UXL`np7B(ZaC1&mhGco)efMuqfyO1z z2Of$7^ZDqSn)3s2?i+rq zXO*AJ?7n{gObzTH1-ilUCjsFnIO#~Yl&!8%>%sm_eZwtEJNh7XyeU%JWk!s5>r5?gR6uO15c~WgPYul9T21d2C6e{m|v#PQzJoF|0j+S?# zRYaZqq{bUI3=EZr6bVUuX!hF zVy6Dm@apONL>;TWF35=G%EgMwSV=FfCJ<93n^g$gz!8I-ClMzrt@cOZSZ<6ez1H$K zBmtcTM2(IfqjMf%6EcR%DMyh*=ndk+Ev$;jusF{$6k*Cb7UewQQganHI8H9T^vb4k zL$|q&-w8pVL(ISnI1Bz(o?C{BI`&ACl5<%=BxMx z-^X_`q^UKs)WTr>-SahyDPxYIlu7m$pFS~SOW4JmT$ zQKasEluj{6d>q1|X%=;{#Tq_6>NgD9<-XV0-D+?kq0LUm7KQrBb(UI-2=TeK2zd?n zuOKKg1f;+cBsRJ(?QdoKIC6}6JtUf~39!zLC4i4jH=Z2sFqxz`=a5ivX!Rx~gMO&f zfD^269SR9C$s|*gdV#*T-L3I?_Ai-qI`e9ltvC(yi$qoOOlCO+ISSGCy$Ou#gj5*} zj8!OBPD6E8Gfs_i$NkSmkrvP91BM~T$oA*1qvaVsQn;vP$tjbo`YhXj9Ljo9I1%d> z@X9)QGvs=$oHEvzcpZQ6kbbq9JWI)I^b9zBxUR0-*I^Yw>{#6XVb(#r7W(ms(Rr=G zA;zxsr(gu586&|tQi6*mpqGJj8I`?CR#d#ZB1fJ~rqY42Jfo`2765B-Rz;hkF}gmQ zWeTR{}$pNUG;&~w=i#IVF78`pRPYo${IFUD==W{U~AVm#mL!-46q}R`&$)o`VDIwwsF`YOBnWoR|b^kpXv;r{Cd|Rr5&W zBP~p}%`1u%!PYoN)g{`~m%|*r!GNKO+lAK4mRLX=u zv5gx+Iuj$8oP)nTD_!819F+L1-ovKyL7U9hYxGqN9kO5!fFA-1rhJYZ{f{c7fYW{T z+m}G7gR!QE6qqF@Gb`egLsZE|t|dXiFNDmYn~%SxyL&&IZx-ELJ$Ko~xdoi*(`-o{T^%*ZRZXp1htr;LuIrjNv0PqKjak`|^sLNEUIuVd4JSz)f|?_T52g@n zQGQ9sJz1V68GFj$8z&50X{I@DEWUk*7 zHf)9yq$jLR>XIPp?P4KViyGoOTU;oK-T@4I6&d;KU|!F3emA^*&9vv}t!3EUf~j^6 zR)#?i_vDUx380Bvta{z@FB z@DTo?EChHJd2*(SZQy>XkCz+8c!1zd*Sf}Ht8-py+&zvEB5HXg>kA*d6L7C>Ar<7J zyrGN2JFil^Q3t~iX-^8=O9pl!DB#)*3p(pM6IxhJa&#M)xXEpwZjuey!fWR2A9#Md zpaY031akLfB;>lG?QoGZq%DMxr4o8wjhcLt=g5p~|Ku~eu0y1@+-F_9(Gjp(Ln7dX zHZMj(y*RA_k|{_*);SB)BNM$2?5yNbT0+n&J4Eq^Fj<@xt7l8f>o1U=Q=yGEB#!DW zYfn74lo`}g0H=q?Wre~zY7N0W&28vbEE5^X;$C%fDX093dDZRObcoXvz0fL5cCYU#Q$Ss-vVhOJZg7*;M`N2A;Vs>b0yO1U0Zuoh`nQd#3|Ysx4CisdoAD4N*urxwb*tsQgYakKj_bNPy#^`RC(zgqtE3u=-g~Eo`c`eH^1=&J_ z^{Cwje61%G-`pznLg?Nv&zBS3VK~Y#T`}31?U38V3baHCff;ez@gH(((hK{oi2q_v zaa5m=W0AYSKQvIXrBpY=x}{TEP2t+$GAq5wc8jb-z00r8g%Lw9v1y+dLH_}nQlkWE zt?N^1z<%k})2}Dfs)OR-hg$db@dzn1$DZGQBHQC5-+7OP{sE}1eWSKjs$|aFmKtx@ zeEo5e1Psn;M3_O0wMkB9o^B3p2yWje;!R8hTH|nev8XGlxY1|102-RwbQ9)INCQI4 zrbPArxK9wdw6yZrTiCoG58ltX*Y-u#qZrKLsuVkFn3(X6k0KhmVaOpnTaL{IwNUv($Dm)w4aoNJ}Jcr&!j0v6&@g9F@Znz%&!ZMKU z?Df0C^nctS$1RMhUAgB%Y+!q%WRErMC2PKUa?vF|n{!T)pTvavvgMuNcPE05Sm_0C zJL<;Z4@=A+Br_Wa;EfnPrF$Bq*^q<{?PN=*spg8v9oNw?DJ0DRG=@UinoMqsn5GxA z6Nmli?=Ezt&ImpC18mC780ci6|!LD`L%P{=(M7+SVMZ)J$$PthI?Vs#@ ztDM0O1K2#pUjYDN506pH)9>SnT_@MXRipOi#%Y{D2zYHWt&^XKj0P%rZtM;m`F|Zs z|0RywUnM!N|5%ZdQ#r}ZYF(!%N7F5iM^h`@iBKLM<+x&KCKOTW-hsaF+&9!f)*%K^ zew}=b0(ib^N1}x}skx7@s$SbX9$mc@olNJMG!M^onCQ|~pq}uggSlFM=yX{%EB{Dy zz|a?&PnPtQraMrJ6U_N0XmQ$r`slK5!qS9!#E6S$|I6-IO zgY>Laq4#*UQPPrX9J#Rv0kVt?KTraMf)Jm%e)RIhob0oQuZl8``Ym=e+k-XFK2b^{R zJa5vi9H0f69(u-1#zGU<3mEjO$ELsIkM?P|GEhF*hr+^POUul*wRe**N47fktFLR1FaVRESS6fCGnt4H= zY+_m5q=I$mXM@v=3M&wCqdw!c@`bw{#T^W7)!`E?C-X#b4mCs8J09~g&TiCioE!== zU+S0=x6iPb3ctf^;V50Vas(1Bx9ArKk>P57n)dBNF0mnxu;5`=8$`4u&@U}aQLgLv zNm1n*teb4>_N+VVYD?gePS0?7uWnN{%%5su=(Kt7tR-vL`>+m!v&Ex#_T3!TJk1vA~Zv% z{~L&}oy~IUlPLMye{M8wX9om{z3wPWUrjnUHW8K-)1P24 zVXk8>T`@P@V1C)UVy^PtEi)W{YE;}AZ^L%G=kj-d6rR05VWYVac6trZeJZ*gU*lsx zrFhs#udjRy^}rT7lnYTca^TbuYjoOUPS0V7Ww+`>KLJ*^Dw*m}b%u5%>a3N)r{8U> z7v0e@sr5zf^Z*RjaOuh^x3XWx{|E=bpJZ{6ZRd0Pz1c_Xs@7uUev`o!Qk`5P8fL3-HpfAvL zdEvjH9;>Acl4k#U2M7i+(zk+HqVw?7M%x(^GU=Md!Hiu-KaY}~q_x?8;IdmLe%7i7 zSpq8&9sR}tepU8fiR)?T*Q~~13zFXIifGy~_e-j&`MM?U-Y!7G>s5o6x63L1FGlBz zGT&zE_~~?3B*u1jnzK-rf4~*TQ3I z9Ltm~cvkBtW9@M?xfp-sQ0-Pz6(D~Hfk@N~SXC|7ji|BNbPP~B6`!4Z<_e-ZuDiwC zjk6IHvW9k+hMWlSt}9WiG9h2WiF`%rw6=yEHxSU}k$EKH|&210w)%r))Q1j^-%QI7kozK?k+K3>`xXO-)%nc@)vz+~XVfZ1@M?8sVUj0~7|U^VdzND>y@4;C{rG7Vth|Z~>C;L(0}N3f`Nzz3{ANpTMYD3S zG<0feV@w)kVU>@q7udGnTdPUW=G30SKUZxnTKS6YYNXGEyJw^R;;y}Qil!1Yw`0S&*s_4*nUlg^{dSOg?>$*(ok$X_IN61MiEuXkf*kOj$%n= z6wor+$0ijh-`!V{=N!-FRRh`<7+#ThLe}tx{VHjqlNv3*dSPRrG1IVN;;lS-yxK%^ zsF-Iui~}4|K;P>5Wk_X2IkV98(rM{)BZPn%*0*zOa#0 z>x|^tVyZN($KS#`7x+nA?Z`8DS%=bvXONjEsh-bt_| zoi)8^ITO9eUHRVjFyOXID8U_{m><%Jjxn-cmo%7p3~qv9MXYG&-=7)P7d!yj4Q*n2 zy*`v0Ht^#v_RXGR2_S2u!kH|jI5TTUG)k53Wwa^}N|G88mfbIPlV#%eaMGOMTwt^= z2$zU_ciAAS9gZvAG2-+tlO0#h>t*$cL`zBlZqc1EGE|v=V6&-f$4a9NNfl!pWbQojQ1xx%3L_j`Mi)$De3P?ZB6dp$!qEPs$BS*rztm6mxyS z);4G!@nL+O?kvz)f?Q43ioU0(R>ZC^cG7I?5saVon44Jw{UZV;umH^tdCMANU0EpF|J(a#pPQQlobTxU$Xj0kAVrU*{J2K!FGg{uX@V=Bp2f1)}-{Sxhd+~{1B z%r^LAsma47;d0`KJL?xy*OmC4w1cJyFw3QowH1?r*ADRShm{Chdtne~>rYyy7QiaeXQJf*mXmM2&fEwB%gQUir=P zbQzZe>K-|kbLlf*Xopq-u?6#hLu0X%i*MwI%1Y-73q!viz0@XrO#+uEeUbbd>$nGW zP>;nsvkk&iI}=IrM+D;pm55m(xbpQL*>1`zQHU0-Uo@YLM-p#d?dzx~I?q~}CpNJ3 z1dxUW7E5olS(Mu2SPe^ye_uO&<$V-CY9&qDvm|L?ykw;x&c6-_ZIp^(^g0oUs@#Os z^QVHb0E8&|m@^FiKeOK8O`Zx32TS#*_qWgu z+NWh<<-~frc%ZWI?peOnA3Y;Jm-t>>mkT)u6e#|vx|}*0t^>dB zZqnUoxDtzKODvC^`GAW;3%yE|TOdLmTaKtoFcd)s{@^Wx#U(v)faArX$K(DiCn^~# zm2vp=SUKn-9Nd(ACyU=_wET7pyV4YOM#n7BwL2`skN8=WNJilP1I{qIMVgk+78XpL z`X=nxK}I4{$6&YZ{lc-Lv~|A5kqUlty>wJ)RR~ob7N-xIKZG*MFaOm=PL!^7*a~J^ zaAjTU87hCb-q7>>U7gM$TCPou><(`WyM5Z7u@nnIb@Oc$SIuuv@i+p{vWj!4c44MU zX`P|ZH7eXxcrSaFP==Uu_yq-i0>&`%F&@0!#K9gSQ!b=`D}#DOh*J)ug?WGSppPL3 z5s#9iVZt{?4#HfcVcKsF-($R{Np}!u2}?hX_)*Rp5(J2m?S}t%kJPoLZ`9XuN^g$t zLD3^jXTc8=(UC(}k(*$8<&+aODai`BuhTn$Q4oWFhjr2&Wmu2uICJP9(IOw;>%F4d ze}4x4sQ&`Jva$^{DJ(fC3YGauoyIpH{EN?4F5x2b;|fy{+xP0pF4kM}>g`)hRAGK$ z)~@rb@LvVW_}N$UUr<}fg(7m7J!DD`s$&W$R*v?5<9ZG+B)Pj6dM=kkKGqGNA1kSC zQEeVFw?S{PP|li3*tY-Ib;|!7i9h}t?t(E13%;bwyxa`0G@*GmxE){d-yiFV_3&z|Mf&=n-k?)yJ2oaCHjqfX|bnG?+F%1?k;^TAuFAc zMpVue=BRBFn3;+OtCEiM1d=V2>$3{&LIJ5!uvJa>)O_r95@}&%MWjK#KVAHlY{p&N zZ0OX9PLy?V`QsEJ_yHPYH9x&sf}E)J*i+>81?p|BHn3A&gfwc#E(deNo4%uX8kVsW zg-E%S#Y$RWiy^UA*h7-^YrVP5+#05{+UIo{jR_`g189D^bbnu6@q3-x>UnObWc_r_ zZABxL3klH$zprY3FFtwb-Yi`E;c+i9=AqxM`Iue3Mkj|hl}GRi#UKC8K>i-=Vl!9%wRksSsazLL9DM$ih{zPm zbjz@)67J#X(M%1*AAYP;Gv}z7XuwGS=JK<}wJZBEk2MC@{ReZPZqvyc=*BUxWE)cK`fLAJZV!yvv+8@-Wi~3G-Ntsw?2pH5AvCcdlISz> zw4a{6Tc^MG-bapqX;76-5NB2zI!mSY|Mf9hXS>~GEB%Xhf{up5Y9m(!%y(H7bAIMG z*{C%t*{hZ+K)d-A+zP_ll>Mzx8&AtYgayetl)Wl9WCtFoWd_&g`uc}?{@CVKCS0IC zIvnrVW6lrFYXNq1GN`h|Td8~4gk|{EqzTtAxE+innyPdKc*~S|ntI>M3?!e{h@~bH z6AOhuWxS;pYXu09u8@mf_%9>wGnm;-_Bfm+%J~U?E1k@)$xQ*tJG(4;W@nV|CdVzI z*SjrT`lEc4sy4&#-*id%Ral!)x=)fkpje7;-C;`U%j-N#xD^cLk1&veB}P6aGM}5MMo1^yO#WT8H?dk)6${0ls}Q}dFA97 z$DXo2F|N@$?VU>Pp^V_sZxyimc>F!tHV3bX(9#PMZRpmiPB8D!Kr4Hto{^dmqjZ6L zQL;f&mHh=v(8)%>;I!aGkvPtJ{Zcs*DnKYN&s4th502H`gXEOyGuoH1rODjKtGtrn7k( zOWpJ1P~DlwpZ*rL{2ctK&YZG??9j|=3BO{U{;P&r)4gvK`EG+rP`bB>u>xu|e=m@* z05pO3SCz$?jW#i^c<`tq3!$X|F)aI+3rkP8aE1OZ8Zi-v^RIQrk#RWh<)k1ku}{M;c0EPlI_< zj4Z=$JV ze|7%7t5(tc(d+&MmeqM36ILwI`Hyuj{qkV~*!=v$a=d3jMjovveFecW#6c3oM=v8m&SfaWg;)Ch0!Lx;}qW@i`T`KD(B zWonmKSM{zhGx9$30k}KDUp<{kc;cIeX29Jrl~b%1x^lN>9UY$Lq;%%FSh8xXcnr(* z^Knk0Mm`ac#%rOpg6L7+mh=k;ws9^tT;M#W?u6(ugVI51(2?6oO^MFS;$&*MupK{T z-2 zgcYZ$1~jAeWrvEk^!@Yo@czDf!j3*;2Hdg>DYM?<&Z^|M_@}ly#&T;{#$y;m_M9XI zDs)wLx&Hy=-l7L~?YmR|Kf=y3D2_I2(}M+fcNpB=CAfQVcL^}K6EwKHOK^7`+#Q0u zOK=TN^6tFf?)U9(?bhzEsh*mis{Ya4&vT!1uIrFtIx&W-t%2=Ah$6bODEkkeyL9zz zHtTmSf(?mbgA)2W1HnN%x(HSDT17i9GJAA9dy6mGd*EB7jIHoI9T#WQExPCi+$+i? z3pkW;(`&`HhpxI(C^$7bnPSf{2=vF9g8tS4u6_h}N95D$4TRK^g#2d9X#1vCJ?=}j z`=g%g!?#iO1L#^k_A531sQ25W-WMa8=U&H4AJ~#VqkAKAqk@=?ao@vJa|1N4wK*zs zJxRe~T5%60h!?R!m+HY3Zt8$EkYYLG4!+|dxv#Ki4xKY-(Zykyf^;4g5W<9O-ozyR zte{j62+|ofMBOgM#@IuQ#G%i?0#yN^du4vK9wQE`SPJA87M`oTZR5Gq6J}!Q74cDi~eK-9s3OUO#%9$1xWoU_#}N|(RdSi67xx<^D<-@nqdm;LN*+Cr0uYO=$@PT z=yW$0wlsNmeyjUaG`r-%*lu(s-QeI`O2Z^ZJK>AXrhpA>3UH4v0T?65{3!Md%Vbq~ zJ2`u3l1E7D@QS{@XN%_ALw~%?1BZD-?53!-9D4ony7zOY=&48iJ_mA63e5%dw^`b@ z!sRxWY2)tE0uNMRn@~_&hCKM`H%)4BaNO77v&1V52hHz=)EI~mYqyobY2jyfR^Z#s zC3(YWV0Grlb4iI8O$d#)=E8sSo&PH~X8!ntYVz|m@$G=q=|kL9i%|Hvq>3+joY?Ul z#y3f+J&h~JFYd*<_H!hCU1(LZWE*@5l5we54i81k^4%-@xrVk>$ad z9C}`aj;~|Cv`q4ov=8{J%%m|B-9s%~Q&@ z{JU@YZYkzpK(~zq46@{X_|x!8AB|9Edgt?zDvdJoX8P0(NzaiO5_Hoe3kkE}9V48g zBTJ{J_tznNAPiNhqOGfDP^L-+0OmvQTT(;NHQkNYCYDY2@!tp7_uB~igys|8onhM; zqUPMn#4-L$jR@UKpom2Slmc-k#IXPX0HmZm(ZEn{W;3|2+~@<@`!kq{oi>^ZD!Lu# z>af(cxgL0xy4%n8bcndtPS&{u5!!eRlV72NIV0qL$T}HyMEQi;_awboD^>>RPsAo* z&cp>ok$}#9y^KfV7sS&|y+Ioei@(N2CZ3&9+D$S)qiijjuDq~>->a`;IJ4NZ49o2) z)*%y@TGOCpR?k?dXiIdXqZ(I}^4`828FF_4{_haAC)g__qV*l!-(jzNLg zP71zIkxqK2c`Cc1;ix)~6$~+Ev0Us;3NDY!QUllRDTc}W3mpzQwi%PBD@E=!B`lOswED*U!1rlnvkgnNwdei$KuB%kl%qD2`l zfL)gzA3tK=`Ot=C)663cEjOUxWJkWLcV}?P^VZ3mf=hzsdBL}3wK(DMiehh=MOLZ> zq(!2-z4nvc)sn+QA#Az!t=5i(n6tFKFkkJ7nHnh4|b#)jmxDs8JHVP)Rxr1j>c z=@&bT2|W($RZRjZEQhy&=A>qALq?scT;axZx+FfK%uBq*=spYA5hD};FoUjl<5fq8 z2#GjFh_e7yMS0#*YZ92K$(r>p z$s{Y@4Owj<^24{~)~M**CP@JiowgdAuJu|eQP>97aIJ%o+F??#X9a#SLW&GX1hbA+ zI7_N2k^qa6be)akMyY*%qNHzg5j+Xgk?t znsW6J@)U`K?#q#5RJ`uCjm$g79y)L0NiynKjE?LVN#27>Fiq=+C_2=h4~BH4ab;O8 z;(3g24XYh9su>j>NZ&~#I;$7NRK_~embE1dO8IR@Nk`LvlF^yPtB21>J&zmxvs_7A z0L46Y?XS;9ujG1n;+K<+F=+#}8HaHCJnoSUmK}lEholVXmChr44EGQy;6W(jFo#e! z{Z#g%{ax#eAu_ab9oyjG!LPWqgGcF-02XlR7>738W@yWh9j7WKU5=|ojeS-&SJE8e zNSRQ~$hhTZ5zy!0X{3_7r<}+|UlfxUbIvNiBcPA-JSYR;WJNY=xVNYm$&EcduV}W* zOTF2Tc*7=lEbNYa9r14B800;UOqR1S-Q_Z}?`CoFcPq7pEr!)m1>zsFzeZ}6sDk9nm0@+QU~yzFO^ z*>Or?~=#_U1l1%Y^OD&j}zHJKej|V^qb}T z4o}n}j@B6&zkFyIaRZ|i&OBSFnqg5kzrjl z+M(!rR-G|Qv!r=c3d1|9WjB4Hp#*Hx##ha~Ej)ZUtM$HISct<4o&63}byf9WuMx12PcO;Ct-L$liV~!D7qsax_`Xe+;stv#rQ% zb)Qypb{7*2hd!;*X;QW5kfCBF{@L9+7m_Y-#!7+~1)8UT4=)Q@ysM*%dfuNR z*t&}%Mno0yt>5j*c7RCYuhC&f+^?wxT~@-@<7<`rQn-17oiEW~8yz=E{~VVy?|ND; zvvjjq$_T}@v(WLc?4{ip6~{Yz6lA^4nyptI#Q>_##OaiN^axkC_oUk}TQm2CtWIy~ zd)Y;$;oOU@8~bo12xiqn9y$lxvZ3-WfQ6c=wH_4Oq9V3$P_EK109NG~=}Rcu)dqZF z0sSvfDk}XaLb&!eXnGqFIk|pRR!sw5R~3FcE0a;X7z=nqQ(8+%NbR2Js}|Hn(*^BX zGzWRqvS9+^m_(bn%PqQAIBV%N-0m+P!k}b5OF=zi;+a_yfUjjT05%alaa2?m;gG1r zr2(eo9qa=&e5*%2U_r*hpon{-zWw7gH?i)ayyz!7PCVxAg|_;D`fO^*0O!RR{SESfWm5 zUWEU^XnehC85EWZb5hp-F`S?*=+DZq^og(a;CG+b*$ttcC@*lT&&VWmbOn4jvX?F$ zK3lgTD;MHH0WSurLXfu`+%nd#O+5ykeKrLP6;>fa(Lm_lOx4>k`8Fh@)e=(6{aQ1?xD zlxWZ=`D*rY(%i5v^kt2{4R2{nYiW*h?5HA&z$aGpZ6Py3OgqcrjKg)?f{Q~FH&Shi zi`Ax|(-W1|bb6V&WYCNPKhf})z>X*X+D{Ye_{L^^#0Kj1!Xz7IMRh&)@=`nhu|juu z!$;&qp`#%FG(W#$6+=_DHa&H}e*kc{=TCiXoAn&qnGf_TmfjKA*&qWo-eH=I3?K(? zce{rHr@9wzGl)yRvK-6zKw!hh8(z;!Hbd!sDTnZ5HS!M)-8P%Em9W?SkH5QHOqO>7 zHaR&~OaWiiH-ttuoTr|%sXp_iHyTTHyTY;-<`_KvMopKjIX5<->gqsuaW+KDf&-c8A~8w|u{&)>m|wy0Tat zeA!$FO?J5aj_Y*YVaX7GkUxu*FK6O#7{>Di1!)SJ1`!O&3OiEKIvk`Eb?<7MUS(jS zI9QZsD~tNf#C1zKbf6`T)S^)qW)Rc=+;8njnRZuNIe9q0bx-z{1FX4-;CEem=I}?+ zzy<2^(V^EOZNGr-hP|0opLU2ym5iVAdSY&k^Qdh=%x*D`7fo=l^?vb~ilawfT)>)` zexYBZN;vd|(emXrf6gK0ef!~n`ymDvb%!Hj`^$EiClxzQ{_9W-HfdFQ;BACA> zpWl7yYF=tElR!tQpWoPPlXmvWE0POw2Dga|*Wc_t)6DQ3Rg5fts*>pF_U zBl%6S-|BsWqz5^#h|P{Rx#@1?=EGVlobxE=YmL8uk})YhElzY6a`?!)WMdSy1E{Xf z!qBmDN#o4v+X^dXk0p1~lGeq2o#1E&n6kuc`yxF^m^!F&eI~^*U^nf_a9ivz#nRJ`#8arj_ZXNni3PSI$0%wZ6gJ?{A? zvN?&n?g-(ea8P@5+&&x>c}ipJmD9w=subzG#W<#(6QD^XkMpb(SJOa{6S?dPI#nTQ zOx0R+Tsh^~!P*}lYnV0#v&_e`r(Wgt&|)klqEVI8(IOn*fjrT6H z#V6HIv`D)$C%#XA$5qzy-X{>@XSczro*wZubU?cj1AqJ`Axna51~g2?NKHvCwcAm_ zqHHK2c$eO2>rOYqn~anrKOO0sK+M=82< zvTT?MhMVKXbrNVy6gs4H4G>N$Qm4B7sIMmND6%B8q;VJ|YwW!y4PcC4r!3-mJLgy_ zYwdLr{c=?SD?y4;djJ}5Ww_x_cP&D3do5*s7W0sl)?+Xi!39bBu`xow|3(v^HKaxo1R6iKs z>3F&1HQqqGHK~mw;KSmy`Hpyei}>V|M7lzbiX3pq9WL z&SC`Sn6oF^w`FVo7R}~{QPNTUK$@ADdQY7xWY_H$w5#uq+x{Hz3e!@eJ-=v1^!Uya z??!yxryfFF;ViR+K*XGLnO)8(Jw|LPoIIoa<-xav?r|y(Djplp;UQP}Xe_WTg2PPu zm*_Y{#k*Q#w&0iByYPGxHv5eahl;^-j<_GW$g>vYh0CKA7$A7|Ok#>Qn#Iu4BoIso zF#0-{F}HLLr6MY#zOHTXUW>EAjEaSl937qH&D`4P!FD_{vaPBoB`w9bQq6{(Yz8{d zhIOmPlmS5v6Z0uZipFi77$v#0CaRXzEmzE5A8smFISAlFeG8@VizklFr&;Xa+YW_5 zO23O9%V|OI5y8-?rLtAtd#6`qyB~R25jC_ZFCot>97WIZ!s~k_R)u*GuiOX)$tK$9 z8hos0(z>Lk3mcOVRak49)f=i=+`>g53wI(K=iPp{GmFT14&@+2oA^3zLEi=QRMec@y7yUCb<%gV-#7yY91mzH6wZ`>BJGK{ z>6vzRdR${;2pfm*hnI)@OE-wZIv}w7oUO4Eu9JsFtd&=r5mi|iVT?85vw(^iWeQ`0 zc_Iu#Y9YzTFuMb><3UGC;{#~jtf-#(&|FV%n3rfHvcTmhF_!^m-ci6LXFG;RE_r~7> z6z$JuDbr}N7yoKJpOXub#CNUj2~xY|1ek?f6I31!K(wKN6Ql13s zoghaMI?PN{x9k_ebH(ds$b8b_W*;FLp(95T6N32ci1g`gXTBfasj6C4$nQr63lw^g zM7`$JnXYkWApq{B+g-XVE3oumJz3wvho;nt$r%Kh>c;lF4;ND)af(!L_gV`7f7(pyOu`?@I)Qkdbld0|NTGE8ebT& zop*O1p4y7&k^2}$8;Uz#-+xPwW=or0o}&{$=KCeDkGp#V;V^|dooxO8oC8<8R?ucb zcOg!-UgXyRjv_jL{QD0JDU}zt(tppfKP+PT_f-05OEQLe zr#|D&d7O4HmMipsWB6y+oz*cZl^cT%NUOuiz(768?3SQu$988^hh~QX-T99dghk02 zFWck4MfWmxOP8~Zt*jcRYq>E*oybufDROw~F}%L7@JbrF`C9B0b$6T$^4(w@O;)bj zx{FYy71%nOCA1W$ZF(~i%^ktOiA)Pwuw>eN8P5oKOkpB9Cne=pK}GwJ*T6}@c5n(f zdMSROq)BBJy$(1_XD6NNjuAE{ggC8H>&RiD&RHXV=c`?i4er^)!WMebth;FXJA2Q`WNk!1-jd2d=qz>~Iy^1@AtWl0|M z>qqFSLY@uUuCS|zA;d^)g<^%HHYzX;1Oj=EHPjdOe>eX8IYPp%*1*YsXlp@bA)P(S zQTV9^GP($t4UY^pgjYYzbfp-45 zWyH$H%Fvf-ddt-#!_%g_ue383m#MrGW{RRTD;m^H=Q^B7@b zgsR_`A?CN1tWgOgTXGhyA)>5m!X{mM!mRmajP`03#+C4!SR7@s*EiAcXnb^09uERm zgH;b&noSeP6?xe1ouho*iE9xsv}Gy3BG7=thAt-jl)D?7)4qRhL?_qEx38c5g!rQP zPM;wFQ*O+i!lJ78h%P_UonCISMY_*z=6B7t#%Gni63IOh%RD*c7WG+|C3Rz~c1~?r zZQ`}*&UDVjw^?5g==D?otR%<1Nf7D5g5m}ZKrMMXt+k7Ox2>JKVV%{!wd0tsOZr9=Cf<4(WZ|eC8*AKn58i)%L~>Oy{443h)g*Yb$NH@bU(t4U9GJ z+Nf0+znPa4+vxW{My>-9IOOH`DK^6f}{s#fv6+et?@pMb^7Z*zIEdOD0J%uEjaLQD^^k6gWkMp7HK z#}v{02PMU+Lbs*rNy}J>SsSs`Rx6{{#5_0?Whkk8!KG2(t$NY98eM=jv8Qc?c+CpgpHIT7;;1A?%PCfxLJHD>cTMfkyg zBHmB}mibF(XHc5NMU1}ieBw0w-@=_qIox#w`gVnpt|iTPoQ8X7k?}(3_RuTFu^2Kp0kQ%#mEeZ z|0eKsZ9%Vfj=d)ed=Py$>92ztl~a8sjv3~C%rCF~^ms{LjF#n}zwKdqh;a*7Y;r5> zfA_e;=sgx!mvbd#K|)OFJlxKiZq(fJ+3^(V*VM_%C&$J-6MiB(+~UZS{STxzQ;C(9 zt*y3I)#-cTuypI{U_tcgO1VPC3J-S%9XN8+Lq(nFKDenHbi4481#96Y(#0Pr5O6** zvGDPgMCb~>O2aj>3v$&3_<`Bb;jz!FS7nZg4xLH!+?xb3c3 zO(bkdZQ#AF5|R$JCu=U$MmsCTxDr^}?(x&t3mmML_Q;%BD1zfhbyL2x=KS6)LMA$I zsaehbnFekQS6&vCYOb9g`YL77wLWsBlvyYKout`=H^%vmIk669xg6EuGfbS#HWKmo_p%ke*qDbV8=;8BNHO@bPK|03n03W$)#b0Yxr#$kqtf@d{ zgT#vt&66XbEw#GfB*{BEgIpG*?sQ&to?V{jf107^tC=>UhpgE#d)DG`C81Yo{33di z?65>(ykVc zI|h%Qb~%MM3inejF*QkL;Wn0o2CdrjuOzq=*7XO^eCFE?wcWjYY9BzVNpd(co=sEizb?_i&k&9|F@~Gwzw&S)0m6 zT@3bsavgq__d6d@$F=BGU2vM@K~+9pC|ex7$mC5fo6Jfjl|6MAi>zx%1-Fj^U6_0Z z`$@v++(A|^#W;A<=Fzv_8k>yGZE+^4s2x2g9-=IVFwZTzr?2*Z~q!>sn) zb2T-CRN}y$acG?JwAdQ#IP}lHh&4ri(30Ka@X5h=#!l*LM)(Z5X9t(@?$hQZ>4y7} zt^^9M1jL|E451b{V*X~5zf^;z+_cl9y6axB>uPY9T_q|`qsoruvL^TsJAe{y)Y7vv z3$&V1gp!D2gB0rQR~tMIRkg|O-`0h}DmJWs;Z{@bu_0(Q)+Hr6(lF#DoD7UtlasVb zsgHwd7?8OxV3#%{M?#Ftz^nzyuV%AYx7SH-W6n;6$H(Qon>ITQc-b~nJl~mE z3!e!d%|cuBmnQ~2GQ;~<6tiV%W!_h8Rm#)K|^%k zYg%Q2AXGc%)4#dvtgq*PU70dm`W-D%Bb#N{i?-ydM>>z!jxDpJS;vMY%ug7MFy1dz z2*{v^CI0pDAe~`S1T(Dac9O&06K+w5hnI30Ra;Gq**Zl>a;`5*D)SbwR5A|sA{ZIc zal#e=hEXtn#Soi>YF~qeCz&H`BZ)}4BRN!8d8=T5fsGGKaBxZ_q)JdU-aBd8eybDT zLpYImbVeak8jAa3nk2VoS((@(9J05`GuvrPQ6L1e$R4@h+gtY&Gsxf>E-Pt#AHK>l zKkQt#Oy}*I*SqK4qIzxBEo#buN)fk-YQTwfgNl|UL7||4hMDrNV$U#cmn}0&A{Kqb4L(A~f~ymV`=QmS@b*>jtA9$lb2MG=AR-iH94qkn2_L4Q z!iSih(-obt#ajbO?5YV(oQnX(a=<;Z0%H_4Xi!XakaE)~f!ms}0FjT`1^=S4btTE7 zwc&GGzbFrvX6n@V!---S2T5M^g*1M@URw@j_e4efXSFL-Ay04(c20Q1?;-7X$6fzy;kJD%5pfi(2FIGXNo-I`Yh zVJ)y`W{xiN1)WmLLz85It^a;N z+N9~DOIs?7ucYj~s1*-bIMz8buEm3zN;s)oxLbFf^jL`W=G~lm56@IS3}>^(7^}YU z3E_x$sxTImVFO%K2cg9dG{wO6GKPSc=5e76%S9D!y)AK38D2GSQ6sW7T&U93LgPEj}oua=QF4kWL7G45iOPw@cAhI3<85num8yX$)-km)>27 zJ9`8~_3K?+N`^VS`iJE^9nP!18FITRcCkl^#W<$UZY_TU=ulwL7$VF`m-%4^_S;0;q_w7 zU0R}>oZAbz(*K4k@QC10?vR;Yn~QO@B7;jP`aw%->3f_n9eqiOpW5qr*xH~4j%0-b zG!bzVww;!N(1cm0(8lygl<)v@0)I}~{q+3Y7h=<$pl9xUZP9f2?|kg$mqRptb{skD zy>{T5@%s60%8{X9cLz6dqB^de#+sGswYC)RZB9WwoRJvwG7T!CacpQ_WmpA(RKm|7 z*C2qq+&vX=tQJlYB}+1+rwW+O(`y$C+QR-qDT3z1lxBGxcfoT^{y}{PrsvZKG zg0xM=%Qg{AY`wHOf)NV;^o)@W&q3oD^6PF6DwR+Oky-=;24TR3m6E|tZItnz0*+zp zHaMw$OxhE~mM$HZElnM5NTZOnXi(fT9k0vEYD$u%x!WA!K^vMQ+j^6*)b99hg>=b! z3n95*zdz!7hZ%r2G$t{V$GN;BWd4c?di^dMVEWn_B&Oy&rn>G?-2#5XWFP^WLfu7} z#P`M%n?zvF@0~v4by}=b!6x0s^<(Y<50`WjfAhmq==zo$B<69HI4imsqza0I6typP zBN5+yfi*wk;VxkaWXBA-*0WU|kJ~;#2Q8a@-QP`yOyPqadh!8&w!b5qU+SJz<1DKU z72149vFFjLGa|r}CPhm4x5OM2Ou+zL9AWBaty8JL;~H>M%I!9MMqU|aIeAB-7FM(I z8^ye*z1J>*NK08SXxm}ie1UgnI>>vT*_Qii@EP=uj_h(6z zSb`lfh+y5bR0OL$q9H9VK~2SWxxI-(iKwwvL^-v)PrK?}cu}6C4L`3b%y|mE!as=7 z9w&G&=xS{p*8gl53|t88c?SW!g7h5DaB&RmxD;zQOR`bt7iUQs>8aI#@;ECvMB%XG zq|z|-ZUmkmci-)Qc`oGsx*{g`n_%Ogv6?vf_V=;F`BQ6$v}huHFV$b=s$#v!(6%C& zhR{@4SRpZS4Fm)~Q=adiXUU=R}E3&y@OVj)Sly~Wp24v0(#|IFI#FDsBf3hKY8|0Jk@apyILI*^JKX-%;zlEX-2A(J&o&rMUgTQlK3B@wX_nIQrpv{sSlR6q1BC`fq4 ze7ru7ejO|bC6e!0y-tN2v@{$aHF3h?{4r~}Lm6H-RCpR9V&xn)4gBI66!%TyGTW_q z9nB1d8it0Sci-9GtmBp}v87kT-XwN0B1q<1C9qV$hR1|H{X={0;O{m(i2x7rVu`e0 z8jAa$J^`_9O#ODyj5QbhIX^FCg=>%AXXOg+c^!>g49co}bMsz0w`NwF~;kL_|oBC_4B9 zPj;|ZwCgwU^Fs$k>~tJ{f0m;&3u$TtW{U}hJ z71e+6W8Zlwa4y4gN5Ro`M_yJ9Bn|sOy0O{wEQx=)x-1w8GXZrnIA}$YlP@Ile2Y|p zr6758h-8d_4kDE(O=2^Z!};9APYutG??R@Ax!Kkm{Y0MZ=@JF)jpF!p6Mz>A*+hr} zIBaX@oCDK*d)twKsoerC*|3xdFbSop7?cWPoYA{F<}r+>^zfY3jAk6uq8$)4)s{@B zP!mQRS)Xi8o##l zCm-tYKyJym$DW2+9A%jF@_zuNQ?1;jxy64C1tV%;;VZ->8^k1Aggt)s%@#m+R=gm0 zBLlvX0wXUTluwc9qv4j1ppdpSC<-+wlS)v6ks?zypeZb)sZrY~Qo9@*93TGy*r|AB zed4{ylVz13{qSDo{qVW#>@%ADsVhgOx)>k7Nj}E(S?jyBm6Y$WCO_mVBOlOhA=f&N zcTWcQ6Z1B%&~-t?O3wF>IJ_Xi@;xi2{2=Y(jx08Hla)FbA-!8oQmiB(RhlP-Vd{uO z%ukHT(!uA(db#N^Q_d>|XG<1lRIHnM7HXiZkNn%jM`{eRP(r;#2aarwtd3yzJDMH1 zw?}A>9O>s!a`!F_D)E4!$UlG;2x6Bk<&okzqqPy%KLm~ok9C~}0tp!y7^DTpw2?`0 z=~0r!q>gUE@{$Q&R&6MQ2o*ogIMXHRL`rv8Gxt8Y{<4eDYy0SquqT-!BH|aWsi!l; zH0QY)J|DOuqKgx*IqOHGem+1mwH4;+ob7NUk}>r3sEdK7q3ujl-%M2~VyKDw$t6)I zCK%0}d{%ZuZI~*C3kTzQj20P0E+V)|WwuE$)aDW*8+FhqOY2n`{~+gZy=osZ_%omK zN9gx@Cqk2|YmUf`4Z={e0=!CQi^v~NpIV$@(PXwoE`nE0LGZ55!sj?aKnh|X_~xy9 zwB?do3+Y<_;Tv}3ssd7WBZSQXQ-(pE64>sX8 zKFzs4%{S2PtzBApL$S{Sb_QrVMETs>SsdsT`rz4nMa;aVLVtbLC@_DmnO&Ex}r_?{|toz@+C_XjeksIVjc^7j~1 zsMLw#BhWRn<+`*tbq6vh2$6-Bl6yfYZ$W43e5^x#?NaKmTRxv6bFYO%rSy?vf)K7C z#sT^Q&I^Q`VbK8b^CDK&=IV+6>N{pAiEu@foPZ1$275<;*Br$-CmVPUIL4Hp$Aheb z|F`usL;pv4Af!~G^6&bXEw>&1o7`G<;5D|Z^4(0|GgYRH_wA{?t;~vqEsd@S9+-{ zfe}P2Fl|3Y52c_Hp%-gL8YJuyWDU=gnX+{cBT4M)4K-By)#2xueEj$*w6Qw?9!n*B z4QfGN_xhFhVYfkYZ1d(-@M5%sc5LYS8QqZCK6roe;Mw)rMNifAB9~`wv_OZDSWypT z{dE`I@(5BIJ|ec8Evm`*a)+0SmwB1B0!*u|3LtycByQ>?AjGDj;y(+Cu+~z1WTDJdX zLsx-8B=19cu+wa;@5hHx2vuJjZo?biT%T(5_21I6oq#Lm;($_JVG%Q$YvpgYzT53P z;JEyP<-ggKX4JZ!`PPr$Tk33^GDmxC@0Z7Qvi-8BEDC!+OUi z*yj<4`rp~X6u``nx5SI6!1oGN;VQeQF39W(>+T8shS=x|u(N%0`EgT~9`889c=Grs z_m*R7MdsFtdL~q9Z!$W*2J(xvS+mqC??g@uAYxmD;i(s`F?<}JGS1$Y8= zI9(N4y<#4EZ3mQ90t<)Z(Z0SL>jt8G?p(CCXo+le>2_zue*VzW`uK*lmqFb|yp8!@pic&FHNUz2UFf>=o*?i(**u zWmpuJgs>zMSV3Kph|N=LuuFoL7RTmCWJn~?5hQ2ZKzp*Xhc09gsbzr=%gn`nTaEX6 zfl^P8msN~0k*=`-+h@k{IAujYLmVxl!(g=Xq}SURz@FQ-EYHET()>(~B5^f*4! z=rMi*5-?cRnge|M?B$nf3^kl(t3$Lli@Z4$|B2A1O<_6|bAw-WcuYP?$;O&g(=q3Z z@@s_XzIS*9D;;notgB31mPTF2M*ME8Rbs~}q-(Gzn#v3tW4`R=D+fZg^nU-9_b>iui09Ws{oi#8Wh z(r??LExo5L<7I#U^o>6QPk?YcnkqD@F6ZS;}jg)i-& zX)N#2wZs{1=^Dk+K*ol-%&%J$*px{pPyXAUet^vi(3W7FBhfG~CJ8_7Z%v?#!$i%G}9|sE1KL7|P5dtGy*j*@pffD*Tmq>xJPW(=0VfKl0Xp z!p1|jr`4pM!YChEQ15Ry)^!kyyCiEu2Aja$$(t*0`7OjxW{d3ad96tSGQv>aO~jLj z53;MeZ~FMscTq0CjfJdAKx5>iw*JcZPmO>EWj>w0<78VbD4C zIdzdg-gfc+0RYgqAYN3MakFQbr_>n4{1AIMP2np>}Khjq*Q-M^-pRojMMAMKTPH z6`|@xq_o4B{8+z^6T26MHQ__0y^syprs!|e3a(Hg^|25|IkVJE!!t)40*bk7raOv>mbigph_NU(kol8t1Xyi5s!7b3Oz?Gy=c@3CoU}!Y0YJ_#GuaMrV)MoHHA}Uc@k(I zJ9bthEpl7ra4rVVj45y1bP_r{sr!Tex&`M`F+R#Ex&JQY~g&$=V-?#)RJSA&7s{jaF&9dL=!CP8ifMX$0v$g zni^#zgCzs56go!sN!LrTj8d^m?Yvz+q{A1%`Xj2+=13|p zh=GAYmrMkiJvPkvan}m6$BrjUzl>RcHeTw6WFxBj?N+tUW8kQQwmN%1rS)^5FSIMe zy_`sFMntN0wHM0@C9bsPv}7uZI)HBuIGYg@$ma8#a25#r7@$vbpa#W`zcf8QfZmo6B5H1_L#0;Sg)| zS#|SZs1MtgXr&`Elkuu0rc(Z7mSuM<;(WZ_x|o4&%Ux{ZrX9%~hnS{p@ZM2dzNWT7 zR5^0NhY1JV?vnSx*K9c2M2F~?nS*?UC3!QJc>FVUnQ&6S#+BI@fof{HG^dqp>Z|w9 zzln4YOb;#(4VB!-VqVfS3jW(cgy60346r8o96`KZmS7o8M&jrq`3nQ$(u z=CGwfIce-J$aPa9F`j#8n=7S#rknCY{%>R>EeV2t`kO9nTh%JD6k88`q=Qmr$Hd6X zk;m`JW&0K(fMnswWC{Q?4kGxdCdO#w!Ec?HOLjuKtCx*Qf7+hDi!Rw#MgaUvSFAnR zn3MmLj65FFICME^3vTe3BI&cS`I5TF=7Uxzz6_xOvt8>f`aH<{3%0f5EZ-tN``Ob` zZkG*qLVlA1#w;qG?|=eF%ceKLJx8V!B#XLfh>e&#$Oh0TGQN0DQ-oX0aS`v^q}~3k zzKhll3_+R4B|WP$vNA-L(H`P3ni!(NE_J?jEN1R(Lre0J{j~oTY zi?ZAXZw;ymlv&JN`p{!AR~v*|^`(Ml#OFAMFo{wGH`+GDDNZ0Yg~EGI`=kjDTd7)WuwA38Y#I z$TiRPM7aO`&CdAG4-*;P@q&8}4(rj5D#!&Ejt`PB3HOPAE3Xam4|su>?P z#1I}~nlimAzDmLTTB=QVn@QjI^3>2^*~^!e@LDQswCby}wteyPQye&MO8KuPGex z;R`(SqoKQz74ep;Z=dtFM?n$#mPb1-#DI#XJiOm-xfeZG*j8zD) zt8%QwwRm=Sb=g*_z@(bGsM8P9hz?#l=`@#E>pJ|g2pz4(XfJ-u9*ib&rYvV3jygYs z8l%$TAkeCThD~+_-7r-&-B&-Jl%0;a;>9k~xk5u{ik#S6U{9@IjFi<_;sdj>3Be7^ z(W4Wx79D-QFJ;^|=Z^1shCX}Q^+0%boS`&6g}BsYNs)iQ`?T7^pY%+vZ)8jUSru_t zgVpSBW+){XV_-ajV^c2{2j}Y?zaV`_8|ZHzQF=<#BJ*-jtyk0-a^xh>zB=fR^>cCc z7WO|w`K-@iiP@TfG`fRH{S{G?ncI-b;!4+y8lUgHXpQG}rdTqE)*aY>&U}35O>?AL zO8v-3rm%)CB(i?>3%dL+A-#?y1@+yVEM{{fTetJP`MhHw>mT`)lvu6vwtB-BF3naH zYv(+ka#?hFaBoAVkqnW5A@X@WQbo@3gXBId3`SR5H-RkiW8h8Ayl&u~0*ao?VZM1-pUk?an3 zx$Bq1)o2}E9bX*F8ol-8)U=AKfDDj~mL}M*^mlG*YDnCAv-wQtf8*>egBpn%b=}}I zID@;pyEC}EOJHz!hrkT(?(XjHF2RDkySu~aWqDuN>|crb+7k* z9@q=I!b$ZMK|8}itkhI_-R1~ z0oB}@_*Nz0#2$+Bv^t4{yPCh+V3%F0TWvX@rxhu>3o3@9+-XSSMM?wiOWgHmw z8^qc-35IY{f+<5}lnqy8WTb?bHnz^b<@?^%#7YqZ2NRSD)*zA{RJ*K8bg{km9bz@u zC$%ox)&c1`d$A+tgFSm6j1gxe?kZrQjmaMY%U_oi5Uw`nHHglS7F>>KnhCwndUoQp{)^~7Uzqv2 z(bo@D-1{XEthl!E8MKL_=qAKo9GydHmqP$W10F~%cionB*KPSSI~Z7RbJxYoR+FGu7n>!K|n3-cyYbif9%QVE-*B@`OXLP?cz;WD9vGN`Q za@^oaBj&Ch@Ia$7Te0fU3sA|z(Pifx(RblC{y-REcc@b}b;syZ6hw>jDNlhmi!H+i z51hsw3EzVB!8=D=8v}_Er?wm34Vm;n|9=2RQR_b-w3<~?fbiw|YCxKJ^EI)i1xWfN zH!e79Qr96yDJ&(sM6c9Ed86GIvnc@?2RI_9mps%dn1X(Cj;qww6JSCX>fUbwMv6QD zeI33h`1FmLhcuG^8LsGr?>MBfi4T=LYrrmd9GB3>iO-0%F90)uJ@gOUv_2Q7z1HWZ9gM45hNP&B_vdms`#U&aNH1w;-71-J{Kcq||zCP9hzidX!AsJ&5hwoE~ z8k=SNP|;~nm(PHt74JU;*K6DLZjGz=bB z9M@}3lSIZe2%-?ylD*O9uNm#x?=CKof@;deqn|`XS2}(%-Fu66W5LXbQQ>23I8^Bc zr14m)P(qxX_r`E!SK0Vt&9t-6c{;|mQs&2~nc`5gy-#(Y`5V_hJefDIsBe8@+cW+A zi)T3Jm?zku=kqh!Xqz$99mZkrZ`+o^-EU3~4*em_slCy%-^wr ze3|a^s7HXZnPJNVMctJ)TkIl^b~(PM2yaum0$;_hTZy^VG^O=f2-K?Lznq+i-XKZ< z@L*xiy-dT9BKHN^vZ^s6@5a7G$#Fpqgp1&eVi`;k5~G5Ec;ETB5(jPkPW9j{nYITz z;+ScNj9$@RWJRE{U%dstrKP?WAY(ghB->lEC>ml5o0%hd6o;(jwASIYdkm5Vam<^O zT-mPZQ~yL=uc10icWn5qNC6Kxnwd}}{W8?nAFZP^@^)r-6zA*n>4rLHm{88F^UG>0 z#JhLnBteGpv9mRTO8+$Ur^Aw%4xbvfnwXbDfHWfWnQ=G$nvABGlS@Ydw!LbGCYLeI^ zyGZNM$!*h!vMyr;vdE7yX^lDNV@xvqP^b^NRBXdj!x1Vrb_W-;rapxAxS=A0Jb1H} z1{+~f{YOvZs`_jS1d4e8ab)La`t~x=EGY4m(^hi9^_wz``#nlO4$s?og)7|;yP3Cy zQp`efQKH1MpD(g(TmGV{hDM42KcgfR*#fA zkzDRz?CSGR(rUYr{BoaKyTV-I^$8{p5a^gvk>0u#h`lKaV{IIM7* z<%$%gbyQE#H&%n+8P6ocnUd(or7BWN+?GC*f#uo7Wo1O-T~)Q3UsUw*EoUM z!B!@KQQ8|~Ffqnn>VuG3c;$$x{j@lRp!KlWa-IC*pr;)|L&uj6R-%)j#@vi3>XcffPxa0-t@@l!iPKrn*quBJDyoNAd${>90 zkzWW7t)H;G99|{iYILtH%_gscjiJ-!$q5chgk6NopWt=zmB%-aQKbjlWOFC!IAdTf zV_a_5pN0`5akg9J%+$PIGxN|g4!BUk&kcErdS!FsIZWm2^$isG6s}*AFl|I;)~umk z`u@s({qxJ&JJDpPbwMJdls!bE!S|OyZ{2j)<(cj3g<+?Z6r9*4%Adlk-|kZ5ADx2A zU7=0Ix=)$1<*`ZbD`zb?c(k=zWOT_b%f?-RtPpf|Wg3J4Vq@XJqdJVM(h^Ik7NXu9 z8`PWHJzM8}aFX{Hk&01fOY)gM0$Cf2w#`V>_4hCLl_BT|UxQj&0uMwu`o3>S1mBrO z)MYUz!XN~1Yz!xCmD8mhGa_F)6iGtVF6m0d13h1=yAD!YF*pkQJf*pZ2lhURWUXk% zyQd_|{sV}ZIsE21yx8`q@?=dA0aPvzEv5(s-oat;ON^5O)G+`13D1AM_F*<>T?ik2 zrHdf@h9PlKL^BG&Ku4XVNL&M}DylytBsch;Me+WhovkQCj}&?znF^We>W_&WA!bU? z@Wxj%HLU6X@bCXqy1-}Swe~>BH^i`QsvYR2pQP;1P{Sp#z>klBjwrmD-FTym_NIdf ziE>HR%g>IJB79W9{(o-i28tcyzpHM}+EN5BG(R8=ezeg3$2R)-&k&k4k@mw1<@iS2 zoN|SI@7IHD337!seCE{mOd4j8fT@3IzO9O|m+!%_-s^O#mnbuWd!rcl31tpdQHg*B z%Q)U>(cF!Rl+1yWlj$#z@}tJOi84BVv}Upo{BCnWlMG7E@b`^OtQ(xH>$8WTR^Tl;>8kep@y&@^m>-(zI6aIc&vFLvD@D?%@gn(qhnXvkC zC!r1XFDtVqQFx%3nG0Cp6l8lJ(RgHfpR=Omd@0jLr0>AIGC!rTQ8{6bbPr<~o1>6f zqG>CK4%+GtXEjTt^r1|dL4-eBI?9`bkYp21Xs9nAV!a6=SA?mbZ&R99ZjUjBa)yXK zjLW_L(j(I7>4Q(ipfunKH$ye8of1wk>=jG5<0Mwh0PQ1}+AHV9$lGk#>7GNJM+m+m zPB67%HMTL7hbzOxxSCyN)*(~6A0uB2W-vic;~yBOPDzr+T5F%|!|s``UbI7JhW-H( z`WLbklb}3->PodXbSAMJ_Xq1+88zLp>vg4V)6P9+u$V1b+fZ7VD0JY*(K~3Nj z5i!U`Z}^OD>(*DW&8_u&X)3R<5d38f(55%*$Ea=V5$^A7rGJ3YZ-=)+d69fJvO^Ps z7QPn?+X=p<*VtAa6Zlp#Zx>&reR{NO%pE9MYOnVW9#pjt#Da2+Sk|H8RdK@}Lwr$n0kxLcX;G~2tR0`)d-%9OxWk*JJuec8PQ(Y{xuKkoz1 z;c91uGZa_An!emOJ2S%2*k9#H#agS{(qp(5k8Wnq4G1(>5+K5wP0JZBume$l{tnzBMYFB&@fCKXHq7Qet87Au}mHsg35ixel zP61CX2`YRyQw+&!t|LUCHB868wGecRt4X=8c4b8{m$`emF47(SU^%xWt~4zPZ;zw~fem!x z@8n;#?0(oU&D~ZN+24n84U&Oi?QQHzLg3NYk+xVzkmtOSLn6IRO~}%vXch`V7wA-* zWUh3vE#`gT`1oiH;&Zze%3i;gT zpS!@XzWM?~_p3McIR5L*Dp^GDMgJ6naUcGXA=mZuWhBR>E-?K0u2MA=-$P*g>eni- zZ1&fvz57}_`mhHH(;oE02(RjAbCc!QY&VB*+HljKy*F@?B(qpfz8tkv8ORS!6l_1B zuGM*}Y|s?YG|3lzH_}KL#egc`J=YrV9j*Tdpmt%*7jV8_66_I6f6fkZOS4_p9J(>I z!(=3Pfk-w^$%Ad9mC=|QT1>AYrxs!()NqBMFE33#_`{ncpF6FeJq0S0EJEtch&=d! zdGEiZl-H}w93!SP_+9V4C)3)Fya~B8`_ejFtn#VIsaPTYCi6s^jdD_KjBoUolq}nBrg=rTiM(3PflMxSjHpdG7 zH>H3B?^HMuMoxXQ57nnxmKar>9j^=jbdu6h*TxXR!RdBwCk}4IzU~U8{BLP$IhJh@^%t z-t}*~Su1{(9ro5mN8NR3wLsI`T$VY??`3JTthW+wYG1h~xz-u>3VuRzB`*O{Nh!w` z(^M2B$|sqV+YQPoNyttT;2nm=;cbi`nn~aj;sNXk=3w+!T0XcD007hg&5LbR@9!J8 zQ@_#~w@9~~Q^JmpJQlZHSGi8wNWK00B*5?3(j(z-nU`X{{@;p8GW{oeNufyqJ?kQ$ zZu3OC#yFL?bU3(9pa<795bnQ2HkikCn^6z1fUCq8&B|};kBd1aqv@8T1}<0jN}>n$ zCeB73FCz{+j)9Gizl_ADw96%lCcD(Qbu@{GR-012{UW*Fym+>5(Xk%}YGmXY{Stirb<;%S$o~ZV8QYPb%Oa096>y=2yf^ z{89^tcFsdv3JWq4nx6t`RET13%dV0am+PzWsoR@yMfMMxnZq-F^7DXCYHHr;XT{2X+*~b}Xl4#f7S~cc_-%}&-5OC2FBecb(;QOpu_EjBsSaj-cbV=a5myKG5?Z%Vm+6Dw18e@pmfRQwNcUR*J@ z5Nbp@Px1#PGXHQns(&9d)#$6x2ba@+Rsy$NSl~3~TTT1>Cc-{s;P2Wr-VMt-D3yIX z*Iy_g1{8zW4*aDjoIyqPK4|v_xXMp zj^~<_1vIn_^7#${lHw0xHu=JNuNWndv^9+K9f$T_cKWD=Qv+H-9V5Cg(p(2F)zN5# z`aHFvrUvQCB2JEaFOpmq-L_)wps@R`?3Tj4eN_i+qU;IUYCheFGV$op6t)07>E0I? zYa@-$D)ogT)3yrtmjo)ts7z(_fI!_sI*WE2>c=LqfZ9hV-t%{*L_*oav!)6))U?^G zU)XBv9--^C`xewB6$8kD>9)FdIjTvQUKsWw$>xgzT9H@iAEf`K%wV!cGs<-Q5O znSscSGmFgV=s9HHLqnaa^klP34W>%zU9!C!=gA4I; zx=elU4Rn}7GN9-(|YP&rwQz&4E?X7){s zvOv58eIffh-#vWkUIRCKVG3o6k_!%v8`*BnatM{Lws|_S*Iv&Ge8$eIBt! zO?J^T)e0)jfRm4zi=r{j0n`%qnue@p>LP~eE2d+0_PUKUuLKMNI)H?lT{GpslCaN0 zm=ou>L0v}iMaZj>KaH{r&cs;JYX2r^-xR_Zq|^M~rV9f0&92-^Oh~CAV6e-2Y*w?J zp82Aw03+vKzq)#TmDxw?GYZiCoPj6^A_l2$~q_L865w3t&Lxp&0{g!FK{4H3!?N zb*4MU?v*VM#1;*mEzE%m{Bl=Od8nq?i02zjS<)r_;%(e&@F$G$pGwFQHRuD`Fagv1O)L)!`(Id15ijP?;7zv4`zqhd~|-(n7&=M_*u zTnf7j1yaBZ3{#c&4=DS}2JqeKL)*OS)8u&#IF%2yMc_%(=>m^v%$BMBkffvx7u0>K zd8CHY2{z3T{Eli43J=oV&^z@05%G+j#4^eT2pfVX3mQUv^EgZ)~o+ z_NWSplxdzgU0=S}R1@QLq8&Ybsfa=^GJgD1Sj0*=F@=6>vUa5^;IPe9`5vcHhDOw^ z)X0yVF8KleoEVIAbmp*>4V`n;U}-NiQTV@9GbBUa03eD zEIP}02bCV6jKQq%zpa)ux09E>x#(>aM5chgCO@#S4g*>B*Ipb}J!L0UY?CN8;whcB zc5S+Z);N;KJ29b#In@PxvPRth3=i<~Yv@X@I0;Q0RLsj9X=X9&=>&#I06s>hyl8A3@s&`;Y=q7T2}7Ldhq_VXh_sv25#!w zPc2l)HOM&acg{(Xb!r&hQ>P)x2NR}yMKJ<$ckv- zY%O|L=bCb8%KC&$*3i8r`_(sFk7^?)RBkYYxoDWJ0%gCr*etMvA`e~c5|%UYeBV*X z=UziVFaLDsao;U|Q=3hRYhE#uBJ+zJ#{*54IXx!1#A6A$D5C0?pP0@_In9(_eA6W4hdAL7wZ z(j0M6P=)j<)A$rmLQX=3EGsK3jXs=~121EL&rO#|m?Cu6`J-SWcthnKsqMDqwL5nD zpydJQVMMT=^ax&SkI*1=6&Or)isSO|x5WWdzZ#2w8)@Unt#{LHi;;}6<=ksRxgH4X zAkKt{Axb;u<`B_A7krBSTuE1DzN@9NsK8xYC0h)t-F4fLYnPfu4Mjg~4<y2#Qa| z>u4I>U(zcQD`}x`l|#`7zzV{`GBg8EI`~V%VVq^4vH0)K^n`48z9{c3Sdv5!pgZI9 za8LF@Km)?6z04+LK+Hx#QZrA>!xq@jz7D zdnptlP?q&!6ydI-y&Zvy9x?!Pm*USev_kBboUnP4zn1+{em(ke%pnK2P-s8J(0+wD@&MdS|IMq~#793q0m>$@WQmjpq+DPB1EHBvO#-f-J zVma7RSU2m>5v;_OwH9!p-a#phWM?P&s$d>!RSsJYE$+w;^MYlj*tCN*{DfV%SF4fM zy(Aft!r5&et`>9ud?t*dp(ZHNNoru<2yQIMp_#Vug{IjXf&Tp@CXqEk$u_ythwEmy zL9*zmV;5-CE;R-V8|;}xyuwF{caT7k1bNWs+;90)#s>Bg_}SZ<{o@cnn?8&;%)<4A z@dt*YDL4(4A*r)Cq#0Go1?S;ASnXj<^MP73S_m@{#>tlLHxsdVT+~0n+1;NpAC=yW zI}SOge6OaSZ_%ivV+0;c$DIMrU_l2<6NpR1zPUZpSht=EdZg&s?U7%-qLl#%)KdDsZ6@^&Vtd($N8MIT1~Swq z5V3gHskH5mBL|u5tL}DkgE`DmZBzD3xGyTbNebv;st1zF-<{V);VY+zI2&X%h}6L- z!{%mG*22a@d@#Gv7i67f*VJ{Fu)&9j2Sm#1*@bBd8MESDsKNHcwho!%6p z)Be3Ux7roC=Lv07bQnNj05Uuj3{(ItGCWEQJk%B}GR*36RZk}!Q@D#AkkI&U6)X_o zX16v|8!IS!w#vBER69%Abd*%~MSi}t-rGslE#Mxy;x(#|6#Ubw z%Q-E}J`?A)1> z!en_x#>V9hXj)ln>|)R@`jKz%fG}+GL(8A~!ou)BJdc%#mX8Y$G2jr~nxM?+TW=S| zT1JKVFO=8&ck5{9+;12>Z)cGURjONZxARzuk~27$S7=`M0cyC6QcY&YqhtH%~ao+sqS=+8eLREB1M09e*_rG|ft<-nVxIt__^; zsve)?S?Jew8l|mup>ruE`82vhw8<#tf=eaqmdA?uz^6TWF)Vy~eK_fUhOJ5DwJWQ2 zInQkV%645RQg+h644Zqp{U#0}T70)ypY@6LC}PATcsq3BQS&{5a}K|k=#Ag~zpId= z&GBG|E@xb63bb;>My3NiuyjIqYL=0Lm6GMQG0^T8@Hbvz2lB%y6M zlZUe9oHI^8F3;zi!p7n-r=0oHgQGc!n=2gr$3^-@c5$mSSmPVMpHoxo2k7RfFJJp( z>TFg+G14r@0KIc{oI_<2v!GSI12CP0KD?F1+bbDyQrwV}sqx~=^adV~*t^q{CCX_l zL9sJz>g8jss?BOk{tRyDuy$Tq!Wq=lURi~Bh!k#iWa8O}$&BlLB7n)Ybhi~yvEOt8 zbDk{!&V%4d`K^HkH)j0SJP3Eg7Xfg{4q0-vZU;)y7J#)BFm%87I(XxVhJEqD1~$}*|$=B%19{1)HS<9>tPi(0(NJDXKx72OQZg*OedT?xl|MgyA-JG{{Yua1{7tEmH+ zL}bhdhH?8I2cD&|o+#CS_I0>NTPx6hdWYA3Zd6(%JLOiX-LWY#Gx5`!^(pEqtlC%c z<*ulFQ*$_nL)w+I+zCjRkoh5?_vr z+hqpn$Se>;c-8J#T6W-gTEb3~axPG`)RIs8aIvto!C{vko74T^vgoeG5#es0ce`g$ zE@G<6xQTfRD#ae+mT0`y;A%#;pRaR(f)H_lCWx^BwO1WAwv?M|TTEo7+RoU{e1(Jv zF{HwXU;y-H$=&NcuwbPzM3wx}+lNk2SJZ$N^}^r_ec9jksw&&`SM=6mHPg zjuXFk-FNGD+F`qVYTzhLnIcGopX$Xs7<0mehCJM%b=IG_-Rcv*Z?);a`3 zQdc&hbjIy5ersskQzp?+v_B4cykzWOZE5*&3PP>ov5Q+(h9P#!OOOeKZ`0oxf{U@+#aUEm zoud@{Q+Wb@^ID^ebi)=@RhC!9WzO`(M>dTtVz#H;FkyztxxP(U^E!PQu4VsuwVcOe z46(9kW#3;9$0{zaEKaM9p`cMbqjgU0u4+Tb@)8b%q#z`g4hC^?6r~U3hi$tboTJ<)MDPh}*u2{99#u;S(%#-nK1Y1xh?59WAz< z9WbAw`E03Lw9Ao%<@aJ~F29UJvZ5N5{0}oaGS{@SN*zWFkv5ysKkJVbdKY4|Xh278 zUd8Q;-WcP`ySYoE!=W0FdL{;%>Tc8EQ&Usv<`GInA!b2@Z_VI51nC(L?V0U&L(9?_ zDs8GiJbw2YndfG1<$>4cHLo0T^m1V;z=;cDDLoBw~M7g)UI`@oOZ+cu`TT6c(Q6;v&P1>YC9Il<|uPpeh?vkswZ1IowUQzkDDS(blm|1#pK|Fxf3EQPK7WcG}w{Ka~L|JpKiPkLl=uWh8o0} zC&lK^_E~AnE}BaUOk4?Fg;&hx?AvC~Pbx!q5FCN|$OBD{*{Tu_!?_^oMMrvLe+jb+ zcV_|qqlGt9b5~7S3cEn}_zB*a^bd%%jgP;RKFUk~)kK-?#t@j?v7q%ThuZnQ__F%b zq0e9J&M@dPJ1^U!+m^>P`+b=5X_)emLT?{SNTsmZ@f*krLm*?iO>yfJCsDdU@g=;t za3_Tx59gCnMH5H4iYvpOulKraZE!@(pD_0+uuOO!{m}Z!^X&b-Z^!)M)Q%JR$6>Zn zzHV}Q6-a8IOBieFXs4c0-i9u5=$YY=r9yRA2U7cfDS>x%%fo37VyzC_FMc(!NqZQ+-QzkNU*5h&X@Uo^l_Mf@E zsVyd?^>hrU;=zuN7Tgv@wPbgX%4!;?HcaaPCB$-5eWs$yd~R#n*q5*tv7BqjqKP@O zNnzzG-!s^>xs;OzxsQqK=nq#dbxkB4h=Z2WaB+?^o|4ca4fOV|-&QSO=DogMo%bLG%zRBR8lF#=sHU$-VZ0<$`Fng925w`O;B)(=r#Cc~8(AlE1RdNu za4d?};pUn?4}Wkm9*uq6fpgZ*}QgL@O-0W6=zCy?cnywY2wB z(j%t@`3jjAr#i9OZ3p}S_m|+TcEUbFfuH?EvCo$0FkgW@9zV5tr_-HB4;4c0y@>O_ zkK=<__9HbqWlEzu)w~m$MGg?%0^kp|Unqkrol9jx<1v~NCJCkVqoFaVwb{q;x5(5> zLK=+-A-LiGWSwidoZxAb<}2Nc5)}Y%VYz>W%Na###Fe3z+v(T zgI&k*Ou10f-$W9=*3NcQO8FwarLz{dfrmD>OG~$yqlb+USnoAJM8aWINPKMRtRFmv zGttOGn={oEC3pC%OS74sjp0d|0zb9o$t9y(R}vPNS6Th`U9Ib-VfenI5#JDr0)%7$ zN{3l=45(I;J<}%wqWqf7eIhSV7&cnV*T{67pG=Emj9qx)Z*i3xhV$B3T$T7W9lHM+ zq{JN=@&k&NXajo_(4-s`&8IYorF9@pk0?%O{8Uv%C`U;Y~V7ba}lAA!HeJExpP7SHJheH|N-jnIRo3Ryoua_#qJO9J`pe$Ko5m zIk(t6G0pEd(O0Cw^Qd>isC%h1`VGW1Q_b>g1O*Uzo6xeB^pa!|W9?m}Ckn^+7XEyU zc=x;0B?a-Qq}YRB4U>~=o9v1}b7a3S41C8Iwqn_8hFwL5S3=30S%F8T27fOL{{aFO zHh%B>0ZTXc&|IslY`L*;=gj6N|Ddds*74H)5PbVtG4b((QR_*Q;HLO*r}=-!VE*TV z;|Gkw5o&`BOR6BFaD)7A9{1nsELyJU@B84*%XjN2a$t>NulKVWmTSLmpGZAvT0|KV z-S=U@$DVm=S&^yg+5IB=q<+cmA}lEmozJ8VgCD+hQGS^Q@rd^SuMd=`7@eJ`JYS?R zauINt#Uaji*`9kzuAU+|(qbOZ#2>vbOaDw+heYEjmtu>mZ3f+v1B|BLsZcM-9#dRk zADBvjjb7)&aQ+MN^=fpiIm{uN*eJ|6+y`#piOWT*`J)ib9eXak_AGd(dk$}LoIPOI z$ca(5I&{SYfOMJ!hq^CnQ=LV1LES`U7K&^3C)V8eC<*P#MLWtc!CAyE72GS`;+0Bj z!c4PysW)aNA>dzrZXQ6dH!o3)xmQ#vb2UANvX5n4793BP7))xz9yX%Aq;SW%aM?QI zoSe`jnNk6BdY@%7d$%T!KXL=tpK=1oVh-pR4&{q-|lHWtE_^%2D&7Q#e1bySj0Y{QYVgL zMxUP*dyNT??Iv{%5RU(0URjA*C8-Q%G7bh5I`fShe4^67a;SMXbQDW(R{3Id(qdSU zw*Octwbiu@7Vv&|&gC}(TF`J zGB%3cdSec70nqi0>g>R^AsAdjSx)Ad5liiyAdRq(U;+`^=|9$An{>f&=r6jo2iui- z5?d~^Fyr!oq%xTCg2v0%}5F(H5df8 z``uoow)!-J*)6eaUITEfg!0j31== zIu}F3CRb}>pAHH6T3F~#9@yIKYYMyukxcjH4H4u^j&6uyMvyIt7!b&4H~z$dRL5RY z)2cHwA+Dxx7LsbW8DOwwoF)G>2X~s~eVkdKoBrJ0zUOwkXWKNM5T3A|o`V0>vop;L z8P{F!bj=-;+`;B=kMO>`g#G3+X0h|-lY(ayi)<#jZJp(7%S})Fk)tL5RENzrgR;9R zK@SYr7iPJM_jSw;Eh)pADmot6WI2xP68`6KbE8c+u*wYcM5joJsu&yF-G zr>ewRK}?n-b5=I?Sn4?c;xCrvf>#`lnfWlx7I(m_0Q2gYSbQiMtS|*P3ou#OWv8rK*K>9$F-#NoI}&X4-z8ST!nV7mjwZ)KJ*= zlJsa~hhcc2q}pghBJ|x(3pZDAokM;x1NAX4PcDfb2H_K6yoC@E-ZRqQRxxxYmk{j-bio=w`If`0~^eoH_-M*iy z+I6_JBb^_hG47lU)pO*d{GqU16MWe0sUZyQdRKpp9Z!#4{G7!4vdWdF8r2Rz6+Cf^ z`@>ldtYDPjSrkkX99|1dfrO~>BWs`-w-6^0S`A;U>#=ZC16{H+tfCM`$(~rPW8)f+ zJv-}&1`(p3E;&45FMN~UW0xd$QccYI#u9#i-il*9p*kQ81 z?T0v08>D_1B*}lE#7!PLk4ND}rfSY)j~XN#sAni458Lu)?NBLt~Vj2zKC{_NiXN;q=e{i zk8?KuUg)Ng5vCt>PoW4wc@PR*r))*E-;}^HtM{Z2T+$pxo`Z}BBBx%P_&LS#2q$rB zx7{$o|C?)-iS zuL&y9$ang93&pBoonST_JNPIJ?Z<@~4k;Au=})nJO;9?3oFb>fBuO+Pc5cI&8ozyxgOMa-su9uk?<6rs2TD z-RJ$O>t9V?H{mH(|PsGMl(}k=)tnm3tS-cP+j=a|0ZR7oDao zg=8|_;gcj7$EDip2rZSY1`~Bq==Hyx>SC>krIn|SCxJf)0v^sS-w=t3%#t++A$SXC zDA7yz>;q*>2T8_Vr7>#e`b8T0o^FKf>Y65TJI znNhis(p=BWQ=*vFC;-R8!VOeioEIJZvm4|UDLh4DY+_HNz1O~};dIi5C7}_b%K*e^ z+njahwYg?jP>Y&8jrI3Bt}1=3bI|_*Fu_}kILG;*!A2{DM2q-jLeUNrau0Bl3FL?K zSnePJmFGo8Ar{B~Mb}%vwiRvNx(=reL&MD6Fhj%4%ndU$Q^SeF%;YdLGgHIhFgD~g z&_DxyIp@Fk>gqi`OIzBur6qY=-kxiYF~^sKv(%(+uiH$vX7X%CJ41JVZlkEMLV)+o znMI22B3Z*%Lp+@O2!BDlSXQ4RUgr|m<%!vLbxUhCjfEwf5pb<>T;5&)~IXbB%T%A;p#LHP+!=H}x?mtc?n{{q4@S1KD2)S*;Vj!P*%6qrcHU zT-Hy|LCp(Yd@E++zKz1@QR=|xH-hWei)D*UWDc1rMDg_tu43ufU_v`$xFN_gN~`l3 z(HOa2?{E$0Y(>xAkNvWOt%j%K>mUp`My{>nj3CrfPLENXxT!c*(c(q>Y`LVWi{fl^ zXLm^za=vGzT`=EF@@a0ykCT{+4LBuog|&|yb8#b*Ut2mvvM4SletNRZsEe|#b8RDM zS>pQ4oDyB!BuDw?I3K>c0d67Bt{HvVS0UDPl*OBd=2P6`Ypm>AKSwV?9$pNd_Fc;XM~87~YiINnXzz&GFfZ<`~0Gd)#7SA&kMwB1Fcbzl}XlQPlE z0~TeFgJ{EW%0kt2duSH1FxuBB4(-B=;IDkP%fseWQ)(qQ!IDeQWS1F#fzfK32$MIs}I*$#8M|hBZn-W z;HH%F4cIO_`04NuZ4TEC7eu*m?{}9A#47Pc3hS=k=jCMoe&;lEmDn!w+*WsRl$Xa5 zV~YlkYg1W_GO{kn;Iz2`EC@HP-|>@ zaqAqQ#V_Wt>+BNZiJDEY*etKLt56*A>Ypf7hA-`3R~3Da(fSB(T0gUK>7DE#FLmvm z;AvQNY3huhE%HbGehy=Mt!|0-)re%tdF|&AlYOfbmp2f;Yc{$ifA)-&TrP~}5xWv% zFF^Ken$DZ7^qH!l1?Mb&0c7(9H47Z#BO?^CB_Y9w)Kp-}mH7vjP;5ZQFlv7RN0Y7a zB7m14%pr4N2(@guRG195Zk%iaa-m{G@kcZyMXm_~oCZ_YIh}v)0>A>dV^FhuahAQUo)O?(j$d2tgB5~29Pv^gI zuTgp6c0x5*=2#3sdNDRzYI+$h2Xp12khP4iIXu_0Eb{L&b|VX6%_ed{JASVsHujG0C|k=D-62*Y+HHb1*v4kI= z@7w&Sgi4w#2#n~^iy)a<-0@`#)Zo z|6+5ncON7Fq8HQuS4Qe{?jd*G`urECo7IS8HL$eBxWZ3gcaDqF*O0(w;ly_ZdGt^C zo(s1?dyT#wWn~2EH=cxXd#8%$Q&ckxqmJ)S$VEgg{0tCV#p7L74e`;HepIHMO!n1k zcirkWAC}X(td-FPMo{RPHst|cjhB<5bMsw>$H6XxVRKnzX9nSMth1miYt0v(J1dRc z%2qyQ1pQ39z61mI_lRq>`kF{N((itstAOGIg^dXJioFIB%xJZ4xZdsm0O#X$PmvX3 z4Mc-)OF?t(tB-yi#PZqw-L6mguTs_gl@&b`YZ#{8l1RhJI}MoqY;R?xdv7&?_nS%( zO?I~^;JF(5bwTFioLXMMQkSL``Su$k{ZFzDss?{$hCQ7zdU@ahx)YnN5HvndGS4@l zItP5ZP>r*Ff?GGJBWHaJfY2T0z#({iS*x1L8gn&gSi`|>?Zqmflg&L&w>yM4OJXxT$$A6)Y~--IK)H*P-IB7>S?;eaMCXsucNFFnm6ff|5kNo)VFB(&*KR*V z{z1K`V~B^k;ITDuzLGmgzo8 z6Z&})czj;7ltvtEx|D6Z8CA3^vntJ!W#;eN6Tx;PwRhUkV(q5`)$RC`py9PSx4}Q8 zwf*FhC3odJXId*bsw6Ppd1@+(V)3zc1TaYe`DNPx6T+hn+jPHkZua@`wP}Zxi)1Eg z36*j7IK#>QEDl3$a1qBiUS0?5(u}$_1I@FV5O`28Q`8LZjyr5W!yr)VSV@@9 z^`j;}lA5))+`B{VSF^dreB5d3gF@_VFJe zqlS@U`tg?6c%jogOE75pAK=39gO+Nyr7Ne36M+F86=@BJ;c{@L#>8x1#3`dy!nsiadofmMmE9V|1$6lzPssaT0j+^hjG_@>~3M?eGolA>>8tew8u1@W6s`RQmJm z3DF-AlGe`^8uH0?JACPL+|Q)+jJ~rv6$QxT>xv_X`Kc0C8h_0Ffdu(^3!`gxG|Zo?Vu*xp z7W$D2K995~%RGUAp1jgz(F<(F#o8UCSU(oV48|r-0M8a_^DPEa%#j_pv&YfSYHP%c zIIY8}nN88*-yf(i2pz4cMVhZ-yRL$Rd+Y6BNSZq=$ZIQxdOfIloSHmS#l z2rpGw{PN%Wk0Ed-r=155kmKR)GxxvxNMdWt!mgv9y_Er0Od%<5?+#{myJ*+?N|T8_ zWwcG2`}X7GhOBGEqq&r3O>oa%%3H}+zB>oWZMsQd&+~e2*M8R;+kt%C!+!vlzQC`_ zAV6pBuZHWF-W|B}wS1s`CRRXDxF=oer~&8p6+HT_zM)Hy*xR9f+3=Q z=&-Xc$n73!eUYH4m0nOEmyeeYzZaF8!ZntS;b?B$A5Up24OS`5^qowco#ppd<1ZFSwzk8&%5rC9m08KMSX3cP_{SlsDq@@2 zZq$kf02xE;f`;2M4Cxr*uBy&fc6F0`mMYc(y$vhmY`pwcnG-n*j3#Z3X_^xU^g(ha zKo8{G!K!P|1foGi4&2Ho59z01DS8-9vdu#sgo_h4(w1vY~-36x8+<4 z1k0ae5>RS)7%B`Ju5)H%40l>wscg|7q4lgCl{8l|TEaBI?W^KVzCHgxQvBK8HV1i- z-IoV~O&>Tx6ef1fk>7E`$XG}-czz7ufo-}6TXQE9%66GBRTOEBqE(*?n3A}< zE%D9CBFwMGWX0d5Ah*g+y63(>ouY!Ih&c$`w`&uHVFjT~Fp*^T7b^aqPp+aI<|qA3 zCt4%P>F~D;m}|+k9!C3pFto9V!!pwG+akeSe;#8z`ZSl?>f2PuGJ&o-xoD;iM;a%l zvjf#GUAK1mmsAAQ*pRU)O-0{eb>7!?M|f*neZpfx7!@||eiS^WUdF6a`)GsMw6E1( znpi*G`1n1pvix^}hUHW>&XO%g9>a{$VBXZ+Uh{P=1yIP{a4qg4thW9`>TH@mbr48**iG*6A8z^9ee|-KU#)w}XI6QshpC=B6d{l4r z@2P=k?0Wc}nh$3P4qN9;?o671>F_C)ahU+yjxlOiat za)dS#6wxT0%@tC*?mrG1^UX}~D$~zllQA(ARU)K4wE+({#YKzI)s_c5%4=kGm{*yh zhnZ7_d{Od{G0QICj-{*CI4_s+eO(N#tG&|R-+GBJ)^y&kEc?oRce{RKGOzHtO^oFw z-isrFg-d21z$UjSI*@t{b&mcyb<0gM&A4!yd+b1vL}d}7zr8B9dXFGqIF;d6IGS0g z!+r)&K#0Fl#_1nmA1nXS@PFd$P4R~xV^+(&?Z6vK8%uB1kt{N=gC2uB+H##*@K@QM zb6UIYNo_hM@MVqOdX??pOMT(kf9OM4YQGqdB0tJweKmJ9z8ks{bk;`7jYp^Xg*nUn5#Y_cK;Vd@Dce z^yMIeEty@>A`(UXSmdJ6GFeyh$R4wl3mJU$5%4LE{1~}{m`ttg&O^L+t}xc z*7=ag57*RW$$pgd_ylf0V0CH`WU03}F`WO*4tJs1&W^1xS2vi#prmsl!&WfCjEQtJ z^6G`$)Wkmr>}J6$#+o&m&?naWRlTMrm=^c)$5EEno%v+UP_DS#4U@(EkeTwmq06a@ zL8?>5T{I3}awQFiPf-#oUShw#wk2dnnD`?4?p;-T)S#EVf=aW5hA&Ld+zR7hm_d{G zhct^f*hXIfUdVl;PNLnVPkWvRD^fc=>Z^vF(Cnz)JQxEq*mStSZ=XF8g_sL)xV9p^ zRsSkE${Q2{OmPj!s3y%;&TN$!$20i-EdRyEb$oI5Io36N&__pY27=_cJ>esE=CNnb zsk5azfiW~mPGIHmV~ShdG>U-R`q14#8%D5^F~1i*AAioRac2MIPFQQzQYR}4s48i8 zQ0B@4ST@`zCmPiZuBMxf?F=hT0s_p?gDKZkoNx_sGDqG@2E0?xJk8QtiHU37Y3?=Ri=*|4ki z)0?-Ct(8h#6&TEJIZ~W^_~M-2YW{iS%Z$K%?I14P>v?#!uRni8(utgP_IQ%15& zM=sqWlF&%Vo{?W@t4M_q+h!Ka=+e7J-e_Bdd3!OlU>OV?sYAb=uf8)ft?7QTxmHIJ zO@6bOF#lMdBAu8Bu3G?YjBSUUpPijS~`43X=pD*ReP?=5n%u_y~ zM?VJx`>V+M(&ePYj;qqKoenwq{6`ME!IGM2r^2g7&$ucKzAF{m@>|!1UCe< znc6&k+j?}%8ihj<>w3ZcSMP+duLSjsZZkWqo`bLCG8?pnbm3`)E}Qe~lO3${pjZ${ z!DJ`ei|P{o?U*q>^cP*Cx-8YW!$cOMVBffFD!}tk>G_sm2n0?`V_A;kFS0MbaZxwr zpRr@K(;!k!e8I=kst-`FWvTlA*G%)#Lcm#I6K@gUFQ&6JqT&~_$ECG zmQWi{C3BiS_%POJESA6iLNhJ^MwP{rHTL)+bW5nfO%3%EAoStpo`I&$)G)zcD^|OO!0$S zSLiL#=L2=-LtLXgkET5>p)Qf4(JOxa{E{lkDXa4O+tc6u;{;pr5b$B%>68H5f4_L7 zi(w@yS^rKN`2SBTg_>ewEhJ=P{bPlv@W#rIeLzigNEE)m%|LbhmVbOxAJ3YYWJ9z>Qbv zoesJ#9FlphaGDBJZTim4$U5ujLI&L9VhW3xFXCVD@TDv@dPW?rH@>L&CaIG-ELZ$V zmDu*X9>$wt7U{(DBrOhJ)p)}?3Xu~MneJ#!Om^eGv_T9Xa5A)QPFaP%C z^IH0pRarOgbi3Z|dUmso+;uxL*`tvOwe7Ejr$LVx&RN9iI&rXl?)S&-tUZd!mO94F zMLv){Fa$tII%L;{iZ)5q+s-yHfH1N@_P|v@<`q;@K4+1OT}rNxU#C|Bwdbn{*+P4O zkQ>ns{FwI>@V8^K(+VA;Z{U zTRe8G$O`=@v-BKe2ZZnu{oAToX4-fN)~d_S20k*UD_+T3jBa3?{$4`RaXp@w9BQqa z%k&^ZEt_&*qtf?(NS6>ect{rG7ykx7yc?D|ilnj`KkZvGG2i5A()lGfSEq_A3MiwL zN?ea_p-`-fuHXfmQ<#YdIE4;LJ-$KE^n_?nb-*hO77wtmaL_wX^l|lUK{6&FPJW%8 zb5sTBcpQ10&B9ex(u%s|-8&ZscMSk%GeWnr_-4s@c3I(s!he8Sv$&w>t+O}OXUis7 z?TmX~((Rxsr&p)Ye}Fu~st&Vep8c8j_XOS7Qbr5=>oo2854f)`{Tdc?Ze!%V_-^l5 z;y*yt%;@WH-LxIzh@h?9@%I$zSJ~CF`CU};{r_S2`rQjMB^-9)Uo--@s>fAR_)Z&1s$5no0bnm*=m|yQbA2@|V7s z*Y(qX00ZBr7u*5xUCFBcdBVO-zr53p*quT1+p>?>(~|l1DNbPTR_jyga9@;q5Ywn# zT##Goo6}8p18A>{@ZwIcSN{qj5n%_J&EwBYh_OmHZ6Fn2*!_7>v#FjLU65zxhtEId znU?AJ;+SAp4!mU)7)etmR56VlFmONF%0uef?q!xRS`G8Y9@GfZsdIVXTlU|3SL3o0 z5#ND14_WTGTE^p_y?At`$nh7@miIJ!r)&@@ZVmwAU?lc;HTfR~Sk+Y9oo;S1lJ-k5 z_m^sA_~++81_v>mFCPv9jC zZLT_WHCI<|;4WtEkDtF z0*kLKbHW*HODh(I&fU)faGejkK?@|+q?ohP(yQhXA_LsBm9(H2QduWTh~SUT1}*+h zQ^XuuA0?La`m3tpnQ-!A$}*A%o5i z;P;eayWKlf+q(M9P+P)Y9~$*&fT)f*Ob*SYosUG1O0|`pupj5 zhx+=tyYZnGx}(a+%x)UbxKIH$8C%rM{>3fB8j=gR8aUw$Q)*stXO@f)yIv zg8gRhruUF82tAI3?j4H8DlH=Lk-H<7#PL8o*#4YNcm6;3=YA3Yn^1cmofTB;M zF8rZ`{XXM6eQH{4eq-yz?71X6O5WCutdMlUU7fy&^Nwh9Xp|pJL872&L%3a){mX_x zBH@uEqqw#{tRPG|i0fO(A_EzPEa9%(7Nm(6yoI&_VY;%f0OqUlw)BXJ3OW?)>uuHG z2?^&fc%NV6>Bi-Dc5_I5Z6j=v)HGl^IQhXasz^aJ<(Mhx>zI*>kXlNIr$B5Z*Xg|UMvL()Yb|S`Q#*J4UP;q{P8m~)BW3~=Oy}D^81~EB1cm6 z2rHN8{CxNLW&yh>7f(T0nKu7kvaqf^qZ)isOkcXpN=3uHvsMrjRVF!<0~}tF&~rcc zv5xVMK$mv|IFhd%f;S(3#kw+t0K8~*7O)-9&`Qx_qVg7rdr7rBCDaf^lqvupkEfmw zvaG&_&ImfaZ(A{40DnH)?&Os!_RwcKhmmayv{uL;Rh*-V&(*W-DyZ)P`l`6(|Cxry zDHK4xmt-ye-ed|5)dzOETEHceIY^Z*C8>S?YWGopeGhZ>#73B0X`ep&D747FK%sPs z*Kd&~N0sKWlcg#peh688h83~l=;*{B3eJBgz5n;*b-Boe%OlLy0(Kt8$4kaMK)lYj zpQBssv?|8>o8kMD&Z91HK1p@VVy5wwR)V|cN8P^QVcz)gvv@U4ql?=8ry;|U zzxWs6)kPgnpev+D|5(1wz2TAl(7(|U0Vwq)w3@{JJSC00oPO`Z4GwqVBEtCR_Wqwg ziD%-MXeOGf6W-W3?EY>I`plv?+HFi(NHwb|mIQp`JnX=vcqzrLY?lp^2h$Vc82JfS z+2+xWDY`~&bmvdd&=fHteOoIVa4j+M8Q*twDy_rao0dnF2+Y~q*q=at7Cy*6ZUnzJ z7v}@cR{=?&wFytY#u%Y42itO5ZBr|x@<_C+riYOYW7Zfsoo!f?#WB1`b}K zHbJBHeT!G&bedUQ653B`b?$ot>!0MxNpktG$MlwgohmZ;RqvuSr=qfC;+fi*m6LOV zxkGBp8z48&pG}&mP98kA*=^I_?K#_oS;t{v_foQ+7utC^E2ZbHbFEj+!Tk-`nkcx%gliPiuCnhE1t6QJx#Ag-fB4S6w z6>^2|yKX8<=W)WHLr;XQh6!`^^h90EYJ`hF*=%l< zZnsHwV4>a&@gUtWGvlBh26}aMx3XT+(o_1~wKGveg`4VC zg|tMn-S~`WKY9s2222~ z|Af-|hews_)=e7DM=>++3ykyI8vNos${!bjN6rkrEzYyn`mxuiugGf19J-Db)4>Se{G7h;``H>2_=tV!Q~Z5!nbp|zR+dUp`{j4< zIIuj^fLe5r{VPcRY=fshv&=@};39t`D#i`V0$Vvf=KtXY%AncLWk@R9Zho`O3UfR{G)l516#E6Se6)uvbb6 zD%CD}_>28VDKZD?_h;y0;{8Z(+(~&E;={2LD$%Ell1@fGoQ6IYoCtjtJVW{%i z$j*4U{7LhcMR6wj1e2f{e|^s6#nn4fuH>7ww5$cSbdAbHSu900o9<}Q1!BFdOCp77C4!5q5bZwZEtwso9S?8O32 zKMv`nDx~2*G6%Q(*G@(c7p(~a`r?cRs<;X*$Ro(?I7j>sdl>OO;bTL4c&3yt1`>u% zSH<6JGplW+(V(OOquubw{B}tje9y0F2V`YLB~6< z0ae+?F2}cf)1{6sY1#W;^a^5H5$T4=S{R3h33KST3*RcsZ>ML+Ry*4l9#6hstZe4C z#vhT>K=Ci1;z|#R&w~_JkHE1n)YT?T20_jpli~g3#GyVEV;n?g+&e;9b$*$MSyx3i zq%9*NUatKQ-y=VHq6kUc3YsZam)ol*@c$y3N>O_xhDBhPTH@+^br?y2keccyXlR%z zjGx(@?Z+LjEok!FC=cSROpor_-+T9ZCI0RtKby1`r3I^&zZ#k@CftI@U`{D&WOp_^q6G^#w8p&i;YMFa903sN^wPOOoPrt1! zmu5pXdBrzx2f;$Elp%gLho#8ra-Bwa1``x9x+Hi9tLTf({++VGMaNXqD{K&^r1Pjjk8VGb$oCK^nL~0?1eb$c`VA@HfvX7Ta!DDgrCg}L+oq*iK&*H zqY&?k7Q+l}*|reA)Z~|ERM#Z8&q92@VyWW*QbtNsU7T{%is4&BPG0Bmm#G+XsY_vR zssdF^Wl1VldHe$LSQ>xPlnA~XVX4sLUnl$uv&8;fK0vEge5Um(zwer(jAmrkF+~aK zJdR<(?hb(!(I|d;-pEVdlc?_z2RGnzzn_lp@83TF%Dt@(;{%bwOf<@&0;dUeHD0(Q zXi^07%5smOA|@poykV6!T!dTxlH3xEzby#8|97{weh`;gx_JlHHRH#$dJu(X zos8QYOKgOigyYSOvR(kio?Gu_nbukSXl5+YjrTsA=RRV9w)ElKw_^unTT~V^oyP}) zi4DsK>gy^Gifki?@`lW8l-_zqG&?Ru8rPoYt5U)q1apPr7>mepSYuU94OS358NkEi zIf&FkOGWMb-n;5!q%FnrM^+tifRX6MM?Z_VGL9Z<3P5Z`cJuL!di%4Fb*zeWA)=!| zWE@?LiIb671=K1b+Tamj3#KWmoG=$P(|7v;&29IIE{5x)qPj*HfAlJ5AU^Q8=XwhF z00h~4X&Hal{|DIqul96OP}Z6MdA$Tmw-ZV8!Kl_ly9&RtTk3G>IMPMRlnBj=8sB}k zxn;3n5@ji}e^;Q>A)aou68jm069z*QcUhbk&&1zP+-RL)kh7XAhYV z6hJjsX+vxWy`9*{uJ~HXR1G45ggE{K&>3@#e@S%u>cqwtUL#Je!9YVlXG%u}k{%k>}m^t1l>_>~qg`vE0Re5sTB!xTg@XF(c|d{57gsOiD?W$eO9pwf1RpA zs9>R4?q{MQXfnctgzsfZQnDIr3RT6f6-fgUkz^2c0Ai{HLc=%Y4-m2{U2N~5X>PB_ zSP74{N$!%*KqvoXYX?(}Q1UgB&t`nOfR`+1L0hejj+bqVYf`dKWsMnCC9-&kf-1oI ztSROk6Jt>oZD&MLa!Pb&v{N;%hU(JnNp~Xh*Co>UjMx;94LugwmIRa(1XI?0B)~;1 zs++hSc&mB2y)=!5Yatjs85V3s_Cj(f0C_bdx}T)kt1-{t#Ce_8c|5VN`~r)^_XQiM z9^#__&G^GW@T%8!v&nXFd$o7TQn_6c0hJlNxRKWkp_$D~9k)E2?ROm?o#D2<|A9qO z`I8=p4lz*yKmltYiTz(hz}M1`t$Z-XzCh`0KSW{n4SmD0LS+7nhO3U8*}4&hHV<(= zg;qcE*+V+Wv*Qn2&3g6JS-JzzKtFwzP`K)gn}?F2^rSPcpt`;<`?1~Us&UiNnMR-* z&B}*FpDff*EHz~j)RR}sLZOG>aLj~cIj}naCEifbve}2IH~`6Dy}9E4LNf;^yJKt!RYNz-c4s{(G9nbSSCz~r7l zQ?44faVRY30i)IZg6XFACY0>b?rzi<2Lze}94X(i^xVkyBT((p@kY%$5#3~Gm${NS zI*2Y@2~kiiHI|+xZdaz;ffS#V@+-}=`{ww_@OW=VMv8aEZSfcj4Htr%n$sGOnl+EC zWGYE#czKBI=t8dHC~!+H}=1tG+&1O3!+Vo4Pw9Ai=<~pTCor9+EDU( z;rLTP(i}fC!N-_-aR0(U*C8n*%<)RqXqBuyIg;i6n>c5U0sB)HnmWa?bSg$se}vOE z`I{~Pnr5S{mn8W+v7};{YowaQ#`g?HO)l9gxDdvuJDSW24wx*MPd^Vl8fl=>*Q@UO5stvTZw<&*?hq6G%E|5maW$1jlD z9U2S1r3<9YfLF6bS3W{=_z{*YMAN(L1LJ#&flFn`5c5gGSTsSL@t(&#uw$#}_4@F< zDu=ey35c&u3{18YM{trSpRx#M`8(j=WqQYC*2Vp5ijgQg~ zeKV>QJC@aHO33)@u!NeGd7}tF<+XQ3jLu|kZy6~y2H*sB7}4)u60a_u1&rrg5o4Y# zm*MExMUg{QzvT0hvw*!omBeEmSuiP~PVJu5FNiHkgerQ;ih|*|8#wiU=cDN~-jwWz z)LyCBvJt(6E8=F}+~Pr&TFBW#AW_|V=i_q+B$L@5h`cZ1I@7kUEC)dhn6`qrzxrUZ zG_c8&9oMp^hhheuo{Vo`V*QIzIYV+q55!bCGIO|IlMO~$Z?ouiRNYrp>0_6vG{Bxu z!=AN5fz&XjoE?U}S{-Urzn2f-_h5<6NL7_$9Gkyv$9wS8w?on0r489)gHt8=2Ye%K z@nuhgFdneu&6)T!$66k<5o&N2oqw(!SU}U3%sgcwUCJmp393bQsI>q-r}n)nUhgpk z7?El^K4<&>1N=?6d%SQH`RKtesa!uLG-MF}17KF>5jnrF9w$`_2Dlq;YR}=kbrXNe z01Ia(k1zdVv+g-To8*2Kv#Vi-#lrv8sWqE|asEY%&cjL3tp7lG$o69i45N) zqbmyP7hkN_|Inde5dOBLwib-P~B<0k_k zzeC540=rn3jt+#9@aT??0|KXkFrOf8t&+#T*aTO{w~xi^yH0K&Uv6jr4)4q^ZNv0? zlKLYf)1AaW0Q&XTKfwF>G?5tFBSx+FvA)ucaHt1V{H216y>RO#A>U{Tj|eC6Ym$`K zQ3u3FYat$wk&WrB_!CW-#vpvHerllws#&hDmst*d=?0B)#W0+*q zs8vEmSy0*>$H%UuNfS6tcw_0<0@utxe7gBhW%k+_6HBC?vU2NDSg1QudD!Qb6}#KNb`qNC z*by)swBdhHiZ1XwqT);_E!SzxmmydZ<<4igb?G`WA#sFuRlrgI1;GycmM0LDv@jvI zJ*KF%8mYix+G1OAsbFWbvRi2m7tjoE5e(yZVuiTAfp?-Ix1l)Uv+u{LgVTX7kaI@^ z@gfmqBF?>696{hVmqnUhX3MRqcBpN)Ih=+bvam7cVdv&%98YAvvO}FSy6A-39`~A% z6yt{SVR#eg^S#o<<{qF1T*Os|a4>$a85+5+s&&89(9q!L9Y9lEY{Ab4%3eNrmnAy0<)2e+{xCl_W&s9 zR{|L6aqcZZzd%lY4w_H?T43$Z$iUi+AuC-LmL?vR@3LOaaaMN8(ur?V2QE4?&-fOU zIUPsr740%#bb_hrCn#s|;%QCVSZsCJm;&QeYzb#q1W(j<5(nOxmL&&RxDlcel6wlQ zS<-Q(CWyVD`Sdd{mM;R2o-P{;^M3MRRs;WLPA+z7&QBRHWq@ZgA6%Hsc*St;{ao`Q z*P%==IVJG%pc&|FXu-nh&zZn&k1hAiKw|N5$q@B1DGU@!n;iW90ezBFS&w?xImgqA z zjjC|5BeN;%`|RI63(=~*qMSQd=qjjhha)-}CVgafWxON;a$9sAnK?p&Lt0I*1a~AL z-WKO&FoND+eLv*)9Fa+6lo%NSP^>d94pC=kPbX6BI#RNua<(n4cGty(x99tKrgj8P z4O8{pTPvvMz!)DI|jiB?w*pkpASbP zg8~-&qM2?EZh6(P4Xrsi#@oWK%-s>qjOdw(5Z{?#0@cM~lSy&3k2>G7wlsi~4To=N zGpe;KA>ZR_#uXCWJ383tn0xOxk|Y0|gKK%|Q{ul0*&B7EN(6>yk9*M#&q>tdLEvq{ zX{yaC?y<5_pWwjvlaS)icvZo8vQt9(dF(sH`L`>9+G7gwCH1lL`Geby`$JMP;8@H_ zf;AgKA}EJZ2!9KNK3s;dw$w#O;VXo@?6lo3so$wS zY{g)yuC`zs_7gCf9d6IGNNU$Ta^HMHlSCqd6LNIR5uJ0ZK4Fs*m@gU)ArAbIF6A(aJm!T#M4`rD7XlB1LOCYUSc8?kB0Y!+UJvkw$hN^FUl* zGlaMmYzsje8tn8IMsl@DW-t$%*yb&xHYQv;PY`qf(B1|)9XAcuL~E!Bxnk}V(`4(9 z(r9^-$4r`umK%m|qmG-&=sfXdKFzUW7$ZMS7jMpoXGE1GI7E4vwb+p;nqW1lVUgX( zzz%+><(tc?-eoA(g)`VLcpkEZM-e(mvBL)VR*g5kbIi`DsCKaiJAmll$m87br<^b6d(Jp| zz<(K4ZfHv2R3iG%rTf56n-aU4%u)J+=UJMGP9pE}5|HriC3V_RlG8HySP!;aiisyC zp+KN$yjecG2va@X;S4#NWNR8|i4-UX|C0;mw95;$4M#Oc-IA;o&98Y&%St*rR9RPc zei4S7lxBFVEts+gho<(damF|Wcr{#Zu>j5%52Orlh;p!wOY7_qCw|T!aGAmf1ManG z*iXHa26f2DP|(MHUF&B5I0t;ker=`E?if`a9n9@&orO<5STZ&poYxqWT?v%}Q=sHv z*H}M`#I2a~n@Nd*VX9$R75hf!0UvK{j4FEJhG6rj(Kt_7-AUKj@b)0bk9A415`W(V zr#v#3*2%-sUeDfn052-ls@t~DxgiY@jdaLMf6n}K(rBy?PTLFOpRHj3GoE>ZCjYZ$ zbwbC)Gm5Hkme(?j&DLDQi09ym1!0lMHo`~AmOrS@#QdU*pUz=J0?oggfW=*G7NA!4 z+Fzwth2i4++!vfMiN%j|%d(t$NiA2`g!Q|q9eu`ByibmmC>ZOx! z+lHB^YA96o;>rXWm;kPNKGe!*p06qvHDnX#$ozRpQm3)Ke`VeBUjSS}$8+R`P=2TY zW*<#~s?z|89%AwXxJ$SiK)(vW<#g8g<sz=fiRu7+9p= z)Lu7ISOOm7ED&TKo9zCDuRW`eJ_p8-MhOWtqjF6g5W7XSz7)?vAFpyDYK>c3+ULR& zmJ(M*o=awSWMR7iUM0m-{c=I^%t1g3RdNw6pe_U1V~H8uEW$yQG5zlx+{U&(j#a}* za=U6hN2arfj+F4g+JjrHiM4pI$*c zsnlW$9Ph6tD;nOp>?cf)*#`La@H%IEnevpPoo0qK>CM^{cNHxL5h>qoH65UROx)dn zpC#V15Fz}q_4o)h!x)Za1CogROu$sINMy<_v$K&Fcyjx0^fL<;Q%)XVxx@bCG%Q=r z8zMoaq?y{J-do#2L62wFEK7u> zZ@TEK$I`&>8%tvz8(iOUft)gMo(ze5&gXK<=W0SkgjHz3wn-p>HY5QVrXR zs4yXm2cM4GkoCowqHEkyS)j+mpS}KYzY|jqt|)X(F9-H;Ap~F75Jo=PoTrd5rxvZW zTnm87^!Hg?9MWHpKm7u$p>CO*lK8q*LNy3^c2G@X<&H>7!iFkbSO&xbKeqiTTqjIg z1YbpC?%7YClUKMAB~M+S`q{OJ16 zI~f}`xI!7*<8HgJ%v`_^BUITkc89~oEKHWvrp$aTHV-SllqbsA&y!P>gc;8XDl@l8 z6^M|D>W;U+^ty^?My#MM@lB8c^OQ4qt+@!gV^OQn2r)z*;A6TqH=K&FitSfPEeA{9 zH5^#{@JBqd@T^NT8I4y#pz48&czr7CQ36~*Dx%LJo2`;7Txmk;5NJ(u zjQM{Ed#m8Ky0BSOhM1X|nVFfHnVFe6W@hHZj+vS5n3>s@%*-*w6gwGx|2bzareUbiVOBtswcXUIgzl6M#q*X zy7M}tJAu*bQsj{WF--wrW_rM$`2_;80{h=K&_b{yX##}WDW&1{-+Mt- zUc{E}fEKoF#<^{(RqID9Wd~9t%Tm4|a_87Eao`@Wm1U79PW zh;$`ML1=>&mkqWFR1iU z(j}f?bVSK3qp_b0$?A2mY=%?3ri-2H207eceNKLHz9#A2Q&BNg$Bl}Gmhhs{OAVTs zp#$iWhso54dq#GEtz({&(Z%0jO*t?Abh}ODdhrPsC4KI;^d>EgKGK>^<>byN!;8sV z%&1jU!yR!P`HlN7f+pm!dI@K!?Myk@Bnh^UD9Y?g5v!~TA(YIZykV-pZ=M>AR7(r3 ztf^9(oZ*IVhOHi6*%910ZoenJZF(3J=l4>zy09k7>qagwt*G7pu+(QnT0lu=o51+> ze2GG_Zy0*u(Ra8JYQ+vWmp1fXn z7@|INs;e7ZMFNFT;xM_hT__-*_Q;=nyptgGO|$Z%VV`lR>guz!MhrPbOAG}9DCAdS z04TiQW^2Vwq@Af7HSaH`@Y6Vvh^^quZjwpCFslmD0=Ltv4Q$dZv&Aey-K{HZ=IyLx=;1rdRKtH{@6f6Ex?HI=P9Y}g1_pLwZjOUD4}DnYVW4vChCB+*47z()Sba#wj(D)gPQ^^Q!xikF-oQUV z*8!QIBW0YEmRp_iRJyA#j!mnsqUy~~0XKIm>(fa~wp|aiqxY_T-}eGTdXfuQhM~n# zc(a0*4Ed{(lQ&qjS-fY{x=~M`|6ER32Wb;MRnhm^ZE;*$!gm6NM!-E;_d!T_zTI^X z7Rl+{vehk)?>g$dC>1%TP8`9U^6Hv|z#6jkAQZm&ba>pg`@vebqb^=eg2JV?;LJhR zpt3)77R#G{BJL5@M5+a@v|C+z20AddNrF1rqfs%z%3QASbn;+(r^6V_0eC8jQ>pPE zCnh$mzWXAC(W-vGd*nKM`>AAf?>m(Bw|F}?lHz`5t(5s#qmAw z!ISg8&K3-a+nvxRwsfo3D5>iCrl3EfP_-^~ z2@tPxzwd~z{`9Zwn`i^flc7p|-;J_%8MpNrz`YC75W~Ubu(fqUpFI@msv8v+sCNFz ze~pJ@%SNGL%}bfI`Y~Z>C*Mj>4?e9dt|Uwzy9+V3Z^s3wsor^%Fm;uXu`_ehylVZr z_`Hn!rKw4T^kJ%NTC6xiEmL7J=JPfftcb9;BKS7M#Ut6by(g7H4~UWO%_Yl<xM zL`p$X_3p^zWht(J!RDY5V{q4^Dz&t^^HZA#E|ez7X`KxNB5=k49#D`Lq{k7G;!Pg0 z)>>qZWcR#j>jz4zuMLssUBs>Pc)W~v=t%G>N+I{DDwv3kTNN*jeY(pK4>^-}iPFe{ zoc`mxB@+S-L zI^E6R@f&!zL9%XtYCJKtbm5yNN=0oC;LfoV@PB%Iy%i~1OQ9*}x{GW;`WeZhEGln( zRe*CDp{|qYW7zeGJ>#T2cciFt?`*E8lQ~yyJv6c{ozsccQdUN!*e>0DtXs$-D^8V9 zhD|94r5txCcCxXnsQ~Q4`DJdY-1XE(Qt*DIjCe)yx)@!`+%K`IrjE(ps!rH|wsZb)a1=d(@>vO>E6I zAE_l>C(X^&JO>dZqgPQ@QysNU6D>EJl+CaA%vBh}a-_A%SyO#=(d&rV@FQ60J`PEh zd4uSFfM3$IGJ@CDGXJpm1v`Wa_YT9bT`101uPOJGW_)6UxzirZ=c?>N z#v6OX4tgS5sKtb919Kc9>3fpGB$&LVDxj6p=`;pCIw+%U!1OOm@45Q1X1t37OUp=2 zNmW@{AWCIe-L5KCx~s!wMZP~ZOWH$wT{7Jd%P&rn1f_K&ZXd8n72e#)MCsFKBF0Y{ zT3RlKTn#?4x$7<$2g!W7gLsrIp1UvI6O6kYFz8Rboz(znp#7P6#M;IxexOnX`sF3i ztnNAp&JS{w>WDFAj?~zEiLh3LfS_VjAUNibJcYa5(N>uA0BER^eJa0HHh`Db*>Z|E z0j=G^Y?pTB#%)YIbag zI@TZeGbK6lO)Tl|>L||Kh!f)e#u%3xisSz=H{J^?9*U}d@?Anfy?C$}7v(B4T8O;y z(a-OSu275?w+425&}dd!8Tg)+v0*_EYa|a+stHM_1=(;kF#l{ymLFip(d?kQo=r%0 z(KnR2@1Q~B^!@eNG@ogA-xDg*Y=vU=E`_V4k`Rd^t-+qbuf&C=D^|){GEqXa>ze)#yNz92xcHcC#hY$wYTX-nqxi zXqr8d{-jrOxkm$rzo|<0e6@=_Q(QV5cE2lqluNYLSHB&}eF=3Zd3cpglS~s~e%@Pf_)*bh2C$Cv39!)J|M}tk!)Q=h<($ZJ^EX z?rNUhDfiHO$Pp3L*ePr}Hm9zK$Ep7{&Tn@jXV2)aeL$Rrd$T4#l*%7Tj4q}YpeAgE z{8-}8a#~-lu2DDmD(SB2T3!ToD8z8|W!7{A3`sE7YT((z5P@ioyk#o#+%bk^XSu1C zCcrMu7*_%^P^+DA6aWgvglc*YpihN)n}~()AfL#}I7UfpK&lesss`PFZb$v?=IN6- z9Y8m$uqkhvnQnkQb%`RwK_`_(i~RRB-ZKX+F#(OTJSE~N0K$`b$OF#QjHbAb2Cr1I ztvb0WXBaM88JA&%H>`bQ?D2!XtI!#)ZyJzsEvqh5KP9nV(C>P7=@@ImtIh)$rKUq4 z*R7%f7chw4QeS)HPq4$=>pH)~qpP+0=Q+orJ*nHbp+0NuA3zQMGQ~6xk*CtWyLn1D zkqrdF9OFp`LTq8~{6a^(w5M}zsjkf%la2{#78k${0g_Up)aA->-N!Hh$#sUQSEYE< zC%-h2)N~{nF~I*%?b32bz#-eQjfi)KLi9A-Wt3N5va$_Af$i9{(IrkOWzd4KAm2;V4`I(P417U!@ z@{T6;7EFfGmxYNw8J;gfD-;!rmvkla^IktH>q<*mpdX(5{sBs{hdn!lfgyYAM!TBp zM*SthC%Q$yrg7^VsVjG6ghG2gB=0FK-aoqzb)=7nLFE@#I(k5uKU)9M(7n&g|Hhn> zyx%wf18i!lWqFboKV>E#H<8s$=d0t=jy7L5G^rwvU($1V$k@|7+l5gZjFgasJJ?_a9DyFBdGTYV3Uk*dWguamS)J*DcRxNOEWwK9@OOh7$pk=D*!AWqI5KFGVeUg%g* z|Ix3u80;G{UU8WgblSO+yYTBqN&7LORCK!p^oksr%^zqQ6hu~UNLyS|=HwGj>q>z` z@G~H0H1Nm$;+f29&@UNx znbrvJ4TFZwsgvnb>W|gh5Kvd!zhQQ+1Dq!|R+=5IGH|rI-8&S1 zx1gn_nTn4G#IV7`U3ewBVf_9L_^l)F#$Ss~eGpvom$BY;4GA1s!c|+{ZOUd~z?E*e z@X80X;Wu1zcqy0-=EnIvnj^({+21&MK$sQE3=aq433i1g+h*Xr zqE}j=5-BR!#NK_Z&T19~wgTv01byyQ#cMq%#3t{Cm`iC?_%!z_uSuy%osz7;{dtmt zB-)8Wf2oQ$OI#N{3+VfcKvAf|H2y3h7?de3Qs^MPDcd;#ZXtF{TBbFZi2VTo_yE*# z+Wu!4Px!a|f13mT2k?Xu+lCSP9EyxCF6foAtp>J!smrY@Z>=4@oX5-EOKwbxoPi$H zvGO*VOa}L+q%=;&HJ(%L;&FzFOWM&LVAy=%Vtz`gD;!un69vCh0mmW0ce6w- zTcreb3qDF%qFN>?xp@R%WXj~b%ZNYNi$+vS<1zvZ?jPB=NCDrn%l|nh07uNL0}WrG ze^-|7nC$4(f%@A$fd(cE8(+HJfe)(WmGy7uPU=2#BXh$_vP|0&3?>ZXEsh-?;c<20 zQ<=x?N@{5Lo>VPEIgV#x^H#H^MRT6=D2|aTWZ`__sA#fiI>*=E;L;b@7DNiOt~DX- zTwxoJA+uumBdewbq^>M3j}a~nSPr=|%fczjK%WFklwKar`ewYf_J;oMQfl>QZHWyVOm}p72}l_Bwei0kF*Dcihv}- zB*86Gnu5E=N_C$8sGIrWkMP%nS7t-Dt%|vig^&4%+b^NdcNs;^$KGFB@?#c1XDiuBnf8XsOQT$I#s}q#MFB^9TvM4G61qH�uLAa8@ z4(iUyo)+ITe6r1Xgvdw8r&hqLx1ziYU=W(?y|P*w(JbYHbNsrPf@FR-Xt@Al=N1}x|-5jA687n{cJfC zJ^RZ-J!8WB!{t-(QVW9>$1o?&V8ej<_Xcm__rKPr13ib}WFyn(gD2j*MSTMif_TUz4IYD=iStSd-*L~nka87bG^ZI zf4VF-zi*LbX+9}0QCM$A(!mBhX`(fb`B+Em9%jsG8q+#Cr0e#`6IV3&bZYJ@Cgnp( zPqm6cg#v;xHg%|D5C1R>Hxn6@2GmKYY;7=0MYyY zX|DSlNE1PT+s+}11{IEr z6jncvO_A6OO1+6D1q*B5)Cw7sDJy}t6_;vo9+T6C4%#v6@Ga;;e@Db=dY3$F*KQX?b%9Yr4l>Ar5 zIIGZ0+Gp0d0j`N$3nQ}{aQ<0mPAEU|2()|9Ay=1|&bJlH7fKim+rdQYfFEOrR63cPq>X~B9HBX-c3?=&gx+Hizutc5NP<}SJStPs zJU$CC3IGCmMSAB9JcbrK=O)H%MUH1H(|&+Kx=ypQX^)v5LfOpCsq)rVyvunqKG(72 zTZUIM)4bALM{33+r=yz!nDDilr)eoCL~XMQodSnhekYo$j?&8NI_E?dxzg%2CCiAh z*U!lZ$*gt7k;KE0ai#f(!)&ffn?y1T}1(EYdUZ#w^Mcuxl;xrhB5B z6P+Gl+Uqd@>umsnMR1bsOU?|qZ13CS2~N=X`T2dH34>g7z&LwiU6mu=_^RA`bCOe7 zy`urZQ4G8oz;J)?18nlPRqr7lXpyPr6p@{H`+KzJ-POU@%aJV8RjOu)VE)n=SP{Sz zaQqdXEu&ho{6~c~7PKMDB-XQ;ILq7?bBJdS*GZi!&UiCIA18JOhIwUnsc(}{IcHa& zh%Eby=l1D~@RXU*wam)qE_E@@+?FZ!IQy(ZE5g{x7@qw}byZqK+lBGiO;EDs?FGUA zS*$ml7BO~q=W1Nn+aBZ0J}dLNU-Y}}t!z_^>JxLo z$lCb#*U(c$P7#M3^}Km)gIGn;<7vbY2^PJR#ZbaqRt}3i_Og8X{m7nOd5-+J4aDVu;7$aZOXJM=y4eEHunl=nDl&^g1wNQ9 zhkFI$f&KG7W zye4l(iy)Lh8kAsbL9XVd)IWWEEpxnX?yhJ~?nh5ahh3VDfaErsjhVS0y~jtY%HF5< zPQTJ1ur>rG_2Q1n|Bhxzi=n%qM5(idAwYf)gU$JP%PGk=R!4g9G?ZW$GGFkPrSXC2E z1zQQe-$ktkpExB(D|O#0RvgD#5+~nFhIRHfTn7DBj*xrfolgN3j#8-LX!!%q_>!Nm z{l?g5b!pZWa~T{i-Qk+;E&HX?jN-593A_ zH?w~>Q+pp0MfqA9W=m`bMtQ?CJnRMw+9(cB3r6_TBFs(KV`%R>iCy@u$Hn&{BfaP< zBEf0ur%LxbOwzJcVReN>Otq3?$(M0(5<@r4V7;Y$&JLoF4;7$y>7KoITIc>1!&p|Y zYe9=3cEU%Bv>eu-=?a(oxIktt=B^lKYz4#ks`ERG-D~XMSH($|i;y@BuLfOpO&8DH zkvT%iiTiD)BYj0_LtSJ}UmZ)Dv?Sbc3a9lh2oHH4B6-?8)3Uum@MtA7^7zd{L}Rvl zgyuv^mtE_PexRmq*p8vbdgq8QQT>j#xai@hl#-Rx>QMy`cT%eXpaL2F%2WTvru8Yo z(O95o_4kaEQBU!p8!mCT=r@kGS)>o7d7ZYS@&lSfDwhfNhh~iCTP*Pz>lJnECACq0 zB~3WggzQHei*M{|;=;j>2fU(Yps#}${MHfE zIGjn?Wi#BX_luEmk>l-X5|FFY=}WQ&YzFu(0}Wn}E%Tp+OXkQzWtTL14now?0zzdc zv7|?d#<8Vzufntq&)?~n>nWX>YrIfCJHRPuO)Y;)R0tIj<=3N{- zj6l}rsiPWh3f|nrfW=Fd4397=@Z4cPtM+joB)Eiz0uX%opG#*VwUo>f;?4>;m9nTo znE_A+!83&efO1PpeKN-^Hd?k}qFkMN6IEDR5%eI}?6>Bl-cn(Sb@yICObif1lAf zZM+2yz5hyy2~S$w!&3^HctL*Ip0!210RjuGI_`7xEv0)uSy4U8}qh`;HzV2 z{9aH-pnyrc4fFm}utTXQV!)r2ONBBo0Aoh}2j~J70{6MoYr01YxfHzf`gVJJMY$a; zqL(AQQS?oQIP(VP$cLKwNEPP+IMld5tSY<`=tl0#_^6Vrqw=@E*bx8uDI?t93X}(f ze(*GrJ=qJ29ANVODs%WnO`E3yLwj6TU65!4eOX1Qf;U7dPCw|JK{3`cakdhf&mZ3{ zA^zsW;+E|WD$pqD48Q*uN^OYZ*_SNYlb|dftq@Kev%pr9^gGIEV(qiU9O0E?-iEAP1*3Ol@xEn(Z?*uR`}rN>!;wXR;117*O0*5H;pYCL7*)hVE_885 zIS4rgG5}X~Z{qms>h*<`TI>xN`17>d6X(LXN8qXl8^^82s1yGnhXEZ?`pfDmb9|a2 zfJ2ANNLXL4>)F=ElZr;4lUJGj_X!3dN>;Or=L1#xW*51Q8O=Cc8aA4`oxRjC`Ze^ z02Dk3-J;gJh+KKk>#etZNXL{y7bg?-iKM?12arNx@u^>I!cGVmjI`F)^6njM9bdgT z^3Uvn4%X^tY^_mm`98V#>`f9cT-Oa=a5TzCc`gb5V@FGm*TBe|Smb!z-Ft%*4Q(or zf)B9ZU%!sfVR@QU-`5&sIBI{D&QR`ufRuLM*^Rat5PMin!E|n63J(`;Ud@Q&B)guxeWF55^j=Y~(d2uB@bNN51fT{IsaK z6wMKNf0yX4PH!htoDsLW^XEg3*gp=bL)b&D6+w&H9Q$a95yTc(kYa!wG~|S?p*^2t zn!=l2^gr#8=L2_}FY8YpattBoNv(_8b7K^(Nny1<_h)$)sX2u@0x9s5l4vzWEb`X` zGr1L%?E-aUN<+sogwg#OeO<_`HEvEwNRRWZ=t@^WIVY9X{loEIPv;lRvWjW7gB0I` z?fi=Fr1sm*sAKOp0C#i0Ri7SCxM6Zu(+G(`LaxC>kEZQ!wPSb>XX++rRI99RKEYcI&mRcTw#mjH#fDieX4`Cv{Yst zQftEjl~=n9%UT%>-iREF&o6sqU&_S^v9|?v^{0idxHWJJ{Gb1oik%Pfd;^!iv%j&}Ex+qnf{FlOMu?P_ncV zjh$e4=`-~r>7#Fpem9g`ttnY)kMmqvx$LqxHnBKTdAWDrpmaIz5LpjG>J59vDcT#W znYmOhJNm>3*}1!lGo!lMlOZOlGCgfn@gy8x9)X;_c9`no3`R)d7WqIf6 z_HV4U&pBJSU}u+q(wi);bZ6sUW58{?Wo-{_Ru`&ji3D9W5gyTcl0oAbi241>Z}?vR z#m5>9e!IMw!Y4SG$yqIW`D(@Ho4^$NimOj^*MHlabmyirWTjV@6J0?0+-Ss-)rq5n zV!~$^@kPxpAt!{{>n)#21+QsZ0l&%if@6l+sA+zt?`mhICED&}g(QblTghNok+>Hi zyrISmpPu!wrmRkE2hE-~xJBuP3{mnRP?Bs7g5!yMH?&1INRZb0wID02aJfCo(t|Bd zgrY^naBfOsmTKFx^cAbTD{0;?9A6cBjUNY|&D82kjvUFX`~ZDhr=|1Axlq!Bl$nU! zKfrpiY{L2*>2|w8uaOM09!-@7k7P^=6*P^ej3JxjL~lk=GB=eY zh2phVPu_6ik0SQJUPLkWYB$5Y^EbE6Rg~NuL?`Yt(B70tc7tx6RkwShNDm;m|CkB4 zbr3+?xc_9O0HS3gq zO;MR07jik#Z&1-yy6!U4m+pY(Ys3`i!vV&mPgj^@Wh+xpmP%EK6RpO77RLle;)Kiu z)Q=I&%;6oLkLUXg=0FK$*vaiSE!<2ob*AkP&e!p*OIg+W-0cBzPDbGr267o>EIip6 zxm3Kf)aFhd<$2GgpR5_e)lcbtUPSh^wbcv|3P-v!c}to3BQ7Kl!RMY`H4i8!bgo-c z2KXxG=oq1~Z*O!7D*t;s<-*Vx(X9Y+cB_uX#vY|6vMWGw5-*quJ53@$vHqWziqXJv zBf=-5D^ZTz`wV3Dmyy2RYL^{pF2P38%BtOBn}(h%IWP4V-Z13GVTw5x_>;Yb)<)ui zmqQ8@Ympf?p8;b?B&ss10;k`yQT`lsR)rqtRdC8v;WMc-Ta>k9hlc`MX5-rt`%LA0tVF4h$bg-Y~N@hk3?0z0?#mnx(Vipx|7^{L~xV`BU ztl?*{pMvi4E#9bJXNDW};I=SLN&_9`mSlc+D_)0phU1p}9abVmKT{jyTH;F&M7+pz zq#ZUnD39D>3e4`Y%J2y3H4Ztqj}fO6Tgv4g*GEchHzTyUd5`T+^6e32kpzd*zNSHy zJeeB=%ZE_hTv;=~Ce$cjzw#uqb>rT%ZWY@(9CVJ!&YigqON1ZWMTYKHk16Ic;|uGE zxU6Mf?^bKA**XFTgTk1qAvzt8zJ9HQa|u3v+2sT;1LXHA2>>1f&F*Oqda*yRD>CH9 z!B=awsvpTX4(7aFM9wS!0Mw2oWZTxwZMOA9FXglL%?!?2wRL7z!no=n3ya$(t;JS!xPJk%XA0K#K+e#?T?Q8-FcC z0w3ppua*0b(1O2?5_VAi|B48gr$Dflu$Fy$B(eD$oA`f(xi6V`?&$vGM{$zL_~{t# z@1b$46>Z12P%@y+WRUVYBTKb0XP3T0WdSuMlVd!!W6?ETEkPB(wk1{#B#kn*ieiXB zQs(sYvvAz#5u1J<6pUkQ*x!QItde39y({a48D;!OWdY53-IYR%zcN1a-7fk_p7|RI zKP#DH9vX?;#5CfaJea(6c*QKgD6#lQ>ICl>SWH;lNx3K97fOSrTz0-Y-mB=bgl1Oy zT*COfmLK&*xYc|xI$0ZT2Fsc}qc>A7JSmL43zWrzW*5t}>OIqC7DS7#-=s6a;$F@> zX>Q=v_{2Yexw3@z=>HPJ2g7R_?4?XLvhLeN+M1(toFz{CNGpBwbtWA5^H{ZXtTLmC z66^QADqE3HZeBvNl7gh$*~{B9_t~@LrC0S*Gz7-T2Ym=s?P(6Qpbch*lSXjZ;;O2y z9%ByPX>te$qL}Wzh=)g9ek#W+8J6*Rm1`*6kdLiWNLXZDN#sc*g~pK0lwgD9$Emt`|qinm2Bk}HV@qAnZerL`HemjfP z(yz&8%0BRq0M$(k>x$I%4U2jBz5Wn|q%|ABKwBn0P_deuB)`(sQ1>|@Y2i@{_MiT#1+sAfAg)aSp%~W1%vd^i_=qE{ZyIoJPAY3O|{^aJhH1#4p9R6~r zPikzuBZW?bCP^FUyGT!kYcT?B`YjlBv-l4%SPonl8SL+kO&RAl)=;lXIA=V!UM1&q znS6u;y#L?`y}9udO?m&EulYZzVYs48=o_Bj6nTmy%48tO*m6|{(IS+EP%sJgfst_g z;qCVlR&!yU^9vvN1v!6A+px$dy7Q)N6K^S9l(eJ|njKgP#1&0&Spd6u<*{5EzKZ(9 zR$?Z}^|}y(ajI@f=`=trfvR{mEW}L!mUR7puq-f{>woH#^}zo<8~>LahKcRK zr<@k1hJ5R)&syQUddss-~-sITynUI0v6yYvN^G5e%9~Cmd~a~-Oz!1Y=AC{ z+pz_)J}9fweb{P(NFpHy6p6YCIgeoT@C-$h^G}oA|3b{!S^?dirS##`853vE=ke@T z>Lg2>LZ6r5wXp?{LsIJEUNKEW_rco~v9NT{cy#gU-hasiP}j$Yp+4J!<$|N{1b%ty z9$I4j1Bg}qmA~@$Vf)K(TpZHiMtWu-od8XX+DBRyX!r8`b#dJAAPnO;UXC?;WtD~} zVswmsQR$W#gcqTO=~MsdJV8c-t*}gPqBZq)7@8UJqjb87a$u{}rE1|`& z9)=tqndC>*ZN%$c$}QQp;4DihCZ`d5Jd(|;TyWTkk2S}Z0J0m+@tm8)b zQmi8GcOsQSR91R};;xXGRwskti8SOUn+ux8wrB~i&}S8)TS(5b5$AG{-Mkl{~wD_b-D zL7#aZ@1lmj3G1e^qmJ`CRak96QbW|2&;J-IC9XW^!t2L~E76%@j^^`U+w~B^6~$n_ z(?b2QO(i)?rm)PoY}Ug10IL}ctd5{BRqPv{e3>-&TLQW&KZbBF6v%vS?7on=a;L`N z!U}B55%s*Xx)|iJ*LmXCYRaEE0wDf4^8S>>j5*MF{V}#A9NX|5eCuic>E#}7ck~XNLp+@jwPhpksvRQ&> zaeG_ZgGgu&h32-|_+`Y(wrKV$!*#}sl!O1}-3ZUPx1=GhIfew8qdzJ6W4r;H5WUoA zE$o0l1!c%B$o^RN%ngtc4>+~=S{jiCVD;T{mHn7Ea1gY}^O;T&Cv0lq>S25W*w6y5sU96_w zzFNJ#uxkuSOeb=3docO3b!-Jt0*M z*FX<^ey^(XO4Ay%4B4oGNarzkJ0b)NO=+aG*lD;hKTEnRNuT!q2%R8Y6or4t|7zSa zwb5d!x%PieG5ZH-8JMd!p&WBYGUKOIdC*50>3k?3ay4hRFyhn2GfupPSG4&Dm~B?H zA9D=Z&WY&Ic4c%+8*AgZ;xW@qZ742{gC0YNf=%dv`{irNXVg{Bq`jtg&{db2`4H2c zvBue^NXg!sn3ED-WCFy$^5Cdz~VQv2Z+Fnrd_t*^f7 zPwhYko+-HjCX>1`3@R>;3mh@0w!(1**?A(vH)O zDOLA2IuA@YuiNln)>X&nRNkzGztBW%4BWvBUB2}|-taK-?-Y^U#9{758MZ;-KFW)t zu*w#AV8qYRA|x$W8dW=`N#Aa#S~@#BRY){wg&S7Y;)MLcIVERen=N0*v0;Ka$0%nqN= zF!{nJ(x_K@XeG^=x@Q84SVY;e$WvIvd+Sr%23yY^M{NL|ZItdHd7vnLmSBqhl0G)J z{mw2~W^10we|29DQRl2~L%G<;Th}mBr%*)zc90e?3k&@at1jPdT~S$6NlLm!ZheB$ z=>C^J9a$JKOyJq?<5=qp8uup_1AN zjUCm3z+lB=eZ{{(#u=W2VLyOZQBX7UU|Ir}Xu%nQ)bvNoGrOTV_M@XX>xGR?74a z+|ki#of5Zjv_sQ3BHmL(+6Z5e2ZNcKwev0?v*o_=&j_{>Mc@V==G9pq#jTz+b&apH zwff=t@fn?;^CGTHd;2%E3Lf)6j;^81E+g5FTkJnzAr{)hgt%;6faEQ3)tqNovg-mn6Mp-nE!{56lg3<^EAAICWd)@z_fa z)Q^J>U!O##zJ`a}V6LyN6A#NrV1cU^gOl_ZzlQ_wwSNh9Co}G`YZ1gz#clg_48E-l zn*KGndKvnPVh>dH-%!f6ggsfuH-2)-^h-YG&vG&HWQ=}1`Dtl2C;4k5W1PLa7i-5k zcemr{Sc1d6&T=h7h-*n-z#FGJjU!U!7N9qVfCUg$zq*@nkA^HU*4LJx64S`5r0R(MY1z?h^$3ZNms$o25b>e|yKEZ}cR9$a zFqXNO{ldH*d$sOj-RUvOC3^%c0Vy=CC|fJdXEr6Od0#X+5y@Eg7VU1%Cf_2QfB5%) ziOku{>MgxBa+~F~ahcdDh~lxwR+?1`?d@Q@As%=m<L8 zfhB(p-4Q$XFL)xlyY`)@kHT6mgky8?IK=~bT^~;3j5}fF+i;yHpj>o`kh>TNo|Fu{ zCIzaN)(hF9S%n~di)QM4UJ$We?71z-7URbaMAk{PdJ2V8#WTaJUWCi7MFhmOR2Y~v zFl!5Pd3H3B5|N2!29^vT!ez!N%Y4ZejOP$xgE4+3&KX>d-uqjUoCPyjV!0HacwKCe z>g9pMIFmfZ;#1uU%M;H!3Tcr|hc|_)ff9;d&nHid>R+r3>z66^wUoIuzoeKGp``VM z*&VqsZsb>|3Mxj#wZB4`vAPIJEX*wKqKym%%7jC#eRid=t{E17);!UN0QOWj7{?o5 zo&V<4VdGq`d(uf=*%}}uPz6Ew8m?7yN`DrFkhX3#>Fhlg1Ni$yRMM}aj}eQ zxsE&j0sNQgx8z&w5P3;rM~!0G+d9m$+w*eJo!0Oa**Jv^e$*lRvtqTqcv3w`K z+8!qLX?=(>^S=xnH;~}27>q5#R<&Rp(>UlFzB>e_u?WiS{Jbs_7HLmOH;1QLUvK63 z1bTq2?tKN{xouTO%|mLwgVGg1F)qnD7}({zdn$D#y4poTj52H zxK_EFXX7ByuHGi3nl8ZHsJ|==a@zVz#U2P`U)W)Nqke5y0Nwc5J8w?3v_#DYH~L z>3sC=CM*an`z>W$NW`{7(h!%UhQglg#ui5Ig{ZwkJy#|8(g(cI1wq^|;p`@UQ!tH~ zrHfli{VHG@;hG-XiB*O=AJYf^5KSTXuWu~~3@|QR#d;TG8EW!}n&r7HrTgwB>74NQ zSkxu9{X*m6Yj-JgJY6iB4*=o?Aaa%+`<+J)$(%3L`QgLZa0%;$9O|*;F8UvU8J!>g zsr(f(wg?~gvE-NY1DIzFAP$AN1^X$bt6)CGr8MO$Ag%`#C>Vk}0gulEH|Prgsf!?} zHZi&cTRGJV1d3fqs7*4F|IYB*>8?fA&=o`_J;K9)ou;~@;5p9i>Hkx21a^U+=fD^x zT*6KsU4$G&t4}R~Ap$%9h8v=vt0r=D0!4XaI_1+!gqUfTy5#OO9QKgY>^2LgWEb(8 z8PgTe*t;~+^t?F|@loU6?K^Jv`GZ-bJz>kvf69?)YYHY*-#C%%UgSJ_xWFy#dKdZ} znjRh@@bc3jn;GXbW;}f>y`5Mg`S?huWYfHLvGs|YA;nJ1OoP2H|JEO zo83{}oAp~ake3}!Bx~YO7%1H87)eX3Gtf4$JcLus4hiI-iK#GHEiK@>aDRFRvvf4i z@dZ2O&UcaL%atbzYU&v+8rpP6c4`;GQA$45Sd0 z15GGCG#GL(sKQfMTn(O^7vuFJItii@gPUkjm~MT6GcN&+zjd4WGu53W5i2XvInk`z zi<;J>X0J;4dKTLBVi-d>XyZc1zG@!G^%dQ;xydrXkL?^9f8Fr~jhG zr`4tGxR23%lQf@!S(CLaL&W5pc~_R9DeH^5?~B79X$=(3fG@DqKP*igz7{)dV@|tX zHnB`VEK5rAoZy)dbT~r(NLJ@`+Hio0@JqH}*0ILnczr~+$5r!BUYv}m_=t3>PHc9O z1Lxf3gU}jU>t#Fi`*2!pevnQn(N=jCF;xZ;){>x)k{8tPgq9L7Z5m3(@mgs&aILs7 zxW8E?y%U$;SaWkpHC?m<>x82QH$`|m7hoYqh4W<$b}Cjh7RTS(%-X^w290|I9oS)A zb^!t=`kbV;Xg4U9b&_E?5pP9>Vt-4VEknkYwqDYVZR{9thVdI8lb>;k6KOF&=G6ZH zKclX;{TC~`>x`D?Z+hAk>-2hqiHuX3$4K9^TYLB6<7OH$r=(kN^{ya*2e3@eITIHU zBC$m<&rA&1I+j(jS{A5MP?sDWQkle;MIf2?g#@nz zLNNU}DeZycezt@svA8((Z+k|K{t7@=en<)UY>64)`a9>QOu0(-EyY)MfjM1gZAd<= z6Uk1!C~eA6ZyBOxa<60*`*httSVTd^LPdF)Q6s&rK|YgtWH&N1KSty2#wt&fA)$xK z_5Si?q(G3q56MOO?D7pOa-g?;TB08_E`_r4d(6UpP}VuCv5Ptz&!MU41ej;{Jv8*1 zOS&8#8W1Q3J0@i)776}S9+J}GIMOfeeG%eV{@cKecsU=|!50Y1nqZA*{%NS%2et(e2|ioAZ|iJ!~zU}K8n^TeN*3rc&zpnNZb%Qvd!osS*LptF`4>1 zFog{}#{(wmZkJDQeR!4tW;z$emBd`}jMma{*_3_O2Bi0?IB&5xx*=|PK)y1lYdLYf zCBg4hI-hxt$&n0*3mc910LKr_pC>qPXWTvl8U4MIvBmcCFy$-aBW{}$YQb>#5{0ZDBUvkiX6_z;+-5wm3MowdoeUtk2L9=8{rS84 z^`bYU-xdBDO{Y`4;aVV6pMa;-JsWoHN8``J_DdxH!Qmj6eP^u{qevreis_ zb`P2f=x{yw`o8VWPo)uIWh9a%4FlQforhZl3(i=_-QtjcCwUVg39Y~!9Hw$nSO!-}n`|}T_z+)rI03;&iJg?vBb7yWVVxG+Qc~=<6IVSUSKXFd72o7q zY8Wb6*=H@`VnGmQuxdI|=`Q{au0O~^yne!fpWxEs0vy5gA*gJn%s|{xQZ%rCNg~A* zyw7_ipn!)HEkf=e{9_0%kRmTn& z#&96&FTMjU-zuKt@Y~wP~7UX?YxzEdC)&Ew3UXn?6pwL)=TL zE+_gA0ODcfDY~+vzK}=9C7wGwdag`6uXfY4sAj!AzTdq{TqRhQp?ZzDTWP5XYKh;U zVQTnW2Ak-|=gYq%KMkNpH8LE@t^BDEJ`DwBKTAnB^2|(n@@Z*qP30 zy*%UqCO!ti#l&e*Gn?Lu@X!ywoR*RJ#^+i(3g*tqZG4G_>#=%PARF57j5TeVqwFRm zx%uQGeh39&r6wKUNDHnuRD>EW(y=)KUTA-yinbfqT=t<^+7Sx)v*PrU#7s!{#G7t= zVc#OmiQBHdhFI@+Ez*jajj24-va}1bHOq3w!?Y?inYo1|B^5~_%L|+vCs+PYe<)SQ zws67G_DeVt4~N|uJd(+j;^wNs+ve=kbggwawl%9~P4?uDlvR=yC8>$yg=09 zodLp{v{(-|KxM=b_>5|cCn z_zzlWb)J|l=V9p@n#z%8LeXJP!{sb(ju-KuH2!lmBiheXM6k9qzX6x@20M?|H2b=v zB`W`H*f5kMg*Fs3l=*TXIPr%0(di%MyXx&J@VESWvy)XV>(_`wgaz~Zv4z9}A1d^L zo0@oEJBq3-Io1MD%fMkZa*_NRw;93BS_aKTGW)64Z8>L@rUccs4GwApY|XVSJbT5O zj-%Hp?=(XkUQXLG)gY7=yxzph2_nw}>c)kGy@g^++j{ehVEfm(5N4N?QKRxP;t@&R zNk9||5VxY2hc{2VZK4*j3fPUc=4#=1H(OQkeBXGZx~lU$KhSbZvGfR&SwGs9EqdIg zR2RdlD|X^BAK8|%*qUt3`g0Fg5|^|=pDRj?U`Hvr(-Tj}FT(K1&-k*2i0mzx>w_lS z)1{2`g&Z_eWm(a`hZ`NVYSpSd$gfnx_#&EeT2BGfE6J;r{0h`ev;!2QpPBm`66okC z>(o_9>fuQX+O&L)W)d?>=gpoW6CkQ>hkcsmK7OPMa)0Lh4sCAo>f=Nab@j6lI0e|K z=bdJxZC8aki3E;;Ng)Z#EnhRqP7gX#xu)i~Me)A?=u~_AT2{~&%r%@IgDe-O#p#iC zjM4T4xzcBUuL5>=rSCh)@TDV%9n{M0DI%F+4`I>L#R|=5s7H~WDoU%i$`EWzAiLhG z*E(c8QXp9>WJ1}TI0Y$NHH{>B!fpi+Kb0K14WXc za-W|vY0Z~}up;>$r~C634~S(_E*(y8MYMoU44NeG6U37VnJFzg-o*Av==O+*8vo#i zq`S6_UjIBnD1Wm24{o(bx;m0<%`jFx%E4p~4);5_TL(4$gVgT<$`BaR&6)A5Q=8zM z-qx4NhDgkcL#-9=sDZkb5ZhY<>l!U|m#4yU3Eo6CUJIJNOgD&Zt82W&pFT3np6X=) zW3Z^OFC3&8@aUuJrW#R=XckrPPyC`9yZ`4XglQJlP1wrHWL<55D%xhHZxsvcefz@O zzi!^oB6{?tC*=XI`K0}ndyG2v4YSy5Sb3G4RtS6OeTgp3qy zmKJxku)yK0rG7h_YdyTV9$Q!C{$)EZybU=tx#!5k^8>e_Mf-E<^omg8eZH4>q-BS@ zK_@vs7>ZFjcJr|3h4a;T3V$4bs5)-Y=P8=H#GvCFq4m;(kOUp%pUG1;_Cs=}ES4ky zKnwbn*xrhKChpQHH+U7o72B`>xUM!>Uo4$h(`QtWkzZBIp&(AeS>Kfv>s{!&w)3s) znf&E>ukMeOb;SKIvkl$m;B-ewCr%>^;w?@BhC6j*#VZ02!sh|;qf!^7#v#qNpuZz}%;Zin? z-P)}6`G&Cde4wpaJ)!Xsru0s=T=|4*z1KaBSY{n@Il4SRjym6slK8EiG5>$iKpSEyPSLdCz00SK8v8pOJS<--mM~?v7+j^LK6!z>- zG9wsZMo2B30OAZDx%`)wS{$@epYwRV-&1`LU$`#6_ux8`rBtQ7mW|!(eD7F9@B}Th zj{0nBFbF?rt6bS>vtO;x#!K{!lV+|PTzHJa+-RDf;qQD4_8Wa+&v&~7PW5{uyd^)_ z$=+7efHO&r+arU`YTBzDj2`i0a$TKcZRNq%+Bc~K14bK8-u;=)mWnnAXb zvgGQ+$7S)y%?w4nNj6g}gGRme53HiX^tv>})}JdC5v{ec4}3UeXb8nu2DR4MYU<`z zy~w2v%$I)QVWwPX@%w0W%CpV$N-=(eQ*-FF=;KV-{vlLpjMf4H7@yeH90t_?8vMzn z8|lQ7Md4V~)!)Y^2WgjM?<}Y>x3cQIYuq?VIdt(%T$x^GxsZKRl&sL?j;Ca{K$2zU zT$h@NI(H%~9T|3@Rsk8aq{4D=Eth!c`yh$mB)IL_G6WW&XDB^wKm_K4bwsHJFo>rcWwA zo%(k>F7h2P>4eglq?sCMhUFkbN_>mgzG@+aFI2K#N#}TH-RqiW>9FjLnOa zo57n{z64gk8w#VJk>hD@ZLf#;02epxPZR?ZorZVe%9-_3Lo$%h7 zr9S+G)BQwYPGhNF~Et@ zprnimlNAMYX_TZJCG@(PFgOp1UMj?)h@VaZ_zNJ^BXpD#A5@e ztIvAcB#BKZmCh5T{3D*Qza84cwj-Z+?@18qh)&#*h}2(z2}h*N6gMbbyZPxQkrj!-PT+*N9G>d>?I z;x728iO3%9P#IX`n7B@J6SbJ|far@Hy{m;IdzaHC$4|h&0CRI;ieLDs9ai!Vv$aNc za`9{%ZZ+Tb6~BimkkgktB!T3Sp9* zF*is?3#0ml^N{HF0oNpjg}VamqXx}m*|v4iL!H;X4L!NG75ADPm(-7_{ErE|3E!se zV^uxLrSFopX{bH6ij^?wC)NDd@{9p%?wvzA4@2phjE&M9ZWJFHtL;!HT2>CDTk*xt z6zbWTW|sACXFt{T<;9fCPpw8!eivCFntLd3pXbtiXy`{{{ zC85>Bb~EsNDg9u25+bs-CVNbNKF*&mF#S#8YDx=KEM}j&${|g-n_#LTG)-z1#>WF> zx<6I!zoFJ5jB8J)Dt-5(9eCw>nyD%K*Cb~2za}wdT+L|>Hl~iOiyK@EI0`#OVBdWf zQf+ur(CiTRg@}ZaLkwYaiT&$$2U5k8W)?(5pKKy$PNVYcGGR6QFQiUro6ck=q~jcJJ?41? zO&^0SBIu3Fs&m3u&kS*M2pN`mTyFa~TYQpkCKuHBF-Q;KzqESV@c_@wmNFV9o<+D$ z#>k3tm`R!VJ!lB7IIyLFLk<~IzHZ#~=Q1A!bk@QGlEcH=W_}<(+#t84i+Jbt(nue0 zdE9vhW|H*R-l|X#6ng9npGt@caTaYjq%?5)zY&Uudt9_4t@33;`aU>p1uQ(z%pP|_ z&68g+h9I;St;ADZZVNMxE|hxy@cj%vsv<6Pi{3$%7Lfn1Ze#%{iJvcq&eq5CPt7_m z)VG@#(U`Uu4iD`RzZE2e8)+X2Q7$$PZ*RFUZ6P$q=H|seN0F8V!mN!DShi)M{b#Zv z30>F%Qr4g;FN)dve_{XHy(b@DLx22p9oP$Lo*5#N0`%==8vH z;c4LJ!g*DAJsoEITGYU;`+xW;0sgy0v}KFaprfq|^&A}4qnt)80=3@)u1oMAnz^@0 zL7x#TE`6YH|HP%Zh2tpH$!oL2AGxK2%bFPhxpQ};$Ur6-JWH=nS$Pux0Q84X`t59 zvbbpky^)P+^nS7QqqFe2ZM=XIuyKj6=9b&4LH0byJoSK%ey76aO8BGJjh39jgRC6s zZ*j6}?xhr=R=JSOxP!$Sw3qb-<=;|~?Cn2n5UupUMS5^4B@_iwXV;F8@G1jM9e)AB zGoKAxT<$32Gg?w%k;==7%bfhv+}51Oqmw?52PZkaW(TE{gc{#XgvWTcZQ7&?J=D%U zrV57m|5nI=5rM&-Ab0~=jdOX1VxZ!>I`dti;@Nl+E^Hi3Sfb)n#j(gxC2I9)EAO=9 zto)od)%oCK@R$qk5RVm3y1G%R4g$r#kwJkcmL_@xP_>wYp8ug&5&kTokw181HXGr z(2@Ai!~2mk-j+oEi=n$0#T+)BXXsi1^IGtY4^ToUKtxa!^6gk*mB>d)ogubU*BAYp zSK%u;Uj&QXsc(lN^+j_42@wFSgaiNp(wEe|^V5ZD znW5Dv?WUAghHE@ulml&WjX$*Mr-{mmb0-_5M&J3%!zkJ93I8``xnKtDE3vEi9xg0) zBsz((ek$$AzVbXkaXR7MI$x3!3UMCXn)^wq)(`z;0-Nv|35UVyj=~H&qJn3dkv3{z z77nZ|tqmm!%5h`?l)o&Ef;fNxRzO6AT$*^!R?QHhdh;3~zDqar@X{~e?f%E^=C}X3 zDb-#}QRwc<3(`o1;YoB4?(};+{@?eCJiYWwB{Al$=IvMJNT*iTh6@AIRJbFSua6?d zd8&!_nGI*0uTeQ*WpgBzeDW9RhK7d1(f0vmnif!V4Z*_Gg(0G}dmtjB^+H4MI$#iX z5|~p-4hTNHF>mxHdQ3?OS~Ge_Y`WAdWK8z)Ie>dOb(<4S>&NIo1;q(6)n+(+p|t>5 zsiH*mn(z=Aqx8A}CplsOiD|r1z!^<<z z9ELVe)~t}$t7830V);Kg^?fZHHzPOPXcdjY37|ijc<^Ee>A|%-_sn1HN7v=VB?=Cd zJv_qYioyican#^TD;X<>17%C)Oju;obs6#^{&a>MD~U&wM$PjW`zjN?JS$HIqeoer zd+uomKGPi*Ip-0Ji2Z2{jh(tO))z%+dpZHfPI<|Gb<)CDH&ghxty%IoqsWD3+w+Ik zqjr>9V`5siJA#ioA0~Sf@{YTf1nR{x-k_$R!4a}qK+@SqT7f&7B3drx_T*HCjC8%s z;EG>dlOLC4&nEbNQLU#-)9M+%x@_$X8Hri~X}yOKr##{*JDWDUXXYwgi#lG7;j0k^Yta`ENDvpZCrGeCYZ+ z|Nk!T{o7nHYef1Rs(`s59RYHXdrT1liEmH8ApvWx>u{oB(r?0}6v={`hE;zA4RJAL zbGTG4n+@h9S+KqS;09y@WR75K(lmo1=9xbbcKun+_dnLVH58{E2rmi`nx_>L98`XGknMBcDr1_z zo8`WadVya8hQ9swO7}9%W=W-$I|^y$H6L)Y*rA4SR=RgIS8bdMYi!rEJFSUqNML6O z={T6czmIqd^O810zlJPAyA|HgRR-?XQ%AnaXEip>$3kSKzQK3IceD?c_dol7aY(H( z32fZ^TA6B&P_E0b-*TzKA5TCt&agS`Q`|BvZI9BxAh5jHl2iK15$#4b?hO6~ShCV| zS{|hFbGRKhf73oy7e5LrrZna>i&`J$yU;kXb{hvt^5ZV719vKC@@0nCsbh%ZvC(#j zT-_e*r`8ic%PGelf5d1DVZ}T^KwB(7ZPwZE98IGxT|OuJgzqqDBG|pXGVkkls^#uw zv_iJs^%qbp^A~WX-e(}S@QkkBIl9G4$=HEVzG-G**i)}inTxv4_a#M( zq73Sp={gBh_0R^B3wgA_9IZa&#gm)xnYOkx7j3k*bPvztJogs^y4bVf(i`^nG9D&z z;1o%t;|q7;9iz!JWkn1P`keiyd%qR}Ilha+%gRXs-rqOws z0DW0;=?${e>T0unKbmjZ!dI19{gk`exhKQ5rib&>YnWWC`}n!Kh`XMKFMSZog;C;P zz*a^4Yjo8eX@zg{V5gL(*FR3@ncgzyYpV;eP?I_Nn22{44MrdQq^RhEH=t1vPL#Bz znwZW3I3tH9{ajNj@Wm!Q?n+7^CbI_`<+&X5DZGeoBCY-7s@^QGLZHQx}iKw3BSf7?(kw zO9H(^{YCVP7EI^KEdZbQ2=ScN>2WS+OeD55iF(<%bFqt)y_UhF{v(#V9x;p0{TcIJ z-3My%sq1q?b+s-w+2lu_BG z30M^R0ZU2X%=KgExRlP_5fh}AgPN*AU)a=Q0)O>fmcID;-TPu2$}JAa&4|-|50Cu| zAkp2Nx4se3_%41DYi8=(C3Ey9e#Vs7@gX_bQ|ncVL!xm2bqyuUvV`(0RkII8_AS3A zzg5o&*3nX@Q<=L={!p4M9GZUfnh5+s%16pL@J{dgMQvrpiBSf|(z?5K7v-E+@7QgW z!a-GCU#=1lk+xnGA}8E$Oligp`nT&h_mts=`~#7E^9VaxlUJH;-^(y|4zI4IE2 zL?KP9-sRfAP-JC!_>yg18Pg8hF12c#H%BM?d$AUdF*M&N>Tq8k)~1>q zKW*;d8&#ZVCqp}JQ!g^ztyJ^a`n%_wOVEc8LYkYGW(TJ8K08uU`WLLdm!_n{0tsm6 zUiT{(lIj{tie@;xY4S9f)dOd?=f4tcimF*$)zZeNoU_gq9bIq=!INO>{!ksVDt zH-^rasX)QhRQJZaQ=sC*BdCmn^fz$Q*Vhb|c^O^Mg`N-b>d{#^Rl z)G~*B6HNs*5iUTpNKNiJ^Fd2bqoCSG3u& zL;=$6UqETpu7?E@3BHr%8LhL{R;l0|{ItXICT(d0AP>D9_y>Q#2z0w(U8n{J`}UMG z)3iR6pzg5j7&HSoAv9NEx5FK1A#7qcAJ^YmkI0eSrir*q>+B_id9lCae)x z(Re9f{^q4YvO&7`A$CYY=b}!)t8Zxcu{2T?b`c5+0AqI`ys3{V8#e^X!`bNf3cBz% zme4CVhguS^os*;|kJ&=P5q!<9#Q~XEdn>F?wX3?*W*E__j&+Gf7 zW(u~w>-eayw%8&N-*)6tXu>{0WhOrH2lKl9q+l(pMpcr2Mj}Q?RN7IP#Q3hM3bYbz zj4VU;w^F92Y8dBYE>LwUQv3L^^@sUV4@*p!L*^p0)}evc>~$yteBg$z!cKJ9g!|}c ziBYEima(n8kWb;QoLcHSzhOaT!c;zkxJ#(_1w>R6X4km4X%euOVJJ*am<&GaYk zEHBP+_4KJaHk$-MWB>!Bd^b)>eOURv=wZ|_p&$~r<||T0$bgSP5;Rc(i^!abg=W(F zM;wi{eklbGGLTBPSb-xQx>mqfP|pfN$3lhp?3SkXoz5PA7XHn4n0Q*5ITLh2F$AuW zU_LCb0*8aKhD}~xCf5>%z~(P#{MBF$r%qQ(({TIC9W$@>n~@IhpN8`on3{E@SjnUs z9>=S4NE|mAatY{}26kYs`acjAL2a%ay`N)>L9GGAYb_&9c29ZGsz)g{mPMgmV^fabcNGGaIbUQVSF=~_G&bLc z_g$y!EExLNfLIn}*^hg>r3Y9u%=wwpV>Irv;38%&?md`U0Y2HE+F~EZJpz5 zhN_i}*5stitYtYMFf5D-NU*1vh1trjz0h&lqo<)b8V<9B2-UQ^Eo6Y}tr-8Mg!Xyo zZKbjbFGQQ-K3#2;RFydYCK?mUGwcqGZCqz!z_(Mg?{@O*2DX^281Tj?4 zcG4^31yRMhhIzhnN;Y?vc^i^oYOzjJ3sc4ra?mGnlPRt#*?Zt;zcdQ^dCFeM9oDEP zb9L*Rlx_Q0;O}2(f=00L9p)zo9zXa-O zJG5GfJ*a$#gI#&pbEA@Vm6)qDQ}~RQ94k?+7{3_+=hvysQ-4xJiOGuL&Ry|lJ5)n)Smy%b=Y0ow5Xwd*=qh0EQRc)cv~#Nt4@V}cI4!TR=&~rr zBcM)395IQW9Lku2XO-GQR{dl8)R+0<1En|1d5{B9dq|98;8a}9VwmEKYKVLAD0|VV zKPM)S7ntGlz!3X?8a1fJ1|WKqQL6(t44`NhNf^YY&2ID-$|m`17gPeBT|(yZeoit# z{XnDT)^C@mJwT0u$3}a3SnLo7GKt(=_{}sVmdqM{t&js4g=$n4m(?nM)b5MaS#u~0 z!d{Z%kElW#FiXN2-hjL5Tw6T35nxX+QSGR-HI{ea`bW;az3mq^L^q1M-JU_A)ty*<9!8RRxu z+9jMa^lHc$O1mDv3!XdZt1IF>EyZ8RPTM(5Ro2#xwlRQmJ5zj{j@sUi!&SrN>z6{k z9j@=VQzA>l$Mki7KwkoWnIHdGdqNL-THASxebWnw=zM>**}Ae&(c}VZTz{yR2X$x- zDI#zo?;pmdu9$2)#gDAKo`a+NcDU=08|4USX6~TdpG?t?l6|ax96AqI+(*<+t8|i5 zG%M>eh&S12cTS9JL6ZsXy|h>5jxER6XwyudZcR-)3l~)j_A@nJw$Ixs;))_<^qIm=wesctiKWz@pOMMeMW{BRa|5%1I^6v(K|AEv)PB z!v9BQ>A%%u$m*{01hZ8@XD-U&mL&MjPjRHpO0eQ-Lt?m8e`o&lnH;`!zis~SJ|^aLd(=Rw=b?6!DrM*G#i15PoNp(adbrq*X_;hbUxVj)&H_+6J1v1YUDqd+ir2wj0qY^>Ew~6 zH|;lfUVJ7w6O0_j;1zl)68J^wEHgC64+tYd8;e$8GfUHk z?*-&2(5Uz>fHs#JI%dsWz!JTxlE|Ljv|+t;yC2##I<&JjFar2gy}J$7I4gG(0gpkC zdIGe?wr1Fj33>Dc1N8mk%zCA@lw<9bTmd2Xl0h!{4t>k$_8s!W``j&fUfj1aTqWPx zdmm=yW+_MMwoQuItbW?9e4F-gDN6sPy~tZIUY$ahPz1p=Tip(&7M9rBI}=|Cq^!K> zQfKm@F=N&J)=0BkqtZ@d@os!wEBXsaWRdy+mZC9-V7GK6YvTx{E&dnEXb}Vy6#JeU-H)_i z_Bw>wn$A4Z$2mR$8%I-3lb>L{73a+2jTc+0K1c*4OoHSBKBmE!^HIoCE^3o1DU2v7 zd5Xu>b|jmRYqBkvrD-GEe0~&T&@&~Z#I7B|t`;Z>t;N@lb|lUr^kAXtbra8W^qJC4 zHZn!6>eELo^DYEkd{XM8VrjX^A??7&chAN2X@~k#HQCCDFXi_D#g03ek4ivDY zi2i&|4%%@8Nr~R~xauKs!s+40e!mEJkA(uODOL42$fFq1AwE24cGK54LCN{6U>#Zg zoGra|&XU_Wb!;jDPc}}}fPy!`-&j=knZPosmTUTOOggTla2JlO@ekl8F!7G`vRbr9|b=e3=+y6N1%*;spO6bSGc@2&>oj7oX5d$vKbew_=_R6M%22OWd?4y?Q5JhYfRc4&W!Xnf zG8dc=`vzF=5tY=ZW|l9S;HM5%ypJ-Xo^n7V)B{BKKfS}Rr6)WHrQiBdD=YFS8P9Ru zsHn>tELvtjuix1k@fSh>fT;iq$1kv3b~&BGb?0Y5V{L+kY3rYis-!D;^Rc$<>Ofxg zq7JJ*_JCmP@&f?-2~TvabO>+A0mkN#{;a6vw-6=KkQr3YhO2sR6K=x zF!7RIi#hEJ)<2D?{y97PRg6So( zZd$j6a-;lUdfq7= zG0wyD<}HHjebOBff9xDgCv<-13~E=E986?exY!-J^mMBd>2w>QO#8Fcv(A1AOw*@{L}4C0Gvg3L$VevJjPLm$`fud;i)n1&CUwUB&{1=~Gw zWws_Ma8JUEa-}NQ5tgb@x$=?O=+X?3_cQ(q`A{HFJ&{nHAKX(D)>tf)0~3aB^(zNP z#&^WhxRy4Wd#G+rCl{-qqY0)h6~WuAywupiW}De6!QFocHj3NDpYs&Vgu)FwM+?h> z(|kbHc8+Rqfe>fAkT5im(t~G8m2OrjLzZagRP23m!%la$3ad_I#i=F_6?qmVfG z!WDzU;_-q07k}%AttsAL>BX`}&l;R-$2r1SU3mtyaSM(@(=0POP{VH6^{wOl1-V~# z(PAYU^6%ms){aYKe@qExdgO>}_dlAp$yg%LWgI8Z%RyB$2vXE*geHz<#5XJiW=^l6 zteJLyOEJT#&N9aJ-H3Zg23xOjxBYy)*<$jYa;c97-B2aaXoJJ{M~DDSA4U(kqUSD9 zkvw*NYEX>YM!PQIS#WupLfZK!_}0(J57t6Kl)yoqrnOu@$}<6snY!6qlp^!Yo58U) zP2xQcm~xE{4s*+)IBbWqR5k2$>FSB{4#8Ez>e)f{+4YV4emxfXrVzSBR22j?@)F8I zf;GIV?o3g2uptWEG{(eMGkbV)H#vQH1Ux1>0;dtqatWZkn_j>3 zfY9ptz8N^CXl{kPUCr1AtQn@zao1&XMGGEqmt{cLuy@iu>RY`?baKfZ%Bx@N%`~ab zbBe{-$z+&F(*XV)<6y_vFhNUG6_n;*=0%BsdsS3TN1-5orxCbd^sRz_(cD7mQ8W?Fs5n zR`f1P-+9(&>=T_qCtG8%QD)pCvX=<`h01j%-qeX&km{=dc#dv~!Y>U(YNw zM&Z{vfC`|f5PiP7s1nsEd|uO%xQ#xKZ2YmN{uXtix#!d%4{3O{=S(stwQ4%+o>UJ> z4bJ{fxOW_{PDFL5N0U%aAu*9zd2h^Wf0Z~t*Hr)e_g=etw9Ntb4%P|k*a+jK&|7f~ z%3TkNQL&V)24Vt;m;yiL`~wahEjOr0{&yH+Io1iNij2hOS=M*;(R6ozdj!G=h6RAtSkAM`yL^e$#47Pcdy3 z0hifw!Ire%<2;Odjh-offqgVy2$)rGXHKuZSBzgY+mR>q1LEyxBA&6`aUG`0CvPyyq2ya~59T0^ZSjwBS8iAKQgq z2+NF3@*|`G2`m4x3~zb*x?MoCyH6Gp)_BM>OSBD9X0x`Rc6}%~C2OR=7elNf>hp9L z2xR!NBRd83{d;Px^{42K5_$>W5;RNQ=wf>$R4K%W3#c(jtKR+stixJnIaRY1S}t24 zq5mIS0?v?7N{vX#Ec%dyid?w=IvMwyp9$$c=C=YxiM~|`5Q+J}D!(J*-o2+b3g}jG za=w$hDdWJUECr1c0L@e?r2VK6TMuo_mHic3=``NvFN|s!75n z7zvcxg$_w5D^k>F`nd?LP^^>>i15imb>-Sa0LB#iKtx2udruxhiZscku$xj6@!bcA zrR=Lx9ueI)_ljQ-tPwsyoyFmt&W8w6pw9V)jhpoM?W1LcPtOdMNzCf`{Kb>dGsS5+ zhO{$|k2pkW=Kp6In~fNpFH87Qpq=pTQ=1{fpp^9!2q)6*`hOAydFMQ^@=HC>JEPKPPnhB2P`Wj zI!BVnDLK?`I%?delxa-HB*l(Wv{XXTlQ_3LCdHzuTyKZC4U^pd!#e>wj7cF`dJCT3 zUj!DhK-hW##P_PU%FX`!MnMBeiBB_9@#h#`QI(xVyTkMtSGUc2n=)K6BbW_Mc}YaX zYsB@VHnpr^S!U&z09wtLoa(#+I+7bN5);1~J9dO2NLngvn69P@+xE*oWO~gV)*M*^ z%L|pX_H+64!}5EB09^#~g{!pq2QZj_Y!0gF#eTWz+<{1n|C;$)0`*AQ^K zz>)a6gwV<#)tDVe2w3#fdzxjW zqVpSDCnls|cH(aEk5pL0n$J&&G4h`&EQO)bFQ}M2WONX1wCLZdxFiV6S;G5{>)?B= z2K`^a4@I?qW>HyleKph;@+hF8p&|M%`KLMZPfO%NdE}gu{ghD9%RsRG2aKR#z*fQ0 z;4c|qV9ESDgIsrf?M|E$8~sHAlX#{N)vNTMf&sn=|H=g z-NW$9%}}pyR@2$O(4B=7Q;NLaMgt*@0q!?sPfb9xYvGzuIKO$Jf+UhbwOy1Du;oBN zFu@sDkLIm#rgtOn)>p(s*F@yF?pSNX(UgBHHPp6+m$ZJ`278MK=D9^J;Y%ttmk}kMiPt-@JVwmd#Z4S)asuIoI$Vx;^J3YUAhm+Sy{2g^>MpT>5ahfTD*i+ ziP56EY@l$&K+pq3Gt7D8wEaj>Dgxjqjph4 zFMVRxcX;M6L(?TCGAInJ<`T_k63+v1%itX1bsMD4Ty@Gi1;2%lk{agJ@NSy`+%?f_Z&u8d+Ja;${Bg{hL(ow`99d8 zg-*%g2%UBr5DGq->#$VcufU1(dtH;+OmGnn+7;vFxzZeg)S$Uh@;WDJEa5cj;TNH z-2ax#VJd7^r(KBFXri>Sn0H)+2B8~ zYd9`tG~YGZkQLHIp~A3W!>c#bheL}fq9YDrlYlkaK$A>CCcT!`hnU%RxU#${W30-=TIbf?A>lG6Mw1hsL}=a}wPTYu zyT1@z#r8u0%2qK>7sep6q7XG`Vi3-|th?_q^Bg$o+!+1FqN!fiO!)R@$1V80X#8EE zkATe-T5>hN7@8|O8l~Ez>?acYdrC|;8&i-4w1eZsS_#b|%w1=*-O*On z0F2>Y%)@hV_ohJd5*3zZ~yTf($Th2)^1&z4`+i{ zi}H*nXPX$IH=+D4Q|0A>kCZ*UNFXc8h|7@JvhC32`^*{a$~P~U)cp<52M;OYeZx72 ztg5=Uu`Saz^3JtlP@OOCBDl(g-%I@mFk-9jO!k_c>a21VcSa^Nn{y4C3T{?@iv}hx z;sPKLvxR$}=3h!7$TYJ_VIgx7rWxT6+g-P?TP`mk z6Cy#kQ*nuzF47rw^{Wemcr8Ftmd=`%OYlk zc!%fK_Fk3n3Ep zuz8{C|AQ|4ACdU);{RWP_@B};?$7(sJ9S>3zkqW5H#Cg_BhR2~`_wLrx0w00O!!x` zOrO7i5wfX9qzl{}79v@Sy6W~(n88$ke_JB-3AxP&y5)O&+MeAv_sW`2e^l%jyiWcE z28ypJRRo*or)R*w9wDq2Fd7{@CRjU??G)!8s@|iWzsJJr(U8S7!Yll#wD`6XTf5QF z^z~2eVeX23ZJ{O`L4il-;ciuDvuvPcRU0g%uC|E>Rf<*>!hNhgpT6dp*D-h!gn4{* zE#;Pc$MLIVV?EMHSsMDI`P|U|7m%mPO0e&v53vi`-M6ZJGHP)P9XQ~WwCzNV9?|WYF5m_V}_l5xXqSIhc z(W_OVFIpAr>b<{YDVkDBg~OVWWA|2H;C1gyIZ_9J)bFcrAp=Ffh6X|@{np-s3Bh)d zGgb+!jQk6*4SxS$+`V;F9NYdU+JpoM1PDQchu{vu-5LoF0fM``2W=!lgA-gEcX#&y z0fM``d*kF)&OP^c&$;W}ncu86^VVC#Uo^ehwRcr_)mJ_OWxBYUY`dDiZL2L4Y!;k` zbe1`*ArDc9j4zlECin@;L3XvLriT3y_zKSa1qwCk615#_znlq7} z-n#BV#UrJ1{3$%u1g_uLn!iQb6sN|M#_lkB8u~Hx;tqA0)xU~t@7+m=Pp>}s$Q=z= zr^IdU*H21-T=E@(G)ZX%L$jw1da_y>ez!_w7i8O3(mR7Y*fvRzjjB(d#jw-z$%>i) z7im9;m)E}Z*{MfTJig^~;~GKmZkOJd8N2ZMx&;rG+Gmdqdb#Cs8gx6&*H$S|g-)JT z)cg8*fTpEYKK@afLHR<*lLJYCdX>l?=|+@5Pj^2K7_Jz))5>LqTZObAdRg1vHq9if zPoGEN&J>OxN*_(T8fH^1D;k^U(E6?;Ko~@vsiIUf5gPwQeawysBqJ)HWr!$FRSH!2Hc({p9s)$wchr+@?zZU?K<)0GXz>PYj z^D*dZ#}aU*B`#L}1wu+GSU(?7bI=vIEiNdp2_nM+rr6(%W7~Lp1Ege@G z<(iJ;^?T%8h}ye6RG>D>j$w6kP|>&o1fCj9QJngr)O<8yT_sV%%H2=(6?~IP{F3+{ z0Pmp^QaB$Eu(8XS`e~QN`Gnnxa%6YpzZR8fX;D_cCFzJ^uzX!gm>{9RQ3^K{zks^s znHU{wGqzJjd5nOwky#S6u!P)bOZ-^`pr2Q#jg74X0F$ZsniIevefD1X?#2G=|`uN!+-AhFR!w7XP;>LfPi-no@3O-`a|iHWa);I=ShL%LI!+Z;)Wg`U zrNE5vJk?j<}5l-aV5qo0Z4~(puvNOm6`d zw)*;A#E@kcn;)o_hy997*s+9&sMdBiemOL3^O5ZtNC}^1vB=ujl(3MW%3>*zhPQ*1 zViC)q)KMASB_E3!jeAouD>+>xg4UPGeV6He{CJioGQs}Y^Z9+NQ|V&60bi(H>X<>m z{W;%&025AT(;`q5AA0BBi{jl0IG^29Q_wBju63xXXZ&W}v=b z76_$T2Gc9W2X2wffCTHpA|5-FJ{Kk2Uu9>zQut!4ei-`==KC|E`f>I73RQ>X)^~L` zPo^pPA|`}2K)!j_NOaM)Wn?wNJ8#0j|LQB7QbZ^1{#QLpV|3!h3LZ8jo!}=&PizeF zRU10xHlo^Z2P{!JRm5MhK0oraP0bBeew}3$v}%y+uWEubq?xTC&?D946e5Bcl!JWV zBn1}V3trgCVr0j(9}{GNxVa>g$G9x*-1J^t`5khEC$aqk6}ch0*yL3(l%$mKQbgGj zynk|||wUXp1vdnIJ2A%ANtv5Wzs zT#UM1cL+RhizrM<^B7b9@5ZY?|G$Y>YnxlcI6=QamrB1tnIa=aZUX2e`z^+9=$$d% zRnuzyK%g26wvwgydL=*$DA}^Z5b7-zjFv-sogVV~ceiC~Xd05N>h6tWKKg1M)!r`B{ll`MB(S4AgOB54 zy&mx){&9p`qz0kGoBUespsb1(C+;u8?P@$b{TG>0zXA zHeaYXPmxqJb)#`#5LX?T)b(159>Ro#Aop^P(XR5x}n3NWeVHta6|O*s^mu4+Fl@QZ%JmdtIyN`v-K7Y^Xg z5UPLyx4;AF#zk6O?;>G!?E|&$;rrb=FVXq=qidjk_&J$bMnVtZwb)+QLTP+xp3l#3 z&jDO%QJ!`p;n|II00te$>c^i|?$PR@h?P_-DYW+z<6bvBsQ#SM`2~DyN811!c;NUh z0*GiQ_yOlBvk& z(E@P5BpH>R{PfUD=g7V$UrOre;>^3I5%Io#d2Ro1eyINvj&U( z9skVG1IO%xXcj&J9&*wPb-4Zv1nWQ*zkx}Q*qaneL*@OQ|2Vc9%to;#1aQ*@!-Hy( zd`Dj$mj|lFSDh;2;wkcoZ-M6Z&wzDuxIL2-qSAA5ySo50M!hfw^}@|ac<#t(AU!B>8c;5=U2Nbvt+kh}bL1rRF^YAz`k}M)om>Uk=tq`; z?|?y2tlql5lP>cSK2A$Z5?9R5)Wo3OfrCn2G`n=j`q>MHqadxXOeSim=Y;PLZDJ`r zva9lkT}4u7)c8rccTvY29nmf{yYq|vxQfh^y8Cz}r*p;&88CKD#iuC}i@1s*opTrC zLtm^7fe?y!7S-WP_Y}-B(mEMo+ZEGEqu8!kSz?ueIg~xQ%`PK1IPPgA-w`3#XVv3@ zW`s%;`u5jymyo28E5+-#azEX(e>A#jK3^Wiv91c;!0Q=aVBt8*Are$0(V2bUQA;^5 zDI>&g5=j}EkHn*;gz?(x`XD5o{cV>r#?CTstzp5Th2|7-jZpUkw1{BJN;iwoE7&zUtU-UJ5N(~+7cUG1_=WyS7E(fx%;I)v9vog5i#874gR*Ktg`9Z@N~g+&Z{+4D%(bdiL{d+9zo7 zSf9apeMUOFg-ba0+;#>FAE#|Fd%5Y*PgKTT8c55RFvqLE#D=@o&7q!6Q}fhk6PnO{ z+sHKvGU)Jcc)iA^tr?`9n@}Mvp69Sf(OOBXQGQLeG=13too9%13J7bdp~x;;*J@}* zg>fg^X*2F7ExRYEPsc#PT1vRYA5*_aWn{1go8rD|RMI9;;OVC}HSdxq*GaXpdsTmI zt+vbbRDCW?eVBSGfOg0Y7k$g44zyT*bYjTvo4L8T?1CWNJ{`77U^j>PbyK}c2=}!s z5>asoWAyI(CkfT3UJHydIz!yFmVhQCjLIf}CquGt3& zNSuUz^n?N5&w8?NXNSkXUvoyR0n(UAnWsVbkno`5w>!~zuAHbe-#8b%cv*x!Tn}{| z7ye9E_#2B0@+~t$V^ys-$rm{7qJtRydf>AwX(N?YC?xqMWJU0VI@aN!v`LN5dByX4 z(_t0IVHy^%PAm0Q!gTO|Hn7V4$Z2?0{m%HcXbA~kLnF?BSmlR)&X@bL?~o9!C9k28 z<{rXCCwW#8`c2Ofo13S{%icYPs-s`Z+&wxgA8P0h%&sAO&!mqw^)}t!c2AzCn7{d= zwU^Fc-+6X&7I#ofu1O|C6G48sJE_gY{q%N@r75giX5d(rH&$Y*&^Y|&{Ev)K*S8Ga0Xx@Im*^#V@dg)F* zI$HZl#1ehEUn%xWAfxwn0R9vRW5JTvVZl0N{Qvg#|luugk;oQ5MK)<8px+fkNcmB`r0t=D@u{qDyS9j2|zMSTXUZ@RLl+$WH~Gv;+?%z6y6E;LQ|TnP$vT48H+btGG>R%N`~&sbEsH(& z*1lg=*OVZ5M82uvWWnCGH+{e4s8G9)GPQ2bS9z%BxcJ%1AA1TX962GE1NN-+00DzW1=y)u^u{Hqsu>ZE5GaBs2?sjw8I$~^ zBAm8nDo#%>J{B>vQEM8SSEHKI`NnBB~ z{w9aXI9?e1f-s1_$syM<2-zn}Oe{^DD$av+w;WMLzo9WLkEN3Ju%oNMFhl~*k${4< zA^T>E{{WS01mTIatvQQ!vUD(#MY%dz7va7wuZ1Z;6gIK-1P*|2YTI#J@S*w~hN0~q zt*`mN%gO!Na93=Tn_6O7iO|75?^5Uen%3UTMSCoJF1jC3R84Qe`Z1|;m->#N*mrQU zWOXiWlCFv5Wb=(Jb-6PIq$sdZi;Jx1_j2 z^@HV0+DZFJh_GM@U8ZsEgFz&s$zVJkOqdgHxhI7tHSwu?9Ti$G*5=eT@ts^bQ@fQ{H7GP&uo(Z>Z+an<=H@T9(dV>!-Xva)i_2 zq(2fMC_Pk?9ey9^Y~S~eOXh1s9#EA0>L7VVEA5A0^lSl??f}7Ib+~1fzN+ zQ&t`dHwtmoTQ`JTl2ZQyiE3tZ;sg`7`G^1ti3!|Dq>YuL`3T`Z5@kNtDHrJY94fr| zESVLXgqLAcN$KF@XjLdvHv5e62`z1v7n^$2=-$E&(fb|zeO;Gbf9GTer?9U+pK8M4 z!|6B}s$2|s>+RHazXWRPTE8cMJBpywRm|4-V1pP(=lQ{@|La9ol6@{uZ=7i8Q<9Ia z{zY@IhdS8p^GjxJHW1@RztPR+jUiLUxRf-qULew<;2MJv6P{Ya1WXPtlbMUX88YQt z`|O&{tK$}XaQ0<5qtb3H0V56XC!#|~^cqf)*>iFz@#XH#>^Bzti_f&-l5W!;T%(6v zU8HR7^)x&C(y^@ymy5J0Ftq077Yv2xSNJI0^=H27M__)lwdm9S$U4^yxL?{W zIH=Lrc`|Z8r##viE^Z$8f7wThZ2lZ`p9V!)ytm=r_WNy*SiMhWqGTr&6_-;ZJdwq{ zJWvtbHD$(YXMkJ&nROrUy-sI9$6DFo`Xf5$t=RGaw@aw!y0?96`3KIj7K=R+k(p(J z4OtFA5e-*I=zAp&>e$vzxgjf|W3v92?8hyu+0R-JwF&GKDc^rrNzSeZk4L{+J9nSfylY`0KU3@}z^Q&3;3XcHz61D2D*9ZWBeRQ_Gq; z%4mQL2TORVcP-%!jJ9zfeGYdGk?9mW=lGAG}COmd5&4Pz^S%KtFTwk-*Sdk86c zZ*_GF@B4t51+>g(>$;CYw{@ zYSs8LmYBPPd%BMZ=%lQ} zG^9shSvR3C)GS$dajPeRCZp1}`$E%Yti&cjyZvw`g>VP*NJcyy#VXkNAOGV- zh$&r&q5ZrP32GR*oeQeXJdhX}6w{o5A;7vuHlPeah$SR}E6az^Fr-^xZ?@N=G@k`& z88EPAWC(kRzLF4ONR!*aKmUNb6GECjBVj*(bl36$4D|~}sQ^9o)O7pZdctIRuy2WI z5K|5$ieYvJfzVAGCdITo?0qT(=MnNqcI_^i0CO`u^+B1UYW`Ia^ zzAo(o-1j?G0CPU9J_ZEk{LzX?Gm7B82`r}$jd9|Q%}c?J{^^2uiqy~`SaOrj^2`s^F? z{L$re6Qmke#RUN(gXKId6rf;eUjWk3}QrYy~NPdwF8tmCuEZyHf5aVD5BNj5-To$ zj)~Zy0y@GeLL?pRj4?dh5 zS-T6VNer^lER|+J#^d&vr{olAGA^ToI46x-d zP@ql0VJI$LV~>W_&sM@wmuxGk`hD4yC2-xU^+Jq^akK`@L7Cb~-Luv+oEzbL77F6- z!seJ)Pd3b+l3h%8V`-^W^(HOU)aMyL=t_K4XD>}~utAL)ZRYp2UKpbPx)|nEyEIyD zO#nV(Z_vw$4X&)LhM&j&(k{2{S!86S<`g2=l@jqBReSOl!=?FkkE<*fdXRW3J7cNt zT42EeLy-NFlTU(iQSwp8fSU-;?qDrnNt#N97DnZJj+{2o>YFgOHfd%FbeZ` z@_NzC=X0{@?2BV@E1k*wE8b%^mqcVZD`r+m2&2KRQFD5br{R7Z)UB8&N z+jr1W=O%{3>%nL zVj$k8+#;X6Iduc;g#m zZ)Ui5!VzXRnXRjZ-v%j=?fD4kwLLE@AmhDUow8Z( zuGu&)DWAa9X}KpE{@{8Ef322V=bRgv&aC@+dLoMG_IMBRq)gUkU-r%4=So_fN)qwx z@W#|t5_8>e%O~k8fG={QTLqtd|tVa_M6R1o>j> zsCo=@3*{u~Hu`Ow_JhzP_U`}gWz`=cw9h2VBtR!Rt~o~EclXo^$$lxb$YQdSr@~$( z>SJ*kav0QRt#Tahx$NOP{2m(kKKPmb8*XJ9Bz38_S6Tg@^$thS=egd@&F_yV+0uQT zL!|hXEE&fMb@NjUT2(7n@7k0rD?22lrCY*d9JFbw?-y2+58>Nu*`gOvK!|Znz zRjTr2?Prpjh7;mt+z@@XK6myGyCF>Ux;o{;kAK?^sq87U(NRXVo-G<4|E|E8A~knp zHPg>-jOCzQE6XeTODqyS|{9fB4B{9)0y?N$|VUhKjHnu9XeN z?uln#{4eP&x}+JQMzZfp-V(h^>U|ZPgGuNDLd)>?JY&i|uiv@aHp<$fUn;;qiDv0@ znM9=0Crv`BeY++8F%YK=X?Co@uiz{NDKoUS_vLHT?3_X;n}QH-q8EOWgGq!RPY8d) zw1}8c9g_&>3Aj69l;?eHKLe4{wgT&(U=?aC|o2ZgA_yxuVeIy5*3w~ zdM!K0n%tSFde`F)&*%yZwdo+xG z@6>wfD@yx~BAwP77oaJz7noPU*{eS<3bD{Y&ir;q{LYrrqF|AmY-j+rQGSdYjUj#) zeOzq=iqO=Z-Nb(50+X?ZMerVe@9`6*oNhdqD>h%;`MEN%ivQyr1}7OSH?b_Nq03CZm#!o-XS zbh;&*J3A09QmOrf?_11rwsCeg9P}Ah(4hk~hRww$)S%F4p4`vOCyJvVs`QODP~j!$ zNgGRj@=63oK2H*!1v%-0eN%tS4Z+eCk!9ry8gu!_WueP&YCCtBYbkBc+Aq}|UmG@O zVIv|)C2$po8PB^GQJbrzbB4Q7yc*aHkGAPJJBWRXtGz{vf9z%^L^@?nv7#rtn(z{|ElgRH}Y z!9R>;n8u&KBD5HVia_(dpd)Qgi{4zhs?+ODVvMJY{lt_@`h@Kxi?IgaxrL z$ey8Q4uM@Q{?+jL8-U|qFPMIf{m;`8#i?p%DF<_nA3e%0He?rv&8#q&igJbm!)wnj zf-Bj6NRPJMO8iNj>QX&)bT@}#BJr%@t;yz5>o`J!hE6ha$_53Hz$Gf1n=uYc5(a!U3xCqmDHu5?%Qgc6;dL6)!}w0z#-=5A&L1 zYL&X0ogCP-M+4M5N{(u9ea0crFO^TcL@Ri_L{-cc+>Q$3GqvppO>Dyz8tLK~RR)W;aI%X{;{2%Tme}Ud- z-89&7E*6&$sU=ZnZ?%B{Kl(`lXvDnH?br&)>d1y zg&a3@yj9MM+69VP_BpoAsePjr_}6PWCAB$dNkRkB-g#WLL;PR35|f$EQRy{x3_zgG zFyeUfcq08~PM1x3tP9V*h=u$r_ZU*WX!$?bAc;uwJ8NWj*24 zCGuL5_pWP)9V_y&Yh1cTn?$IMH2@CPHqMdbXT}_kX>ryd!MzgXZIeNIKfZ}eZHQ?t zlXpWB5omE=?%Ar#9xpZBC~13LhR~l|%_5H4HU%h#_IeIrWPR~S&Uxn)lnJusQ1;&xi4)DVLu#dho%k+QN2Mk8dpl5hHuRoG*P*nOK;kZfU_q{ygw=;GmGldhmBaoL| zBtP8+E3#z&W$9k%{u_f!;7*>NQB}OW;qn-AkNfW!+>OaUFu0TjkHI9!5gVI#@S2nV z0fYNJA#?7{$?wXI$h*&>ty{=s6~Rl{x?<_$HiT`=`&qw0;JwSO`IREbaoHurS_kq8 zQu+(@MQ7(MgTPl5Vhbx=RWDHP&$k)svW7wFBu}{P3O;G!-#ogvN@>n6BoC`wmB%ncMsHN*g4?lo2QO? zgx({j^x`4$VH8SpDM-iJa77KEhK1|hV53<5K`P^~f}CMM$z%mvvLElg9`GhM0MWFA zck)^b>}tV~8hsT6rA)}Tqw(~9PqsZS`BDbnrp>VomLG!rU_|0X9r~fg$L-oLD0>kW zzxWH3D5e~I_v9`X4DIA6Nsq7t3M-VtR38yPh5<_3(%Wr|KuxOPy&_}B^t_m|@C@;a zBK8Z5zJT1%m(82mwfRny5ocfeh<|?7STcP+DDX(`pe-p*6G{I(RQ1vxXTDg;BI~?P zQbzv`G9~j@B*Y}z*S0&h*UTiz$>L3i_sqA&=rP=1L`4X zMgXv|-OT)I>EC~6aV5gH;f=UjW7oWP%ng9j?bv=|!fFZ#;~?s~JH;=#=N=bTG)vEH zS!p)v?#hzw=6t*tFY-FR<33yihOf)-*neV$`wExkok3DaprRXyZ)U;J?@n0yVy7^v zd$iJoM}qdtGiSI$wdc=6czvk-ZW_c?NrRkYH(A7ZK0l?&%r6bh8)7j(ey_^S(wkEL z5FBVVoKU(brp_#DFv57Bz2m2}7CS2ynxqT8Or0fN9gHG{bGs1&k%0)KJUaEr?0`hP zM-e=OL4BZb>f>p+30$_PAqxPxhxb!{sQ*8~dkYG1%%E^U3SB!Y>jO8)1s*Bjk;x_~ zuYXebP0f2zZk;c+;s2Ivdf8c#V?7aiHzL6_( zntj2Li5ieNV0H!$gY`o3;3Xh$==?8&-+$o@figm??Ci4YT-hiDSB^5#Lt?tQmH&Gw zyI=`{>Q2L(151$ym0C{c0`sB(&oaX@O{L?YkTCj|D*VEcjz(JOb2uJ@+``ZN1d;2; z*!v3i1}!g%vro6g+UE(Q(LsqQK0~1>M&P*i=zl*UVCxRs_eX%Ze9P4x|jw78aUI^Adrv6xOH|!DwW^ zf8L6_ZRn~D6leUij{5!|==Ts^sC`0mSG}$D@yY!{D+R=Ulm2rmz`uAcsMGBwAfgc! zk}DNo+n=TV{TqcAwS!+CGuAey2g7G(CRYCFk#~i(4yBrLuDptlCv%)!(T8Hu25VaD z1>FlVtDG0%{NWXu#U(|SLN%Yq&~WOYJA`eUR$?}8C8%!MIRPmx zCFC`wEG#)4+0pR973AmSN$elP-)jAw+ucgw44S&)={|p}$kFEJfo-%m^ml0YzcPbA z;iG?)UVn}M&yxgA%;2))R>%nNSm5KbYR260HPdZ*7bI6h(+Utm&f6P*@tFDtZjd&- zMyiD1-TP@uvMQ5PRhPl(0PB;xb`RwzGoxw`-?ztRzqHUfT%5=q6}c$d1Te0>jlRN{ zyV0z*gSKE`!f_y`I6ffA6lG@QL%WNLDo|ltJY1S=fp$|o(&gX#2-sH_zq>k2V zw+_#PyDIsO5r~vULk#c&DB2c!z$m7XuqH#Nc>Op|0uG_o4BiII!D?T}RYA7t`-n6u zNCjZ2m|jG9uKj?rjb6|;Pp>2oN!NyB)lIpzsT{z2{c?_~krsV)-!U|4&OOX(>o``lQ^=6u>BP z31rF(7e$xm5F@%G`P7|$Zj!FAZ{Xn{ayZ()4D&Ic2sYf+x^5rdEwyiGZl^3{hOK#s zAO7h2vbH3&CD|lh>vc|nleoPs_WD|be|PDqq|k=pXD3l#^zma~ST5{JFV9GoWz*wb z*PMWY*C_)+NJtn=ufTNG>?+Trv9_Tp_h?46eraIi?-!5!zb+ml=zrndmY@`e0UHCt z{{Pz84ODj)d2f8%omEcaWLtn z!8V8fo`Lw{*j06!(`j)Y$(3MMdw(nG7bxny`xr(IIlpv!{O8BT`0Gv8>$G)+&aTqLC+l8*z2x*iuYFZ@c2&UJ{%PSdjKaRA zpKb-=U9;7Ee1^%P+8^<7FcznMv*ReI%fi5g=?5en54N;6?BSa%)(QQYI1*9q4V%rH z*dsp)8}rQ&X?T}pF8GCpDa+)-o+%tnhIEXc^DV0(Y%UX;fYs~3D37?Q@y0X>8=B1k zY50QDu`NF*{wd1@ZG(N3im83g*?-)5uq(LOA5e$5et`fz_t|Y~)r=XY?sR0pkr>u#0l%LQVXq2CU!skIiaSg~deeg6 zD4{=VF^PTgN3@Bl zx=oItKFDnGTXkCczfZcmBrxLOQ4br-9%NGL6`T-+SoO|YYz|g3Hs!rtRYrihFld=&Gk&zz%3k1v2nI=F<+c=5d)`RI@QINTk zxL(nEWcwL#F%GHI^aE-fRbCIB?SP@t5lP3JxYU-U*8ulT4xnUm?Y#vIY`b`{+oihh zzV5(IH=o=!GgcQ0-Wk@IYBu}=(f5YL$guwR z^-7>VJ7tF9=T5d9L9-WWA!EZGA{o54rm&o>s4+10)xO1v^$GJz4LBZMQt=ac^ z50#DLQDxSU)g^{^?j(~s4K3KUadsp%^Q4Ykgt$^KdK8=t4I~x3^R!`i}^K zdFDPO)-y{?J7@)wlwg2_B*-%s+`%Vr=!mFyx7fyjAq5Pp`AeHQ>%j9qOHA_{41RkJ zpKLCo;v5hN{#%Dx97^Nlm3R-NOe|swlm8euN}_)pkq&r+jU1ppepsf!kbDO-1++2p zVqpk?AD4kZ-v|IZXGYj0x(DFoN|ZZKIY6AIYVn&;Mhex!?6;HkZr-$HaWkI&K$B_( zbU~Cxdff&npuk8-@3FwlF~%Q=e4tq1f$Su!fhYW?BusHZ(1iQ-77QWH8IM&ljhqAc zk!~z7^>KCU@jTTWlx6}jIbdo51T_qnx|Wg2-X8FuLaD34jBTL{=%Map;Y7Yii2Y)k zAAT<{L_KdiKSUp*|5yj~)iGei*P|G=`o~`|EF$kWyiR_B09t4l&B4&o=x>P@ta%Yf z68i&mm!O7?u2`u4DZ=CR?<|ifpO*G*n}QnVuQip1g&5^%pdJliBh*kJC zTDcn};016ti?B#iuA1*3S8)lmC}K`+fDSqZi-(X%Q0*vAHMky4?|?b5O-wOp*TA}> z+bqN^+9KW>02K%<6_O>B=X-w=B&dUD0tGgu6g<-P@17-Fw={2^%q6<=$dz`zeU^y@Rd!|b z)J)dHZ!+m#oGNk++<==AGS@;R$S*VUUGoa6c8$NbH(LknOdG9b@yw^`H0p-Sow+oL z&-+eqbDM4X0&#wUn6+?Sm_?S;zrXslH{Vw*kBN@65#A$0|KW$SKZ3)PmSRM5Z4`f^ zp@=ehv1EfKu5UPpr`ogWHS>;!Z1^0!l=+6c2Q&r2(kwVXCai|U!^Z1~IA~t6(jXgy zs3V&kd|SP6#{&xU{}Mv~PLmAWc1qeBMJ1Q})X08;c$g=Z1dJs&V}@Tp?j9)KTU+UF z>o69iSvc>0_-j)2_q^m^@BB}Vwto-(?+4{GNqM*Ap0t87@dv23su{z&*k9xCY+(dA zaU&!+gkg7%Ff5Bd9>M>}kN#YTYQz-D=!cc%$9&xjZcS|8E%csNoriQ7ubP7u!D*Z| zAVEzI5tyK>SN&9P4S;Fp&TiQj;D3Q8r60eb2$XDG^Fc~4zikL2%ifM?>rw(-nBRAk ze@@=DGDAwpak2RuTk}6GnH4OM%U&_70!1mMsoL~x9`?ybJ>KAp{Z1;UmZ+oFpQ?^XT{ZPe1EMaQ0lp;4!So0A&BzS~84(sndx z(p#PRp#A`Bw0*wQWU>%?9DrW~opJ58F(0Sy)t;xk#M!whjL+6Kpwu2V@Y$8kG{C}B z9d~f{rr~3oV7Xx^l+u}5w<(mITa3G%}o_Defv!yf0qDpOY z8%lAX9Fm4V#dPwW+WIPb2bk?#RV~qyMDG`O{pR0H`S*7pDE|f>0&N4L{1Sw8<-bSi}i5I9U<*scM*#IP$Ko{sPSvx@8)X!~j|c zu}d>)f0Rx$?OC1=@A>n!Bp|ba%M8xOd#=uT<%EaGdTzcqJ&?KkmxY zoU-^D24ha?@-dtrA>Gg4chzt{q71jjFU!+893C%{u3nlRv;ICm*Ktm%{eyRely0Y} zj>k2%j8EBYx=5~NJ~dA@-h9$>*SXBl_I;VYht%(sJ~+2c&Q2u)wqUBsoIx-sR{3pDQPo5`p^C1p#=_t|Ar{^#d#w zoXk1m9YtJjKrKxXXTmEYJ=QGLp|#!fUQ|p|@sCRHZywuUE4z#lRf6f^LAg(b5cOXI zCTJmd=&q*#3(hP2(MuCxu`EIKY|pX)KAyjz3B<`P#7$n$)*-0cwvPJ71)pq*-~R}` zUra#}13tlZ-nwrcD8+Ii$3BRINL;JE$^bKipLLu%OWv0lwmYMnFK0N;Pu-|PO+^-X zVCPpmp~4?N?@@!?4!0-8lx$Fk%I_X^nE=vV2T-U5BC-m|K-ba@pxh-f%8R)#ZoQg^GK6~kwoUi|@8FRfhG7ejC875c14@ksuMdJXKWhB9!x_&FuTx;! zdSm{?mN}qEt}%+sJSw0RsAg+x+cdqg6qKixoF(=e;~O0q_USxkUpj(fjT`fVomKQRg?77oaqid}7OKXd?`OiJb^Rc?Up( zTz!(j)BY3)w#0)9<`keb*ks>%gWa3GbXb5Xge5nnW~aA-a3?XjP!1p&iM)Jy2nWPi zzm-5N0hCkb;EetmP*x`{mLIVNLN;e^QG|BA^Rw$6;8*gn+BIUYv`Gv(>;Z{+Lxgnz zPACqKdsDsZ@kH1(ocCTsvKF^DDe(JD+{qeUd^ryOkNv*9V5XE~ z)B>OCV#?RAi@UpDu;r9?GnvY(SRD>X5s7y*_yo$uNS5$-5UhI|~C}L+%UYus| zzgWq392Wi7z*V!h4<3FFi72fXW7O1Wx3)Fh*-yGkK|-Ol#O#$C&Ov|DxLXw$!$p$n zOypls>`tFiF}aGUH+P*k%HD3UPgE&WTx?yS4VmHaU_&!jG`F0c@mHR@Y@NlHf%Ynr zlNm2in4e;GYh};^hs674W=Kk?`rk88MZV17Xmi)ZH9Tt1W;?v4P!$2*> z?Bj+^g&t5S@uPsS(!FyHp{qWn=jE$p{EvQ5i1bJ~niYI}uG>Zah;f|$e8~STocQ+_ zxc?o$!T$p>jw;7`8B_EF1DA)Pm37K_T-t*|ib{2AUg+)Pc&}`F_YKq7IK7bZ4nZy> z5t=KT=- z1)?|)mpFI?d}S3c7wH+?lfi)rWd zZRJ%Qi6C&IeYgqy1=?t}|NfA^d?Bko_2)@jJ(>ql%;-mu5&Fn^;s;>z=9T?fp9~9uzhysE>H+W&!kTDH>-LsM=An$f zk<4fWgAdz;4Z)|m3MU?|L@O6P6$~Ep&DyXd;@hkA&W{BGFxQcmu%@hxjoqeHMz0%` zx`UfOFh1IOx zBwHPCAfQ}?an?|;LizCmuSTnT1&*Hf05$!}*mM5xf}|&q?A?|UzM)#zGx%q>;>mMy z{!lO6_&Uj3J@kvuJvvPHv3ZF{!Z(Qi4^*;;=3CZPZIO6PV{A(kIU`x9*fGFB{euTM z7J1tk+h;Ue9+BR{E5ATe;~pAr|2jAg1)Dwe?07I+n>l=W9WkW!lJh@IT4LCdCCg*+ zosa!u*=70Gxr1|ZnPInM*`xBT`_toggRzG{zcF<$(OGJ8UHW^0BfMTo4vCx(iTZDeL$`eD@hwE ziJ>stZ7T_!PUgm95&1WlgY5LLBoDa|u%`Ar)*VxGN-X~zuC*}7Iy&3dnwYC}mq37n z_&A`d|JTi~9KW+pz4z(xj>?7QR844Sl@;*Hk`#+G+)e(6oz|e@n4K&p$&Ld^scdn^ z|2WPcIz)_HC)H?kZ^QxpJ0Hm|kFBNrzZRB# ziEFmMCpRv!j~VKHY5v#s|K(!QijI24n;H(e+jCSMpvcWulu$zy1Kq7H1rQi#>&Wg_ z149cj<3Y?_7KZ-o^d+|IqfHVNGpo*KiOK1OcNoMT&qlrAm_)kwh%? zu5?hO_g)eNg$N>2q=-^N6+}Qv=m9|y0g)ypG(oBqX`uwdH^F`OKKmT^^E^Mk_lK8w z5tFr6=9+8V;~rz&bFA)(?__v8T(*y$x2^mTLKA%2j%DXj_Zd|OSF9e-6R&vDBM}t| ztYqFNG*0N(4%D%RS+MGT?)N&WK_Se+@pPN(VdN93xr}F@yFMH#t9mgl(@#?o;}fIS zlkZtDf3UCIVkQmH?841vm;O^uG52SwEUYhS@|Xv@unL?OF^1Jk3%fXw3Fc|J!f#GA z+RuFWrB9fK{c!gC)7^1ErvYyVkpsrx$xuCN$&QreN>pCKbTZg+C0z3oYYqgoSou)~ zL-^#VWfXQ`e?T2f+{mZV1>e#O`o|xM^Z@_|r__&3La&wlje}!v3IL)8mcU1~4HyAS zBx;x=4wzb~)6kDpoNyxHXiRqALs5oZ3*b}XWp7gG0D;VQc>Y)3D_*RFS*zI4O+oq+I;r)uTo=2~ zXdUL2L61Q_YVC)(#va6~PhR)JNU8BC#L(z8equJq-kW8_{!V~BdEneQGy5HBQE{ex zkjWp>jZ8Nj^iGbjG?B=1eE$Z0n6*xh5^+A%+E`l?^8GkDP=db_(%1Y?#P}C`^gsTF z`TsI*=>H9{yic5gt*%G_670OBGwcI0k#UmmJ1(<&;rzY|OFwFSgAeILiOE0F)SBc@ zz3u7B&>ecBrtrc!lAhg`ScrI_ot(OfkRA zW$yOvN3+%Um~tL2J)DxBd3x;(d06IU&WNCEQYJ0^0xIz}Zx?99r;KS1wJ92ugM8<; z(u!IJy|utfC1H*W^Z_TLQX)S`cD7c<=!@&ypHsYp-QqPihFRa+W$pgNw{?$w+nFe_ zQ2}c|(umpxp_QXKZSjETYmEq-2a#|Ye!ie5bYWstZ4Y9dvO&3(*6+LrslpN0wqi!V zC%L-pCZ(=9Yw)K|zVM&L&3BK0$EO4p9{iWu_c5aAf5dUS{%`7NM3 z%dMq2e)bxgS8_%iA;fh4h=`CEpPr6dp_d@D`2?64qOVyoVRre+-8&Y-h-&&N>bDcl#0wADKZkz&wqNDRn3m%?uUU8 zCOf^h8!@4HOZ3t{j#L}$w87?1=-)drPtmRDBT9VuK0!08#Sr-gcU)%ri(f}^rlDyU zk`I9BFSnP9vvmCUBW0gUcij%@54>pZeq=-m5TxC|r$=vGD{aMpJ$oy-oiWvCcibT| zQRbRm#~F(u?|?~%NLN3&kDU30{SCjZ+I!WVuO3S(h>RHB?u&|h8MkE2V3hO5?=bxr z38%c~NwtfK{JOz2*K8`k{dnjJpL(11#+9tbCzZ@ZRA%J3oXq9rX8P}BdyuT>p?i=i zo@Ie*ogD{Q6)CHFY77-k+00FV>_NKP!D0~OdnEVA@6wjv2?QoknaX@yoH<55*{VCb z)0D!qps`#;`mr6y@m1v1uxlHuS}Z_Ma{>RTa{VwP!#CG#I&E|qq0AH9M^|rC*Awn; zqA`0A69PQH5_ULtd3G8$7&Uc4%%oOkQlos=DC#{(FD+Aiaf{qSy1H)?FdM#7wkL~# zw6XbG8J*@O^0(-U(|`plEyb-NDl))42flvsu>z%7xp_x7E4CA;9_0sB}jT_PY0mcnPJoHP!b2x*vmpQH>jXUf}!2?O8 z9an#tIk6N0J>a;?xevO2+Dn0GU+{#sp#KyB*UAltS0^c{%3JmQ+%YLdD0D^R1eLcI z(+Rb8Ra^;f>QQ|O{mJ+(+1v;}j%UOPY-;5n?LQ!Ae0p!b1B}%DTA*h#X8zEIS;!si{jQn?hN{skCZuN%Il8#f(=A<>y&GIU*Y;i48p z^cOwY9j#6I9bE)9x{RF4i|Qd%MXjqPO6x)3AXn-Q&2L4l9Sa}>HZJ&vV@1%u^mJDD z>@GT}lWCi)pNEqWcLbfrhT#KKC_sDEr?hF!1|hhR z7Jicr{?L(LsPe&-WTT)DbPdNb{7r7fQvL5F5K=FmXD$3#0YvE*qbu#lBpo`}^W%P> zTdRd{LRE8KDVP{C4<3(7h-7VK{4W2^#kg?cQjtcSnUOcQSMeg#<&k1@H8Hk&azD!Z zf`WsLhYkAHB(;`IUDLX_vkQ7})m#)(zSfeL1aG?2Vj?M>IT(2HIU_fqPhLM%laRUyzd;Y?|1GW>p(^{S2la|ut&&4C<;b?V zpV{Ww-M9d*pE`9U#?koN=-rNu@b8OsV?Sf7a31lqe(X_S-PayAt}fcIM90mos@N0y z>=tX+3%&DwC0u=XPuO%+jw)iYCQ)u$4ATI3SLoZXvH|NrJ3Xzo56rN3OxO1%|6XpmAoTSPCWd4C z!*j=-g^|VC>QLIRgz3@G)u(c*&RqE_r`B$C{mn}4_Yb-YY@hF?#nW$pj(6(MwchYn z8xnQGV!d&xUMe|NN4^<2=cPX4nAJr|3m+j47exPM@o-oYVYS%0y1j~6uzOHK00x!v z@=cWS28@2`@LRU5xz}q&AK3HSt}Dz|kIrAGd)8U+J5+3LS-vf~;3RfUK6=3q#bcX_mz_-<2;BZ^6Xw2r1s<;*Mo9MLoI|2V6*lPzz|X??e{wk#(7bPj**nc{ zCD#3M)yLN{_`G+dVQZc`1+f)X6`;Y{%psD6I**}3*}mWivKucSpxk#hLuYBQ>0wjg zqC4-zx3Xnb`dJH!n`Qh)rG;Q*@dzkL*odJ8`&Zuso=M~SfS#)Wc z3?Y?dC6^1H%K6VrZt~;bT{V5Fe_e7b#XntCz1WJ#=>^AO#WWC^isTr1hNN>n+qK?n zfpRK2VaA@g#mn88O0ld#AU`%*zXv%cmyVkET#}ZsJb}>6Ri|?-$udtW_t5U3C z+zCL~7ne^2JRK3THW9I)_S15IA|d=4Hv0>hY5DBg5kF> zBDd>C&sNJAK~TI?$2fLVsDFD@#@hwsvZzrL$DL%Ki%ZDg8ix|3UdcqVVjq4Xwbz{5 z!2Q+-=diBn%Dj6%Y6{c9581M2QoYBE}T150*361emaZaYe-b5{k)@gG0MnO5EP zl=M9s3y$xD|MWRvo{bTDxmxB{A`0+yffc_$Zvjv4rXWY^R0n2C4+!eO=`FMw}guvZ@uU;bQ$x6>2r-MtmFPNa zDx;L=iSI}sNXNI!L?v)O0WxLh3ZCq2U~>Mh{L5Y;l43;ZL9(aa8q1u z@#C8rh0mXzwgzJ=Rb=@)wxQ9E1t|-oE^!J z>1!se@yt7Wzn2YUB39gG$xBcj@J!BcX-oR7L{8V;(!=PZulcU1is1C)RneeLrsLp( zxC#vmVa`@a%7ts;Tz22#2u7^9I@_%WciOm*Hr=Xj5^$+9ynA>5b%!1NJtZoEP&L}C zqI7U9+A?tPEh4ty@MSrha1(>;e1qnr9fd;}VIf=fFB%<#AjbZ&R@WyYH;8+c89;8s zc8CRs_aL8YjXIW7vnhP9Z;8wb6K`yIy1ef3zze3$Ye%Jm_>{E_I_G;8fq7itwV%LK zKFV$o!a!hbP6fkpoH+L8)qZIX^+nwG$F1or|Cs%{sCO`{LW|)Xnwr-V?c57DL0Ed& zvD6Jil|WT!i<*gWRUuu`D7xElJA`*f|6QK;*cYL+ z)#NR>2DmX*=sV!F;`9ouVnBRGeeFS%aac_Q?rf;Ahyw=V8h>@o!%dco>0xY8)w5e# zHsJz~DfrP_kx-ifMNQcc^bVBca~R>X?`pX)&YbJM1TAL4ppBbI9nVKM7wE_5F+#8W zhP&C*`Pcp95XX1n(py@ajdom5ZF}7PGnOCzrT_r*4Q_-L!^(L9FB*OdBD-rt*c~aJ zU%&{-R)MJ6jleG$VM9;_00jU36;@R)0a-VS+8?Ht7ewY4es&sE6>#Yyky=1J_IpuQ zaGZlG|4jlY_){T>Xt5FodeEi2_rc(`L98K}yfsE>4kGE?+rvwT1K8c;*$F|)(Ne$d zol--5F-QB)<-B$*Wyzw&@iy3TEG22{T zd)sE7km^ps9^!iqOLzL^cqDqVINs}Ri-1}?m`7JE5dKZ1Y0i3Dz4Kn0<1KE%{GvMs zZWU5{kl=DM3mLx8SqqnrvRQL=Cj!&)PA-|>7U9P$iImJ+jXx>JqTF5Po!#e@wLdjf z^)e}!U;P|b%E@D-(P)u>^v8!2B~W|y(phd^=j!KIB#X^tEIpIn+V!)RyA&JCT*{Ly zANS3@@ciSt8`2*Ii^)MqT$fZH@Lxkn+|ow-Efxl&vmbFisam+xr=z+ql}W&oDVC=)6vC=lZ7WxE(R~eJCJ#%-@H6qCn|I-T6}@ zgwc5^A)yq-3zt|4)ARhj?TGQS6ZByVUi;gT;b`QK(x}z51ddOe<1@6%sAnSCA4sE5 z3Z^$Zx)0T4?j)=w1ZD-0#lq!NP;5Y2XG?b>>QiA`H=fuUp&t2cTHf^94(3!WT=UqLyK~>7zb@kN zXC`Ue59suxZ3@|7s$?msPa`zR*z2JihtQZqf~-Xu)8iQa_twQYxiXM|Bc|iESsegw zA@OTz3(~2TwNUjFmrgA7kYiI@;X3D>9(ncO2RdU-0p%iyya%ERgjoIGEx_97QYhpH z6oL^rm&%huq?-V$6=u4c@NlQYY$2`FMeAD3>{c%(Dj##hjcmfjZTQo+yCR{t?LlgN#%35r_)6CLh)VjaJNIVqn`$F(Zr`lys(Y?A%U3=|K0N^34C>FsPxi+h zLSs8mpbI$aGiLN=@9oL~nSr#(KRN*37@7`mSI7WO_&p41)qkn4{rK5>XQc*2o2#2pRd9g%e?DyObs4^oHg z-7WJ4IbYQzM*qADecOKtoLjHHDt?e+nuZZpvfN&>L5_mv(V?*y;q>>+V$f-nHvV9S z&GfG0zZ6;j^4>Z+R|JKDA)5crH>o|m3wbzCH_`!Pgu0#QJ$(5xd6A-GVKv-D(_aOc zTc^1$AEw2{1poz@Q2%kyfx?UCxaUeW((#DvdGq$PD0O- zTLy4&b}~cQ(ia~>y~?x5r6)N~DTD1;rk-E$9EYU^psD;)pCtx>USNsR578|}@O&1X zK$Q1_XH*AO}K`~|>R#m2%cqyh2? z{ZkRdR0_vCeHlEEP#tVb-?>}b-jLL40E4qY)&pU`j1jW=S91(e)FjYo#Xva%L{^yB zP@TYVFz2)tZfw~ZMh4}(3u5V{^%SBsYc?I0yS(q@?gF=I#WA39?_{|0=9NDk ztPHO8Y0Hh|k3wNV|In=^R|_O+=^|Lp!R0QibhN;=f^|diy&!;}!LlXOnGcL|y`n_6 zys!k&jWZ=W>aijRc+_dhrJtRbT0_(@s-omM=z&dK=?cB({$9Vo;T}9M|3)DF?H|m0 z{}viqH(ZJ+RRu&9MhKHl?DRJlW5_v{ogRNRBDg#Rj>!drD@O_ETh)4+wLA_aYCo=q)Q{ z!zInw-i?pHrzADy^|>#Iu&qwk(BAVkrrVsM;^#MA6q39Nk8;+_Cce)}VxGy63DhRN zm;V4m07GRefjYDz#wOiZ1vAwCH1ai@`y>~hl;Gc=6s38!PONDu@NI3x(cQ!a*V2hY z8nq$kh98rV>JNz?dh5d+{67K<=BGchrHr#+V+Ufeo)sJIdQRJvbFUtz>_mC&mn6>6 zdu4BCioeR;9Y}b#kZft#9Dk<6q;dfjpx3wbYV=Ls5&sp1Zcp3Zf|p-P2K!vgB3+_r zCvmFekK#v0^4efT8YAwuh&8Pjimy_IHFaf*wINoFrOQuB=#SnnyqeL?%s z%=*Tg!L~TvJxJ(z@8p81jnSX}v(;7THR7VWtkdH6(a_>Sr?#5VmD)YX+?fsoyl+Zy z^3QhUhI{P@kwhOT?XAO}8hEoAF+7y~^NmPSc~0+cQzJo-eniM2N?fG#s>^oPZur26 z6$hqfc3p!=p`0`Uw=Vb0NPFQWTieI>el~qBb8x%LeY5qugXfq&f7lCB7e2K?ibS<( zGR)R2y&A?g()8fwSGQF)%`{@i7D1Y+6X_BTnJBe%O>l zRPR<(H9;4(@(+h>LlQd8wT9hF8pYT2G46ibVA?%3VYYCiV}xOo`I|$eX#`v(4ny8oPncGUFy&GPOF|ZSlrk~x3?#Bc4O#; z$MA3q?pU&rL+eLp9@wsO(j3wGSjr!lxO-_+VQqL=)h}>egpJwT&H3HJ9^|6gCbA-) z^a(|R7sCEr8O5n$QJtn9+c~?zSOX~AaXP7WK&3h@8GA2<4I$QAB2i`M6*qOp%pNMT zqVD}5Ckhn*bmujC*|_`g#tyM!`!3Q0iG1xW?lArF$(KJ4*iuu6#8NQggnbUaeagDz z>f9)ey6+R&i;HTT2NW7u7^`6Qt<&AhU#JbT-ga)3Bo2Sx__%~>00y!-tL~*&J~P$T zu}EeXy3=;_)^#!o2gm(7_Rr(4AaAo;GkB@^3Q%$w%46#)C1z)C;_kv)ccW!rO(C}V zKXd5fiZ%W`IrJIvuWUH%YEuO)CUs$xrcC}L4soh+E`cC0CANM3b1GQMMOqP!rz{rw zMo)Yp-3Y`Hm=|>Z{JfMuS0amyg}_AL^ob>Z@LzTwY5cibeIFykS95w{^9lK;T`P-REglvq-tJN;( z#lZ+iQtp^x9)DZENn}`M*=3y8$V2rDjb3CE-QDCn8AQ4<9!9F~{_jIR%znx?%=x$z z-`SmK;E+RpbI42~jSAphR8Has%sG6Fe)A?2Ic=R9Ywu)Ul0NN0NLPNdAJW+T?7I2B ziThDM@p&OJp6d5+(#R!ODf{^FSXJztgcU+%Qk zYQz^|+t1NTt=`NM@(A-iKk0?}AeQ~v_fR|AN9M{(IU3$cc{%RMDu==cb-tq8CR1Um zw`b{A4B8eDk0Y}`N7vs9sf4g5$1Y}zGDt)F&-2`peQK)2Qx)V5#6JcBc^FReq5uyB zNQxNbQUsVt;207U2ONhnQF`hlX&Z{CxhAzDRg;f~xB^U|s2j@(VMt>Ikk0Cj3`bqa z9t6gH8MadL9{~Iyh8Pel5zKWbhvXF$B*=nRQu7ng*U#XvUxJQGo&Ohljer*C71fFgWLw9!bWWVc z%4dbOQG)G~3+g#7=TTE#Q;J%Jqt3WShpe>_5DruH5}iZy${UHopm+0Ss#I--YYJ?xqw3 zs%_+O-_f8gR&AOlyfP*ouK0;<5T0I?(Rd-fc!W>ZOnz#L)-~R3)X9zMsRu7^at1|$=7a$_d1*%`6S0kmer83(tyVsJGYb(h^yPr zz)SgJ_&|yQ+CP4=|EAB#Tt(eozAc_1L!33=E}MSy$|KUP=DK83yTj7IYg?8BRb8el zT)rkt9!*?8avSS#7$+uEPCia@7EA5@(X6S#cR`L0Is3>~Vo^Nc(w(3SW@KOQ!exDg~vl!nvZ?axyh}Z*JA6=G7Y(GE>$sMNn52NSxmSzU=iv_ zV_#{&Ibp=ppJ}LgDM_?V(YxVU;y@Cuqk}|O74!95+^pwsaX)qna1)h3G$mt_Ju}GZ zE9Y&~dadtnue6YxF;+3L=v<@A(8U!IUcP(Nyv2I2xP>GoMYu{5R^E2S(CM1AKI_rC z`&F~~(qk*CC-(7^@d4FJ@{8_Mfedu+FRr`4u(aigZ33c5pO}h?x94dZMb$rE*a#jg z{i!v!=G%HYn2IwpTKTY;rJmUPV`5iNe;kjDwC4tYSU!Z7LLiK{^{IGG>*oq>ZObfG z%r)1pAEM}o$Z%2K>l>4F-d!gZF64JC(XWsG%1<`fBZNIx*D={femVm(s8;-ze=A&?C8Z zD#|r0C0zNe@MeCMKR3_3`U{h4C*`+lzBfZBlZ=CtuL_;e@`N9Ayf1!c^1jqm#K{X8 zGargQJiqLQa(yXVM&9};oafrdwg-9nP0V90m`C%y+B-rfolxts{zFX=QRcc&iPiH8 zp1i9y8F#-tnrVYS_)d350i`yFBbsInI?J`(Wu(7qN43b^=>I~cd9GoS^sGe3cjPAj zr|pY%aTv3t>edRc?IP?7in`xdpl0b@!g0mN$*$0?7cX&*{(v~asZIM{$a(H}QE`%t zJ_*<5yd!f4*HvM+|JD*Y8FCcV=h#^T>tOmE_g01W-}(H*8Iex7&8q&b)0A{m4*u@5 z;#)P}Z#Ujr>C+ovL|Q(w&6y+j5_P+DG*cmsFc2H#k*?#EvFXA6#P!h2!Fys zcVo}1XCx1EJQnoO`Q%UT51dQCDCNhBO{0@n(OKlb%4~D>+KmOa?HvLrhN_t}X=~Go zx`@^=AQ*)kYX_ModP7G+m=@yx~8EXd0bkEq#9EWnQ(d_~zu=o*MhV2)T}*gorE zQt&D$Hvz@M3>@8Tnbc3|OuwvXF|)N-T_s!Krvm;W+pRgSC)lEmcjz*}=mx|1wU`bR zrs#x8UILcrfoObn;Q01RjR(q!4(>_91LS2e!*^>dp1tl9SM;A{HbbM6mM)~Bf)?rp zwG4kqhA&mO}gG*SkrSc8LUb$0Rgni=xYr;=Y@x>@DD9~vr4P>^6 zF98R`F3gcK+A)UVzt36WGZTLHPCPJ%VGifjiH@ML8(&5gNTS42#PM?>AJ|bWoeY}K zG(NC)GX0FZ7LdFzpsnH2W~*xK00d#$7TG*UR2zSUuL%a00@>IA$N*P$g1ylhZggK4 zob%7HLGYGjpY~ba>OkVZ$Xpx|`K&CW2O2EDUL`g({uW z@to%n0R?+Si=YBHtOqTV!=LE&r@%_pFxz2n zhO6r&H(7w}F4M;#sZ;_!6UY7z%-EvJgS|Ko7K*ofp2EXXaE1JnEOy3r;t-C)=Y*b# z{Gk4l~2Wt{mDDN?GH6C z4`Z>m%W6!}5@eAQ2;|?G<6!svaBk~r*^!Ytp3TB}vl4-?@$;dZQC1wq$o6ali6ytX zeqW-|J_T$9dt`JnXAUxix-fn(OE+W~7M8LHiDRp`msvK*ulplb0@ZBp8PDlrh-iF1(JZdpK3ME*ngPr@Z#_-d6a#}!4&qll&skT zS%7!OPrq=Lph_f$t@V%Mm-Rr%=BaISgSgZfQp{3mVcfCf^vnkVFt>Fg&Umj;SU)4S&t$%8&kNFaMADcYOQd=JPFrS~A)tj}?4)QbuyD1P);`{Vbm z@HT>+8mE-OQnU6NsuN#W3h+Qsb@7MYGxRq>@#%ptTAbuj2L{9Ui>q*0Ce@ABmO&kv zoixguILg46r773w^FTh?cL{zwSiODFf<6HRy_FEDC zahNmcEos^$dV!ZHi7tC?fi+x1r8y7THw<{yvjs80fAP%13ciQC$RNj|V97i*S;O6eHQ*< z$ORTiNkU!?LQPu#2Xp`Y4@Q?UW0N6}x)x-+YqdbHiw%6g)Mz%Psrq?1iIkl6ErEy{`Vpoyz@4y59Z@`29Bi*Nj;eLfdu6gSpsu)G3O`ILN!k`X} zos2XmWuMSXWukVK z9kl|27}aym#`jTX`t$*2X@OnZWc5CSo~k;5GXlZRR`OO>_0w5)p5@it*9oub#7=+t zbn~8x4F05)I(3(P)60&?g<(Ofp>q!lBF=M6_#{zSSUU3385uqi_PQ9!o$=8ihUz-B z^W`bc%QMmp_#6S($uHp;_Ydh#yGq;aukFe@9j)Y)LV3rZ*?s$=NXa;X_h)N3=X86U zJ2qP1)FO`NPLzU=iS(HtTeobb?F6e6I&{C!BtK&~anftsrg-X=7Jmc?q*}dX`uy=X ztBlvLo@Sb~jnFNx?M919auyG@sQGDrzu9qIG%3z2H_5vzrZZkp_)LYSYW~9>*)XWs zgR3PzWlAQ2`#RceL@~XkA{gt=pV6>{m83MyO3LRYH;cOB~R8_Ti(9ckoM}lsrq!=Jfe{YOysrvTe$u#r z2J>Wu4YSE1RCHq!|J{cz-vtRj8F%8y$oRFG8A{D;o(AmH?LuAc%Jqac_`%ayP9Ys5 z&}5qTG|Y62BVtjDSz<&t1 z(2PSj0>DpX-7(IUlq2(Ci?86(rOV)jQJOXPGXQAP_<@5NU<%FXYyN)0=nV4miT-n& zbyI7I;|!Nc;yY%PdQkgLPN&)kY%Sb~B9C{TKLAG=jxMJ;Oj)WZ$o0UcM+M{_9ky&4 zr;i1It>F><@g09kJci$j!TESpGXdm=UXi$ce`0kDfG+>IjR0VY>KFU5G_Xt$z*g-$ zTxH{zb#YmOJ-QIg}H$CkC9C~AYrMY^bfu88b8^3o8v`TlxX2jq={O1g z<73bT?7+{Bpflq6ke#5Tm+?T`|Hwq&cK{1dKlPQu2u+%!y@Gtf_kpX3ravCQx&tub z=`@ZP)Lea)(c70d$rrVl(m>L1{ptpI_3#PQHM3xJ*-R|`X9}pScpxYM(zL@gAzF;Z zKF@H53OLCligv{5{A~US&tzHecVt;Za5XrR6@GMcTR>&@bJcu0ISR;E2s!| z65Iiz`Zmm~L5do7=!`>0DJ{qWG8Y=V5@vA)UDi)tbm*_Z1}&ywPBu%RQNR9XoyYqJ z83&9R>=mqGbAsHTD^BxM-21>QB8t=$)gvy&*fogxr$kVDK|^_{=4GX_Lr0p3d<>+G(&yO-#9*`K=+r*od|EUh%| z97Qflr(Nm`y>)u&BS+2X18D<)fBZKPg}ziVTb-J<{$lr(!hA`v zuW|iY1GakMbKR19#EXKz3QZ@j+VpayD_G)%? zs@4yVj~F9{J5H^ZVR2;EFa6{SWQX;~4{iZ}AhbZFWIm-gq#_MNU7qkT=)!4w%;M3R z=;z^4np8^@8zAbWl85`4<3sf~pYyn;PT0gK^&gTzI1HZ;9lExekK*j>KmF|=oJJk{ z!lG9kW_yrCm=VWq#Z1LU@0UK8@|VRPq0)3wJnJ>pET}VYI$#De^s5D2Hsq_6GpRpR zx>5a3ZP|J|sus8z1`v`VCdY?6^9HoK3}iM|3$$PPN^V7dBwr+W8Pt^86+8bgdPX6y zgRsA>eRY-ANy1%FP?b>LhOf}$N5H7+x{v!F7_I|3g?s8csJm49x3;dLvFGP0JDMaA zj|?#P!Q_fE6Y~in^VzxHXSfx1vhr+)*QrqpQ|jlOs-sTG#p!=XS2)Uq+6t~%EZmnT zAXFY}a=kGYkCSal*f>6^tx~>o1#Kpu6|Gm5msWLyvx=IHG1@RxO;=C#9pZ%E#rx{d zAHBdF;SZvsa*({v=<~Dt>sE!=+}!)#>#lycBI+xS-9O|{;oo9(RNzh_p3ANEmX+~G zyn)^8>Y=#KghS85gL89Q+SIn*arO^0=NaEF{+3tJ`*_;n2?H-M9M&qT&r zjTx&o64hN~8Q%NwX`$^pschy81Ml6e+k<>waNL8C^BH*4c*4CgAuKiTLHswEH)^l!TnLYtqsn8wIjG-px}{COoTj@@G5MqPZqHVU zn{=ejn59sEuQ5+VYxeSUK|!&y1%5YyE_vj96N2kVL!0~YP%FG4u%>vpNcIG^U~9 z7cA20XC2DLgoatve!&RbCr}bV-hSgghZzo)M^-4m4!}`B$ye%sj1n3PM*;R!K>MeH z(k}}p%wAhV+}D_usejHu?%Zm!(l zpxpi0$xMA9QPpv%ecH(^Wp-PcsDynFH?h?kRwia(E8&{C`@p@=VgUf$gaZS+0ykdQgIm8C& zGl}8tM^x@qiR2yNvNOlgpW)@FH30oZKZu_@=^Z+#gEMa8v8hpzDNltaSsAA6Ec`oQ&YhA zh;0SYRV`*|&MeLg>;3?At1@~-_PYRJ;}&HRjK=QwFA&-F3TfnUwUCb-5Ut}kw7^VE z$C;M3bhvsXEQ^|}8>2Bx^HYndQ|au^m@nAta@@Js?*F6&*qb7ce5)QK6x;$`rmSHF zE3My}D$4u_3AqbZX6XrQDFc6H?kF!I#W4Iw!tq5alK{dW?zE#c-y)jIawW)7M2rJ- zD_L?L2q&loNE=+=$DMrUS`03#_sieY6#|73)`6@a^0%uuB%l5h=$&Vet~G#(2Cu@V zL%tEKwU|a;0;{9#F#oPhfG#4f>av_V1EQo_i=HJw4%`h6>b%Y;U~M~-$Jy0+x3x6` z-);KiuoEl)6g=N{Cx)IcwfO+;nu-;E!qN#LGC5M#Fe^xJIVSu5R?Y7i6{Y%|ybW@i$0S2vOg3CmS zrxYxj>=;)Fj*8`L-V+J`aB~++q>Z?FFDioW>TV^GTGG8|ygo1yP4L zh)_^TO>+HDyrkqWFTvjgXZy=YxFoKNu9%DiSbC*T@F`9LS$^PBFuJ0VrJ1b>4&ZRK zbza?B$VwC_&Rc!He}wSS;ha0(qAR(cX3>U&?|5JD3IsT?y7oPYLgQ7`O0*$6Xel++ zMQNk1RmTQz3V7n1tcgE z>hj|ne~y-l`O4-l5LRb}$K*d5J0!QcW4aD?LtpixP6Z0}Nskx5gxM)J`gIL(j5nsBZ0p`d|0<}WK?S-MvR=HNF{eB) z?b{df9Cwl>VVgo_MZ>7IIBfaT{OY=U5D0bc5(qq;chp7%L0;E5clCb(F1cm8jC8yl zYyfrTbM8U#XHmHky9(=n=Ld)N-j(Q3ao&9lA?uw0@>C)^>$0-533dS##C;5$+3pMh z%5Y6Uh8Ts*v1EWmIxjc6nb<*m2cR&{&UiXcu+`BOmNOul|63(HMnrUxc*4y| zSB8){mk9T_W1^}$7Iy6O=~rQb0SXdQS|rNriN`62cgF-QdY~?;7ezvsW&>@)2>j-# zn$w1!hmE`B#VYJ0EJS}2zRV-Qi& z5=C=Vl{O@nAt}1&!ASN&HknZ3(bAXqRnIOun@3)d4HlMkI%OVzEGy?k1; zzMd^bWIp63U0Qh7&qbzp{ig-|osU``GYJ#wi{P!!ywbgM|P0x-8 zM|t!hijqCIM>%3qps7v}>e5ArP<{mQ3juj8;b!r% zJ4IT|;vg==Fr^du1yC@5kZ#i*#H=M0p%hWC#VmJb+GVDF5!qK=3q|-P@CRqnJEK4Y z>1M9eouI%D008!zkrVI(dkG@X#3rf?2RK83ghO=(l0j3k-1K7rcr>)5=cAiJCQZca zgIMbQ$w*8q%!&18{GH5J++3$1{9%S+iQpm7Q0d@t>}=7>7IGVfg@x<9zogC@cR65xcD3_4uXV`e2U%Qgb{KA26d`)5=1 zmk8kCBaGk=*}qV8_1`%mZ41Wh?5l~DaQ9;KM=$~iu8`7@MMvN+Qk{R1Gp}la#{-y> z?(w8+VQP+01D;XG-`-@#mdXRs^pjgUNPmz9ej;mmw@?(Maq>Rhk_X%*`qp8U(#z!g z^R|g)(B-g3Y%5%gtc!dLbfx{XICAL2(PgvUARlu~Pi*IB0LByT%Jg%~0=cN+dsQO_?IR`!9=)$E=P!>v?rB=iBdB(8?3c`lW zbuq5B?TH0V&aYJpY89p)Cpo|+QmW2fcV(vE5?%UNqbkYTXf@9Y6*Vi&w>lTl@ zAhhf-*5q_Scy_ziFJH$D?dLKidoDc*eUlzZ=NnFits2?o3>rJrUA=k!KE-R!VfPfg zJJKi^C-N;S|8d{9t>?jS_g@*B!nU})^ra6n6(+G*M?E%n`yFlXfQw>=XlRau$6G~; z7OBOXC7&0rZJYpIlj}peG3NxsA}TnuSXG9YhH^R68IQcBHIfmhhH7$VyRqPt54Fh% z-^H*zq0nMeJ2!vRiAE#c{|tHm57&~xZcEzNN^*@NAYVt~%dwjxJ}1gA?*&TLA`E1nzJA8d~|vy9C#7?xHlm+rua+-o32xvcDP&r?K9&NJ&oKULtk#O zhMYFZR*`JFT|eizhPuP+-0J+XB1P@V8|f+AhnE~^>0D0>rafy|v{!YlxY`U;jj~6V z-S5E zwHs)7swH_j`1u1dtT08Qi*YOB`)@AFb6T`i@!_RoxFnYg-Ado%&0ampdqOyerFgR@ zVijWAZ1g0dEHfBfH>uR|#@7o16aLfJ61!&Fz79$+a`iF2EK%1g`!=XCtX(c8QF`68 zz@>f2X0T`#9`*Fjph;fSqf6C4Cn=BSh3K6WW%2mhzp8HCDrd@SgAj*OXzW z{I;-eys#=(nnWW^|5LRc_ms!~A7gJF6;}x2iFf7QJ;4?ak z<1^Wd8GS-mhAv)N)yne0r`eThX4Q>6j?+N-?b^KeP>xTcZ3)LAWZanKrd?OJ37Jpy zGWC(}=RuQWnZ2=${-P^WG&|KwhbLEZu#nN{98KBF3imF-ut_m8W%S7p3mKgva}kl) zBYVr0r-<^bEibBQA9jkj*H4k%_}<0u2pAN9;1nzG>TbjU zy(Ju3g;|NmUd9#s>=v=WADS+6v{Oz7C@KSdax{Ktxbq zd^nvHe8*)OVb^j5C(j-p$5U(b6pR)+GbbAUW^KMcBDt3}LR>Dw{Z+1Vc0w6a8H-3hFa zgSU@w_emoXx)Sa&9s1wAL0Dt6_97PXAuwOHHtTg+Eo6ym%t(E2hh{^yC0NapFi5Se zhLFV1Ig#Wgpl4j6l9fOIyUO*ao~(+m%F0-i{8k0gp~_dSH7v6ORVsXS@P4y3$&g`F zLkqtaZ*XBUUp4xs<{|=`0`}o_?Jt#3{Lm(sM*|lA#=%~c(uUPZQ9epi*ZsFUN>5*6 zuD_tW985e#ESR-)1>H9(vsuQ7@b>dKecdyG2FF|3vD@P*3CPFPr2P!H*Fb_7K$L5 zyW_PvXV+w2FN3&9oONV7KlANfu;IMuzdtoqm-{t?C6mggMp`TK`;%gpXWsOBuxs6A zb?jolxwqtMuTv!l4bwK}1=_Qg(+G~hgZALbiqK{)-e?K=x1hz;#>&n{Swx&F0U6 z5XS0rHjVM^cmIhMs9aBQRsNCI@!U6_wV&rz)?>@Ojdyh3$`!tHhbEE&oR;N&Dq`Uz zFD|3pm(*-N6O5_HuP;YhR0rx<)s?9m260)dW!H{ABiD6o-MY+(!%w;EpHqmv-=KK^ zLtv0o{DdxXFrjbUKJ~u!sJGIl&VRCB0uDuR(!Q>0?lXC%p2OK2wa09>?X$F@+B?H1 zB(CI-PR0{N7{|pV$Ojn~@%l%-&h#I!+PKBd$A2&CXc<>dauM z051)T8NM|Xt0qbBf92FOA|KOFtMO?E6xJm0-ovfw4bskwVNx{f(oL~rU`ssgwqil4 zuUi7zIe+in-mYhqX04Gm%*SHYz)IG7g;9Ak*m_yGJ!ms>hnwiIWARGdk1b}EU)z_P ze|G!@n@Oozv`tZJ$q+#{`v4>ey<>bUuKGPbPOmk{;H=|jzR zHv<{<6sSBjW`>P)Xk}fzlbWhY0xmO)5l|YdzB(bjl_YqZ>CU37%TBzt`jO#XQxgj) z0PcRjwKxZU;nE9z1Qff*Cx^Z(qb)x>Z#N2~6^@Ksl1GAAX;R5r*JM|qzntRpDhOo6 zx_fXux!+0qf;(IH-Gb0`a-U&6@W>aH_-VdMr1G~!c$vGj%othsJ-NLrr&rXw+wF9Y z50_=f!kbqUYg;*sj>j8Ltk*wlPV|?a>^U$P?7Z>L*wOV@r_o16{B1X^y+-#9`!H4w zmr@6b^3^gM*;qs_!@I=DT@Mg#AD^@Ic1aM0NQ>Wa!gmt6yj5&kB&j>45w zz6B`8fY8ik#%w79WT9_n33ZIrv?MrU0sIAf<_yK( z`pz~VfD(f+#M+=p8#O|UcsDfMg#INm1Lsx1w8^f97p7v|dvS4g4@|xoEtkr_y4ir{ zCmHfyz-mw=S&AvPS_-x0KU?Wt-@gUymEBvx%iVz9;`XOo0Z8=*44SR1d)=uKMBl;( zr2kQ}T|0vV0OMA1f30W_;5sIGmWMp@!Ki5lHQ-~&8&E1nfr)jCq2>qyhPs$^n8TlxJdj}Lm~EYlO52|8ewce0h79_hM*F;2`3Q8 zZJ=>$m35k3-@NuxBgC#n1Jh8LQv(gbj#6rg_wajXFz{dfRJ4!sowJX~kQUFsni+B| z$qIJYf&Z~ACF*n(4ggT^jQY<_`_sq3CL@X?l;_wM0%;dO?t$M&0|)IOR7${OcD6+h zA0kQ_X?Z9`4WQJ@0!&I^Vs6!421V|3++n?c{}})Sa**}={a4YG>Qo{gJR%(M(snse z-06X^ERbb~F@eQekod0e0i_v|+?b5L(noc4UkXi;Q56b$HV()=z;TmrlNQH_A@h*t zKtNpi?|~P1g}{XVpSj;~7)N;^xOSEh`HPks&IXL?01JR=yah)pi7S|4ltMEcX`2Q$ z)-Z;hfdKKCU7|QV!iATBHnOu=G+xu&_*FvTw@5a-9!TS&uk z4$3^r+7Dp{sP(1d8vVmP33x%<#e_I?2S)GNf;ElRA{+@cbp$=TT>tv$ZU=}1w4u$- zfWrWAvvBxRJ_UZn$B|_zlWnd5Qs_w|FsIpDfT3twoycz%`jHkWqDb*aN0c%sg#v6_ zU-`EYzq$aQmwXvbS@U`YP#|6GQTGox5mDfG9CZLm+8j zO$9vxb|X~rbHLfMh?ynP+A6sXB#(DKjbiC({0KaXhO~s1!a~ntz|>MEY>Kd%5yGNz zmn}lAfhn(}w!;G_;b{wF%QH=l$Y> zSb5<%tx}Eq){$q6}l_v2A>KGbhYh@(#A2;LbJC!fWwjAl%UZKQk6YL8GBltRYqweU2_ zrZOp*;1}F=B)s@`4+{jAX8J6#h0#6YY;TJua*^u>5S;XBd{FWPH|-0a2GxBb|A_RuFr_}=P7I&|8SIc@l0xKTCgsyr$u zFO-;(ll`G1rJ>-6sg|pn{7vA2w5DK~lEo(}`_Fd&mv?-G_Gw^kER*RpW=>1tLG;oS z`swKP(Le8pyxt2xQab*kf{KY{M^+INBsNz52^EDNPQULHCL3v8Dnm-Ft&xuS4x4S& z`Fm`mma3}WLY9GLlBI{$A?J>RlQOPV`C%iJUPLFL`6I(nf>a-|y!8NApXL z)0hjR$i5R&m0yfEf+eAb$44dhAaS}&o79~W;I@2ly>D{_h58#V;~#h#Ivia>>)rGZ zTIp%_X>vv;rl#H)s~D?273q@cU{Q3t!OB1N(Q!_JMH{CZiJt6EY0AsEx{7sLuiPsY zKkX`hQmLj%k{7lA#N>`^&tzFy&MmLSyz$Vw#OD49_`atr@ZA$yqrK4ejhg6wNU45v z1@r?(zrPy)fbLs`QC?(UlD=;?EU((l8^vFzG`>AZywrKIX(?Q#^3IaC*-Ij$By^m@ zR-VV8qfze-qH~~Rf!FnW-+Ozn#Bc73PsBXT9?(1MQO-Pm?W;YHYsIt_)X>tu10aiApm zvC|hm`vva$S3(pFrS_lT=%Hasn4(lwr#sPAUzh`po1njft+&bE8a08`$jTV~4FsyK z{bplnJ_>XTKP55Bs!oiI;PNXmv8cXF@oif1I=R-IVB-V6dn;Sai4r66+S9 ztoip%|M~eAGy%BGW&$rwZ1hrp;=ONnC)F`nk}5pCyb!Q`ezS>EqpNFi3rn!*@Su;%5E(1hcm)76j`{LRwZxI=8LG)U2iB*=@wiCW6A-DZ|7 zrlj`>AbdFTKr-O)_|_n>e=F9|eO#~Mul$>fZd(uGeFo9z9rTB6(A+?++oPmpZ}eZG zQF@uag!a5bQzmjFZE9AU98q!Zka*zPEgvtz6PIRmR^%QFA#AE%m4#!TrBY&y)DYQAR zCvI+g8O>QDo?9oRX>;R5Fs_wMpNSKikQy`am7oV{xo{58J^`a&3f~jAm2Lr3-RgF#i&rMU{JTKh%zIU*HNV}iQD&m>bos{4K8)tIGWyl}s6OPrpKQ~gj6HPtwC01LS zCcY<-Hx4gRm1=Kn&*9u`J3WmLNtvta_nqwPy43!bvUy&$cMW($9yl3Dmh zp00$GU!L$14xNlLxO`A`)Tk(LYxB*mCVfF#PS%#b1m6x|)%IaIn{cP79KtC-oppr6 zAq(Os0q?KNW-7-7PHlEA;<%6UD^tQTN&-IDKTFHMjx2*Ev&?#vSNIKblM>0oA?&4L zdc4qmuBnYqF=Tn3=-{k2p|gyWl(LlI2|!l)>Qb$8{<*X?{0F+`Bvz87E?gbW=e{5~ z_*R;1gV<%VdtJ?ix4$~^xh3}#mV#L1>Az*b!8ys(E$w;6gs&EpCiTmQJWOUMR}RpM z_Y*a)I=^XFPej1ObTuvP?3##&E95}^ZtfW5U2RZfZQhr)yqlt-!TH-`9K9~`!%0BR z37g^o^+blG?l0{KJ8k(RrP^^K@2T{Y?jq0cCNtyaT(f-f#KoR?%Ef6OKUShyOofKQ zL}{~fC7Odkqb9n#lNlTw&h?7`h7ooyOCCQ+B({OR7O)Oyv<6@L&blOKjZvKnf+eaA7NSRdS=@npM=Ls5LfvQ8Bm5 z@Zj(Q&k54&5b7nNqWAW})|dmJ0_c*W_F85~YKuhy28nB>d`R!Cz>N*vrHJ!* zLO~UrUR})H4lGixHQ|KxbY0~YHu{%94Puc&>+F4B2O1;jObjnlfA|=#UGgMj^0QrAw4Gfez{JXLOGe|adq_0= zJH>Z;os^>I{&sE^rRI32lj;UH8hy)H`7wr99xhIwHdBU}OPulWrDcaV#Cwc_gqk;G zZgO=L`i}G;nz7`48xy#4Rfk?nIR5zYF0{-FQEL$fRNH-TlM3@XzXwvZo@N+f;{Lz^ z7{)4DQ8OxKlvsL8b>VpZdj%j^{XmlZN|7Q9Oc%TT|B1Jh`s2VDm$o%P3g*E_qyp}1hFv%_IKC>k{QI+&J-ZB{wtH++ z`<2*tt(U6#k0@BZiY6r!vXVDz#|#g@frvt-`qx%(-V_F2$K^H*z>#)bviSS33g46H zwGv_qE+ydz5(7$a(}FZstHH;OLv)PtVd0gZFkVMEr{ z2?F^s2u20KUNBbS)aK`@$S1Uqw>D50aI}9EjvS0Eu#pQd5E~B0AUSq`#jdmVg8>>% zKNV*=TrmpR%?hwgpF#neVVytT!*5j>gB0A^21@gYXcqv1qDVv02He&&o&Xu?-|1O0 zhC9sP%b%T%a2z!e(@RnI0ND-ue>qhzjix9Qe4YaG02g#Pv!(Yb{Q5@#q~$o*S05sL z2Y082SA`?3cr*7g4Gnx~^82jh^5Z?Q-NybaLp}ZZL2(P98rnc>W`X%p?m?6|C`459 z2*^k<+`;K_2#WJxJOwTT!KZ|km*aczz{sur7bBg0O!+c?1n5fsJ30HrZvMv=x4%r5 zfPHgya|aYN8rl4X@|puY-fZI_2o49weJqZf2axP0tctEf^1?I)9A7$uND;5&Rl{){ zV66Kb2|Yk*$`+*EKw3hoe~div0!JBmRew*Jf9ArFawJV8bofpj7nOn-30ykTNZmgj zi-vm9v^ek>0KiH8)8IXrN=l=2ge7+!0`UdbzWeGaltJ+A0o|g<&;;c<1ur6i77+&w zvcmuLxBYwkl*W*P=K1Z0@ecA^XQD)3Bhd3eUC~Xw(d2?R$%53w(O!|RBal4__){MnI2X9{^}e}R!<%zcNN?T%vMSLt&s2Jc+DhdHkozfri`9jp;mUXz!bf<53n2mH-P*K2C?^i>^BV*UMIt&}y;?DB@NwTyiYwrJ z+FoqNE6vIUF2zU4i4D_u2fNy6(#cNPbRt|}{w(g`rt}_fBc3dQ^N?bw_PoKut9gK9 zg*QBHm_mMM;SS5{MTsjXZ#+9s@7bg5<_4y=N39q>?!IOiBQApjYpyJ`zbUJQQ$e3Z z!P@H4Kw(UR)XbBz8tU;4>^@XN=2tCQEpiOUn)*ecE`#qt51Cb7LRM*_mD!e9W+fZ3 zbnt^gCi2PEiz%TyLhLgrK@dWnC1&V+TBE}_?7i+!`r6da$}^|C_x2{Ol2qcGiJZ$k z2EKfi#e4FQ+(sGc1Qtt>w{RqDZ=V7_ZwjOM-W1*w$A<=<#YTa9qat3O>xq@4vNS>c zRT2U?STqnWe z1C+P-Wc4E6oMzuw(o{ZSLqYR3%GL89#;LaPh~2R# zet2Ti%13pNk%Lbxi`(<#)Q|h~EhEEvtI)mf@_5ou8rPhWal>41zKdX*_pS!&<>oq} zj@sT$rd`v?L{DR@)y|eFjPNwOdR91%mVUdvqs9=JQ|y0qtdP{f>-2*cH+s$ z8*jcaE0X5=Tc^3|4>h(ytVA3{n*v_tQPu3Pf9sSJrWg`M(u-u-ef@=DoU~B1QC@ZJ zcx@>Xhm6NHcY}{wv226nwzrwmWY%L7CFUXr_a~*WJGQ)uI{`Xo)calV0hcDOqWSGd zda~k4Ri1Xx*m}%_TQ9%*mHdx-n^I`gxzKAt@?)mP24M zhb*VNo+d4uDWYt*Z;331?*S?8Hxls6M6{G_JMx?u5H~cjigK9}ou`(8KH9HjEG;y` zOwD%K4Q1b-WbF9jBkzWd3!i zzvDd?eaexwAy}hPT&nyQ9uA3lU?K>;6KZga^mU}uX=@1f&eD3a#{bc`SMZsju(`B~ z?kYlEkRov_w$ZoPNE>GzZ%alukSIU+%lN#z!vVVjsOym8!61j@aiTpOGyf4TJ4*1e zY*j$(K`*c?t_7zz>j9VIPQ&&N6kz{5f%3dRP#y3ik7V}Kv?is=8?2QO_hufyOUkgY zx?OU;EYqKvt0c9@8XmqjSQ>{TQWX_IE8~{of~3mgdY8xpJfsI98T~B~2(SzAvSXuKpwtJS zv#u6HP*k0zG|VZpfY}2`{<=t%m%BF4r`@`HQ^-2VbQy&R9jho25}*a<*grnOeh1*jeXc zc9h;%cVcj*i!Kb!jgK__8=y4g_nn@C2PYhtLA9diT)K9wNpLqy#y>sl?;9r{e^>D( zuA(#>g`59KV{JGu3o-p0bz2LIy!LD~Lc zL^QE8B10@-b++<`gsf0wc5JQGn`>B&03%xAUauxekhDFQ{v}nK+!So)S=q(OfJxz* z(sBRx!9JiS{8U1AoUz+@>km7$S@SnHR{ZoJpjtD>2Or$J?Vhvq7sbk2kjb7>P@N>B z+4|t7bV@L*F=R z!$R2-#W@fboGiE*;&Uw^z|Ns&YT9Hnx7;yQwNIuh9^= z36p0kQ%Z=}<56buc}O5yq_ds)q0Jwz9HuokLaN2834`(3N9cytHq_OPjC*6D+tRmo z<4iBq9bz%J91u88`pAfeDTit+jd?AO>u{7tg@02ZlsZHAcqPY!aR! zavDutec(8yR`pX(xr!+&ASh1fAbwrPX25nArGcFoN~lcu!IrQd-IzgMLT-#sb4Hcd z>wW*Xa}5D=JWpLODm7Khu&5K|aTI%r4Z(P))1HtE=}FPWY8JF-w0nUI6dMEfbHx$8 zcIFEds%-&Mj&r^GZQnFeoJBcq0$#r{zjAqz6n1~Z5h)xA7G<8F{l-Sj7;H)|>kZ$P zE1nUyT>PS%t_aiPni@7=oZxs<+pPZ#ueZptw6S%YHsTvh58NlR+Abi7VkUG}*eRi2 zj)kCp_}23d?*NtS(5$bVy23Ip`E`lY!5XP*kEQLxA?FPScul@#R~A!*AA`bbNN^Rm zR5wWM4EzD0rpCEfgLeJmTjx5IN5#S$i!b zpE~VZOb9Yi+-FI4`FdYeV6RUo>oU<}#FaGvV@V6P9egl-NAk zuEzVRN)VoeT@V|K(2MwWy|JGJAQM3UAOup(uS{$joc(vnX-R?xACkRZ<;>%;RUqQo z9xk+~S)Kqy{{xu%H8VahdX}{y9Fl?>S;+4Mg1SkO{^>Pi8SwU_?)AtJR!nNLvJo>9 zV6P?22q9m@@uZjkZcoIw4sco)fR*jY^n=M31&}#%4hVYsE~}s|ya6664g*T9!?$@E>0b|NaZD`+xsM}HD}FRJcMUg%`z3yO*@e|qMR)rpB()KutRcW16UhUz*lgNp_M$RnoDS-*pN^8PJT`kL4&=Y!m_{Sn~dA zlk1UbJ0Oqgzx?pV*$UH~c-@&}ur z8s|C^C_$co4vhZLx}bkY`u-((G+@J@Vgn9;s83HhTt@I&)9rm5096A;DD`O|_u)x% zguKv2g7e~U;*nCz8lbRf`6H+Vw?)MtK>_ms-k5V5{ZTU-__K=6N&oaHkcOO-1Ain! z*#yo(T$r!PnmGPkzlE0YQG^`us5}21GW&}YjvLT!19j$<9HL+cDglFn?lHehv$RVs z!EeB!)YOzi+MXhqz|^&<>0g0bMJXf&(YL^nYqT*z$oz%Cr3t(Bg7h>^D*@c=*#F4! z|EszDQ-E>cL^WL*ga@|i!|b4}>?ldI3!vhJ7+_;{t3pr!@QSJ%3>hQL>uaTmhxAIe z2zVR5tG^jYQ)x8(CyGEY`zKWhykTlSx%EqNz^|`+eVjeGzJ9bUr5-H}_k^>40AmNb zANCyE|8;BsC0ePBf%nM8n8az>b?^PZOZUNRdj;I%oc-Vj2z6|0JYjI0KZn4v7jXO=Ws z^)6{ug9zd%*AS1xDzXuxrLTsLlj^&eGLDP5E8k(94d*W8PFl%Qz z%i?kgx`8vL>(*6`5<2e_@&XB?SF%X9tu9;>dKDWrukX>}<3QbNjNh^OA zi6PO%+_C!KWC9y%lkhUd_StHC^K}0Awe1?Sh4Cx{`xE44H81;-2Bh_6X zwL>l)j*OfmJnyVGK1prv{rX7yfxF@Rb^oyoi$k$o^Sk$3&E`whcEimyRm;3Km9VLc z5QPcjSD}20pQdn3lgQ{92jr9|>pK*&D%M*2zBOq!LD9zgqN+<{23fMpOUW%gWZUA^ zQcmnEw`bU1ob$(xxQYmUvA^tdDc0hPL>+q@4qV#L(_Y>}!_`H-DO)+_QMWl`>e$m6 z4mQltiT3+(q{Q0LXTQIqSNx)<+WBxCAe9xnpQP9%E0BW-5xM7ZF7v2g zY9(Au<8H1SG70FtRgWtKyAVQE(ERWQ17S`&yj+QGH+G#JX$ zpaBKBPe$(F_#wKzuVqn=zORc91#$^sxTYN%vT3O)vB)m?r8WK55$|9Uty)87THS9L@5^|{DY(ZQ@ z?BvozVT@>B>?Pfx^DKq8 z$L1VmP*=%S#=3+z7f#CPpLMqqt?v%!~UWB0z6Oi$dKzY))-tKxuT2%8YX1M3t3?82{Go2I$ z;*s)dm|IC@x0Hj~5^IBrcKb-pN^5yWl)?w*<9HTWD~dqIi@!zyr;6Hc1QG6CmJ~2ZH+G>Rz{N+{?DE~ zy#V-(-mcTvV$UKmH6LAjMuATSQ?#8PCz@Y8LV{-DO=!leID^wo*aqeLBo@>b%u}v2Z7ut24QbTpCr->u z*go#0C4>ARAL2hEmQ4Z&@q^v~+v*-Ki`ZSI-dh#2&-cTPk=73WD3PxQIqxMEkd1O; zY6c9@-PG0QGz7ZDmPcLNGkDb#r#NB_S6>KfM z!ooCvUnMf`vPvi{9Aer}cS&d5pBkf=WDk$Nn3*J*$RUSnSYYk35=+M!D-k{Rz8X2D z?d|Tf*<|K~i|ek0nXTjFt5>gd-J7>#4@Ey8cE&rnldXCYOyJUtV_IACV3fqAH|$50 zpoLWD%nV*Njgnb}vaAyznnQcy6*+4@vEmM~I z;KFCEkDu$3nACWa_D0ck*V3E(IQP}}mko$@4xOu5*<68G$y}FK=a9-N0Z%pp&eOH> zkwT&^()~drPidOVTq2HNyf{#FvYj+c-G)opC?D*2e){IO+O_>tY&b|5VOOyKop&nqN7nCb2&j?n5BX63nJuc&eu)3am2!%Hj4CE(KhWp<`9`rZK~bC zY|08=`}TXKu(yu!p#iC$A5G7!JnGys#v#VlpPX&|Q}s(cvkUUC{`VFB?2s{+#Hf@2 zuPwm+sDcBd0St(Q6Ne)^%kK|^=dG^FwivN010;0Y2nPJVpes7q-ru^qnOC9j{IX7c zw#bijPchslD}7+m%XkZqa!$lZo>jF;=-%Px5d+ILg$T?0pKs6jx{>2wwz*9z$1&G- zG(8;dEeTcExb{WpP;G(Cs~m#ePuW@Q{K@yH(A2!Qa@fxw9Q6q<-NSmn2vyYLSeRKI z5$LwYwmY}$&~mj#pW5ooInkijTVFP+Gl?r)8&12)Ba0Cp*;gn)(caF?EWfOD^fw-c zbj$i$BTpvKz*$6^0M^aJYW4rxL#p8?3Upb=$VVPtqX#;LjLa_~TlKV+^{dP8HaATK z?13r|ZVR((lN^jTONGOwc~t9Dzcrq8RFKx6En@&hpWOjtc`g}ZM6*4GrGZb(=s3L@>HMuEGY>9Ve z4a!Q7i}*W||Mb|In;?)7+jA19<}TGh%Q9!#OyU$0im)nY@lsMxW?EF`_5pShwqfpq z^AjZcyNAT`u4agGm*(`jF;GEE7WHVDNR31W?O^FmtTp-MUg?B#5zf@nI}WGxbQvq! zAui+uo`H8Fc^>+uw6IO;_!y7gV7_O&DuuJ0+~1TgZ}Pr>w2)~Rw*HFSfq2Y{wKB`% zeJAOpbQIunjXeL;?@Lw>xY%n(E zev1rh{+*Qn+-cQ%;d2t>7Xe~tAxU1vT0u@*stVYUJrf6-qy`B0lMqStT3gRaz+K0S zOZN+mbqPK(s@Y#@)^jpGbBoXfPWGaB{7$hGJFoSQ8zEoTVpXW($@V#6m2T9O`%e11z8fJgt#e4Pf2+Szgkw93_RJw- z$@Q^S)a&KZW^0@s-`p=&kS{V1P2?kfl4At+krz`Z(S$~!RT!d1+Bee%bYHAM4GPAL zIBHy_nQ`LShg?iCcI9L1tG=zb3O_!a^3#{an_n?{S7*_jzC8P}|G8Bcd_$iThsdY5t7KVkZ_J58~50DU36A7aB zT)(b2tSB-C#xAyQy0oD~Ebsg0Q}9k{l$24Nh___T{Vx+T9EHw%#6Ohro&VTe7~L{_ zeHGW7YW@Iu(xN;p;mK#wz&!=g?`N?Vb*>$q1L7Ug?!Z5AKTtU8D<3`6iZ80ED}cjb zjODZ^8p`4fm!N&drU!n&84QG>P>fH1UmU{C( zhM(b_l3L2>rhinB6n`vVIK~bCBAzZg%1@9~>?kcnCj})iX5aFHCQWLal$bkZfWs3N zRWm&37GaFCg?#^;PR*P*S;tPS$)JG{EJ~7RMdXCf^FwdldyJI4HKL7TznyGTdw3t3 zU?qCh5Si))gdn_K;VY+~ranM&Tq~0kL^f*mCfq%cbwNxtWGo}_8?=+9BAEJ>p1^@@ zkw_Y6?Cn{{FV@ zlJX`8grwo+V2@ym@{z9p1Kj&a^Yb z9XzH6e#g9G=g;fQmtFe;d9850XUQB+hzL+hWw`6$`Jv{mreVyi_I~0E>k2{V7`9fr z8+5i^E<3hD?P2~9){OerxY5@+T10H2#OirjQ2cTT4Q$XyQy|Xn)XtyVzY!mQv>rtzzK?z{WbI5UZhx zgA|rRebH$+h)~P`3(nH4sv5`H8PL4g_SZr3KWYpi=sHuIodbCYz(koC;dt)6AT8U2 zhX?qjL!M;izsL$d>CvXSFYeFHHxVBJ><(>m zobP~#$5Z&Jsm|bl2FYGZ)X4iuh2c-y^akPT!XmS~JD?P*`HY?0r3R1CZ@aq85d;~r z@NYS!+cYeF=%$mwLv?)i765r;=EH3uL7b(eYosQ}e8@Pk*DuB#Tm$iXs4pB}AdU!rhT0z6fGREU79{#?M zzH364=U@g+!*j~F3DyFC{@UW2W9V11$+7N+eT$1SB8Jfj?xycg7INz<6Gc56lUfQg z68v`W%S7b>XfE4uu?W=|vsHjeeEoy%=$Ns-6+TX(jfDJ2VR3aq; zIA5{uAZh;B$o&^y0P4&m%`VXNtLb&bHaXB2!tym$903&I-7IC82mDMj)Bj&$>EnMl z`2n^vU{J|Pksc5Y7(vJiuqLmr5o-hQWjCmewk{m5$Od)~U%bHa!ZSz&2f;Zv{w+8{ zQO5nS#P3Bv+uB*3FY%7BRXq!>@a>V&3wtM|wq23wb4NMi_-$s&2+mOU#xXh4WYt?; z`G3z;z)b`fC-&@n-d@IKTN63H5OYgYU@935lOXDsPZ?#SBQ4frBJ$z;gj3NfMALbW z`fxP)Q^+V~$H$Y;J57P4xj$5bsBbi5oR5hVW^1Q=iBXJXe+i;a&O;D=bTh`ks@=cu zBH3yQ!R%{D>;B=DbUk)2#_9H~NHQ{>L|jAhrKM_x=tR)Ax#?6YG#=_vX}ih9vLPhM zUsY27k^?QLm>Z|ZqA++-Pq}_!P)X&GsYFYhCbo*rH*V4a@G!R0e2t>Hn2a7zw`(e$ zP-K^uM=Zbbw=R!J$(i7FstA%NB{96k&sZ6aSDQ2RQ=Y6V_z`09q(jzY)I`VCY04W8 zUqZ^Rh)pbQ-^Dl?Y^uBDV5dqyqI-iO;K9c5A>VcV_(AA2XB2>1m9wnAjfUa`$YU;Y zM1#Og8+>uaB2NTZm?UGN)acm#*z?`tZIT05&cYi!*Y+(PZ;c?MAk2k(?y8SLT9F_CzAR zx12RnTG`LmHYS_U!(vyd*w{_F(qB*?k#I_n55Cwf<)kc!<88QS&C1N?gW?-BUse^5 zndkb_QB7yrobIqE004(zEPKgZ&xEaGBgf6~!=?8a#nQSLPiJLrF2$v3=43SU!+MCH z8NEsbw<8<#r-eqGJqIl^lWwYZ(u~)*2$R!PKCKdM^$)5dj7GDd#eR;xxNn-QUhTy> zb-P9_wq&ZvUakz7aH^};9CBUz<@5jNe{#K%>(=a+BCdcVGNMAnh~S>N*k7 zH~tSeHJ{JlUlrj-H)C6lNR5`YPoTa{3CFx$rLI#T#p5S6l=6bRUd&jxUI?lkJZL^~ z@mH@W^RxT}uIahPkqNjdw8;0=~t&wVx`f%{VCM*nkFb#b+vap*u ztZTFExi$2E?nsB!(%H>leyQd1%EcM=YFsTr6{eSucV=Ya^?cVk+LBJg<4NrB)hFjS zuRkd}89QD+ zwGIl`FMCD_Kf<7GoK=JGw+MDT@=Myyp4a1Np>IdpYT92(uf^4I<&4^;VN?)FQy#em zG;^G^RVGpMCTrqJ2~p#Iq~J_&yJV4No5_A8teRh0nA;lJ%tm=d!7f05+eq6f9oINm zJ}GbXBZM1nbG4nuD8m}tRCqA1+8?H{)3lA#XyA?CFa}@PHjRZsiZFbHLDIm*nji(w zg^daaKdNEj(&;K$LWs zEY>_t=ZD3G@8==Dv5JigV(+Dh=#t()xQ$YJ#QU?Bg9)JYPW;Wev2T7>qd#-WDyl3+-`B#s2i)o ztfTwviHVn&4c}Xp8A||%iD3gmdHbXN2df}Gi^CP`c|XJcshV_p+5W^;92HIdNr18p zj+QX=@I#Wos2Wc_**iXVO1(Vzlsl(`>+ruG87r`GC4P<|H9~|-@u7{VJCqb4W*dyd zaY^0s2*C2N9biKkq2^ahqA9?#hf5h79vhyl!ynkjF8t?w@pof7uIUX*51w>hN&zr0 zz$=hb!q}6(drrGa$tp+=Y;Y&K;zAxoHVi$!+^fx_I;kDg5;eIb+ah^W1=tk{`h`}M zGKa0RRN7jAwujx}60pKNe%jyvAL`yRtgR>w*ADIy+@ZL;JH_4I-5r8!3j}vBEmGXw z-QC^Yp%iP8_GISF%sF#D`~Ce~S8`?VWbdr~u6I4p{k-dbGJAY#K0c@PR2ypE9nR_=F{n{T`+oPejib^l*V^1b;k3zkuhs|tj5n__qfYg zBD5lDL(B~pu$?4@cYfg=%eIV0gtkPy?oOQLUjJ%*zx7Vwxv?#k$AT?s6Z_Myy^aKK zbt0tSvG0cwc6}`>2u)T|?qa%NQESP?B7x;yDNBWwx-3`Hu=}g{2*Sj>20u^1%!k7D zE?v3WnF)2A*j8z&Pjyl3w^F85Q|=?1F(9hZ6;Y;9!NFdZz>xTAV$e|ibxFnwkH^AJ zlQVrrlFk*CE*75R=p}C~*dhj&bE2#aVu7(lKM>_F%g*N(3jM*HzT`FQ?wPxd9c;U< zd-1@%(Y^#~=5IcZE3aTK=gX}9MMm1X90l}H7* z6$w-XP)p_PHA^xLx|?a6dU%#kFnCSJ`%V^(-N|Bl$8?EF)c-*@?%&&R|9r^TUmoTL z9(09xpA*@#nXN(WXwCwy%~S*<_lA6oE}R=jP6bz z-MFagg7RQb1S=I92zYpnR7Nba6{m!xD?IL8wtzta}+VRK!>V__tu@AQNcP} zj2XXjFqC>$UCY6eN))D}xwq6(e=Tc1rLr65Pf5w#{AW7jS-c1<@VmYJz(i|74OMavA-T@Xqoq-4Mm(C^%HbO!>zDho)zku%yT1q9@m;iL;A;)ip z8+dAi;k9Bq+`<&moh`9GS6SNVsV;<6*vSEVyOnzZ;M zT*%esdk7+ohU3cPMh>VlHA$rVk1$Xi@H?jXWKmp;M5t(C)=QWXVP2LE@|t&uMc%~s zLL|=qjKl{at+x){0$xxgpSTs_(fNC&$u<81&Y9jZ2r}Al?R#VWcOS(phkA|3!&-k$ za@t<^-rvxci%ERw>EJek+7N75%nB3;pQ%M){KN2L_u(bvSg$qH>iN)NgZzS+?2ki* ze$ES3$zCR$u?_mR1qjC7lTerD!y7mtQf0H)Tgbj?y_4AkEz-q@aeXJM37fi8& z%G^IaO6gB9iz5DBrqE&{PvJl6#Uc@AFpR1y9q#kp z#pNezj+Ug?(uzl{CtjElZdbI;AE64vA_9#Va9Q*p=Bk zistKQoF(N+6rg**m@5;42;P7Lk$S<4OasuvS;M#g((}=?@VH_~K-Q%p-tVowa+w=L z4Km9?mR@;VV32npaZm+ix<`j1Cg@4x^Z-ainIaVoa(?B#{u#OdQyuR!`{N^mU6dUJ zWxMMQQwFp3{PBOqsh1uXEs@=}L(sFa(#q`tF#Ax2EEj(?j3LRlv5;V-N$C{1P}(Px z(`(+t=fMmV|UMR4&%ULAjw|eGaT=A;$4`i(xz(|AWY64t$$L%P)b61E<^to38()HX$f@2iWg{N2o_as~nA(sqU;PLHHa%>S-+# zS^1G}@tFJ$S;puxH7rPsJ)ZLyI{tb|hbKHf_)`Y@Gg6g486>@40YjOglQrV`}) zSMJeQDv&-R`Jj|h^S{uTIH^lekY!U9%BU&fE}-v}&BZW3&)8e4p! zEEGSMBcB?Bmj9}uE;ZH_euVygvt+x2L#;Jlg9k@9c!Z#p;w1M3o7m#gMCPWe2Cjn^ z=zdmaL7f$>_ar^8DX2tHNLoR@j-f6t8&t)iq>0wgeqQfn;d@>;MqD9J?dE8Jpf8$_ zPnQJygHu#|nx*j@({^!{-O_X0nqc*&s(k+oPoKn5kzsk;=C< zkpF39)4`ONU&QAxyXB(Nw`%AtM4wO@)Bwzh<3&nrb&Bx(r zxKA~8y9!u!x=X-)r>OBOMNoPhpp!l~Xj5;MqXoh#Q8Tn|l^kR461ecKd&h+t!}7e2s5}gJddY0dp7|;{sGg&1*z3*`Wr|^~`A2Ur=sR;66_UMv zY8&XM9x7U~b2+}5mL{e3*-{XY)+1eSrH_KLoDb%9a>{*;iFVvj^D3rf+N<4^!<@Ck zTXRsntTc$;5rL5QI*IH-rVzBbuGrmzS z0A@|R{dmYIR@_LaZYGpta?@g%vo+{1z>8j%5P^9{mdDn^_+xklnIKIg=z?Dbc{PeM zm(MJvl)i#aU$d-yXn%8SrjXhB;734jC90iwm>=BJ87zhzmh++LaPZGGVTqqhTH|$o zFnh?95PCS&e;M91TnJ0*Fw{KN@r~W)rKJ2nE3U3K0~JCcg2XFGQ?eZv)sH+^3G|;cMk+)w3bxnqOzruw8u1 z=@2T}OiGW)^&{TG|0>m1IDcNuvf}VCo-Ye`=BMEHVMf!+&(xL>n^w0MXHv@|r$bIj z1@uy=IC9Ey++m%5jqge10`NgG8TyoZERuB8l?d*|oA~8e?v6yk-u`+K%|`rXG~+zS zo{05q&4q|`pl>ZHkgnS#QuV=Qq4a8SoIH|oRCu68_9t@?kN)$(h{(UsyEm{F^#9ZI zRvpoooVzifRbo?&m$%p0dRQ94w;}2cY1Q>se10Z2CGFprZhcR*I#+poUhK9DKHf9<{jnh4NRmLd`+AXp) zk@Kf-du>v6ZcP%y$7yq2$xodF?z$ryo$?x$>XS%?8sbsPNwq9FU!VNEU7BzHpiyTm zc7^0M-)@@>ERkODJWz@q^eTL7>=X+z60sJlPSwd5h1*cCi$8KvhHo3e8t_B|#=qA@jk?_g;@_1`Fhx4oTpl76M`qJ-M z#G3Gi6z471ZLLLx@x4?ZDsr40n)rlyCUWBH;%iTNgs~uocNFro+G5r9(o8XQ+$g`? zBe5yV=Zi#Vplmd_9sb zS6WIvnr}y*@aA*vuE3j_R&>cdP6VCxA(TRv&0r zRZ1_qR(L1)XE`^3eh5G-Au0wvPqTu8TO}WFiJgq9e9GW>x5PG<(FG2bsqnA~H_8$$ z0$$RniUv#xe3A^Xr_rD-G)9n5M@%|>jIj@_R3R{Qqj!(uKxvc{I5Cs!e{u^(vsLjM)#FH+I;)x?3_cCLcO3aN=delz=S$woo$)p+~Hq9Ogw$? zY;5PtVI|Bx=Qw#*@9Q$zMrZ1u6qRYQOtESLdDwMU`&* zX|l`1yRiAQ;~xcw-RzvuukO$jyPfwu8{@JVw9b)?=`z<6Yse&@`7tkW{?uTkdF&XM zd4q6ODDvhr1V-eIx3E@$w%vX1j>^};Bv;ChI;*cNogYBIGxEnbb*IP_tuGu-bfhut z_M0{wEMx2lX@4dpeAP8zjLt2X<;e4oRm>UKEQ-__9w3gCuaiQk`*_#-8R0Krgy;5Y zo9?*&&shLdo)4Elf^STCkNyZX#ZN0k%#%OxH?7k@<d8luWVUMj;c=)J*-Hz8^O_=oEW)k(|u#h`z^l`Pz?;DJ3pO&baNTpxj+ zzL1reZHSAWPaiIYzodeR+F31GYFYUsn4koJ1$GibgX2a3yJ8?cX$S9CKA7Y`;aZ-> zDs7=W*h6#%c3&SBd2(|aMB4bxdwsq0c+zZL+5!eHn~oP6KR7d;3hXj}RaDu|Xwvoc zA!hwm)*vlS^|PYTL1oM`?!v6THAo|)#4oo**0{Cz!&7*7x3<>5Yt?^RzHu2YVGMK3 z=2W;pO%c_P_oVY*9Q9aoG_eftnSAW&Y~676z(Dy;oUMP5}gRv#ubNkvSihChK#!w+*;uB7ZgXcs>bxjTYS({?Dxe@|SWNUt5w)2`dP)FF02@1$m6gatBcE(+;_H zFtp;M&}NDWerBjCyNAax<#Sw6BIke&D?WHSa4yd$BXORYNc-h&EyUNzId$14TF(?S zAA;qKdx!im{z!fjqI|1B4%5y47tnOctVf378?>()Zn|Ayu@1>^Y7Nr}=@40*^WmHA z5KU$cF~js@qA_a5fmBO4l@0flu678sJB6&@&DI8BAnpnJ*aq3})KXG`;U9je15FBm z5ER4>XdVZ`l|XO~g%z1?mr}V@oPvZ?s_dRi?iVtgJz@!tKmz~|A4Q)9MAzo=;J;{! zf`co1V;uvo0_=3l@%wW3UL6)(#m*VwD`HaqsVHn3VL&V_Z<|s60n&ZF7}dN>@2k9ChQ_;OkXVBXiy@IOAs3-GUJ5 zzldBq#gs~RXeujDEvTo2%?r6uQs(5DQK~}`mk7&kwtiD+2|&RhQ)F~OSg-%1J5Rz= z&iim{;}*2e7yF`}IMZHTa^%Qo{}3)FjKvL3hyTpcx>X(E-%-s-Y|plWJH)y)BRmQR zN){BS1c;MXgjclOV~1ESLvX`Q(w*6C-!Xh@A$gdQYF&jInN7l`knH#HEI*&i%QfNW z4R9`k9I@Xc1fjW`_ZJ`uK|jW-!4v~YU!o3v^A)mG0GyX#j^C?a&SDs}*(ji*Pa!Hw zA3?(az-x#H_9hJQF2GyJ;3EYc4cjd)s!F>@?0N**7#>=rC{f2mgNQ8* zb(BI?@&V8E;20^K(Ga}%?qG=XR<)yW8tvh*)M@q0vQ1n}+aRgYs*#grDoJ%Q9YLK| z%bVdR%<~GJpPn(T;s@$5VOnIS#?3$r&HNdDgY0I{Chgt|#S~KkOXh0#hA98-G+1KC zRx%^(#4tRMCv2u*PVR*{2F5zt6U4rP;d%*~kJ^iztVikBF?>otVV&$fqmKaiblqm< z6Hmj$C4P-Wtbt^+Y9zls^(&gy8(XTkKeQ)%#5jJpEGd-5S^1zvkw*j0DJM_cwh~aV zNK^|&-@~DIEUOpfuSXTsJ1xi#yBjC|wDy$jcGCVm9Pvm(`|Ie)!8nv-e?6?;r(Fav zBV#lsHV}Z`Us=qU?jR0i&#m3K{|T7KL4vPOOy<&^*6;w|2v;EJV@z0tmwn+?hZ}<@ z(?+Bbfc1fbsujZ-aGUaoRN^8ijjY5-)1RN{d*b)m*pnWWIKjY_&^FI8@Pn-rm`d`X zSgSCd@pYK$y}C>p?%K~W0>Rx9U0^wU*pOC}=5t;-6#!`9`Kd4? zpH2=L1q1;-?+DW;k;Nk(H!9X&B zBe4ijNeduvtjMnr7iCAL%=zzD5To95OM{ze%w6hRc5cndy!-=GsiXe@8?TfLxDtN{rD&CiQ3LcmPGH7 z!#H=MYwK$#dq>uGEoLbR6)lOk$sh7OG&EXD3DicIf~hXKptEi-tsp7G1?kD++$M`{ z*~G7HF5|J>3YHbum(AeqBC82Cj?b5ETE!6BP|yWc^kE-^$&<_=b>w^#mZ}=`(TjvF z)4;BTyP)2Xnq8;a`ijd0NAlu2UXTY8emv(@Kzni7wkPf0-PA#DmO@<#v?g&GvN-@I z@M=TUYKk-|Kq>ZvHK&YzQQoyZ-*(<+)2uN|weRKx9=3-Q@%9+rz$9cFApjXIzMmiZ!dm;|g zNJ%ISM_@{vp57Za-{ETdt5Yk()haqp7An;8t=+EH7))u_+hP@W!&O}p*(_bZ zJu;rh^;GU!e*dOnY*G0S#P!#teap6#(0hoPFVD{q;0M@qc?o`=_UA)D|YBB z&;P5wSI6POq717Kg>0DOtDjIrr=r)?uR$ny2U4&_b&-QdM3lKsS7*dcelp-rDj#a2 zdDW;ef5@t(G0;&ROE6R{je>=V61 z5eW?MuUDJpshZe3%eBM8^$iJ+6n;&eZc7|7e@bzwib%Q