From 25cec122237b9747dee466a582ab0a8bd36509db Mon Sep 17 00:00:00 2001 From: Ramy Gad Date: Thu, 20 Jul 2023 22:18:04 +0200 Subject: [PATCH 0001/1367] Tools: added name to GIT_Success.txt --- Tools/GIT_Test/GIT_Success.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/GIT_Test/GIT_Success.txt b/Tools/GIT_Test/GIT_Success.txt index fc7d6db5d721b6..3b1c20d8765801 100644 --- a/Tools/GIT_Test/GIT_Success.txt +++ b/Tools/GIT_Test/GIT_Success.txt @@ -175,3 +175,4 @@ Yacine Thabet - 57 Greg Poulos Torre Orazio seba czapnik +Ramy Gad From 3629037177af3b14c523f6844a02a7edc8f86cd5 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Fri, 7 Jul 2023 18:37:51 -0500 Subject: [PATCH 0002/1367] RC_Channel:clean up metadata for AUX switches --- libraries/RC_Channel/RC_Channel.cpp | 109 +++++++++++++--------------- 1 file changed, 51 insertions(+), 58 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 417e6d1007e115..0b155587e7e772 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -108,24 +108,22 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @DisplayName: RC input option // @Description: Function assigned to this RC channel // @Values{Copter, Rover, Plane, Blimp}: 0:Do Nothing - // @Values{Copter}: 2:Flip + // @Values{Copter}: 2:FLIP Mode // @Values{Copter}: 3:Simple Mode - // @Values{Copter, Rover}: 4:RTL - // @Values{Plane}: 4:ModeRTL + // @Values{Copter, Rover, Plane}: 4:RTL // @Values{Copter}: 5:Save Trim // @Values{Rover}: 5:Save Trim (4.1 and lower) // @Values{Copter, Rover}: 7:Save WP // @Values{Copter, Rover, Plane}: 9:Camera Trigger - // @Values{Copter}: 10:RangeFinder - // @Values{Copter, Rover, Plane}: 11:Fence + // @Values{Copter}: 10:RangeFinder Enable + // @Values{Copter, Rover, Plane}: 11:Fence Enable // @Values{Copter}: 13:Super Simple Mode // @Values{Copter}: 14:Acro Trainer - // @Values{Copter}: 15:Sprayer - // @Values{Copter, Rover}: 16:Auto - // @Values{Plane}: 16:ModeAuto - // @Values{Copter}: 17:AutoTune - // @Values{Copter, Blimp}: 18:Land - // @Values{Copter, Rover}: 19:Gripper + // @Values{Copter}: 15:Sprayer Enable + // @Values{Copter, Rover, Plane}: 16:AUTO Mode + // @Values{Copter}: 17:AUTOTUNE Mode + // @Values{Copter, Blimp}: 18:LAND Mode + // @Values{Copter, Rover}: 19:Gripper Release // @Values{Copter}: 21:Parachute Enable // @Values{Copter, Plane}: 22:Parachute Release // @Values{Copter}: 23:Parachute 3pos @@ -140,92 +138,87 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Plane}: 30:Lost Plane Sound // @Values{Copter, Rover, Plane}: 31:Motor Emergency Stop // @Values{Copter}: 32:Motor Interlock - // @Values{Copter}: 33:Brake + // @Values{Copter}: 33:BRAKE Mode // @Values{Copter, Rover, Plane}: 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off - // @Values{Copter}: 37:Throw - // @Values{Copter, Plane}: 38:ADSB Avoidance En - // @Values{Copter}: 39:PrecLoiter - // @Values{Copter, Rover}: 40:Proximity Avoidance + // @Values{Copter}: 37:THROW Mode + // @Values{Copter, Plane}: 38:ADSB Avoidance Enable + // @Values{Copter}: 39:PrecLoiter Enable + // @Values{Copter, Rover}: 40:Proximity Avoidance Enable // @Values{Copter, Rover, Plane}: 41:ArmDisarm (4.1 and lower) - // @Values{Copter, Rover}: 42:SmartRTL - // @Values{Copter, Plane}: 43:InvertedFlight + // @Values{Copter, Rover}: 42:SMARTRTL Mode + // @Values{Copter, Plane}: 43:InvertedFlight Enable // @Values{Copter}: 44:Winch Enable, 45:Winch Control // @Values{Copter, Rover, Plane, Blimp}: 46:RC Override Enable // @Values{Copter}: 47:User Function 1, 48:User Function 2, 49:User Function 3 - // @Values{Rover}: 50:LearnCruise - // @Values{Rover}: 51:Manual - // @Values{Plane}: 51:ModeManual - // @Values{Copter, Rover}: 52:Acro - // @Values{Plane}: 52:ModeACRO - // @Values{Rover}: 53:Steering - // @Values{Rover}: 54:Hold - // @Values{Copter, Rover}: 55:Guided - // @Values{Plane}: 55:ModeGuided - // @Values{Copter, Rover}: 56:Loiter - // @Values{Plane}: 56:ModeLoiter - // @Values{Copter, Rover}: 57:Follow + // @Values{Rover}: 50:LearnCruise Speed + // @Values{Rover, Plane}: 51:MANUAL Mode + // @Values{Copter, Rover, Plane}: 52:ACRO Mode + // @Values{Rover}: 53:STEERING Mode + // @Values{Rover}: 54:HOLD Mode + // @Values{Copter, Rover, Plane}: 55:GUIDED Mode + // @Values{Copter, Rover, Plane}: 56:LOITER Mode + // @Values{Copter, Rover}: 57:FOLLOW Mode // @Values{Copter, Rover, Plane}: 58:Clear Waypoints // @Values{Rover}: 59:Simple Mode - // @Values{Copter}: 60:ZigZag + // @Values{Copter}: 60:ZigZag Mode // @Values{Copter}: 61:ZigZag SaveWP // @Values{Copter, Rover, Plane}: 62:Compass Learn // @Values{Rover}: 63:Sailboat Tack // @Values{Plane}: 64:Reverse Throttle // @Values{Copter, Rover, Plane, Blimp}: 65:GPS Disable // @Values{Copter, Rover, Plane}: 66:Relay5 On/Off, 67:Relay6 On/Off - // @Values{Copter}: 68:Stabilize - // @Values{Copter}: 69:PosHold - // @Values{Copter}: 70:AltHold - // @Values{Copter}: 71:FlowHold - // @Values{Copter}: 72:Circle - // @Values{Plane}: 72:ModeCircle - // @Values{Copter}: 73:Drift + // @Values{Copter}: 68:STABILIZE Mode + // @Values{Copter}: 69:POSHOLD Mode + // @Values{Copter}: 70:ALTHOLD Mode + // @Values{Copter}: 71:FLOWHOLD Mode + // @Values{Copter,Plane}: 72:CIRCLE Mode + // @Values{Copter}: 73:DRIFT Mode // @Values{Rover}: 74:Sailboat motoring 3pos // @Values{Copter}: 75:SurfaceTrackingUpDown - // @Values{Copter}: 76:Standby Mode - // @Values{Plane}: 77:ModeTakeoff + // @Values{Copter}: 76:STANDBY Mode + // @Values{Plane}: 77:TAKEOFF Mode // @Values{Copter, Rover, Plane}: 78:RunCam Control // @Values{Copter, Rover, Plane}: 79:RunCam OSD Control // @Values{Copter}: 80:VisOdom Align - // @Values{Rover}: 80:Viso Align + // @Values{Rover}: 80:VisoOdom Align // @Values{Copter, Rover, Plane, Blimp}: 81:Disarm // @Values{Plane}: 82:QAssist 3pos // @Values{Copter}: 83:ZigZag Auto - // @Values{Copter, Plane}: 84:Air Mode + // @Values{Copter, Plane}: 84:AirMode // @Values{Copter, Plane}: 85:Generator - // @Values{Plane}: 86: Non Auto Terrain Follow Disable + // @Values{Plane}: 86:Non Auto Terrain Follow Disable // @Values{Plane}: 87:Crow Select // @Values{Plane}: 88:Soaring Enable // @Values{Plane}: 89:Landing Flare // @Values{Copter, Rover, Plane, Blimp}: 90:EKF Pos Source // @Values{Plane}: 91:Airspeed Ratio Calibration - // @Values{Plane}: 92:FBWA + // @Values{Plane}: 92:FBWA Mode // @Values{Copter, Rover, Plane}: 94:VTX Power // @Values{Plane}: 95:FBWA taildragger takeoff mode - // @Values{Plane}: 96:trigger re-reading of mode switch + // @Values{Plane}: 96:Trigger re-reading of mode switch // @Values{Rover}: 97:Windvane home heading direction offset - // @Values{Plane}: 98: ModeTraining + // @Values{Plane}: 98:TRAINING Mode // @Values{Copter}: 99:AUTO RTL // @Values{Copter, Rover, Plane, Blimp}: 100:KillIMU1, 101:KillIMU2 // @Values{Copter, Rover, Plane}: 102:Camera Mode Toggle // @Values{Copter, Rover, Plane}: 105:GPS Disable Yaw // @Values{Rover, Plane}: 106:Disable Airspeed Use - // @Values{Plane}: 107: EnableFixedWingAutotune - // @Values{Plane}: 108: ModeQRTL + // @Values{Plane}: 107:Enable FW Autotune + // @Values{Plane}: 108:QRTL Mode // @Values{Copter, Rover, Plane, Blimp}: 110:KillIMU3 - // @Values{Plane}: 150: CRUISE - // @Values{Copter}: 151:Turtle - // @Values{Copter}: 152:simple heading reset + // @Values{Plane}: 150:CRUISE Mode + // @Values{Copter}: 151:TURTLE Mode + // @Values{Copter}: 152:SIMPLE heading reset // @Values{Copter, Rover, Plane}: 153:ArmDisarm (4.2 and higher) // @Values{Blimp}: 153:ArmDisarm // @Values{Copter}: 154:ArmDisarm with AirMode (4.2 and higher) // @Values{Plane}: 154:ArmDisarm with Quadplane AirMode (4.2 and higher) - // @Values{Rover}: 155: set steering trim to current servo and RC - // @Values{Plane}: 155: set roll pitch and yaw trim to current servo and RC + // @Values{Rover}: 155:Set steering trim to current servo and RC + // @Values{Plane}: 155:Set roll pitch and yaw trim to current servo and RC // @Values{Rover}: 156:Torqeedo Clear Err - // @Values{Plane}: 157: Force FS Action to FBWA + // @Values{Plane}: 157:Force FS Action to FBWA // @Values{Copter, Plane}: 158:Optflow Calibration - // @Values{Copter}: 159:Force Flying + // @Values{Copter}: 159:Force IS_Flying // @Values{Plane}: 160:Weathervane Enable // @Values{Copter}: 161:Turbine Start(heli) // @Values{Copter, Rover, Plane}: 162:FFT Tune @@ -233,7 +226,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Copter, Rover, Plane, Blimp}: 164:Pause Stream Logging // @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:Mode QStabilize + // @Values{Plane}: 170:QSTABILIZE Mode // @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 @@ -242,8 +235,8 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Rover}: 202:Pitch // @Values{Rover}: 207:MainSail // @Values{Rover, Plane}: 208:Flap - // @Values{Plane}: 209: Forward Throttle - // @Values{Plane}: 210: Airbrakes + // @Values{Plane}: 209:VTOL Forward Throttle + // @Values{Plane}: 210:Airbrakes // @Values{Rover}: 211:Walking Height // @Values{Copter, Rover, Plane}: 212:Mount1 Roll, 213:Mount1 Pitch, 214:Mount1 Yaw, 215:Mount2 Roll, 216:Mount2 Pitch, 217:Mount2 Yaw // @Values{Copter, Rover, Plane}: 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8 From 029070cb23fb354b20bcca9e2f759805fc3b9464 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 19 Jul 2023 18:51:27 +1000 Subject: [PATCH 0003/1367] waf: enable CANARD asserts in SITL --- 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 98005453a60618..3491fb79205c04 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -649,7 +649,8 @@ def configure_env(self, cfg, env): cfg.define('HAL_NUM_CAN_IFACES', 2) env.DEFINES.update(CANARD_MULTI_IFACE=1, CANARD_IFACE_ALL = 0x3, - CANARD_ENABLE_CANFD = 1) + CANARD_ENABLE_CANFD = 1, + CANARD_ENABLE_ASSERTS = 1) env.CXXFLAGS += [ '-Werror=float-equal', From bacea2ec8efd8c1822d9294c32e978562d717f00 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 19 Jul 2023 18:51:58 +1000 Subject: [PATCH 0004/1367] DroneCAN: update libcanard --- modules/DroneCAN/libcanard | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/DroneCAN/libcanard b/modules/DroneCAN/libcanard index bf178bb75eafbf..22102c717db29c 160000 --- a/modules/DroneCAN/libcanard +++ b/modules/DroneCAN/libcanard @@ -1 +1 @@ -Subproject commit bf178bb75eafbfb9445f6e8a0cc4717b3ec2be9e +Subproject commit 22102c717db29cc2a2c2869ff80f3e4389704d89 From 7e91de33a4f27d1442f5946fb0d5c0f8d57f9c0c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 23 Jul 2023 09:00:29 +1000 Subject: [PATCH 0005/1367] AP_Periph: update release notes for 1.5.1 --- Tools/AP_Periph/ReleaseNotes.txt | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/Tools/AP_Periph/ReleaseNotes.txt b/Tools/AP_Periph/ReleaseNotes.txt index 76666579839791..5165da3b526307 100644 --- a/Tools/AP_Periph/ReleaseNotes.txt +++ b/Tools/AP_Periph/ReleaseNotes.txt @@ -1,3 +1,19 @@ +Release 1.5.1 23rd July 2023 +--------------------------- + +This is a major release with the following changes: + +- support serial tunnelling over DroneCAN +- raised CAN priority of MovingBaseline data +- support APD ESC telemetry +- support DroneCAN and CAN statistics reporting +- support KDECAN to DroneCAN translation + +The serial tunnelling support allows for uCenter to be used over +DroneCAN with the serial tunnelling panel in the DroneCAN GUI +tool. This allows for monitoring of uBlox GPS over a telemetry link, +and update of F9P firmware over DroneCAN + Release 1.5.0 27th Mar 2023 --------------------------- From 9f9be8da0f0f57c751394a78f773bb9474c8da69 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 4 Jun 2023 18:51:30 +0100 Subject: [PATCH 0006/1367] AP_HAL_ChibiOS: correct voltage sensor and current scale on speedybeef4v3 --- libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat index e5a5dca8a7414d..16826a92d19873 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat @@ -50,19 +50,19 @@ PB10 I2C2_SCL I2C2 PB11 I2C2_SDA I2C2 # analog pins -PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1) PC1 BATT_CURRENT_SENS ADC1 SCALE(1) -PC2 RSSI_ADC_PIN ADC1 SCALE(1) +PC0 RSSI_ADC_PIN ADC1 SCALE(1) # define default battery setup define HAL_BATT_MONITOR_DEFAULT 4 -define HAL_BATT_VOLT_PIN 10 +define HAL_BATT_VOLT_PIN 12 define HAL_BATT_CURR_PIN 11 define HAL_BATT_VOLT_SCALE 11.2 # matched to ESC output -define HAL_BATT_CURR_SCALE 52.7 # appropriate for a T-Motor F55A Pro II +define HAL_BATT_CURR_SCALE 173.5 # appropriate for a T-Motor F55A Pro II # analog rssi pin -define BOARD_RSSI_ANA_PIN 12 +define BOARD_RSSI_ANA_PIN 10 # USART1 (DJI / VTX) PA9 USART1_TX USART1 From f93295017ab172022740c38748841ae238c98e96 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 23 Jul 2023 12:38:38 +0200 Subject: [PATCH 0007/1367] Revert "AP_HAL_ChibiOS: correct voltage sensor and current scale on speedybeef4v3" This reverts commit 9f9be8da0f0f57c751394a78f773bb9474c8da69. --- libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat index 16826a92d19873..e5a5dca8a7414d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/speedybeef4v3/hwdef.dat @@ -50,19 +50,19 @@ PB10 I2C2_SCL I2C2 PB11 I2C2_SDA I2C2 # analog pins -PC2 BATT_VOLTAGE_SENS ADC1 SCALE(1) +PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1) PC1 BATT_CURRENT_SENS ADC1 SCALE(1) -PC0 RSSI_ADC_PIN ADC1 SCALE(1) +PC2 RSSI_ADC_PIN ADC1 SCALE(1) # define default battery setup define HAL_BATT_MONITOR_DEFAULT 4 -define HAL_BATT_VOLT_PIN 12 +define HAL_BATT_VOLT_PIN 10 define HAL_BATT_CURR_PIN 11 define HAL_BATT_VOLT_SCALE 11.2 # matched to ESC output -define HAL_BATT_CURR_SCALE 173.5 # appropriate for a T-Motor F55A Pro II +define HAL_BATT_CURR_SCALE 52.7 # appropriate for a T-Motor F55A Pro II # analog rssi pin -define BOARD_RSSI_ANA_PIN 10 +define BOARD_RSSI_ANA_PIN 12 # USART1 (DJI / VTX) PA9 USART1_TX USART1 From a602473e89836d67e121978b48a634b587e4c9e4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 17 Jul 2023 14:04:55 +1000 Subject: [PATCH 0008/1367] hwdef: added SIYI NY flight controller based on pinout of Durandal --- libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef-bl.dat | 8 ++++++++ libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat | 8 ++++++++ 2 files changed, 16 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef-bl.dat new file mode 100644 index 00000000000000..3c34c3011862f6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef-bl.dat @@ -0,0 +1,8 @@ +include ../Durandal/hwdef-bl.dat + +# board ID for firmware load +APJ_BOARD_ID 1123 + +undef USB_VENDOR +undef USB_PRODUCT +undef USB_STRING_MANUFACTURER diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat new file mode 100644 index 00000000000000..ec27dd4bb00d4e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/SIYI_N7/hwdef.dat @@ -0,0 +1,8 @@ +include ../Durandal/hwdef.dat + +# board ID for firmware load +APJ_BOARD_ID 1123 + +undef USB_VENDOR +undef USB_PRODUCT +undef USB_STRING_MANUFACTURER From 19029c4cc16029928e690c9f5cd8a83ee5e23fcf Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 17 Jul 2023 14:04:55 +1000 Subject: [PATCH 0009/1367] Tools: added SIYI NY flight controller based on pinout of Durandal --- 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 956b1027b164fd..94742f85d832a2 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -233,6 +233,7 @@ AP_HW_HEEWING_F405 1119 AP_HW_PodmanH7 1120 AP_HW_mRo-M10053 1121 AP_HW_mRo-M10044 1122 +AP_HW_SIYI_N7 1123 AP_HW_ESP32_PERIPH 1205 AP_HW_ESP32S3_PERIPH 1206 From 9dbcce446009379e95e3a30323e2de8ce77afd49 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Fri, 21 Jul 2023 07:07:23 -0500 Subject: [PATCH 0010/1367] Plane:expand log metadata for QTUN --- ArduPlane/Log.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 4dde2e5dbe7ace..374b612adeb61a 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -377,8 +377,8 @@ const struct LogStructure Plane::log_structure[] = { // @Field: CRt: climb rate // @Field: TMix: transition throttle mix value // @Field: Sscl: speed scalar for tailsitter control surfaces -// @Field: Trn: Transistion state -// @Field: Ast: Q assist active state +// @Field: Trn: Transition state: 0-AirspeedWait,1-Timer,2-Done / TailSitter: 0-FW Wait,1-VTOL Wait,2-Done +// @Field: Ast: Q assist active #if HAL_QUADPLANE_ENABLED { LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning), "QTUN", "QffffffeccffBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trn,Ast", "s----mmmnn----", "F----00000-0--" , true }, From 0de7544650a126ec70639c5c3f81690b0d9b21b0 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 26 Jul 2023 01:17:59 +0100 Subject: [PATCH 0011/1367] Copter: SURFTRAK_MODE: mark as reboot required --- ArduCopter/Parameters.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 95c362ea17cb2e..334c4b02934414 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1040,6 +1040,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Description: set which surface to track in surface tracking // @Values: 0:Do not track, 1:Ground, 2:Ceiling // @User: Advanced + // @RebootRequired: True AP_GROUPINFO("SURFTRAK_MODE", 51, ParametersG2, surftrak_mode, (uint8_t)Copter::SurfaceTracking::Surface::GROUND), // @Param: FS_DR_ENABLE From 2cb3265131b589742e0786e04715097676dc2131 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 18 Jul 2023 12:04:09 +1000 Subject: [PATCH 0012/1367] AP_HAL_SITL: factor _timer_tick into read/write methods --- libraries/AP_HAL_SITL/UARTDriver.cpp | 39 +++++++++++++++++++++++++--- libraries/AP_HAL_SITL/UARTDriver.h | 9 ++++++- 2 files changed, 43 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 64ffbf93776fb7..2c75d77e15fde0 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -796,7 +796,7 @@ uint16_t UARTDriver::read_from_async_csv(uint8_t *buffer, uint16_t space) return i; } -void UARTDriver::_timer_tick(void) +void UARTDriver::handle_writing_from_writebuffer_to_device() { if (!_connected) { _check_reconnect(); @@ -809,12 +809,12 @@ void UARTDriver::_timer_tick(void) if (_sitl && _sitl->telem_baudlimit_enable) { // limit byte rate to configured baudrate uint32_t now = AP_HAL::micros(); - float dt = 1.0e-6 * (now - last_tick_us); + float dt = 1.0e-6 * (now - last_write_tick_us); max_bytes = _uart_baudrate * dt / 10; if (max_bytes == 0) { return; } - last_tick_us = now; + last_write_tick_us = now; } #endif if (_packetise) { @@ -856,13 +856,37 @@ void UARTDriver::_timer_tick(void) } } } +} + +void UARTDriver::handle_reading_from_device_to_readbuffer() +{ + if (!_connected) { + _check_reconnect(); + return; + } uint32_t space = _readbuffer.space(); if (space == 0) { return; } + + uint32_t max_bytes = 10000; +#if !defined(HAL_BUILD_AP_PERIPH) + SITL::SIM *_sitl = AP::sitl(); + if (_sitl && _sitl->telem_baudlimit_enable) { + // limit byte rate to configured baudrate + uint32_t now = AP_HAL::micros(); + float dt = 1.0e-6 * (now - last_read_tick_us); + max_bytes = _uart_baudrate * dt / 10; + if (max_bytes == 0) { + return; + } + last_read_tick_us = now; + } +#endif + space = MIN(space, max_bytes); - + char buf[space]; ssize_t nread = 0; if (_mc_fd >= 0) { @@ -929,6 +953,13 @@ void UARTDriver::_timer_tick(void) } } +void UARTDriver::_timer_tick(void) +{ + handle_writing_from_writebuffer_to_device(); + handle_reading_from_device_to_readbuffer(); +} + + /* return timestamp estimate in microseconds for when the start of a nbytes packet arrived on the uart. This should be treated as a diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index 02878d2fd22651..1538908864688d 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -106,7 +106,10 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { bool _is_udp; bool _packetise; uint16_t _mc_myport; - uint32_t last_tick_us; + + // for baud-rate limiting: + uint32_t last_read_tick_us; + uint32_t last_write_tick_us; SITL::SerialDevice *_sim_serial_device; @@ -134,6 +137,10 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { void _end() override; void _flush() override; bool _discard_input() override; + +private: + void handle_writing_from_writebuffer_to_output(); + void handle_reading_from_device_to_readbuffer(); }; #endif From 7b83ccfdd1c1156eece6ec986e7d13336406c597 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 18 Jul 2023 12:05:41 +1000 Subject: [PATCH 0013/1367] AP_HAL_SITL: change SITL unbuffered writes to more-closely minim ChibiOS HAL We don't ever actually do unbuffered writes in ChibiOS. We just poke the relevant thread to say there's data available. This kind of mimics that my instantly evoking the same routine the timer-tick method does, which may or may not get all of the bytes out in good order. --- libraries/AP_HAL_SITL/UARTDriver.cpp | 20 +++++++------------- libraries/AP_HAL_SITL/UARTDriver.h | 2 +- 2 files changed, 8 insertions(+), 14 deletions(-) diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 2c75d77e15fde0..41f109274ad3a9 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -263,18 +263,7 @@ size_t UARTDriver::_write(const uint8_t *buffer, size_t size) if (size <= 0) { return 0; } - if (_unbuffered_writes) { - const ssize_t nwritten = ::write(_fd, buffer, size); - if (nwritten == -1 && errno != EAGAIN && _uart_path) { - close(_fd); - _fd = -1; - _connected = false; - return 0; - } - // these have no effect - tcdrain(_fd); - return nwritten; - } else { + /* simulate byte loss at the link layer */ @@ -288,8 +277,13 @@ size_t UARTDriver::_write(const uint8_t *buffer, size_t size) } } #endif // HAL_BUILD_AP_PERIPH - return _writebuffer.write(buffer, size - lost_byte) + lost_byte; + + + const size_t ret = _writebuffer.write(buffer, size - lost_byte) + lost_byte; + if (_unbuffered_writes) { + handle_writing_from_writebuffer_to_device(); } + return ret; } diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index 1538908864688d..fb0476550bb213 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -139,7 +139,7 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { bool _discard_input() override; private: - void handle_writing_from_writebuffer_to_output(); + void handle_writing_from_writebuffer_to_device(); void handle_reading_from_device_to_readbuffer(); }; From a5d4133a2c23f0d17fbf10d061a00be03a29b2e1 Mon Sep 17 00:00:00 2001 From: Asif Khan Date: Fri, 21 Jul 2023 12:05:42 +0530 Subject: [PATCH 0014/1367] AP_Camera: add MNT log msg for mount's actual and target angles logging --- libraries/AP_Camera/AP_Camera_Logging.cpp | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera_Logging.cpp b/libraries/AP_Camera/AP_Camera_Logging.cpp index f6a5e26541fe4c..bad765067e36f1 100644 --- a/libraries/AP_Camera/AP_Camera_Logging.cpp +++ b/libraries/AP_Camera/AP_Camera_Logging.cpp @@ -1,11 +1,12 @@ #include "AP_Camera_Backend.h" +#include #if AP_CAMERA_ENABLED #include #include -// Write a Camera packet +// Write a Camera packet. Also writes a Mount packet if available void AP_Camera_Backend::Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us) { // exit immediately if no logger @@ -41,9 +42,14 @@ void AP_Camera_Backend::Write_CameraInfo(enum LogMessages msg, uint64_t timestam altitude_gps = 0; } + // if timestamp is zero set to current system time + if (timestamp_us == 0) { + timestamp_us = AP_HAL::micros64(); + } + const struct log_Camera pkt{ LOG_PACKET_HEADER_INIT(static_cast(msg)), - time_us : timestamp_us ? timestamp_us : AP_HAL::micros64(), + time_us : timestamp_us, instance : _instance, image_number: image_index, gps_time : gps.time_week_ms(), @@ -58,6 +64,14 @@ void AP_Camera_Backend::Write_CameraInfo(enum LogMessages msg, uint64_t timestam yaw : (uint16_t)ahrs.yaw_sensor }; AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt)); + +#if HAL_MOUNT_ENABLED + auto *mount = AP_Mount::get_singleton(); + if (mount!= nullptr) { + // assuming camera instance matches mount instance + mount->write_log(_instance, timestamp_us); + } +#endif } // Write a Camera packet From b5d1363c284d820bb0f5e3add0009d56eb2dfad3 Mon Sep 17 00:00:00 2001 From: Asif Khan Date: Fri, 21 Jul 2023 12:05:42 +0530 Subject: [PATCH 0015/1367] AP_Logger: add MNT log msg for mount's actual and target angles logging --- libraries/AP_Logger/LogStructure.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index 9ec9e5c15aa1f8..7254072b7ff94a 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -131,6 +131,7 @@ const struct MultiplierStructure log_Multipliers[] = { #include #include #include +#include #include #include #include @@ -1260,6 +1261,7 @@ LOG_STRUCTURE_FROM_PRECLAND \ { LOG_RADIO_MSG, sizeof(log_Radio), \ "RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed", "s-------", "F-------", true }, \ LOG_STRUCTURE_FROM_CAMERA \ +LOG_STRUCTURE_FROM_MOUNT \ { LOG_ARSP_MSG, sizeof(log_ARSP), "ARSP", "QBffcffBBffB", "TimeUS,I,Airspeed,DiffPress,Temp,RawPress,Offset,U,H,Hp,TR,Pri", "s#nPOPP-----", "F-00B00-----", true }, \ LOG_STRUCTURE_FROM_BATTMONITOR \ { LOG_MAG_MSG, sizeof(log_MAG), \ @@ -1370,6 +1372,7 @@ enum LogMessages : uint8_t { LOG_RADIO_MSG, LOG_ATRP_MSG, LOG_IDS_FROM_CAMERA, + LOG_IDS_FROM_MOUNT, LOG_TERRAIN_MSG, LOG_CSRV_MSG, LOG_IDS_FROM_ESC_TELEM, From fd6db1ef4501b5ede24035a0961cef528fc31601 Mon Sep 17 00:00:00 2001 From: Asif Khan Date: Fri, 21 Jul 2023 12:05:42 +0530 Subject: [PATCH 0016/1367] AP_Mount: add MNT log msg for mount's actual and target angles logging --- libraries/AP_Mount/AP_Mount.cpp | 24 ++- libraries/AP_Mount/AP_Mount.h | 12 +- libraries/AP_Mount/AP_Mount_Alexmos.cpp | 61 ++++--- libraries/AP_Mount/AP_Mount_Alexmos.h | 2 - libraries/AP_Mount/AP_Mount_Backend.cpp | 168 ++++++++++++------ libraries/AP_Mount/AP_Mount_Backend.h | 33 ++-- libraries/AP_Mount/AP_Mount_Gremsy.cpp | 73 ++++---- libraries/AP_Mount/AP_Mount_SToRM32.cpp | 53 +++--- libraries/AP_Mount/AP_Mount_SToRM32.h | 1 - .../AP_Mount/AP_Mount_SToRM32_serial.cpp | 49 ++--- libraries/AP_Mount/AP_Mount_SToRM32_serial.h | 1 - libraries/AP_Mount/AP_Mount_Scripting.cpp | 126 +++---------- libraries/AP_Mount/AP_Mount_Scripting.h | 9 +- libraries/AP_Mount/AP_Mount_Servo.cpp | 86 +++++---- libraries/AP_Mount/AP_Mount_Servo.h | 1 - libraries/AP_Mount/AP_Mount_Siyi.cpp | 74 ++++---- libraries/AP_Mount/AP_Mount_SoloGimbal.cpp | 59 +++--- libraries/AP_Mount/AP_Mount_SoloGimbal.h | 1 - libraries/AP_Mount/AP_Mount_Viewpro.cpp | 67 +++---- libraries/AP_Mount/AP_Mount_Xacti.cpp | 71 ++++---- libraries/AP_Mount/LogStructure.h | 38 ++++ 21 files changed, 549 insertions(+), 460 deletions(-) create mode 100644 libraries/AP_Mount/LogStructure.h diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 3e1ac030fc96fe..5b7cdf6c3edfb0 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -646,7 +646,7 @@ bool AP_Mount::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) return true; } -// accessors for scripting backends +// get target rate in deg/sec. returns true on success bool AP_Mount::get_rate_target(uint8_t instance, float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) { auto *backend = get_instance(instance); @@ -656,6 +656,7 @@ bool AP_Mount::get_rate_target(uint8_t instance, float& roll_degs, float& pitch_ return backend->get_rate_target(roll_degs, pitch_degs, yaw_degs, yaw_is_earth_frame); } +// get target angle in deg. returns true on success bool AP_Mount::get_angle_target(uint8_t instance, float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) { auto *backend = get_instance(instance); @@ -665,6 +666,7 @@ bool AP_Mount::get_angle_target(uint8_t instance, float& roll_deg, float& pitch_ return backend->get_angle_target(roll_deg, pitch_deg, yaw_deg, yaw_is_earth_frame); } +// accessors for scripting backends and logging bool AP_Mount::get_location_target(uint8_t instance, Location& target_loc) { auto *backend = get_instance(instance); @@ -683,6 +685,26 @@ void AP_Mount::set_attitude_euler(uint8_t instance, float roll_deg, float pitch_ backend->set_attitude_euler(roll_deg, pitch_deg, yaw_bf_deg); } +// write mount log packet for all backends +void AP_Mount::write_log() +{ + // each instance writes log + for (uint8_t instance=0; instancewrite_log(0); + } + } +} + +void AP_Mount::write_log(uint8_t instance, uint64_t timestamp_us) +{ + auto *backend = get_instance(instance); + if (backend == nullptr) { + return; + } + backend->write_log(timestamp_us); +} + // point at system ID sysid void AP_Mount::set_target_sysid(uint8_t instance, uint8_t sysid) { diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index b4187eabe46deb..6067f7073258e1 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -199,12 +199,22 @@ class AP_Mount // any failure_msg returned will not include a prefix bool pre_arm_checks(char *failure_msg, uint8_t failure_msg_len); - // accessors for scripting backends + // get target rate in deg/sec. returns true on success bool get_rate_target(uint8_t instance, float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame); + + // get target angle in deg. returns true on success bool get_angle_target(uint8_t instance, float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame); + + // accessors for scripting backends and logging bool get_location_target(uint8_t instance, Location& target_loc); void set_attitude_euler(uint8_t instance, float roll_deg, float pitch_deg, float yaw_bf_deg); + // write mount log packet for all backends + void write_log(); + + // write mount log packet for a single backend (called by camera library) + void write_log(uint8_t instance, uint64_t timestamp_us); + // // camera controls for gimbals that include a camera // diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.cpp b/libraries/AP_Mount/AP_Mount_Alexmos.cpp index 1b831edc01c3de..f7f39f6119be40 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.cpp +++ b/libraries/AP_Mount/AP_Mount_Alexmos.cpp @@ -30,58 +30,59 @@ void AP_Mount_Alexmos::update() // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism case MAV_MOUNT_MODE_RETRACT: { const Vector3f &target = _params.retract_angles.get(); - _angle_rad.roll = radians(target.x); - _angle_rad.pitch = radians(target.y); - _angle_rad.yaw = radians(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); break; } // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &target = _params.neutral_angles.get(); - _angle_rad.roll = radians(target.x); - _angle_rad.pitch = radians(target.y); - _angle_rad.yaw = radians(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - _angle_rad = mavt_target.angle_rad; - break; - case MountTargetType::RATE: - update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); - break; - } + // mavlink targets are stored while handling the incoming message break; // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { // update targets using pilot's RC inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - update_angle_target_from_rate(rc_target, _angle_rad); - } else if (get_rc_angle_target(rc_target)) { - _angle_rad = rc_target; + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + mnt_target.angle_rad = rc_target; + break; + case MountTargetType::RATE: + mnt_target.rate_rads = rc_target; + break; } break; } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - IGNORE_RETURN(get_angle_target_to_roi(_angle_rad)); + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + } break; + // point mount to Home location case MAV_MOUNT_MODE_HOME_LOCATION: - IGNORE_RETURN(get_angle_target_to_home(_angle_rad)); + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + } break; + // point mount to another vehicle case MAV_MOUNT_MODE_SYSID_TARGET: - IGNORE_RETURN(get_angle_target_to_sysid(_angle_rad)); + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + } break; default: @@ -89,8 +90,16 @@ void AP_Mount_Alexmos::update() break; } - // send latest targets to gimbal - control_axis(_angle_rad); + // send target angles or rates depending on the target type + switch (mnt_target.target_type) { + case MountTargetType::RATE: + update_angle_target_from_rate(mnt_target.rate_rads, mnt_target.angle_rad); + FALLTHROUGH; + case MountTargetType::ANGLE: + // send latest angle targets to gimbal + control_axis(mnt_target.angle_rad); + break; + } } // has_pan_control - returns true if this mount can control its pan (required for multicopters) diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.h b/libraries/AP_Mount/AP_Mount_Alexmos.h index 1547d4a2fa8840..6485073dd4f5cb 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.h +++ b/libraries/AP_Mount/AP_Mount_Alexmos.h @@ -112,8 +112,6 @@ class AP_Mount_Alexmos : public AP_Mount_Backend // read_incoming - detect and read the header of the incoming message from the gimbal void read_incoming(); - MountTarget _angle_rad; // latest angle target - // structure for the Serial Protocol // CMD_BOARD_INFO diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index d4bc9b3a15085c..ac4d2878eb7e93 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -2,6 +2,7 @@ #if HAL_MOUNT_ENABLED #include #include +#include extern const AP_HAL::HAL& hal; @@ -49,11 +50,11 @@ void AP_Mount_Backend::set_angle_target(float roll_deg, float pitch_deg, float y } // set angle targets - mavt_target.target_type = MountTargetType::ANGLE; - mavt_target.angle_rad.roll = radians(roll_deg); - mavt_target.angle_rad.pitch = radians(pitch_deg); - mavt_target.angle_rad.yaw = radians(yaw_deg); - mavt_target.angle_rad.yaw_is_ef = yaw_is_earth_frame; + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.roll = radians(roll_deg); + mnt_target.angle_rad.pitch = radians(pitch_deg); + mnt_target.angle_rad.yaw = radians(yaw_deg); + mnt_target.angle_rad.yaw_is_ef = yaw_is_earth_frame; // set the mode to mavlink targeting set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING); @@ -64,11 +65,11 @@ void AP_Mount_Backend::set_angle_target(float roll_deg, float pitch_deg, float y void AP_Mount_Backend::set_rate_target(float roll_degs, float pitch_degs, float yaw_degs, bool yaw_is_earth_frame) { // set rate targets - mavt_target.target_type = MountTargetType::RATE; - mavt_target.rate_rads.roll = radians(roll_degs); - mavt_target.rate_rads.pitch = radians(pitch_degs); - mavt_target.rate_rads.yaw = radians(yaw_degs); - mavt_target.rate_rads.yaw_is_ef = yaw_is_earth_frame; + mnt_target.target_type = MountTargetType::RATE; + mnt_target.rate_rads.roll = radians(roll_degs); + mnt_target.rate_rads.pitch = radians(pitch_degs); + mnt_target.rate_rads.yaw = radians(yaw_degs); + mnt_target.rate_rads.yaw_is_ef = yaw_is_earth_frame; // set the mode to mavlink targeting set_mode(MAV_MOUNT_MODE_MAVLINK_TARGETING); @@ -356,6 +357,49 @@ bool AP_Mount_Backend::handle_global_position_int(uint8_t msg_sysid, const mavli return true; } +// write mount log packet +void AP_Mount_Backend::write_log(uint64_t timestamp_us) +{ + // return immediately if no yaw estimate + float ahrs_yaw = AP::ahrs().yaw; + if (isnan(ahrs_yaw)) { + return; + } + + const auto nanf = AP::logger().quiet_nanf(); + + // get_attitude_quaternion and convert to Euler angles + float roll = nanf; + float pitch = nanf; + float yaw_bf = nanf; + float yaw_ef = nanf; + if (_frontend.get_attitude_euler(_instance, roll, pitch, yaw_bf)) { + yaw_ef = wrap_180(yaw_bf + degrees(ahrs_yaw)); + } + + // get mount's target (desired) angles and convert yaw to earth frame + float target_roll = nanf; + float target_pitch = nanf; + float target_yaw = nanf; + bool target_yaw_is_ef = false; + IGNORE_RETURN(get_angle_target(target_roll, target_pitch, target_yaw, target_yaw_is_ef)); + + const struct log_Mount pkt { + LOG_PACKET_HEADER_INIT(static_cast(LOG_MOUNT_MSG)), + time_us : (timestamp_us > 0) ? timestamp_us : AP_HAL::micros64(), + instance : _instance, + desired_roll : target_roll, + actual_roll : roll, + desired_pitch : target_pitch, + actual_pitch : pitch, + desired_yaw_bf: target_yaw_is_ef ? nanf : target_yaw, + actual_yaw_bf : yaw_bf, + desired_yaw_ef: target_yaw_is_ef ? target_yaw : nanf, + actual_yaw_ef : yaw_ef, + }; + AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt)); +} + // 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 { @@ -379,61 +423,44 @@ void AP_Mount_Backend::get_rc_input(float& roll_in, float& pitch_in, float& yaw_ } } -// get rate targets (in rad/s) from pilot RC -// returns true on success (RC is providing rate targets), false on failure (RC is providing angle targets) -bool AP_Mount_Backend::get_rc_rate_target(MountTarget& rate_rads) const +// get angle or rate targets from pilot RC +// target_type will be either ANGLE or RATE, rpy will be the target angle in deg or rate in deg/s +void AP_Mount_Backend::get_rc_target(MountTargetType& target_type, MountTarget& target_rpy) const { - // exit immediately if RC is not providing rate targets - if (_params.rc_rate_max <= 0) { - return false; - } - // get RC input from pilot float roll_in, pitch_in, yaw_in; get_rc_input(roll_in, pitch_in, yaw_in); - // calculate rates - const float rc_rate_max_rads = radians(_params.rc_rate_max.get()); - rate_rads.roll = roll_in * rc_rate_max_rads; - rate_rads.pitch = pitch_in * rc_rate_max_rads; - rate_rads.yaw = yaw_in * rc_rate_max_rads; - // yaw frame - rate_rads.yaw_is_ef = _yaw_lock; - - return true; -} + target_rpy.yaw_is_ef = _yaw_lock; -// get angle targets (in radians) from pilot RC -// returns true on success (RC is providing angle targets), false on failure (RC is providing rate targets) -bool AP_Mount_Backend::get_rc_angle_target(MountTarget& angle_rad) const -{ - // exit immediately if RC is not providing angle targets - if (_params.rc_rate_max > 0) { - return false; - } - - // get RC input from pilot - float roll_in, pitch_in, yaw_in; - get_rc_input(roll_in, pitch_in, yaw_in); + // if RC_RATE is zero, targets are angle + if (_params.rc_rate_max <= 0) { + target_type = MountTargetType::ANGLE; - // roll angle - angle_rad.roll = radians(((roll_in + 1.0f) * 0.5f * (_params.roll_angle_max - _params.roll_angle_min) + _params.roll_angle_min)); + // roll angle + target_rpy.roll = radians(((roll_in + 1.0f) * 0.5f * (_params.roll_angle_max - _params.roll_angle_min) + _params.roll_angle_min)); - // pitch angle - angle_rad.pitch = radians(((pitch_in + 1.0f) * 0.5f * (_params.pitch_angle_max - _params.pitch_angle_min) + _params.pitch_angle_min)); + // pitch angle + target_rpy.pitch = radians(((pitch_in + 1.0f) * 0.5f * (_params.pitch_angle_max - _params.pitch_angle_min) + _params.pitch_angle_min)); - // yaw angle - angle_rad.yaw_is_ef = _yaw_lock; - if (angle_rad.yaw_is_ef) { - // if yaw is earth-frame pilot yaw input control angle from -180 to +180 deg - angle_rad.yaw = yaw_in * M_PI; - } else { - // yaw target in body frame so apply body frame limits - angle_rad.yaw = radians(((yaw_in + 1.0f) * 0.5f * (_params.yaw_angle_max - _params.yaw_angle_min) + _params.yaw_angle_min)); + // yaw angle + if (target_rpy.yaw_is_ef) { + // if yaw is earth-frame pilot yaw input control angle from -180 to +180 deg + target_rpy.yaw = yaw_in * M_PI; + } else { + // yaw target in body frame so apply body frame limits + target_rpy.yaw = radians(((yaw_in + 1.0f) * 0.5f * (_params.yaw_angle_max - _params.yaw_angle_min) + _params.yaw_angle_min)); + } + return; } - return true; + // calculate rate targets + target_type = MountTargetType::RATE; + const float rc_rate_max_rads = radians(_params.rc_rate_max.get()); + target_rpy.roll = roll_in * rc_rate_max_rads; + target_rpy.pitch = pitch_in * rc_rate_max_rads; + target_rpy.yaw = yaw_in * rc_rate_max_rads; } // get angle targets (in radians) to a Location @@ -507,6 +534,15 @@ float AP_Mount_Backend::MountTarget::get_ef_yaw() const return wrap_PI(yaw + AP::ahrs().yaw); } +// sets roll, pitch, yaw and yaw_is_ef +void AP_Mount_Backend::MountTarget::set(const Vector3f& rpy, bool yaw_is_ef_in) +{ + roll = rpy.x; + pitch = rpy.y; + yaw = rpy.z; + yaw_is_ef = yaw_is_ef_in; +} + // update angle targets using a given rate target // the resulting angle_rad yaw frame will match the rate_rad yaw frame // assumes a 50hz update rate @@ -572,6 +608,32 @@ bool AP_Mount_Backend::get_angle_target_to_sysid(MountTarget& angle_rad) const return get_angle_target_to_location(_target_sysid_location, angle_rad); } +// get target rate in deg/sec. returns true on success +bool AP_Mount_Backend::get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) +{ + if (mnt_target.target_type == MountTargetType::RATE) { + roll_degs = degrees(mnt_target.rate_rads.roll); + pitch_degs = degrees(mnt_target.rate_rads.pitch); + yaw_degs = degrees(mnt_target.rate_rads.yaw); + yaw_is_earth_frame = mnt_target.rate_rads.yaw_is_ef; + return true; + } + return false; +} + +// get target angle in deg. returns true on success +bool AP_Mount_Backend::get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) +{ + if (mnt_target.target_type == MountTargetType::ANGLE) { + roll_deg = degrees(mnt_target.angle_rad.roll); + pitch_deg = degrees(mnt_target.angle_rad.pitch); + yaw_deg = degrees(mnt_target.angle_rad.yaw); + yaw_is_earth_frame = mnt_target.angle_rad.yaw_is_ef; + return true; + } + return false; +} + // sent warning to GCS. Warnings are throttled to at most once every 30 seconds void AP_Mount_Backend::send_warning_to_GCS(const char* warning_str) { diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 827c7db133f4cc..c663d0dadd7816 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -28,7 +28,7 @@ #include #include #include -#include "AP_Mount_Params.h" +#include "AP_Mount.h" class AP_Mount_Backend { @@ -133,12 +133,19 @@ class AP_Mount_Backend // handle GIMBAL_DEVICE_ATTITUDE_STATUS message virtual void handle_gimbal_device_attitude_status(const mavlink_message_t &msg) {} + // get target rate in deg/sec. returns true on success + bool get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame); + + // get target angle in deg. returns true on success + bool get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame); + // accessors for scripting backends - virtual bool get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) { return false; } - virtual bool get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) { return false; } virtual bool get_location_target(Location &target_loc) { return false; } virtual void set_attitude_euler(float roll_deg, float pitch_deg, float yaw_bf_deg) {}; + // write mount log packet + void write_log(uint64_t timestamp_us); + // // camera controls for gimbals that include a camera // @@ -175,8 +182,9 @@ class AP_Mount_Backend RATE, }; - // structure for a single angle or rate target - struct MountTarget { + // class for a single angle or rate target + class MountTarget { + public: float roll; float pitch; float yaw; @@ -187,6 +195,9 @@ class AP_Mount_Backend // return earth-frame yaw angle from a mount target (in radians) float get_ef_yaw() const; + + // set roll, pitch, yaw and yaw_is_ef from Vector3f + void set(const Vector3f& rpy, bool yaw_is_ef_in); }; // returns true if user has configured a valid yaw angle range @@ -199,13 +210,9 @@ class AP_Mount_Backend // 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; - // get rate targets (in rad/s) from pilot RC - // returns true on success (RC is providing rate targets), false on failure (RC is providing angle targets) - bool get_rc_rate_target(MountTarget& rate_rads) const WARN_IF_UNUSED; - - // get angle targets (in radians) from pilot RC - // returns true on success (RC is providing angle targets), false on failure (RC is providing rate targets) - bool get_rc_angle_target(MountTarget& angle_rad) const WARN_IF_UNUSED; + // get angle or rate targets from pilot RC + // target_type will be either ANGLE or RATE, rpy will be the target angle in deg or rate in deg/s + void get_rc_target(MountTargetType& target_type, MountTarget& rpy) const; // get angle targets (in radians) to a Location // returns true on success, false on failure @@ -246,7 +253,7 @@ class AP_Mount_Backend MountTargetType target_type;// MAVLink targeting mode's current target type (e.g. angle or rate) MountTarget angle_rad; // angle target in radians MountTarget rate_rads; // rate target in rad/s - } mavt_target; + } mnt_target; 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_Gremsy.cpp b/libraries/AP_Mount/AP_Mount_Gremsy.cpp index 43e2bbb3817559..5c96daa7f17cf4 100644 --- a/libraries/AP_Mount/AP_Mount_Gremsy.cpp +++ b/libraries/AP_Mount/AP_Mount_Gremsy.cpp @@ -26,70 +26,75 @@ void AP_Mount_Gremsy::update() // move mount to a "retracted" position. We disable motors case MAV_MOUNT_MODE_RETRACT: // handled below + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(Vector3f{0,0,0}, false); send_gimbal_device_retract(); break; // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &angle_bf_target = _params.neutral_angles.get(); - send_gimbal_device_set_attitude(ToRad(angle_bf_target.x), ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); - } + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); break; + } - // use angle or rate targets provided by a mavlink message or mission command - case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - send_gimbal_device_set_attitude(mavt_target.angle_rad.roll, mavt_target.angle_rad.pitch, mavt_target.angle_rad.yaw, mavt_target.angle_rad.yaw_is_ef); - break; - case MountTargetType::RATE: - send_gimbal_device_set_rate(mavt_target.rate_rads.roll, mavt_target.rate_rads.pitch, mavt_target.rate_rads.yaw, mavt_target.rate_rads.yaw_is_ef); - break; - } + case MAV_MOUNT_MODE_MAVLINK_TARGETING: { + // mavlink targets are stored while handling the incoming message set_angle_target() or set_rate_target() break; + } // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's rc inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - send_gimbal_device_set_rate(rc_target.roll, rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } else if (get_rc_angle_target(rc_target)) { - send_gimbal_device_set_attitude(rc_target.roll, rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); + // update targets using pilot's RC inputs + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + mnt_target.angle_rad = rc_target; + break; + case MountTargetType::RATE: + mnt_target.rate_rads = rc_target; + break; } break; } // point mount to a GPS point given by the mission planner - case MAV_MOUNT_MODE_GPS_POINT: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_roi(angle_target_rad)) { - send_gimbal_device_set_attitude(angle_target_rad.roll, angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + case MAV_MOUNT_MODE_GPS_POINT: + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - // point mount to home - case MAV_MOUNT_MODE_HOME_LOCATION: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_home(angle_target_rad)) { - send_gimbal_device_set_attitude(angle_target_rad.roll, angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // point mount to Home location + case MAV_MOUNT_MODE_HOME_LOCATION: + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_SYSID_TARGET: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_sysid(angle_target_rad)) { - send_gimbal_device_set_attitude(angle_target_rad.roll, angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // point mount to another vehicle + case MAV_MOUNT_MODE_SYSID_TARGET: + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } default: // unknown mode so do nothing break; } + + // send target angles or rates depending on the target type + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + send_gimbal_device_set_attitude(mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, mnt_target.angle_rad.yaw, mnt_target.angle_rad.yaw_is_ef); + break; + case MountTargetType::RATE: + send_gimbal_device_set_rate(mnt_target.rate_rads.roll, mnt_target.rate_rads.pitch, mnt_target.rate_rads.yaw, mnt_target.rate_rads.yaw_is_ef); + break; + } } // return true if healthy diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.cpp b/libraries/AP_Mount/AP_Mount_SToRM32.cpp index bdea46bf1491cb..1c1e5da3eadc1e 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32.cpp @@ -26,32 +26,24 @@ void AP_Mount_SToRM32::update() // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &target = _params.retract_angles.get(); - _angle_rad.roll = radians(target.x); - _angle_rad.pitch = radians(target.y); - _angle_rad.yaw = radians(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &target = _params.neutral_angles.get(); - _angle_rad.roll = radians(target.x); - _angle_rad.pitch = radians(target.y); - _angle_rad.yaw = radians(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - _angle_rad = mavt_target.angle_rad; - break; - case MountTargetType::RATE: - update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); - break; + // mnt_target should have already been populated by set_angle_target() or set_rate_target(). Update target angle from rate if necessary + if (mnt_target.target_type == MountTargetType::RATE) { + update_angle_target_from_rate(mnt_target.rate_rads, mnt_target.angle_rad); } resend_now = true; break; @@ -59,31 +51,40 @@ void AP_Mount_SToRM32::update() // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { // update targets using pilot's RC inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - update_angle_target_from_rate(rc_target, _angle_rad); - } else if (get_rc_angle_target(rc_target)) { - _angle_rad = rc_target; + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + mnt_target.angle_rad = rc_target; + break; + case MountTargetType::RATE: + mnt_target.rate_rads = rc_target; + break; } resend_now = true; break; } - // point mount to a GPS location + // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - if (get_angle_target_to_roi(_angle_rad)) { + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; + // point mount to Home location case MAV_MOUNT_MODE_HOME_LOCATION: - if (get_angle_target_to_home(_angle_rad)) { + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; + // point mount to another vehicle case MAV_MOUNT_MODE_SYSID_TARGET: - if (get_angle_target_to_sysid(_angle_rad)) { + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; @@ -95,14 +96,14 @@ void AP_Mount_SToRM32::update() // resend target angles at least once per second if (resend_now || ((AP_HAL::millis() - _last_send) > AP_MOUNT_STORM32_RESEND_MS)) { - send_do_mount_control(_angle_rad); + send_do_mount_control(mnt_target.angle_rad); } } // get attitude as a quaternion. returns true on success bool AP_Mount_SToRM32::get_attitude_quaternion(Quaternion& att_quat) { - att_quat.from_euler(_angle_rad.roll, _angle_rad.pitch, _angle_rad.get_bf_yaw()); + att_quat.from_euler(mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, mnt_target.angle_rad.get_bf_yaw()); return true; } diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.h b/libraries/AP_Mount/AP_Mount_SToRM32.h index d850869f9fd15d..33aef375c410f4 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32.h @@ -42,6 +42,5 @@ class AP_Mount_SToRM32 : public AP_Mount_Backend uint8_t _compid; // component id of gimbal mavlink_channel_t _chan = MAVLINK_COMM_0; // mavlink channel used to communicate with gimbal uint32_t _last_send; // system time of last do_mount_control sent to gimbal - MountTarget _angle_rad; // latest angle target }; #endif // HAL_MOUNT_STORM32MAVLINK_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 9f94ab0a7078ee..0fdcdd53c70fbf 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -37,32 +37,24 @@ void AP_Mount_SToRM32_serial::update() // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &target = _params.retract_angles.get(); - _angle_rad.roll = ToRad(target.x); - _angle_rad.pitch = ToRad(target.y); - _angle_rad.yaw = ToRad(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &target = _params.neutral_angles.get(); - _angle_rad.roll = ToRad(target.x); - _angle_rad.pitch = ToRad(target.y); - _angle_rad.yaw = ToRad(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - _angle_rad = mavt_target.angle_rad; - break; - case MountTargetType::RATE: - update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); - break; + // mnt_target should have already been filled in by set_angle_target() or set_rate_target() + if (mnt_target.target_type == MountTargetType::RATE) { + update_angle_target_from_rate(mnt_target.rate_rads, mnt_target.angle_rad); } resend_now = true; break; @@ -70,11 +62,15 @@ void AP_Mount_SToRM32_serial::update() // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { // update targets using pilot's RC inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - update_angle_target_from_rate(rc_target, _angle_rad); - } else if (get_rc_angle_target(rc_target)) { - _angle_rad = rc_target; + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + mnt_target.angle_rad = rc_target; + break; + case MountTargetType::RATE: + mnt_target.rate_rads = rc_target; + break; } resend_now = true; break; @@ -82,19 +78,24 @@ void AP_Mount_SToRM32_serial::update() // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - if (get_angle_target_to_roi(_angle_rad)) { + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; + // point mount to Home location case MAV_MOUNT_MODE_HOME_LOCATION: - if (get_angle_target_to_home(_angle_rad)) { + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; + // point mount to another vehicle case MAV_MOUNT_MODE_SYSID_TARGET: - if (get_angle_target_to_sysid(_angle_rad)) { + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; resend_now = true; } break; @@ -112,7 +113,7 @@ void AP_Mount_SToRM32_serial::update() } if (can_send(resend_now)) { if (resend_now) { - send_target_angles(_angle_rad); + send_target_angles(mnt_target.angle_rad); get_angles(); _reply_type = ReplyType_ACK; _reply_counter = 0; diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h index 5ae4fe773aa1f2..e6632ca10eb8bc 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h @@ -130,7 +130,6 @@ class AP_Mount_SToRM32_serial : public AP_Mount_Backend AP_HAL::UARTDriver *_port; bool _initialised; // true once the driver has been initialised - MountTarget _angle_rad; // latest angle target uint32_t _last_send; // system time of last do_mount_control sent to gimbal uint8_t _reply_length; diff --git a/libraries/AP_Mount/AP_Mount_Scripting.cpp b/libraries/AP_Mount/AP_Mount_Scripting.cpp index e1809c4a844cf6..9eb738503919bc 100644 --- a/libraries/AP_Mount/AP_Mount_Scripting.cpp +++ b/libraries/AP_Mount/AP_Mount_Scripting.cpp @@ -20,14 +20,8 @@ void AP_Mount_Scripting::update() // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &angle_bf_target = _params.retract_angles.get(); - target_angle_rad.roll = ToRad(angle_bf_target.x); - target_angle_rad.pitch = ToRad(angle_bf_target.y); - target_angle_rad.yaw = ToRad(angle_bf_target.z); - target_angle_rad.yaw_is_ef = false; - target_angle_rad_valid = true; - - // mark other targets as invalid - target_rate_rads_valid = false; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; target_loc_valid = false; break; } @@ -35,92 +29,55 @@ void AP_Mount_Scripting::update() // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &angle_bf_target = _params.neutral_angles.get(); - target_angle_rad.roll = ToRad(angle_bf_target.x); - target_angle_rad.pitch = ToRad(angle_bf_target.y); - target_angle_rad.yaw = ToRad(angle_bf_target.z); - target_angle_rad.yaw_is_ef = false; - target_angle_rad_valid = true; - - // mark other targets as invalid - target_rate_rads_valid = false; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); + mnt_target.target_type = MountTargetType::ANGLE; target_loc_valid = false; break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - target_angle_rad = mavt_target.angle_rad; - target_angle_rad_valid = true; - target_rate_rads_valid = false; - target_loc_valid = false; - break; - case MountTargetType::RATE: - target_rate_rads = mavt_target.rate_rads; - target_rate_rads_valid = true; - target_angle_rad_valid = false; - target_loc_valid = false; - break; - } + // mavlink targets should have been already stored while handling the message + target_loc_valid = false; break; // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's rc inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - target_rate_rads = rc_target; - target_rate_rads_valid = true; - target_angle_rad_valid = false; - target_loc_valid = false; - } else if (get_rc_angle_target(rc_target)) { - target_angle_rad = rc_target; - target_angle_rad_valid = true; - target_rate_rads_valid = false; - target_loc_valid = false; + // update targets using pilot's RC inputs + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + mnt_target.angle_rad = rc_target; + break; + case MountTargetType::RATE: + mnt_target.rate_rads = rc_target; + break; } + target_loc_valid = false; break; } - // point mount towards a GPS point - case MAV_MOUNT_MODE_GPS_POINT: { - target_loc_valid = _roi_target_set; - if (target_loc_valid) { - target_loc = _roi_target; - target_angle_rad_valid = get_angle_target_to_location(target_loc, target_angle_rad); - } else { - target_angle_rad_valid = false; + // point mount to a GPS point given by the mission planner + case MAV_MOUNT_MODE_GPS_POINT: + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } - target_rate_rads_valid = false; break; - } - // point mount towards home - case MAV_MOUNT_MODE_HOME_LOCATION: { - target_loc_valid = AP::ahrs().home_is_set(); - if (target_loc_valid) { - target_loc = AP::ahrs().get_home(); - target_angle_rad_valid = get_angle_target_to_home(target_angle_rad); - } else { - target_angle_rad_valid = false; + // point mount to Home location + case MAV_MOUNT_MODE_HOME_LOCATION: + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } - target_rate_rads_valid = false; break; - } - // point mount towards another vehicle - case MAV_MOUNT_MODE_SYSID_TARGET: { - target_loc_valid = _target_sysid_location_set; - if (target_loc_valid) { - target_loc = _target_sysid_location; - target_angle_rad_valid = get_angle_target_to_location(target_loc, target_angle_rad); - } else { - target_angle_rad_valid = false; + // point mount to another vehicle + case MAV_MOUNT_MODE_SYSID_TARGET: + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } - target_rate_rads_valid = false; break; - } default: // we do not know this mode so raise internal error @@ -136,31 +93,6 @@ bool AP_Mount_Scripting::healthy() const return (AP_HAL::millis() - last_update_ms <= AP_MOUNT_SCRIPTING_TIMEOUT_MS); } -// accessors for scripting backends -bool AP_Mount_Scripting::get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) -{ - if (target_rate_rads_valid) { - roll_degs = degrees(target_rate_rads.roll); - pitch_degs = degrees(target_rate_rads.pitch); - yaw_degs = degrees(target_rate_rads.yaw); - yaw_is_earth_frame = target_rate_rads.yaw_is_ef; - return true; - } - return false; -} - -bool AP_Mount_Scripting::get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) -{ - if (target_angle_rad_valid) { - roll_deg = degrees(target_angle_rad.roll); - pitch_deg = degrees(target_angle_rad.pitch); - yaw_deg = degrees(target_angle_rad.yaw); - yaw_is_earth_frame = target_angle_rad.yaw_is_ef; - return true; - } - return false; -} - // return target location if available // returns true if a target location is available and fills in target_loc argument bool AP_Mount_Scripting::get_location_target(Location &_target_loc) diff --git a/libraries/AP_Mount/AP_Mount_Scripting.h b/libraries/AP_Mount/AP_Mount_Scripting.h index d5f945fa120f29..356f9229b87e22 100644 --- a/libraries/AP_Mount/AP_Mount_Scripting.h +++ b/libraries/AP_Mount/AP_Mount_Scripting.h @@ -32,8 +32,6 @@ class AP_Mount_Scripting : public AP_Mount_Backend bool has_pan_control() const override { return yaw_range_valid(); }; // accessors for scripting backends - bool get_rate_target(float& roll_degs, float& pitch_degs, float& yaw_degs, bool& yaw_is_earth_frame) override; - bool get_angle_target(float& roll_deg, float& pitch_deg, float& yaw_deg, bool& yaw_is_earth_frame) override; bool get_location_target(Location& _target_loc) override; void set_attitude_euler(float roll_deg, float pitch_deg, float yaw_bf_deg) override; @@ -48,11 +46,8 @@ class AP_Mount_Scripting : public AP_Mount_Backend uint32_t last_update_ms; // system time of last call to one of the get_ methods. Used for health reporting Vector3f current_angle_deg; // current gimbal angles in degrees (x=roll, y=pitch, z=yaw) - MountTarget target_rate_rads; // rate target in rad/s - bool target_rate_rads_valid; // true if _target_rate_degs holds a valid rate target - - MountTarget target_angle_rad; // angle target in radians - bool target_angle_rad_valid; // true if _target_rate_degs holds a valid rate target + bool target_rate_rads_valid; // true if mnt_target holds a valid rate target + bool target_angle_rad_valid; // true if mnt_target holds a valid angle target Location target_loc; // target location bool target_loc_valid; // true if target_loc holds a valid target location diff --git a/libraries/AP_Mount/AP_Mount_Servo.cpp b/libraries/AP_Mount/AP_Mount_Servo.cpp index 840d19803e0c4e..6d1d45a7668a0f 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.cpp +++ b/libraries/AP_Mount/AP_Mount_Servo.cpp @@ -27,89 +27,87 @@ void AP_Mount_Servo::init() // update mount position - should be called periodically void AP_Mount_Servo::update() { - switch (get_mode()) { + auto mount_mode = get_mode(); + switch (mount_mode) { // move mount to a "retracted position" or to a position where a fourth servo can retract the entire mount into the fuselage case MAV_MOUNT_MODE_RETRACT: { _angle_bf_output_rad = _params.retract_angles.get() * DEG_TO_RAD; - - // initialise _angle_rad to smooth transition if user changes to RC_TARGETTING - _angle_rad.roll = _angle_bf_output_rad.x; - _angle_rad.pitch = _angle_bf_output_rad.y; - _angle_rad.yaw = _angle_bf_output_rad.z; - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(_angle_bf_output_rad, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { _angle_bf_output_rad = _params.neutral_angles.get() * DEG_TO_RAD; - - // initialise _angle_rad to smooth transition if user changes to RC_TARGETTING - _angle_rad.roll = _angle_bf_output_rad.x; - _angle_rad.pitch = _angle_bf_output_rad.y; - _angle_rad.yaw = _angle_bf_output_rad.z; - _angle_rad.yaw_is_ef = false; + mnt_target.angle_rad.set(_angle_bf_output_rad, false); + mnt_target.target_type = MountTargetType::ANGLE; break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: { - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - _angle_rad = mavt_target.angle_rad; - break; - case MountTargetType::RATE: - update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); - break; - } - // update _angle_bf_output_rad based on angle target - update_angle_outputs(_angle_rad); + // mavlink targets are stored while handling the incoming message and considered valid break; } // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { // update targets using pilot's RC inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - update_angle_target_from_rate(rc_target, _angle_rad); - } else if (get_rc_angle_target(rc_target)) { - _angle_rad = rc_target; + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + mnt_target.angle_rad = rc_target; + break; + case MountTargetType::RATE: + mnt_target.rate_rads = rc_target; + break; } - // update _angle_bf_output_rad based on angle target - update_angle_outputs(_angle_rad); break; } - // point mount to a GPS location - case MAV_MOUNT_MODE_GPS_POINT: { - if (get_angle_target_to_roi(_angle_rad)) { - update_angle_outputs(_angle_rad); + // point mount to a GPS point given by the mission planner + case MAV_MOUNT_MODE_GPS_POINT: + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_HOME_LOCATION: { - if (get_angle_target_to_home(_angle_rad)) { - update_angle_outputs(_angle_rad); + // point mount to Home location + case MAV_MOUNT_MODE_HOME_LOCATION: + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_SYSID_TARGET: { - if (get_angle_target_to_sysid(_angle_rad)) { - update_angle_outputs(_angle_rad); + // point mount to another vehicle + case MAV_MOUNT_MODE_SYSID_TARGET: + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } default: //do nothing break; } + // send target angles or rates depending on the target type + switch (mnt_target.target_type) { + case MountTargetType::RATE: + update_angle_target_from_rate(mnt_target.rate_rads, mnt_target.angle_rad); + FALLTHROUGH; + case MountTargetType::ANGLE: + // update _angle_bf_output_rad based on angle target + if ((mount_mode != MAV_MOUNT_MODE_RETRACT) & (mount_mode != MAV_MOUNT_MODE_NEUTRAL)) { + update_angle_outputs(mnt_target.angle_rad); + } + break; + } + // move mount to a "retracted position" into the fuselage with a fourth servo - const bool mount_open = (get_mode() == MAV_MOUNT_MODE_RETRACT) ? 0 : 1; + const bool mount_open = (mount_mode == MAV_MOUNT_MODE_RETRACT) ? 0 : 1; move_servo(_open_idx, mount_open, 0, 1); // write the results to the servos diff --git a/libraries/AP_Mount/AP_Mount_Servo.h b/libraries/AP_Mount/AP_Mount_Servo.h index 9016fd2af6d962..529a97bd7341c1 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.h +++ b/libraries/AP_Mount/AP_Mount_Servo.h @@ -56,7 +56,6 @@ class AP_Mount_Servo : public AP_Mount_Backend SRV_Channel::Aux_servo_function_t _pan_idx; // SRV_Channel mount pan function index SRV_Channel::Aux_servo_function_t _open_idx; // SRV_Channel mount open function index - MountTarget _angle_rad; // angle target Vector3f _angle_bf_output_rad; // final body frame output angle in radians }; #endif // HAL_MOUNT_SERVO_ENABLED diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index ee60bbf00cd76f..f1dc4a1bfa6c8d 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -68,76 +68,78 @@ void AP_Mount_Siyi::update() // run zoom control update_zoom_control(); - // update based on mount mode + // Get the target angles or rates first depending on the current mount mode switch (get_mode()) { - // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &angle_bf_target = _params.retract_angles.get(); - send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); break; } - // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &angle_bf_target = _params.neutral_angles.get(); - send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); break; } - // point to the angles given by a mavlink message - case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { + case MAV_MOUNT_MODE_MAVLINK_TARGETING: { + // mavlink targets are stored while handling the incoming message + break; + } + + case MAV_MOUNT_MODE_RC_TARGETING: { + // update targets using pilot's RC inputs + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { case MountTargetType::ANGLE: - send_target_angles(mavt_target.angle_rad.pitch, mavt_target.angle_rad.yaw, mavt_target.angle_rad.yaw_is_ef); + mnt_target.angle_rad = rc_target; break; case MountTargetType::RATE: - send_target_rates(mavt_target.rate_rads.pitch, mavt_target.rate_rads.yaw, mavt_target.rate_rads.yaw_is_ef); + mnt_target.rate_rads = rc_target; break; } break; - - // RC radio manual angle control, but with stabilization from the AHRS - case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's rc inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - send_target_rates(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } else if (get_rc_angle_target(rc_target)) { - send_target_angles(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } - break; } // point mount to a GPS point given by the mission planner - case MAV_MOUNT_MODE_GPS_POINT: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_roi(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + case MAV_MOUNT_MODE_GPS_POINT: + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_HOME_LOCATION: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_home(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // point mount to Home location + case MAV_MOUNT_MODE_HOME_LOCATION: + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_SYSID_TARGET:{ - MountTarget angle_target_rad {}; - if (get_angle_target_to_sysid(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // point mount to another vehicle + case MAV_MOUNT_MODE_SYSID_TARGET: + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } default: // we do not know this mode so raise internal error INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); break; } + + // send target angles or rates depending on the target type + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + send_target_angles(mnt_target.angle_rad.pitch, mnt_target.angle_rad.yaw, mnt_target.angle_rad.yaw_is_ef); + break; + case MountTargetType::RATE: + send_target_rates(mnt_target.rate_rads.pitch, mnt_target.rate_rads.yaw, mnt_target.rate_rads.yaw_is_ef); + break; + } } // return true if healthy diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index 2643eb36947a25..907b09a0d4574c 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -36,61 +36,66 @@ void AP_Mount_SoloGimbal::update() // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism case MAV_MOUNT_MODE_RETRACT: _gimbal.set_lockedToBody(true); - // initialise _angle_rad to smooth transition if user changes to RC_TARGETTINg - _angle_rad = {0, 0, 0, false}; + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(Vector3f{0,0,0}, false); break; // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { _gimbal.set_lockedToBody(false); const Vector3f &target = _params.neutral_angles.get(); - _angle_rad.roll = radians(target.x); - _angle_rad.pitch = radians(target.y); - _angle_rad.yaw = radians(target.z); - _angle_rad.yaw_is_ef = false; + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(target*DEG_TO_RAD, false); break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: + // targets are stored while handling the incoming mavlink message _gimbal.set_lockedToBody(false); - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - _angle_rad = mavt_target.angle_rad; - break; - case MountTargetType::RATE: - update_angle_target_from_rate(mavt_target.rate_rads, _angle_rad); - break; + if (mnt_target.target_type == MountTargetType::RATE) { + update_angle_target_from_rate(mnt_target.rate_rads, mnt_target.angle_rad); } break; // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { _gimbal.set_lockedToBody(false); - // update targets using pilot's RC inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - update_angle_target_from_rate(rc_target, _angle_rad); - } else if (get_rc_angle_target(rc_target)) { - _angle_rad = rc_target; + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + mnt_target.angle_rad = rc_target; + break; + case MountTargetType::RATE: + mnt_target.rate_rads = rc_target; + break; } break; } // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - _gimbal.set_lockedToBody(false); - IGNORE_RETURN(get_angle_target_to_roi(_angle_rad)); + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + _gimbal.set_lockedToBody(false); + } break; + // point mount to Home location case MAV_MOUNT_MODE_HOME_LOCATION: - _gimbal.set_lockedToBody(false); - IGNORE_RETURN(get_angle_target_to_home(_angle_rad)); + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + _gimbal.set_lockedToBody(false); + } break; + // point mount to another vehicle case MAV_MOUNT_MODE_SYSID_TARGET: - _gimbal.set_lockedToBody(false); - IGNORE_RETURN(get_angle_target_to_sysid(_angle_rad)); + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; + _gimbal.set_lockedToBody(false); + } break; default: @@ -105,7 +110,7 @@ bool AP_Mount_SoloGimbal::get_attitude_quaternion(Quaternion& att_quat) if (!_gimbal.aligned()) { return false; } - att_quat.from_euler(_angle_rad.roll, _angle_rad.pitch, _angle_rad.get_bf_yaw()); + att_quat.from_euler(mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, mnt_target.angle_rad.get_bf_yaw()); return true; } @@ -114,7 +119,7 @@ bool AP_Mount_SoloGimbal::get_attitude_quaternion(Quaternion& att_quat) */ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mavlink_message_t &msg) { - _gimbal.update_target(Vector3f{_angle_rad.roll, _angle_rad.pitch, _angle_rad.get_bf_yaw()}); + _gimbal.update_target(Vector3f{mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, mnt_target.angle_rad.get_bf_yaw()}); _gimbal.receive_feedback(chan,msg); AP_Logger *logger = AP_Logger::get_singleton(); diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.h b/libraries/AP_Mount/AP_Mount_SoloGimbal.h index 87503e5f39d8d2..4e64233284a9fd 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.h +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.h @@ -54,7 +54,6 @@ class AP_Mount_SoloGimbal : public AP_Mount_Backend void Log_Write_Gimbal(SoloGimbal &gimbal); bool _params_saved; - MountTarget _angle_rad; // angle target SoloGimbal _gimbal; }; diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.cpp b/libraries/AP_Mount/AP_Mount_Viewpro.cpp index 5b199d7af3e93c..42749f74605c35 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.cpp +++ b/libraries/AP_Mount/AP_Mount_Viewpro.cpp @@ -76,71 +76,76 @@ void AP_Mount_Viewpro::update() // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &angle_bf_target = _params.retract_angles.get(); - send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); break; } // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &angle_bf_target = _params.neutral_angles.get(); - send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); break; } // point to the angles given by a mavlink message case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { - case MountTargetType::ANGLE: - send_target_angles(mavt_target.angle_rad.pitch, mavt_target.angle_rad.yaw, mavt_target.angle_rad.yaw_is_ef); - break; - case MountTargetType::RATE: - send_target_rates(mavt_target.rate_rads.pitch, mavt_target.rate_rads.yaw, mavt_target.rate_rads.yaw_is_ef); - break; - } + // mavlink targets are stored while handling the incoming message break; // RC radio manual angle control, but with stabilization from the AHRS case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's rc inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - send_target_rates(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } else if (get_rc_angle_target(rc_target)) { - send_target_angles(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); + // update targets using pilot's RC inputs + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + mnt_target.angle_rad = rc_target; + break; + case MountTargetType::RATE: + mnt_target.rate_rads = rc_target; + break; } break; } // point mount to a GPS point given by the mission planner - case MAV_MOUNT_MODE_GPS_POINT: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_roi(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + case MAV_MOUNT_MODE_GPS_POINT: + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_HOME_LOCATION: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_home(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // point mount to Home location + case MAV_MOUNT_MODE_HOME_LOCATION: + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_SYSID_TARGET:{ - MountTarget angle_target_rad {}; - if (get_angle_target_to_sysid(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // point mount to another vehicle + case MAV_MOUNT_MODE_SYSID_TARGET: + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } default: // we do not know this mode so raise internal error INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); break; } + + // send target angles or rates depending on the target type + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + send_target_angles(mnt_target.angle_rad.pitch, mnt_target.angle_rad.yaw, mnt_target.angle_rad.yaw_is_ef); + break; + case MountTargetType::RATE: + send_target_rates(mnt_target.rate_rads.pitch, mnt_target.rate_rads.yaw, mnt_target.rate_rads.yaw_is_ef); + break; + } } // return true if healthy diff --git a/libraries/AP_Mount/AP_Mount_Xacti.cpp b/libraries/AP_Mount/AP_Mount_Xacti.cpp index cb08a54fb4cff2..62ec3396a3e4a9 100644 --- a/libraries/AP_Mount/AP_Mount_Xacti.cpp +++ b/libraries/AP_Mount/AP_Mount_Xacti.cpp @@ -54,71 +54,74 @@ void AP_Mount_Xacti::update() // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? case MAV_MOUNT_MODE_RETRACT: { const Vector3f &angle_bf_target = _params.retract_angles.get(); - send_target_angles(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); break; } - // move mount to a neutral position, typically pointing forward case MAV_MOUNT_MODE_NEUTRAL: { const Vector3f &angle_bf_target = _params.neutral_angles.get(); - send_target_rates(ToRad(angle_bf_target.y), ToRad(angle_bf_target.z), false); + mnt_target.target_type = MountTargetType::ANGLE; + mnt_target.angle_rad.set(angle_bf_target*DEG_TO_RAD, false); break; } - // point to the angles given by a mavlink message - case MAV_MOUNT_MODE_MAVLINK_TARGETING: - switch (mavt_target.target_type) { + case MAV_MOUNT_MODE_MAVLINK_TARGETING: { + // mavlink targets are set while handling the incoming message + break; + } + + case MAV_MOUNT_MODE_RC_TARGETING: { + // update targets using pilot's RC inputs + MountTarget rc_target; + get_rc_target(mnt_target.target_type, rc_target); + switch (mnt_target.target_type) { case MountTargetType::ANGLE: - send_target_angles(mavt_target.angle_rad.pitch, mavt_target.angle_rad.yaw, mavt_target.angle_rad.yaw_is_ef); + mnt_target.angle_rad = rc_target; break; case MountTargetType::RATE: - send_target_rates(mavt_target.rate_rads.pitch, mavt_target.rate_rads.yaw, mavt_target.rate_rads.yaw_is_ef); + mnt_target.rate_rads = rc_target; break; } break; - - // RC radio manual angle control, but with stabilization from the AHRS - case MAV_MOUNT_MODE_RC_TARGETING: { - // update targets using pilot's rc inputs - MountTarget rc_target {}; - if (get_rc_rate_target(rc_target)) { - send_target_rates(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } else if (get_rc_angle_target(rc_target)) { - send_target_angles(rc_target.pitch, rc_target.yaw, rc_target.yaw_is_ef); - } - break; } // point mount to a GPS point given by the mission planner - case MAV_MOUNT_MODE_GPS_POINT: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_roi(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + case MAV_MOUNT_MODE_GPS_POINT: + if (get_angle_target_to_roi(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_HOME_LOCATION: { - MountTarget angle_target_rad {}; - if (get_angle_target_to_home(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // point mount to Home location + case MAV_MOUNT_MODE_HOME_LOCATION: + if (get_angle_target_to_home(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } - case MAV_MOUNT_MODE_SYSID_TARGET:{ - MountTarget angle_target_rad {}; - if (get_angle_target_to_sysid(angle_target_rad)) { - send_target_angles(angle_target_rad.pitch, angle_target_rad.yaw, angle_target_rad.yaw_is_ef); + // point mount to another vehicle + case MAV_MOUNT_MODE_SYSID_TARGET: + if (get_angle_target_to_sysid(mnt_target.angle_rad)) { + mnt_target.target_type = MountTargetType::ANGLE; } break; - } default: // we do not know this mode so raise internal error INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control); break; } + + // send target angles or rates depending on the target type + switch (mnt_target.target_type) { + case MountTargetType::ANGLE: + send_target_angles(mnt_target.angle_rad.pitch, mnt_target.angle_rad.yaw, mnt_target.angle_rad.yaw_is_ef); + break; + case MountTargetType::RATE: + send_target_rates(mnt_target.rate_rads.pitch, mnt_target.rate_rads.yaw, mnt_target.rate_rads.yaw_is_ef); + break; + } } // return true if healthy diff --git a/libraries/AP_Mount/LogStructure.h b/libraries/AP_Mount/LogStructure.h new file mode 100644 index 00000000000000..ab66620cf7bc1f --- /dev/null +++ b/libraries/AP_Mount/LogStructure.h @@ -0,0 +1,38 @@ +#pragma once + +#include + +#define LOG_IDS_FROM_MOUNT \ + LOG_MOUNT_MSG + +// @LoggerMessage: MNT +// @Description: Mount's actual and Target/Desired RPY information +// @Field: TimeUS: Time since system startup +// @Field: I: Instance number +// @Field: DesRoll: mount's desired roll +// @Field: Roll: mount's actual roll +// @Field: DesPitch: mount's desired pitch +// @Field: Pitch: mount's actual pitch +// @Field: DesYawB: mount's desired yaw in body frame +// @Field: YawB: mount's actual yaw in body frame +// @Field: DesYawE: mount's desired yaw in earth frame +// @Field: YawE: mount's actual yaw in earth frame + +struct PACKED log_Mount { + LOG_PACKET_HEADER; + uint64_t time_us; + uint8_t instance; + float desired_roll; + float actual_roll; + float desired_pitch; + float actual_pitch; + float desired_yaw_bf; + float actual_yaw_bf; + float desired_yaw_ef; + float actual_yaw_ef; +}; + +#define LOG_STRUCTURE_FROM_MOUNT \ + { LOG_MOUNT_MSG, sizeof(log_Mount), \ + "MNT", "QBffffffff","TimeUS,I,DesRoll,Roll,DesPitch,Pitch,DesYawB,YawB,DesYawE,YawE", "s#dddddddd", "F---------" }, + From 9d2e9b37c8ac247cd0586f4445330fba7624286a Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 18 Jul 2023 20:27:13 +0900 Subject: [PATCH 0017/1367] Copter: log MNT at 10hz --- ArduCopter/Copter.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index f7a0f448712d79..605532d44439a3 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -583,6 +583,11 @@ void Copter::ten_hz_logging_loop() g2.winch.write_log(); } #endif +#if HAL_MOUNT_ENABLED + if (should_log(MASK_LOG_CAMERA)) { + camera_mount.write_log(); + } +#endif } // twentyfive_hz_logging - should be run at 25hz From 84752fbeaa72ebafc8bb10ef07e1c056cf1ae367 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 18 Jul 2023 20:27:20 +0900 Subject: [PATCH 0018/1367] Plane: log MNT at 10hz --- ArduPlane/ArduPlane.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 47f379a2e1f657..61d76425333278 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -245,7 +245,12 @@ void Plane::update_logging10(void) ahrs.Write_AOA_SSA(); } else if (log_faster) { ahrs.Write_AOA_SSA(); - } + } +#if HAL_MOUNT_ENABLED + if (should_log(MASK_LOG_CAMERA)) { + camera_mount.write_log(); + } +#endif } /* From c4e6d83be1abc8c6a285892d9a3152aec612b93e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 18 Jul 2023 20:27:34 +0900 Subject: [PATCH 0019/1367] Rover: log MNT at 10hz --- Rover/Rover.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index 2a429dd5556f37..837e95cc5ac310 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -421,6 +421,11 @@ void Rover::update_logging2(void) gyro_fft.write_log_messages(); #endif } +#if HAL_MOUNT_ENABLED + if (should_log(MASK_LOG_CAMERA)) { + camera_mount.write_log(); + } +#endif } From 816f9494b43ddb9c390f109514bcfc3661595064 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 18 Jul 2023 20:27:26 +0900 Subject: [PATCH 0020/1367] Sub: log MNT at 10hz --- ArduSub/ArduSub.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 9869ed29b80ad3..b8ded91fddc343 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -210,6 +210,11 @@ void Sub::ten_hz_logging_loop() if (should_log(MASK_LOG_CTUN)) { attitude_control.control_monitor_log(); } +#if HAL_MOUNT_ENABLED + if (should_log(MASK_LOG_CAMERA)) { + camera_mount.write_log(); + } +#endif } // twentyfive_hz_logging_loop From 2812b1e8bf2991e0a652c7408d14a208725f589d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 20 Jul 2023 10:08:32 +0900 Subject: [PATCH 0021/1367] AP_Mount: viewpro fix for pitch angle reporting --- libraries/AP_Mount/AP_Mount_Viewpro.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.cpp b/libraries/AP_Mount/AP_Mount_Viewpro.cpp index 42749f74605c35..36965cb6911f3d 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.cpp +++ b/libraries/AP_Mount/AP_Mount_Viewpro.cpp @@ -315,7 +315,7 @@ void AP_Mount_Viewpro::process_packet() _last_current_angle_rad_ms = AP_HAL::millis(); _current_angle_rad.x = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+23] & 0x0F, _msg_buff[_msg_buff_data_start+24]) * (180.0/4095.0) - 90.0); // roll angle _current_angle_rad.z = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+25], _msg_buff[_msg_buff_data_start+26]) * AP_MOUNT_VIEWPRO_OUTPUT_TO_DEG); // yaw angle - _current_angle_rad.y = radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+27], _msg_buff[_msg_buff_data_start+28]) * AP_MOUNT_VIEWPRO_OUTPUT_TO_DEG); // pitch angle + _current_angle_rad.y = -radians((int16_t)UINT16_VALUE(_msg_buff[_msg_buff_data_start+27], _msg_buff[_msg_buff_data_start+28]) * AP_MOUNT_VIEWPRO_OUTPUT_TO_DEG); // pitch angle debug("r:%4.1f p:%4.1f y:%4.1f", (double)degrees(_current_angle_rad.x), (double)degrees(_current_angle_rad.y), (double)degrees(_current_angle_rad.z)); break; } From a81f1cb9931831cbe27344cb973cbff0f38a5c1e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 20 Jul 2023 10:26:49 +0900 Subject: [PATCH 0022/1367] AP_Scripting: viewpro driver fix for pitch angle reporting --- libraries/AP_Scripting/drivers/mount-viewpro-driver.lua | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua b/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua index dcbf158561fbc3..9786e6327bba34 100644 --- a/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-viewpro-driver.lua @@ -379,7 +379,7 @@ function parse_byte(b) local servo_status = (parse_data_buff[24] & 0xF0 >> 4) local roll_deg = int16_value(parse_data_buff[24] & 0x0F, parse_data_buff[25]) * (180.0/4095.0) - 90.0 local yaw_deg = int16_value(parse_data_buff[26], parse_data_buff[27]) * (360.0 / 65536.0) - local pitch_deg = int16_value(parse_data_buff[28], parse_data_buff[29]) * (360.0 / 65536.0) + local pitch_deg = -int16_value(parse_data_buff[28], parse_data_buff[29]) * (360.0 / 65536.0) mount:set_attitude_euler(MOUNT_INSTANCE, roll_deg, pitch_deg, yaw_deg) if VIEP_DEBUG:get() > 0 then From 11a505f16f8bccfcb74b404a747efa4c2ff3d142 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 20 Jul 2023 20:18:54 +0900 Subject: [PATCH 0023/1367] AP_Mount: Gremsy fix for attitude reporting --- libraries/AP_Mount/AP_Mount_Gremsy.cpp | 6 ------ libraries/AP_Mount/AP_Mount_Gremsy.h | 1 - 2 files changed, 7 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Gremsy.cpp b/libraries/AP_Mount/AP_Mount_Gremsy.cpp index 5c96daa7f17cf4..b9bf372a680646 100644 --- a/libraries/AP_Mount/AP_Mount_Gremsy.cpp +++ b/libraries/AP_Mount/AP_Mount_Gremsy.cpp @@ -128,12 +128,6 @@ bool AP_Mount_Gremsy::healthy() const // get attitude as a quaternion. returns true on success bool AP_Mount_Gremsy::get_attitude_quaternion(Quaternion& att_quat) { - // check we have received an updated message - if (_gimbal_device_attitude_status.time_boot_ms == _sent_gimbal_device_attitude_status_ms) { - return false; - } - _sent_gimbal_device_attitude_status_ms = _gimbal_device_attitude_status.time_boot_ms; - att_quat = _gimbal_device_attitude_status.q; return true; } diff --git a/libraries/AP_Mount/AP_Mount_Gremsy.h b/libraries/AP_Mount/AP_Mount_Gremsy.h index 84670366e55e96..79bd42af77670a 100644 --- a/libraries/AP_Mount/AP_Mount_Gremsy.h +++ b/libraries/AP_Mount/AP_Mount_Gremsy.h @@ -70,6 +70,5 @@ class AP_Mount_Gremsy : public AP_Mount_Backend uint8_t _compid; // component id of gimbal mavlink_gimbal_device_attitude_status_t _gimbal_device_attitude_status; // copy of most recently received gimbal status uint32_t _last_attitude_status_ms; // system time last attitude status was received (used for health reporting) - uint32_t _sent_gimbal_device_attitude_status_ms; // time_boot_ms field of gimbal_device_status message last forwarded to the GCS (used to prevent sending duplicates) }; #endif // HAL_MOUNT_GREMSY_ENABLED From 380c20154f1aa45ed2ae23e9dffa279cd952ea62 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 21 Jul 2023 10:25:37 +0900 Subject: [PATCH 0024/1367] AP_Scripting: mount-djirs2 driver angle reporting fix --- libraries/AP_Scripting/drivers/mount-djirs2-driver.lua | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua index 7f94df7b4e5817..ac050cabc66339 100644 --- a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua @@ -462,7 +462,7 @@ function send_target_angles(roll_angle_deg, pitch_angle_deg, yaw_angle_deg, time end -- ensure angles are integers - roll_angle_deg = -math.floor(roll_angle_deg + 0.5) + roll_angle_deg = math.floor(roll_angle_deg + 0.5) pitch_angle_deg = math.floor(pitch_angle_deg + 0.5) yaw_angle_deg = math.floor(yaw_angle_deg + 0.5) time_sec = math.floor(time_sec + 0.5) @@ -657,8 +657,8 @@ function parse_byte(b) local ret_code = parse_buff[13] if ret_code == RETURN_CODE.SUCCESS then local yaw_deg = int16_value(parse_buff[16],parse_buff[15]) * 0.1 - local roll_deg = -int16_value(parse_buff[18],parse_buff[17]) * 0.1 - local pitch_deg = int16_value(parse_buff[20],parse_buff[19]) * 0.1 + local pitch_deg = int16_value(parse_buff[18],parse_buff[17]) * 0.1 + local roll_deg = int16_value(parse_buff[20],parse_buff[19]) * 0.1 mount:set_attitude_euler(MOUNT_INSTANCE, roll_deg, pitch_deg, yaw_deg) if DJIR_DEBUG:get() > 1 then gcs:send_text(MAV_SEVERITY.INFO, string.format("DJIR: roll:%4.1f pitch:%4.1f yaw:%4.1f", roll_deg, pitch_deg, yaw_deg)) From 7de2dac9ca32e2dbf537d135579d890d0009a4f8 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 21 Jul 2023 10:26:09 +0900 Subject: [PATCH 0025/1367] AP_Camera: TYPE param desc gets None value --- libraries/AP_Camera/AP_Camera_Params.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Camera/AP_Camera_Params.cpp b/libraries/AP_Camera/AP_Camera_Params.cpp index 8f64550bfd27ee..ca7e34ae3e2288 100644 --- a/libraries/AP_Camera/AP_Camera_Params.cpp +++ b/libraries/AP_Camera/AP_Camera_Params.cpp @@ -8,7 +8,7 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = { // @Param: _TYPE // @DisplayName: Camera shutter (trigger) type // @Description: how to trigger the camera to take a picture - // @Values: 1:Servo,2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi), 5:MAVLink, 6:MAVLinkCamV2, 7:Scripting + // @Values: 0:None, 1:Servo, 2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi), 5:MAVLink, 6:MAVLinkCamV2, 7:Scripting // @User: Standard AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Camera_Params, type, 0, AP_PARAM_FLAG_ENABLE), From e194cb704c30c3ae8bad9ae4c554fa9bff15482f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 24 Jul 2023 18:02:39 +0100 Subject: [PATCH 0026/1367] Plane: fix throttle going bellow min in fbwa RC failsafe --- ArduPlane/servos.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 30a49fccc41715..0c01c153930224 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -546,7 +546,7 @@ void Plane::set_servos_controlled(void) control_mode == &mode_autotune) { // a manual throttle mode if (!rc().has_valid_input()) { - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); + 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) { // manual pass through of throttle while in FBWA or // STABILIZE mode with THR_PASS_STAB set From 9d0f7f25863a4fde663759d261c2a552726f0b80 Mon Sep 17 00:00:00 2001 From: robin luo <151809425@qq.com> Date: Mon, 17 Jul 2023 15:33:41 +0800 Subject: [PATCH 0027/1367] AP_HAL_ChibiOS/hwdef: add controller CM4Pilot hwdef: add a new flight controller CM4Pilot --- .../hwdef/ACNS-CM4Pilot/CM4Pilot_Pinout.jpg | Bin 0 -> 135341 bytes .../ACNS-CM4Pilot/CM4Pilot_structure.jpg | Bin 0 -> 60133 bytes .../hwdef/ACNS-CM4Pilot/CM4pilot_inshell.jpg | Bin 0 -> 87450 bytes .../hwdef/ACNS-CM4Pilot/CM4pilot_size.jpg | Bin 0 -> 64652 bytes .../hwdef/ACNS-CM4Pilot/README.md | 97 +++++++++ .../hwdef/ACNS-CM4Pilot/hwdef-bl.dat | 42 ++++ .../hwdef/ACNS-CM4Pilot/hwdef.dat | 199 ++++++++++++++++++ 7 files changed, 338 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_Pinout.jpg create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_structure.jpg create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4pilot_inshell.jpg create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4pilot_size.jpg create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/README.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_Pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_Pinout.jpg new file mode 100644 index 0000000000000000000000000000000000000000..c3e32454cb0e8b7bb925027004d222e689058427 GIT binary patch literal 135341 zcmb5V1yq|$xA;vYcJ=C23W{sjscukHQBqQ|F)-5J;9|eY&Be~id5c$6;MN^s z9!}1?vVy|*#igXAZVJc)Yij|t0RpK`1ZHfQi>GwA>`fC@p zE*FzuxI=c4{sKAuh2LFd9Ap>BE|QyE{{Kesmng{3PlvuF^_5!cktQ8l;*lm33mu5#LTt2&W7v7^{l{8#DStFe@);y> zm$?6@fs35I*1V8uBl2Nl`;9pu*(bATN{W@Nt@O1a=`V!&s&39!`V7w%*6i!n>6e@m z9^5flj1J79`h43B^-<()R{6t+){2mmop58e_Y!Q1|7o3!j0pxFBXx#-PmD(dItAVo z!JUp;Z;0^ZfDYCk)+ETa!dJedG(gg(-+2|o z>BmiWh}T4mQ3`|Si^JJZ2Bz78&$>opU6l2Pxs!KdQ#1}6U4TSIGksL zbcjY!&{gWlLi#;cgWI%9HT=}Q{de`(+Dx88(9IUZlWZoAZ{sa&=r+FA@qBCjAbQ$Z zMkpyIv_}lH82IJH`mT->VA+EKjDrDAw2$XhE2e)cXQ1V$Kaly={ea8d>TOQGqK)}1)yjj!1cm014}C!e z3sp8AShW47~5dZ}nP_+?Nl#=m!-bh2~iI~kJDI8=gcMGeIqQv4>nH5go?L^#FGYQC}&bBt1RCW#OIUt@{ zO&s9x@-I3GheXx`1=UJqDt9&ai+~D9EceHCWGO1G4-&ZYi%XZZtBMU+wbHQ?W0`qA zOyK+xLYSG}^upc`(1c6`C_?5`KSJij3Q*YsrSN?yD89V8_|T(MG!yxefMNZ-H2cEI zz6{y8&*&BMHCOiF_#eOvOTj+|0A8PFjjF?k**$QZ!Fj_5SLo)w9LKAAbzQlAikvRu*`{8^Fch!)LQy$IZbRgu{P`u0|iV zlS2-;ewz5LCb(<}ozAxbbxdt6jDk-HVF2raD!!;j^8?(h2Is25bnT!a-fhS!J&;Mm zrQgNvGX$~VTh=#eer!`)HFn4G+tYYiZA6cYsB6m&jqmn%)?RqmZNBgzx}%g4LqBr2 z!MoBK$#-Tw=j47kDo!4?II7npMI2h|U_!*R!}Oqr>wjaBuPYmpj4XXjcVvriS$H1j zrF29e{3d%z0%?wew0`7ZfnHUB!Dx@oj7O`Wi^FX`Nb`Mk@#!w-z;3Rg%>vNS0T~a! z)81LNE=mxQ$D_Q6N$bT{K8hRd`FC{PAS_<>_E2hvMoDMVE(*7~JYbaly#_0P%q3im z%r70^5#@XDSb|pkO-B8*-9j8Kci65vd5Em%cKz}&B~w!VQ(>1G^l7^}}^BJa(nsp?XTPYi_9cF?`hwv1exW3e}ZK&qfq2p( zi9@t~d;T|y_(4ZmP)Q?TU`95?GIaAd8Alp+XZOr8#}^xGk66a!_@I=2E*b*^x}4!? zs??osM#+i_JRJzbUef^29C3lTUil?G+`@Y>6xRUo=`x)2;q&Y{*qlHdc?_0*w(o)H zMCCphQ0S3-4+`;527*Yk>9Z|(Qe|@eEE+bE#Q;4%&6qu1#su#-_4s{i>0jV+2)QPB@{i;ceY3IC@k4s??n9S}Dhp39>ydtw zm7e}4Ll2Ax{3g4)dsp(qUr0g$jEQ06K#Gpr$4FFwO(;vYFZM~xlA*xE1(Tjh-{o+h zOhtuN-L;-fdg7vXrmfthG4m}y+h8igVz6xMlJl6pC%?@{g zm&N^Z5U&=yIqd{f(fKrp$#}ob?7tm&@8qucER2xj^Z6c>0KxYiYu9>J+r91JPN54M z7iLU!*LkpF`Y|ecfalhqeDbGW_&jbr3Rf?asA%yk#Cx%wJ7l8-R(8r#b)W>hu(>{) z{tV>`j>S)*6~Ll0{pK#ZCE1lTP;p2-8Ic1ry4gT50g5izUj2m3)XxW7s`e^yoOo{t7RPp zL5*9MRVJ+enoJ{2!YN7vCMA#`v+?UTvhNt+C};LH%jVr||CZy;YB3$rIgd)H#OW65 zDP~|t>{Fa-WG-d4X6B^k(rj9t@Kgb0x`DqQQ=%ZbpllMTa=X1YuJvnI?NP+=K*!@{ zV4lc{Ku#2P2M_bTu>Inw2PH60BnIq&P))Y4K{UQ~mQWN1?Gn2;DIRa%{oWo{B|WP@ zWOk6M*5hs?{Hf^8ZOw@L|Al(luQ#ON;QMK?RXNG1a2Y+WQMuDu5~K&=&O}my7B|Qn zvbLM-vg^e_zykT60dDUFM1YKU z2rA!#u^`So4`OiJK1vWbYpq$f=KL|B1*aq8FghllOWe#uKkT^3D)mt5=F>0}50BCX z^0uobsi^88@HS9#+-vi%XOP=9f3oQ?k#{`xtg|Oj;&M<^t!*`DZV&K*tI+#|zsI+S`p=Nb+*+F=lf&6dn_6)H_F2 z;X_9|!Irk%C7A?sN&M0YEi$Bj!1r;&zut8Rb==YNuP=^$E;^L|YQX%ID*csYEUDZ| zy!5pRM?wh1tpUrIgSac{mERLr;lt@kKt7%?wV^f}2nh(D!m4WhVy9u%(R+>S_KVZM^q*VDh6LN(+Lf2Nn5--(b zW;te_FG5<5(>V{*-L)G^8b`GzAFekAat#qEKk{@1z6SUZLzJiJiXUe<|LH{XuRl>1 zYr*EMvf+}8fYo$iC@Nat*;pd3Ce1#D-#&45)O>2az4pUu`Y+D1a+*xyi+LNHZbWgj z=_})KuZEI@wC@Wq+o5e-aj?lJ@(mt@_VSIG?=3%nlbL~Hj$k~Sa_uZ`R`CJTRy3%G z#Tk_itD(gZyLAKZY|jgMMpVJF8&(h2JB-&>G3AL{Yk+2&s>kQTIokEUiQK-=--0-i zJkO7nvrTY(BtiAfvP}a=T>x!K0*JZ9+1=KRxLThLvS=cL8=5DR<$ZPsL^uzT!F4;~ znMmzG<4G6U@3v}0OVKki9q>&+^^T+-8fiHosJK{Bdv`0C>Rq_~yi5to1lc$sHv3Z< zvcBsNN+)6Eb+RzCUv@Kq0gjkF4P%MZwl-^6z(s@i&i$ncF2nh5US!oNm>T7tKxKY& z3rO{|N0~I%pZ|0xZ5E_8%griB`T{==t`LS7G+bdh@o zYffmNJCq!O%noOMe#$`PD$~&>g zaFZwgzKN7n_;bJuvCh)xmr#h#VRiD4HH>qB+^X;!3gh|knw`_!4=RH|cKmE3Q2waP z5pWqsC_b?rnBjFy{M8SD5%&?bzvOn`Y~5aP`e`-aw!&hht-iJ_v0B3FaO|iLj2R@r$fOe(ef^ zIY~}_3yb`B`lF36-sttBe)ESPsX+Q`6P`RLiaVr@LA)r9OM;enTA_1~S8jlA-)=w-}5JVjijbaE8 z>KKG9>lQKb%I~PP(8@7AI74;?Dps%}MN|ovdBa8@hkYt!*q!lAFpU}iHm#7FgV*K6 z;c?j<`R}bg0T9)kU9eQiVY{y`wsm0Z(IK&se}w;=ungwqAH-y#=R1qjh|w6{_TPF$rq8oPUmgDW?Pl!?khLSv1JTZ_c-`=QB6Hee*rn%s61Tos19by(;`(H zPtQxDLVVrOum$Z|kOc{UMF^2~)}Eue^e*LBM8pqHpTH^)q}eLlr`Mv#uTcO8%3z>k zfJQY2YV~n|RBg$n6q5imLpC;rnWP1Gg-C{_Iy2Z{AN5i4^FR13@h74uo{U7(jD!zM zI!N$EP?$?LIeLf&diJQWaoAd?tLysASRD1(DiDU$@fkn^>6 zu{nQJ{y@8QGwBz2tvwz9&r=oA zTiI9w%g?I#h-vHn^j`hyW{@u0jPQSy^%Nh^MN(U@y0=iS+0~RQUlICr6qZ&s^>sk| z)OmOYJAiRsRXl9?SfZ^EK+=3`P0pUSgOF|dhIg2g&Gnu97_^A9x{u3s4``}e6ku_j zp0H~pIsD2F;W};mat^_Cx#bV4TT#7t{=~Z#1#@_v9{)?R@}pa(xSoi&>2S)3(eyW5 zd>z`~q*K@j3(NT~{s~z5;Q+@dA)DSRS!h0?6DkQ9tuwL1MsT0*>;$F2+M`hYGeg>i zWj(F|ju}#2-r%m3coTqIQJTTAoAmgR-f89c^(P6k!NbQY9@*9Dhau)f{~nd8UYAfE z*e{kZ<23sCUm<>4GUF#=YRRV|Z-)ZJ6aVnpAL$dx4c%^yTaH~`gpGX!v42^R47bOF z^+BDLI@S9N`6fC3U}Q-)(b9Kzw7*0iQ!OkroV8OCWs4tmkjGvPhWJ49EbjY^XQ6%D zU9&+PUJI?Zf+$U&qkYd|wv?Syffm9c0;RaOXyJJ)Xa)^+G|C(SDmv&?B1Mh^H$4$; z{)DuO28MFCGH(9I`Ipdwa<_U{Uq01fBF$#LL_&cYz0)iSBE5%$dMpV%DU*mvWC1t@ z^(C7|{zngwE6@`XaN?NDXD$@LeOmPO`}ocxR7qh+qPE)}l1joxy9xmHbla>+QUzoNZ7 z;S#nwPzx&!Tu@Zf@kpRg{Q>w{I)E!joY|D zFp^<6mM_aa)TYz_Q+T4v9LbSF*VUz%)**3h^me!B`dFveP?7iK%L<`G31PkiY&$Su zhn@sS^Gjs*c(@J)uq}^+QoK^C8f+~y%s~{I1a-xeJuDj5yqUe9dzHOs3e%yOYllLR z=67ipPKF8j%dH*igoFnV2n+8LCXgz#uI3MtI)^aRy>SBJQ@uNzio5w}&Om)b0kpPo zO%C0*&^Faat=nF>-n`{s?GbSiy9fTC7Jh;Tv|$iPNVe^eZZPHJ;LnO{!K9uUtQvlx zidMRjLLte?8T?Dpx2{Yzctq|n#qa5+ZP2Q1s58}G{1e>Gwy5VN12e4^!9A_=c<>_7 z4SkMTGH<=q?&jPus1n$i>6g8IaMAfYMmPs$vJll=WjLu__Uu_p&`Yw;P zt}Jo`i+%XEK2XxpPEd+~ohV4YB-DmI#8P@{n#zL;^m>8k`%x=-psq zHfwX56vd;6BF}s=e-cW?Xxuk~cPQTvKq?IZ>GfQivTUc?i5of^0|CDc+j-61=z-G~ z=29@tt(jEub}yKq0VvIvHikeMS>_q-c1r}#4T(A=rY^wTj|&{p>YSoJ?78wF6Tcon z4iOiL=AuMN$W!R@+D~$&IY?WxkFfwxZj$&C^?sm41z;Zwx{@oN z!uex-SbBU8Z*-$kn#-fQX8(v4GZNG#H&?IKSquyUs0_E6XeuxF(#9qq|x5-}P8lWP9$t!){)8hqnEffFVl@gR> zw|dubsQXO#B@1hj-5qdg^AqJ#EUs-nLUOek&;q}x69w{OWN0;=F|rcH zm>+~6c}BD0wO?mpQ?m^HDOX;LCdsK+W1E2xqLvS?uxXg?%l+|1bDZHs!)U-pV@NQ- zYg(q(u&H$cyfSV0pr;mTMun%7cZu6!Pz`nvb4^lgt5zyHP_A%ts9g~CY0qt88lX3? z`EMEZeTb7nB(|tJ?^?lOa8s&ci${usL;?pcD1M=QKsyw-KKtrt^I{0FXao`%%Z5ci zGR$5bMRD>yoxBfN4!50{f#~S25PM>zQx$av>vIKu&g(oB>soCWEA_@XWDEnaa`?KM z#w~HQ1x6D*jBT)8ON<9HnH&1>sE_))VFuqShaX_X>vt|!#o-|a)pDa6u@k<42MwQv zM85sKrD8t?ZQo?yL20_gpVnBDH*#kWl&7FTg2Bym4|6S+iQ_+(7pFHSH8p4~?i6W$3v4m#A{_Z<<;1H=NKHS^KlBIY>f=?`nG!HLUYh&ozu+@Z2cZ55QmlO=guFyQ-*^KyoEoT_freTI9ZV{@LfO$q1_`-63ow6>!mxL* ztwOcoTu`u|V^6DKlgLekzY=wAKXLr*R<@8h-ZJa>M(Mhr~5}RLvV* z%~s`ZPZ>?IT@p;(;P`XNy&V*YSLWXxpjvGdwu5$1Eg3(Uv9f-AMHPzR+Q)RvML)deZOg)RA}VWQ{i~rgNp?j6~rYx>zl^VFdIz75{9yk4R=w#x&_4H z7Qbo}F{tQe*ht_&hhRMgT=NJEf0}Kp+aS$hORnIhGKFDs)WVf1&hG?6Gl_Hcm~6FW zjO)|fG=rjM)dC>T;34pO_D82~6Q_zw;Jt{CK2}PIn&Cfoeh}KLyQf#n!^PoM(#~2Y z-O{rrzQX{OY^*#6Xr@uc`!b=?Vml#r)%bp0&lSlikGR?vm)KZ*B6WQ)Qp=l{Fsv9H z>!8os0u{JsqQ^q@N@CmaLe@(b`h*%zL|Fj zxCvaGcYb_GdG*12Zvc zL$a-d7#BZDdkdlTwWqT%Y3@$NZET(8)~q(a&#dL#=a<8*=AZR1^@2i{~a-<7S^e~C+%0LrAw@B0qAv>+9& zch-qIwyVKV=qHCae|hQxH%s^NA|HN<>wZ&l%{m&-g&52e16OArS5xQgAOu(wON>D0o{H%htna7;imieiM8dPX zSS-zwUG5(C|0a6|+-OrtogS|CHvsFuB$!luGA@5swTCX@7an>aGF?k@UjSFDnXcpb zel~KqW2^**fe~&Lc$DsD-QtbAf02?MSYDm;e{Ge!7!Fu1o^us%>C0?c?NBZnWG#ok zjh{M1AdV1+#R0tw)*CvOKpvxGG1*dk$cA|7)@e|t#EfFA-b(IpqxvfQ{kcPWK^bf% ztM{-Ajv)3SZQZvUhm;VnIG9zeM{4J^DIR;{P~kr|@WQ~tVWJmKbz9Ln6W3Q%^jc8^ z&NhC0wSJ#_abR5X!N1Uy9I>J}V2CGj$`ccg!39E&PxF)?>|4~(DgZf;y4t}+w+ll^ z-F*zSAVvOb=q)yQ)jBFT+iQ8EA#*4t9syW|iXvJ)8&h<)Al@rG(JR~0W!3r(*wl4A zuA;2Dq^G1{$PBh4K7g8=`xZ8bFP4zTSAt`gbKxImOBmL9X7_O`1fnw};It!eEXb`O zSM?KtJElP?HwT2A`xhj6*UvogN?XWF{2Q~TiB@-}n?F0!!vHrT0WOXPz(En%-F%&B(GZ3SP-!}dVU;tHf9|i(GW*YWBjnQd(`Gn+ZTQMP6e`v zXuBA_@G)=y^+_>xXT|kj%S#<#l0W% zY7pG|#b?EJ3TLjj(&?LY@zat-xd``#&63&Pq9!I~cjk}~Eu&)f>9s-c9#^;FL3z6_ zS@|>AkE%tRh3JtL`TfkOpflKe`zvA%raxI`y4hD`iX0l;{b0amTh|Ox4zPWk;f9X= zk+0)#GO>vPGtQ%K8j(+OyWfTo1f}0(${2X;-XCXWf2Iq|r&bO7N+>z+4QnB}C-bfX zkXFcMdx7&-irKvV!C1A=IH8H?ot0E$>j8zm-;&JLtMU@dUK}Az25kg0879`q96h^- z(#qK?1xFT*ooGE%47isotzO$XOl+G49HfZtK~4ii3i|tr?3lb&9Dy5LdGLuyBu9Nc zO#LPKth2!@$Ds|`e*Rm>h~hl?-(Ir?2=uf;qYqnA`3M5$EToktb25FbARb}Q6z4ZW zxN2@IH`OU88N2LBAFk<*T};sSBxx^C%E0fd%(mAL0C-B&PD(6RSz1KjL!X_dz%7Lh zGKHl=$9Jo)@M!cs6wq$T@rKHdqSAtgGhg)Y+^witp9HQC@g;~hl zvDxXLX4zwF-ic)&F6et&eW=d6kkzBo`~^K65FnzRUQZ|jnX^s2&DDjo%JfjCUm5b0 znuGD=g>Zj283s&$4<2%XW`B70uW6F^8C4Pin;_9h9OJ3aF6uA<`07bZRmkIFo`iyR za<;|CBAyao6RmSpc)QmJD%%}fJaFK86^&rr(*;L&OE+xyS?Vz~T9IXo3R*_R9rKJ! zKj`2#3kB#~e;dAz_;6|uGHzx5VA zI}mvN)Yg!}Uws*EAuhyBvoF3#SEP!^aL#*xlw`Dg-EptEJAgIc5$if-iVZ-Z zs<~H^VR{gwK67GwZVaSBa((+>Q+EC>w0%3L^w-l%hK@>~dO%KA!cVEdAFo_3`*ioi z@lAlYc31$X6|FRKL``v{5l$--Bf8Gt$Q+R}RG1%;SM%mM4#&^^Sg8rZc|5vC*uq_- ztkJ26whJ+u_rL{&uAASC6VD#L=^(TIrwg#3~KD^(BZLOJE$6+ba46$ zXeBbcMZP|L{D$PKRH$T@P@0gox>c~APzn#xubyPj6WlqZ(jXZBCeu^xziI3g)ZV#R z6Xf%H!~`>N^MwzxfB#UIKpm1l+-@O&yGF9za>1VWO-NTNRx-=`v=xMWUC`5m;9poR zE(zP+MWX7C?~;ZWpWIZ=-rjqdGyKogodZWm&U?H z<4sz|xrUkpSZ~xl-dd@qBL>0RUH36gDYi;N9lQphB=l>QMbAiTA!YGAE1btL3 z7o+Fl0_YF%?i8<~ByoU3KPk5)}J$D|}yG)+_~blo+o%d!++9E#-QO#?*b$9Fp0 z9K9&(E)K-oGBm`Dt5s!qLc0532uO43)V72jxw*KN|V` zVunM|j#)?E&KU9I(NTwa`h$O0{R31rm#D;h^jx^s;nFe|bhPQ%p%hjogt`~-tPf80 zB}Xuwo#R=QZ~{8#T|!&MBTmSeTD@hoV0-Nf7tS>>=boGA<4~{Ug8J}h3i51<$d8Mj z@j-((3?)5P%MsBJ+DjY$eZ2o6Ujyv$66#qb6GT|1iHaSK<fKpX4dc1IdFWNaC z!T(tJ%fI)!cw=f~0{H$N!dR&L9l~u=B_|mm;a1JyhwK8JOGiNf$;|2ZKhk|Qg`l4NIrPT!~6V-^rI&)`DC6lp9d#i zI}cgBaQPz1_i}7gJ%+hu)zI7&A7kMGt`hO-uKKfT1!Hcy^^z6J-13Js5M%Op<3#ib zwb@OkkbhJs|LP6+L-pK_`VEg~`>G=Ce`~B7{%Q6vW9J$MJ1nGo6CVJlfPn}Tcf2T< zeP>0J50s{MdD8sfswxb_<+9OzrWIGs{=d|kd{Pg=asI8yGk{xb4V?U0>)!zwAq_h1}sIvz&xLX|^f~SX$ z04wwZ(yZ6vMrB{N3Lh&hC&k!sIS0G!0v3mZR75%TF)!~5kcAVJTqdhW&z_akks5wA z{Ze`cLv2hS)dW}Xqk{+N-7wY6-LGl07~;b`MyLcMX!kbuM#`-V_Ij3;1kBB?Ihbdu zXsJuBq72VD=DF3=ZwmMBP5DJopU1l9-0R1{^R|65Xw+tDB<_vumn(6e_&A}=`fTxT zkjZ(O+T}+^HQF5v72^WA*FMvlcBqo>p^DRt3%h0+z!!L-k$YLp+-;^h)-_Lk)djk4 zRem$T=7`u}l>y)?e`Dh;VW~&YSl?H>D(fVdz~AUFWz$o9j8|A+`srLk@s;mgH#47N zwN0C-aDq*UwuGk>xO-{J;mjD^FZVtH%rg6%j7xTolpa!@1fE76DOn^`wqXa#iLa9@ zW=b*O49{f2^)@ToRB^ezl^mXrayBiQ7VoT^6&sx=@+kO=_fXQuseDvVH-}%mQ()dT zJz6D_?ggrSo8$sUZkyccTn{pO<25BL9pz&Q!)9{x_w6^|?!@ zwuJTi-^>^&sGd)7{Q+GK?Rz8LC-;#XjXOx(!HXl9j^SR}^j9(?TImFrzg+Uz7epzs zZTJq-XrCo_kwaluc=XY?N4BLcPOj>`QUmib9n^fy~w9`kj))9>gv6nJ2s^+FT)<8E$Nb5&6)jQQJKdm>jw^i(t0Id zUDO+Oe&b{m|LnlR^OgIr5(VGkx;jcv4y|j`Wq^Axj$ikASeqLgF*9|)|33tFX06$Q zp7$8$%m1g!AH5~*7FSD7B0XnYzK`QS$F*{NDBpF-)Us6T>*pyJyX){ps-eZ?cznk1 z7Am2hLs=be+0f8YbgeBwzOX%R5RuJ*KMO>HTyYGcc;6q zUvV}CxiM$@S4=kuit0r5BeZ>1ysB^H`WKR91gtSp!w5b5m6Y=eB@sZ7rT5fef5W|l zfis!cO?5Pd-*^t3gVnn%PAA(67pAX89;PR1@je(;F%EiSsd3Zj7xID_^bbNB&r8n! zZ4WGE4gBW~R(+uHhC1h;1QkS(K`hw!ZcKnmX9Z8^_O%9%TOAQ{b4HJiUJEk%H`M(pFu%`sTDb#7|ED`pQ7cM5c!` zV0jQ9dS|&8R#+Z!XSu)0bIpL)A%U{yZacluedDRxDWV4QrKN(&A1DSaaW5<-b!mj2 zr}|n$Plc1HD!ZAGap~jWCtywR-AUc*RTGuECk?jd{`1uSnLz)^L9nZI9i=mKxGAHg zNMx_y?Q{|9^!E*Q0?sXKLc-}YBYkz>Zz7e#O*!=85~yMrNy69K`Mu+%`xovOyn3$y z=TGGNP4;!M>&gdpsmVCGCgSZ|d?}47RBk)))^hFR5VN~fJp(u5YX(Uk21%>U6iSuT@U^;Gy--@Vevq>+LG z_d!)%f0H$sIJDgu1icK2Zx&nJJz8iGLNMhj7YD~pLr)F!VtAFGA9vV&Wq2E!{tL4S z9|Pt}3`ng{=i1c@llFUJZoJp=^3Qt~KE4N3`1nfsi;mD^D#DF}PX4*tiCFH<%{%Tg zDb@w6lQZc?S=x15OprjKn_e4Fcg>`I%V*lEoT?eXJDaK9J>L^I*Yo;!2y!E?g$aS^~25S^+=_%>M69C!K@*q zvCP2~ia(RdTP|5x`ArsKznLu%bS&|!5#+iHIcUx^pH>y@kb&z>heXN6np2pZX`b(Ocf0uc1QQ01>K0Oy%V_2Zkw5oqldZJ?j(7Dbzm}JH)(6Vi?@buTeAs zfu!6NW$@ssfUnaN|5=ly&&qPA3FS@N8|Yh(M*`j(T@2Q%yR0OQ+@b_Tr%6SK0Q`9$jP)4ncV zYNOc=p?xbdW_pr4>e){P`J+|2NU*UJWkdwYBqq6iuM$jqN(YG!{bIY+7AKVk39tLaNTIL%^vWzUox z>30xY34ZEkB8?np&S7=NvD74{MI-^^?Ay1k#l@wmC!Gb|C2Wef+3vi}{kdJ%(EX;S z0j02=29@SZ9+y#HqvRDVxgE7le<@uvWd``t3!fR)Y3DUFVsdZVIDp_9yT)6t z^}Nup`f|V|yL#a}lTT9i{5M72t&dJFU!71Tc+iFvZodsPZMZ1{Rb>2$@|5o5m7(aZ zU{n~^*GnpbOo2*&UL!NWcVHkV6V0^Ft zYV&DK`-ns9RtgY#Voi(>m{aeymh_7)cxRnrs8@`7Ko1_wNRXaiO#r&UYFYeV4K3WC z32(Kh`L2;DKTZ9BHsc6Ie%ztV5ww3vZ|hwk8R}B2L~Phq#fr(e^1;^~NqDrTc$mS1 z0;dnRdFh{&#J$NL_Z+8Q;FWJ>Yq~V4{cx!EK(?yEht)yl0dA`yj?PuBvwlq8TWV}e zBCbauS<6JO)^_(8pEbUnIiIIEZ>^I{JJc2Yo9z1>ALo=a$5EIun+=0g>!%S1FOvx8 zVOqRlbt~7adX%C9$f1?&vAJFK{zpms`5-5`AAB&*!mM&?(}_n9O0V@vjh@HRWQwP> zhS^KTe9Eu>(z#q^x8F1MzRB9=?#Ja9*ViV(<#x=X>Fb6@JEiOTZ&e(=nsDSzC!;jX z4@>F1W_|dG&Y@xspJvQR?p-J%7)$?VMT*BiEYBtM2_^aQ`H>|{&^~vPE?i9td3fc*Y$<`7*ulHiMn$qxxq%w>0jpvac|#GOVODvO+ok zxKf_1RepkA? zM39|pUN=^^kJ+9>vEasZVk#K#8TF&qmudRGli;QBr!?m)o$p(J=4FwtM)pH-z$vJN^zaq^;FgHugq_nVXAvfK>gjKV&d6uvj(+Yd zAV!XfpOg1_&fErlvUck{UNFd6kxZUuE9C+I0gh*W#cS$U&*7h4f%?v$rSM+jD(X$1`gkZQcTg zYI)rgwa{$#fr^#|o@Xt|gZ!g|5*L3ZHZ@a*9wvyq6+27NSn1ZemegN-pAGXhPiQfA zY!GbmzUteAwbSQt6Ipu^`gBg$Gj{OX#ZHuDQC)b$eybfWciMMzJ_qER2UK%bN4VOB zSjdwuS@CO{S|luopeiF#aBMQFJwyeau3Pp(Wo1ulilRm)U8)#VZU<--Z5nysKl`^`i`;AM} zLFM?9rmlJ_D%aKD*j2`kjbf z+Vs0N(O({mQsNxv@ml#!LPU;%xi z>ZCRNItXraJ66=};`Qn>+%K0)@uH$)7Q_i|ymgilX85HrUP}Aoz}HgT+qDIbtProFveh3DrMC|Rgj~kp&nw#skxFNs)UO6Mxl-&rGH(&DOP8uFg1&@_b^IbI)pp3bS zj{4E9qILvxzcBN_{gFHIiu~#WtUVa1Gx3{@Z(ccy|tng{a7)qZN_&##HQ8;Bq=k)HA*rKb(ehVg5 zc)f&O?~rY&&bznS_YO<8k4;ZRa6egVHb0J43G05gVbTH~e=F{>Ws*8DP8rB?EVJH`J?b_0)&o>g6$W3)C zeje1h51I;KwpqDBoyt-lSzmt8CxED%9!mD^Z4PwCwhR&AC?cf`RQnniYaioQDwA#^DKqNr>v7|IHat?CW-*x3#nC?O zNGO$LoLlB9X;38WA36S64(vA9UPC7&_-zPGT*`(9*I(LK8C7xNOmMQkuIyDHoT?mH z%=5{~Ed3dhD-`Qfc}rDIJu0obb|LR=yfU%fQiCtqm#Wr8I6ZZ+?t|Y&FZnzE74nV( z{03(?xS}zhX@(>HX8MB#wfi>Df3%Aw`RN>b$_Rq*&OC$&4P8pivDh-Y`?X3bG=JMe zKDHr9$^-!rMu_q)dsI`!`P*r9nyFiVc=dVn!Iet&YoGTn$-T@TcpvM2SVh8|n$b(8 zzNF(R;drXg>=aMGl57M4t|uUdb24c^0=krz+|BK##ut0U(tX0SWA(P%ZL}|u%j6UV zz7v)uCbrv%WZDfj*zwtvOmYWE*G6t3h@<9YPVKU zoL0?bf5UxXCc{Ox>uNvb)g8Pn-bZ!n+Mft-V!zRdN^o3SR$1XO;$oAK) zVfJcd)~vj9;dm&G(7{tyb*WXu3$-Z57jL6ZHJB-AK8)0=@vO8m+niNc=j|cKh zyzo`Q_Nc1nLyS@j+(|G=jpKgIjc&4RU6fU_SO@wBNLa!3VQedZ zfUmdJM!_`-Zc_OUR%b0PCGT=vrASk)wm0>LKyGq>l{K_?Vy#MFr#BiQ-X6&smeS(J zBe;zuSC8t1W3Gu9zh0TjQWMnh#C21!buv=_WH0j73mga=&68ZE)Xj;WRvR7szWYo( z8C52q(PPpWUGM|d7U59t9^ciLk_o^p`iJ>ACA|ojzwt#JB`|yQN!QYn7LPi2+M59N zkV4h|w(B!-BMmr#$o)hap~+da`+I3R!nQ{ymX6GGku>SCG)KS zUkv;AJnDu#+DxszNKFr&4(>VAEJ(PP|7)*x_4#%ICdUc?P~1!YYJl@;*i3d0)HZZOlof1SO!!^iS$#N(^_u2>BJ z6$aLP3dtdY;dD_}v3Y~4aIzF!LtLtm{($c(Z!Hhdb>3?91b(ApHXK!vRMWQxIzPim z`mAg153^!uy1Zg!2OgsRP4=;9kwL8B%KYk*WzSG#kr2IxV#?GS92kMDNzhI^WBArF z%TcVJsd-#Dn=}deG#{=H7j}y9(we00kaPW7ub5U)V4dc#ojOULE5O~g^N4K)$7N}5 z&1re(znu39-nL%(!`^{@lYfbno(9cL3FrkF2Lm1r9@@set9&q2^;kG%s+33dxoMp( zuMF#luzcZr*_T)?*w{XoT{*B$&DXtje{!5Y%+vKc(a`GTC+H*Oyn`22CtKiK=jJnqz2SjaB88sN3`Eo~w?WOrIR=zs|=OkoMin z;LrD2bi02-`eoZKQd%h{{rdP)dUKHG@+Dmb^Z>y0gWt92Df%!HxkA&5NSRk$Pwsu| z=12}|h1*;{x705&@x)$_-A95lO+4|X6_0e#%;k(4&o0t0+GaC_K72mVnR})*rsn0M&4z5-3t1zHIM?Y7_)zL|ssg0l;c6`CLOc?Bfk?{8 z*z$}qU5%c$b{1;jZUfA8E}>5zO{XTRJbnC~By^IAPfZ?ru;E6-rOSwpc=r`<~-GjTkCpZf% z?iSo3EbhVGb#W(XaF@6FzH{!o=iPID+_&A+Q&ZjB-P1EuU0q#WeSxrGiM&O9$eeKf zZg5$crSej|a)usTM||^ssLO7QiK$=uaw=bry9_(2hpSwKH`K??OIfXuspQA~WqGI~ zawLyyumLug0WQ@VVOWMN#Ym!DqZMn3pb=z!-h0-n71K65w{U*H6>Ce12coWcPueAXn6UwadLQ1OY+hCT0fy&aP?VLP~mqgCGOo*(({6J z#UQ)jM-w5wE|%ongMT#GerLgMnSafREjwS>^3v@mHs7bw(^YMO{^t*(9GF2Jd&!_3 zdUt18^yP&mlL{;6n|fto(qUxBDH;xN1H&>atn_&I;KRynVfo$W+!TZ z#K=Xhz9z@lTggQ5o6(z4)wTB5S`OcO?Xw#ffajs_W?8}ek3%P%GRK~*4MPWxG<(a~f^9|T_4?s268Bs_ zK#$x#(=#birE7YkOU7i#_Ss_X(Lb9b$8vpP1T(b}5_nLDYMUx^c|`cTs&bk< zSzAZqmww=8Gd%Xo;=!|YV{T|>zK~wBeo_{*t~tZy_<9yN%Mz6{N8;*!{<(NCID^WM zxpVoJmOZwXR{*BKrUng`pUxyI=?gxE|E}?h%jYb1U%vSUiTjBC(qwJHyvdA1X7UGX zJ93VlS17O|SY)C(SO_8%VR}d?GP7B(V~`pUu2_-v?Bi_ib2+YZOM>g>reW7*tBla- zEjL!Lp<9fzm1?>mt@=!e!I*}*K=wo!)~H$~OMQR}Hd?L!aqr~};UE=O*|hnbNd1pm zOc~>6x6rp(Pv&b{RN8jU_Zss*U(x>VGP5q*x|pYI*X82t9(Qw1oQt@%u_()Dkym<8 zc)jupC6!E#|J8{2Yb3M)sbt{n%oMN%o|>=YdB$S zm9?M#7l1m{#r^7j;ZyM-&g?zY(RE?S+ZEa^b3~SiH!%HU>AVJF7(@ycdOMoe_{%N7 z<7xvR5>VX@N|%|UuW|G2TRQMuRu;b4^0U)$*c%CUT{A&gZ+h)xbkkZ7|8$L{LMtV~ zw6LZZ-41zyj8j$-xw$Ue_nzW9(SfbO&JB}DtihEZBUr7RF5dAnR%GS7725GfiXALd z+_TCS?9mL6g^P&5M}gsGprd9^qSS|3RShePF%wO{f6AD60JPPXe$C@O`Q>@iZ+DGC zC3m(l+5_oH_kt7jKz+MInC8qaY-kB?F?HXr{MFYjrqTwRroA#2?1>Ux-wpKai-)#y z$>42KGA+yRj%BKaGIdKY%kHpo>0h2c6CN_tdl(TbTv|4W7K+}UCBK9{b;_qdgKu`P z?>}jx413Rjrj5@n8ZXJAlblxnv$JpAoIy8*VW;yA&EYhc1RzvMv#_F3-?04V`;u6c zbm?E;qhuM~Gu28p_Mk?rQDI3hjwj~DwIZrVZgHwzV_rL??DgJ==RW0~UeQTt<4lJ6 z?{y97by5pIK9HQ(Ri$e=T&avP=wuKemHu5Pc$>|G2uH&EXbzFf!TwE7b#ZJZkp?BB zqpO2XUs5Kds&XO!Cv;o5*lGP>&MF7c0 zmFrsd?(t}_UJK;@bBqpVrfS{Hm6jP==5Mi?Gi1q;W|{|0;@C$%T*79!)obZgFlykm zBL0zzto&#!_Hz3RgD%ZN*Xghy@H8>Rt+)9Y=!KtqVi=b<8z0>F z<`oLB!3tc@!eu*})j@DypMj34FlAfx`$Hsp>Ht-Wg~c-+93D6>oJrqfT+^Z_V``b> zr6lCSUE7y*-Y~D{$tVZbrXykp3W*~4$4hp^FIGWWhGc25e>k!mvi-F#S3$aQFQF?8L`%Oa z`*IHH30Z`U?Av3l`Edrvcv0}$ z?WNN`^ugQps_*8OY}$;p9TTz`$C`-E!R!v)!nf^qe(5<@pIS94^;(?^J(+EK9G7Pn z6It;KdT~e{%V}-b^QyGlwF?`Kvy5z2sUQ=Mm#S{mS_!XElorjK3o^@^7RTWDrC4Qg zLeU53=z?%brlodbVHkmwZ6JGzPNl+c^R6SHChuzg7!dldFktTh^MGzi(-xRsh{U6v8C7R5#&u~TeZEYHF^whoSXaZ#uKfUXlL*XFFg4XP$e^4y6WK=$0M zCZya3rccJ7TR@+us2KZ9i6Rm?NN&V(?RH11!;zn2og_(htUs@3y+S#RMZQ8c`c|#N zc94V#(R=%Y=4L=6Rf_Qz29b?Y`KyVGU6+(4Gq44)M{*mFsk4JI@#%5Fx9KL@k^)YI~66VL!cHyRN^n_AAtI>apKqkIqf!g@2h1 za}8Y4B%HxE297<(tw-Y7mKn!ouRgLUgdHeAR9zj&_f8^&Zj9eaWYxSe9c<)CkS~<7 z?HwK2RG{AwQ5fIPm`6I1JHgtsb!M%lIqn$>CQFTBT#NIFFOuZ^Y0kTt9_h!_j(ajg zdKDnoS}GVJesh?dDmiJ$o?NHUkgxl(LEM(TwXdL|Z+^0}LD#kcjPm8w^mMpFcWl6k zb^|>I#`j=^8~`=R2ESuRbo{e_ft5dAHRM=7v;jYyxc^)l5u@1lSgYK2uc3K?;>TjX zr`2-rM_@l?!H1KUcyOzC^McpS^6G`jL;}H1e=}>96lp3_joxrIju{ex%;)Nwfiz1e zi*E&CHXc7yle zKAvM$U^MQ3XD}C3`^7BPfWZ`+tzPZ;9WV7Lx@oT~NU4v4ZQ+qv^4EcDF|4~e@R*uZ z_m|+cFwdfy&GFo$bg#7O2xWq+C$sfeO1wo_4Y_9yct4V*#<+R%(=8g$WFV$L@bpl+ zgLq5XZcy$dcVf#IV*bZ3OW0Iryk=g3!m#?-b~h>Pp@q9rCDMI4NT6a&%0F>k^GMTG zp;o(M6?amOpELY}&@6+B45zF|G*!fRQnPI7D0e?WF|lJsRz_1<80L+jE&I+}r_<|W z4Z1rgbk(n4w#QUF4-LE5-KS^ts$QXJH#KYCUn;S9vu|-3H`PcCi>)1YPR$6UQUS%O z+v-_3f=r1yqU1}#Hk9rfHrVSA&w8VIw0gO`NI!RI`CcxLFS}b?rk~kQ*V1_TcWT|R zD9MHOhmhcDaxpb5*%1&Vbd;=ISdExTtu7AC3X?;1v{`nip-FkodC64bhB^JO103c$ zvcvEO0d*AHIv+D~5s71vi+(g2yu+@p)jWARz65CZzD@b?+2mt6DA9qGm&l`H{MIa9 zmiRN&FnaXBrd|pTVb#znVDG(87SIa$TLOp9CA`zJGu}}ma6_q2#cE0;Q8t?G4J#k& zQ={~?%ob$11k*kBDadzu=Jv2t>Lp8lpk(hCSU5vEl>5pbJN(_(Uk9l}Gn5GxSswZe zZfN}q_B}K+K)(2JA}xdf(uOJaz43c)rWSmY_)VyEcVmkvB0X4u6j_oC28XUEV7vc_ zYS2amR-}Kb3rp&&V!lu5KHpVSDj*`X61Typ0NNE|^X|yp5PW;qda)M{=2VqPpNAZ@-dVcd~en7i^Hcwu< zC9v&l$W_H++jw1T1?Ymyo|rT)pF3$UWOhDl6QDm-?gy+qm_aAU8}h*xC~f z7Wo|}JP@t(D4?My-upkjDsZLvO|6su?3-Ews@X~yqN{E9TBFOFxl7O8aP6xDYCBmA zo~xF30MTVCs%Y*~c8Hd8@)QW^Yo~}kT$}w<1iH;|ruKxVqT0BkoPQ2G$U>oWgW%4U zoZ7{XnsArV=R(c?6)84J> z@fkxu)*8yBF;n-)+r4;2FZx#~E3XF*mWL&#qKd#dBpu48ZqucT@C+X6=G*hqYKCwm+Mznv0runv2p$ z_>H=EB-g}#iZv9tK73>4M?|z9QIvzca-Z0hk`>!d#lHZ_hYAlB7czf&YlQAL52(M<+#@BZY8jpgq z=b1^iVmI$dLC!`$l_VMDJn}<-PK5P3mgDd7m>2gz@iXFinB}#?JF{sC#vk3;w3EL44%rk-fPMdkjtVZc%(6eeWRInVhKJl3? zE7~S2&QPxUfBp8oki2I6qlgpU1{#-d>%sdONf+sl;9%)_CH+C*wd5d7O z3@7sILkMILh}IDIgs6;F#|02ACG1hfs^dJAj6`-$Sd)2$8k<@;sCPD|AC(ccz%MXK zxaoT`P`ygLE~zgvwiKuv0&u&lR4fni>jWI_m9S zp<=EAR7&K~$Ga)M&((oj#>~@DEhxrEKoOfBV_Pb{%2*cPcW3AijI`aSH}=1*F1f5& z$qFl+raN0n7%zL}C|sUKO%#4z(}x{;(PR4|&JjWpxqvc%SVc@k_E~q+A?CBkLYd zfAbK_$b)h%NlG2jugzgoS<}GOFqic(5^HciU3=??kQX!59w(7t`DxR9%OJ! z-d?>-7~Z?aZ*s&$u%xYhJQTdG{3CqhTd2QawW2j&6^tDuxaYiR<&e-%1de)#XmSH9 zcEG1>Uu!EC-ICwrehKVTslqY>s4Par_25m#eQW6>N3&=sh{|K?C~{2B%Cicj_8h0S zG~ix;H)Pk*1yk39euM|qx`*%I*)gPz=zFkaso41J>Gvh^O{yqo=@cTm|Nd{yeeLVR zDFsCN!lLOJD>Ex3=ikO`NEn{M4C%jO+b41My8+5H!nhAIPdha@6=MFz%8}r&%zzF2!m~*_WDBp@(13-Z-+{$!oiCf#ZN6-xosDl zQzL{^v-*Frw7N6<#&CHtgXUxW62q;UE7TS=SBVAJA8>s0aV=O{g$X-Z@DfV!2a59fs5vC8n+=!F zXJOjKis{e%rJv%{@1vW>T2&rxe}LK~~i_=MlJ( zQb(vRtvDI7e>b0HU7d~&BUPw7gyH_voLH*q4vJY(f?5IbEGzL25)DGY2E-`xm6oR6W4mLLG&~*JMZTFsJ1pF=Ok3wrSfSn2GZbVy zyGmV6x5Q1gRSZWlY@TDu@!I^=iJ7#SHUo_K@z4 zmYjy?DC$7gy}AVz@VeHD)h)bZjokZl{B=`k>mqxN4XQ^ZwuYa-0{=;e< zPTG9VHkd2O^yULT0d(N!>bvadoq+OPQ;@dnPrsbqZHH%63gY6zmK9=Z@RnK(reOO zhEeCOH%pBZDTd;y`wGSH&3BqLQ}GH_6t30J(~Z|(_fbHLi=rB0#z0DYh(l^w_MZA??$Yu*LPV!(>p2m{qG!Q2mUF!q z`Nx=@{foY<1VWIp>&}rX# zmTSWcVY$N4-A3&Tzy>nJr9FK*U&JXk=rvNw{Qgcp&?lijLi9lHxus5Qr`BC($cD3G zezOvcQ>znUe#k=m;WKVbV*(|X0~s6bob>+qTu^G6!nw50_{D5E$Zi8C>J~rep_6Z5 z?!u|lW|ChL*9b~ua|Ty&ng+>eQIMtAe1#t|f+;G^_7w_BG*c*H)!dMZ?;iGBe8RyM zQ|g~ud%cj5_j2Jmj+nL)4ExeeHWEni9t~+d9iK9<3*@MUI_F4QI4~UqGh7HG*(-hb zF!4LOIPkq{`7k!A%Wk>2y9IzawypQpc}L+RQDECjgdlEnqRbp+E`J57cK2i^qQWOP zb{iF-2Ayy-11l_R>9&{h0@vpYL^b$$K_Z(lg3bOWr>cJsSjR>9W;!fY)GD5pnA(2- zFyLB6%RXS zUe+(pZ||N`eaxMn-*sdZ{SG%~6NsmwCk{++7`=dB$sx@ltL0zvThOg)ltwB2TtpT< zER2?#Z!4JSf}Fb6o<=svaR40rF*c96Ea=GOYH3@Oo%Frl(l?xh90N=4hyvv_Gq8y$ z)W-1q>isqYsiB%q{igsY8`he(9;3=2Cao$}CaEf=-LMa!rznS|BHwH+MA;zr8neBV z8OIxq&6BH<^RQ1IQOy`}TvSvqj5dNQ1!9v6%)e?ZLZ#0)*MzA}_Y~?X2?&cH0*+q{ z_+FtFFElfaX=>8b1q{*?@XB-d5$p^?Q12bfBlV8OGx2kE1H~+1{H`oZ>?LBH35hXHAB$ZirAjDx0;I zWZi1Vd?9v-7BOLeGNPYxfRvU*&0NANgFC(e-_=;&7~O=M``{(}(J&<{*`uWnBc6r= zXR;17J(NM2txra?!uZ%pZJ*WRehsY9lotdgOM&v zISWt+*(y%RK4~wUd`Dd`-6lcVVOBS3W=}c@w>YSX^#Rksc^%`HV@{FRjiKpUO;>9+HWfq_jjcgY32 zLob5D%T#3CKyL;gRqh4lN5a>BlmcYEqNaL<(gIB>Q@08QzfP*fa)OY>x8ohk4}_FC_3jw{gPGK;dqt4nGN5 zrgBCDpeZD6i)U>Il_cl+)4{!Ghm& zD!y+nE@guPzkS2}a$byW_Ut#fh@HAq=8X5z;~dXJL7cfPhkl5Z#5H)wvP4^3$2nY# z;@K8Oy3`B=sxdA&n1>i>LK+tSb>;P*Y`^<06qV3f#U$|talS8RAo_8?LQ#`kU-F{2 zjEQxt>H~Rf<*}V|B?vCs7$`Y^0_b@w>1PTZp|ckyi8EM)iM<_#864kb&Tj+h1!Zc2 zYe&g2R|4_!1K%lRY4uy}zXAG#e!8V=9eKKwAh9*QYp?kH5h!1_h8r5~oS8~6PJtbq z2P`%6v>yS3y2fhp-pz;BD2+_KWM4nEDwfUTeh^-rM1;DEb%X9DpK|&BAd@$<{_xOt&JWAK zb6E3Rzm}?%D@UHMI!Q~A9&@bdmLd*k2TJGT4rbXvtGC6tuHqBtYLlC@j|J0eU}hF! z%}?e$;%lkvEr?(cd!mTsX35}rcRA^}C1BSAP{JSL5%ZFWBv6qdSHVnkTZ;K^{QNd9 zWLEy!(H7`vH)HO(g-xWK=%YSc)28AjG_!8FJA6MPS#Rk#pm{aXKz9$m7wV)4sz`^Q zt0CC#Z`w$Q((|0}wTU6vhTfKFn%bG$RD`7$cdLOZ4s7wHFAfB4&+B=Y$7nBn0C`_8 z5OnBSDlZ@bxp7E9Tb*usp%MoOO#;trKQ^t5WXMVij`SfJY0i8MpLeP+0FHaD-v zsUqTaBG;3;*bwSL8|t`ZJT#w%GhR%yI@wpCgM;g-l`xR{!?Ynob)b~RbPOk0 z*}UOW*M9Uoj$=!?4>C2T=(j%1T=3HJHp_BE+AXneAibSxw>tiJ#y!a?>dKww&(7!o zf;)|*lmv>CWyO?Exg4&^&WHelLCk|;!|#HVz+wSDPjJbH*kZD+p~@fkauSJQHYpkm5`-p&LJuweqVXtkq_;t;E3w(%n|} z$Fa?50rcXp?2A}uH(=FYG+nLYC5+|@smb=K$;ED0$rS7(*3p>*0qmkY2_7UHR=hn_%gHE#BN)nR`R>NAwr56}KRUcqnzX~zkicV*u zpaoU&;hB*8r{Pe1DgkaJg39~U0zz&+Nn@>)@NwYr{x09fbs>NSIrRNaIa{?M$9X?C z9gH+j&xZ-Qc|SJD?58XR!^2R{C*nGYa2g~p%O$`WN=tjv7e6EcEit9(M(kO~$+)N! z3-bO<_b#<85t@@t?z|#{bDhUY1JFPo9-YeR;WKjp(1+W8Q+1qi;fm-Y(I(=?IAs1I z)fd%xnM?jY2FtW*l8MswIvwHZwCIsQ*X`L~JUn%`g3rb`vbz_%V_;*xdo!yCspK6Q zP-whU%3hR#`px|^D2yE7KkuO(x)a<*)VV+iJ7k)JHn- z&K_@|-gE#k%`ZMp0-$yu9zWm~W~5LoDX&ekU&bf5@8Taoxp$fb+9fb#lzQ)ERAUe` zYkWjZCot#$&;U((EFB?>e%_eXhJ`?Pu&M=@X;s1#YzlaKIWuZ9K1l{aZ~Uy7iO7xr z+J_1+ZjDi{^ZvGg08`r8b6lGh0Y$j=C+Fq`tu>J{4tkRwYxRf8%3NK!hUA&bVqIA) zY(ddGpM^+Z(-Ck4I1)u4g$SWO{Y~dg0`xJ^i&YIajAiB4Wy>Y0bRdNMi6=NfEEwMr z9VVauFv_pWB_O6 zi5#-Qg&VYDfMCP?=0_W}+Xf~TgbEGj|0Fkqld|EyBNVbScH7COrLM8BxUxOY!i?XT zuEWcbH8h_9X+^-1joqp(Mq5(uE^KSG!_{6XMyM0? znScD{e=)Ii`GH=A7k-vnKqEI@rOzr{)|kd9@JkJ9^1#9?R1!Oy?M{+y)5kQ(bXTAD zqk#&}$Fnji@nA;348f7nJ6}^}i781NaLf$%s!IE}e*Js`zHMirJam)pOB%cU+hqTR zbkZ8ih;3Ugt-%snx>`xtFsm=GP$z=AB!(}_yUtFLog!~oU!;_z*tqW^g{*WutbM{> zq3)OA!Sak2>YvuJWl4^| zl;s{#iY$!LvBz-~PON2?M$%S$(>B#bB>Bm+Vt|r|3MP;j$)*>h4^5cluX{_#ew&t# zpk0KJ7gmrFVqt97`)T4Fr(^sWAVN#NwI!gf^O90%&a)l(YY2%e`{fwmh1@*>T8*#b@^TEJ-8($rP%bDm-E`LFAL zljOgnib827UZFmi{uF4!Wr7>|=DeZTgq^`kY@kM;0=*+Xy8E-)kx36R1$y^qpl1Q| zS+f5$ZNb`wyoG6QRxx6L@j#7+d7^FKjrRoqXBMqBAA@nBJcs7#(LzM^_$lIyAa!AW zEqq2Pc2SxMtZc~Z;uFWp%Mz{=1(1d(1^gVo7-yx~#m74iHiw@^T#1Mn3Kp3)Rgq#v z(ty|e<&q#x5ltVkeexKP#oYP|gYXne|a#C$HyNCN=n_%^*YVoKJP9^N8~a zuuL=DoEV$^(P@PAWB~gtU3WwL1Ca@>&W+PErr!v(g`P+D?zwXq(p!uUrMjj7%ac}( zR`t5M1W1F6?a_Un(~sIqHlntaDo%Fx%to4xC-(YC%!-*>3Zw4Mo~|97l}nbbeVev% z43RVtJ>R@So!>mSFzCSZI_XSi-jG+r**GnQHjpAWW8EdP$ipq#if*HkHNVp&GI&dS zE@hKt^UX^3^cAXG`%#MJZU^B_0iYed;*cOtlmEPK-U_qLy`wM2I6HOB7_T4CxF--- zUWK$KJV=(9QIxXUf@Df)C6=44Qt5ESlN&lMa>#QBp>#h_OGfq@)w$qL%Tk9Y_7yd? zkut`k153MFee;cqoHAY7#2JV;sf{x}DMkLo(DBVH{3y`yaa}3$E0Jz;?YPjBU#EkE zAQf_cPgVEK*16p63iWdL+5LB0W%>5)`&i{Ls~=6zRqXja=R!AHpW3p2KT+n?6(BS3 zWd9id9&8g*U2C#fZrEpB@~d>-Q^GN@>1U;n)Jw$6zVzlA9-XBAI9{PJp4jwEpbPpJ zOvvXvk+LvU;9^h;&T1JlpfxZzdW9O)y*W4w=ZvNa9px~p7Qi;HCi%caagHl4K`)7n zM;g<$p`se7vl;T4+PKa=4}Fr&rxWrP4sZSn;LL%Pp8wZk=-v7gn1dhpLR6eX(at7% zsSE!EW(Z~NC%}JA2Fuy}V^;V-0YHgl#Xk*lS#TS$NfG1z3BHbC(nh%Q?^AJj1Rh76 zfJJtY4zeZZ_xV334#zkNA(^2+9M#_nhuUmIEfBp!$mw5j|MvoNzp{ifgeVPJc6>{2 zbw^h7e>x+D|GJzMP0WdbSl*yPhk}OwV{`*@f^7Bm=l2F09SwsO<|8S~XJJe>GG!5^ zuSS0v+kk8zCIrzCnW>UEUd^a=7hf-ooZkHlzK8w2>8E&QJLq)TU_kbJ!+6JVhvzVC z*QEF$jzq4xn=-sp=&fp$j8`c0k~xCBl&;y0g9_;k2s(ohM{9?QI+DRwP7X9eNWQzJhrYj&15GFA9=0xy z4KTw}rA<^;M2KorH4|VCPz_{?o}x8S)?CNZjAFlXy=YY%peLW`VlRGwF&2YyCa(!R zJU{V^jRs9~@x?xidESm`=X02-hd!a3N=~?%N%TJ_j^USca+*gOYgqOX1i(&=iXB3f zDS#pxJllnXXOQhlPy}gFA{jsz3#S6^OAJAm>)6{{ht8sZ=k80ZAhWUrD7(4|toRnIag%T@H;rFN`J?Yd7sGlX@`9s?S~er6E5iey~y^rrAeB@vRl z+DFHMh~g}@Q^Obbd++#*n|&2pMc~>vM2T?&M4PT!E)(~FOGdP9nm818YFQjz zfhX*+2xdG0r$ouDID#(cohfsGCSgEZPf(He+a2Er@&Q|(kqb^SLCwuLg7tNNY8#OVOvSRJe@gHrFj2F4byYJr6OV%L@uNhR~#ubb}+b}tac!fgu zW#=THusE0<)r^|jaJ$b&k(Za32svxeVZ=xlin`zwiC~Zn^n4cb!@wj&JBwY7OmG%L z+Oad`J$|Mh*TlD7v_Fg8(y*=ZW$#6W4ft_KKG>`HUMy>u-Qm+Tb3Jn0{RgtA8;Cwz zYRhQ0hM`Gyw-Bl-!sKe4zbyF>6_qnbJcbxVgBvs!9enI;*>Tn8`$@s4EnAUXalVFW z*4CEULp4(}K29o`cR(tw_P9tXPqtra?!sDGI~q0Na`VvHb^Aeun!uQB#JG;y#J_HY zxt_Fw>C?uQ5Nt-xq#zx}_s3{|R`A|$Pe>b4K-0f;Bm~ZUL z?Ozuyp7J#)_l1*rP{IRMyS|&{PQa4Ybhhaf@fhtMv{nB>@O%C9k@DOsEoltnl7cq_r}s@V_~SYw6r>~EgkZ^qgm)Gg@}`s#R<}P zolXw|jPO@w2 zm(alMah`uS*qt*|lG34!neVZ>4f>G;Ga|G4T#SlWv_=nKGfrSuTNccCUg%Da8Gz?N! z%#SQ=pM}YkVX;JvoYYu%x$=Rl+?!T8Ea1TVInJqprFCpG|y&IAmx_)}+EwM?ckexXpKUkluu>@0bTtV$^r(Ha@ z(-(%E06|`w4n+n<2C1lJ~NKsL`aaP$@yw0fFI&ZWnf38DiyX_toBJ0p{XQ zewyB<0U?q3TyH%vF5JXeWE6HN^?d5+Oah7D=j2_C*)^ABo{I6iFimodo+f>Y!+r1uTh;|UXg;Okekkccc)?++tK{|>REXR# zRl3$;q-OWwu65yNcfndcNI6q}H(6|YY3C|QwI`#iNGf>M%V`_{PB?y!Z}3DA7uzU# zg);8V2`cbLx0^O}emNf}B0#tOAJ>7&@t9bSNcf@@uj3E&yPT1#%_DB;Br zqce`&D&Q=jB4E2X7NumyPSup1hWY%0b{$2YXktJ=cjN;Jfut`-TrzIGPXKA?A$>@}5^hzJwzoOOREq z$^DsSL5>cm$pDsJ6mcyT*uO7YG+D(rLmakAM6E>c!R*m8W(w{V3f}&@KfyNwi%*i| zn{9){NFH+*#jmxo<27l3oO6LdO8#x`BR%=#i!ZTN?ZbS4sTqd3c-Myxq#Qf6y0HqO z7z+J-+JMk3^j#t{JFWE(@nliyOdYTal!P*7Y-tkoRkAg=m&Wn33Bwg$7?|w>;cGel zTNxjCV#5R~T^MP?#33rA?V6jSdCDEq+IrqnVpsaUXcW^}d1EC@(GVZ*ODd1?`wWA; zXf}FMGUP z(Q~nzkixshu=;8h+a~_fJK!FQl$?4XX@d_zKVu{$D+R{DYI7QX!xG`3p*SA8zIuf+ zimWs*(^19)Lu4rNw3US1WY07y&(He_W8 zg~onPY}bkt>dFf-C>Y3v_4_ZjlH>`Mx8mUyPb%7HH=9buJ@pxt35-zg*%yk%o)qG+>A{yZ7orwq;$Du z;RI#B`rx(*Ab=3Sl}mS>xok=`8R6Gqt8bN%Z!3-$S@nrccqq1iwtCu(k3Oz1R;_MD zhY_dFcv>O&IGtp}=pikI%kCvgx#WP-e4GY|H;~&W6=k!XSeh-&FPhe=EnY-HDV4Ll zH*h_}tm7kG(ct{odqAE$}YH&L*DtCLEZY{byyJv;A3pw+tg+Ng(s{tT=%Ka=TVzqlxT!jyr6`3AkM(P8m9EBpfzY9Jo;=aU|NQZ|;j3 zn+69w7$Bolelf}xE+Gp#qN!%WSdj9rKyl(l#suvS)-P>wj_b^Za_#`)?ic3_LhbKuSx+e#zK zJQ8Xgdl7kgH!z{|%w^0Aa9rU5j0pE4k#)x>QwJ03d;?uQv_$-8yUOQVz{ zJz)M3j*wJ`w8yWov#Pp;#!DIge9@?y+QCt+%+<~yQgN$4j01KhdPG99My&6dS@*(4 zM0+l+scX2Xsbv7$=me`kBf+&ndCdcJgy}}&@BIOOHJ)PdR@ikJFE62g3Ndwp5z=zq z2=#|>Q@cc-3;7vxDsW9wLCxZ}B%m)^9NaPh6q?LS5!*M6`BM}YK%5Lx;XnR~nIh(I zM=lU`!9F~}5Cd`1`$<4|TIF5StjM6@33{T6+QA8Wfr^Wo1~2^fYzZ$4hm=<+t5+xp zhoJ~Dq6qT_=Iz^e2r$raFfed`wtPm1fiM`bXqaSd!pa}njhy1*r^s12M4Z1R)L?y9 zaS6-?b!{pccZ=r1QG79(R?R!bIJ)n;b2v@g!N~Z2HGekG#AABU_J(wY0PrFMw zZH@V+hm)j9h+}}~o}oy0c2{)$Qd<)up?!r)_RS%8;v-u&MLukof#}M2dsOG^qF`Hv zneZ)7Rc&)v&$)455s#d=at5>tQLMLF91;Pd@{D#E3ZwHL@IQaIt682GzxsS4aBoaS zUKr3zJDWk(e%n1voFFyy8N}R_Esomu3WZVTx9o4fV|tJ7gq4YyML2UXm8%o2Pgv#p zRbIp@n{j3zIp9x4ur^?XbDAfT?7I2V7(bzE%ft-E5{!KYd} zJACp3G)TZgs+339^Q&dXTIAyaMZmIiadQ10gEmN~BXoc4f&>q17^hNu4OIP-^9sdq zbqFdg)X5$Rv>ay3S9=?Vv-s6Wx%@L%WNC|=Ze6+Qsavjc-wYn9#A@rF38%w9+b6tO zZN`274PB+oy+nNZLHZZ)*U8eUdh4GN+N$Et>ji>Sq)o0=b-P@p9OBV<-lezrZe};6JrlN0?ntCWeUu*92H2$d@VHKw8)^1}N{zt^V+(V& z$R`btXQR|iosM5zzZXj3eFm+Xj~mq+wMf*&awJ9bq`til;1oTTW!Wv;53Wjl$-f(4 zJ^Nw8jH-oTK2@6$eixgfg;D-jTSAe2al4t0H;|8o3y`mpzXGRBn$XIL6rV7HEGMOL zbq!en%2Qpm>>ea*Jh}ohpDNi~&Wf*`NZxxsqA#+JKNG_>M5HTLDKFFBDtmVp2%bh{?EWDP(r9z6PP1)0+3IT@t`tJD~v#O*E&RBf)W^KmFCr8tB4ogV1c6 zlqL7G7*%4C@4abr_O+VU0`^rjkvhSg6@hIY_iy@h?)~Aym;-t$@{R#9HC*pegaE>O$-$#lu;319bTR{I2yVr$j4u*>A+BU&^*>&q<_ z$=82-;H;!>H>>9`U2(B7!pQGWDZZVm+Qb*PVD8u<@G8AM z`ph6fv!(-a+WLmO%Uj-{|BhL@d~qG_fYXO?WNS zzY0QP|NqN=AHiwx?2F`=Fqwl*G(okRx^+tbzo_~DlN5H79TlSD7XAvQT0A$z$b1>UUq=%8KM;kf*40;KRy9S)cPhUWD{6gd2(w-yF1K{A%w77AU~><|>a;qe5$Hdr_-|R1S8$=jg{1B@2z$?0|p30sdP zM`|!Eaj%v8yxqw-slA4^Ymaik1ug7E@G+v%|xEtr@qCfb)?jyE<$(-H?`A@$r3w&eES~J~%*PsP)+KUkX!@{_$J#zL~i@oMcA80N}V?<*F2l?}&aYu%d zt8rEF9DRoMqV=LN*t)A6zJlO~^)+r;yZYe`v-+1lNMf8GB@-}a&x8A)&e25&#OM^Y zR0&f)x+~-aVc@J7VWXc~{@GV@m47~*u$`?yy_qG2hu(U-#HLz*7|Jt}N>b*<@u~Bi zu6VU^Z?|I7dmtmA0m5Dt$gV&yXBQs1GmtF)2r%wCGCMq^u6LoX=Z!891Jd;fCxQ5t z>ZXXyq)M=VTQ6HL{pI?~ajMnrPYlYgeUu@a7-7SWYS1A*pv{%qe+^b4 zE|=I7)_k*6ZR4Zf)n4{UTt26TG8g0n8I`vi%)0w%mPNGe+BR3dbqEUCKI|Q-l{l3X*$qV_a|>tnlBG{USMp=K_9U$cs`1qFFn_5D0`A* zEX%vcwBbL(-$5TeQ>UKaU7L8ealYU%^PtH zwTfe+=W&`BrRQ;aqOLiVw#DiS#5r4Zul9KPBH90d^WyYG+FfPGzRiR_*JG&dQ%iY7 z_fj*ByCd>x7uA!89if~xptCsTlyYDrL&{ORvDvlen>6MisHcelaVw8o#>YNVuUHd0 zW>`zO4BPv)Pb8Wb@f}6flOV!A&{&9L(POd{O1eP%K~)lq81J-xQe$lgZ#BXO$n!Yb zB+vS@$yPSeL58RYq=g&3%&o5CYyMGIjfI!}L2nWmHQt%Rc%AKcTgr>}m(RWs^)TI4 zHjpLP2X&=Ia~27$E&O&vCx}GrYO;Am(Kdt9A~#|e{o-COLcsd>ZYG+1dokBU#e?;NvnC6RHrpQxVkKYzvv3D zqgwIf+3^)lWq@v1^m|RN7ud2?A{`M$E;N3{cE%P$jZ6cwkR@2dSVKAy0E1K0CRta?5Z!V2SRTsljh27(; z4cinS7lmqdy(gN>1qKOkrU{AF?T=V2gj-ka@5Ta>r=NXvQ^graZA-Tq39GUg(J1f; zvxd#K? zAZ_l9Yxdf`S_~Gu;CO$6kf_x8oE`fjd;cFSAy59Gr;qtD)KC#wSBJJO`n6Xni%ufw@XYbgQQ9) zAMsV_=Msb5R7-DG3d}`{LS1IoPj1+)P{6nLUPN+q+nR9j*Dsg1!tO@|&%v|v2A-3R zq6PXF?L`ZWSdr$iMjxF9*d}4xZU; z5LSnXN<0@!Bj(0eAeKSEh&)hw63Mag3MScmzTom+LWYmp3UN%7XI3#jwQnn2n2u`& z|IFEMg_eVPxodehv%iAt$GrH~%a2<|V%v2jG;s=iIM9(N^DW%1dU&OCDnLUlBUJHyE~(>y=^2}>Mj32VX75*lsl2!mVu06TC$ zGijaKCEpl27K}F8=k{jq#7pZbfcJ`Bex;r@&-f(!aN2^4NHsODO`vbp0?zG&abP)& zY+}`SGe6D7;Q812Ec8XGX9}jl^6kRiIB;1{M7NuiEJ}f}r09d1KhM)iV(9dajE$6Z zx1r*wfKG7f6^Cv@iy>{5FRk!(#pAJ*tk0&XGuu!J128@=DXnd}ew`}r+WdQtnr0rH z-81vIbg46ZvxU;F=9&AgOf#S&AuN8?r_C{IfW1Zt{lU80>xxDu=)LxEOcgI~@0Op( zf)ycXRV)Q2ENI2LdkjM|@^rOw7lypf{GuG9b5^QwKL}IT)H+5}GatL8{!A4e3Bi>! zC^wS4iwFkk>Rnn1zgF2r6FpJ1>4SRP(#Kb+vGg7)e`FtrC;h5!-W)$S}S! zeirygw?E<@u-+`CE95M$JLj*$C{X)z?BNmTMn!5O!N z$jEkJmtKv)qd2`H@5XsDOYDr?k(8d4DsL9xGK%*RXrrgHKizP4cFD~CT>3h*pS}pk zf+*)blQD$_ufEe(n{*=SpLPM+i(IotI+R53Rs&%>AWFe4slJIxD@_Vyz9%%4`90ZL zN097-Id*;5vv5ATCB|x>+XC0|Sx?~Qeyuqxuk?ViD>^!lu%IMC{0#%lQGLZ3X6a-6 zIu#3!5*YyLJ$|lI9N(|kLGr}mV{(;$+>tkoxtl)Nt(ZB!m4g$!!LYgA$v z*%mDuRms6J3QA5FrZVoctwHO%t_b@k8uO6GHe|SJI4e+Mq+Aa&MBBF8rt|l>^O}yp zXA02EYJXgM=LkG}^c;4-{jiYK$bL>7ph<1G~Ca{Xf6JD7sXGP#2 zXxSfd5E@DRFuUmEVxX~FmDgljWX=7CbL9f9;c@R*WBNgxsG7*w`hql)RzakN!reP@ z!&`>gIBOT=I%x68bq_+Vf0FIgx2onr$4qb>z6Rr|zlC&D)fZ3hFo)CQ36m@j8+Muy zYfQb@MFBUKSe9}jbmb07Y>#5xX45lVo#I?&6_pAZcL>)juz?7H%%kk%gl`VeIc|v$ z!D~?l!SQDl13U3$b9MZ(xwxQlt*o~Eo%}hQB4&vaXdIu0uh=KU4z>cxFWH}N>?%+H z!IG*xqb~KDtCjWNsHe$b2j&I6sij8x)f_@jh+}Nbfz{%%cfF*%Hn7zl9hK7EAJ?0@ zxaNCdX=m~Zev%I!&j;34;*YUB0mtL^ za!*007aP97wKV)(h1mC|l@Oao@PX$*g z4_f@G%%S9NKM>{7<&ZBJC=|Bk>k$?w`4V7+^QT=inbLR>DC;y(;S+1vpK9frC*J|g z)5OV>l+&e^*nYj@f3O<< z$UfLTIepOX;7B=rtMm_+-9_xAt_pfF*5yw=uA3MA=RD5YcPn=_@Bi)UdUgMK%rU}9 z>u@E)TEOT`&5FXCl4xnx0Y4!5qc1;+v0lw;SKtCHy{v>UbzH77i^a#M+AE`9k~6pD z$5hOL!v_J(I?RmZ_y63;@o(c8rm^&$(tATn`v3V7b`gwJfIR_8oT}U3G}-AAh&K(= zR}m@4xHnKHd?r3tCg-o1y6n{^%pzUqOFbG^^6DTed`v*&Nv1>Gb)41YtYSsZGB!?eoOYJh1Vl^tG;m9 z)={pPFq?DS%t7nuLz!pl91c^&F&SW?-RUA@&1nQIcmz89PR6rvqV6`6zU*AS5lRz6 z^*GT?m2|YmCL;yB+Sg$=HX0H+-_^J7NA=E;q1&oYLE;sVn519#t7o+o^NB0C^QrgC zfZHK&VO8u8bW-HjZoVRC3N=jQOZcVvFY5onx{nG?M?72v+1MGy5BP9r=l)*}|HH}l=u@7KCvyY!#x9GX>DtV5@D93vt{N5p+DIQ$>& zeg26-$s~*PR?zvr*P4#u5xX0(PNMeA=U2{^sOJP-4_^mGE9=C=Ag*oF%GQrHI;Gu96yB7yhv`pJR_|^IKc_oLKto zpk=(l0$FGipx$rseBQ*vD#j6I`Egbddl1@I&4l~xF134`Joit1m>x05dF2VO{Mbw@ z0%K58i|8q`{f(HcMD4kE;pKusLe6a+r~3=bus*Hp?rJbEsiH2NL0l!~ay5ulP}{R? z@E~T?-Mh6pcC-oqIX19cMew+(7mH-|P&**%!)k#ctlvk=AkYqynL2Ge$KtHLd8X;| zGS1b!tpMyi)|W>@n&$WxXr|C)bIDFZj9sk-!U z4eNWNc&KIxiq!tdfHEGTVKwnNf@@X>J^lH;Uk&cT^ceue`#L7_~q<9Z=+Z@@f>Lb)b%BE z5=Wd8u3~(Uq7bFp+uE-qMX)pH@`0f}Zsvqnpl^1^1OamXrXLi<{+NIJ@Wt2Bwx9y0 z0#TD%@@JDkaufWR(lL!bk%{-BnVtssW(=i zleUnz#vNt6pq%Mh%g_iy1}V?F)El%3#RbiBe61RP4Up{bhNA|AnC z`DDO^$)BegLB~(oouYXrR#oZ6{m6@*KAx|8>;mjVfivsCT|1h`8^)Dl=OYzk>!+hA z+~Du?E(Ip-jHo2(`>t0qrn3 zogxe;13Dk5l&hGcvK)kNJ8i`w+li|yoeuK?Y{rNDHcU`J0AkYU7n@SY3wKZR;toG6 zZ{*>@1A&40QS%NhWfP8c1R~WpzQ>d11CdjYe_0{Qn3NHMaGUg=)W;Z%$ANaz_QXIe zCS$>z>`?0{^{-_ZQioOIC^a{^Jy(fbB~5cyXD(*F@Xi}BRX#5Dj!=3_1`ac2;wYu; z{pv?T+RACjZIF7;3sfUzua7K$V?EzXUwx+Qko>lrYL(gTjRTpUzc=vm357@#zY1Ay zhrtH;H`TDvKzi1chKD=H^G}tc&z#YgJDV&kI)Isfup+zWW1Si)$j<@sAec}vhOoq8 zSrl35XrgaJB3VoRb?4s!x9NH3H{NTUV(igPSx@OlxX>S=KaaNV3JIf} zb7%-arLWHof!*sa6H6WJHkm7p;fpY}GG%XFM=-BUBeVQ~>x2FZI80L%q=97cpNd=efr8db+dm2Ebpt4U90Z@UU|=NEPG)6gX7epd3xQ+@@SCPh#TK$kh09` zZLARK@#mftWy$^r*pxOl>-TI=AaD{=mTo|g>ewTSEG;jzNTV}(ix@V1%6w3G5Y%6> z@K~r|H+BrpX&qmrG1mmOPD1?Wu>0OO5{SMTl@6&JE<-n*snuzaw7AK`s2lzD(yI1D z=GxrsS&4850rmk7Ssll;6U<>i=jTcK~b@h5B@u-dH9ya@Oj|8b5o2 zr@S<-zu)5SWP!-C^Q7Swe7{{`LKAU(M@@IDGAi7-+D*A%xju6p<4JF-7fr`XE9>#w{qO6xVF?=v^axD6CLZsb2z z_kN8wWa9MrY(vT|HLkBLC_9u$$gOT=Oq|syY)fL}MaziOr1bTRb+7Cu!^NNliprV) z$L{JYyKNb=b(q{gh%aYfnGWsBzgU`JA)U%P9fetEvo^dg^>0WKB^qSRqZ}8CGGr*# z`JM||_9B^nqc+io=Nne7C}<@NhKz53BGCKPK!G=*>&C%T+R4^*g!!$Agf}v!*QQ1v zSS8MImix?9xs_oAf`p67!pLF>mqo8ScS7T1fX&Y*D-rmNd&L9PjbggfXGXG3FbpX9 z-xQw+!mvIR)ms%V2r%gz}pXkQEx8E3PB>k$2&CnY3;!P^HBx=};lY7Rx z3RTTIS4g90fbihbChFGSbk4MTwgjpwJC8c;*?B$}`2GrDb}=Ei`^QMH?Ec6=0pcye*>7J^Qtj zMB~C4U%wl%o=)(r;9bhoPf^`qSwO^n1@EKoR*?`qZovqJutO}4wiHwxD=iFCPCwTd z`T??KS|Y&|yr!>|T#^06F?;&DH7vYI)9NV3kd*>hswxwcp55Eam9g5BU^`>0M|Ijb zUqV|c{r9xQPLYmeEBCo9bPCT9t(M4nr&XlQ7)pN;$<-D>^{6Oo5FbOudSVhu6qg=R5B|IK*^e|( z-lmMQg!ZL!-pEc#X?eG^-(NAsl<4rqFr8*OXb*Wg)-si9Gm*1~-TN7Af#txX?TD-| ze`q7<@CZv8?R%>?naZE-X|aEt;@BQ7g;W>j#$E z$B;LxgZi!uUo^N~Ybz8VyI9^ni>>)>*lusi++1$L86G@fIU9M+gUd zdEFz)vFsXBCQc=L{g0_&wkQl$FlqsNgec8$*40!w-^(w^M|_hQ;~5lEw=US{>Ar$j zeBiAs`tju-EZMK6_2sr@SYZhNKo#hTX5=}$`is#gQvz7NPXxqqR`1e4UAs*~m)HDG zVICKiw>?3kefJ6XiH%EiN8S&d+1`#lKh<7_Lq9idR}g*+?Q)wktW+ua9gQzG5hh-|RgHKGyC#$rq}n-;DPxM;b$1W6otobg z&GCD;c$Rnr=B${G`gOhCv}N5W9BU+GHf{h`3UeM+l^o83(6DoL*X~?;$ae$Q_h!~2 z`JI#zcNit*6Z(K;R|OM(&08tIX#Ft8|k@pWbx$_Y8|IqZt^$`CZ?8sI8l_ z#U2?46u!~+H&8>f3Y{}de3b4F_;d7MC`aM1xe+8&%W>s`b94AVSP#yVkFCas8GWg4 zXpG4$30DVcMHN%(7IjGdmq!4Ik0HWObmW1n4ArWL4e0e3YJfZny^Ug=4!SGyA~FtU z)c(THLLR4_nR?jHrwSu%>Le~P_)B$J7FXok)=542QPJ3o!z~4n9S(_5$(ETG;CQXN zl3*0OX78%Tl7&w(UEb~)`>Q?W+Bgi)@QmQfsj4_*q-G|xG9@Ns{;Gg4jczGDI+^lV zV$JS!yLrl!-i}L@vVE-hFLk3KaD~3U@d}#VSfE?YB|TT@Th6xe5WKqAmVsD*NblyE6Z-be><9Xm}EI*u^F+JGjyA(nl+r@ z*q3L@H=FAy^Xod+&Fs+Y33dGQq2H)a_XRr$i=v=PhP1bSIkew%f4|D{pCe4fuX?g7s>X=WhTvBIjhm z(8{K8Pm%ELX3MWw_U_9EdLB-;Z5iv&CN}g-YdZMXI2FTHg9@H?gh`FwYR}NK7LIP< z6Db9|mgoqjNgH5{f8TKW_AP>N5t?f>tZY^II&A;#(`H3GK*r{ia-HiB=-gu!=|cc1 zy(`F;lp!&NwzLDwRm$j-`xx<=k?n-7b4=c+=p0Sz$HBZ!giGJSr4zZSBUgwnQ2|=x znw|!shr{8`7P6{q>y@uL?%)FOqBG?kJ4`uhv#o#2<8l?UIP-NH+GcwJ` zQh3zor=y19f&Tl!$J{p5jIZfJzFyHM9PZ5>A#=zsAg>l3ymLbZF84jWm;q}ow7qKf z_=?UOMbk*Uup)Q~1TJ4V?1gNTcjZ_mj8eGJw`SR3(q~=j63_M&FI|!$o0(7Kx=q0< z(>R=nt&?vC$i^31`MC)mgH>|92+I_;47oxWQsiT5$A^`3nPgdKI)=v-p)n+&1W?n5>aO&Vj%Ni?eRC~ZVy!;Ft<9LkX-k?V(vG;# z+5bwN7vMqc2)pps=*t<*l51*cY8iFeRUBFhP`VYO<1On=pSmd>>?`Uguj4c+{484R z)6GeS9ObL)!XrMutM7f{_wvgXKGSf5^CvzUMZ<-U@%uEH4Npxd2d%`NWxhe3wZD}K zos&4}`!+n0!*gT=c4@>Us9&A4rfyvFWc4idObhKZ7Z9WJ z`(r$)cDxV0AtI~&ithtX!k_FKYLc%0igj5X*aAH`@%sOM%K!Ee>Lmu^R=VMKcN%iE zy!~q6Mxz;8FMXCazsa#E{g{m112@t&;hcaAK1bnRu7<9{@pm}2qYGJCQ!xG2a#Y)QoXd}aSN8LgCyaepMh8ZDpt*PBu_SSGlZoLogHO3 zPY}}?pIB+TOsw&|e6D&f@)M1#MBgc(dT_WWERu2cHFLm!($=%|XUeF*$||Gx)7&Aq z$*rJKUl{ZQ7Pg>$Z<)AEtSznZ!^K5-DzhPTi0_Wx|K|AlZ@oeC*#LJe@vlD)|My;; zzfKLz#t&>2V&7l1cq3tw?jG zFR|));?RQt11*Z6CW1k^d;umKcjrsl>h8 z6uoycYrVf+f!<_gk zVrZ}BVSaik$7KR9KH;XE6~05gT;%$&Ul|wSn8X+?&0pM_>>}RrTKd`Yw_uJ8zo9Gl zK^F}^o&8bIpD4dlG?S5eR%@wbf3xSh!W~+NlG%AT=;qnqNWU~oC!mFvnTldq9-;?w?XadDi(KKi_R3U}u%FZ5zTF*OPb(ySZ>0cV<> zfO9L3I3z`uqfEqlxb-w6M%YfcwKTn$6L)a&-Wg>(5!Z7q(#f4>%A=K4b^l!Kib-nh zdKs?mtQmyd)_{(NWS{htj{CcN=hBN~-!+iu7lZ_C_goX1K;F}FWt(|ITqJ%z<=*ZG z$A(VbkQdIWYpu6%>F0mx!7V58I4BNkb7q-~*l>L8FkAd(V=4bdGB2yh^sF}^*KTjb z+_r4>m411#>9$)VrD)rW`=P*soXB9FoynfbIOD-5G5w{>L5W|Y75*I^wKmPs2 z`yhg>#2#C|d=E)#1gsC%kBMz_s^$mc3d!r?$P*pL>kdfES!<=|RmMdzhm z#-tu)8?EvYMUSpIm%tJ$?z!UxH!bHtti)7>MFlN2e}bnmN?1DW+0je9mdDPVL_LI? z#Q*DoXrxK_L@?YT#MkJJui;zQLv@&Vc4^}F0WLZXEp5M;dW`nRO?s0R>1gh&G^h{b ze7kw8Uur-ygAZr`c;GXj}V4J=0U*araBr1XP3J$Zfh0w(gASt2XKmOODOM$ z#i>Y3GyvE`a*OM&p#? zW!nm|k~7w5{;_kiP9Ntk7^pRlsKUzP*p|$H7=FxxKm_t^Mr8xC>VE_-?qUK~vUAO; z-5m`+Ak!n(g4xxULEIQU^}AUTg-d<8&hL_TI@1MBgt0RjfT9m$vrI)JFT8J&rmJJb zmEFY+iv~P8sxYm3y*rUIM_SLSx~2`wxiiAe`u4N^^^;GGE6#b%3AZ(aeAhOq&|j;52jDav+Zn7NQVG*<4d4yU4? z`z3SuigEBfAO<|R2c~Bh_y({yAidD}eobFcd%{krRx>=Hj-}0ZxWd;Q$77g9R zDM&qQ$zG*Y3cLKWZc2~yVuw5Ds5zp@H*OmQk}x)kbhB4wkVQQ;@OAZ={E@4Zzvd-6 zEMeQ)D;Uhy*~MQoq(kpQuSag{{9gt=IQ(=fgWfZ9Z(JL){TM8hm0Y2fzV6&cq4g%a z#hn0Nbv)(^ud&BSm-yjO@9ep9TBCF;$GU_jMN|A-9TpIYPdq@rIt(SOiC-=m?DYNm z{XC-x8B!hS15TX03JFs!D>-Cca*y->%07R`kDzA!CU)b#XO&F>rni4*U554}Z8P~` zS)Fu$*kTx_0Fc} zOTH4rC5~9y6z-&4GzzWpB%}T(KYm`^ugr@6YKpw)@5IJ zpXzX``o6sW>;?Gi!lq)s(Ggm?yY;rh5j)iFIk@_Zg53(GLjxB$trnw8T^ zX`jPE0kBC|)(EY&K9i}iQzv=FBC1GTT*?fhx&QoCyb)ih#q5@I$7QR}xTf{eeZXwK zhA~Rc?sfb$W!9^oQW_QbvZofHaF$%4;tFBszXP_wbR86I&MZ2Cat(#Yt84|1Z;rd`i~=~)lMI}NR+dCGuE<1^Dg z|NnQjKQfuU1X4S7x^UC@O!5U4l=gMoQ=?ae5OsqbZG3`nneDC{nY@;o_!K!QF)ubk z7jcd8o`q#w^r_Z-bztOyC@@vN7SR@^F*$j>rf$)LS1_J4myH+K5;7a(9rNBjk@PM3|hpf9aGxGv>jLMz* z&95uJ>^#me>jl?^AsE%-{6AP9_heitL9DW9ut`xDZ%)hM)^5~{;~q7Gm@IvcPMwZCGmX)14 z;xLU>dzGTm>PUetbRChd>~@5PE63u}JY$rpJI)<3ly83fEw^#psnf4t1pNlZDJNA6 z3GPo`b_R?ecHJ1`1SR>ala4UqhKLz|*gYifX>(fg*7BDd_&&_*pULd39`NzWf`d$M z67%SkeTzq)68QLOjv}a)`F>y{n??6a*<5BQ51R3VQJ{$&-#<3O|odx1OTnWq@ebnL#ffwootKUkyIc@U16`0VUu z<4WF)#MMcxj>!K+@FO7io92(PWl$`zF=~~PVX7DQp6ul_fXZw+kbAG{lya0->IDgQ z6!U?%84LaEf|3$a7n!I%vf@`1U6Mmu2cS?ImGRO)zrsa}R&BSb|Ck_>NPWxCzH4SL zfW2ERIznH^E)pvr=E!Y}D%XzI{cZQfjvoZRs_{?7DhjltX_j?U)H(c(G)=fNthviLVKpXd{_w~7N;vks$L2LEI14Qd); zH!$~Y3Q-rV_tVdH6y`}&6{@qTRexF%Upvxg3c1TaPS7|3vos)0I?a*xEw!u1>QP{R z`RZ;BiAQ}d(lT_{MV<#Gra^*Vr!xUSMyx2!jwa|rC0p#+%Nnx8vJBMoE97lRE1~hX zCE@dhNwFq)0w&NQLwI-i9bl#vlGy-K7DTJa?uQxhZ(?H|C%j_R>q-1KzK>I#msi!I zaj6GuKM@IO3gF{uBT8q`Fy|Jcf22F1%Kw#}S4_XP`IV1445VZcTA$H;01W?h!#XLS zN@-_Lq9G#7xEegT!}g!F7U_es#3gKBzHG%lgf6 z&0b8ug1nX~_FtGMp4XyybQiBtCFb?!6U={3xaplvCC-f7(@MJT!7)U17QsrA@DMDu z*BM@`Yj+&kzy8HB>D3y?A4%QkfC2s@UiU)i*~(KSNj`r3D@5cGCODJ&g~b-IEO)k; zaW7+nv-p_~(&2?Y`PwJelGFY`@q$H!kl{aA)=p(Hny(FB6_B4)WCVUlZv3F9{B&(` z#OP6-Q%jvw>|ct8dY)Ym7ezrq@Bq>k*vGA%4=){un9$NL-;_~e31J9M+%SdQpFyEl z0qdnk&{|DVr{B}x4Jd&RW+Rz3mWL3T|vZhRF`uu1ZQ?poNGk2 z2y}G!8E95aCv6|0GSVuOh?Wq^9=6uUYp`3|ow|*O((q zd(LeA!#3pH0(A}9k^(na~^1o8(hafHoJ1&c)@gMA9+J7q}SSp>>B)UIxD@& z9URv{#Nb`>?I)>$k~5S0jVU}lJ!L}wTC@;m0xGj#RcT*JT|GfN8jn0KTf7d(d}CDC^{)pII{FZVSM%H`h_M*` zb%Ml5&6L)gm?O;|3abez&AGCFHn@AIVF{il7uWxY#kdSWEZ=fZJwcA9)EPKL0fo+B z`(BGY63BSuj_s!nK{N2MmlEmJ2E&1>~$kVtU(L@r8V;KI_XgwBD_*NE&(z-T_-&>~^& zFoV8FzLO|nz34&)bVYGuq_rHmW+Jw@7Nu{bCLt})XYRH&g5&S|h`2R26#@FBEw$T7 zx6o=bz9w=eNGD9?5sLm@u?}xob2)x?EU(Ac
`CDJ_d=DKhDvye%l|5>(M?n8gj z_`j=*(C2{_hrjehzC>`Qk-;`wX)gBc+L>w$o;`$LNuM9%9aEq(1ub z7uFK}Htb@4Uft|%pL;1vqtQ6pbdNTj<2}$S<{m$50S%Qcp1q{nI8pv9QfB*`EOqhl zEG1AFKve}tWo?(wG>FP3Kn1xbQ~dJB1xh?T*&5hJ(bB5@aY(^6g}GzGk2)NpS!J4; zVcAiefx~FXb?4stOX45o1EOuxQQ1XjYMZz_2PJf_}M^O0ekzo2G+4SLp% z*|zlSYKJc5W+j0)VQ;njC)eNq=R=wHETmD20e`pzp4$EFr}5s4$PaoVieEodJvxSb z#M@^Yt~q|P8<}syX<@Fzzp}XAi1KO$h3)ey$W^`6@+_mJ`MzHBi-r?NsyBY@R6x1O z^Js&GdWifAjkK^3j7yi3s`n05 z;r}70hz>kX?Wn4B%Olf&_P(<$AwlWiS2Gg&(Dw(R{#P;imPS|81mWRmNDLS!dmPzP zVg1AtUH7zJp>~zKbI2*7s2O|E8Z(^97JsQoxAuMSkZb#slQ{rIxxVfLn1{tIhG%D$ z2OOM!Sa|1%rgmBfc~r;ml2A}Bn=lF(@(Y{9%+Vxn4Dl&6rC4E#2z(rbev9UEfI0~} z;f1z$)74baYnf+9A#DO>$>tU#v796jdCS+No90Pvj>(HZdXU$7iZr+Hq)I6 zSEK^dONn44l`b06w48oGloK6v(RizaAQe^7Ng@siDH@}9VYQ!iX4k>EXj@bx&LGU%+Nr<3W>())4Et0EeHdVTKl7vMmbG=>0^il+URTDJzTB9{ zqbOn@vi}&vom{)?Tx877TUw$Q^<_OuE5G6Ks60;N;m_t8%u_24=@Da#A&Y!h&Iu+Z z6MoEg`h@q`rsbStB0z-A&nu}p(dX%-TInyju?^{~A9sZrVtw{o)0)p0{%gZbU|=0h zmbw6L*#N6vPB3;AEhx54_!Wu-wu@3&DN{9$pts2Q?h1Aco^RhZ#@jv9k6TKEY8Tza z-^)(T+)ge3DZMoqPk1A^-$eKPJ#rtxhFj)^A>hWI8_%d!SQ{{mVi=rpd|jed(F`9u z?;WX|_T`7*VR>auS7Wlt(_>yHjBZANZCYRz1%8P^xu{}hQVb$>9o01p-x?J>Z5A%< zS1K0!z)`!T{N&Liz&vr3)<;bTa(KL>1jjG4ElSQj%tJc(2Wz$M=LY9zriH1N+UkI= z2({eY*j!A^KF+dcV6^j=M)}}F+wG%Z`5&?%cLLY!@Nd0r{Ne@fR{FE6K^6RWkiSGP z2byUN|}TYPGaI`vSSoQvP7PrPHUItKkVcDkH@{x==?gh>OR z1-Bdp*>#n}9+lt;%_{9uJ%{p69vNy~`wRHlhrvVGLh+TYR@6$lX|m9^;BN9*CE#zx zMOhd&>+3=`GR7n=Bj0GmAC?(C_6fMob$8o)cjadr=h|g(xU2;*%SYf38^0~+Pa?#` zT2N4a9PgToVY$VN4al$<#zf1_@bM8HdkDEtI8>YGFx+sMVeXZWlz~H%ukdYp<$EUa zSiRfy{@Zbj`#t|-L1!FV3CM-uL&v39B>6Uh;X(=~U^DAt^i@n)#nnS^SvJ8FBg+r9QsOIDy-#vrmrr_y5;6%j8u`eb46>| z>;LfiQjMl#J5wNNkz4n=DPBr!R?A&(QCg8duWV*@iaHA{ zW*@;xbs0)Tw_inN<1M?rOU`-nYD{uO#+Xal;Yl;WFsMrm6M1@n{EMUHQ{#6G9`jvt zcA2Tt*xgM}|5P9H@1{w0OC{@1$)J|kqBJP?m;^VtgVtR|HX2uMT|=@N<~VPQGuFNr z6PWy)=<5pu^C@#Nz0h7SZtj$#oyKO;1oqZOsclVr*!Ck|+4p!YYIe;CZn5`IQ~~Km zB(qFj1O5xwjX{cED*+sht>N-ON*v`kVPvT`h5M_ZbA3=3g2T~>hl^a|c*H6!OrOxa z^LgsxXsiq3k;YX;Y&t}PCi$QlYrwSrV4jCgnyv~pkYT(cUO5itOZmh`J4LOT%~#-L z0Ce5etKa8aRA{&{%`L2bU(U_Qx~EhcrsS!J2*`L0qM-vDmAVp_>!|5o zb-5VL397q^oonJPu|RRo!-dB6)qWJDamNkDHJw9r;|*?A5OxRK&GZs`P6Pn2e!=He&tj@6I-KDX+O9`xS98&6IlzstV&q;cshX<@abGV%HzFo(OyC# zW)2sIr*UHT*Ugof+86M8$ifcMCOSE>@!9_C^IbYq6$Kn$J`hKvwQ08Zm^FW9&jJ|8 zkq{EfIw%|m;=&5)5R@hOY#`pRZYU<4jfU{5v}{;TpYf(YD>oOh1{mPx4^&2)ev^i-Wg2zH5(uBEt`OH zIPm~aXyc7h`S4*Gc`Y;JYg@XZ+l2+57dP)BCP6zv#5pbl546IPEC=`l#@oLub6!wm z(z2d28#Q{b<}9l#QYlV{$GJ#lGj#w`D(b54e+_J88n(K;l!U1xsia%RYX`4C4;*w# z@3gig*!n*-DQ=Awa_ApJon&E%b9FnsNuqFGLA=4W#k$};g{L_OI;5}ghS<9nq+I)w z5}@r0qjYAWEV$sN$r|lLn!)VsBqyMd@c2NM_l9j6 zp~l$_V5Zd=tM@$;m+eKiX*XuG^35)}7s%rJsnioRZWA1+PDAPk(+-E?C;QVB=^*+mh(ubkr>n9cbhN`no_U%vtA`-!x| zl6;cD`4%1f5tNF#3rU=F3wOj;J5u7W*6o5a3W^0hM{$!POshLPnGBg@0A9sCGlTUf z2WZw0)9%ulCK}q^sS)K-4tk+|{;#JRGzd--qBGtR%cRHw8Rer3zg`lAD7%gw7 zTkjfDd20_QX^etTcG$J+5vSJ_B|)@m1Gfxv`t@nByOwC-bm9aCIgw+z1as5Br_sNTe}-LWyRO3Y4I zC_dM)`W-~Pl+mfVqUSlj@2Iz12^7RrTB!=@phCe}^#ZRCi3cde1Q_5VtBhE&Bh?Ai z(Y_s*He&il>XF)nd*&RfHT?t7L&wPd5TBPgR<`jH_gqUJ%AboSl>H`gntZBwqI5tq zb#lA+!E?d}ToN|~Sp`OMn_Ojd_FGy@z}=3yT5F>>G6wrGEnYR!Bwne@g0iQirPG4; zQ3nAfEp1LR<9Rj2sW;{JQHL|6HN-$6uQn%x>l_1K7N4JkZc9~`azfF^cDkY7%7IGX z4f%?eGTk^*J2b^+v(8~f8fA8lh$UOC@!;@GmHMs;B8j@=oP_-|E>eeO8>mCHhCln6 zn-TVc`AYzgNZ%aJ&F8g-Q^2BdlAQHUSCE!~!gCS9)LgUE=%j;Et#B%z|v7 zd8D?@^jIN}DqdO__wN-1On5(Z;6ilZ!on)~Hub~GZk!QLsOH_J0XGa9n@-Og9jRJq zXxenI8S^8Wzu!v23OJJ)WW}M^c7`1;_glQL)y$suTX?Va$y#v&3c$k-q&0LW|Gnn= zlvJG8(62|6(VcXX{r#k0FDDaBT@rHLOe*@Bbl_=7@RBi6+q;>-y%{)ulrM7F;QYkI z4q3#&4s?;qgP#5U&`0)Yf+>bDT#Q!C^zH&hHajg#Zrz5THjB$ZB7H+gI62|2QwnR( z6P2CN@do@V4?ND%MI#f9dVTT=hK=c&z~YCKlC#;J>6_u z(bAZDjM?-;+)-PNh48--AkTSf3GC+Yvu@4iu<7?`>N4YR`uNsc5b6!!3{Rj*cn+U9 zZi9hN(@<=DpiYCwbhS%PYrx`)1pOV5zEUk|uR70hWvFF5_$x3MDUqPHdm;Np{*2Qw z&R)UD2-=>AI?1NZKb@0+Fx?Y^?u$YAFylTx#K2$E@4f!OK zyf|0uK6Li7pKNW;T5DKml%``P8F@VYZl|{I843|yr@YwmWV!5}^$0L?o{XoR4}*mY zANvfp8Lhm(z0jFUNV+-HH)wR`^8Eu4dvzqw)cFjdXz>h^oFsc@z^H9AG|M-`>}OGt z>>)I3JS#@CA^h-fkv&zxjrdak-Knz%dpR6gw(tSSX}CZNLV#ews>vb9ux3YSgSi%; za?R$34TXGbh(qdB03>TODDzt7NkSLZ>3IV^*DF1SwO~y?g_29;$MK6xWCq>O5f6_) zsw|;rY_!>Z@-cY)R}RFjmG+#il|zwP|5|*`LSM8b0LzvBUOwO*2H{-p3HJLz5>0I* zBfRqZFp*yE>~=dt)GTnP0lbf_#(SUp;q}9l8X<03Od+IUNclT5{ww|?bNMSi7_$06 z0Az3zcIExvVe6nP!`=G-Zv%$x_AWoNTp6GKjpbl`{RD|6-$C6*HftU94m&!5d>xBZ zE#xBX0WP^T5y4_{iRlMb5RcACwO+SoycV-gvmeN<&kGz<>+rI|BdDR%33fnRsuR@e zJJ%=AhP+4Qysq%Hms<5lLYB!IQ+I^TW}@p$?G5b(Z@VKPSN8J3>|XpgsPB6EU391c z*AWEk-X7^w@Ai=6c%N#VZzb6z?<$g~OmNS7!45(8=C^-O`??G{JxsGhWQbAKf8pjf z?8x-d(uvfNbM1Z+wU2;KB5PICan?vb&qi-^-lHsT$tuaKv>@Ob70jM|$+ot+)MbhN z&VL7aJV0rgJAV0o0u_1^-?W^$ECnXOcbWO?wgdgKKFltqbtJ(RU>Rd<-v5QQrCPC4 zF8A!GNeZ%hWTdbc%cy@SAmEGqT3>4(ZYRrZg%CSqd@(b@^Dl*u$l0}tJ?d*uYN=EF zIn}u3aeotz_63yVslSoS6@foLs~&dbRAK0uoTL}omo7WLq{};a z^khZDu4HG|e1x&M(6jC!9OeOYGI^0yL1@6A-ZOv%#-_d5+0p`N_m=w;9l@o^f62?m z3!!Z_)^CUK32^;?gF~y{)}GwP<`41z0c_E+;bZW&jcLB0y*64va+aO;Nj5kl~k9aq~;x^U%UM zP_Ot~?EIqDGMz}2)^j4a?^q8X1K3Laq+QTP$ zT|<0GLXmc&M`?PbpvI4jWL7jX$49}SUSu91RONtkZ`-jT1D&OL26wi`U+E7CQAPiI z*IU~Yqcu1#(#;x~d91Jr)iar`e(Y9uPXWKI{Z^@1HxYi3iNiT=nSh5${|kEk2QVLE zOEO&wL+9<;^Wk13)Mp6j}boOG%4_ zVtWVoj_-yX5=XP1$bb_S(J-kIOP)OjN2JU$c5pg;d#TxwgK*4Efto|%Ra<7srBt}V z?8tX*lnBvH(kbCL={p`IHwkDOcYdb%z4TXLNdysCYTD@v18lp#&fk0tvP(oFNzUcn<(yDrI?%|7i^nd33 zrEZH@0qZVvR3Fx!qZcdugZG1v?Y8@89zO>kn_ohdlD3vS-F6$^1 zwn(I8;%P_|GNI~{rC5n+qv!^LG+K%Z?moQiOmd6bzZCfYmHz%e6)@=WaDQDod)CkUU85n5Nuq<27UF z0Ib(B3fKC?;(lZB>pyiGR>t1r{%zDjU#F!%#Li9C4oA~eYFQE{b(+CG_rn8lTrXnFrjwrx+&M!W$i5OO~nf+3W2?7SqX z;g;sJ7DZN;Rr?$p!^YXtyOTCoa|>7lf(NlMGK%sqrQ%z;a)CLIuU*j*I zIB6?2{*0JCp{nVE>C9zh-kI9x;he{DR@FgQ1PfV4Lmts1FQ3$~8M$ zB3p(c7^D;^>-JZgi-k{0?a>`upC=$vJ2-8KF=Zzd(Z={)udSnkMqlG%y~}}Z+e_ow zN&?eQ*D;YtoXx6aQli@+3*>+;%g}FH;24D>tsMH|Ggsf#4`DTGJ)n=l{q5T6YE6?u zE&G|z&0LZ_Cq%kS4cQLs_J%BYXFpD5baU|6Ku+=rg?x?DvW{(NLfGp%dRK3@fuNsp z3%|cVmnb!vpH-RlmwSyd{Ch_s?K_O0uh{cktmX4lw?M9eK1P#Mu~am)XBZr~Nh~#h znew~7)q+CC9u4*s7FpjWoa#|eLbhe9?A+rY0Fo_Nr$&MqI?na?R)mCsdEJ}?RNA?d$Ztx5 zu!|p?vNkWDC9ZjoIPpT&cFm6Bzv=8ByX0b4-B#hHf3q&-PXjCX9L=@~^?cHx)=XM* z;%t|7RG(=gcEg=`&FTjnEn4gvut+r%tDo<+Qk&LdK148xO!PYcE`eB8!dTXt{*St? zA-UL4-XgpPd(}UBF+ufzQal zBLB4{^pj2cHj=Fv5j^o5-PhTc*t;C zTjeIQ5w+>#I&-8|B4{u+JL2+f0cMjsL99X#@eg%LvulsBEq~27^#utC)Wy2|A3!c1 zCTt=||FN>3-ToiIrhsHX`n+YANfD9O5(`nSf0wg_M`n&?FO6mKN9<`}kgRq!IrB1E}K3U2_LGuH_ZhJB@-D8`jwm!%GinP0eLqnBsQ0OX+4XEx)`n6g1$H zTkf>psX?IEDAUE8)dKr{;~wV(v`@ze;kIWk{gZ5(8Dl+iu3zO}9pA(>ArHMtb4Gh^ za1^|rXGNr3#|rN4>JbqR-Xd(9O}6XPqg2Nxm9>;aZE>C#zd?TyNe$8p@9*Xo%xmY1tpt5$shco`=}& z5;?8W)n+#wk}0tWC$Z^3`3x5{x4Fd}VMHzy*#Due#y9xY7AsxH`=hg7x8B3)|Fs?< zrOQ&)eLdGd6eOoIzCXwRwlAdk!W8m=51U%JBG_Gc|K|-hB3j5oyzFirEy;pQfzJOD z^8EkLE(2xJ9|6U>#L@Q@5s23+2x4Y7o|&_#o>IE0%Kwu8HU5(S<@qUpif8H`f%e9uLw-T&J{(?gscx1CLdh}QBW;! zuIk1Kw*qJhOhb_YyStD<7-3)!WlK=|XM=(om6cDY-|okr58mAVhXQ;XHP57XOr8A_ zhySVkf38Sf5F-{<3~`J7>M@19vwbwIYR$&?3H#9^3LjP`ZMke$;F~QjBM!O+j?aT$ zQRIi@I%-_=XZ1K@G&@>F$YV~Dg^qxF5l<>05w)Lnc_7W(=ymnq9J7m{+b0Qos09qR z=OG2Ve0$^1)%L)H#~>Nd-cV!R;u7%Ny1`q@)pjr^%cAA2cJZgsOdH}_I#$?m7pI<} ze*g&6J@}=3jve+sPhw`xQpmpk@(j=Lx;I*7)`E6I1S?OlDQaf!kia{P3xjsIR~FP; z7URhN0tiA-ggkv1-0<>f&`S(tG3Z4fxGSKCjNos7+)kTyv=6q&)f6h<&$-`7f9CFkn(QhOjaZ-gQsca&L&OHhRg z0Lts0Me|CJR3#S(Am?~AN~mRe$j==ml7b~%avt`o{lj7(sLfdOLwhb9qD`*F&{_KW zM?s0Qz^NZ7Fv6f^A3$ghw$CV;r|cxG01$oA_;akA%yNEC{xA4^WlO!|s zfio~}L-a%Iuy08@Wd?6PLxaCNNF8jH4)R*u|KzYLr{TtvYKE&A1%~k;Z+{42_H}#i zC%ekjI-!}EV}(;Hzoot6>7Jd$Ju;pT(*FMB{Q3_dKbY}`eDB>D^rRU8$!i^=r-;fB zWjJATI&E=Ox9BXY1zv3Ns-=##;|KLDH2w(>21!QbiuHP+1vsG1%H7tG%ut8($|6b4 z4X~%}ozY$n5|->e2?e}4j|jAhcnkzYv1xD@a1)^1<@w#@m3M91Jgd>lBX7MMSmA?y zW55m#>Q(3k#G=G!{){`I7J^J}%Iv9;c!soI#7>%lgT2mkzjPmae z8WG~adNih4DYeziLD7HLiGoK?TbaYgeaJ8pdzbxt(7(rSeH?Y{eSukx#98>#`{Y0U zt$6s)<3kX^6gm2s2u|OV6!v4FHKYB+eL!&D@!v21{3{=+v6Er^*IAOO8Cs3HQC>*Y zRo1(vGt;p*eL!m_J*O-_tSyJmxHF3BIm-l1VODeAE0n6ShC5?iPh5V6abE}yD}s+5 zdfIEUb|~ZUWVE2=BIhVH)_vY%0}{@a03^{cJh6+p+uK;@ADUFAQwG?LxCJCT9q2{A zNy0+ip{LRCg-=an)?Gh4oK3Vn7%K$U?4$hInOZt+!YIF>>1rN=st1-Ci23h;u*hbk zl`x+&NU_Z<^b2REzxbG=+j{B#1E|3GfOGP0PB6lr0NHRtp@p7j2O&p(ByxXU{_7=z6EWXyGWz56iFzJhOYG+H9F6M)*!FwdQf|qs_8PA2N1bnG!=9=_l@|DNK{te4 zxyCs2slMTUez%=bf!?g;|t%o5tcNG-m*^ljShl~3f)=A=^kPjden-_Fm91!WLx zeEjWh?D-60bvyr>XR!<<4>t8K)?v>c2+aF$m6-)d6^I=^d*cYo`m6-8;C~D5R=FUl zPiLN@!$k>{s6z$%>OPeJcIOQUjVJ8pR9$e#gAU8N2$|Etpg+7MrJ%uzteYj*m5x?n zSR8A)+O~{By2Dk{2a8(y&KwH-c|@pW{YcW7aX92>S6Q7715k_!keXWRCY8@V_1WHQ ze|oR|pkz5W#H+r*)OX%eihuGDx&>R!kGxK%W3vkfg>*&~wLQ|GnVZ~9gtIK@&h(}9 ziOEr#!xQ*IK3{LRKPBULu`3Xv7UYaLlZAPAkMx=ADM5}Jdbdh_s@?Y?QL-YE=y>Q% zC!bp3*ONHFcJ*_Y1nGM6+9Ji&q^V$dVn5OVSSar^@PpR`w_SLEk$X()3T3obdlt_& z@nl`UQCKC&v-XWXTZ=hEvrPuIwpx6x;|sHWatS@B>(-wrM&ws_&YxGl(@o+=2tT_B z+88;{6n7Q`wkHo?pPr?WANDJatCd^)2Ofm6exN>oL;T|##R#?&NHg|1Wh<{S)I1-b ze``MzrZqR3>Q5k-Gs1dT+e-=fEUT~WT|u_v498slYe3f$=^wx}q__R?@DZu(EH%D9 z3o51lH2U~n3#BaY30LTcbnS51PqvVD5-`AFEEnOObX5o_{JHydCP!_SS~mXZ{SP4T z21s^h1wNeKNkj|EMpin8YuvTj!)Pnk^|b7q+17#yh}ZaY`*kW=t{F~+rNXU%k0|Eo z{dg{LLHSz$kCGJzG{4Ol%n}TUXFCQmh0Ns>? z**s7G5(nonr zJy`P7kNc?JYhHj(gsJ+`v>0-7%BCHR%8`qri zMrT+rE|h!7q=+MmP6O|TmZT8(u3I3I$UzI^5A`4J0YItDLER)Z#Pj|~ULMx#&XJN0 zwLdh-de`q?6J83=k@Q|?_<%pj>KSr`FLR3u_B%$qf|(}+T6W>EGlWNHR9&mO>)8%o zc}3cTo1SQJT2O3ZC%JGsB(kTaC znXS+$qKgHGh{CElRWlLPvAAV5t(CuC^jKi~4aEyyDW2~I$Yi-LE>`#N#JVUNr2+&h zz-sD^f`o=<_xD1q1HV_)sf9%>;2$8Ps9i_Xx$)sq!1!<;XPU=@_+zCM&2EQ}rTmap z65SD($z6<*P?>IJ_=2i0hFl8nP}_Od&5?lW_f1~Ckj;|H%!r-LhiNCHk^R1Aqxp6~ zg9Rhv5jVWSCIT&Lo+UBDGR=oVsnAeP$sY>-%Y`!X!@!{#`~o>((+{J^LuQ+SBdoCwECumyk%F#An3?13`EJ^m2@=u3ZmU+G)S+@x zD@Q6#U*$xF{+Ob)h8kBykX02-_&MWh>twEEIsv1RsS@h|YrlEkpm+4!TI8;05S!UA zCUny)a7m3Nj5pQ@*%_Jk>Ewvx@9@~VKeR9!g>qn}TgC}BcM+Q`=XDh9dNgo&o|b7( z!pH_%%eO=>ezQ+dJzX*qer9nO**%|B3^9^nHqDUWP_ivW^viP!G!tAm$+pUdcH9=z53Lcb^J7WnV2)oIJ`bZ@Ym9?{9pd}fI5x4U{uU*#xz zzMaBEwi?s&P2IZsiGD=gH|#0NzR!_EwS1F-1{G#s@?ROz2AQfOpt1GfZG@A1u)ZH2 z0K6al#<*Dn#kX0j9rj}uwzVbRa?2EZ>HQ3h%CY`zwGBx%RCpNOmAca;@SXCFG2E)M z4;+SdRx5=;Q`MoAUUY7%qHGfu3bm5HOae|C)SSc$=*<=2F-h-s(pq@df5oI;_R1DR z<-o}Le{+R0c-l5Wt!*0GYa`-fZE6`dFFQi2Ep<$*ibqsszDr+RHL0Nb!5CNwOl0Vk zxCl5wmjZaZmB|a>v#VBybB5X{X-kaL5C36@kXicz)q6g$y{19Z2CyZG=cJvs_ar$P zq@E<_p=BK+?-XIW5YzqK_4{-1*Khc5GNu3bn4ZKOzGP+$aOiQ zM1Cy7hMy%)DkeP5|Hec4d!1H1pPAIOHfRbYx55%_J44xGE&TW#psM(!J^P=gV+bb>gJPeQB4 zbkCoj*bY~AqwrIlr_0EayO2~{Jv@;(*NmsofwX0Y{yVmB6l~+vB_jh^V|!=`6QQ8N zC2P9ysk`_=L~?ifO#FsYZ^L+Vi87DoWyX|=*eIc=_lPDE{WDDe;Xi=TUz8{V9(y;x zCH*!LwYrapHSUe&3U8J2tbXEbPRaX;TZZ@_X-1}k4Ff*-Uxh^?YsR`gOc}2x&C*U*sPs3vyku)IA7w` zbIS>(Zmaa$pxH)+rH8cAq}p{Mnplkwds#Vw$kZ_iq$4&+>;BlJI1f7a{RtJQ!)e1k z2lS}61vHUdZTYUTAsKiMs5DWjCtySnsS_HXv;Lqfi6&!KV<(DpH-%d{xH>HX;M__ zb^jm0&gd@@e2U0p7HGOV8e0H~6VE4!3M0gY`rE#9SY&VZR6!u0gYz`%aB1lIXrWWnytR?t_2pvqj(yaA5 zkekhkzpao+hbBD>UPM<@ z9|!_Z(zO_>cgp98U8Zg(N2N;PX^2yp`gO?f$(~MR)_JXuST)pKGf-8P$1p3{J|zBP zx)jXU$+*9SwHu34KgXdsAppVo)oVM>utMI|{0PWgv=xO-Y!&;z!|E|dB_*1Du9DD; zJ8A|<4P5<6gYq4?xyzb{5>)~q4<_>`9}pTHb+k~iZ^X&COl-?KwaiegrJ8;lQ2IAz##q@)1HP5%z-1r15ED&Al;rPO%i`KYG=M%?b+?qC8aQy2Da9R(z zBQ*a+8H26Sb(CDo;r%=fcpC3{t>`V_)SimvzSt+*Khg~GKFZN08|yQj!4~{Fd}8Hy zCbOIwKijBpic8&8Jl2quA&HLW30JXu^(A&?WDzKuK_z(N7@aahwOad1m!m*QG*C@C zg&}5cK^ayk+19MjpayUi#3)hIV$I%vjEx;g!T~?HW2qA{M9mGZESlj#vKD+q4@uuH zQL%RV25#A!m}cxxA&r2|#WtjlZzanN=^yA2GSDpv=%xuhqi(VEXL8o;PsHKWpISRd zR>Yh(Jnh1m+GyGGawkn281@?VGEv(Pxw{W5{MbhF?vC<0u05}c#PE~V!04MbKs(4^ zx|p~6m1ewrnD^`Y_XRE+Y`fyM7StUm*7kF4;c8JPaajY^s(VGu}Y}- z@}Ydwdpu*hu7GW|rFB@Y-ao=ecJ}0tSj5XBK6c!wa7V^Q;OCWlMP;gnQ<>aK z8dU|Ft=q7MKk`aPE7O?B3n_~~R;LF%;swYK3N7wqlHg^Vhmh)q zCdRosNyv3qjaQKAwB?UV0i(W7n(QsD%O*q(x9JjQFCFq+k+`}$x^-DVw@a#4zAY`b zvi>Qhkj}-Ts=G~1I(s$IBF(AOCCVAyfm{W52Y0f$$qMqB-xTv*%d1l92xlEMbi|cJ zoYU@mcTfKSI`($<$|l(sC6KbcVsvtQ0f?W7u2es^CW=gb8?&Z>v?W>mud_~Kg_4E8T-~( zPnH|EsNLk#DT_cPvd%d15H8;;$26?07K!^bXxPcEec?+pbLOE&JRxe0`-mDPqG!p< zOUC?yv$ig)4uj@PR0;2oWR3L0Z$-<OMf6_HcC~{}bn@85r?ZcP9 zgnmO$%(FC5e}i(XD&(Iy1yrKC2qn>?`q+2{@05`0?<~e3hu1}&)Ej!yuUe};>*_!+ zAcBxpq*XV51;L8Ok$OM=aN28LtjxwhYv#j`N|r^@VN+~4oeL11W4Vo-iaRA%*Xwo% z)E^O0xlHOkE1bLknyWN&d$^@@d#}uEwms`9LtLPaLnOBk^|mMRavVA+INJMWTGrq><}`zS7Cn{0fLK_ojg{-t_KOSnvJ>IXQAkkg|_?-%Mas zRr*$_TxYJU#D%hNMC;hV?kB@<%8ZAYizN|4@ld(N^hsL8CT2W$R%k=lnG2SEbA)@k zO|haO7bUUkn*j9O6>QXj)hT~ZVEYh>;vr8JIYf?e9RimG+va7D%l!`ha(5#cZ9vdPS`$|@WpZF8^S5MHANY=9J?&8-Dh#&u4{MgKnq;M_ zdUiVOcyPO7`9K#l^XKnPWi@zB5{xZiYp>D}B3E~2vE6PeS$rA`{sc?!Fn8WqbH3;_ zg4^h?HW{O_-e1WuG2t}=vBnOxffvRdy(biN4n3onpTfk=z?%cPMBvE@u1?jW9O}6< zmeR%wEpx1EY3`WDcWva4yn&5sb+fiKm#BL135xAaMb&55Lue0Ba3|Vb>vgJ*3$Ez9 z@rGo{xwHch`-g8bGU6*s+ouy&W-WRAk|!!M>(*6%rNV?>+OMgQ$h;h(`9~0uCCsGDR=YdPVr6=@;N6 z-Z%pe8)A|0$8|a;4GZD=y@a9J=nuL^Uqk^+yrUc|s^V6H!6Y^*P26;b^SBy&I~Qb6 z1r+a70p#hwuUDuKd-v-8C}W^Fl^?U}xUz`u8Op!~RqOMghT;hP!O?MlAqSML`xWO1 zR;I~k^R@sG)w7RW)|5LGbj}uP!*r2(S1Dk zH5u&`B^_OAn)vXfgGf>pS&y~gQ_8B!a%<#LURA@5St39re>{1PIG!vHH71Mc7O6h) z+<=$`OX*fUx~M)whgOGcBDhJ!J}FF7BJ75REA?XYwR9km+-DxJoiJ3GNT>UK00luV zT^~R;>t4GgIALt@`RHc=6=hK3Lr5WHr19KBs+v$)z zqUJ}*6%Bcq+9Os{0TtO!n9WVi4l!MZC=W4tl<(DjnAS^QX4D{3#gpTPn2V`o8MC{+ znlE%J`NxTopcMPh2~auNPpOb@ePV0etk8O44#`#8HHmfZ(_V;RVF&;{hfNwF>mkCf z`twnIL8IaXUP83bHdH!iwDDCXXDEt z?3HcF=nW64oA#4uF=#&*-k+>?T;K40{LDD_vqokjc<>xQa-J5824>hSRZxgh>lt+* zwVT5Th}nNAQUE{RC4CIkd>rjZ3ES|FnLlq@@=d;-&|&42yu$}^*Jo)B2+kGm(n49z zFv2pQTbfw<4wF)ExMVQg<4uMR#e{!7(u$Y(A^^%n=_pfHfg8u$MY2-&1!lFcC%OSW zRe2UmFtXN@ImV@JOS;vVxfW_MCkL4jVKMl?)^kWuGO;egP)P^{wl+`;_7hn3dn%{7 zzKZMbyGY0V=fJ59EAN&5jpn?Ie*l?mTx8-kH-qn{+9e#+@P?g9=a$`+E>Sq&Yqi5f z9o{wATZM~d)D8m>Ea#2nW#ahTC5+nW&SP@?5c>aMfNhr@XS*(47>vXad>R5^@|m_= zp=jp{cN*zTn>|PwbR)J`b@>Lex1IY%N${|{{H<)C@syIj56@!0_s^ay#PAn{@cCZd zrCSz!+&RixsBZjFzxD;YXleR%adC~Vu@ygP0k)C7B$YEVzYz_mt62w2 z{-w^AZT3ai#gs90pCTu8(ELxbhX0;@vMi|fm}-IhkD+*l5Rbb)uAvdx7wYUm-bq&g z4@_+U1~`4L{Y#h%$A*VlZaFlNFZ&F3_okFu8~v+p3+Do~?oUD)F}q&=_Ayk+=WqAK z!xEtr1^SQpsP+nB2=?MLn*#!BjqSKFfH0>lGUf2!4eZ%ZdSw% zT;MMD?GHIi(BzP*U-=>BkHrBF$$meawe^^dq_8SZJ;#%NuOVt>QdH#D*?MwMdl}{t zqB;G-f_s;?PsnpKjSq#( zN2QCRLp+_qzAZt!sqwco1}t;G_53d_E;#Lod9TPJW6F6y|6y5IehT#wFlwmwkICYb z5IVY$Ns>&qIs}*oOdqxHrS%mR)1e;ZMVm&_Q5*Q$cejH5RyEPT)Ah?rJJ*{OpxNlW zjxkn$Qy$ND=xtwZ)R*3Fo2ZzoT}T!IbscxsjaqLjf)Zd}<$nj3B5~C~G^`(x>dGMV z5y?K}YGIE;uA<8cD6|U`zO4C&{g!yHtL?7%txh5dD%1y7q%RVg`m6p*$>AlaEyx6& z=2UFI`)3e2h2KJ%s5wRcA<`uzLTt}JdmGCW$dwMf|>zss;GpoEN9EWq7X z588cg?QHXOuH`U9z+C5LtXL&8j=F$90`ftF!nomo^m#%7%8IgxPCqWT!p?ndmUL($ zP)7$f;==~EI`$(&k8+&Oc8W6eE6~ric`GxCVj@m>u=B!SR^g~V%bitV*0Kb=M;SjO zj;Yn(Co%%5)VwyBt*Ad{xpJtMRJ*U6%rD+zqm#>jzO{9A8W>!+lynkA%X(7D)5C?T zZr5+7A@!+0n)3OoMYMs@)(&bI%E~qFi?xXxRO&WeGS`^BOVjLwJp{5?q+*ID-7;$G z_FDR(bsfi5YIf%VlO`P+2CL*0acH)TY_3G@4|!b{7&)~3WOC5hg(#2bvFmsVSCIvN z3kTVB@enHbseI{WPsmR5SIK=>!*rp#UHDA%UcTSE_zHY3_zKa;UmKqUDZHsn1y?@R z-hbwPFa1`B@C#N+tPb3+A2X$|xpOWsb9jFu0yjI<8SR(1>fAm4JUBDtHWq_FV!~f3 zO{;uCYO3MqvPsf05*hlfJjqDf7lkNWsxD&5e9#~{1EP>#u)o@qzoswZ&jeLHvvs6; zw;CrrvO&q+cS;$wR!hmvrb9_I{LH`IJE5Tq=Z3emU34YPL=`Tr07Mz^I_+g6+3xGO zj~(*0njP&&SVgl~nIg^45+*lW=}p120Bi=#CHwt~S7P|D!} zk8|aL?m;xeT!!9 zdz1bwY5xFn=t!XJT>M6lCdFEtDipiDKhg=7hS7oWBT|j@0de(tfPLey%QQKs3|^*6 z`%wC2?(e(%)vI4(n@cZRVf@ivj>4h=fs`RIxim>sB*K*jkpo#$=i$T(rq-DHna*UN zYvxBR4}L97G||DLT!5IZUbHCek>l$Z&x45bT2`uy#b3N)SVmIJN!jBNGE13oz-S39 zRIK_4GS9vR!ZadxNu}`CTGKTS0U%!7!73>FI1NubL%b2PJGA`}L9)tj9AzC6Z`vJM zWU6`67crNUFmWQ8*zh;SiMK3K@LW!yiJl{f&m63rBh6gqxv*&1V{IcVPusx+;a|GQ7nH~cX3tQ!`0(g7T#Cd{E#K9vm4 zV?N)SUCOzTd(&DjeYjNlA;3Dz8|7F>A34oVd1Qrht}2>PZ+oOKLfVCE5Ya(E>njhw zO6VldT+`ttZ}{NxE*RPF$nLbIi~o9{GXR+vV@ua2lN1|euu}b5Kc;vF3J;|sNvd~I z2W;r8kkI3nUk|l`^*&cy2=a-G=A0QrT|gk5xfJ|XAe3{Z;7XD@I<6kAN^B+5QkW&} zG2%fzp-e{t!zznY72jb=fp%r*JJ0(Y7aLcUly)+Cy$qed4Ll*+#qmVRQ#v?l*ll`> zqk!^pMy`iK@}BiZfBR4OrT;drcu(+|=*-<#?^rE>_h7_v}e6)9$rX*2Yzwz*R>_X#-V@{o;d$`~) z#QbFh^}QVh0*T2S!yMP$GXoDH*)1ym%ihOAc^f6U-jih+pTgbCv9r~yv~zY%nZDrT zrpx#a6a#Z%!itS?4J22BfMoq7Cv2xMh!ri=tY$E2wH=P}5qhPvk{edz&kEh+M%IKh z-g%6hVH+?;85*o$CDn7IR4vqSB9EXSsI0^dZkMcGRFC7^#pC17ui{!o(DQaXhxls~IV_wQ5BNqj1>Qj*2ES zHFEx>x*jUYi7i;iU%^;Sx*WHH-fTk^Uq$Rj5Vx3JvTtLsE#`=kWmKM8!&zx##PE@k zz^V?8!Lu)3-THPm9&-&O+H(46A^IB^ks(6eBgScv0A@uzB*uX!rX)+q22_A3xzwjTS|F;GV3F%DcM5WHX|DJU4IGQc3moP5jqHYv+^3>$X>&7} z@zfGUeOQ^y3;5;dZ8BGuDj<`UPs3lJ8Y3rGpSHI2L%96HZGM|n?StH+*(=-$kx4a0 zxr})eRv(iuWuUC1OS+ni^0tC^yO^#t>O8ySvHhlo9RofDW(7NaTTw*{nVpOa6ly`bkY8K3GwF7kW$!%+H&X13%1Q z#A&S#mryj1-$o})w8tr#dYX6|bS!}^?!(j=?gCs&Hak+o2^bP!1-bcV1K%lQsMA6JEEN1NrSVniX+$gcW-hq|kMEGCvL7 zp3B+guv+QUw;95>B+ax!Je4H*l5ya`u-~(n44)mbcAaY?d#u@y%36@ z>Plfh_m*JFe4KtE3_vi^4L5=+N%pW$tS#y1B#jM8%(PI?wV+3Q>AJXAdkhMGGP5y? zdxPPVP;*xM6BC`m!7Ae}&=M%u85E;Ff}K9s(Y6GUJ$(O^qPcZTLS3@gA9~^(>)X`R z>Q}Aki1eVvm)=aMd;PkjV~N}dC7U6JYAxmO8i-?%@#E(`A3@Qa_7qYdT2ESY{)p*B zh)g2>YCM%CJPC74z<<9l4N!YNX0I28S4;P0dQ7%A9zG56RH9YOkF#uVD)5nX^}>8A&ys{X z|8|OFGuNj7O#UE1hl9P+H6aeG=7rt70l@R^mU4tr#dPxmyO)NxtO`oo z33bGnC%m>PYkuFa(i+F(cLn8rs9AG-dzjGrEICBh00<6^JS zRWGgt2fmUn9KK$3t;`bzkQB%_=5ohA zXTooZGPTAUW6J%Z3Ds!QOsrX)gd;h*Z<`(j_1g+=M&op7!s>#LjNyBo&{Wws_AyO%%YS|R>im+r-=O{NBA!>JHAh3J)dwm z)S3alPWsnuU>&kVHZ3qQ2ZM=y1pdz_qhwMy5&d^KrM#J7cvvTVO6tvkL6Mjz8nho! ztT2XXy`-fSxXN-hy|$A#3Umv7`<8Bpj*(`z$&R947tRchv+LeK^)q&i4q^WZTtX<<#Cl~vEw_0mK@C1~W3f-YzM>j$m zR-aR+yPO$L-Z^J+zvPU{YJ$Y4 z=}FsPD1+AQ8djP7Y11(QJucU^*vkW%dDji`prz@IN@NO$-@c-R#{3K=iNY}$EdC{~ z-PML3Z6(^yG}Az&WXdaT72xe%YcAI#vP)upP;~M(Nxm~GuW;^g&3!3foL)^^d+KUK zvkRV^ywbd(Kv}(}`gm^J6>b6iM&&96-jd?&k^P(fExXSFt`=i$2(po>B$l~=a=q7x z4`Mk2jS*E;iq2`*?XTKMPni!@SI-W0wncFU=exENpJjY-=G-kimxkp}uGoatVx*zs z_aA;Y>`%W}wxAd5_>q(*anB`^37aoo{mi=U;Vx;N9hmihl@r_Jpbwvv*E~UJk`YGl zjSUTHTsJXU^x!4k@8IRalPTBziD*4gh_Wuy}7SM6@%KqS(nVBiJ$ILM^Gc&VeW{zWK zjyYy#W{4SLkC~a7DaJTE-@WhceQ*DJcF*XjPfOL+RqBz{Emi%>SUl6ex-`G)KeU_5_&MBsNP!&xPbwxuz-8P3?u~Z@)+UUY|S(grd$Tv{bw8yCS zu=>`F+&5UA9(~uez1;iC>u@-?%|K=&K6%{4`ioQNXvj{ET~*B-6FG>P_OOmc?`V0X zMwWMZ7HC?jI`f$if=~b;Cl!u(^V>&SR;!$J45GnDQqaiR zL<{&dRDEMk0_y>F!ivmqr9GUjzHsbJuhD|sHML%i=u7aUQRu{?$Gjp$8)hx-$F#0z zSfjJVa)%=%yoNZ{rJ$+W^VRD_`)8~)yy)0@-U8Rld+s%ID1=jV?DUvF$CtuBy=tv* z{o>DKgN-Q zxFtr`A*R7%UJBi!N~AF;&aO+M!feVTceQE{fV1ujIw$^>Iu=pR%5{rWKgLXtua9D4 zO^M@|-*vJ+o;T}q*T%YQ;tmD6sPSLHE2dP^`|RcSe!{{$<~?ikyH&rkIv(1oNv!E# zMlt3A0y&x6YhGWpIMumUSYNvO6E(Ha6`kQO-@eV=d9Kq-BSd<&$eS0u-Z5rDshXb z6pHJC^(Nz?vJC`$-{_kAp#kK30U^Kh3jdUy^nQ6|Sqq5y|2oP4li${;zk~$i5TS#r z5m$XC7U5k*1?`k(h?%&w2k@j6DZ)?A0728}+{Su79Jb$OC~Zt|f!qkYhgOi}_K%D# zV-H@GLR1-TVMT}>0V%C>7Is8Ls|?$V(s4+I$0?oR%WB~(v26@+O$RZn4r6!MNRe68 z#_VcL$vIlcP(p5ps7mvirwlmP+*W_68|8oBWk|MlbE!VWMr)&taO!X&m^#&Af8teM#}xd0EB1DR$_ZIA3!3VBM87fGc1b{ySi+RwU*d#7%1Gzhll z_nbecp@e|F8+x1lp(#x{zuUuATP$St{r0}|8C0)d!e2L`x5BG5&xmy%oibZUV1psM zAj9bK87ky^2eflzlqLG>(J6;Rpr~|v-u-A9UzqeDXaECD9pAsdj%zi5+IFfXO7TY&>s#_P+Ll9@( zU`NAgM{-GbFzIX7Z)z}hu}BL}#ZrCdvqjdSseJ!>B(`CGNjFU0QEJO7s6 zjb)y&;apki6BuS@`oFxuUDG!yH z&L%9qKxsZjo^fy;*DD*6SPYx9NN_A}lozg4*pd0Zk_c$MB1QB|mf7txX2q|8+u^tE zgrm-P6jx!SWoFum`OPNInF2ExR>VM5XqJ;TO(WC0hEkh}9afFOLUf9uHgAhUt;Sc7 zo9JSCH5@e|)ismkb^q)d915sCp8NnD=NGgydJq=fc~n3RVF}!IBgB}b5;w8Zg5hlrWY*C5$gIENd=Y zyQv-Ru4C~r4yX4e?IJhY*|fjLzWd!-wuQfpt`blB&6N`_Ee}mr^yqpwI1jj4;i=^v zjpgCMJeHq)DdV&7n~K;Eq~DhEtJh)*D%bEuYUbex$I3`HM|`X|JtWgRA9k@2fC%aA zM{bCZl{?bqf4CxR<#ivb>v^pnw)#G^98xZ!Lcr^r9w~*nvn=Z=h+vuSX2ndGraqh= z1MY6!QYVorniOkAo9;}kw@mms&m?_M-52QLfeBeZYE}+5x2zjZ^d}H9{S66K85~BP-@LVd ziIeCU#1$>ERPOUifnrT&987%vqE)j_)H1N}$e&b^ecSa~R2WhA$wR?S{A7A*qIF68 zx?5ZlVbak3=7=X~*3m#)E+yNXV;y_N_6T9l0IA>d^2UEXC&0e2`DJ?8HD z@<%n_l1twJTv{J{H8Pl!w#*NQ(IxZ~0!6zjUzKDnc&|~D?K`SB3a8chB$*qAe6T)& z%#}BWz)tA{1LYPJBc<^|A?Hj;mLdMh*Ql4c#@%J=<;*@ck|DI98zm1041v;VQq2v6 zYn#j~fy=bhkF}N@eQ#%~F7waU4kr^U2S~@RRo7Z2`6@ zL_HFj;FndI%@NV)B@MGBnXau>|?9bYw;0=$%ES z@e(^PwGcB|NfpL*ydk7yQ%p`&t~8hW?GdDyY|Gj+XH>dX{NUj06lv`;q#Q3dt5Q)& zO<-Z&YaL$vUKkB!&Sp*e6bN>sSDOw7wQIS{uNrwrrgfO#&Tn?rCXVT<`i@e!uKPEJ z;Ib0;Q5tP+{)9Ucilp0`vfK-ZXTMA(^Bwxy{tD{1SapG}QNsJOqob<8@KLH%ZFfe# z#P8(n-xuOEqS0iRgRn+<^FI152$BHcV7ao|`HnzGj%=&HcO=VDT+;KKVnHx!5N3pU z+D^zA(e~9*)5nD#oiyZ_Y_nci7Yv0`>4~Jwe(Stn#6C^IJ}4eILSkBrmd$ui=2cd%d4`Jqx71`-=ZO z#<_D>g-)GJJ3$uIQJ+GiV+_^ao(n%{Q5a4-E8@Gj+G4c*PuS;j1b#f@lI3U>Lc&5} zwV3)8rkm1f@D#+q{C;g0^@Y*o<#Nv07+`;8ofl+{K3U)26C!@21ue|aFtrs!gj>sc zGAeMMso)?Th#1EyGG6i&U5_T4?MzusUvP?!L|baX>*6e5L72Ey8G-2may+Cmkp8s8 z=%^Tu;};RbAkyxVDd~a?sHG?y=Z6CiEs!O$#O?7FSmX=de98i~b-V>@1Z|P^NBB(c z!=ET$;M@I6UF8VBQqR@8Gik|KN`}W7PVi!zEYV&Og)Mv@5yS%JTGXBz&UF>ZJWY&S zHdTD3&Ii(uVl?sOhBsil{+VH97qtK|86mv-cVsb4>WKBtYZGVc$n@~h1%IO1A1WBI zO=rhpD=e_Gy_fgw&9KJ4NY~{No1;a*aOE$NOh&x08@wmknXup_t_VQ4oE7AWlQ#C?Fv_n18pmv79H`4 zmI75RQ<{Nh|zvZ-^XefSc=~Dt#r1 zu-7NA;xX7Gx>KTtB&ThD{bL#H3H8L67R%bj?Y81M#!uXlwO5gi*>rt7O(efXl#<6&?^GIB`V4XjXYG~u$cToKt>LWaUC*S? zwLfxN($nXK(xC3ggc0F^Q)3!XKkrx!J(L0-oS{GK%cH}{QS-~9Q7(1_)CXeRhnt`b zS-5ZMzx_leZ_U9l-uOzT`4L}KZ5a&Es|AOLW*4L8las*%LVgy=rP7&A_tzm8DDXHu z92$Y8f>@Aguk9M@*OKg5SGff)zN%ajZc=zVlQWne@8G)7+vQApn-!y7>1~xCdX#4> zNkICFPU&lHPcWFK`sZh#g0$nFtjazr>1k)-brqf@mdkEn%&FlpyQ(ydxW4fJmNVAy zKN@qo99*6=eQA%jS&%ES!~bSqQ&|?G4j0k%^U*wwhpYqcNg7t zd>j%ySoCJ0tGQ!q@=|tHpVQ0QFOjF*Q3-)l@39!hwFihVkL!&L`+ow+H(34BJ!4e% zqr#KZW~gIq|A4!%*6=Gxbz>MCl`UdFS#H&NGDh=5(lX;h zDc6R{uQydhUdZ8%yr89!23S=?O}WL13CsxUml72UkXtj;8gmm;y2r8L6f{BW=Ce-0 z)Ly3+5lBqMgK|BvPlQY>hoLWpGvle&;icc8)39G{r564bhoblr_3b8qkm(YsW5d;r zJ-rgXnw}qvi@g1oh>&*zJyIJFmy4Hs9HAeO(3n1;<`LG zhEEEWB{MesBQjBg#URh7u!*5UH;w5aWe~q0e#xbx$cSGytU0k-{Z*}6r}X?gyUGZ1 zDOz2a;jGTp)2#=GaC<HKbe4Wy)^#4dYyC7J}+sj^t~@3WUtw61h{>FB1dr6|0Lq8a*&9Bo;f=Ifi$ zup=tZK46O>#01k7m-=!sliPUyea2saCP&JAFEEm*&+!L^a3|NNmDrkO4HofCW z?kf4cFt}@CU;&J5{iQ-m@TD559vAK86ohUf-1ri_)2Ix++aD6ny5q)Hf87DSVf<3bf;cfZ}5WmXOM> zhgS~0g#nPdP=xTXs{sNIfeIPX>UrXgLRvqi#c+NOW^=*%w})~WJI`)SPMotW!AWsb z0{g0G&;J5wG{)W2k+?E`%KNhpNdM>x{FdN8*a%yN=M*f*xY%~huA&Hb=p;#6LI4`z zvznSCa(mq%4Qp%Z7O;Orfqvc}bJZbB$9a`UpO|B;a<{zx)Vze`gR$BFeQSHOdbpbf zUgmXP99Fm}$l*k# zQ!5DtHZUV+V8fB}f$dlBe-|{Y-5zN$P%%#Z?h|Jku0caLsplaz!j|znO89hS;u4{@ z;^yFIe{*Vz1WSR0QIN(}LPfX`dsNgWhR284&raDlv;G(e#=~+&PqU9G0&eOh6s9cI{uHocF2^`~>e(Gwbq!h&Gk zs^yDY&#?TL)n24@mi>CNmyjuH^L(3ZQk1|mv7^cIV!F_Zn6q@Xp{A=Hx;(nE8b$Y6 zgz6G}76;6{GqAOjd)Zrw@Fv~Isq&NDw@&pxb9q<)qx2-U)W&lBR+-4P=eN+d=*_o)hz9ZMzcFG)VXQ@4}u!l3~<1TOGg$YD> z1}S@n7+UY88lTS?Fe+<>oJX#9huZ48X^2zr`6d#bj#x390^t+FdJywcZ!qL1hD6Tx z`=+yvQykv!qtwxFF@KZiFBruwxP|oUExu?{TD3?qS)(2c31^+(aE-k<9cyfYV>AXu z88n_o`u-4$xkdM3XxM@VIR_Mt@KTLpmc(P0kKsgnP9>9(H4*08BZY_t!3oNv=sCoMdkgO9+61EBVMO2486aA5K6ASIEmkM=8w~x*1u){B!BZyU9jOr zbH(mlBW(&KO^)`lgtD;$W-2=x6(G5YsqFX1=kYGC>7qBaVX4DG6yk8eP1>X`o~gRxHK;$gU(~RKgXB7uN)H|Dz~T{(pk=5 z19>>Iqy4mggSIxD9q?lHd6WsFVZ2=fU5k=iNjAXQd^t)yrB-)h)?^n091P#+8T_$VV6*?Bn$iGk1&%G zildd*_!up{o3;7s7XE@Cad2M^r#JjQQ$Gpl ztK`QKtu0)T>e5Eh>#3*Bku6W^-sI_Ps_fuNv9EeVTIlBYy0+t)!N{*Py4d+3@;dOlp9pr)%bh1WuTfa5CEa@!5H{8EKliy!v5*$3bk=BK&p@|}Q4AldX8 z)ehL(pQN7-VaaTL3nln5L=Tt9R!~(wb?*#~gd7cyngXzsW)s@6Fkd~6RjD|NlxCRn5VOL&e45dYj$EMa- z#Y@?XMI#dN{dMpU{M-*-g`Lql0%v?3jPXJP0W#V`LM|_0Ih4_6c2bfX_|I;WaYZO7 zpvLts9I^gv*nPap8RH|anV4>h_zU*|3wIvu5uCvM{93B0T^yw6HS7Yk=pV#m&HpKc zHxhIE7Z8A^oc-`JmEpG?jQwL`Fw+RTH$g#rWTB{3OAAKv<1gS1D6M|ubEY<@k)^}aynDoo~l=x>+BerU0@q_kNjDTG|h5kxQ~fS zfW%nRLJ=QrB0*^0qOJ;d8lq>>Fiw_94k5((#5|ql)1$V7puJ6(0x@O!F8i$UP7j&L zEQ(H<-IW|3G|Zu$@Wm*?l)e--npvToZ=66$M?ET-0c7vzZK|mhq2>~n2&?ydbSWt0 zv3!@sn5gUP@pWVH#zCvp^bglR=HXZl*W=6;sST(l=P?)K@RHk z!^_pC<DKh zf7{*x$A_R!ipEu%=;bj7egE2B7$k1nvOW%tx>}{_ehNI~JDMWf(MBH)wGO?K_FDh; zbote*f6p*U(#o#yjK^@3yg3>5kxn|->gi@>6JKerQoXojkoHS5%bvrJIG^qLcS45x z$4o7ilW<2NmEaXb7+5RfNm2xPB-Z6{4dmJqUCcS}@WwmafLZ#t%(vJ-KVAK|Lz#~r zb1s~|;MS5u;b8xK_e*dJGGQiFS-MP_bB8L}?w+1o_C(Mh+UUwwB>_1ETL3A?QCwIl zyX4Wz-Vs!bo?rUj1{@aANrEwnre!i&H=b?-DkhF$D7!#?C9!R%b4aizEcWyWk-1Lnv9Zf;n}l*D>M$h%jP{ z9P)P;wU5WUtxfv!=#~?@4D}d@3?jlt3$W@hn%|DY(7HE}oEofi&}#5lCy)yb*(J#S z6S3bOeR(>kthb+Kr7)8P>0%Ol|F3yMMlT&U|X<9uw{f^1c;6mympbfc=NM9kA14qpyo!$I3x@>O3{Tb-He&cSTeHqb+nU<4TcQV3ntt&Y2X@8F`?$dd z!r`#X=$g7;a1Drko`$np~o=os*0?io~>6CeS4NTQ=oXe)Rw5L~ng8F0Q-7G_My zWuOt_2eftuX@=|Zl94wLC3A9)@M!>QNeWEPY=sSlTBhF_Q&(GhU7VR4ktB%db>ym*GPYyQS9X_L;)2Tu+S8=uJQp{PEkCaziN;vXx3;aj?kH#jeVfyC^N$=@nFGXGzDrrgR<%nL!nAnS{kF7X#Y(nfQi5T9^gvkojbFt38rBqdfJnt78oi)r3f>mG zN5{0O7?yL!mPwO40JYnF66En)nY&T-RRp-i?1I2UP$Lp{RQQb5paaj;%G$p%a@GxC z=&*B{ys5%}l|#;LtQai>J9s!f3Nw8az#CI47k}Fx4_)1cJfWJU=y~Fkr&UH0bR!l1 z4wEI$mRHT(<80VM>=fWuL(`Q1WQA9xB;{-6>L+9hUMnos4)s(hLG>rxI!wG~5+>OPv{)!=l`f#p2N03|3`*?(s{t@A!R|%A zCb;DWql++$$HXE;$lW`SLESC_faN}=9`nM_s)lg1De6dWDSK&L_mps+kLlS<>3*%z zr-aeML8gBJ^>;AdX87Fr>EtMYyWorVNcY!5l~<@y_`iT6**d=0zkrLnnvDe;d;M@$ zUe5T!6n%krW__k5HfMkbvo5Y%LY#W6ZaEl~yp-N8mLZ)*Nh?VHG0Qv&mvU216IcYk z-bVQFPs#eLu?^U_?@eTT{Y|>D6%2WZ&1|MOMeJ#BjLu-KSnfMqP9%MBaDndyUD24J11Y#l8_S6n3;K%8Nt7%B+g#r;8XcPq1Tx(ng%X9hwLYwcj^PJ}Yr9tC|Qs%&gY&>DZX5M1~X z4Kq@{T%)lTtlrjVBTPg#TNM&Yrs(O6%AecMK{_G{+5xg+GAxL^Zdn0tDLMB*KyS4K zzU5P7zs&p&WJKjWU#0UAUbtd-L`*qdXiQe3fV+v*3Q?y;XdUvd6cBDo^fgb%%x_!rm@u|5reDDp#cesS(#$83TQtfP@|`q?e_X}W?5o8jPo%CqZ>kNtp+u8Uh!xVyu`x=1Cdg(9 z|3H^-=InU|<=ZLN>*$t(K{bo#6G+JUhSS5XS&7!~!bGjUKw+Y*DIWx1|Ad+X$$v7z7h!L`>c}VU1iTWKi zjDA&Dz=)pc8CY)9ug&tqIqlFUihcfKu+J9@bH)?1%pzBTqVCnp?;B*uNtJ0=Rz#VQ zQtFg4u8$r}sUxYYAUR7CJsRzORviE3_e!pH26-T-SxF+6U4z0AZK)n553|hYbccIO zL&`?#E37FuE|ia7X80jLZBax7LdQvWtAMG$?OHTQ0rcv8sz?kOr59FDp{848-X?8Q ze)p*`*~|CX+7nai{F?LEgk5sGsfagrbmR3%J|ui%xHy2)j&L>BrPQTe-J;eq9uruM z`iWfX5o12cBR^F}teVj<5r84frv^44+sXpXFC03BB9-=Xfy1u^VMehFXVsyHZ?P)s zW; zuQ{>O^~xxQ=S7RSQw{lRttD#P#yF{v276U1Qq4L1kl+RKf_@o#ORzCinu-%C+}Gzv zY44j3PXF%^cmG>$%_(W6ru)u)MgeM(3ontmq)C1f?ZiUI44r=X8=J^<*4(Ze1By=^2v28gjPAiq} z(;Kv#*Q5jC$oZs;<;b~#6qUC!{nmLvX~FwotOP~LJi7-#P>@_WiIrt!AAD0v>qJXP zy{)RKO_-v*Vjv~NY?7l1keEC~O3tg8M~dJ+Hi=iaA*VfcSu#$_Hl~}E3A?kb`jYq8 z9;&!rN&5V%gTQcS8fdE&$Ng-SF9ZTM9YV(%Xr2cw3R*?9Aez9=gOF25OLpjv@TfF-zW|1k? zC;CESF!h`l95iMMwi7f{QCrUy(On-Wc&H%>!YLRkmd4-P;c2*rIP)7f{A%gpf5?Jf ze?kP38Mkss9U)pRnOT_HJZd&^F(r43)5;3 z-OMLd~4`IxMlv$bXkm|ElWh~`}Y^`=(! zrGOx8XHubXP)+ zninINEJFAKnc^ze2o!#&oslS{r&#Q0w-a(RnK~Q&aNWjY?SG0FST1bCN<$gRbT6ZI zWnz%LWbEEjkY~3#Qc)Uen1BIFbfETNh1?V~w|_CZgI+xmPjg+pa?fmC7U2nh`##C6 z+a-Lu45ijaz5D$0%OfSdvCJ7u*hK8h#Skvf`&iTcO~*I*;b-6B%Ub+I7^n*U;I)^7S)R1nmTWoRayn%w6NGGnzn8N1Cs1R8kd)-~hq`XLO_iP*7XS zTyhd8o&`FDXO6(41Jy!Yrl}ED?$KP3>=7^LM@HFYV8gDIUkE?4U65c1XAMx!!rKe{ zG9t^_xN%`NPU#3hegT6~Y%?1V22e*N|IrNqFI*;oc0q1w6A@wWETi5af#cv((&Ut= zx;F=-T#9_uY!StmGdOuPd`Yd1pA$paT$vKvkvBkw@va+(-r~m^ZLl$c3^s6kx@}q746Mx9; z7hPUg_D_diHY*gGz$+X{na7b*oyfN7>dCa3^}%lXDtGJi0#2x`;~^yz`xiOXgg2n~ zkC;>D=wAuZ4bsB_OuU4XLdBb8u^VG3FM(1qb>EQEZ()sTSyfRh0-$xl?hMZ^H*T1o zzHR7@(z7Ce0Uh!6SxJx2b^SVCYyABIX86fA8qS26UHJWYYcU3oF~_7+CQFhp=&f6ymd`cxDcRBvTvBl6$s=pv+0W4k*9T|KKL@eCuD* zi7H|Vs*l^-Rkbl4w{Rf()KeB z@LN~r3<)GvNtBz?yZ#gH_3`B)*_nFLHj(2I@U4NrW$|Y4XS#3d z!?BiGj|6Y`^bl+AQInZ|rA{mU9v|sv)8^aM^%k9m{YKNLdBR}pOw2g1V3JRsNo&%U zC^y&oef9LhUkH(_&6?WcxA=7~{6%Q5OY#Er?FB8bzCM5Jg1I?nS3J2%XDs^S7u{O4 zQzihmVuowOEbZ(Nehvk{YTKdGz>iR5+3-eJir%rm?{87XR4VvkG&k4)Zm-<->qbbI zET}5ERg56i`ny8DXj*ou^gp>D30fH^%F;CLK9g2d`VS70-DAiINxXx%CM{V(m7BWJ zFz!+W%l*@&iI=V-1}*Qp2rh0MXgLaF#SjtIRuMy$8L^WKB<Gwl|8*t3#1rcqXk1;b3v`lwF|NAx2X8c{*i-%3GC*ejoxq&jO)p7)CwToU z^W=Q}FMuTkTZ{%&mIbSvg_whgSi0j{H~eE^xY$8Q$mk`KtMM{kbb5$lR~KGiEE37a zbwo3Reuwa@l&*uRARL$4R9t7AgooGe%NDrF?)&L!tXH9ak6IWtLEF4G2^PSYadKTk zbR^}mJ0ea^@168!VXFKd}F6d1eDqua2r(UReTdS4`X%q`vE!U+)|<7~M-vZ+ppX6wU@Q^=gfDihjqGKnlYb3nwz;#~)Z(sp z|A-K;3uS9o@_?n%csc$PBTdHf7jT#dat}{HJAduHm!+#iRo8Oq-GjQ|x^pBcEyMe; zt9tH*THGOBV`TgmCJK!XPTo*dPBcUm5LgI*0qFmB!ufX|R%4J~^%sz69O&89@T4@j z$&coKAvj#G>7x&bmgrqW$&`f+WaafqSKS~bj7dC^eUx9aZ&s)06$Fdo>TAx zJuDO3khpaxF0_cD&?*7_rJHh495hsFRqklw6;YmwI+XCUEQD zbw)LsqXY}m_UBG3pvH2lMz+J{i$m>^t**teFj8z`;Xx|1b|QmDP^HJDXeSrdYo|rx z9#55Zn(Gf<^oDW)6io1)XKHrZ8 zh8C!p@O@CzwjAoBVMi>KJPO&Sp2h~O--cIr;+>CFWpNn3@aCoeqkLTAO=m^=xk7Ni zzCjyXy}yQXd3sSkJFZikj5Fd?6J&NrNbgw+SrVG84YyQ(LH{&Xt$JdvlQAADo-15p z6$pM(QPD-y*(L3x0YCA8tP-AGvJeb=VpPkMV)~J93(J`eEEoCJnW>dKi@*p;T;Xy2 z|9PFLNg)xAu1K{B@d}>nL8M}btX`FWAyQQzB={@y1tl@9jdh(UiQXN8wG?Qt$2URA zoUv3g2)m}b6U#TSAqVZO@luqA0k;(!Zz{N{UhzYMY(v3d?5?i(UE28FHyj(z(5Rco zEXeWd`?wb;5~=qM`Ngbv=h+%L2@f2H_9k#sjK;*%JhN(8$Qc?y5ko4~kZIEeWpA|n zo2~kplQCXVi}YYq3x3Y63?svmtRbE-F9O_(obl(9l~K3YF%?0 z!-?x=zTx!De4h9V7z=y)q@~-*9ArKRYI89H=l!3=;3(v;$v8qmRlub>`ewt@M8g94%hE?261`KgH>+ z=QCT@=vwg4XJEsK_U{#nN)^eL{2-iyb()7`D`HZY2`a? z0#WWL<@X}})Lj`U2(U)Nfv1twd{)0|3zTW)aa4+Ur_g{Giv}I$>3WN!vafkt!UZli z!LcjrM}cPS2oM#a@D+wP3Q{_5<$7k|7&6~(@92+lQKok*pC7$TS2=V4iOryu{7-C# znA<-p3$3=EC)!1z4+6|jGD(yY(Qu1yRfahkgw){}D)DH~#s3sW{ksl)uqd)2ullm_ z7jPg9F%R}Mj0DdyF`vAvkub0Vj0ek%IZ7uz<&j#?3q^{aIsRSj&89Nu zLRj=aJpG%0=ae;H3YLAj!N z=0C#!e`jKtVFdJl0br>7JaCjJWGHY*C;$`y06@Q=7Pt$7C+`P9AR?;)h$#X10C8jh zngF=`f29f5c@XEmh`_F*z`QaK)&HY*TA*-LfOT5nW{^jHl+kTOpkY*?=>MR(pMW0} zA!khhLXDEoOaE{F{}A(#i$ViLp;`Np(Srbx1MuVk=>H|dzZmWzgJ>_X)rNJbDQ7 z|H%ZJVhBAL1|CWhAJESeJSG5${ogcG;AmC?8RXLf&UfVE$oMzW@HDK0@c)bEE(j5S zKQJ&q7QQOH({GXECr7FW0*d~twIEu=sQ~2x{waXQ-#_S*dLoUi;_0RB&r?fj z8m6GVU`#}UC<|peEWvf^1mph@+)f?qP(pf&7X__wLTrls9CWqMru+fNOZ1<|2Mhz@ zzsq3+qT84G3=_%`i}dgZ8b~Akhk#KFx3#ZqC7W!d3Zf`cWRO`%x<}Mn5XkV~4Z=CE zl!!mHBoff{l{Z+I;WIN{uoFXTj=sTu9OpdBzl0g*vnVP;!AIU7{(-`GjUu@Hryi<8 zOWq!5;lG%Se=yFAR zv0-wh$4W$I(#bD{{@jk3y#iCMMESp%%#1_I;xFLQsm4hZQN;?(PcuE?vw}b%Rb;^2 z@V{w*N%dEYG<%mt_>x6|gKlwmgFTzh@c6J*|J@+)GZ0ASC5|OP-h?3!;t*&x8Hiu7 zt`7^yKI5O7{(YlyL3k|t6OLen;toU{M=FyCj%B<#cy`E+hxsYi2C%fF0(T|*vXnz_ zPv(h_n{PRPmbKXZHS)S3NDE;8t3mF==?~o{Y0VF!1vgDye+^OAtlvy>AVq10@;Fc8 z|67MbApLQ*yt2|mq;jIPCmGKAv)h1_Rbjd;e7;LFg(1z1P^-7lC2Q4|gBDzZzDxJ`Z67FXwS4lgKcDgJf&JUE{snox(z)f{cS ziSS|-aN}H`uV7SdZLCy&giH9ZR=xiva=RR623^-zYUSV1vM)sD?=qI`YIQ0~4v=QO zpJv^c`h2$a>^S}#8(LAXmkLS!rKO$t8ftrKj7ygiol%&`do~_ zKr9es(!bLe3$ca7gf}Yt*s%&37~Uj%=^P4x!LA1nnE-%Ob?jGxm=5=gE(>u8itmm~ z;^GbuJw-TvK>}=}$n~QF6yuZ$-)nA1v2VVCHl%vN5gs7#8uCKFImzPZ!~9!cl=_C{ zjn_unCs=)szV!a#N3x!U#IWm~iIW7dCdjPQHtRC~FCO!gpP=MQ0~k&AskJ>x zerUjCKfXW2;8VtWo?!L?)c^H#_9~7I4Rz)08=xr66r!Fy^AvVqiN(A;^m79TCt2r3 z|G5!H&5kYs)|%JJlea9#r;^Eds})vN0H(e3ATq~4On@0f$~}WKFEJDCnYC!%vDBuA zn#G|x%1Z2tjCbP#4gWl1>c|jPS$nxEx>34clCS%{x@W(j)g05%{-p?*$#~hg#Shr< zzW`aW?9iAy{J6qvAzo|})Azk?rBUlJb<@L`Z{{5nzZo30(23@q3GziA4{ttpr~cfVmAr_+S56m?*~|5BtwGrM5)W2T!QI_mg1fr}m*50L{_xA|K?GXkcVS7M4Ce=AtXtFa zIegiOwr@87hY8~G%*Q@p92qr-tg4tw6 zrDZwzNXS(wH3iw{Qec6qe`qfFu?`}}hPzM6Nx(r#SAhD( zziVAi5d6>O|95EwJ=+A=`~Kh0>fe7T{~_W(n)GjaFzbNKnBqB3}Bryv#qLCkQfGBA8zX<*}L%~Vj{GRt$ z-G3aPcs~Qg`Tzi_9{?cyuMT1S7r}oL|Fw_!7ZDV}KQsdG0YJ%6|BCww1VH{3|MTw% zpzi@dK_o21Ld=2+1`dAu{(lGld@mIM{Q-=8wrO0oskTe`aoKM7J~h+3x6R|?tMyYB zTW4Ke!z4Ia=PPmrWuv-=fk|*C>q(d_iT5Dq4ff|Wv*!`#m+Z)^r$=TNhG2TVoa$xU z3_Q4cv+Zt9UucKRho~^VC8CPzSIAL>J(f=>Bd6IQx+};-ZnKYI-;!6k8`UV&PFW{n zXRhTMpu6dKBo-HD=WSsI7X5O&^{?a4D>x^tfzwoL?oUJ$1O7FAH`z)Fo)T84-t+{a z1~w;lQbq`z^y;dYO=Tmdd-*6coOtfUDfRVxk!Q03cZA_I`)yv``-f;G(7KIkcYgqP z^jTGF^)GK|9b}A@OV5OS{`WsJw;X5BoOrgfR?(5_s<+bZfVUpicWxNYf#>0ePel3{ zuLvTd5d<+hLn7YTuKy>6-?`ltaA6T8^kTg^`H_XoX=W-COQPoqRMBxeVcc$tDIuY=;*nr_jowZk z!;K1F26ZfXsw?uoxrUB`)7-2P-5`;3zS>T z`7xo-?jdZd(Ko7YW*W<>YDODKxNOdf;KS$k)plm6f9pC#W=y0Ei~7x;&+iiYmR`aD zcM~S$quPUL>+YuswmlbV0<#gi#)*W*%_F}3&_OP&cTA|&pSZR{?GWf6spfdT0bb6> z+`D&IP^Z1wnT4`I1DSqkKAY!o-Q>VF_wYsH@m9VOpZL3Q5j)z@Wbb~7rpo-ME%&Xx z3oWatw3l{Wy{Q{5P82Us!8}SknpotpAHUC`=Q*3?mm`=#!{9h| zYR(#))opyurETry4ZdPe_wicA`Z%1n9~h*BuhzW9k|mn(su>^KHvGs-@bSaRl95NO z0B0UgXtwP~`ZL|%QGr^X8qirio50s59P5YeB=6An2hk(z;U%AR>ldnD)%06mL%KWK z?c6`|XKLBB<66TMJn5ou%w|h{-=z7#%mh0mol3p~wkO*ME1NzO4 z^#=WJMF5=1BCpp>$ni( z)%3bZ!2ZI~+U^Y|%UiTCNSO8&a-5}zdd%Pn@SKhIJMB6^xim$i9Bynkv9XbptCihKECaN7SG2e<*QjiJ=@?6I#jIKbzF~We8qAKZ9chX)S~$w1~CEV zk=7amukcF~t+ZRi6!V-!g;F&s-#^if+2E7+@|nW36@S+!S`B|+0IDh?V9QLuT<1+! zVy3fd(~f^j*a*75L3c^os__cs6G3gHt{o#W(bzk_>^|A4iIUSTEPC@}*CCR-YHhJ~ zr-P!HKX{_hv+?(;XLyFzNnW4iLiCm*X4TOl><$u;z^<=JbC&o31N)2hx5a5$N#CS9 z_s9dKR+iKSb1?Z36Vp_vC&vrcVkZn2Dl!bN$?PgtYA>z@iV45a^>4=hgeRoPwqILy z*LyolJfvq@)5I(p{eBfU7-pHM3)y^1jG%bv=UXis?)=QLc-YDcA>J;+qd@CqBP`rN6F%$Pj zB41@6443eYJ2aeatFSUP*m|!%2J_ z^ByLvM<5+8769yJy|3P~y~&83l9aO+6u*h)iTZ*Q=N5f*Yt>@)30H~4bak!W?!&i+ z49|uPSZk*(JEn;x<_1ECdW0iuYcDtCA4oANwhL_c-)^(-J&)%Mg4{pf`9><~@|e$i zLsgkY`3iVmiA>tuG^}hGS1-BS6?QIMQ$ep+I5)Lf70z(+?%i()Y+@^Y54n1oY@*UV zEZb?nZD@GcX^o3WHcer6nJ5+zjkI<|Rb1CsmAeU&%NIh#4^;AAXaWeQznLdTC+lHA z_9<>-3>^=58?IRo*zqToNPh7}<nnCUM%Q!(0-upbcGN0<5JZg? zQ(}P*lk2`MKAYZk-)-KV-Gek^YKVc>#$p?QquN0$);|CXKH09S#=n~K{#*H1T79Ca z-QMcL z>}>NKE7D6W-A;<12=uiW{>I77f{i2^dzZ;2T5}SpuMo3FOB0VIhJ7z_7tA9C*o{#U;Jj%;U;*v$7CJQzX)-K+Lek&n;6!|zEe)c1}D2{aC4axRCyjT(!5cf8$w zU-eKSlmW;@X0X)kX{tgeX(T1oN!Z|O$|rY$n`??*euA+eQvYZO%U2oibl%60dW-8G z%AG1gw&t#aOVbB;*!vTqJTS(ZhnOgbtp|~-_w42MqItPpSfCN>gkd?OHZZycfBVxL zqpX*{tW@3D+sKD7Pe1IaL)&(d;tL>dM{ZVjj;Gu8PdaeEO-Vd=fP-*jIj**pwF`4xQ{=CEkw$K@zHwIY16_+ zXpDgu&d{Ac@=v={mthH%Sg~o_!y}w*!m^#j`*7ja8h`DMavP_$F7}-eFwI2}NR_Ev2)F{2ih`Z(*8M1u=y5b*{ezonr><&@I;;c7qjWDTBh67W9 zRggQl)5dkHbTDfK%O(i{E9jt?lLeXiY-VJA9!f7{?aC7Sl)G$7UK=YPImFM%Z-O{l zqstSBS3VA*6E~6c4-oAxn1krNC{`#6Ywa3^1J)V!alJGqXOmP3XU0{BY>d2Cji>$N zF2V$>x>wANmz}zSA^7tz#-3OBL-el$L|(P|rkR4Ldnea1M97qGK#MK{J4GC^CTz$B z&z)7yHqH+Y7IR=_f*7;O8wqFP8_L+%;m|Z5*Ct4%VZ7hE|h+Prol$-iW>X ziFjKL(WMqaOa(88jx6J`Z3ZhtpWLAEf3Ny2jWFT6VhysaM~f0M>-IJnhh@gPX5$dey={R!g- zaof`14;cIBF?pgT)+JNMil#I7W1a>J{i*mPG|v<`0vUWcv7r$|aV zaP&cO>fm_s;%=k3UPiaZRDR+DkCn|%%7Is{A;8RLq2HPYk_ujHdE&vO{W#wj$JRFx za5%|owqnlu=FsEYzP)}VOxpUv#Q3IbT=KoshzPOWrL~m7H%PLVYt&U=r1UGdGG^yw|3jA zDXK|`04Z>#tESCfZJ82ZPxu~=9$VS;heZOWC`IDs!HrJj8n7s8isR=)wORvd<`-*R zkDUDKxF*RO+_QW#f#2$~C!mdvfqm4j44+AYu0NU$pnUt_ZaazpFcEhbYk>xHK-kW1 zfq>*>GCIr*qeymZgum8Q?4d#JYW@v99D1bM4S(P})ENiuCPI-HK4Qn=jd5e;WZl|e zFxV{XlzK=~f~h5jC_C*!q{NrYL*(L(R8iAr{ZZYmTt2h$b;o z-5N7Tn5nu7bmG%*1}`P{cz?2VK#^A9n>C+edTBEV*(Shr|&ReB`SP%V1G54la-pDHiAM9|FMyv@jwgK zwJ(t2wMSel8y6GS_xJXQQYsMbuy?iY8X28vye@6fUjOUwteOk(lNc`y%RM?8cj+?8 zKv~?3VE8*A5Y8Pi5@gZ(j;b28XS-E}Hcqj~9k*X8zCH>ek*%HD+g%>)CAr-}uk(eal{# zn+Mcuy6l%~UBdLBg=aVS={G|}rF>v{q;z}`;bqWJQ34Q*jHIrVmg ztNOG4Og)$U2!BV0Jk+Nm+dbC*2ViCASmpaH^KNO;f!^oFAR!?jq5rnE{;{-#-bYIO zLGigYJr~oL#Dd$*^7?;UTo8c2M@=Rwo4sM^?e{)fJU8w5oIZpHCt-bi`FXY({;zy? zn-A6h&gkRF(_}$knDq#Jdy!l3LM5F+nU!~hj)yt=*8%igE z{UrfS@Yg2+ssC(fn7BqYtRNEL-3%x!fcXOumtB*a7C^s|>wiVR6cBy+e`e5*wTbDq zLuEiI7IiN;4dWWPh z2hOQ^rEeS7&es^`iFfMmJ)eLb5{2qCXJXN?sSq^BD`-eEvWuUrxrmD~0fGKu7`O%F zFZg2H14Ps=lW8-tzNoYn6(=9(TrRO!%PJyptH%BK*;vhJ#Czi?PK_XYce8V3&=g?x z9Ejq2q|fxOjkmCeO=*pHetV7`;Z-}VB%iSJD-ein*|hAr95$cRAt$P*VVd=V)qVxn zwl1ma68-_~Ad{+fq?fYqUSEjz^+J$AwQnt=jt~8Cm%~P8+%C<_x(~);Im{D&E1*aI z{s&O57xpI2v4Xup_T!c9CK%LqOJd}DAC1lI)TAWS<;DZ6l_jU$?sH%=-Xnv`5AX?n z(ff4?LyW>g*>l`8_*#{!rDU1HgpJTF!RzqpjTF8Ky&aF4=at4z2a8}ZrfzpMBlj8CnZ(bpk?oI%e*gpqSleKY zGR%Cz_wG$uHPO8gz19hT)P8?Hg>e#ku-2%#&1r_;yxL2=<_TSDgi z)-&klvS`y7)tu|#Dq82$;8M5JVuaJEYx>nNbNTO0o~b2j^C}t z7Uj+dQAbqfL%oNh+nudAA+fV&hn~|z`1KA?d=~~7S4qr0N9Z<~ z4=anEn7t+Rs`;Lk``G)Ym1lu^C&FoblAsLJPP+>g&m0MYQ}z zCu}TrlC$=t35`E%dkTs}mgO~iVTcUqgR}!`QpvynD)VW(kNu#san%vl&0C?cc#f9B zWvoK8i@IGJc+<6O+~8|U#+Xch@hp>XYF!6^vnF`HzC-;CrWwDV(;jRltygb|h0{A| zaF4!-NBuN?NbhhWyP6N90#KmPv9buQ$81K9gS&-oiLc@bLea7%amI#4jm?ByEMy+k zHdDG`bUNyKzlXCW6EMbhVnZan-){gtB3`%4-J#g`4Q6)o032P~SveR;JC7sO%-5-F!|CDQx!`rM( zVLbr<0E#+=onHC~u#f1TW85gsBvI9ZMg&3vO{n5BmUYd>9#YnxT`n41Z!*`hPcF#b zPsWk^YvG}2xvD_we#dp%fG$r+bdZV>+Fp`2LEJsI*CuB4v2R zrm9f(jZ~u>IJe()`GEo#!j0Z3I$D`+?Ee9kURHk(Y3uQG3V-xnWQ5v7qB?1e6<$yr z+Ny=(%U{S^+k^-W3`D)pGMUJ~Ik0;r#a66m<`%oPu(Q;mcYszv_q7%$tYXOS6I4BqqueJ3nlfrAF_C>Cc zGi#nM4jnMywaCn<%sM5oCQ;C@9F-=@%`HasJf5}e=kmK>hzxr6TPn6ZS&(Sh zD)OmtIDNz7is>vqT6!`jQ zr%^^sAAupEE|sh`MhWvCVl~KW(pOpAU-FeSgr-tNHEh*INnCPGzS*FK>Di`Qe{E8f z2T-@~nJiL+K`lZOMOqPS`7G0TC@SJEBwWz5eZ^G1>>=Lj3*&gjIaF-?y+=kB8{ZXp zh;qCm-H6R_>*RVxg`~Mmgui%eIwYqTp9Os-$Ge=-Voul>Toqn$wsnUKz(KhBlJ-el zme+BtrF~za7!4+L6-H((;3W0!#|561Ai}UcHpYzB6E>F|F}@NUM&1|u&$oFOgrK)X z0Qod`;$g2^&WHTm(ba+7KY%RC{Xc+U9NRjd*6j8-s&j$xr_CLo>xX}5o+tm#RQz`d zv08B0G+z#~GLD9sW7Zf|c-C0gQFi^`M9=?O{Xcm5hX0$_Us8O-dmRj!YAQK%} z1hVr&1`x)+AKc6cMynUP!tLxjsmsvt!Q}{#Q zZ-sm+-zjl4(=gxdUVeK>T% z`Oq+E^wpIh)>sLGB9nwj_4t}E@U7)NP#S5HDnX6nWtwF0Xfrv`CIEY(FdSq`^ZDEN z=|;tO-^1pVqYoC^Yo&|UUt!4At^%Nb-fGj?e0#;!N9FRD+``HgRk_M#=SzPxVIkgD zeP4)8`U~m>To_aJ(l;TCeGOl3Fi>|J;MjkHQa&Q=lQlj?xcZm^fw$gyiO0^q(&+?x z$kD_GBP!%7Ka)D21gt@L`J(7(MI;t1O=J@u4#mN&lX zk2B9yeP@xrdY?-H%lo-zU!w&h*=~Y0(7tsYSVGMYcpJgul%8gn<4}$IrrBen-#Xwg zir6o{QT+j65Oz~j%$T;SOI=p>LHYK%opt~DBk|Z zclAR*lmZuJ7H7|6wi_sVhwrFQHu9QiozoqWMuRo3V8`x>)flzJ{ge=igs+c{tJJN5 z??Xo@EUD)4eSZMx#6=V5J37hB1TA;TcvP5f{a}EneJXP#^7pl5Zu5K*jTU_zTTMUi zO?keZAn2Kd?N#ER8%E*PO_w~i3Vo*xB$oXVPlAaQtupi!h&Tt@eR_->j>>ig?nk?IZN7UGIXD={1q(B=v+TV2CbydVsAau=V5b z3#$8Bx=g!L%R3a_ObN2j!Jw|$bB>Lw`^??B?>v*rUGEnpLM3{_rkwf+(`&M{Ac}xL zN2>3UVno;S;%ichxW%&GoT;c5P- z3)Kdu3e`8cHOP3@xs~(=R1LeZ04)P?E^cFlT{EU!>&VF|AF&e^_RI#*4cJ>C&QZjO z8Ie~>Mo}3s#6t8;zzd+2X}}VO%4*lo(NYDrToU4_Q6WvIci)n70y+-^gtZ_`97T>M z>!-9JqfAA2Q!oc~Mqpvz7sdh93U`w=>w^yONdFPCn@N#N>P9sBopAq67Fv4OUO!0;e9k-BdlXTEK=2^lDd7W z9P9d+{^id2tx#!G-0j! zAP=ex$W$R$)d09vw=e9fb;#xJiX$EbZZLFX7<8&eH49hOwm zSuV9YLH%vaC(%BTr;G0(Ps8j?2u8xw*WHC8r3YXTr5pKcr}je`90=oDOL(aoy?d(O z!zR08_3E_z>{pGT1d3fB?3k^$GIlDiK`2HlWdy_(4609VKrON6)7fhmfQ<98w=zt= zLdVJ%pl^kzU#I?taDy@^%BO3U?tJzQTm34;;$@aP_)^lNsVgIv3^eiQ;_c6n2Yo)- z$9LDJX3GMN8-ZE1+QO>o+Y{$h6pI#9odrh@7YG$9f;Xl4gqb-LQe>T2u_6?LCOT{K z((=|q(+V>dV(rKqH5&0fF2oIp!!Yu$cslq*fAd$%iQ8~Si~h>|{COx_?hUq7XVME5 zuQK4M2QH0Yp>DybV423bFocff?3;4A&A5)Ih(Y8sC+1x7df=|%9>zoib?Y$z`EDpd zs}hNJ>Z|?(t-@ZCdBJl&+%;^5*2Ohi1a&i=`XO6)_b#f$qzglz;~Ht=hT+n?1#VU{ ziK;R)K^aRmYE08EPM368-dB#TI<%7r)ye|dB!uITM}@npyN>gzW{vU3>Wn-_=vm7aiwZX@}`H-G^jMz?m6B zyJA;rXHLE(m+3dZfb(KxczygqOAXd)Xb=S!{%mNhsdmADD0S;KI!|&1Z@kVQK)cvd zk7IfSA-)?I3ff|JbbQ$xPIL^~ope{pjzZC(@D|J`-R7_@4V&~tj4{p~l~R>;WTJgR zcznes*x<*Al$6L|k6aguETk_CIntd7PXqqB4n1yu#`M3pQ*5di!}j*AQcrC0SZvMo zxYF=6N)Hu2ARQB$DCgHylC6Zb=#%MEa%&tGL?qhytIfG#L$Mhb5(YM|x%o zXeOqb2%V?d#9N?Uo+$QAxxh*$q8slO$D_^JJ4!EUnwa#A_PBq+)&d)}iOv+89YF;z zf9))TKsTtVb#S6BL+EZY>HA_X2cuik@{IyP-}p?sgbX?`TU}XQL$^7gbRLV%>ZJG> z-r&pk+2#o3)T=&)D3bOH9{)s*tJAqcKi*>-@$d@et~&neh)6bF1M#SaMF+)uzv-nb z--}OpB_8Njjw?X;_Dc{cqwQ9iU*nTn_w5dNQT`;nSeKIzsvv!o@&Sz^j zr-A(Inz<#Q41XQSdjvE5lG`Xdxkv0RPt7k;u0KNNrx*9bv_6PsF-4$Py#&F^X+GnU z2)i)J|9CMhnuSEGkuBm_^+M2IcEs(=f#wve+r3lLpg{tM>2CYM&UbZ}-bLtyeD;X= z280*~8-R@1=VOD&--)FstE{74EHt?>M$U=$_ztWn@~Aw~>(a?{ZbK}2RSDE=gD~T7 z_c%3NjXs+Y{mp`^c|BE9@}^aUqKvDsrQCjKiObK@Dl*K>fPEcm9Wfl*-!ZcHZjI`Q zNuhR`G={o>c4?_*VvplO8W^}rvTAwbHV*s*Elz!e4qJFP%PMEWhO285n_~@*^tsIHY#7 zoUDNb=NADNYB8hebmzrXH0y=RB3_z30rCUV;|jC^26y$``%B0mWW2JuBLMFUl&2t8 zL0K|xUD(-K>ApMOyYdsnLt5*%M@;3XP>+UU#xxNQe@6yD`U7wPJVG9~k1{aPZaLgV zzjVl``XrQzf$}Q!QVWowQwxJ>hruN{8(SlLHwK-WtZdyU2cyKW+%U<&erA>cWe=*$ z6c!N+rifDfcc8Qv_zD99?tJC|Bq`flL%`k)HS>(E(i_1vVsYyDUq-9ous2m@aR2!{D>-GomqK4?EGka1|5dlvc1bwQSOM00B^vlq9z6w zH`lO+FLwyQ>&RzhT2edgXQ5a=DUrU{?o>gwkNI(M_YKTKJ_2M>ec^5Bs{T*ke6)~# z>xG3M@hW8<%u8d-cC*dAc}P~xv#{+{K392Pq2^Q%ipxBDFwMF0YniK+xPir=7UtLj z!8q@qH86Y0J$P4K2K1nB5ZEDyc%EMmW5X5nk<6)ojzqy}Fh|rJvib-1)V`Uw{WvV> z($tTQ1yXk4lA&_2#0dmVUVRMLOqTyGq#_eRUR_w5c1#%{q_merRXP7u<=j%9TQ{N= zPB@hV6wuHIJ^IminbKgu)bdTTynDhh^f-ME1LI?d0ID-}UK}RH*J;X`l;M!8FPRNEpS!2&?ScEj6_UJ^-UcP(Fr@IR*Cr3af;iN? zbJ7bHdx#1-`ZcOTM-|1ETaw}z+GymF_5C|8zp9O8FZD}2CIzeC425Q;73u2OhgcWX zPBsz0NR%U+n=v4rhv^HBdu22;e8&a9=Izq458T9v8JgC~Xp&)si_mBSd`!{}7?LGa zYE4MsRqBYCeX7%;s%^u@?Ua~I6dTKWp%gUbZMhC0NliC;X|NOJdFI8rW5SZIGcoDW zT+p#S70 zM-qko!BD-3*<8?2!GfAM5PduW*@9ejk@{%eGhENf(9QdJR&%k@nR4-o)L7l=XLwr0 zmKPp_^{4MsPu;I#l*OpB6WVT%|p}tSrsJ)5zdPy580d!DAnHYJcB9 z_dT#{3#2)QMRLG5Q%yg}-MzGjM$%yTAry<0PxbvZg9rpe#204BiMv#(o~#k8K;-Fh z>+3QjT+Kz$&r5pCXN6F=SPXMPP7zGUZOYTS4od|Q&g?vAc9T&WKsN$m5Z&(=92$VP+KiyEcB&8+{YnvNO`2g1RnK+J%+)5p{Iiny zm0=7GOG`?jvfNprS;x9Z@^W`zVAe`T*I*%=YvTAh72$J8Q2J>!JqU@zya8t5LoCU& zvU6t6qrkZ?r7~5B{>_&n56i>gVq@NR@vbn9pFbUQcSrk){IQ@J^%3zt9C@4Yhr#La z32|gc6b;fUCy?8#o^GPGq~w*H)61tz7Dk@Z)lW40$BDw0n2FoIj8%)YccpeT0+mho z69wtjxito8^hm6=sUS*nYRo|DIYlO!LM@RZM6=oHN%h`22Y#)6VJ{}b#1x!N`LT*~ zg-6#=Dp(gvU(|4)#ppxh=IP8Fhh^qH_vWwZLvY%l_XDH-6Jt$ z>9Al?)91#>K$mCyzoR-Bg@iV;+pc#{m<^)g($V|;bM{f4Xy zGs%);snHwGXj9Kxb9|||QG=20pt7@zD&2g!l87z29}n*DU28>1tT4tT@F+}F3Nq9B z9Be(2$l5zLfd?M&(+0*hws%87gpF8NVmIQ|XuckBSQmPec{MmNG7-x4U1Y15jM0ir zCa8xLxbvRO6`^Jbwk8MlxhJ6ust1}3ZyoFtggQ^tLU+SD{EAr6mGPQVsLz+2Q!k`g z($;ev9Z@k-`vagL$rpj(tuC=^mrSZ}@QaYoTg_8lWIFb3H}_hqxS>EwC=;TWNJ#bG z5PS$0qK1T|fUshO`IIZ`qVV~3BW_1WTh()Ci(hxEO>rT`1x^GK)|w{8)iJ`+v5I#O z!KEdb!4Z!?HZ#A16VYbUErrF27Tdw!M%O4%*?;P)k<;Lpj<7H;TEez@p>oYWvz;i#Wquppx>*;uxEyE*YpqX2I9e^S$2$6YQRnT$Gh!-MGRuxzlFau_mGYYUx1Y;!oHb z=aMdNuwpiE?^wO_V=ds|mo$38tqzfCFs7zZZ0lj{h#nG~O@P)XF8t;pQ3Xtu0QIGx zZd3EB%#Ak%YXW`x*^JFe;q@^zBQBVdTB4X8Gfo_y`j)E>V4V<@`P+~6RTNKNMu#t} zv3s)mD-_hNJ0GJajl`@LFxP}LiYj+A=Bx$%ji9l;l?T^;6^KgmSRoEV-p*kfrnvMM zw0KzbqY`y9qY0xV$xeIERU~T zLa{etBoC&Zv31i0<`)ztqGhAZPc@O|vQy#K92hBs^IGDFp2hH=<2q4@N-4#fbIS(+ z1-h+7%k4w^TEuabN_BZ{S?opeozQjCi2fSici|9+Y=421rT|=5cd{-}#fKgA_`&pC(Hb!6yvxpSo zcMyjrV!joEkV;OfFNh8OQx#>)nn7W=hH=^XxnlsN%{cT4x1rqx`GF(T_XDzv;cxKC z49>^o8J{>7`Z0AIKn@Bc+%e9dkGa2K1><()ZB+5JNPf`xwfEtylD7IC1ZyW)NvkJc z5~?Fp92&~y=$l2+t$L(Rd{!q@Z*v%2u!HV9sw0Vn_H&cJi zV+!0*=ZeD7;5f*4GH=wOW!7IkozeA96^>^oGB ze3g_0T+cdDjJ`LZXk$-M+6VbxN4th{;Ue1od6%2b0=s&Lu#QFK!BR!*x4jJ5b@mv4`WKfxaz+KnD5;{=;t_`grL zOU!)Knu2_i1*xlFvCW130X)c2GKCvvd0q6q4%vqvZo|WelKY%v{p6o%mZh1+M>aWq zNa!}?YJbU-NRv!v7jAVEHSSRDD1$-k zvChFe$cF)eJIzrz3c+r>z5wf_*dkBFQTl-2y+Y0>NPpX~Ut%lNj^*f_igc2}GoP$x z?BTbH@NDyb?8q}Dqy7NEmmz>n(u+OQD{l;cGv?1=O_#B|%lM7q{elk~j!*fZ*l3M& zVb=#a69Y<%cC+Jmei8ySxS$9LUZ8bt#ke<5;b6;Lzr7*tK+1E=%6tib)`?+S52D|B zj@+s>q+QPWMTzmm^D*&{2;tpEUcf&-j zYC~Wzr|)h#bb-%JCB2qprS>m<9K297F<#3pG`5+;ac;v&D#qHgE8e6qNbF;jan^EI z+Q-!#5B$MDD~Q<4CvnNd-I&ESppmUl{q4DTWmH+^mH&Sav3M$&}jAh+gVNTOo{K-bE=EYq(32IHu zgwzoeqm#<44Im?)ddC51#N{(&;~;PWI1-4>ZUyv9!)3L{$|W|b4C?v2bn2=|XrLs~kIE zx8MeokP&`jmN{TJUl8qShmI=G?-=3i2$D&hrNjbH}!ZZb}2~|0KKkqg-BI*pQr*Ekd-!1n&DBm4z5VTJz zGhBK}i=bhsS{6`2e`m@`yQyN?6t$TegV2m`dk;Ugt(Ze@jZR`jn6(B4t7c@nuXna9 zC8$-#HtvLK1NfBpiZ(zetH&*#7Snqk-V*?Opjl#9@`LlEJNLKtV!3vF-$wa%EJlSI zeG2GHzmxB~>PZe28vKTRSBzZ* zU$!0f@IGWf{fOMP&s4|rc2Kd1y=-JLgP6+lf$B3MchFZG6#kkp;yx9_1IA)kdYUxN zc}ohv8lmD9Y4X}AWmx0i3vPmBVaJUVXcg5u!qDxQc_sh}=rZz|&2F~76)2;E8Jw>( z(+OtCmc?@(r4iOl{W=U=ny?F)d8(g@XUA+nAZ8}ok+sgAR(fj(yj3g(t;-!OMkI(> z*LDkYo3Hxsc)`CEt;xhgF7C&8B zIX{ci@~XhNOOx&-*oYMRWXlN;=uX#bzo^r8s+Z^_Jy~)5KL9QEf*~j&sIrt7{os{` z5zb~6QS;djHrRvER3vp|Pg@LS?MS8##M(#y+gQOQ$m#j(6MP~ln^RSH!!I~2t&N*$ zf}EDtH9wi>J}^KpiYy24Fg#N1Q2(NEb-5gvlU1h$GIOLqlUT4bR>R1Zm-ja2GnSbj ze-yknI>P%ove_5DaUV$&MvtjG%kyS9rMPVPJ2)Cmu?$-x_>w6kF@Hv1B~(Z&sWzlm z11zrn8)3dMce}JUhhu*0rN|x)@W>^n{u&+`8Xvk`b8JBD7n~%F~|3D{&1(Y)YAmrd5lN z%VqSYT;5At(X<5Ca<(kAwRBDL95&*b!%z9;0_Gl1>DH}x=k})PPcu(v$fvjN6%tCW zZAkAo_)v=6E>m4%g0e%K=0^WoN;gvqK)A^?^KbOSZ_)dB=nPIHHD2sVmTp2`0IGG~ zU$(g@hxTKLLYn-P2Usw@;@K3co#K2pzE4)<<_#85RAfpuGW3FrYP7QK{9qj>pkhGFoMb2Z zUN}OO^0@lCw8?#xDcSfXqr03RK0inl!km{+jCQC>N zYIL$VY3z^jDZlwr*|1baeGXqjpN@uQPywt}=u;uek6r)@d*(BP>^W#|)uxxPp1JBT zsggNqR?KI~oR&!vPIc%a=k$U$nN{KOm~I_2`+kr^61XHEZO=qsq)JQl~labmKf-MSu zYJnAY3e0dC@JX9kR8kwVPHfD+V>F$=>aE<(A!KHlPr)c*yq)d5pE@J&?_d^@7iXqE~!@ zJGg_piAb2E!8td$YJxqb9V{ZEg$feNf*eq><{WG3C9_N&>dYhco^6TNzX0#iq8)qn zNzILA1FZ?y5F!ySH(`{D>x&%3&!_eYXd-H-+tPzXIdlp9` zX5NY?3uOEiWFXvAh}-$gVenv2!R$&jG+}9JNkbyA<1`^qDH(xoa?bi-UUA-m+YbkbG>^b=Sh9E;}F!C9)$CU9N z>iBsoby(1NG#O-FcKh8<(!o6^6A;SngwHC>+W8az3gY7`5P-qeBHy}8xE~m3Zp@db zzCdkJA*@vbIVMNG0|qJR_T5gdXjYp=f8)!qj(KrZ)pU|IIT*40(${W*qra7wtcG;> zG)kPL++;EaSx_3u(B9cG7Q?~Y#&2+NY{=>P>uIp;)+J7td9egHZ{iTOm zH&DCB`D24{?k?*tY*^QVfnrov3G>0{H8YAW(-V~=$WHBs0f^zfH%u169pmP*HF<2Y zhQm|5yWgj}Ld@W8!PH|~Ev)kd0EZct>j6Fj&`dG1w9FMR-+h^qby^T@o+`h82pGcd z0>I^ITXX)Hz%HG)`X3L++=>EsUQQx)%_lY(PD>)s5LU;#r+&TXv=mb}%HD z2LakzL&%FT$f8{AN@lHDRaHqm=Shf2f4UaVliwaZ&8&^b_@)>$Ng2GrXS7ZP6r$xa zrBWazhHOgacib{ps9l&{rWozLj2?Btk=6ZZp#Z4R3fErMqmKCgBasU@gc`dHO_?yr zULKK2d9_Od3Cs|&2GcU<#@%qD&6+K@bo_sG{dG_r{TDt84i1CM;7)KG9D)RgAOQyV zK?8%k6Wl$>KnTIz-F0v$K=1$of&_O--sSt-t=+x1>Q;Bvr{&M?u0GE>j}SWi4oxmI z(4G}K7udI{=s7S}DMe`hGq??W#;hpEf7ezx_Q%j}AE_b13jUeBvyP1I31t;lwLnw@ zbQ;j~jmkD|WTi8h;nUV9VZIW&&NND9E<^nzTf0j(orp(X^!bW|uAAhCw0!lGyr6}H z>km76!Y{5qFAU5iH-Bz322(8@bw7P6MoVzDzi8Z*6ET%PQ_KpA$v{(c^Yf4Y1WUjh zd`x@Q@x0Tx{n}s2^{UU{YlODC>0S8QmW!#n`JD$}?#ELgYSU-BLet^f-G{@M7XX~) z^4g2IHII={022n%V@ILU+3hK1vHhtfngT`Vbj@FA$^!c$`~g;zP9azySyD0_XhzBS zg}13fA8A=DPCHFvmyUxZb&c(Q=KCb6 zG-n0(*3Qhcftwmg!V@rfjI8z$g7;bz;g~LRuHY8;cQ=vhz!jJqT}Z3aSWdAP6>UkI z%5d3hLq%bUKMFUxCERxmYP~0MW*Pn&MuDa5L?pzK^^pdz)Ky^Jt)Y`aV%bHQsb(h7>l{vyv@fE*;(*vElQLb5< z&pIu{u)UV9b1-|ESziz#8HZ_5u>p$KzQABug8|~}aVb6v!$-I1?IPTcY4t3S|@=oNFe9ri9;{g_a6?RuA zTZXm`6##YUcyy2>9NUyqmONR2U$^@{j9Z z?5m}O(vZ8G*n`+c{&wc(-(c$3*3TL3J-8ICoJL&fm}jU^v0Tx_f!GU zCi_aOJd!Prju3)`fp9+u#7A(=pE|eBS%m>}18KCW?WjRlp`eF!=14yw_k;k(v$}E) z2JMtjd=i;yY{Si$Y>q5jdt$pHs&HMs*=_(tc9Os3LQh4m7pI@eJfyI8=h}$Kl%n$P z%k01pcA|4xXnelmfZ7BKYK`z<3x|NU5q2(`vv8E5fY3O~BrL#8oA1Ly-08JQ7nuxr zR0el+--LKx6O3(BrO+pyG|x1Cj-GUkrXaTT6}L&0sb;1R0hb)hHlObE&@;bK7ioJ(T)86r?G`FpGo6KArf2zx z4Hsbem+$7Wci6x^jpgqXD#zwfplgF5yV*5A(6KyNLiD#=u zsZa-TJ{qikk`Q>OJMZx^X zssEAxZ0I?wh`xo3&$zRMg>AHpW${1~(Gvt1;}euDqtU=4g|1?$_)WHgQfEv6B)M3l zy9jJHRqP8(X4RYx8+R>V=$9R(2a;D!i9qIq6wXz@tcJ(Rj0Ndvb^1hk<|OQ+F?V!*Vb|&hlDPiHS#&&}r(WtiUK%DLbO@dD{!K|@CIniRFoGFDncDeVi&Jg! z)&o#}Jg|SJcj*w(YeiHQH`#q=Lz1pPtX0^OSw2kG&TBa^iV&m0KWgN0=kTf`iX!g0Qu!mLYVU28j5V#$R*pz+G)aI1^_l$(J}uHl`k`bwgBdV_@QP_(1h zXY)+;BXcbCWLXsH8eD;XD31m$H9BDaagbDcdzDG4?|h&zg?v0QUaZCxb&dDMfO}{n z=}T*SskzKXeZ6`vF8@cOFWOF;KhPc^zy2mM{(p-3*9C0{ZC?^?{y#wK-`}(6uL*?z z0iGDLH9=-b6P6~#>P~4+QP@?-23u`U06n9VjtB-rx8byoV*oaG?MPhHkUkqR*$?wignS(g=ieufPjVXnibL>H?qY2-shLJWPT zgOsc1vSGJ>$bRFeOQBz)AegDC198=c59^WqeJd;~Uefe~Nu?qY^=5Pi(LDBTF#&Np zkg;aBqd-*zfDk1yoX-R#lSZFzY65 zPx|#D{&Ppht(j;2UAP40;jL|edZPFl3vSr82dSWR;tdPQ62|T=4T&^SA)EKzV`X}S zJ)nU(^k)5qKpGS}q>lcjdvw4WvM4;cqQfkPmxe-2Zf81DjLcobha9si`GIpy+xuBl zPg~3{<`iEhsvtFV(n;RXlLn!S^pRPK{ufRG?hvYVBGRG>#nrG+x%&^zk}NNr$>v|& zyHvR>@+{wuGaFy&9l{KQFa34ZZx{{sEI*fItGqkKPnm2=*D7S^7bK1K0?RMt{(SoY zI4VV6wGi_jeEz+UR0CVNZ`Uty6sp}9;>^QeiZ=Tepm2qV4bt zLJ82%vxq_QQBioAkJ7X3rDP5<9A;-b=l`+QmPMM63h7uYzO$;r+t@4vMIKrX@qAR= z0~?REP2|d38?!o;BLyC0*z8-X1z=D+q=J(uygqH{Ev)5vA1&tp@TbW&ra7c_=3U+8 zmJVM#iqD4E1{59GQlBLVO>{nf6LshM$WsygaR$uHHA&_IVI}~y_-4(?)OcD-P6|O` zvlXZ_i3F{nE2}?1vH&}ymr~8taWB@CUkJZfFB7$ z7tM7@FQHE8hEUK@5A1>Dl=O-fpn7Zp6f$$RFMx599ET7c->FqeGkJV~gZn?Y7gO1X z;O`)Lq;!t8r5ZD<0!=Y1bQS75wF%9Fb$YUM_Q1}zRDK2-iyUVAOy_(a=?1->uT@I1 zb!ZBVfEFWUT=7i$W={1l4VZvx=R8FJN9P0bz-Wi+rMI5D*=|{cSBWGa1wye?8vtKR zAq_k^&MAPQ^wdnk9tw(?Ik#La_k-Ue24fXpPN@FhpAz+C)7hw2f_#Cc?Nbs%dXa~2 zy|e-F0)se*L|p94==g>0g-U$>M8E8|5f9lSXHsyACX@2YfX3HeLw(TsdzWev%-tf2 z!G>&G8*`L#8sO8e-!-wWBimglu+V4MA;f*LSkiv?(Ec`2FDh(#J($k7y;A)8`*M@mtyXt0h~?oi3JteuAWK)TC*Ew5cbX6OY(y z&-O`W(ChFMA;04sBvcOc^@$45+KtfK7VEw?W41k)7_iT^G!g1wATPL!5Jh4W^&+P} z!FUfSxuSdv6)h*Hd#Akiy^~D}@(Y6fz-r+(}&g|qlCTQp+9ym<@p41A>ux!@?LuKa zw#18-=|Df!yFT7tw5{9=ThYCG%u+xzBl?Bx*xs{I2;2nG?6%OVW3KUhRSC3tFhZwVTWHVutXL@PWg z*QDw`DU@sk8V%B^a$*kK`5Zqq_=7Z316lEEZ`3CUC+iN*MW zxcxK%SVkBO8%IJqN*BS_s-#5;re$md@Yi%0NRV#6!Cxkca5})Ds5BLu)^T(^4zIl` zH?8-=q;kk+a2mJS2k8vf&!h69Z*+eM`a3*7Mdnb0rhbd^xAb%$9~VUK&i`+Y`vXaB zgbPvf>~AcRxnV1ey5Vp0Qa=y*xcH9Xxt|iT&=a2Y56A_+G@4uO&YPP7E&J)@2iFCz zpA>*3E%O#|l_?=yl~1wSp{>XFsG2RYT(x4xSUcjef>zC4%+--@Jy+|TU?*HN^4suu zqFO`NkkTMVIc4&W8)PdLtC~M%j?ARx*@ZSPWWn^ag0A95$HuB`^~;5!S{Y77kMZoO zl)R!b4rrgv;H)P4Rz%yz&Q80fy2jAfwR_a1HXVm)wL9cjO(&Vj5Vwo_4tYU)MGnlG ztG{8$|Cdnk9NN^R-LQ%UbD@a`&Kvx+2$m@JMxoH~zj8K#{0;U#kZY%(Z@4YP+XV@3 z!&M`f83r!5JwUdAcy zpPHW1XN;Ec!F}&5!j)d())BUfm{hmC&rqYMR3-$}kOd;;Us$3ud=Bh0jOM@)k*q&_ zBthBaD&#m8kX7{U!q4y{#@wOLi03Z#nsva?H^NGB<)DwGb_yYwJ9O12kNO9FTR2-U ziIwB#7(o27&OJ)Ci?C-V!7uE{5Ha|jo0?D@BHYOJ)bPQ*cy$^E_J8}`igmidVOcLP zDzkgEl$G4Brh}n9d=wVxlVnnu>y^V=#+E~&^*+Ftmik4Q&BWj;Uelc8yw$7(Z{hMf z2CSI&T(VrBP39V(K%p^l=t+`SC`h?TOQ-GrEB$&@ZAVH|Rochi)kt%G1Q@HyS%j9vNFM$r11E z<{$knok1{SK}jx#gS~O5{ZnFYN$u7RVVpdg?~q=vMIa$0M(W@<7O`nT2$nEruOt(* zw6~ecK;p23sM5HtxGVrnQlYl`i7kjf_I4P?oUS>NpC)q_j_ZlI%|v&Fo=;8g2)gGp zKPg#@?ZyjLh3_Z!{@ZB5npZwscIn>GxQDOnL44ciVGFfeD0A>6ju#H1j+TDY87t@picxrAERRgl5Tx5qV0crFzAC*k7}JWy(f;PsH!>gYoXG(@`-G>45KlLkl7VD|_V}8e@G~xp|G#_*dTzsjoMm=p(w+wP zA#O{w5OaztiO9%_kYhr6yU?Op&BB~XKj0H{ET0>2d?%b=j>|~)h!4Iq_PdtRSefOX zJa$yd_Ce83lR=OqiG?Pq@vD5bjQ(||Pd2c;iv}ayP3o94?(!qrlAFm0M)e#r3omt`o9EX*FvVZu(|=)02u4J&mj5D(SZ&g_3A>zgzK)J` z)yjRp)CIOans3+Bw_T!T&FSfvKCp?1q>$ia|K52A?^?kpLOCxZ)y~!?Oj(lB1LU{y zDLbVz{0i+|l^xp^AB9}gxe49b?T%as(157yqY{%zj$W8X%jek_kMdaBQ|mdFi-HKhn}6 zQFhP7)c*igCMpT!N}Q_-zsQqG*YsWk4q)=e6~-;yFD0Dh605wf?V=*E{UWhn;Gf36 zNVBp|qH|j6^R{@qjC=PQ4*4VpIUL(B71Q zV^xJ_nW29?m|!7BJLPy6i?L&Xi(`hF1B=bSH&#XWhZy~v2Gua6H^${Y=b+`!j=BTv zYV=($N7|5IcA8|C9xnm??mW?;USk$jS{K;Ru{;=A5K3Fp$Nt`2%NwcKfctPLeypiH{CBQ zpR_)8{kTShUP!-mUqVh$gW1)&LvV}!R!8>;Dr)4nGo*I&Thpp9qzX9C-NS)Yw=ecW zWN{t6x};q-hIBqfhSAjx>WV~j)T1qYmfyz>Xh;dNu{%QDand{cI`u`;=`pbuzvwZ` zxjxJ{sau*O1bg^*s|Z=Rs$Gh;&s=5C~QJ4wADXVe)~2w)yZed-9m`{hz8MbR=QYz~2j6 zY;lU&9_*-x&Z39sQ`)u@r|EF843}$yHOt*idmHU%Y(LB&kT5hW4n^Jt{n*8BsZ{W`Tu)vC=} z7UP05zt;T*qvCsG;EHmj$!Q}UyF7nn;$SyD$u1iKeSwt=P|9J@3fh^g=zIgQAxv_;W>$ZvA4xdvnLa zWw^RHIqqN#dN}*E`JOLD)2mLIn#&rerdbUJjpHt$aZchlCO_FJ0jtI%2Q^iEQOv z9u&8}s#Izft|!}ky=zgEXsxs$JQ;~cb-kp}-q3$>8S9!yarkKZ^7WjoTo zrU^xHcfTVLNm}vUFQoq!`Olw6-dXZLD?ARDl63s&*BWg;_yL(tkno7~y8K8m!a~($xAQ$P=d~rMz~SV}<~;D{w&{_2{0<<>c}w;-#Vg-56|BfWaWGOUp(0`QTw8mLJ* z_9dI$Ux2((G(g5qhm)_ZTc`lRo?mb10*T{hP+qOW>08g@G5r+6IRN+uLHgjqg7&J{ zU+lZUyL`9$zxTRbzWfCYzDa)cV21#^Zp-rpyE%HbaN*_H&Q0h5VVc4R=3PoIbNy+Z zPm7q-Ioe|?{4sLVFvD%8e)2Yy6-za>BVV%3qXR8z)QO4ORly=;!>G*XNDmZP=|Exv zGRt>~p2zfq-yA?)9BwgFq6(}FbaxS~6Q#Wmmywf`+1E6$o?I;w;1)`v zwoAm5tHuRtXT&Y67Vs84UN`=HN-dz5gB!R#F`}n06)`|wQ$nY4fC&=hHh()x9>xSo zEJTnsm7lZ5#koPt#)APgk|7PZ8Tjk$7|Q}S>UOYtedJ`}oRnPJG*T@$d8AmjeydMe5QRPY%E3hg+S74W1tX z|4bAB4ow|BM>G{baso&3+K_ES-}Mv6j$xELhnOuu5Td z+e_&lqEt8tO%lKX8ZBj%Wggy#|GeL19Y>7bd#M2DPpBeRtd+1cxvSEmacw*ixk7r> z0xv~PHzqkhgB!*kb!$f!&@MZtc*|xL~utru$hjr&l8HPkH?7H)ck9iDymil(krT5HAMc% zu6N(!ABF}`*!dCybDZc$ifSBIN0)M+k=1H(h{AE0#Bp>8@Q@i~k;^u6AZ8}Isv*1k`9m*z76V!HD zU3yKX@1)<5c(9?SMkRE*cQ*7a+Z?Xl=Fx63L6Tzu!Sh;I5Vn;}flw4%kI9J*Fq$|I zxm`imU6PAY%uce$H@=J%VZfZX%V2@Gg~X9tc6f&dq^M~!%92p!EjKpiA6(XM83!2x zQEt8XJ05+DhMwRg>NhBa)Uru+f0X<;>@u^>dr{3(>aPKnb$#-CxqRDyq~WkpUvs~LsXyu_SC1ioT z+)pEva9lz;n;;xvmFfC(0+65C{rQwf{}xB~ZFPSS3MW>e^xBcB-GO;VLBohzz3mBU z;qT9^@Oiefj|1prSRcw_k(SGd)}BUnLD=g50ooANgvR7U>_*CV-IUYPdpDTlBpWGBAf3++ubb%vn_VL=QB2a|~idH>3aLf-TwF$wNPM}T~5dSgeq?3iGy zsedZ2NE!s6U4Qf?T!b2znh7tbDg(F~L_gs>48{pSsK7iKNIe$daKG=z7md8eH}x)vYhC^52UyKq1Yw)eOE|>K_Sa z45j%?xkxTdej|91*7dM=?pUQ7u=KrDeS1n&e2&r;y{Lb)=V;GAYMOt5A6y&V;3Juj{?x!RPIEnR#8iOzFM0gFH=yaM< z-!viL;cd@p4p@apffwJFND{5u+mr+rrX|9#4G@1gT|_vO+YoYG!%all%7C@b%zcib z&w=tKD0q0cgajmVfva2tq&YYGbWbh#c=QVG|8oRsrk4&yM#Uuf-x40(v;O{@uREW+ zml|)eGF{$dv@5s8T()DzYm%xecnj;Qv?ye7wYB4UQVTcP7b^k~y5HcPyI~bT#G=0W zd!l~&|PY2*L98j^XE7-p2jdDf6vfc|wOm2|_1Ns6u>qzGit_6#kgfqXhq> zuikd;i1*O0CTT8X9<~$1g_&WkW>6cCLn;+b1q)&=P?3Upj5vAqc5NX7uqHZH?mEW3 zJC=UD7%dK|oJLypd2nr9b@T5*(vW-D{!!?kUHT}gZ}zcfE6y3b{Vh>8p$3YwS?c^{ zve%1U*pwcWeI$kN*pQ*N3CFBlRYTjdUyZrt8oqCtD086dd+`edg|=DDiC%jAUJ;0ixZYF_2O(-^+*!EDqHjyaLJ+Zf&{%On?DjiSy z>Iv!QGHP35gYc>iWM8Edexcfj=)g8814VJu-%nD+C&CXbmFHOG*();a83G?Dd}!)@ zHtM1ow(O!NYR1eZ2CNAHxMGhAP#j(LT>a?JuGWe_>=UJ|hTUOx`{<>Uyeqt|SYH(O zQBOEVVcYElGVzAvBGLT)L&S>YV?u5J^jLDZ>y zHeNcuJm0h`VI%@_jMRuFqS}!5+2|&<@xg=0EN7+J?@RpLnuK>Qf38bWr_e*A9|Gkp z)H!lomXUOuRG|$PF6dpct{BXj2c1!4Iw6g`T2*9NVKjoSw+!ARu#=`nTY4RfK!ZNV z{_xzlH(yigu@C!6z?>E(pV;28ha~dJCh_T+32$!gXH=+={JiCAsIq>IXQaYB$`F7a zn5Z1DA8Lyo{LO!6nGKUhRw*Qnb0HfPw2STVlxP}!{Cbv8-3eLKgY>2J)l*~iTpP5y*bZ* z>f6m4|0$tyy~=BF@SGgCi<%=?+7&BVv8QCsXTk=7)EPhD;o?_kuNGD_Y0bHhM51oG z0XcgJ34~+07We_{`kDntLz2=?V2CmFB+y>fXm`2nkPWqXW`ierR{C1AoPuLRdwCZ% zttI>ZS5?>Wc2`A1MO6M~f5n&BIFHb522aKw8~!AQx3=KGxj#4gMYQWRK2AT$Z{hOU zo&n++m^)xmLuZ0sPPcJYM?m9uMwJ~3h4_FFk{Ul7MTmM%B{y5kpO}fmfez`*Dc|MX z#{En#Dj$5YdP>??hF@j88fakG+X=r)G|t9%BXF?)=us}|Zy~c&X;5KUql}#4nE>a( zr&G)SgNFb_Lm^DR$5yt*=^=J!W4^r7b5^qESuChtYweSL$ z@q)1rto-P?ZoMd9ETNn~ihP$HfJz9A#9-ox15K6H;XK&+bXNJ(tk9M1&&DDEn-&Yw zM0ZdT8K+=;#`g!mn1~WiRw9I6xrDw(QXV;*N^wI%{IFDTLu)E27ur9yE?eh`?J0V6 z%w{>1Nd&;LOoZcT#WynPGwr1x&WergXNr!|uKS$8fAhIA(k8T+z&SSkjNk+Gd|`cx zJ33|7bPqEqD}j^yleFx{D$;E&bKgg;=t-wXhE`$qh0j8A{>%vjO3?L5MZSxk+~}!N zouF_rx*PRw5v9OFM5Z1JD?9WBEyB`Gs&a~@URkV27lCsT$E4t6h< zn!QB_!oMoM!x(*#bHB@-=R&>pmKNxWXpe}hLZ56`$DEd}tlGa0$D*(!V_hhv-dgUL zH2OHi!}Iyry(ZXJ(my1rx>9VMcZEG>8I?p66J=u+YBKYOB_>?@{kqQRiw?3*4pGp9K~!( zf=xvlDzEaf_lEjMxHyBj(!1d1@1=v*WSr47q}vvx1lv-U?#Y)KC{h`G5z-V>OP8bGGzuhk z1f5jV_1)k|_c;$r-WZOdvl#MeX6!yYoJR+(*FHq5%)t~A7cD(ZZ(sl_0*)F)kLHX& zFj>ie?sqE;;QI*))#P02<)m%c^wmN!s)Py6wa(#xGYs^@`f{5gMxw)Wc*CUPvQC*Y z&z;GaoxwvdNM2%PwT$P}T8%ABCbY9dGS;A&bgbp|ov0DOS-I8gf$tis+Y(et$n-(C zI^Zu;9wYno0fpjOeXj>Rd)zX* zEaOdmf2KGPZo)ZKI;|iX`EB2o-mM#N!kayn-tcp5Qc6vWn8!2AeRHpy^7;?J!uRQo zaecXEKSgcGNKbMB-+2!h1*)PW_(P#E_K7`TbwuoU)z}-wd?K(e6D z=NygibpIHgVKMxRe+>d>enmT~(}r@|ubHROe@LU8+GQolF~;JJHSS{ELI}5Shl8@+ zJ)`!3 z*@?u`yp-ihX1i!(ofrxNFAb#DS))fe;01}tA{RBHF+3@j#}(x?BC-93c}Jh|@GB!@ zh($V!1mJGnk`cFjz6o)x=0-Rg-lQKO-G?Y%9h26gXK1B%U=L#@pbJO!c)Wr#u{q8D z{rlX5Ij$Exv4sBAa3qyK!D+KD0{8~A#gjE?lxNb-mu>N zVxu8yS+3&CDYvg(lHEid8Lv>kiZc;1!ZLGGve|L;l{PXfaHX6Pq4j{psp_#+WFfzD zp{uV%w4!X4bLJDIDbdMeF=FZ@)uUVqcFIfj^teas7d*PUM;mC0pa&q?+b9o<5jZye zoGzE|Cf*qc0SDv4Oi($QQ6jvMn|MAH4S4*>>)y;Q&|8qQ8Ah&gf{vwkWiZQoY`ra|ey%cX8SFq?u(zdOEJRj*RfKY*lZxl+~lqtT+Z zGYeT!hQx)nCcQ|1HY~^dYctx-(=YjJe`XWCNjQgydqcnQcpD#$TF4jHZX?3kMp~d@ z0B=w`Ti!B3F!ypJwaq_RXec{%(rr;_n>xgHKu>bPMph1zwP1DB@g&t5-7pGz8UEUWNa?cJ1oTd z_jZsXr4;iU`vy6!f!lT!SeU01sjjKMF3)qB-~Fq87s%)?yKd%x{1&xYCT!*DyuSZ?M1{x()w%hHYL zECqF6`DdX1j0gK9w_mB&_|r9bKfiDqW5!Tdf9?|)856*ELq==kX&~%oMn`8CmIz!q z-U{*yOHA8-pSHa{MqAv_P}(x!Y+erMIez?wr~(h!aO#}x3)W3U>$Y4cUprdV#8Y+Ez$d6w#TZ)i zIMiZMUocoBERnqj4m*39IVTk|Z@iMLt0#sqg(eygvl_V^4L#VNoEgw`Ka&jt8*Jt?bFUn_0`t~lPa1C2fKSGl8`4A9wsD{!h@ zQ}**mkfuy-DCNS_KVp>!W%Ww`k{U`*i?=ker&Fi=8||1W$eOZ4e9< zxptWJdTN@^&WH^ADuX?8)}-M~w{smh=h4WPZ=8dxqW8I!%Z7BupveKx{+Bj>6t6*z zFPOxo)l4so^jRgcSx>Zl#6XuJn?r(O>aXf0Y79kkN|NUE?_ap@M=Ab~MeWOQpVZa= z5EwUngWGG?L@nAT8i^kOZqjVItaeoHv5l`#wbJfVc~bQu2ryCMS=8Na;`?>c?{S+u z8GaLy!tJIPMiqan=Q)tWU!dnGp*X+H8j}*+WE>UMbT(q^ydI{;140eAGtS&H9u)vE zQGS?bj^W(AWUs!Y_>;i*yS>N{FUFc!S8sQ>w5j}nVOqL|IloRh4z1+d0d1GeV+^&b zvdvcTRmL**M_oi6C{Avk%j-1*PIo$nvih1olE0(81zwJhYlRr5znC(@Mm?Z+?qMq5 zY(byCgO3M%*jo5f4xJ0y=Ubs5>G>X0lVZIj95rQd*N>)9cad2|h>hX-!gZ*Bm9A0A6@A=wybGY4k^}8`YOI>840d))N(8N3 zPyPwa_EyD|nA~prAsHv9IgPzq)Y2S0iT(Ed)ox~~IgRs)(+KzZtK@2N#czh~L~)yW zHlxph8pu}fEH7-m#{}i(cP$tTs%;aEahzoOK}vr321a%#(h%b=$!{Up%7G#14njH; zGI+y=mm8&x?;82^VSF7rSb+6Daaf6TjDzW8_vWxW1CB0oq&u|=jKH2K6&?x$U(wPL zV@5eo^^QAnh3z<&B{UIQHkbKzt`!N5V++H-REJaNMWAM9W&}WmauCv7>rSL6=(HRC z*o=Pe1;HzBz_bd0`f~H{1ZYm#-gdqyht`OPRwW89(+MuF7$=p?F5N)9yJmis8Obt3 z=%GrRH8r)GskAJ>DDzL<3{zU&fY5&cEiGk%H-}f6S5wyW-Th+Tb(hiw3dx}7DJFH= z0Ig|vM(D>deOx0n4bt;{y44oaJad6F>%rIIyDc7j!+DGib|+oU*VMzXSfnE{9>KM= zuN%8Fc*Ft(S_NL_qww3)JSp`3jL(LBxr5y}>*#(SUZHK(!=+tvSD*UreX1|5dv|}# z_9vISa{LlYYDVHfftkKzhXNo#MdDxVx2cVqaQ&QeLxnf3!;GcJ62j%ec#U!O97kvS z6ub+!AdbCfX=D;BWG6-QP6&$>N)q5xu46z^JH+= zmhnyR)z6aq|J%){{{T5=ApyqqOWiY`#g@><$HvIk*A1Ygwyl7vTRgX-2 zlz@Zvv5kONyUb`U-Cl;8DibNKr)}Bh=0Zk-tBTU>kX80RYoz>R+ZycRM>)kR-KkYD ziG^FvKFs=pb%v%;TDykxsN5i|KRWCl2VGH0mXmWE0T>6_b%>?Ai=E+Pi}DGGF*5ZT zLM&zpg}Jq5IRa$^O6 zs3v{G1{RTH>Urm>1F0u%qNSK08GC24zl=ns^PQ!DUD#&N3b@=uM>S3N$yy24x^Dd5xTz+LY(hhA!NBk$Q6ZL2VJ z?zytPp)}WmB9S&X@2}r4N!#Z5^g!(N2i1k`*q0Yb!|_XPJXVGy^?V)roZ4~)VHmWH zg(V7A6ljkoa_;iJ+BTDs)^){=UIWeE>))mn^5eF5(HGijB`Ctst|!QL6|>4O0onv0 z_iRmLpH|GDLXF!kD*C1fFv~TCF*W_$>{qJ|FO?>yzAvDbt@pZs*6@AzWZc&t6`d(xTaB^0=%%ej6y{e_S(WPdpk31T?k6(uYrYXj(nSl-)385|l zX`z|KN7n*%wx)MMyMjj(BwR9}3Ds@og9PysaEh-bTF>S?Wv|RP*m2Y)>uS7 z*GXLh7iUIya{-9qo=?4Z9=ED5lPLZ}R4t9c^5-_Bo6qT-qSCoV7<5>1s`rifz)0xW z_N=mGQtGOqfU87pQfGf#6}hfD$UNa)VNl=Qu1;ckt;Ty>f_*IRbt#B&`TU};-o}1} zHKhcKqkjK5p_-03c2n>l&VBqILAI$=O7yBlw8e}QsSm#>^B3mhC2ew;cGBdO3X*kjMm{`8e1HO1Qa; z$Mo3v#X(~&nUAEpgK-l8lQiaNs5+o2fOYshJU~_q{Fp1k>WD`xL^q`tQc6SQd^=t( z`%g0sUlZv5&yEo@O{Ldz!qzGa^zKPgUfSM|>HnTtJ<=)>17^_NU^@!>8D^AinR_PU&o4_3Zp*G$gFQ)G&W|Z;{*1kd{>QMrZ;OC8_o%# zCJFisGb6Ax{RAGwAJ;5aQu`GqAO)}MrWU=>t|*&s(y(Xy8;~L zrGOIogy>#74W1|%ZUxs5*Ms8&esJN61dQJTKGUBo82OiBcMEVgY31A$q1Wa=nns;B zn{tF$h4f2LFsUo=es%k19B1`lMN^`bx>z1Z!-OF_axmcf<6UQ#|H-%JmZiq)gB&UM ztvJ`y$>8>gqhTP%nq`j=1$ss}Zf*g zLS;~WKTjKS6!ilwuk0I4 z*q1X|Qv4y2uS;zt`!Z0s*uLRwwz@?$_e`5&#pT?xkIt3gU_V)Q%g0zQp>oB+UgVe|73z^VYRqyf0y}c ziqW)r0D&6smRXU2dihiglj`Lwa%liJLqV_h)oYzv!Y3s;9~KHMokGcE@@t^C39?&k9+x7vE_a##~(o z%{(X}K4LZ-5q@WmEm&TIckkp~Rd1R91MoHtAi56z{lxHgiQO{aMCwDL(fmD(B`RcE z`52M5fy!EzBACoKnj{wKw`3N*M!R&^PzRpC;0136moryHXAK^`Uk5gR?3%NvyWu7E z;3EH;s%ed8b#U%s`RpDXS8{@MUMmik{PR-S*fCm5T7`GrGGmoI&hXVB#jzd&hyu{` z(Nrcf<@j47pkk9q>FXb*@+9C{pOwNbu}pFNab*9v?lr%Q{k^?)drtku_TE-$%8Guh zVQt(2E*q*h*s9$rp&h8kZ zrBGAh-@EG(NUCIW7i<`M08$D+=QpcshHyHKADs z9tf7MyHBFaBwb}>#JOoBcZ1iZ@z!TzB2%LB#}*8uHJ8IXwN^-l4rQ!!N!ZKys17TG zUEPk#wF)lM78-&VCcB>(oO6(fH7S(B_=1=Qh4eTkbUPYd#m7iD*lX<(%~(u&VTsvK z^wQXz2PPpeE2c=l_^F{lU+Wnw9&8+JFBQ#6W;pyfI!WGs=rcS!T8niof-MgxAaYg^AG~@W5^TjuZ<4_{{O47uMUc%`PN=s7I)Vmi@S&5 z?(V)g1a}DTt_vZ-3GTAEyA#|!1cFPjkjwl2Zr!@KzJI=|sp@H|k?u3yXZoD;JYjYZ z(V^ZEJ(H}T+bO7gerzG30hS9jZnGmC|3H${D4HU+%q(oTD{zJkaZ`<`rA-?Nh+Ox~ zj6W~}G<1mR?2*|~$_PUJy9cs^#($dK)(-LyDK*{qN0axUP`rpaG-)MAh)J|A*t$xS zkj`-XHsfWX5HV}(%7HP7&v}6Ym9p6oZb4Lc7Ho}W#n?vm?1$yhO zfky_{NHH!n+A=ioO;<*JRWi&)2>3gaI<7p8;PDtb3rhXm?$ONVXH97x)nht%oCKX( z=z6U!r-~wNrzeR}n1Y7DU8Ts8P}ZyvD-ytrF89%cv1%NVvF%sWjT)ySAwS40pAob% zE=){;6Av_y=tpFO^Coqr-hPT4JljDWd{lJY=%>|_BB^_eIMpN{FWqKa5t2qh2G~N- z&LB8DN1}NEd`5+=aWyWBC`e^{c9k=|ybf>K;-QI4k@PC7};Afbwmx9^28Demlw?(OjL0gJJGfSKcA;A)A(51QKwl11J5t^u#No4oyT+t_DR zL4&ARVagh5>I3@VwbJmqhO>8|_Dfu+R(EFAkSktE444JY9&Uo{p*Q121bWRQxJ=VZ z4RELWCs$n>?>|QY?9~lQf&DhzD|}5b)msQ0twiK!mhZ?1)>wsDYG%*?08OwqkpBKk zsd~m|$N`Jbvt?v+LCUVtCAz^N34)jGL9hmF|A~s}Q z!NkKkI%Pf4Acd*A7*r~*qD#`C&pQ4&(wJH=OK5r1EYwY4)?J2z%awR?+&h9b^?9ey z+dG0>X=>x6vS$;ga4XUKLt z!ojl(T87m{P;bbo7RNqzUz;M-i)r>!^_Mc#x9MD{Y`lif)rd%y2%K^*XX|lhGzb{F_YiEkm6ME5*`RU2^{m#~+E2J9^w3y9buhFbUgf?WZ`9sz;QW1Z>__NhC@cAdX35cTlX;?~lpx*$>qJy^ z4T7}r499K{&@Qq83oj}r$>D{I{2{ zF(VmpzU@I=SWUXYp643~53XHqtJdShQo5&)` zOYg$OR?+IJo@i-lkMxTSz*18aFNO3!p$$847nek3Jg%SD?+b0T8SYpcbDPnd)zyb~ zm6~q+FZ(F8UR&9+?DSTY2aw@|oKNCa^dh;h!#1mOex=>0(#lA}!=mk}sW$K(M}JAJ zrB($zBB0Fti&G)IcTO{rXZ{Z`(413G0X7OTh{S*9BL*RrZj3ZUzx-gak?s2gO!F0P z9@l~BXz-M)qTNp>34R(r@`XdGe09ekpC%`)I-zaP!OOmYat0r? zz{5zKzOr-i4} z8Rrtkz$hDpr|1!G&@W+HWFv(QGgKO?0dMBEnx1^g-#cCmstS=g3k@@595T8@mGyMt z9feQtX{w{u7JR~pe(DDnKzo@vLc{cq3HW`Y#c<|ZZt%%d=dZ8aR-Fq}L#DxlL3T>5 zapeI+B^-u`o}`v z+pzYN5*1@tZm1Ckg3b!6%1_u0$+&`BLI}&YmhRz^5ow$y_F3jhy*3Bp%ehJ0)=09b zTTdPH7oU&rA}`ZXDdpaTqa&sTZ-Lp}<$-f#Dbo_YJT?(<3m=fKr6UWri*qL@v@vu> zFVEP}S@ZN7>RC#ceIo%{kD$iMT7%#&wZ}S{_#RR%r#$oDIigW(?w~Qg^ZHBhP~3JO z5(*LAE(Q~s=H`fFr!Ki_&z81{V)Mq~#AQX7IFo2w`U46zS>%vlHhwCye>1@ZZn;mz z!Z8GHRg$5n?=OH~U1YgRgvla3k6zo_72=aHQCV&%J|jfaYmg6ERV3s4_!j`T9ObMG z;TG@JR&OM(F}iyt2!VA@J=CJAVnu{RJHAmYd0_n#Z75O5%5uDJW;UT&EqO#2EBDSA z zfyDAoykq_}RfQi)ET}VQ7=o|H!KKvJqX*qEdaB~lrSB714e$grud-DPo*;A{QtnVLp&h+T`*q6aZ*54gu)r8jD05Y|`gM1e( zQ04dU!6(21aJN!NI(*%G!YHMcRB}5Zy+@_eFvh~E_7?tjS20b8nzVp0@8#(1N~ zy6COlD)x0W)G8@*0|^gengANLzBRNOV7ya@`U~7BORisnoeo5kn3o7%o8V5r-*C%y z1Um0pgur_f4U>@g9!~J&Ig2mJUO}>nO{q09w9-w5x`E_(qG_~~VZHJ(%6^Fm%>h+Y?UfIe_Ri96bGLrXIx~?y8_fVnZP65cB@pS@A7C z27b1~z@7YlZ_WO}T%Zl)*K#;w3vfq#qF=`O3S;pFH#z{B=yPL~d(h|HB{e+QuE}s; zD_5L_6L>p)ua|R8Nd)6bC9MU07yO7-`t^zH&EgIG!4!42%^ zC=ShKDEy7uUHZg=38yAPe-4rs`b@yT}m4OFgPnhSdmoV(0@v(Q(|)ktXBS_AB^)QW?%zOQ@Sys3WI|Q-pW zIzhGH*MH<oMJWP9E zgBERXtL(JtlDdaVL?`j;xk`@xkDxg9_#kG)7R;PPvVf8ikSfk@17%*wUjX$PkSh-N zjnGvR>hFveb0q;6^xZf=Obtby}YFuG>pEHAq^0M_(zzKL)A))z6T&J8q6 zr=}K1CsZ|?jS!t>kqd=ZHtO)U)lwEAICi&s|tt=*{lr9Fw8x( z<)@HKztAa7S>~~XG#~%|*!Mrk*v-Kv*0{4en(zr~$uA8L`mG|1Uo9O`TN`7BLk{|a0fiyWd+55xC70rL zxi6!NDHqRFU~`{0-)NYS+lZp-?R$lBfY7Ua<`xm#T3oX(p27Lj^k2Yd;FC)j>+heF zW5oz7zI~HsFKIXIg5}Xr#d9p?+IC zX6Bw{IOWY4Z{t}10yx2r_2XRprIM5R(<6Bb897N5J+Oc9D&6owri8wT_+tx8i;FFt zZC51OD>I=09AxZ;@N{#N(Mbv*v`Wb1wgCoN5sw%=MZ0bEf@gLKF&&TO;-S!^P{ zZytL!je=#?FP1w^Sutb2PjA8oSF3j$|K`s-*Bu~g7NsLFbFl;?G?!YS6P2R6r5DZW zc<_Y~1zucW)|hhSVdXvcC6*f3S*QUfEqTitKbgFB;?z4g(z^RScM9R9?wR{lJtH1b zq$aK!V+pqGD>!#Ny`Q&Z?6*11Vpn?~7{}U6wJ53?&V1tALp_RF{6*oBk|pQAb`#<3 zUUR+cyyL>jXvd1vi0sS41BmN!1X8oanOA~z6sNO4=A~oK!Sp&+f+OHrYGn*U34>M0 zr3$}u51gUAqY%3?8qgI7ikT$3;!0~b&cmaJFpf2UEWmJf!XPe{onfzD#ooHYY%q53 zU#KOUDt6^40DY4lv>4x&INg6$CnSVtzKzP;#B6F0hKqZpYWL3a@h(Hgovr4$?I|`# zFkqNov)C=GuxedGC>A57alb^@(&V{eO_N|QZiWpeQkN53xVtskCJf7mTyH*z$nHIb zw28kvDrTOv$Fqew>25|JSM3ofinK` zBYb!9N9Xdl9(g@yf7Uu(n?R+F)8`6;Kn8>iU4!nUn7T!DN#TiFoNwty%wDZ%aDzWD zO%n_p);?(72RJMV? z$E8x6^h0<$(hqL4EGqgthYQJ>a$DdAUJ+OKz)*^0o*QHt=U5c`=+d8s@CFW=K<22? z+$qth)z|g+@Y@7>Nc(e~*8svLUA8rwHCGnFI%r)5_5H#E^4GtBo82<%Ayd%o=L}Zx z6>_h3A4X{&=^8#V!6Z(Jb+-ENnrXi;!pscZtOc>X5gte_h~uFIHrgAEWm3=V5U(pl z<)0ap9vSb2B7wT7H@?AtPz4lkGm06j6j#P$!qZuX1Vb2DA5C^Ad+fZL8f9(c`^E`l zB4Z4CUG->1?!cv2FctS@QWf}@yJECs&yzcXV~<(NQHa~qR1Nt$JyrO<)`L%+@_z^+ zOUZa2Y`e)`EifeiU<=;TtQi3agCSyUrKiiGWQMnKk&K$dTw<r^8wx&6Ky$X(S}#^zg|!+v>3jiuSI&B zSEunO%0=3@s8xlYCDOQcVjya-?ClXrh}~d#&EWik63k6jIP5HakXSB!0FM%?z~`Q_ z>t|F@+qF)4D7N67w?13OWMAC$5UQh@VC)-YqFpP&S@%m9Sv4Cg z?+LJ`o=u~qL9OOuUuD(S_O~o05hZzkq2xf~sM=yOuh^lnr`R}@jq}fbG!C3}4KKuZ zF~8JmWhfRX*8R>KWJ5$6h*MQ|GcD$q+9PI835V;@P9|QDnuSnR2046TIOPvYS`vz) z;(HWhZU6BQTA6&jr{|!y>)3Unmx3w?3B<%YR4bx|aX#mMV+|~g7jb`@K>qCX$%j+e zAl+ZY&B7-;%Fr%6BT))W zY*xob%pORLU@6eK>n1LW9v{S3zjx&pr)8gVY^@$1jpVQ~xuh*mUvb{t;2}k#Jfb2s zpPscb2#S-DEXvi=;YZRIaZpZj?i`nn(pF`rEM!$vdD%DWYvWil>GBv7!>-BK|E(lZ zl)~0RH$Qh{U8!zGN80O(kpAPPk~jJLoEg=;%aHe{9U16cgz&NXGuH~T!cg+#Seh%h zMMYP1`a7x>YtxgWG`85RxU5T0a)qp18JzLL)+&vqvcfRsmXDuySc2pgEol|2m8^3r z`qDyd&yp%-6|Kk_?QbVjbdVYrKuu*XA|{YvG5btCmz!J*EiPwNG-2#ta1KuJ&`fZw zJ;+BNj$?{a)1@1fq7)OMi_8(S8+v{kT^HXAt1Hn=kl%uThMjt27zTdfTqJ}0olRO^ zMp@NA3MG@=z5Z}czdid9QKl=-`pu0g1jv_$c0g~Wf?baKm}%*j7U7o3aKory=sT1e zf}JUC|K>+dAEZ8@mBekuqa;f=qKz9K+>+wl7-C*rb$m`dm0PfTgp4pKK)!G-o_JZu zi|nbIY01_C_?ocCtWa%6WCpE2b0WD-x+Kc#@84!*HXM(AmH<=d$9?TuId<6k+7TxI zF*_&3?-M)_wEk2m9)(7Fo7HtRH&95@Mgm7(Z2d0C0l&=uf1F7c_x<6TCW($d(GKFR^8O*a~&glg96yz)=!wcTyvD{pi`Nf>M( z;4b>L%$_M^h^UC-DhHrz!sUOm7YzLDG17>^dal)8{UkB)o?zD3Oa=@g%*~Ze#^;O3 z_w$A->mZxwt7?XlE8ih~Ul=Y!$JXe7C#HiQ1>Fo>;fLi2zVJxdjy>^=SW@s_&H z)MY&CgUxlfDbISX{_~Slp@khr$n1!dQ6(pWlfAuGfn%kzsk?1S@EzF*LVBAInM3FI z#m&k21ZE?;iLp~8z%1?Vti`s7Rb*vspIm=2c463J_&qS`Ojx6{WQ0E*z z*s?>1A=Q4kXu?mVooPtEV7u7Yk`QKMyXhfn7-s)9|EH1#*L^KfFkgS1Y`zni9#$lYa*wGASMJ2H^t$7{RDil$ofq96EWU1{1%R7k4_gV5QbpU zo^XaO=H(Kmu}F;smwNpe#wzbs<%vxPov&J)#yAgKG@BgeW`Uv|M}AGlLV^XcH1r`a z*v1>+N z%U&pdoH63nl~V3}jP2Fvf~2M@_Fev=)9k8UfBCpm_7^~+jtFtiZ1W(q$yE@bKoJj4 zr%xEyp-VwX&TzuUzw$}!ZYD}YRK@mnpmN#zt)^ApkWHvkVU2?YgS}Jo)r?wo`0xe! z()Zc)enUdu8fUN-iL68*S$!stgW518Y@Vgtp#VEZWg!}EL)p(P8@)E!^>`3kC-MQH z2v;YP)I?YjQS#fNwk;raHPIhSbuS=aoMqh$&28O#!+z`&r5@Lx!o!5#SJ_gLf(Fmk z%#CEikc9%Zox{*ONRYDFdZYtKZ`^O#dm=qg4t;!2$?NEI7`3xKzHlfrB>i^ORGqG@ z8s5xDjE8RZbL3J>Hn;kSk6leGOr08(Pr50xT#9u534d=LV#Zg$PMQrX>4mZ4cN`gR zyu!3Luuj1o$pV~QSv#+(ancsVAk?H{>x-<$hDU>^h>IR4)KkazZ**N95+@OnRyWi+ zd$31kAxPo`F!DNb5|Jv9H{{r{+aKT3z_leIeZ=KrNKLbeg^Fs1!j*Ns7gzGTO$Tqi z$V$w?3a~Q-P4)9Kj9o3#vbEv z)6i|gm98-$B*ZXq&{2HFsLU{5b|UDt2<;tq_`vwW@-s(oI>28n88$5LTu_VWh%$t+ zSbd>D9M!%pe&4~o!^J@uEMYRf)YxT%zh~76CnnvBT$EOk#Ms%VV5!qNGR4m2t+(W@ z7r$fv=F5k zesQ+3skxpR(+QJ+@5bm!@03|LkMt_sS>uF5q`kQ+U(Yo>8cMKpn=O0LSWk6En;8_j z_pn>ySloy=jZmbbtRuE7=`0}bLmvmFjvbAzFmr6zR`s~lW#hz^-^lv z!Fjwldg{+VLv_eSU3e{+(uHsl=!OVT%tkwll-=P?@R}^p#r4Ho-DU^sm|k5Ezg&}@ zyUnklZBWfKBg$@Bg^d$;-@r>0g{~j*_wR6toZClgad0!nN0D8)0^BQSk7&(rlil&? zqHRZPxkjKK3!-yc0vx(mDBO;hKyQ52lKpDxHE>OL3M8#pzkU+a_NF-6om~QGH(7?(QO8}8 zi%Ol>Y<_$vgoRxl%dWG~3)6{sVP_^*w$1$sRC?4+K=sX0{_y4|4&HKF{gpT<*zN?a zri{pJ0$PvV-1{U+ec}}-`Wxe@Q7=sN7nA)BaScO!%c_r3#!ce$M+>VEYq8D}%q{a5 z&-pY4%%X%lKN=UWMEc1|?C_-lJ6lfGcUC+L?akX6JC{-mAS#`MTmB7cj|}&$2x}3< zVsey_RiDK01$HsG$o?m&{)dH@bl)1VVfwpp;|Jj^rg#?o-k>9sp=b;BM*eGSEd>N4 z^1MA3l~C-l1K|*bz43Jwd}2q%g2GmlE}DWN45B8R95aaNO4#fTX+|~{@GgFQn26zB z+ov}(_Q_vBOSvdRw(1fRBIDCW2@&NMhA30^Vi5+T>1H|ta?r(KWY?>ZgtUM|dA>!$ z<~ab%A=L=lB@_L_op$`lB*l%!LDD6jkKeNPDNYmDT|_n$xJGCPTXde)>G0X;&)xw1 z+lBgn%Y7AWh$K}KXw&zF(Oz4%WFzIh%jA^>I^JaQoAD`Nl8xOB8e$zin=gXtKj`Ce zNFgPr-i3~CqAIoo2@}Dk#Ks;2u>F#hF-yO7jtlYk%OB9>6dtI^q+Sz7TUZ> zlxTCSFmbnlO3tyIXQhkqK-|fwKbhS$dA5H6X?r&7W20VUCg{=@VLC`y!D_|SYqVW2 zhX)F4qkbE8EfrFTAui-%j&rFo@q}`Y*CQZ#IyiZisjqTUjO%f0{uTumW6Fa_bm-56 zRJz|Su%6J+Rt8q6EdUgeG-lPX$uUx1#$PRD!|}TvHgK}xX7OM=y`HMZC#gciB#h}= zPq5*F-QGgNU^0Uw{7nU8XpV9)bVX-F=DQsKfX8?Y^w@&z;Gm4mNX1n^KJE9SL8)ce zRkF_36LM<6rGOI?Ps!0Ny2oIE+wq&*ocJQn*i64G%uMVDW@y!7+2xavg`el5YE!g1TS3${yONErnzLO_|%00*udU$ zIE`CAm$9uE6{3;RR48)WmrRC$WS9UaA=XzEpxElo7naGrx2g;~SRd{f2r0L-rDJwR zlg!KnVt!XxgKMlZzt6g)#=$oqJAVW2*f|(-=xKv}UGK5RCNw|XKMofw9CWNrFwcdx zK853;w7sX(8^P6oFddLfSbHoqM(L}sv6jk!_KhVu?+U=|saLzw%R763^W5unir#& zVdM+j>%lV)IGRcE{fvbO#RbQBY#F4jreo9`PTM8wYlIlFFm>s2(&gaM;vrlc>!0#+ zevEBzpF{l4)Nx#9WUy$d5)(iQin|^1$p2Z>IUu?;AsV?er|7;ggH46i#?gl!<~rbD ze1jeUcOus*W-c*6H!@izU(q3`g9|};ioZE}`qY54S(~qg_vQ|>r<_?OgQ-(kG1XPu zT@jsdyrg%_953#3&4f~#`781Hsexg(4kY(%x z(UkOU?llZ|O8qeU!+LJUon5+nuyX{m3e~W0Fy)&o9mkvM@I5Glu>G*)`c>^N8VEo1 zr$lXy(>{=VqSuq@eYT6JfVEeYesH>myW5Jg?#$4O;zIi;PB>KI$f1kyU=n(DWn!HU z(H=xr83;S)tN|{CzdewSQ;;o>b+`lyGi#N3a|{(ZVi4+sj}VA!f=zcJbB2|wW|yUP zYqpAo3i5LZtPBv0K}*D$Koiv25vcI49~qk<;BO+4=5uvwi+9jd23c$yN#RInwYbo4 zXl%ey zyqX;nd=HbJ+rxbX@Wl7ahgD?O(?Q+-r?jXSy`MD|;th|>Tw$3QJBArjfa(c{_9Ocp zceWf+wFDL5qT7BXgMBLBeWtr;^h@d$Yg~-a1A@LTxa>Y=1w1j?HIeo8=&|gB+y#Yc zoxx^MQxBdb<6ni?_avg@lmW%?~?_U3d~Jg?T*9yUgN zGRTAK#cCw)kI=aDxTPmW{{qmIWD3W88NzX%s4#J&RB{}nb_d|1*N|lD2LTOcjhiB;ES= za@$Y0hJ0i8$WeG@^|{;|xH>%Spv!_LgDQ;QOl;<12W5?F=}ZqajE&4#_d~udb(k7? zppcRy_!N)Q*?WUe`q$KyGUGXOH-l;`5pR#eNgBFWeBu+l6mh1*9Q&p(Ub&aGMFB)G3_Mf{khArD?SY3zMByLqIra|Zc)Vd(K_^zgo%}ta7(dz? zw#P`}cn1iQ%R_L=o82ac6w<9(fhP=^uFohZ=zKTvw(mJ<`Q;@q;Lb0zNJv}3y z?&Z2BvC!a&m)_t|yMJGa^{vTN1`;sNfuzdqqNqmcJN-~6LL5oee}%&#lMwXFJ=2`^ zy=jzdhh;;;&vs{0(#nqWkj18_7|W(3FO8)B-j45M`jL5grwQE= z<~VXvZSg&XET`#Pm%N|EA-M((ngEQ0;$6(UI*-O#s3K-6&M z5^T-dDm6fl`UiOq=*tB*yia6ysFUPn7q99Ejpza4$+D&UtLtP+A3)G^;*&yWE8&C= z-6edB`N$)xLre4KsB+jT#2z}aT&6FFbe0-jU<#!wC*MI$Q!%zKYeqaD5fuHufE|t{ z1$#3EMZ6KWp94dV%-PkL?Fz$!Sb99`oqOc8$-yKZQ{8g5@AGjoxei@(yPW-NEp)Xn zL0$*s?7NKosRD-dqza3AnB$DPB03X=bIHdB*?YP$O2ih7Y*ihTa#4v%v6?ga<8??( z#v*)?hb}09i9tri>6Ok*JMxW474Ou+cb^_>Eji55Vr6}B&ctt)b zqaz50DcYCqcQjH=#p+5Yjx}Qr;#}{j02O5bcj3HUSOS~X@WWU^nu+d6SipHQoGTJb z9jR^D+Ms(=;OPgqQKS!511wWUy5I^34osH(Hs)Ud{0!xg%dJ`Un8l*%S7j{+itMOA z$26694^`l1$2f0CN2Os-hL#THzOF{fF@4n~n-^p=gmsS%DBFHNP+_`UjVsAa^{0C2 zYbf;#a+vJwB&lhki31rnwCQ|dc5vF{z>17UT3>rH`Kkk^-a0@30zgxZO=bdT(FxzfgGvWl%OLRM>) z7^>yirGA_-VwWY@1amOIv+zsf?uhXJ0tQZX-3Eohao^AI9JUN54peV9`|?Wq3#QZi1VHVR{PqkRFwng+@INieIi44w0IC@F;= zrprisbv2UC`RB*1u?c@ROx@UMW?==RW?jnv{tNgNVHh5CE`_ZnDC$;N1?f=q)Yi>p zsvTTojICon^hJbM>Y8}yJ^j}L{m$Zj=}N2wjc1%3 z9%!}HT0#7fo@HA0T`P|Pqdx*SA$&*<0-$=eEO)fxyF%R$%Qwgpw>JiImlGtn5;}zp zCarSQeT{D3w^XC#Evwt#jmT4(as5xle+nM73TiBFzUl_0sJy?DeYy+rtv5CH3rNmu z<}V*(d9c>a{-@og>MOs|$~&And26Krn4>)O*ZK2I!A@ppe07H7ALm`}r5L`|T7xm=o^ve(EUx74>GR$d72H}=^kfE% z!y)F@r2PeClFw<}h9c+KY{X=B)*SigCq!s6_mtki)x^VV8&Fs4=W(ruJGe%GB;rl3 zT*R75EUk|}^3DuVUI+*1(5Ju#o1i#Vs{sfSNFV)_8)S$1P_-0C1!>|GKb9OI>l@S- zqxpLr&eaF0#;Eo@zYuQ_S)w*pFr9`a(tG>C+xJ3U>??}AIpc-try%yEh!G|p?+nsq zt~aYmTbVm$D*O!{zvsA_l)T8v{_}=eAPUqkZBE0RlA*ogV&e4_rnwYB$oK#l(%FC_ zE{k#(R5&BjFy9d6u(LDWNle&Sjqx_^wSNYt=P!UciPH^proQpb)%+X_BNWxJJ(f`A zs@za~kmdKEUx7f9r^ipS6iK`HPB}D{H8MgGT|JdtBAS-VE+P@r6 zHs03j=HE?+s!NnVNk*+O{3*r^PUkRl4lgG%Sdt9a_eW6;9U{3}ENG3O?$2K1aO)1I ztzLn(C;}Q6YEeMbnh21n?Z?Gs)W6??QBMNO?|%gRUn%)F`3pE)d|hsOvJg?>e%p3G zyn_N9U3?SIYULaV|7|%GU%Tv`MK+3~Nsy@=S26q$yIs)V-p+pbPwif6;PPgM=fJU` zWfax3>f#67JJrEInpYpRUj9!;vbzCJdA7av2OExVvTbfmY+gkW!%1Gu)3?2#@`wNb z3=Mcxs$Per@1IV_+cwE)3e+G3K8rG(e~5Wb+6&r$$b-I8>jN5?iqv+hmrrAoZ$D_5 zneAF@JCv*b`tyI9QIU$L^Juq;aT^Z)4u(Vy89A!GaKNa5(6v zQWC*vHO~i<$E&>CJRIPPm`8$&c|b_hQaKO;$opA z82uG%_uJHaXZmnJRgOqtU&P+l!i6Pzega9_BjH{;Y}3P7JA%8bw;FaDyVOvz)C)UnYv+I+VJ2-ShMF-e ze)Oe_RgIXH*AsmH&Y6ZFvq(DIH4Pe%ffsBG%ahnZW5EMsyRgZ^>sfuHS#Oy3;3G?m zUmOY>iaOwRTsjX~z&QjM)M~?LX3kaufZ_!uRWkS?_$2@)U2&uwuiIuZtER=pthZtQ zAs30~by=jxWle&v65HF*o4}^}7eM3pj~wZ<8I5TCbHXW+g89nwlCim|Dvo`va&(ER z7MrUlc*C(%CG5FWiaTKB6seGRweaiv}KE_n^5%h{Drz)qnwU2&7@OCY>pWqjJ&VyGAu|C zZ-oF#Unm26$}_WT)UCUq*@+>O+)cAM*d~3Q)Wr#%4~s6gDp3^BM_B1Hn#hU$t?iGq ze)tgnRqzb#G-u7!M0>O&gA@=~U@T$?FBK72m2Xw&s{aNioo>x?jZ-oBb4W1Bm)D3b zVsmd({Ya}_%BWI4OQ=?ONQi_exLjQ3@@P30jqk&}v|MA@M?%U7zK_f>83KY~Uzcjq-I2Q`ip4l&DvLQ=vW7;0B!M>J3^usA>Zs# zUCTy+$Q+c(7TCBO{Lj?zZk>$``BT6uzKs^7RisJdiz||$FoDnCa8_!5yLfw-YumbI zUXu5pS9eF<8NK%#Kn7YsaG~Q0f(I*IcmC#y9HIU;@^b8abWI zUC3&gdwhf5?sJiL4j!gpL+m~wD;-w zHYf-r1}u?_%4_^hYQ&QHzO=dD@yBuOK-EnhnUD1R_MsX29Ec4rzsU_RZIh_QM|Gni z7HKFU_%f~OHYUi3ru^j(>3;!wNFA(_WjuZHNQCgZTz$$FR@YW{S>f7ClRBjQskJIJ zv&OSE)6~QL^LzO6V$~A~!Jn za?9$kb1jxUh#HKx$D~BCka*FFJ{KUWH&`V38}_eX%^^r&s@eJ8>O*NxZC|yBv2maH zqmT|-fqIU*wd({YyejL4-HbN1qr^*p?vu&O)W`yPbkcE-X<%4pzd1?0&p%%zr8vT4 zvfDPv1*Ahpzpz|(fqKrG*(Uly16KMo^AdB;pdgt7Isa10*%3UN8dIg>k~2c4)^udB zy4o)W8~Usu=R^1+;+?rO@}hXBT>x-_^x~6m>+|woK+?^h{z61e4aQlLN_>U0FvceB z>Z&%k9g+o&BKnjfl);u}+&Wrk%oM!Fw`p=vI3l7Zw)t2+eVWdt;+0mXdt$g`A`2fD zeWVUCM{_floA26?0md0FQ_yBJa642u3k7eB6%AgB;wEdWh;)&l#+-;ud~t{Ixc7yuiH$zRqr(LE^|2Y@9O*j1fwIuE{bOm{XPMw?{{m>q zvynCEVu)@Gc>;9kxQ`PW&@wuIv!M~8C(Kq^+hGt4w$uYZD9FFSjvQb8!Z#J*_boEXyg+?j{ z2c*7^0%SJ9C|SKP2EZ5~^o=~dmHv0-zeyg+-4|l)y6q3IvhVl)nUPs1rV89n{$1~5 ziTM8l26;VM3JPQD>;D3VzJF8sBII!rrbH&Az^XSdJ<21bfG##fllQ>zPsPtglwN#A z0;7S!=e*8p4V3TyO_%dOyg9EKu%oKq2A;J3SIPg|=6_1wrXCVr0*z$c4Z1LAhra-) Xe{b@ihnU@W07&m(q#=A*{=52L7g9{6 literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_structure.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4Pilot_structure.jpg new file mode 100644 index 0000000000000000000000000000000000000000..303819d5527ade51973e298a4289d37c82c3ccc8 GIT binary patch literal 60133 zcmcG#1yo$m(A~cn3e<|pOS-$mXV2-m6ec!i;t6;m!5@{ z`B@1V92^`X0wOjN5;ijtJ`wZ(@%8i-fC>wC5558cMhpN)1%p5Zd+Gw<0l)wdAZx(@ ze_oJK&|u&YFrZ2t5F1qaXAOt|)j&c$EdUT9zyRPV5GWwd@^%Ap8XJGDy9`qmcF&ML z9#fck&;Oh}t;K#2>t(>0a_1eMY$cA}RWIB~5&i_#s8Sqt<|)m#ZNm!~%3yX_P)#OIXJs-G521I|Fp>|9Yxeu(k6VL#WzmvSNFSL^yW^*E~$ z3-#4T$1;+^wB1J)Jf=4G+SMR?5fcjNNZuK{#@k))&mBMr_DQm)510ZIv&_9fwV-SJ zqjYi^ZRh|^|6JePNMabq-sg*(7x%5l3`W9sxxFMYI4QnPOEAb|&H84M+hZEGNBLQJ#3_Et!t$LqFWGDSEQPnrJmnnZ9m%s06-+Cvl}(Hxi(4`Eea@C z%fzuYf!!QkM(JMhqVnvFGwdAdk(>6wTecg}w7nrDY=e~d8;Ynl;4>42IcPvfbs#Cv z7vhi67pE+`%=T&05fDhP#C9Krlo+E(YN@5Lkf9H~^a8osPQx ztXMnzml`|9?ZrZs_3e*0P%8fesW7Y;K`4mh-+HhL&78bP0 zPdi>JNEk6#1TV^mWwJu<)V=w|>|^0R@&XAx(Pd0Pwig-7LE()FW@{ivL1#F99JJYb5K88q2i z@Wt=_4@R@K%-&HwsKXMP5T|Zg?78HG79j)|sStIhS6;*~qW} zvIiz($DZXK)yv0mH@fc3x%@9v);Hs3Bsi-XxkAAoFIbq%>feUDpR#Dv5f0tl10O{w zLRZC#DssKRhDK6Zv{bR|6Xk0OB@*Jfl@>ei(DppA{EY%RvT5&ja)I(%qlgu=UXS#^m1 zV&CJq=55ois;dkvTN;twU(>94!-a9i%4azI`z++@Q7=G z+As3CEEIahf5z|m@&jdD2pMs(cuwqR6>Q+&c0laZ{o~ANb|Yva0ZI?SL3(=FNde?U zAVQEcDS&L-it+&DTOpT@J4~4J`N=o;BtM=2TyxOF9caB}q*u&6sWW!u9-jxq*tOc2 z9~cjOklS7bw{hM;*d4$z&a`nRS@B3)J3{V4c|G^gW${;3LgpLUHOlbQ0I^}^i6r@W zLxLRJNHXyRg1`HkZH9~Ftm$5y@$m*JVqRcu#X5^Q@#yXB$>$UH9DdX>*N;&>&`*PF zNT(cjbI?aVFlSV6Q!w2BG8VYXADPc%&Fru^o(f!qS8tpn_d%Q!`M2H?Gx9^UmM(K% zJ=f4|3nsV}*7zyRU8*XdRfo7-FNjf54BetPVza{(L}O;GGT|pOXSZ8WgCHuKo0Pjg|^_gJ&?`oasA+8EquZ)Y5gg?t~aqwEi<{&+7Z3aFbLGk zKSz&~E@-kdk2QRDm9i$bzbk&ilW^0jb*@2q=g3dBJm_YX{*kSd>fi%EAy*r1-O$Zg z-z;JsQ2g4_$##|Ce5R(8WH{e6Ng@&6fxFOrt3bSs>nlYO$%!(n%b}`49MO-G4Bo5k zh`YWNKfZ=j+V_Do0h@{sAA<`8&G|pkJr5e1RE46v?^2L?l1@aY{dZ(Yp*^Plr@hgv@zsH)9n8a^tCe>muPjuyCB`x_5iyw?<xbDFs0Hn#RX^}Cy29OVB^xE{ zS8Cf1Z~Z4fX5Z0>+g_cyBfJL?b)<`{-Gx$S{678YYW&^( zj>fq`o$2vj#||DX%#X?M4cA}zSIdhCodsgeyPdCCBot#@1ZFCYIAU(dsC(uUR^+et z$k^|AZpV0AFwC$fX(82v6#QOjr*!SQb9aM%T0V)J2Nk+1b&38*e=+lQB`bb; z?cpC)M#?S(Qg{TM`+L<<2l+}@M>e>Iyu%lo9u1LWyGQY9Uy3a_8|mHv0yD>qLPzU* z4`l%WJC^*R*@T6!tzR8?(?Pv4ri@6B7O(j|yl7!vp(hoYrz=q%3EW$^;NH78=a)~n z`uYT@?L@UR+;7^hW!hTJggBqS9<6Lu3@kn!z_kNu01NutY4kh*(1r2{vnt>YdqK5X zAwQRC{VQ0io5A0~EoR&Q61jHg`~JLSKd(Q%;mvObNG<03$ct;_>W>waf37onRe?#N z$;2N~#*?^P{qkqH`N^T-@0wy_LX;9hL+R>bVtPqs`YRTJDg#eh)XilU(loJ-KpjAY ztX5Bm>Z=ZlN&~f$ThL})+^TS^dwv$M%+4o_^d6Wpjg|A*V+idgkCMjhKc8o5#Vv5A z=RMvO9}|a;_^|Ck?Bop_#uYEn^z9x5PnN!@=l*txQ!Z;qG|2t!z!y}0{lM=jsQyfW z7(Q5KeB{prs64BpjPrLG5j(l{SeKui93E)dA}tdhY3FGIJh5GHE~qdc%l}F?so@5n zdt#_e@ng%qY%DigcN2JF_%&bnM7WPdCjsXf=~PRic9-0jJ za>G$=DhoA)xe;mfQ033TUpqZe9X>7*tBc-cd>-;sHL{;iIqPrCYe;Wgw?93|+L&|l z{cYsQ;4asJZ*OUY%Qydv8+Qr%7xug@$b7p8J`6mYDc?>HxyE)tQ#b1Mk^OInH;;%D z+mGvq>~@GQit*|~G+9+3k_`SlkACb%LP_BRd3=+P!mR@-${)IIL;9Lt#1@SgxpRZoD= z`gG2G+P3?x^5Tsl$R#G8XTWd|lS)0so`jbN>mo-KZu>h734=6WYCQtdyg)5~?LdS5 zgZTwwHT$3hVzQuMJ&J*^a2rRX9~1b8T8zjN!&hsqD^O{LB~f2?30J^u zT>fzQqky)duVGaC*JMDy8?bLu?xs8EGi}B4ufkL+tkoaMS;HLCRBZJAoP zbK#HQtpOSF8?~nn@H8xzlu%7t_ADnH8zBju7kA1-o0F`*L_`b^`dl_Pm&8!p*&j38 z8)p}RmNtq@4m~!_$N`;vGo4(iI3ERqIkPY-i)e!P$76GxJes;%Mt=ua&+C(OZnjM) zgeNu;ZE{8ZdewaZ8`t}7b!o-35rE(Dj(k61+Yy8YZS6bv4t3GaK9q%p%kFMWaaoVr zX1^nZ&CJOBlJhW{*o>Uxd;$VS-^q>abNJM&)^08?BMWwzoqS3ceJDPWb5d5N9w#L? zmcB|O@a6_f`&(cF!DM;mQjAQ2z)`x#C%`LV+6}kt1SRLe>~B8}`D0zAyZM@rX3+{X z2&^4C=3=rla=T*$hYq_;6rKRg*)q8wfAFHZ?u=7)%)!An1r0!coXeA!X|*`tDL z;^4*r<&RnE4XQJC-jN4{6BVnX=HLC{5A9X4ZB^dAEl+Q5DUe0h@0|O7$?NWRFIyKW zApf(#7m2Lj6@=+WdJ4w-MivFF3-Xk3gY!29V%-j4hyM+Zjf`s+&L<(+HVBUOlX?iJxpMj zY+AfmWi1^4QuXk+#s7%(ICM%bvs#~GN^tByy03<4D?^YOI#PNh3T8LG=e_;e0wOt_ zpS?Mu4up}LO*CYp?r7F+Tis$R`Q|{F7qqhdB)kuikwpS8ISg;8%=4_Tr2-i*fAj=Xa#J{$Ytwza{T%Ce!iah6c?Hc#Fd3 zuJ_>H)u!NQLxe9b_7b%#sI|3s@MLHGXW^OqDf5NNAE)7SCWHkA01gHL0R{sJ2Kk&3 z0nGsXV(8R*;NyymWVv2&&Ag~}gFevaiARZwJ&C0BC zeEzaMhbGdjki*#jRbnR9VPd&Z7F!wa^Cz^@o$++zk?N0XEI^!@ume$t9PaUSTu5vr zDi!X(v;L47W1z3-@~izr@(=b**#5Ga?+-lmQ% zYvq=;^h(_W;9>1GG+N*1I94lcYw6#k8$lJRff}|xgvM7oPBq|rSIQkT&+f-laQgD! z5RtlG`qCQm^4OBCc4f8^&CMb{c7OD&bXjjUXx-dPQKi6a0QzxRK+}2LIl@G>)gG0R zS_cxGHsExHC&h@$Ateq=`7f?h%tjn$GHVQIIl^3^8Te1tEmDdv)#qDEW}=&|(manK z`uu)&zHv=WK1#re>OlTnD!a*^);0@026CEMhj=xlUN6_}Z6g@@`Vq zRB_6d-Vv%c%da&h^Wmt>)R@M6YSxh^Hj{;aS+Nv()nwJ{-uBaq#npQ?rT9jm$H-$( z{l`ll0k&05xs&~xChnZ+Ib?TF%ceU9%APii)m7#A9LxT5ilNfSkte|VL^W{Q5=3mL zto2Utd!}3s7$isKASx>m1Vcsk#;lo9O8(GuJ?z|UkPJLIc`z>k$_{_Lo{tRn{4$V* zUfo&w{WR!MpOJkpo~=uuLiCbR8#})=gL&>uen#zPh~r9<+zSo1vD*06?c*}?6F}+- zFq|kjZ(c%#NXuT^XFwELVJ$}%Rb)poSaJo!a4O^Q$&#Duy(1556`A!HaI@{bQc`!4 zotrYZ4EZ}X|D#WaZSiX1Jxtop(Sn+Y^h?50sz8XxTKSo>?aBkxcpQ_&1giX`(}U4Z zrG+*Fb90AA zVY1wC;6&>f%mu&|rV>fBpB>Ov;7A0_J4nO@LEyu!5(5Vy6T1@j%u{Oh zQr5*l^Oj1~qikr*%%iUo9u%l%pe#okyU?Lf+R$hrk>^l$J1?u&mPuAhbp80A@8Y42 z9HjC-p+5RYWaeWP)qx5Lbt>C|QH%L3Fy*33tJZ90*k!&<{h6hO8pr;(;@>5(KU2qi zj=%g*wNqFq$8Qm9{;BHEw$p7PgaX4BK5uUa@V#J{NM$mL;W>>Ink+C!Y8rf{!kbX? zX>GTd^b`B*$k6Ql->Pm3A;hl*bldXHZHU+J@^h)tM>ya|l>#cz#Gz9o`kK^Qh2_v! z)5BXZ3pKn4r(bO@CaZHU2G1>pFBJft(PZ;N_KX@;OB2lUQvM|9=1{_Ux-@BLCD|s1 z?W_Jlu;L7S@E?)<7w%6vrDQ!@@s#EN&}`hY-QQ|EaP(a3M$+Szl60i532S4IimIV-j&?>ZX#sd*0`T9q$*SOcPW|y-}BQF)WIjkY2&Bb5UCI%J;i{NW+M8 zea5F7PTU-RB&ludypy6;<(fZ=3Ixwv+3I#?aY$)$mQ~A4F(a|AfCu>=KuhMjMR!f5hpmxL zqH=0zQ}HrW`OzkZ%nvV^NWFg9JMlw}XY1snnkoDXzpb#hZ2EI$VZ^c4p&458GX>jG zk4u+A8@=x7uV(3)wsl*(n7IsiaMv>DN=_VtS1s2eY;`ib@l=Bud`S@A%(S^TLG)=a zy0-4>oFJ^9Ii1*wwek}~FEVjJzg>rWsqgx1Y8%ID}`F88rf|E37Z1RN8~&d;NmZUcDrr~}nwMC)JV$veTo_V(owo=ZzNGYC24VV>u%)bd>*b#bt;y?cK)Z9h&pQ6j z^$C#icv2>N6UNh=ap&lC_3*s>pzVzF5J?G&Ypb#R1~(a!8l1OcqvvN&0IVkXc0H$1 z>Q$RK-h>$M<6v#?0*DNlZmgr-bFWIOm4o$){P;*5b7qOo0@g_b&FBX94;ow1!b4LD z+UqfXhUT(%f~M@gt~PU-O3#7K8*Uqs(i}so0KvIf#!%!5aGPc^Y91xTn{-Mm5r?}@ zI9C$jS2d7@<38P&v!jj-8^UgXB(G!^$D)Y%Ol#axTd94R_IYZ z_wLpibo5kX#itr#x2Ay8h<3~`1fXq2-zQT9I@*5k#?oN!cqiXGsUiM6EOnhIk0eMH zM3QlYY`m!i|6v0mT@jR?O{8F|T;dnh@XVFI6Hs$+~fA+e&AjA&H>%c77o}1U=Tgg=!uwouD-hi zF5Nmu9uuwq@+mXe((A$1Hu?9@n{ptI1)V^3*}r@~cVQ7hyj(TGT@bB}2IiXmjcAN& z0a_j)XKuHgCER;-<(P;vRg)~nT@>ttg4;|>nVEKL(~;%Kopwzt&O^pXvDO3V(DyKF zU4F>Anz{UP7GB&sb9hqc>FG4i|1s(L?EI>Ht|K4iE~PAwG1cwBr1{?nc$cUFm#O=y zto3A{Y|`j1t^Jy~_yzVimG#y+pC50gu9OzVNlp+_~a#yuxAtr?{pI*@X)RELQ%m3LD548 z6fw?J=}AwYb%N`?N-O*zx_F$Vb42T%zNjMQyvbE3Je!zHM$ik&6xQh1Gvu} zI~Z*FD?BcO{+Gu!yyMW~py7o)56_dX4$`lG{mVM5c%w68vuGvb`;LCU3%4Z_w)u+o z3@MppP|%C$#B4{Z(mmEE!8oq{FpQFHBRp6E?fr~0tt#z;zVTMWvD;c}##g>Eb+6iX z_T9N@c(dd!5z2_nq(xykL$FT;&6bCxUdl5yRhuZ%*i+tZLQSRi)-TJx^V4PVQLQWf z{-fOzep@$VPvDQEh{_QIdhzYkhr=zxo8~Ia8gj#pG_xQN0VAP}QX^ioP?2S%=jL+3D~=Rv`Ot{&7kx(kmC@TZ>?D?3~67!nA| z*1wlw`K#0NtQyxG7}ZGR9?>m0G|6O7D7Oxq#teMrFrj~VW|T}QCk&g;13#GXNIIrF zFixpx4bE#1ns#*GlWqo&1rIEMTet_hsx#b?I|Di^H5Y3s zmQl~fn+?=#iKg{Ih<|El^j8#fP{uP4A;t_936D`!Vf;+8TK z_5A^tiS;J{kWk=ihemMR|F$q3QVI35&FmS?!exAGS^Ub!&tS#j z8Pg;P8QmUdk;v6wFtX#@l;h!88n{lIa-3AfEE~Ms8Bp>woI1xYHPQ|ZR}sTI=yrrQ zUd4%g4X276U3dC&%O4?>o=PG>r(VZQq(;M6ONf6w$~&a|8&O{8?O8^3eXG_7yDC4$ z_}&OpDa1hRLL(eg5wHCnjC=r+Gl z)OcWYhS&A2SfE8Vd;%cY3EZe!>VLgcOx^3z>z+|~6r%PxfO3T(4B0lk{=!%7SNd_z zz(u8*V~6OBi&zUzAJdy8P6<3hAkQxlcKN%P?itQydQyOfn`?q(;Kdf7iH%!x8CzJK zcq^xqrnL!vSJbQ>)3q|;tkI(~(;g;=3TO5^7+!j**r0Bm@L(bI66JJwC1^1^&jw|J zNfL4-M{^=PDvuu(8VsNboDm~SeIbrUPzj!jV`-F7%kt$i1bjkHAj;{Ld6b~H;A08Jd+1)pb%maGiCw}*v{^Q zT$Of7jx8>1H4wECKq0#NAUsGL8CUxiqh>B~KhX>CL3A$Mnd9<`ax@Iiiw<))B^nx$ zXlh`*KfV&Dg3Q49={VD^#e~$GEh4=@IJM=e5q3mW;lr}1(dv~0$Miq%Wj-9BB2TYAXO;e?#dta$PqcNrAN0ScjP^Ow z5cxeb`AZ`X)13?snke3^&ei-?di%SS>FFrbRB2C$Qeo<@Nx(%Q*>RxkDC4`1NhevH z^ElCVcu-7Xs=3}bFQDN;GEm3Ke-hJMvT_oah@?dr>+yW%g&p}ckiK^|tW)PPR$9QQ z^|#1U|8Im0CL9k?RrZ%Et)HrP{!(QrdAAUGN=UCUU~7b*{m^JRPiFBLCPo5pzS~l8-ZRT74isx90l|s$LyDM$cA^&hrT#u zhsAvZE#U~Rx{4M`+Sk-gN?12eZ>S*`SL=OJxn5HmGFy}juAqcS^Ty>|ML1we^ISt1 zb51Q$h2wPxm?P6cNkJ(g>fCqBfwvZ1(nPhO&rtfHXptylbvCF%_7e#0siS zYgIVo)QHxZDN;&uHxU&9G8;L!qsNX$&Ri#9Z?1<$(!rg1y=TZJUm5JY_&Ef2xOCJV z%&4t;JI2~Cs(F}Ix?SQi1DBo&Khs1;0${$EB-->`huVG&q~71>BG`pCEv}C;St=G& zzM_rqE{`0(JqQ;~Bc*SGo`T$-RFB1iw?z@E6IKWaIcB6&qUX7C)&`iCC9=BO$B_*aIEU*p2$CXQ6M-IJh)g`bTw-lTa9Gr)!F{FgMpdG(3 zA^RWGJ?67netJcvFD3tDt;l;pd3-pFf6Wp7PVD61i7x(^EYceYf}e0bkUZq{0K-&F z^hQ^Wwv}yfCVMJu2`gVUq?0D<<-{O7vrZN>+U|FQkEk2XY8Vt^H6k~HkB;&)R9e`> zes^Y&=keYd{`-CE zGZGcA?~{G)3fxNhj&UG3dvv;%TOsW>Lh(om3Y4K=J0GUGK{?mno zAqD5JSEg4rKuidpOO>2B63&tFw2!7{0kVo8TbVS}zPIWr%Y6+vSo=P+kK$YGrCqqI z_sHyhQrvmy><1(zab*ba_V%lEtVut50?r&4n?(gWM}6 z;?n}9c0Xmv{&K0jHk|iS-(V47^y2EWRZid0yc`eUx6z`?w2DA|lexdeXMG(>jlXuc zT%zC8FA|0#`Gc*CVP^oQwG0j9=ZwFz1nUM~U&!$Hp}Z~h1LT7JdD_=V*L6qaXek(` z2V5p=ax?zS6aSgq{h2xzg6)>qAWir$wI9$a2>we937~}kd-nP7TD_pTK{J)IK}5sW zgM6B##;n+`Hq%3%8;$=7FU}mYo5Za9#h_i@P*$lZ3m3MyqotilP{81}BB@Y%^}5x* zOb;l3_*f1?I8T6{cdKDOUB*roTVxozilSLq88er_^pe$p)Q;oaus%#qTwOat0=9ly zi;8W+y=OoY!o6<91|`TS^8T$WKnaq`_^UZap$wvct%CE!wgMK)(0kY)B0ln{L#0G$oyW@K;LTS$O)oWVVdu$hr9GFa zKt7aoH!^0{N;uW=!ve@EN5CPVYXWN zS4sLGrGM7_E-|2M1>Gb!C@(IoqAjN2hzGELT90R)HTmH>Ie6Kd&aX+d)&f(Llc6&M ze(+TSj}6DH$Ue7}g%axJV`iHR(1v91;iH%hbH$;qhyR4u)f|I5)PY`0@#(yMV#_7M zOoz){nb{)`eau-ah-6U5I8yre(p77>%O19ls%C=Zt1wS9Lry)EKU(y_8F7?nd9A049z0ZzY6OlDwi|b=%*Af!;d_lvoRI#35#p#F7SKoL~X+a{WnRWIx3 zJ9p6Qc>yrD$mnbAnzx%kDOa_m%NnL5Q~iah-kPFFGx=9Dg?zu+Z-2ADAV0J7`GD{L zkoG++y(ajG7qK20&GRXMmTElEP7ON0n!{Qqj3;G`jV-Im$6j}7#=8iJw1k#KFl>yQ z(!SimFwVEv~{3*8FVr_;6Rr*zIrF$o$YLR?ch$F z-N)lXTVNUf6~~4rS{k+YwY9?)&@hGN^7IisUT&SI%$2$ykF-9uvv>~!^X=leA&-SM zX#}6Pcwyy>l~Ah1P^OLPA0eTyk9I55YgynZR$rCnDyYI(iNqb%w8wB>{MiF-Z=~`B zHSJHU=7vZ!-CSCu=nXoCp7WTf=^LXnxFuP}ZN3aRWn7;mk)g?l4y9+cXZARfNa zK!6y(P0+QX1xrO4{>|$*`s;*U)Ha_ZB{t6#39r;2UXz(0+l}t2;O@RUJyKxo>r>

T=#jcxhGZ<(fudG+2K%VZ5Y3)>#Y`1&_{XNyO5(I|jUhLd{=0Kiuc>!@`47bjHUB??vZQ_Y0~M#xznoA_V|f=0$tbs^utEN z#Z1)AoHQIbo~R67I;U9BktN;`qi=X*`$c1s&1+?e`wu^<#fPh`>wrYa^eT^Hu>3jv zpKhHKDZ!4R@bxkpLw%{hiLEp!kW`<$ClDJ^zJXia8cV93i zeyXPs(mt45o^;Y?U6S@2U$OnEBVOg{m2$F3xBzY zq92iRoBtzs2}niD_V^|sHXl~))uJAv&7>;&YU`XYzWvM-VAJWR-24~7N$u-i0=8(G zyJrdYCqVS7`P&F?GowO?U$P=RM?p-z(iV*ntFOnBK$K~>JN@3HWTR(BqWu$qY*}Cw zM8_Ow?&S5~fGS)xC-2k6zKofJ)N&4kn#u}x*wLexK;ldKo51B8evMBoJFM4(hN*ux z<;R}aG`Rx+u3E^1*cs^#Z_@*0UoKBt#}*x# zWoho~qC$|ylotux8%8c5B7qPC=@{&YlIJ{-kJeBCTQS)wU6?#BEYS2*VD5`k7XzxG zYLud8Y?Kpi=GnZ8s4@92wMmabJw#K5rKAJRuJU+d=BW>ErK}k%?UMY8-moEU#JYRQ zRs)TbVb3;hus_exf{99`Rq%-?q){Wu;=1c<2Tp0w<#oo@cTuzKme$w%lkH)%BCc+- zPS+IgeV=E{T`3#R9ZKB49mBgALSeG@S=H69D6sC%*f38R?f!OE;^>- zwV&HnuhJ!k>&qOl@Oh_o+ZYuZICZSpN1 z1uhRV7q{sL7d*53PGwUk|4-S)D}_g6+tfg*@JdYZS$wL)h5DhE;kp0mEjLPyv{+4s zs0l;OGG;sE@gQt)X*u-&%n(aI*~!9Z zboDI~>CoAH%@{8JKk8lrD*Ihc?mAu-xv??sd)FR*?Y&PSJW(aitc8(J0QKg@*y9Aw zu9z?l&CfJKK$LQBb}bXjKngJywb|w7#pW#RHGO>SF)fX--c+y=g`@Ov{p{D4wxjcz zq$}f@eFm)}JNURO_ML1gyo*6V)*5aK(Vl7coh=VUuroCT z_FMDB-C{d{MObWs!i;Gg(oFB$}(CV5Cvq0s~D@X`p z#;iH}a9-SpZd(t~pb1cMi8wcnta3`VMIcKcB3+O^0+X>|EXNdc&TE8c8tP$vHoBMt z0s8>he76*O^5QWae@m)A$Bcl0)iAS)UzKUga}yTYFPtWf5LNAbokq(|gl!}(ii_G7 z1qlvU8JnNDW~WQ3`8vcbo$0l$!sct-m#n3XZX#x*K|tqI^jU7bH=9L$Z&*o9G<2>* zW;36aP?g$udH2glc^QjO)OVa>l<^anr(K7j4o#?!q#Rq9Jj6CH#>~t+k=^4KOA2`t zv-m5|&zvY7^%fmjt;y1P8X_IAPIRDIA%p`pfWB<6NBHX_UZisw9gfCW8INu}&Z}Imtc~SDBP_gmx zW>$sW5AS-$&#WtC87q$-IJ5iw!Pq8p;*W|qzOARtJY6%2%PITe z=PLFDAc?sN2~60__A}ZgVl#Z<*S|8*Hw;}=>mz`g?KREK5mK|DU^9PM8Xvdm=>G($ zlUVP^l3THmyCB$J^5r8CA9I$U>#^>}H*MWlz1Eo4cBH+hH~kFlRgi%ln(INT{O$>` zXn0C9A*|>0Bc9{^jltE`F3A&sb#wA&?iQT@G?}}~(F(Z!xh`nG$K=9VSjOD7*(9fB z{>O4fW(7kOki(b0Mz&OGeD?Li6ZTsSMH5I@%;=b8@_oYRNrh?JPDMA0ux;McbZ3fm z5O<7EvFTXPV#eHa{!m*~t1?1?MdfKV*gN+5aCv(v%JGZm;;?&$7QXqcs5P4;S@2>a z(xh1yZ*#P1>2|yv;Mv0w(r9@+3KSwFZ=_IBp9YXGunM&FMhlP>0)fUWx zCzKzxirImJRLIK*^+jEjLo%K#2-UMMlRX3Nl?#5(^YQo-pl>s^a;}8h^Ff?@Z#v@* zx<&A8PAjFEmILVb$degn+FiZKDGaq--6NKp3ik=S$C7mfIK=xr!(aGwnir$f3!eb- z0%G@NRfE3a8NOT&{E|46UoGsZ!b*uJjOPuyn}0cN zq8^5wrc2tv@o>evc|zY{Y$!x+N4L`eO&cR>bx9qEjF$`0Y1FyiPk@iZBx&m+sy_Z@ zab1_Z&GNXE!70jsWrx*--*XGDM$L+0vs$4nk{dwYPAHjQL&KycP3dDQOYM5H(sI~$ z+jw#E+u@e?Ewj#qKt9CLB&NLwx10mQn=9FWEO3kT6u&AT=m#Hjw`eS3W{rYVy=w^a zgno2V9w;?T*Z-wRQwr9Z1pMEM{GlKR7njRRk+HJiAJ48}&^RCDXL*Jdi%0>kj5NKb%HI|;h% zs!q@EOB0gDVPSZcmVW(R5zb~_?kB2J^v&BT_|}`$d8Gn@X?*aTPHE?ub}!y!Cnzg+ z=_wwRAvU=2hEWzdv~Qn(wyXJA`i{6sz02g1qFQHn7#}06E|l1BxpCz~5zXLGjAoc^ z77_A{QBb~5$swjQv`v>~kp{+)N!swr6TsHqLccS~_?t6^DWg&l8I}fz6ycE+@tg^1 z9BKd}%o894ynoPlRfvGGF=zLE&)0FKSY`Ng3$?jcoQ0YSHBZ_;ojgjl3;~Wnb8W<U@lkASgLwS;3y$i?^?ALTV7= ziL6sur$eV5{D+SIYVc2caLgs<$uil;Pl{Ho_1Ov5PkN`iOT?K@6*0YJmP$I32UGOS|33Dc(m%XT~be5zeh(i`JmS z`f3^@|NA|o$cn@7Z~NWM!Os!Gi*$LV!|V~QGqYS3GTVK)^U3zd_B8p{cqt8%HNEL< zL(z3rT#1T>s%Zz`;FW@BBn**5{DDjBzGsThzV zc6Q!3H=Po@p9T=Xg1v6Z9Oazc{G42d#DtcsRP&*s5&}Q6O>pV0w(|(mSmUWQWi9L? z!M@g|KTAW$MIY^$pi$bHvS9k;ye8hd z#lA8O1=INU%D5(5p=y42+UMemJhTEwFIFm{wc(_`tw8}Jw^&zEPok(niZ}RMEL^&F z#LfWjOF#4DK_Y}1Jh2e^-D6c%}iODx@oww&D&K!F7IGV)PGp}>8l z&oI2ePn!Dkr>fM6S!-#^WX|?iG6qB_;}O7Ft!-(fNY3+cn$MKmO^(+<=FUHWOmyuh zJr)^vxxRdsc`3{A#2?=_x4C&2y_%VTg2T16Yfa9JU*zzFzJt}p0qwae2W+>V;UeF| zEwa-n+0LvqV283*x*anDY=siVPE`>{ac9-npAJB$ff>U-~ATpeajlp&alhH6v0Ed7jj6W7cvF_L*Q zQin0Bfn-BEhpW)eRJY$J6`l7zOGg=V^`)VErukSe3kSu`qp?z|*^gn$rm?IL*ZH9C zGXQWMsH1$U?Oboam0HCw(UKz&)vs??4=z31uT;-aqsA#sH2e@Bo>3y*M)5AKvM!y; zn0KI^xXlr*k*x7O?~Mh4XD-Qtzzv3Re%ibg(ga*{>&THKjYW`&%{{}iir!-q(@n8K z<;v&)eYHGvjVPXG&*oYJeNOX2&NIA7hzo;?fUTvpo+9t+)MfX1*;)X_ zq%2xPY(8S|l}?quD4(V)txYCa4*kSNp#77;(ez;!Z)L=Q5!v!U#ioGROPB~9Xcxbu zZLF9XB*~(pudSC{ij`&_$3IKyznGu2CZ%9EXJ99}#4taQ5Pvti;y+T_ZH8tkT-w~5 z4yBu=x>0|{nArLT2Cg%<<*gPf*+`iH$IVb76GsmM^S5(%|7qh*?Q7;H783kdll?O^LQgN*v+~;s!71AOx!#PwnhJI;@1vTC%kTB7j~?-mYxyzIU`dw|q-d#{Bkx z?cLx6=fGmAT?AFFnAULJ+b!uzyszx%CJIWSLc)>Ecq0(6wz}y&;a~#z;x|8K{Rv>1 z2B;@e4mV2?*~~N!(I;6Oe>77UB$X-Nnue0lzizyw#>vohAyFFV%5Q%Tx(x;AbG>5&YDaBNuTpqvXFlsXBmuWba05g4bu}FlK|AEYgmyV(v9^UA@k6twdv1#vT*#N^_G1r6X z)X){-p+??^4Usy$_Zw5k^wUnTL#G1u;bZPgqk+ZVj!|6k8Ivr-gA&#gCDBaB7FVd= zyD|y#%AN1`3#(#ylZjj3QjeRuRllO%_<+53GNbLOS8zCJCLr$l5fy~Ge<5X59 zy|~j-M6SN(=xdBjVbTK>SIjp ze{5DeJVvF1HZp$n98pvcZ1WZ5((J+ubMLw8J|y=z)j$an)zs3hDWyAphY4nOyfO-u z96QbHNE>6akNg)LD<A}h}9np#1tcA0oqd9EeY*JT_x zA{I4RjgCIBVg<8FntPGe3wU z6>@*2@k-l{3r=-=I_87_@YaVahwJ=G+&wv^^C}I5UZ0fxddyuS@!l1#5u7cm2sWEA zxx^Ml(z!%&%6-s7TbNy^+CjS_`EK^ zPfxv%b}0|xcqRPJ>Ns}<-`zmZ-Lgp<-L-ClANGrVbi--lcVBz-nRB)_HiW z{7Uz8_Hyw|?|MaNc&+^n9g+v!q#dD#zuzS5g*?Wp?k4X?3zz+ioL_(sX_Fq&SbR5* ziU$=MoWowJ@q7=BX|S6gJwKlg?D2<0HFYxyzEY;5WAws4gEsN=kUj6zcv32N=fv54 z%lkPaMaJjUSODADKjTvP({{_18gDg(D)~c8iGYf(sr?A9O=Gm;Izu719h^x(423mm zUGvQMJ3A=PDXI6cEdtrGgq2NrRqXOdXY3>i$w2mk0I&dZU)E76Ai`-C^cTdjrNxtWYc&i@P zNw6_RC0B$XtsW};c7O%`MM3?~{>UF@KG!EcC$8cX0#|ab!Mc{Z{rqe$Il?fvl#fvo zGQr0%OE<@a>p;8m%%onj)jq)=r2&Gd`v?8OSRk4`5MA>pRPvi=&tS&`~6})MJvs}tD9`azQuU!`w*1pjc z5$JC?NT!LbiJIA*Y@P^&J1Uhv+_@LrVcWLT16Y>Xe7#p-Zm3^Iru9rXDOI<%v$pp9 zLL;5oT;uFM>1BUSbEx^kstp#GuTJ^}2s$%%{qf0RH)K;ppY-9|O55h`)WZ8;fF7SZ zfuC2+?!D(P{}9vR&y5&;Eux8&%k!$~KRo7dF-1*dpM}Bf9TA7^@h{}fZu@tzmEAn<6`YNQp3$__k@aG) z>SI2QJ*)mLD1C%{M&9~Itl+_}d7$7DvKR{3qlkP2v=7dsT2+{6=xvXI!rw4zOp>}# zn@#L5^r=8ki;%3$8jK7xsxCjy&-=3ClaQV{uHt#QRn)w`Zq^Kvsdp&4i?LXc`-1td zDq)8_L6>kygrJHe)`v~!DfrZ=qK9hve;3oGjxNET{u5-6vTC(|j1|)ytF^(|T2kn* ziz2fPvrE1>(u)hb7i1z0(D6~!*wu)U+-F|L_2Sy{f5feSfIy5_G+t9D&6?fWLy3Id zCd^9?wx}pZA=b8yvVP-Xw>q;T;iFjhEcj(6R+pyboCB|-{tA^*mt^H5ruBSvWKX@s zRrO*)$ht~!&6=;2?GoXWdNXQh`h7E(hw5A9pvKn6yywlw9~QE%|s@(Rq<+N8Yel`i#wchDdJo;}#OiLy=SKV11n zfYa9Njfq*V{qhbml*)Z8F7jDADA5$t)g)WOL5Hmo`U+nM>@ozNc4stN)%S zFmJ_JH(7DlcLTCl#wbq{SQ_}I4H!=lZDfL5hq$$1@AW)*b**;MewcOr#iiOA@qM)7 zUW6fb1xn(N$Xai?om0S5yEq~lx;`Ad zfThaIwOWGqlhO97PIcZPrGpWtf40)k?*zP`)tDuMzf%-kUQ^HA8RP2WPd~}qO4-jZ zJLNwMj;l{?17&Dmji8@I<4Mp$PYvka2-P-J{b=Hv&__bNN4q}}M0 zNE!R4X4h{F_S}A%DBkXZ{0x1Tx8>`N0Q~!w4}zFq$KBME8TWHqqwAWKsE;P4>_m0Ehml_&XRU8$9hNz2p2DO#siotveT&g!d(#;ST}- zNQ-C5G82*7tFP`9s=W;-j}XUHJwW6wC%IWZ9D6PZ3 zw{j!W1O|zNZ($j6t?4$nb~hxC{$e&2=`GCtKJszI#AY_MP?2naFDnVYdK63-Hu|Rq z_Zj&~zvhE3raa2a8)ZfH6Vn_*M`$>J$%q*@>>M0{K6U@$rjm&DQg@O@#iw@M!IgLJ z*4Wha=Ip=PXthtWbsdKWfIL;PM9N9Rg}&<(W_Ne~ryFhZJWok`qPdSfKYjrY`IvuP zUt&77<_eG%ztFLR0chBQ5$dqUnTEyw^*0Ch$Uf3?_<}O~k=|~nU63YgPE_#*XkOEY zl*1-zA5uOBU3Fn0*~les`k1FSkdQXk!-h#ZWFIU-rB6kkIb(@qvY%uJT%JD) zMtK)SY5>|(# z&ivy~c zo>75WRqO?q8#ITi_b+F+O&z`ycb;`mnjBoMk%(1YsVRv6IR6fh0a&+tQtx+FHcm{P zpRlg#EA=x|x4*zeTUgV58ZRxN7T@%k+-jG`F}|1=+cc6k#}r_BrZK7Dk*nS7lwro9 z6R0BAq35eEJ|o%+ttULc+JKOYr{k=S(GiTSZ62xF77XgD|il z+AnQohvrsdLr}V^eJ(aK+x*1PVE@zV2wT4FRZWq~NL8#|76wncDm`f@!BVbPlfGS8 zJ8_&#d!AZwT~*&dxLolmG`Q5}yah(D)jQkrs^XS!yDnT*`+2(=GHo4F&CyYi;R!7| zH_UO;$hf5U%7D0}mx>0wYkT7@P?OJYT3MI*r1v_%e*~0$qy94mZn0nJ+)i)~?<3KQ zrHq`1CKQXgP5$5;-qYyS<_#oR-j3SDHH!zvt9|!$XkD=L3vVVN)ZZ2Rn%?!*F;{&# z8JCvw_NWnql0!&<cymvG9l3tHd5xuJ6!mG{myxNS z$J-%C9oDl&$5?DT z;*paVUI@_l5!0{w#~Aa+RYHz?P_A-P%4P@Dm=krBhow>%{wO;q&L1k;*eKv_q zN!T}R$@UUehN$V%gzK=Jc}scCeJc0w*OC2dtn)S7r?>hqLBz2#f-7^<9lQwntm~c? zA>O2~CKskF`Xw7%eS?lq!wZe=iZ$JB7+&Zm4!_hrtJKlYpPa>*j7M)!##ZizgEV!fm|T}QxbGbO_t%d@N01s6ob`>YIL=IBCK2azJ<^X9re8d~Jcq4H zx8Z_yWjth0_R*!4@O9cJ2Bm+}MQ?a#b~B;zg7&Bm&Hi@?14 z|7s&HplHe-ktEiM*PD0~-4V)*X?|*KV|wr(Z#19rY>*v;?I(ic>6`akUn?hv|EE-x zf5;VkHf6<^iLTIA=VAgo35m1Y|KknrE(gb2ILEX5@y+|N_JK0AsJ%8*m8iYEe34`m zVvH$#PGb(bflFf!+O_R9kHZm{i^}kAe|EyOZGZYtn7i5XGQLr&VE;mzLKh)-284l2 zwJGvp_QdFOv{bjQY_w6&TPnPn=~udx(&>#pHxHA&T1`H$6*mgb#M5eime2aObwrH9 z`~$Y5pLs!R-9NwI)_B1$wP_ByroPQK>DX;|CmWCAc;~Y)kiFCCu&wgNq}i?Xu5P7G z>t5g4$Qt&mX&hE&|Lr1lC=hqJC9CVN~=AAX`Mx~AU1BE9lrHD0Nxn~oUdvpLIy2SS}+_ev$|$ zz6ZM4Wm*;=s9Pp4+OoeGA9TM^TKE}Tz*E{+YIM>IndaKZ}8ja5X` zcXh?@crWuBM!CL96XeM?UuXJJnW^47dsa^{Z z2P)0!=KliBTR9hXp>D6W^0&&7^9sCF{b*`R z1)eoi0offq*!+rltBlz)k*|6OVxK*Y&PEvIGvTRc?<_sJsOCRuP%oZHihi!;em75{ z4D)nGOs7bb7RyGQFKwGr{KQbvc(K^h^pB7vHIgk<>xECMOT{inK1sdwvcfG?!N0Y+ z^6oSi;)Xqq07uBPi1jPzn!mGuy0J5D{Gqhqp4-|XnwP`DkzA^1Xnzv!D`Qva=Tr`N zAJHoCQVQol&!+q%pCCnqB-tWI#@-DIokL*ktli!%wWNfQ(To;~UtyjutQN;7pV;Ts zuIW8{9jDU#hB}a9rTMO-G+-@T1;#?}zj>@hAqH(}sZ!+-Q`nr%fbAhyKXS3roudxze|J1?!$~mAMlz406sx&*2jJhbLcV?aSTr8QJQ;SK7?-QvS#^m2Co?-Y@0L@z}N>E zY%{tyi3(Yk8s@T!0`BkJ9zH&ucg@TGgIOWrwK|KIU&S89q5;^c#qCr{|BfnVjdb?u za2OUV_J}}p)m&~O!NG-thp{c>mX4eeBbOtIvXF8+GNe_KeK@uyUWhA>maoh79ne

~^rvS=HB;+1!4f}vUYS!3BG`yuo3Qo{&}^I=aT4emBN?~^W&($D$Z4HF+* zUfe9q-dPWY>5|j+Lzi4EMV-+OJ2CNy?@8Y?VS$UpW^_9-)OKbP;HRP?RzyYE0Qfz~ z#gjvu5DHik4Pd%QW}d>()r7G9=;+U0<&^Al)Pb73FChAjSg>?D_wYzFtZG6aO72A} zWoMTOiL*SaR1C#G{_ z`Nv>m#$ys)8}?`TOkPyDd3qRVLUF;X%?zo+Tcx{xyW{_OitfKh>PErIPnZj&QF89? zjg%HsA=+9goOI;@1JnFV?+?PK<=NiwzZ*>G{{?W2A&huf!sI~uSx07y^}|@Oi}I$; z-B04oZRa9nW&7RMFF^BuAZQ-AETiV;EF}C#d;afta(h?=F!5$d%Z>_0jOoanIoxnB zAgdM$bf1b?ahUtY_#IaYAO1fgQAn?G3KTH+(Bn=S{d>a4UuWuC&czZ$eQxJ=@ITQv z{%>*zKH~qv`1tb>`CT~23Buo9yIg4kPw$m4>p`k=fsC=^Na(vM(J)yfWEw?g{x;l@ z7f5Y5SlmuSIAm`f^MwYuNpe1L3w1@`)GfLyWbVz^kBC|hRF1@#H;+qE+cw+s>G|}I5($t+9I-^;4jO8K>ck5ed z>a_lUgAINI3A`H5gt|^p0LXH(NV&aWi}b$)NZgk{N2qVlCt$W6%XgBSs&u&!YyB1b zWhIH%TktCt_gaDz1qP4!GnTQM(eSP+%8wpyc-@S@0QptoE%Ur4?eTfvbzX|x2cxP_ zuCD&zhiS@{U@FBgrL}ay*9T7tS?uE*bBGOV$p~J_z0P^Z`s}SMbv?n{=c|fhYxbjn zMmdDlIq{q;CZ`tLq3QQAF0l2yM?J~De~*7Q@r^~m{<<^pG2m11PZs}?N+;y=Tvsbz zk}~2QZeBn$iy*oC+956z`#v2&4SD}brIKjmB|T40Xs&DtZ>Y+7-l z2!%^RneVGlbD|fUHg^xTd|Wm*Keit0CC?q9!Y)bAx#D6Nw-voxYCu^;fYz*GmRjd| zNJ8RJAW?}yKHW3jG`9eJ-NHQepa>Z*HG*&Kz;?4(T0fAgAG5amnov~+V}Lf^yjE#_ zBvPSLO!&KMoUR`1pPx?#=5@G4bgc)+U3?W#^g`?(i-)^46LD4Ku7Q=WOY&0{Y_6NcDe zEtFtV5RXR_*J>byKWad>VezH`af7mh)vwy5goaEN!+cMD;yrPoGPe@4=La_35kv3h zTD*0cy+@398a30^ycA6ZTZ5pI4u{O(t6k$LP5v<21pJ}=b@GJbC$6G4rqIAfXhXJR zl#Y6?Z4Z;NVO$-f6nwI|CHiwVWs7-WO+2osSpe`+=&TYYliJYcZn zWj>YXO7PJ&L?uZ+m!n~g?7&vB3piIi9ij| z$>U<`vqx#m96ytEYxJ4o4L59V9j#qZhUHLBAhQI+Z7SU-7SOqq=Gi<&FD3qlW?FXmq%35?$z!Gzvoj^(Rl`V_ zZn_3r+owV>k|&+*nRvDp%&g~RcVAcZ9M2e@CCz!&8=S$#kek4XH%Isb|gG` zVn|;}AA8b_ETH39pXO=sBwJnNB}&(ozK~6^XM&@#4&ORa@?NG$9&6#8J)~%tCNZkj zbsI{6t9mv$6TDC~DR2D5=yQfPB4P)RrWZQYhZk$gWUs4LYm~;-6nOtS{Ws>GF2qOX zAG;Yk{smCptqgVuk%1}X;#g7a% zPjF&&XO_hnzswSBADZgZVOP_cLfd3_fI8)7pZTt&Q^u~K3l7%hx;|r~eskucDZiY# zW)cx_bv+h<4dLEdZuR%^ZEr*Ir1#mlEQGEr)>&Le)uwOung%SX6$EFx#}LC*WZ4iZ zCtpO>anQ%m{y74C{}`>X08+`Zz~uPmX2EUHrR?&uschkJp$3hCp{=JM*=J34P8XLn zEW4S9K*AMtF5&Ap?q;8=euzsC8X!w?7UcJy6ec!_~Zs`!0YrkQSyqg={!ON-16;{v%u+!k0cszt7`+5ZYakU zrgM=i{xb_qupQP7)cwNw%46aGHqZY96;t1Idi(5uXMjEef{ORi$!7n7^cbbq|Q|Gs;^&cetlZLpqu;^%LY0g=_ z2V3tCo(4`mu=&S`;lF(DefMb)JC=EIxTiL*j~B{Ro@`_SIxJ9cvW*kU`;Leh|IR~` zrF5|o<3lS3W!i6rLnEU33&7Z+Vw?_QQsC&~iGjb384WIUp^o4;nA*1%9SRvsJFOMy z>y$1)g3BX*3bWRlj~>5@S@QIq{n&=?O(5CjB|T~JSZ$UKoQfKnM94)oyv#x*Y~h<0 z6f)94Ic*c{u0@3on#YXd{cvxuWPs?U{PMWmQq1Qps<2jd;EIMvGRb?Fwj~O%wu&t_ z-z;|9`{O22#5jghIXBcNirZot<;}rk^&4+cdsZr}b6Qd^j5eNm+h?V=sXD3*W2FVr zO-_j@?alU_wfE+=mm}DuF>o~wttKA?hS2?Ca~fK%9F45J*b zDy60bK1-|dAT-9zrnzTvg*Wug%|oB$i78=Zq9fVO(=z`3; z^KmEggj{!cp+a!HQbQi)Hq>wr`VSkMiP#_ds73RtVC;$UD~gBvQHAPKzFiHDPZjIv z{jhM#bmep}ro8a$S%X>R`9 zDP14Sj{Vt?>URs1vG?^T-H~uAF%=tE>CAGOnq?Uu%SEY9rjuw8H;vf_*&VlGLL+KU zCnt~)o?OjrcCu6Q@x=<}RQeZO24KNd{O^e!X~8$y=i5eydf*M@=UBOE+Q;$L3pbM?}s?{-N zwHhY9tRY%biEnOi5m2NHma4_e8rOw?j)y_^>e08&2!`dHXxs1XR5J;~8&@pCW}B1t ze$JWysNU)N5=bF?I^Wnmxz+rkU)sddD=%qLa6_+JrD)=lk&LBO8gKJbGJ-Oly*;;% zF3gHP&FKiSsE)l!*6lE3(Y-Qyle-YKSbfm^l&|Vrt^TA#kK;cThWvjD@Bgjj@57(| zo5LR*^+XnUe*v0Urndc=e(>!7_B9n?L4!x;;P@3UiylF(!{Yz*Uk%&1p~r#UI#~$b9vi^HXwir@} zj3Y(2!tbBw2!O|8OALxykp!BONO?`nGGNyatMY#qCr_}0?U#Z1 zH1-1kU|2B4>~G;D5`HctRAeE*#2_!X&c1zjq&nVYQFDkH?n4s_haH zcgWCXg<=5&qF^pWQn~IX%+#NfYW)UrA9h5|fYNFR5C&_$apbB@qpyBP!|s#A_$nrH z)0tDiOfpxF5o*=-MABCCI4-|=?gHYg#KkKwFhg(gTQ?nl#kg_o0@kG<5m( z7n;*iTP9}~5kKWQxP&RVeqa&=G~h8;km#6yuUHi%;4DWwlaasZwxuzK;vEPNx^2;L znX{TktabJn`;yJhtKwshhsSI>+`~~#5#;78GqOlmV<}%)w82qD9hBq5qs&(gp7h6W zp-2C&Wzed|dV|Cg%I%1zE0_T_E!Cqm#ncB_EfQ3@G4=+?-F&v#j~n-DF01AZMn;&x&!#m{$)G8m-EV#N^y8v--H!B8A;*Dl_EB_h7~ zAQV-E-BNJ~T;bu+CL&&Y+O~|KOjZYV`}2MRl|&5%jbWjGi=2t1_3M0tkB zZ={5bQ>X89X(7E}&G%iKoo}8*=$=NBm&>v-E)V;*K9}%rp9zlf$#8?J(6FhR96`hQ zJ6bl__;{PmtwR5`dE$ZaD;XQ{3;etu7v{QhJ5s^gSyXIuNS>~O3~r6DpR}zi4j)%T z0zWFnU?>pLC&J1A({Mb-YUhF)@-9sBUfPWjKCElvQ?wSz**#PrE2m@>4vMvn5cLTa zAdk}V(9On8({0f4M%T||n=GB&*@5`?b@9t!;5rrg+^ z=Ne_T7qoV2>1gH84V741B^z;ChDIdvhDNv!pXZz6AdE$Z5;IBzBhhCxZ9rR0Ac`OW zK`cx3dERsd7@YtDnn94X#Kl-C!bw5m8T`!L705ss&O129+2_q=?Gct98ERDsfP?s} zIcYL3Th8`v13lnr0h915VYYmQ@LNohF%13eNZA;hyv=N$Qm(${b%cFRscuw#xPosv zhvY#^U7SLCHu=aOdkm%Rz(_BW+T=kvPUZV|Kd%zh`>$=yuVwJ+{0e#p!%`qb6>wn{ zp;%v^NY9epl>@m&&kQ)7LQyYVzqM6uG;CjR@+rFp@@WoP;($)9{ADDSFmDHD%e|0z z>rz(DLp7=wt@RiN?wJ{36IM)NVMRnw>L@ zEx?$Rz)sth!eD}(4)k(%>e@? zLm+5zmgW9WWl5>;UvH2;vv)8$2;VpoVGl3TGovo(o1_c%**lPu6bM-ZU?2kshAhES z6Gf2$oYRH;AgU}7WA^Ut2bZ$VytU>P31YzD!R8;`@qX$XJd+%O&Za5-_b&oVaXnpX zUw2&J;0F8Uoecdh#KI6jL;RPLe-R6dlL5ffh(Pnw|8dB_2;}wxV~OBf47LAFJ?uL0 z(!U>u)KjViAqIT{ia6S)P!$Yd#$OVo!6$(?0}LNv?sdl)VA=Ya_fHd})aja-A#DN3 zWnLn3is7Tfy_i-73$*|Q`{DA;;1WU9Xig~aQ8iIG>8}TOh# zqk2tR3WtetadzdM05YDLzh^xYFTIYGub?inXYmD8TDlbzM7Jd>CfO+6H8DrTqlK0c zb-eSmRSUTksg^<}($Dx_$V~D<0rPEz%ur~(`hGwhzquUOshIxK@ z<=LZr^q>~W0~X6Dl#W8hV}!Qx;*em}9G05NZrok) zr)-fEfL0o_L?5Z)lq%;Y>`!SoJ6c|{G_F5KufaaEgju73BnB%jQa+B|CI`)HJN!Ot zSaQdS4o_g$?8xOJK}!XZljOO?JY-OhSikrL@CB8H;4K!osNRuc8sC@zk!!^UM1&9d z1>nkJ$}}TFtd*f};t`z1C&D&B>dT=)`hjdggbX<_1&3wWG1)9BI%xuk!ptfN^A3RQ zZxQT>L=EwtSfW}PO{;|8VbezCKST8f!)0`jIt?6+BEWrbk}KA{a?Oz{1gCtAPKiRb z7;*@}Jm5tHLYhF=~WvyiT8?~`@v$6r4x zCm$9dQw1#W7+2_{ge5GeBIXDV(9auhr)s`ZP1X>y%Ki)r9VWyn!C(#5UAjqy(3}@0-+v6eOe7S z?ceX)%9RmmClvSb0>W#;HNikmFTnU-a(fCq1GW$}?~?)Q*pW+`luXsj zP>20zBA;CtV_6J~9mZt&65$xUMCzAhs1R_36N#d1MVIF%OBox>ijaG#tA zokyH51J6%J+E|*~Xs4I>r9U$OWSWy9e(W4ZQ4yK*2(on_s>`Ja>KyR3cR&RK92uoY zVX(!!)l(GLpSt1RAK`X1UxFNS1>yABMLz$bbUqIn*N^dL9H5}f$!-(L#CK7MRX?|D z9R+-2yTVjL>#Hb)eZ8%JW{|Q4M0O%$;L}DEVAhxrDl7f|HPO!Y1@p`&gK5Mn9Nb0B zpFlzkqi3lIIclEA&|PdMNu7MO+#YBz*8;X3oPR8&SOBADMda3hPZ=3rD!{CrJ zB?XBx7YV4LmCru3ZVFyYY6cUBaN_gEY|TNb?;_nn=2q~CKxO2i7hRM*9zXk{5Szv6 z&-3D|Gvx~osP*4LsOO=h2=J&GW4c5pju~{jxE-(ea6wYqpGw%U=oGW$CQvIV$kP-0 zL}%?$2^JXEp48OaN=h@n-A6};vkq~KLbQ|ILDpdrMCNdQURpZjR>5jE@FdsxL21baZIZF4PWK%JoezHzueW9a*$>b(l2(SVyJ`IB) zDuW4#cA%@A&jxtHnnVMn%%4kv;6u;)0NhB~Z+Zfq1%ftq>PGKAAjSv;{m~`A@Bt)g zW#Fk2vG58;q_+o?=$`J7snv2fOD>q2wdDXJa=HprmG?#n1Pt}a&X6BsYiJB(nW>Ic zmw-Xr&QW~;8HAA3G-(nvUWpV)aSG_2MB@e?vNR&HC{~UYG{qaB94+lsq6m}xT1CVZjV_Yg=BT z*V`#E#(X2X`DG`_0Rv!~xZE41wi&;HGX-&h_DL;O>9+mM~H^Mv!Ed7A6|XzRiz4lqGg zQGIYx?q-R_oE7^l5i@LT9?+_d5{!z#qT_G{55Jgphk)DX_7|2=T+PLRunL-R7OB&Z zLZCUac6vg~dz2|g5i%fQ3^$%FEe)UX!VARff>?XzX;G!GmOctI3{0Z4Cp+)4a|Pn|L#O*&|*U!{?%La6{u&$QYU z<}6mb3JRbDZ#s`q5eiBXwq;l%F~Q#>OWYDEzwzI%$+0C56zC6I`P01v!NmpdzWjJU zfQsWZQ%DV4Dql$k9W(H~pfrZ?{6is|L9Y?ZBKzGKzeF8*V>~D=dL>a{3=vx}iSQha z3B{_jKN;~0A6LvYvQfm(Qo7nm!eTyjk$|?KQ7szE>upiquu}^ zS}x>}kdrjV76*HTNZDiD6r#Zrv-V{f6YFi(Cj8nCq8l#Ez6fCaaM{{eUpCDOc7b9v z4qP7~Xoze`20L!9gw6&O1+S#C!>nYM@geJN8+Q^GcaEG%3Q3tnTjaa+lx)sZIO9Qy z*o8@aYO6vZVk}Dq{tli8kwD~AHef1RsJoGr3_FND2KfjDf~xXe*QzDGs?tJ z^DEas2lcXJmXI>lX@R7UyXt6(lBIH$^nj?<(2>zzvGrc(8|oBMWPpE_o=(Z)Cm6#H z0zi|`AGgdev!CC#NJc~k3MD5IKgblPc@*y)LkfaUoj zam%nvFz#g~9{g6Dv@Hq}imbl2bH4l{HBnzjqTM+;N=4AHfk|Y)xkpMf-%k{@veIyt z@coyq0E1;jGfO-hCNtfdw|iS%GnU3?=$Jb8(ljbMcAY;1MD}zC;6)}a$Rqbv#6A zqELTnzzDD=NMn8W(GyVo7=({AxUQ$`F>{ZqQ>j&|oXPzAU&e6}9(xJl-OH=zvc@1p zHPxgd{@WSjh|WX^>Kk=782-=|tX5;%!2W`PdFlwf8J?8c z!E6DuFS%w=AC4ZOvj-F_Xeiiiz3sBVvx&6!(M6s|Ja)Ink#L`B_`EWmnVxMVB5i<# zL$n;EK7L33_~_$n9s$TlPy|4+srmiD(+QwfH0WZy(#{=mnQ@JJNfH^bBrq{+&g9Zm zu&9^0rKT34qJ;<|D$Y0ep))h0p6aFah^C`AO?i2h&^M6lKo`>6c43chhlvfRh&oHw zUI8a(Wm!(gD8C&mITXH1`tt74hX)Rwod1v_nuhD&aYnq2BK0n8>&|cIKVQ_JcaNkB zTW9$3ZKrb#1^F#%{@qP77Kk&9lAcZqMIM=pUu9mCXH58-MltE><^=i9(g+zhA|@5* zcO)bDd!*l{P3D=KJ<$9|XOD(t2jC-^I(A7DxZnuUZ1b0_vH`5&v2)`afpLOq)X`J% zm2nzFA&yBEaz!X`;rmyzjin3v&czgkFRzyGG|PAOsa;^p-%A%PA;7HPSb-IdW)r-v z))0oDkB0e{ag_uU0JI--b>8#{&{h^VxE$9vFWqVO&G0};{>c~o;rNP1(y$XahHJOO zZ_PqDcnL^y>M9M&s2SVrF(H8ZcN7uFxUZoIs?CeI%k2Q2*VOAn?CJdiOlsRWQsX!Z za<_~YTGodj*9C)!uc4wg@(QD*fFBF)C0kOd{v?gbb%y#xnPA=&~EC6UzP2g9Uj6d|7|?OO6Er z{aAE-yty6cOd50Uw{m zD$kFF%Ol{D_X2Xbmq8L8djzs1vyRs}|NTaoK}1F_Y*iEz>QyLDMT;Mmk}E7Wl765| zHLuaeIiDt{BpRqt2+-{3?SO_^6p&4DJv|p4zjh>lAiJQ2DTYMctLy{b(Z9&#~mB6Z+O3~%L!t9T0s(JZHk4YSt!e(BtqCLC_H$} zIGui95;Uw1e5-!M+$?7{W}NuE>9^}xC>_Za%7zaHq4Ub>q6qAt)&J!`(is&XriKYg z&Z|>FUJx#vQT8DdSEtEebpBC$}^3wM1320)fU za0{CZ&Peyb&npMvYa!1v5U_|dXh=NnSSK;FF^}}3#Ni3(SJPHNl4W4(Qvo`ZmvO#f zip-xbpSH0h1_ITs!)0DXlEn}3ayr<+ReZuMFTl33mb$*lM?5N3%*;v1>jQWA*JHFY z)IVOPWyq527#7oG?xt*OZ43unBgu$GJhnv}skH1g*uZ8VcpY@764Yx0CXX4D?lF_c zM~Qthiu)mlkp}dgGqQl&Jm;+~ga8*d7jE?-(KQEZI3h_yA{ozmq1~>MP^8t^{vFwj zHUm#WcL*v;WjPXtDFm=}kAiCY(S4(EweGhv&zJ@vE|p-e-0}#u?A?g$ofX{7qT2Bh z`QaPNqGk@CL=JtQgzxc*j#8c{qri9Ab4O3EG3vv&t`uz24GZI%v_Jzd`;?%0T!+^4 z4$2E94~CZo!s7z77q#01@TS9bPG8vu--w^VUfjSrW0@cd5}N318%I!o8ACu!Wm`@YNLnAHRu9$9mhR%BBnM^cgwdPawkkQ;QcbtT#&JU?V)$a>`Pyt9n zYYw51VhsQlJ!LEpX)(5?cyJ7g7&&)k8a>e5kIl)Rf9=&U?9EfGgS>)sPG>CTs92CR zQ^13{%Qzuh@sW!$6`7wT6o;ZIG-03A()s8SYCrErES(j1g`%cu7lZsZ1}7YA3|B=^ z{cS+c0U~7I;hY%4OeDxgp$etGK(KovFY`Rt7wPmz3rrKj+2x~%6_?PWK*f#frkOSj z_kM7e2%sKRGG9WdDiW-qAur>)tt^rIG;`uEQ1~P&a+z7MR9Gbt3Dgr0K**9HADL6N z7@@VF@T7}qnX>%U1u2|jsqxV#lydy**?{CDH@{3_nJLkhm6WR;Q-=l^HyIR?4EVVAZZx%^raq z3KVLHO|B>^`tlKe8is0kO~XpVEll;GX1b9TVKWw5*qo)l{PyGb>v~_rJd90ZX2pgu ztYd`KatD?^Wt5Xg*J?v%Y)1(7L)_q!zVd3Pqm?C_zFQs@MJ5KebuG=gtwk%FvC`lJ zq#=WVxe3U22`4W(Boe@cfiZx9PMN5AV~jxuqDL^MKls9EmWs&0ZL^xb{5ZH*(TMOu z3;PorD$H=Va6YVI#+cY4r2zqm)KYgwP_|mcIWP)lilVz26&;bU_x_oDbLbHP81f|v zn*b~4Hmo=jVhRQzCw@g0ymA43Ax1vvkeHKbubi z-HbR`4#|u%-7y#KnSb~fGlXd!L6!pf3_WTn0Nig8Irh3@8wcq)1%G56f7;3p3^$a=AkQO1k%Pb3*Lw5mzOSvl&*eLB1p}*6}MQ< zs~&2@3@yLmtz?0feCB!>+?pacCl{nPx%>i`UiAf!&15>g>PH@{1r#$ZsznAV*y`gY zYYpNXU-ErE*nieMf3@1Omsh9ZR0`7^pO1DbCt&Is#C2T$reJN=fHmwXiGm&|oHe}r zyNWYzSt4@zm7ykGleVt4saNJkn~oOrTMjWcn!Tz=XcaQu%L+2~Xu1#I!qibnk*bW_ zy_;AKT+4^FhYn(ss31z#(CK^W(}F_0#RRIscDKO2wFXhy1T4dRi0wjcjyw{HeCT1Y zwW1~=T^dqeRC;>HSk>cq zI)P+sr^M-Hfm8;Hr6w1nlWt8nb%JQ|j`vt6^a0dT#~F!K$rCB40)=pDEVvD6f>Gq? zCXRg})yZzG1#y+$Sd4hwxt=c~;SuRG2A2Da+}PeO9j-)!zEEU9etH|FFkd*8#V6$qVMfNG z+S}KlGgBVpynC|Xi8{P~v(zbJ?8Ca-aG~tai5_Nj8^ws2z>#Zhr-iX& zL#+9>lmX5ZB*B=*CCGw$yPdm#&Ns>G!lLNRK&@(y=7}mK#m$i7gH-W)h7L(aR9x*3 zJC6zk<-7#kYPCllc^3f~=}TsfEE6!vJ6R>(l!D&u;!4D2Yj6?$f9^36LIZSb9}* z!89;P8BZF=K(BU9HX#i+PEyjxNG@~I@Aes1P#%H8>RMy++?m*h*zT&&TDt4#*^5U_ zOSL0dV0DXRB``z#%E2Q-Gzx&~Y$+S|KCr*Cp1k)}SQzBSRw|=+JAGJ#_Llf2S zJY{T-KqXY~ExFam$zg!F?k>_a6#t9D-O-X#L?Y$Dc?wMmSPp&l-=>YwaE^~L`4!wy zc>Yb^ClnY6LLUyKwfQ%BCxN9{L|#0AIf}}<$6vXqe@QIC3Kuertqh7nrUiLp5{KoDN^c2b><1|+@98VX zF}#S{3vD<1sxys`WYC{s7S;Erdy^_aeo|6=h5t`$V0MH=4bOc8M~ev5b6d`OHuq-* zx9uZQ!R8A<*$1+J_J^VQ*l24*h|GHmnEL;*9-nuOA#XB6M?&g>5S(0A=P7>jib^=Q zHC8+eR?-gY>6yv!C{44VI92pGxSb~_Uvo%wRhK@SI=gC$AaklEnV6OR0)!dt$)C@g zVQN%lcRwnKo7=?Qw`yorU47xAR29HLgjupQ~l(B85iH&eH-bLhF<{79E3P++9AD!@EUu`*+DnL zNSz~ZbrS0~J;Zk%2>JQdQ|%Y#YIkjX=p?$X3E_=;FHMT!YA<)?wWD9VQ<|8L+0AW$FTrvDmcxZqlQt#u#Z`-^aNYQLia}Kcm zf?(S?e1lPgK1_1Ggftjko41* z8=&k^TcYcr2ndByNzv80V}zwX+ZK#2puh5+6ln!=aL$`=9U`?lD)^(v4#jBC@&il5 ztc1N2#$zk|le?+CRLbCchRVTy1$d-W!gh*Q7pJM~m+tjqlJ3Lh25tx=%zE#5a2=f3>y|3lnc$3^*k4a3W_z|u=e!_puKOLv2G z2}nqz(%n)^r?i5UfHX);NJxW#G?LOtcZYo61@-&8@B4Y*=b!iUc^*C&d(E6Vb7rnH zb>_^O8JrE~>!nHy%H+VOFl72P71l-c6&&- zd16EI)REM@ZE`v>O&#?-vK#L$S#J$(U6(}@gj-bU@}BD6fD3s-+g&7`U$=-TzNcXb zmKw$ZU;x@%A~Ns#$vvpae4eEG@&FbJII!$eIVXn8)CErqAN?XgTY<<>s^6NdDi8{h zeFH^mFRvj~uQY0vcg;`8r^iCS3YLO`!0Ym;CXc~q58{33kTPC(gYZFkqAr- z@ahVQlMbX~XCr30>9hqxVDGvC$P#FtA@Jj+1`Eo%psF>p0w~J+7uhLhwDx@m(?>zo zx@30EjMvGi{{T`w%FqFLfY+W7B!I{gAXtKq8FA`-FaQi7l|cbi1qNU`?!+TBOu)cZ z8~_vx0|1bq0fPc1=%0#au0%Y!$vM}?YXe*8XZZ+~~>ZBQD?2z6;8W$P!T=q0eO*6=0X0V>^y zDBuS#6#%x3fZb)mtF!qL$}dc{FaAwXBND~jBWiU-4u)j;=m~|B42V=A2?csP*n*lg z_{DL~`WHQ^jS3A0Dep4|t6a7OsYC(jEh16G=rL6t)3ITR3jZKYfQlS&vU^$J{+s-t zuD@cE%{eFlLlN|dTz0Wwja7XVaLW*(4g8t(ixB)Ky|%n5g-Vcz9ih3P?BKbvzXXyZ zfz-c!`tNoF|LLnCmF#6%E6+UuiT{E97XyQPpp45_@c(8cAW4D&q@J7`mzT*2u;~O*7|VJmI4;s7!u`3F5!;L zQLi;Mx%v-)yhS>c6=b4uHinR)xt@PbWc&mUR~mH16X=C^2G$C_x4H)^zk}6BBc>5N z)IE3Y_YjE_i7`x2zJo}dVHlFv?S}lmH2{OttYI;7LjpZ3i8B})w5rO=*tl^K9Dz?I z@%E{9|6$|mRFw!u>nM{H?v|mc5jNWO28cvrO{O;ajG2+D7(DaP*QFvDtuXplGBotR90T=p{FJZ`d#S*UeHqIY8;) zjXk=kDREx9vXK|2yr{zt*;z}f!reZG;5?`@@{^@6>QQWQtqEdyEZLFY#65L;15dEC zD9DLSjL!u28uH5Tc{ptDu)yXVwn;(n=$aK=14CyUVp!ZcL6vd+^w1o9`vSmk>U%OP0m)6>?BobflB zgHKRP{M+^toqG?EDCB8nJ%t=6c|C&UK}Zwx*g#LXF^uJTMW+w}>k-hbfB`ESPD;Sr zVLcSNcxE<+hD52GTK%pvBY=Rnci6W5DO({`4j?vexWPpPL?4j~sJ}>Sv9dYbb&)jP zn`fJ(S@8M*=Mqmhd5Q6<8zEFlU`YUT(`ni<=74d9fF${6@IWM#px6&)L*Yw!GLJzP z*_L9e4R=z3>$;zPR}Gs}anBQ-<> zC@U%{UI@(K5_F$|^I4W%BD6Sp4!uE|golDsTO_HT&4DbDp6S_cSSlh$@q}Hl{GV}o z*R@Zc)NDvTn`uUG?Q#!dzhIPSrE=_JlZbowl|tOH8F_uA!J_k^gL2bXT_YD+7Q>FJ zR27mIN2+rBC7gH=)do<_50oI1_e649*#n?NP_;W;B1%p$TYZv*oiPkHUM?%rtqXU(y)qGgZH;^&m1eGLqPNXH6#^pMyah-RH>UF;uN1!C3grd}g z@HW(vUy?`$GKzy9!T4z3PRX1jC1^n!z}H;-QH<#6=ktQsP>YAC(BRo)CF2;`przM=O;*-}3XjoUNBpMgIq!;XHwkSOLn=6d58`QiHt~#=b*7ortO? zl{d?_O3^&z)0qz|2610{-o` zjBAH}Kp+eW4B*M!VIrPBD=tYumIM|w9K?wY0mxzHMBc#<4Wi6{BMgb;k^tIqA%P$$ z1Ph7;hDiXJ?}>1X;lRe!V8^&T#~5~qDAj-QU4}%C?ui^f#-jPkMi7E^*h7(@!Q6^N zn577i1cBgE07r@6MDV%3K`Md-GzJhkkpu#uG$24b2BZ}W1P8<5_e72mSBt{h1)w1M zL_}7I3Dx@n@xjnI6aYYq@F@H@6`lYzW^+YQ77nDN&lJHUbp)Hb{&Gt3{(H*re#a15 z>=DU@@IU|nI1m7rgwUwn!GC`b!g1URs8(TvV@L*|W6@wihC?B(K)@Zm@1Dr}yWapT zk>yT+93@G%q{v8wNJl@Fp%{NTE7w*P%j+Jy!wN)z_SVjV;daS>_V6Zr?AL;pBPK-%!0%700C03eO~ zZ&px#r-%5xXUZS6gFcGmK0^do$D&~!*nevw#$D)v7VJedo&{J)3Dm(AhqyNo3P3Oy z@sEr62i+49zO9dj!07Jr|!}l4ui*--!SXiXG;}4PfS+=%zdZ%dm zpnIAK9J)IPRD;A-&JeFh#%bi$`5{7F{tD3imq@3oz)FnZag66mjKF$~;7ZFoL~@9N z{4Y%vv73Pzaq}Y(1&D@(_`74%-OZ19G@Pc{m6GvLn1qH?zyV}rsqKC*!`*$45STC$ zS7?=D(GTst;&W~9;^qmXt#UWx&m{;z$!~xk0-*D`{2s%wO2RzMs8_BayeP37OAxAE^Vuh2-dVrFk@OHWe^P&^3D{zO*FytbygzbuO!Jj zY(>Hvdoq3$Jp-VqlCtkJBmKYt^W zc}4jI1Ha7(8L(f1Hi$f1^6SySyNMYECISM52)^_{T}P@E4ITcxb4# zubO0Y&$InC&0puYp^Dh+A!e4h_YukYvgyi~oDJg;iW|&?ouGu>3xmYx6p0S)CuqN4 zjZo6wh~u0)GOuj0N;qRO*AIk~Vy^5z?P8^S7H80(TY-Q~k01*0n#Y~69CGys3<~2E zen5F)=L)XUZh^ED!l1*Em^mQ@`zxopTO1RBr{u_GJ6Ns?$$s6-(^vaZzHgi%55-xQ zh}shWs9=ii#%HH2!Iw_CpVZp}f<*+PjPX^#am1os4_|YEEKz;Z?=k_!1I4AFTB>gL zNJG%*GXO^$0RXrH4oN6ZC-YT+plLP)H;Hpt0ESE3%Rpc*UCh?Rh%5`lf$d2XC<7y; zK$xiG{$1oS;Tp=^&GHO^J%5VqKqq2J`wED{JJAuZLnpM@f%kHdM?b~KdGP>BGV~;^ zeZ11*^wD?_I9;cBxLKzZox`$K6}M!05}OFBKCQaU2IHTsi6Y_Snq>%qB+bA(VduyV z1CkKQ@HmiEApjun!ZI*bFq{Gx_L2lnK?8#6>6bZ{aYE*AuNeceNTWy7tRp0dPxvW^ zR07_-WH=aZL9YQqk0u1ZucrybcSKwjSR9wo z86n7lWArCu&&g<|`~v_`QmR{VKtekMu_SkOZFAF+<8M;@8K9olh$_3FIEaZdLlqmX zIRWX{5J<2@0C!K*%`}Q0`~oa#hBX$wp#cO{!mj$6>H#fiQbMyw!zisLtKndOu1mPSqj_ z0UlzpDa&6$D+@g6pEr(JzMvC+vCq+Y=z~Yu_5b>Yga#~|%r2e=&7u7Yct~B3qC=VY zS-eO?`8pH31y>)bSJpW{QEstCLHi@atx37#f!)EYam<#Ewz{_Mt43VZ1+-Ed*wcHj zI)`sqkVDYqsXG-Ss_u7_k9XehSw`3QXsBl+{{S+tBZ96|_%1{}CKl=(q!W+HxGqlw z#W_ESzn6}`_pnU(^u!-;XulsAi*5TgK<-2N1wm!AfMvloaHc*ZrUGRNlsyU_0q3}x zgWXTmhw2v3?3)R>$6ibt;eMd26+p2;Pk%}Kq46qHWa!<^MjoE|Axg~9x$rv!MPb}y z@akC;rGDyUjm(RI<~K!$q@p95Iv8&@KlTR{vs)&y+-##dG1i25eW&gyM;kUA=lbxb z|EX@IDr9V~oqflgq6ZC$XUd(cA*pnUUCpL#JV>}p_JK?IFrY~mZzj*W>7_1R=u{pX zgJM;r@b^lY^C$u}(ZxZbvL?i5%#?eeIV>WWo#)5-;EI}|-#@9@m5O#jdbPpfD0wfa zJKiDt$e`|0X;N}oOOgL8p~j(-j^wfpkC;*tV$ZN_yD(({RRPDYmeu&}OU8r8cuK9k>SWR1{N3{iaXNqn#6zI+ltPcAJz`F0)we*o;CncQO3(Q+! zvU?IO;JDNghC}fz1}QuUnRkSX5ddhRVKayw`wd3~_a8AR@~IjtuPoJK5_wXTkNyd9 zG9nDap&N5CN{RkUE&YE|)9N2%yP(fh39FF%aR|p+-%vvSden27dK6&no^z+jS=cE(XqLh{#)Xv2*Di?I+I%OTkt9th-L?O_G^-nSE0u`3M>`PD-KdmAD6I<9*^oDx-B>?Q z=1K%YWL#@dpGP8sTrK3}{IC#jkx-ClU13N7OpEsQTPC*Qi86Y6u@lDBZcO9Pqsz&s zGBXJ@^gn0LDRHxn-r=ast+Se`lE5P&oKemzU=wGMpPDK@~N z@6x}m!o#4VIcEi{_F2A#yskvs4ck`r^0mru+AQ{FOvL0L)M2ezeSN+im@n0n|f8e0LW|!2EHVt!$w%#~5zo??~Fd0TVm#Z*G zP6|(bOs3-CcX8Vchm`rgMRV#;9?!;%c>JUf8-D#h3QH}ER-JsNnOoTf$q?#2)Q|E) zW=n!!qb&|PJVFK zg$MIQk0>zntz1JYR|ZUK2l#yUbf$Ly;)4t%pmJ+fxh5sXq5+Hf=IseOU&XPw1au}; zpzPt!rMQuinG_8ihdfB#%kJ^I9+(K94Mo~@J6l#07lJ*_LiIXMHp-l(lCuaJG-wGC ze}A*ydhQ~CX=_rrdI0xkSmwH#LRpzpyi?vuIer7L#Cp`vQa*S8T~pyT(* zb0?3St;bC%`kXx-3|?+$^KDx@A96ON*cGYjoNvF`LB$)Xte2GtSOJ3O?CPhYEKhbi zuW$&7ghQ^c<}_RaeEK|n#8j4!u$p+J_V=9%A?j{C6>BR1Ns)G4B9o`l)j_bhM>>_U zq7Bj-73LM|7>GRza7wgv9UJy39%LuuT4OEVy{GkXkIJwa)9^5<4zDftJxjSy!4K8V zAMBIAOAOqxqtcC8I+bgvMsbhFgXljq?na)&7+WX)9?~E2)--A$Mh%;9agxA-PUrEJ zvH=Y!Tj1gBI+a#yChF^TpVeg2SwJXmEyLr&2WjlMs(k_gc}kxBO_#e0>x1hd;M-EV z%VP7oA771_fXm%LT_4RyfO+6`Lq2dhYOK~J`>eOg|J#A+fbOT>ihQEA-N;~y5-bCV zHVo$+>5C)u*T5kvpuq_i7;Wo(m9F8u6u<-?BLFjZ_Xtq;8awvW^#l4dhLVjk))7UU z&EZ_y`m`3D(Oq@&s7JN!7^6X(lOB)S!G5}1gLFIgv)ZoZTV^Z2BkM?j| zgr?Ejqutg3;HP{bgyg)q!O8keY}yycU;J_?U~iqeZsJ!NW*m#V{!yJDg$%Tms-tmV zS#(fq;C17&ALp%gNey-Tds`l0z@CxVmLG*?BKWfzJ6*u8(+>4dZ_~G}d~=^y-e0z$ zHEaki&)bac4>Osv)~ca+uPT#NLL0jqmr~nd^6{z#cD4JY^NztAy0nlck+~qV2`#+3 z7Gs@AcAtHBp8}t$uFKb#1Os2&A=ZV(xD?du{N594)E>gOFz$BYQ9DeWL7IO6$yq-H zRL}*t1M=bSQ~s>U-*LP*3RW(iT<{0KMOCTt@a^+myj7)BRq2@OFa7p(+oV`VaD3kR zRwy_X%+#0+@melI?jibo{%Y+s;^=CN{3WJ7o&3p)_V!uVbh0G*gN>8g=Mn_^OmeXd zb1kq20BxZn&ZyyubFk~<{P&hrKaJ(y58b*fdN=g!o+?>>g{u{|^%eUO9EY+29Os$? zdijA)_|k>ciONZVjcRCnzoI`@Nv9}Wo3}Yx4A8xCYgEqUsEI?vmk$igp(z@46;Vn2BT?43}BvVqhis?@_+ZFND$ z7B#S+{llexfTB(1$)^M=Y^>Cy<*4Znqz@$Epz$ARZXW>FBXb%|+Cqm;!`K?Aea_D0 znG`Qh!AGl~{R9Ct>&fq6ozkx1IjNeZnJ(I$%re}cT3*^$nH6$aJxyh%bRvJkLjN!+ z!m}-4*8yon@zt)GIxhhD{oHAgBWGy+AAsP2=-kTL)kp6_j;fP3aJg3Uo(HFSPHLCS zaK9>8*Pw>J3_G(Y6`v#Kmy2Y+Fgj4@^{pcgi)61(;{y2$YLY$-zIt5t{yz}SHy`ZvdhP?8 zSSl6?%%m*{6^lZl*Mq%B^)~Y_0Q~r2?zSWLMps7Pw34=_!}~l0);+RjCfn##c6YQJ z(R>dZg2um5fP7&-zmw7T0h2WtS0)HYh5U+_2$rktJ`(u^N0V4^7glNl2B|xTN1*pRFiTWf>M3v;}Fa*1uSUSh{U{HV)@6n2+_5}S%bkWM&{g1hBy_rrfL2zB-1jiwg zhPGBV%&!6#(W?0Q<5Sy6lU^A$xpCl_!z`~Z_l*-E4=W#ON2mggSxhdOCspPIvtq0I z?BgwI`}a*uYJDMkKvY3@{_QNiahwsMZAQs&pT^@?GYis*Kq9UP(+Q`araM4jE;Luh z-$KA~pbxj9h9GanvQrNXxsYJ06m+a~17^q&zx-IH{M`L&wRP~Um>}}=HsY|_h|iu3 zlj%t0T&*)gZ_({fF=K(-Sd^3b{PF@1Oa}9l`-NUEO_)*ssC?=Y^px#8^VY~i_ZV!8 z)^nJB45|U(=T@^={MWGp)eIrm9q1UQb8wUFJH&@Q-IF${BIvw zi#uCw?ZjIqk?O!tZ9qT~q^;HQ>K!9b*~8Z7KlrCh)pxri-@pFU9Un^yQdj@V5_a%iRO?2|((u684`E@C^SPS2i956~IaLVHT;j=(j< zJIO9pN}DR>9Vc7{)Bk|)X`RMcF7|iLkDVW*QgAVYUVOfV8QC$vaWmSHwxx@(rFe%k zJN`{f#1x&izxsH(H~2JrPlT+VC^t4{n@IbbLSoGhVuZT6qd!96K+1U%3^Y>25_~k5 zN<%;KLHR)#icz{f8u~SWH2~iX{E2J!F$N{en0I$K*22quOZFYldT92uKIfB1?z)rT zF1N{->i4Zanu#BGVmefiJW$Yyn?P6Ha&wUK!F73HD_EBMV)Tu$Ll%LTyG9ncCT{Pi zf%eR6A!HnO6aleAxN|w~++bWCl0EgqQ0*R3oq$oMqyFSc2Fxf&H?X6yW67}CwCET< zEJWIZCXT9LO-DvewyfusGk z=%=zf)79a}pSyHV%xXWbL<6jHYoW&ID|$8^%C^^$+vNgF1ktj!(Lz*1w%QxGhqc6q z$sDCv$)X*~FxV@dwohDWTS&BloFfbGNk4Kk5D*8_iHmV@#mzh*R?-${BvdEn$_m*l z^gW1vy7~$yp40j2`K>=f{`oN|?oe`VOI`QeG360VRrAOUAtx)fbRBRk;5O0*V_NOT zkZyp-F>K0)H%W9oR?j%w6du=N#O~a3sz3t*>I;PI zdEk}n@J2)527b4Lmy45{e#&}jTi?E}2B{jf{xz_IEV{nIT0K%YvbVV8&*!*(qp z5u>B$c%X->dD%vo%dR~NpY?_3Tc1YoiD0oHM>~lwhZXR9eGuX{ncW~L80a26f{G?5 zR)5#j=vpdelLk5qj|+3FuXL%pZ>a3{C!+gtsR2WD$L#6_AK+{1ezcxQ0(Km28Tv?O z*yA&(d`I*hS2CBx6#q8WF$E#BK=eHVuTL&qxqtmLx|rP@p^q@qa%sV*}CyXpr^I ze6#Q#3eh$RC~J;*Y#B+MI6aFjb%)p(PA~Oug*M_dP(*&?o&pybH9NU@c4a+%T{P;v zE@4Gig|6FtMe+=bMd<}YEULenvG94Q) zYUZ+oKC~C#3dg=D+OAW$(4);g-En0Yipuioc}bn_J4TcmumSwWvbPklx8^zYD->kRZUBZsj7BeiAbvr1rI-Q1cLm=!~_UVQf;Z=SIP>+ zpn1-WiB!?{bme7G1wf?3v6ebpq68TLk;!rU10{f=}LFQE=0@s?|Iq8Xs>001NWl=m7uZgymfuVsPUOKj&yLU6T z(rT*XEbhK4v!vwtnGM#O_3~aC<*mSAyk;3g43%kJ06l9#G{^n#MPn$!2BNZ~hrU(K zwO%Ms1M{TP*Vv!O8a+!7i>(#jy|9iTWMGn|(Ani$0|%V7pEJeXwCV+J-VOz>a`rRWSF! zF&rbrGK1ZqhJpe06vI1e43~?(PX>)uz#?%U1G*<_0a|9%{1hH%ni}`=aQbyT zGaU6Jr};(K=5kb;TSE2*g{zA2$O0q}(~5KiPc97g+Xu8op*NT2ty>$U1mP65^FV#z z=Py-X6D!c32aRGbC6Vkt*nxL9?GqNFl*~I{NqUKPpQ~^P<1)r1d>}rTl~_eKqVugB zXM6-UbavZ~-`fd5+P`((j!Dk7bLCK{@m{MJok1MCU})?St#2*P3~p+>=-(z->oG(! zLuWp5vTf6UnEDT3r(0yM9>t^UvD3o@FF9FkRah%45v0V($cYm^XBo#c_MV+|M{0bj z%s_AbKRwHT#I#f~NH9pM&sLzFV22$00h)3}cV!@-q81@UGul@fO0Y;ROJ&+_Ikc$MKiGQ&#*J})YG2_6$dA#ic`*WWs`$QUG+_IlmUBp@0H z(cx^lkLG)@3UQ(Vrq{gwdK;@XV|UZ)q9L#<5bf#p1*a+%3IvoIw}PWs=!xYw2^vwX z#mDTz?OXcEP$@|B^?GFl6jbT@y2#$>`}0TZgLoed zxt6&_Q~PxobK?`VbYx3>LOXr(g7inyo3vA#vT=Lfm`_)V)tTOU7=&c#lp|f&Yk-~$ zh0w_D2NwBR*^t+%zVih%Wv(+{k3250qFb;kHQoi1J;Ur&>Pfeg3E3kXdw|QPEm2(l z51`!V3q~799|00gI>$>W%RsEoymN6-`=^Gd`LM*KI`!_>{WMW%@nx z&8V4s{miT^p!9h*;w;d%sBEA!kK8z;TPI;s9&$YcROHOtR3iztS{>^@f|v^F{X)#4 z?j}t=8!w~&&Y4Cq+Wyyx6cy?JU||=wSpzNf14-UIlBy@btQgR8A(sBJEGICk2GgEp zs5||ModrsDRfFz)WYoaJdaKUufSPJcFiVUoQO5x?Js|SQq#T=UQ2T&8J=(M06eMgd zl@g+8(fNX`y!o(=!gl(!VW@J}@hL#7wM-ooSJ^5lwUH~*Mq za{1R9p~=T|D>e$)c&ek z>yK#a8&dt)&nH@LOY^t3MEgwL_{An% zVv%WrCQ$;8AH?SU<-qs)e1GAK->>_ZVZ}&1mZWSM7GfCAU+RO(tLNzbC>cOzStND| z{$YPUMwMc)VMo68&F5W_=}$~|RWm=`a5IAHDq99|(aKyM3Nj!kvv`8-NVh#6na!4(!kDYXMz+-jXg>&2f07_u|3k2C3W>jN5NJa1K$y1_$GyH) zVTpH&g^!Xv)hj`l9L3E*?o72eaDHyhY|G`on7 z(D^AaFI;~WWK&J>2Hi5dBImRPC#vATQGV zR_+v?_5M+OoEix_uQ}q_Q`u_N4BvWne^t)>6r^=>qwF0c31{{lT1Vzg8pLLMPS{_}OkZ6Gfk3b>^^=*ad>EMiIXb_@E({9lkPFO)u zWMjHIRi*{;0}?xdjGeND2UH94%W&~(Pd)<4R+CEuXZ1GhEn|*RDWjL+3dQbxD&F)AgHMCqII%(xbIbej3RMlCrmMNbr2>rhoXzvpCqbSF?fJ~MB|E7*mbPBUXt_jg1!KGrCV zm=iHSagyzaQ}QqqVTANF*GtV#*BNn;$gt36yow1qa}wsEXtUNz&Ab$_UK8=~;2-sB ze*?>-C1|E-@P(98t+f}l!!R298)SLdPmCIS;BV8yqWo=>jH?0$SS{>*Ui2q#6aGV>aF=$=t|XHSwDsvTq0>vZ(&9eEl z?$wBqrzbVz#XC47aaZDK0F3#RAQSZSFUdQk`SwT9<}oHJbj-@28|gg@4Lw6n=4TGo z{M8EO!Xw3Niv}*TPfpanNErvMwK5;7JE3`m%?_$-V#_n7IdpTV(Hqp?${7JXW*r~2 zRm7@9nklMY!Nr59Va8AzkvX#Nv}rJL+4~=@>cA58y7UHLXjA4|_XD)l*Wxb)Hqg+C z%8x4SIa`6?;S8sTl15e`hj_aP9pq`w-O|CYmcn{GS`kJP92m{&e3M9ubs&#G3+Ga2 zH#}~LQWUYJj|D{BV*tVXFiAyW-G`2KI5ysafgdO7|Aal{APSR{D|Jc^;EaQbC?#lj*S^h)X}mPt*bE9b1Bs36@WS&xawY0 z=V(|Kx;NkVh{ghQdXXzY4sAk8k}B&ihfeE>rZA534g2$TzJ;f01Xd*er_ zzM4;=HZ00|wCbKV=(0Pk;HoNQxHL1-G2rv*!ZA%mnKIIJUqGFFGNT?#T#3h^o*nvb zF)yip@JiE4SfoH8UH>C(qJ5y-T>GTt7j)L8L7SQC4u2%k^0ZHV=(L?@57(5TYOa{`Gf9QW?BHX@{>- z=D#97fVkw)KZThl2T$A<2&PK2OnB|`4}kR6;+FfSO%fXtacu&TIFYVWapOStNHAu_Hu1J6%#Q3j^4}cI$ zi0^BWK)5P33fRshiG|7!;pc;i%PEMXX%JoP&yO}m0aPX(3h)?)?P07 zr0bsdsV8rY5HMw+=b1?=2SdsfrF2pkx%5a6o@Q9Fm-w9E>JOOQcnEU4c*&yoy91vu z_X~lsv*W%3gUjD#dXI^$|!m*^3mm|)=+6Y zHTNS;Zd}8IuuZZPd1~uzp17u@%h@SC%%AXuImTa|0c=hYszNc`w1fpj@JXJ-EfOxUrvZt*5F8Oj zF;3I>;>*~nV=fPIM!zq=X2lvzX%@|fgY%XZ`L zEJ0sd*?a{hb&C+A(n#Ux&iYVRU#CKJ2zC9nnLD%Or~rydQB)$eHcdYw9p5MQBHI!G;@4T<5?6I?qp@FN--%G0bRg+$5zmxIs!1zU8r1K+rs zX(kz5+teL~e}%@0uBvswRYQl=AAc<^AEcVl5={2$C1585TNGQ?Xm})^r#$f{l%uuS?k}fjAgXbG#;OE1Kk-5%@zxR1Y z@XZ3#I_-`ek>_M)#!;5Iqy&~$-_Y}G5~J3)X6}0FtK-AFKgD)sK;S?Rv(a~vOl%|t;6)7&%P}mzuZLm z-GXE-=_{`dN2^g{U;8g!2|N;mHg4%?T#YNnV1Kup#e}EI_MsVd7Xr()9hom~46IUE zQJoRD*gAMQgjg6Ef4=NrBPrmv_)+F}eX;I? zw?ZR5S1_;kqQ^2E4y>GT*o|NfL6;?Q8@uf3oMjJx9~IKiMh3^qoh0>r-=9Ie!IV=g zRgXr%!TbFPR0$8qEapgOZn`|BB{alJ4 z0aK{joTX4pHnwkxoOM$Ya?frP-w!j*C@=Lo{5z@-R(1p60CZ}sh%k~0WT2Z;`zz&G zj+w>V#n!LqG+F-aRyMx-bvtsiD4ob`PR!`TZqXt<4#0YEw`YL8G{}ecprjBpZa;(I5Q*T|ONPcc$esiNR3=L1)_Hi@z#C*%^Jaf>IbBD3?80F;Wp=A~o{;Aj10VQ#9$<7P!%5uZRNa z${XOUc$%YMaRr)db77$G_1~tTgbwt(v2Q=(pEcgp_c8|hjtu>Lu7tIU4A*ShKW}}3 z7tF(jM$zm{E#-UgVHS&x$W(=97Ww&(?GA=R&&t336tx}j8H%)8`n$oGb)3&%G8cSi zxL$i={fX*Y_&7}(JHDog$($!0`WXrNtPeHI$UG!9MQHr}EV@%=CytrHa)~sqKSwej zMp)Imvp#=qnG&9L476yOV%n{9 znfe+TiO2KWpRVgg;WYAZg?yGsim9}{j(!>6+ZP~~!F-D`o=Bw7^f14hWQcnQ#^;Hp z{!`fgtAx-wYO~aiY#ii*U*h+I_VuJsFzf@h#fRn{Ep*XT+_NQGtHHQ92%dZ=Wd_$a zb1&_?=d49Atdv)%ajbx_{Yf;qn?qd_91yd;vc|4Sr6;E46F396=GHgrY`?)Bj7)P!1j)W;oVc? z#6)aZg{-m6tFl;QC*)`?@f(iHzF#9vf8vo{Q6tawH7T=6n6Gwh3aI}%zIZ&s5n#jQ zxF4~Uqo7~<>2&ubiTQUJ*efi8jE(Hoc^mum3HYm^s95Ts6Rtuqz9#}hbe-y0&H=6J zMQK}K6#krLCB5Q9f|r}I((+q;EL~^RU#Z-6^DzK3JE$EF@vp3iEW}1{{p>OZ*P%$i z<#87+D~}3cc)dw|A8_m^#$BF910gkwED=ibz$7x006RJ_~k3pMG_8y|~jd=D>V z>mL$7D!30!wuBVQy(3qGxqNgsm z-y>y;<3!-Jlt5lTgZJxuy1A3LhzZ@js>oNG_xH-XK}%Nu++SxfmBQa}@SpF&*^Fy` z>WaG!cGAwjP#U2-KRH_{+ME=v+cHn4RL_>Y3Pu?7Nd=8dhv1#Ghw!>G zVU@12ZN@B?Ssl2)Qu>oXgReR9-?Zwd|4Xt~f0HHooosPwWB33eAl*z^y=UR9b)s?b zk;}*N{xaua#LU}YLFp|{CvvV7;OF)$yt1dS6>GHiQrQeQA-OY^nXJ+u%`!jXg{ij5 zO6W9lMrsQ@B4aT|{ei~K8mjbN+s%+=+yGxo04Ke!EZy@P`emdLhZL!sTviGpdB^a( zHI%t^Lv_#j+{TLG>rBdGcD|`%cWvU=22?byg&YcaIMvk#;*0@htKg8jsyV;-8(fzY zCB<@r9o)~M!Wi4(Es|aqER8dKmOYm0UR2s+XFU^&o32EM*Q=-e(;I`e8WPMhCZCIU7@#0=iLXSDq%08vO`}6!jZ{s@Q-ZB6ByNp_0`#H z^kBNR6dHikRH_@7HwBr+J5R^tyg9aXa2iKb=~Qm_rhd^zwHp9C+ zLe)jc1a^~YIu?tkT*=$@3ztv>nRQ!wwrCtZC9RQkw~@lU#_*kqB5I?$*9p3D-X}Su z))MhgIZ1Vch-Aea1%&zgVRM-{c;Vx#DHM*49_uH%zbBK%Q;QfzGaIx+9;A?WQr33c z-Cz*>V0UvO5&Gk4BSpb(d94UewDycIkvZbOB2j9_^|0~^P!G}_0n zB${fbDoHXHO~f^2yrlNBw&UfR!;g;?Vn$tjCpMZW;{>?AWHa?%9qoy<8ZbxK6*+T? z#T@p!S4ZXiX#FLWMk?$VZNaB$^gps*L%tJde%^YJ^@Q9jt)bbn2SZEl&0D8g(v{$V z*7kxQ>qH7}_Eb1uN9rfRZ?iQj)K@BJPgoJEtz6b*qPSIEHsDF2*ad?TM~HMr5w*`4 z;S;5-l<_x~ZNu1})rL+qVbXvfrW=PndXeEA=oGjvUM1&d7QE|5%8@oPm~C*!tel_D|Ki7a+! zIm#+L*!_mycYCzirUq4L@KeNE?tSzj{rdWd$1$AEC?m5wOdEU2WNPQ77n?54#K%x2w`mq_h6y zv7X>A z>NDIi=e1r(4npQ<0zxzBOBy=2sZ&Yg?wf|}&%Ab1JL)IqHs2!01tu|!n;j zw5$#4_dfsCL5%SPubSQQJA}CLtz1ITo3oqN2HzKm8?#+=irBh=sxtY6kR`zK^BAo% z3;-lMRA>4axYoZVxz?Xf834RKj>;o4WlgV_NcVn0qN(eA-a5@RVAr2avGQ9}>YXC8 z#giB9ZZHl_L!qRn8U%S8+N%+~u@@!yI!W$0Vm3ifMRc=53DuHdimE;N`XjiOB`-{l zn8-8HkU7F9C41J6L$MV(>p9}Ijm=BvW%X&(oMQHPN(Xl9Z*JdE7&8vbLY=6#uIgmd z_xhtdC&F-uR^0`#tF3V^w97>U3gM9AXtbPH1An>-?JJ&8~b-H08!ok*jE){|6MB>j{R+T zIJuP_nC|z+n50merSOnG2C-Ps`WyLA9OJ++^tI0)JU2HH%MRSYfBSVcwZHv(aofNB zdM@LixWwv+rn=3OYVLsF#`9PBK+RFnPlQu zD5ydUtyJ>dG^uUR@L9`0fDUXzq5)RjfNi+KgzY>UC#lv}ISK0<-MsfsF~+4B^3rZF ztRn^eDEHLwLhpp~P)ZlOt%m`|L<_qCW&=NaUD`#iUx1_}UfX5Nh5-zr&t=;1kuPtL z!)@{R0^Gz0zU!Hc3mUOH0n?~IB6!LbNn?gg%}A}#{zvo(%~gUU>j{VXsA1zPPP`~D zcgX!C$mINR#F8N)EsF@}W?`nIUp=|9M%?6ZA1LT2Q}p<2|7OxP+=N-{+o|#2IN66S zSm06B!-c=AXab})lvM`=eZMMy!aeC~JYsbW#EOV!wf#uXzGc%FNmzVxd<%wd%f_}0 zsMD6N;tVbDL1}cdQ_)m$7K^D^q80@gpLK;$GGG4#5K;eL+vwjsG{Xf*AlcINckDvG zKu$QXL$`0Id}O>0sMWJ#2B z&CHhHxbU!Nugy*pc>k=2^>1pg{#(cYECxjEnlL$Uwv+wXYceYY^Q;T8RUAXSW^@=I zB9@UDyiG5lc}$e@83%d+7(&6H&&!~no>+Mi6fR=G3Nf>9Q+8!kH+0T=c|Ny=sDv3! zg&_>M0*xLP?7xuyM(%(eCG>v!E*xDFzPhqU7L1+tUsx-uA>r$CXvy*`&I;s z3?T}7NM7e}Gb}aR2AMz$o+P=BvQOq$DsnXMJryC|S=@3ZNE+*;Ty5^>Ily(w$JE*a zBv9#fBnw6IJ2X1Xf~1h&jIKrwk<2Hdu9tVE%2aElEcIQ>H2mHEkHTQmWtg z0ym;3J1mbcy3!KANydFuAn>l7WQc@sg@t|U9hzgkqvdrrs8s2&-1G0vl?OOr<$sRV^AYI^LTdPc%dK^*7 zFlSA7A2}0KBfLcN4V((#WlOskW>wl(!3s#k!}Fx6frSJxI%XDN z(!%yrT$-~pboFvtnq5RhP*r$;4de3>zIq&;<&wHNb zJkR$$>&+KBaWAKMM217r!K3dw95lN(;pV9~?0r8nOaj! zkNU)Ek*+6n@?w2~B4!!eCizTyV|4y{SOqjrea7@_o3Xex0 z!IBO@U)?k0;!mU@%iv6Fwmgp$kGpW_{?KjHSg$2 zmGRAF+uCos8JMVC7%urir(d|)?}Z=t>dzmb6}PPQ7jLusAzjMo6sViRt%aBFpo49% z>NjE?T3z+^ylpZz;PZ0Kpis5xx3u5F)84v6f%v?n2?LYv*>3Z(<{faBIX5rlt=DG) zVx?DK{@AM1XCxZloCQM^pK?XwVd)OZ7th}HEFUrl4<7#Rlk$FXGeG8M(y0w;%0wJ7iwKOvE2=(}LG1kTQ8!MGo;mTQ(#~VApOgy~OHtDIMMXtgq zRjI$d1RK$sb>zKosWBR3TT1WU8VB$n*}tu+;GbjSAvd+=QrUgIFoMQ4o)(gc2385e z)PB>5V9NXraEUB+>jHuebju%bqaHi^An6~Yk+3F)QstikBqIU;(H^5(mHM?B;{35| z3l6Oj@gF#B&Q-i`{Ht1*Cm>EBs)k&r0aD6z|h0yP@WQGSTWrWk*G&D33C9fYM$iZ@S&-L5fKK_5Ly3pZ?;M zfc(pDM3+5i3WHcK9yGGYg(D=w)apYjHa&aN5~$#et-+9E$tIc-hSj{0c}J4kK>Oi$ z_FMM7fl|Z6@0nQIiF;ytD!k>CCRh(MFPn>^j_JL)IQs19Ch6)9Xcx?4-oC1z81?zY zo!?mvuOGZBzzj)~R*&d0x^L-o+O4wpJ&*%&m)f_rF$7V?d2uTgJCA?g+H-qV>jFTz z_zoWFS(SL#ShE^ZNV2EBoDA-(P-C0HmCyrHa%Mv zYt^VCP9e~oLWzCg?o77BB|9Yq?%~BImF~Z`Ik&KnZc(TMVcp~O zrK7iB&R>(#H*~$zd!Yw64UcylPH@IEoio%@dO#J}=>HWy(pW0E& zcrfJCL2_>6xaf3I@@L;6{!cTj^XqEUuQCDH%nqpV*UxF=d24Ey+qA-@JG+a|A}Pzp zR<9*AICLz?uxgu**RuMCn`%xb4;v*Qe3mrh0Kr8YCO-8R-^(vy1u{RdCSX_^GOcRz zYm^9m>jKi2sU!sw$(eWRd#eoQQAU#)n9OW>l$G@sNmJwl`pBq_c{k}BGzpwiq%Bst z1LEApUS$W#SV57V!*jy6stv1!(UrHUwWy^k|1EoS;_^cGyb4UBW|W7BIHGS~E+V0^ zlBVM&Zw`1VJ#3qfai6~i9m(q9D!O8I>e0?793R>7xCC9=&#(MzBwWJ ziH%f;&L*Op>MVfp$dkWku*SoQadSH)&Oc!oel2ug&n!!Nv0S_fW=`~>N`0k&Wfl8m zSKh!Pizw@X5KHq0s#72KUho5}jOc&7Yw(lFT4PZe&Gk)T5CX5pZmZVFLmi$3C3EMk zzO=^6NF1zw$v>2Jbxn@jjG`Kj%w>eIr2=huR z8G47gZ#C22g3HYP8ZSx$sbH)cW7qTe&XBdyRDVP9px9xC)~6p+;ICf5T45ROCC6AUk~55?*31;yZ>?^e08kP2?S#rY5~%Lggb*vOSg)2CS8saCB1+Q*y$|JPe{v044i%h_MJKH>wUEjO>6O_cHD{`M<%?f6S_++Se6sD(!$q+=Zvg#MUp< zNG|*}UMJTafMz`t-IlsvCkOI~^3J5Vg*pJ;k^3sMD2m!uiqNqJauXYgio77gA*NsH z>e1swe=S>T69;t+?z}t=2;lsqEKf9z`>ect2jmLhgSAWOv;1i6H2&uBmb+?f8b;jH zHwWPDAH(0`SgNqai!8{TO>h_PPcJLF_;at6hvUjU zs@TtHh56*9BDguLJA;I3yp9*_Ex^2nB3aL^N82;Pt>!gbVukj8xvk8sy7KCSJ~2jz zRZO)5_Zt+C_h}4v*_S2i`;ej$rLy^m$100>B>-Fi?2)87GdZthgATR0 zv@cL^%-Y3~qU|>dq1#>^ad%h5XQEO6wGjUAl&=5P=htZesoB3q8=ui0J!L`ZP>e~8 z?p+KbVNW4M@w(#~Mecu$fzph>ZzFbrRD~Ps9+;;F8QNyeg|tHU?eCQFv1pOaUTj?C z*TCfyT#VVa7cJ|W^#3Obw?uQ9Zet{{thJ*AD4@Qx$=}?|PX<2NJ%VTVLJX3U99*5z X^tsgO+ZS*HziNR^Av|_FZfE45>s1`Z literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4pilot_inshell.jpg b/libraries/AP_HAL_ChibiOS/hwdef/ACNS-CM4Pilot/CM4pilot_inshell.jpg new file mode 100644 index 0000000000000000000000000000000000000000..5f2c55ae4c8dc34a342db7c4a0cacea18733476a GIT binary patch literal 87450 zcmb4qcUV)));EZPB1J(#x>BV}3mrtIHz@%^2{rU0UHVa!Dj*=eN(s^uNFYFH9(wP+ zMM@~42?-tats(vq^{0Kbeo8Xh?vMJ^5*rEh=}p}{wt9X5$9ju*VJG4jr@Od%Sf+t z{zVhr`m5YEw|SzMM7K#v$w+VACL<%ebLTcW#RE!;yLTxVXlSV)urRW*vM@3;KjswT zdCV@r!OZ+rl2_oFh`6{o8;`WSl&GALn7HU)Oo;E?xkGW6;t?g~Bhe?!PelLM>318^ z{o6OpZ-GdN*@AD9uNUr<-pLFxq4H8mfvg=H`Yf%0>=ei8>jo))b z6eQP`?vdQP{<{DD`bY7srjK6*uF3}x#_QV31552(g#WPnUs5EroQ}OR;vTxeK@JHo zgnY&}VUb^uZv3^%MX+E$(bLkDxgD(iY%u(@nzPV!?jQe4_J0@W)0ApbPV$l2J~o_+ zE6r=6mZz4dke(-}P+M)2I3ZgnQ*q>fR4l=R2E;$Uc!%K7kJmnGr3 z{lk@Y9^-vknacZOoZ{;ZP5(PBR4g~{k+Pmfn9NO;3Dg$NC-CyilDii3p2 zmpLSzw0HGed|6U%>8o7Zx7~Yq49;#=4M{w#Z?%jQ?nCbLY0NuotTra&<040Gyo~f9 z@dl|dVQsyKGbURc+T-6EvW8rch2toFSPs<}2x-uWfxjLIRtCW32*2zH<4f815{mdGjNOImM(unWr9&o1E_Aso zj=wM3T^)ftTWe*bHyiITUiDOd#nmvsqS|K&4cYf)UK4J~WQ8yrAX55H9V zF7-U%{n^~@RGaIJGz0( z;nUk}!M>QPEjBwg{>ptp%h~46!si*ynqR~T0)>2l8T7s#c|C`}o1eGKL%l>hf z!on5nQKs^&DlY3;59WpuDX95L-za<0RL>_!;~l+t>;0BM`JX|gkO12~2G%A*&=36d z$Cg<+zY+uCge2e4&hqkwZ65AL^h18BfLE;?_U?E#-Qa%OVKD32kGE3}Y=&Y|r`u@@ zavdjZa!iFbAxuvV4F5+EVru)M0Fq2(ZSc4g!IWN9bu(ZI23oL~B=&W%@X7vVc#LaE z?uMS?v6Yx7PWRr;d4&{c9K=E5!PN3U4OWLVXM0L(k+xum3>T)K-y!`FZQ+rt@!QGP z_@S!CLqyHyvF8*PlTzaVj!W7%9uoamyHqa4`SAuRxHALDu;S=FXj{&G-whaQCre+= zF)65p8)4rh7R`EAG@n`t1+OOV=SCgizhl^$+cCk^qO9r(L8j6mPlJ#vGJEgIOi3CU zp|FxNOUI&aWw&0R$vOpYr^z4#Yx|wmU9l4i?UsO=NE!>hy@&>r>PJ=bf5tRJSej0g z{yo`jzj(}JqIaK0fB6sxs8XRJ6Z!>1#!#y6J(eZ_Q z+^rNojffHgN-&PDOA%~LyG6aP{e@p6KgH@>KG)5)sXxZX@)lYT+Z^MiXw zY(KVQer(dDm_qsenTu^#y0t@7+Azi-(aze@C$zg`l*vBnFk@>>sWjdva~nlt?{!?9 znL9V|Gtk;nHihHjBLTHgqTLDNKBpXoXJs);`dnV^dL1+$%k+5jmX%as(W3tKYjXH@ zjQrGdT#Fk)y)yqVm`MHQnI}vd@6 zSd#f6{9g`QIrf_;qn9h6cANG2-2|J3CT$l~bV|>gnqenLTvx_7LEb06b;=4Wev9e% zf0$^*hi>=*X`mNc`nz@S(ZO?w7-TsXdwiS+)o{+4sjO30rt0x_Ue_GAEl3&`*b>Ip zWB1Nn1mNX%bZST~(2vK1P~Midd;U&tX61P?Ar;W8_UQIaiVp4}w_be;&_4kI|mr{sl|Nc&{5& zQ){|b{!#XT8XnUBtqe4bZSC3oy5RlL z%z+#yAT2ZOpzI-p{(al`4G-p)vm8WU^*k z66}q6v%s$N{?#npNugyd6M=ySJNMtNkh{gcFRs+zEzW zMLK{+o_K3{bMtHn3X9192O?JBz>hIx8FnvfQX0qU*R;fCFBoa77tju+uL&`oeKVbX z7Lb;9Y-nseoTh80EBMruyX?eYz-8L$9xfm^FGJ%32hQ=uOV&X58dJ9g*1md73tO%m z`T@llu!8~Q3$5*Z z?hC$cnvwzU$_x1^hc)TM+(oltZ~S8d{D$<727YuEL%g+N)_W{rBk>PRjFN5AOO^$k zJxj`nEZz`-rX8lt0?zDnvD|Qosp}S>e~JkpO}6|iBWHK2-=*NR6l4M~AF#pTU}`x7 zB&ZK8gY3|aw?)Phf@Oj8q8{8?g<9Wn(!UZCzfC`^OSJAH06D?&k<~DrTeYqT_pe}3 z&$D^KqN^_`BaK*5aJY}V*MN*dXrC|+GBQb6a>?fcnjLx#M_)A7+50TMP z$X-vT`djNn1(>TX!yMN`uN5tkSRr0(QrDMS=_iv8UGo#rC1iG!bXVNAM+%(De)j%u z@u6TGgXAJWgziCo2QRq)A>Aam-y4CLLD^awo)?)08}V(vZpHF0wHv#XZ)~u3^EzSH zGtx`3GV*QW7wh);@$amW9vvrsZvQxAB(y`^C+{>{l2F+dStOn#LEe8t{pI#e5CJXW zpJm8nnM6Ir_KQO*+`pA=91rmA=PzY1Fg@ko!WR}(xy35F&e3o-(+-t<%6siFjz?iJ zcf9q%rudMLUur!sQ-=$}Wrh?iR9^~&W|GqBZ7*`0Q65TPaICgUZQ_I)oWmVRae~r9 z-3b*Qj_0B*^iEwJu)MVG((a*mk2K%CX@(d4gH;@vK|cgMe8ZfduU)Y58I$#{SR(D1 zmb3zm^-zQgGThNHAeT(pxTUNKS-GXX@MXrS6}}FOcX)b%Mbyj>;Z%|f3|pSO1x>s5 zN%kaUSinQ^f-R?pJJXzL>Lag#J{4TEdTF_=Sh(2yIRpQsEs}YWVHqJwL~La4AFSx@ zQ26{Wl@T-P@}(pm`PzlL|0c?l+X~oHPN53?bkPDBDUI7No?MD~0IPz3ZkFR;qNEoO zaqe3?cb95~zi4ltz_ov^4fAP>-1jwJ6qa}A4h4D{2M>qbsmV|f% z9rG)crQqcdCPD@V{!OIEC;w3z6qh~5tU0%m7Rn+5Gz)nZ03ly%i!rxV=>C%X;^Q79 z0o2>CA)mM=Y_>k+#2={OcjTbbw5)GN73YtaSET^ILL3R5xxhkeXI?f(H^nvCP^&9V zJZ!p}blTT_IXV3hYUc!5P(~nAy9cl}$Vm%3YVn@b^D!2#&pUi}{bQO5=%FwzA9P^6 zSzYRn*MA{KoIpJnydtq0ahj~>WbQgQ07q6<^JlDpfToi)lAE86Jw~k@CsERM{^?0v z25vOZ=Cq-;l@fDZ=|CJNKPP?{5_%;Y`}Z3wFw3UgXyA_P$!C$t8Vu6%;|E8xazBOr znDh`k7LEQ&Grae7qdMHZ8L_cZ9q(VTE)&aVr{LGNED4%M!1558Q>%LQ{tvw4`YWsSU-fOAC!K2Z2b=UW-CRDbL*kCLJ?P~wiwcDJP3p-ta8&s_qq*Mq-6BXT_J z9t-tm{4qPx73Ajx*n`ixW|4UoQqCsfgi5u?YSj6;J5sIb>|S&|=z&Ii3f>MB{l3^Z za7We|l?AY^Nu-xkqpcm3E3Nw`hJqt_oBC<|1_LVX2ZNHv5PcPseBy>!M2BF z__?DK8Jlt2$56i7vVU(xW9RMOz{aNc_sxpOrn3V(WjVslc8UV)FzKZj)7-ZFlsUhZ z7D6@u7+tLMQB@*D?aTZz-CkM+cC5uHdfWB}CJSlaGljt5y&MPNd_qaviOpC#fAxN! zJGQ+?3tT=-{2q4};Ck(;28bjRZx%&%YfqY<45iW6p9{4j1zSD(k7z#rjohQl{mlhV zrP8{x=;{+IWn^V7pJbsn4xx$q55S z*Zneb7P|WhcHp+B@@_m3?)=y~^YGFFjFvTzR(sW|jF6U3(^13tn;cbEoyLuGgyo%a zug<0Dsop#ew^t~JfegFcFjtW6oUxBnnwYpT;X#g)N7hB++R z1H3ZDi6I7W63+&jK{;HvDzh3GsteY;!V4-d2lr)M5^&&^Iq{UgVI$H5PpWcgJCU0= zCzd{*GctWhW4kZ;B990GuZBzPO}ZMNv57jMZ)FS8+@7kof0!xxL+7KDsVV|i&7qw3 zAS+e+;YF>xWLIr5KyCE#a4;oTLZ)A)fUk{uNqvc2HQpMLyY#J3rGa}`{?KHe&?Ap2 z42V<=P%`ja{Ypph-|%mxAY2PV0`$*H?9p1=mapC{{JJyrcQRzmd@4dapgbjYusis+v8wb)o^Hmm${_?mN3GqiM z(_Z+Uji1we;F$Sb1Tr}bBm~Y3@$>WY7ndAEKdqnb?}2Y&!^eP{$ef8;fu;8dx9qOC zXtzo$6HpJpRcl-LPvz z*}pIH-&R%-t%_}CDxT(FOHbOw1%MCDl%D^M8+n$a$oH<~G7~>vl#@X&Z5%7)Q6Aj5 z_>&yq{;rJ3u(|cj0QUq}=4J?S~j|i&y7oA?J#BG5wp@`o2!2&EXqA1Ia070EVes7NSB2*XzJs z?n-{Ye^OM|S2sX!^g9<_Sv{oR+lPpP8OCMZ_uB3DH+e_aSzqMbTto^&D>&SFHoHZ^ zz^Pjbm#$i02S2<>VeCm%_1AI$aE^i?=4!KWPd>SCv3t8_h4Sh4LEXM1I~b%)sTZyR zoR3raaV>+Q>&KfpU9kK=qr>crxGGYCt9BnY7K(OFN)6w=6o)9E!;fY z?)BO%Y)7UcOK{lAt!?OR{~67YMTjz+66BT+xNE6AZ*x1lq&A%4DELI%TqVndX7}2Y zC>YKhhSj8bynHzh;>q5U=8)3=syTAZeDdDWELhAc?1}ot*v{b^3&hBa_X1Zgsr3 zpWisOBV2k65xU*rwGk-f+#_b|;J-|WNY)S>Rz zP3a(C^C_LA!?O0AZ;O^%vFa=|Twtlf@xhUsVWBRGb&V^PmT-wjn(`xM{JZY1{P z{@SZlb;pi$cxq5d=(wE3sYbZ0R^_`~a1bMZg$vG=;q&0t@ckuV)L)@4k_>E1G=2c_ zmWY+LiS?8$d=dSs`SU{$bZp0F_1Agh^vT_Fiu@k#9oUg%d*T+K8*{S7t)C^^J{o)h zEiw6{lYgT5q~jx^y>Mqk4SWH)k+~L&56R3pg&YdjD>0sW6TR^C&9f{&kTF;to$wXA z+qPHGrx_o55>u;;5O?inrfgh2_gggX4NWjBG?^|@Y}JnUU9|hxa3XpNe-lsAd(==> zs1I2DUKoLI*T`y z);3R>aJw#X$B)+ZUE4hsC_j1@*r|U&yJXtBUm0l2AU|migC~bQG7bC!@o6r@HsT*- zy2QU#i)}Ki`j^%_{)NxG{f4M@`F5$dKTp2PT?3RG89x2*%YCNJ&$q8(=u=wRr!oxR z4lX!~vw9X-HQCB`SNR(KG=a?FKOJ1HK^9ykl zQoqVG!G1itLtRaFF3(Pw6GD^QLlh8&P3vm(6D(j4m1}$FpVStcuS%kM6y-o-Htp?o z+U-O>1?wpr9*jo5!ma4m2Wnz;pM6v`ME3P-AcIqt?Y@m^*B%4AuFlsUo^36u&6X>P zY8$q-jK3 zoX`b|UkgBdBP?=2G>uv~n53r&&Re0*>bMX{^5^!SY47&`IJy4ZzMqzf6#L0~ww#tr z?bV^#$5`P%9v@CFKV^>9ZpzCE#U-=TM+1OhmF(suk1P^VC}PaXcpR6cKdK$yu%O(e z!wSbKpZT`>R*dJq@?13L5MmjoBuLx;;~oBm0WsWaLprZ$m5sY!V$qvxLNN*d4L zB-JKs%BO4GmU{X)>k&P}%yIP_-!>|6yJcx5Ut864@}5kO{5=Z2nz~0?Leg5~81c-t zMFBvR_zw0XN9g@^(`rr!YMMaSvT9ovF1hR3Gi~A`-JIp`?6jDRxZa-QY8uWRXf@F0 zZaQW?m47QQC;wJ#ky&dNT>fcGUNgZNSswE2nAYya;UJR#QkWCp{`IiLTCoSM`E&y4 zA_Gu(xy2@XuGK*PkM{q5vIg>>#V@jnd^~awlvd>Iu%MGTzHi#!FX*&erggHNtJ0>> z=3e1P%dxp&JTz+WTv}TWnEf-;V0XGEi!Q_(X08qeEnn|dm~kdZ>aoZ!M@ zVsYHkLzdn-%DEZ=f@#KsKL0o;M5~Q#9N5#7niA=?nM5|NrgEKtz>M8@nf=q{V#3dk zpY{8#2+L0BrBRQdH;{u3bkX&T3LuAdK$Q!{KR$4sW-c2HTAv=fmOIBKmWh_O+?fM{Smy! zHon|F_-s4iTZ%EnLa28HItku28xLk8Uv-V6(fS#gXl*7b7M6+R^LMHR0L_4pbRy;2 z&~3y#_H?nvaEkHJT~SEjr2SRqvE~<Z29=kc1w8#4U-Tz!>;iC@{mj*=uSOYWD`)>yp9c<=@KTF=Q=)BK_@ETh5h^|DN3c zboP3H7p}LwPe?ZLBhVaX9Ue+f&pfX@wB6^g+xiTF_2mFep3gyKsA7;6h<90Ej_FjR z`DA+XN?Z-xrcr~4!oD;x!&{Gc3K99fm)-gqa`wos75E9$AOC@pwBC;-yK+|#|F%_c zEVz^Kl#F&?)!Zlm#jJTOmn3wO(khisa~Zp%Hob1=>MEZK?-$V%vw~M+&*M~p4gHEe zK^j+p3)gkz7Dq}JrxU;(Mjv{b01gcN8L-j9dXZ3wkz{+777_TL7XOEG**Jd{yjQpl z6!~+%s?tPMT#eIc)+lS|u@0Y~%Ul+Io(O}wSv%c;^XNnOI@fi~CHt)+ELhJn>hfAf zO@=#Jo0u;6Vt4|C`T$6OTuI9nbs}bvIV?zM-LM(m!3v zQ5Zf6RRd*+vkri>d%-syyDl#GsD$o{iUD`)zpMTi%~&w};9*Fnf``RXHg(eKk<9A5 z#j$qY;1pI4HIlJYYPpl|cc}|s`vCr53|N6?RCH{kg{p&c+tRZky*t2ZUw&!LhSl-j zknTnMkVRqjZ~p{i{;SphB1uKKW5|~}+2q2HSa=33UxYKO=GeC<;XF!=bHDsox&ND_ z5PLAuoT=cy@2x4UxOY05mw73chpa%_tNihQ7yRFSBgVR=ZwR<1ZWRCj*9*HoNF#cW z=*A7=8@EVq-XOmD_h}pA8$={G@6+6(eIg=yk6rA+V-BTf&tG$jzj*o3>dmV^t`FJV zzCLD?RGo|WRfMnV8_x9`A?b69_eiNq(a)8%SD&vDbDkkC4y6q;}+}- z+x!EF`X&`2H$l1|_Gc~Lbk5YjiS7wJ2zikXZU+o1zT1HnH-0M6y~GyqFqZ!4Z%29Y zznO7kdKBeE8X|jJFS10BmVHzKy;%Mx_6~Z~b941tix}00HBcS@xj}VDnim zLKgj0ZXe@c*BU&T0zxV!2UnaGPf0z;DJbc8x+a|&N`U}%1TC&GWzjvp#yxLa0%9|lwA4H}-PvO20T>yTn zlS;9h0e9an_hLgDNDn;jxn}}(rnuhZ($%&$goLt1+acc@L9&^+Y**GMCGSgiHl!MN zAd-x`D#D{zKxCtfRCHC#_1WR&9K^^%uZ{;u%8JJgW8A*m^wG*gMV%-Vnb68_qB9y4 z#l)P@i?8o~6D@jm)wkO7`LwjVwN@|^w8{f!Z&(A-_7*M6B9amf(#%kXY9UP?^^xS8 z>-FzXg$yKE(MLI}dcdS1>Q4u!w3<@(+OI21C7-u(9dp8C?22^6=w+$SdJ8&3sjx#N zlK^vM`uM>kJs)RtodRy<=vy1cEsYQ3jM%|IXT$~7F>NOIQRZ)=J-RsOt8>16*M8{- zebWK`RjaGdCG0uqX&djvH)RJ2tS?Zs!R(ey4?^CDxHyWIKNA)IO%(r!&WNmz_iZ6s zudDEu>J(G6@QC)`L=Tk*F8M}=W0MURR^0EKsbw_W;ai#J1Pi|GtRtT}^{sJdqY|tg z9?Gv5(=hdth={c>wplY_-&kTlxK9rVr|WQPE|K^^ujD+a^qYtb?XHl!wV!IyQ|!G* z#wI>@tEFSbu)$0ZTHs-ckE{*Xlo#1C-RY@W3|>Ck6y4jfd{(-2`C@k}{&Z`gQDHHq zLa!kw0wD9}@m*%+UTbf-Q-X>f* z&7|*ZyW0}uBZE&^L_H8aTFbwQ64=BfOf%ZMaEAhqPWxR-+tKrh zu8>NpQjF0HQ;GL;y}yYBlf-)oS9!cgR3ht{pH+mOa3$Q zKL@JpW~w03!xcl3<4UsHd$;Sihd}jgIzNn2+kMoPAitGsMzLwc;grZsOoA0tn?pAtN(hDZ!*VdV3rxLgO-8@@~XK77RFoR(ICk z?G-tJj;@Brg~c4jh-(YsCEL?Fbrx39lihI*HfcR|S?*8RG{-!d#I^1Z=vNdV^eciJ z74pq_B-CBeQzL&y9=*+vEXXAg8abMZfrWKw;Sw=*Sk)_cn!9^5tes0BzthxHtYVZpb6j0kYRJ&m`{_AbzPwa1^x`6g`>c?kr z=>2hilj&l&){M+Z<@Jog?ZNC(5|S&{r-}@?BFFx*`3nuMJkFP=%>cmS_ZR9%w+vm# z78Xr;N3Ld495ejzUdD*H&gb3T_Uoox>H~X;uqdA zI#p~bdRwGCl~iVN#5KJbG}EcKq;TN*w&D1L zCos9ba+hCwr&yM~Gl(U9;pIIQxYhJTNJ&0xnXlz^S*b%Ga_hk6_|Ni?Y@I>At06X{ zl9>5&;V7{iE!jG|Lyxl+D(xXn1Nm099p=;by+3!L>)1)gCX6Y_^M0`47=c$_KH0iF zkYGWAq#0qN8X#|ykaVdSiBeF#*SoR!q0OsdRvPum+?3cJ-CX%jl{?m5a&4~p&9@E9 z4%b(JPTH+oQd4j9W19M%id{6TKb9uxC@3(2j_4NZw{j!xjo~nIId*A3Vf)ffR;;L*XF2mdO zz+NyoQ`Bw4j_QYVPphtS!a!{h-yZL&=VC)@=yd5;+=rGGg*mSsScnE1WR>8Yw_M@k zxO?S3wtdUj%o;sJua75oRemVwmg28)={N5+;@Y?Gd?e5Ys}*rUuOG^dCE#ul_2l=@}z0d zjFPp$WgLBsY z+gpvwWT5jS4iL2a!UNA@W1R2e`e1m8((F(wr%`0(^yhiqe8=9b;nk1HmS6m?YL73J z9%nsqjD!EQiSr7B4K<#o8jE&Vbj@Y4vPL#^^ql+k)?+-=Ya?5uE&I!iN6W_0LRE{- zXIwWfq@b$BQJ|-KA0utETo*9fv7fwH8~IB=a8vTIqk=Zg+PEhWMZVo_^Zdm-gIJ@H zm@POp>PdR-m0@qCbLCE0!Q5o5Og#-k|5F93r8XTt)p(C0V%_fb`73af^6_ZQvc{N1 zNj`O>NSVxtINT&eHsi~@=QeI@R52~8kzbnYgK*J0jwlwJcq5sQQBy%JkG?P%9Klm~ zIz2KM2vjty(^kbmg1bfpu0RK`;AJe8pF1mKB+NxjM^ijxIZj0AlVg1&<_+p*&k0Ty z274DjBhTU6vTo*m1Wo!w8(U))S&#P*_3X~1{~u|s>S!;9JqSh{_MXCgqB1>YK^YrFBahI>dP;05q%e`e^l3`=;|^Uv)u9$O2?tvsgEXBveSQ~LIM(RP{8q&vqYLqk;Yj)&3_8+7dm_B|6H8yXC8XoOw0q=89ft5 z%wlzLQUCV(D9Dw|Bfi)nVEXC$Wjs%^2vzNx@z?GO>lL6Us^4(;&+ZM2)T7E{KRsHa zX^Z3r<%KEk9xIlo=mAgfwA!E*MCF1emxb1H4r!wcYRIig_Nw21#m@~^h`I_X%y;eA zKd)Gy3ic8*x3(yClqWxO&AK&v{LQ%AGNiJnlTRZ$Dmf}~Ku;tM17XGqupWpcL+uNg zK8n{Kn{AC5hty>2@S{UpK_&P%*lCWl`n2xfM1E@9ysr&UvOp?G&!ZOwZj+5K555=Y z69qbQP#VHll}6cbB&HHbh5}lCnLkoiZ$F zq6l?cFy=6*nIRg}Gqthy0OZJ@)^BhR)R<-tKbdt@)U^YbL<+AWE&{xXLcK$L7SsG? z&YOM{t>!rJFj}(_+RHcQTYk|k`o=Fb`N+bn)m%9z4$OSOO)*{YczM{$!XP*MKqS`Y zA^YRW($_q6ZoOfe^eD1BaDIBB#JJ?f*A&YGQ`VaEzL$c5zlkL8v%ULep1_bWd)XbN zzNTz3Xv4U^+5Cgu`@y$+td(Of$GapW!q~7>wzyDEStlT;aH?vy$>gmUYky*IVi5Gg z(vgmgH+QI8_8(`S|7uxX3T@eAlnFEDJ5UzTth<}Pmd$YWg82N%11UxHoypC~NhCQP|D?s;a?5nd$5P@fQ5+fn{9Cgz>fWAdn!Hgo&Z% z`~0kG$FVs-dzE-3xqhpZN4X?DwGW;5!)DLhu^EzWV(MaGjzRNKnHg6zSZ}Q zAWg4NdVSC-@|BY|?OXvd_fz~io@VmsEvyqmR#{_{*1J--S;JCi3H!xn%+JQR=dPV4 z4K#AClUY*XdRQ9`O^z@Yb6?V~~b_hN5}DGZ)H+=2jsRS6KF<4H_U)eqY_Z%cc{Up(xymN&L_1mE`U z7B@J!OQpZm@>sWS@H%MlGds|bgR!NConb=*6w(j(Qw>ZJBHLunv{~-%3(oH{zn5r- z{v={j|4Ge7K%Bp4X#<1fKtk8iQ%?KKIy~xu6#TAcfbuJG26Y zLPG$Az%rLduQvtuWWM00Qmw2uc?V5BqbJ^#E>F@m##oj!sLyN{8!kEkCh=>~SHq2o z2>@@;dS6D?C;pNgOkktTs&QJ<)M@tJyFaE|mU!JKoD;_1P2cx1kCi^t;AVT7Ubwk~ zvuE^a&_Mfta}UnZkIl#=&hId&wy+2G-R0+-eCr1`D6TM?J;&k za@CTLbS^9}S}6ah(!k^olCWO>Q=2opw*z4U38}WHlG!ZvAuqN117>MyS|ClzQ}qp(w~o5tacv%g~12$u3tGrwbR4W5;m*&!?#ea z4!4;M38!aHk7jzqCa^Q;=>%1o`K|6wNuf_NnVuCW^Q=eT#mS3ZkORIFXV)h`okUc^ zBd9yG!W19-N~PWx3WK(DTLY#`7_=|-x76oDY5+UrXTFg6!QO4ck z)H~gd7r|qNi&1DHVD>@^BZc_neyJG)IwJ;6@exuB(QK$ZUNPzTw);tDHj!{_w;+s$ zj`2>9KdFO20MNwB^3}^rm6Mw;bnfKtqcKsrJm{0w)h_{S!O2Wr!%2os-92H&?SwWZ zpz-V=+S>S986J9Mpgz9Fh?cyjJZV!F!P9~>gE>s9K;ud*RyWmhAdbvMv?hCA%gl|Y zsa~98{D>^9mDx#^5S^{bAM|GYOt{8oRYYh;7s>u9)ZLP{ckK0LBm7Na> zCdI~1r#XzTXz4RN{d%iOf7gr_>--47?gkecvR5ute}UUu`DDuKBtlzqzYaoYjCwp- zMjHh}Po@`|N!#G|i9jNebs`pdzkCD6s&e?Jy=Q!bMPRA~sn3_S)AjUY{^6)5YT_gZs;yLBK7FP1D6OJlM>1zBb|?2|X2cxql1kSOG&_`jbe zN;Pd8o@{+ksqWnM9+S#>4bxI|8b17MPe@JRzKrdfSGq6ZN(r;aGF}`uDkjO1tm@tF zNzmFpJL!|4m;Ge!Z)@98m?xETi7sF{HJ4?B`Kc;gatO-J)4S7Ax=yXx8Ptk6tz$a& zv6E2TgrijGGtXoz#4%g4niFrNtNIJ~AW7b58r19#c2_TjQ%obfPWO=+UO^DuW)DT( z$c0hV9IiAVTL;q_A*ndtD#q;iHYE%0InE*}!BZmUXV_`M-Gm0H^o@M8GbOp;%79o4Fhcr|lC*z4pX$CW&(qk0J$lk7 zy**a^ytb~iUOiY{bdZ^iwFK;Oz0shrQixvxO%pgF@7Mf58mxp^%;k>o8;p_)aXKV=5yRTRYA z6mcR4;=LUPq}#5H9}Vs1hnm^6o@Xtso68A6*5!KxQc4dRhGC&t^!Q#|Dy&Ib8 z25~V;4d1LLOXqVhJX6AM*mtUVf zJ6@#9)6c8}hVkRQJf?()zb;{8A9tG;Su4X$OO7qCz(rzqU1d%dJND+%c%Zku`E^Ud zM{&bmPO%;k77>?)GokGO9G-=I+|P^IXWzi_=pyn#2tVxg@>uo$N-AzXoT=g3Bd zK`%GhYqZ8C;yL0XIW;*VIB#U- z`s%|J>duRFY73VP4@GVu2z4ECOk>o;@Hc@6;tTx}gQ3-aPch|~13n*?RC7f^V3K=z zh^d?W`V49A7fLSD$Sa+DD8NlKo|VZO{#-&Rl-7w;9xQMW$JlL|OE8i?~SI zEbA3t8to28PbLJDA5Ug@i18gSd_&g;+OF!I?atS%a#yBbW}DH^K1+uB2DyzugLw%nL9XWg4pY#vJyqXdsdM*ta{`{&3MH*?I3RYNN#VM#5$n&=HTQZ;VWsG%PD^{x zG*5Gk%xZ$I-2%D4u1usZr*CGV8A5%R5U4-~tI6}v z7q*m`Oc+}S)56Ei_}gXvc%VYiec@Mb>fZ2+?kDU`RcOiCz>2haW+doC$rchJeKJ78 z3+(Jdjr-OQBDv>gFhN&zPk4;#4pt40800j0Y;1pN1;?NiDGR;V*7gRFWmMsJY3G9k zQxo^!$33fz<+m7cL#5jg9(}(n6`^0tGk(|jI+8O*RT*uclqWDBknt!1v8rsZe*+kV z7n&XDDyG_xWK9)JS~6)@Zti@Pa-T5H;-fV${kGzx1`PW36py+&W+aajH`@$+aXKd7 zUI57jOS}l}HtM#h341Y|z!hD^P@!rej>`qfLlqtH2|qPjwBTBn*M<<#z=Un4W1AjT zbq`Tz^a(waf1|}X7*RYg+SrH1P=Jr#D)#c9iTYwY!ck~dn-Qf4uys47raa~SBHPWD z40(~#YkOPa!O60NZ{Dz5x&C#abAj1CWZ@-Giut~jy`tz4PjW+nf4+OhEb|3a6#vXK z#j_e-v*>r%DTo&^TX&Z_tYw|NcEY_*W>iH;l!<2U*rI)N-Lk`d?l_@KhJwOtgEKsU z^^|{{YN&sycCrB;3mF1WvhcF5+5ls8swlbWT)?)6p0e4R0Mw%H{W`Y?IjBtiUf>H) zS^4_@fqbKRoF4pvw*XCI`Q%3SkF~_F-4+^0!7CQ)qDQUsakh~RYBmPg%Wkk;_=%qk`<{Oz=qZUUZu z;Zl<)eI+zl13c9*phwT0>G>#Cj5XZ1Vfs^Wz`{?ggF8>?ds{$%Qp$#>>{;rNrP$pY zIk8#(l03J!nJhdB}n3Ij|8leb5e<%)^)+}lK=Ua-nLcUJ6tG~x zB{w|L#lrIsN0DP&>zVa_*)Q7r-ak8bnMNW+hO9u)m=`D zmv%(`6^)h&M=Qo24Gm%1U(nTJpI3$(2qp%4lU$i5gL6X_lK?^T!QJ{!usN<6BN`$>*x5 z*P~gLv`l@!iBd&{d75ZJjcRE@&+n^LhIPsGrM*nXiZo&l2RxWUL2;}8{rna6VO{D| zR3nevsD(~}GCX#1>!d66D!m7>tCq2s$;TLGofRJc9eGu!4h1>AGf`WArLrHe1xxHS zPSoqQgx@W{?r#Pl3+40<^6me_(^mks)kWO~3dM>QYjG*=#T|kbidzWo?hxD|Xt9>y z?i$=efno)M6sLG`r<78>^yT~Cdw*s!lbIy<9=T_oefC~!Z?2^UCCa@;%!%In;~@G{ zH>tEh7*%!zI@eIkCpS0HJPAe7Rx7kY{M=XBU#cP*W@9|n2@%!6SGhfIyUW;0ed{{B z(6_SH#Df&eg25ZCd3bpESvh9GRq7)`ccPvB1kyQbHjAEEd)q5LER072bI!zf%HR*Z zOP3nQLasIZr|pAA3Y6`iKL<}l2XdZib9`|Us9Q}g5M1ujZJ}wi?&#gApNp-S2s`q` zShcvdrS*IK^bhcjeY#hDf6={O>0{H|A`B$RW%SNYuzN3SLnOF`(k8fxwADvw zU}g9WZN4p$<6^}KnW^$H_6t_oBq36G8UWrR>5SjAxBWv?Nt|VUxqC;)fz?6knDUrS z;G^9{BbOn~!XL_GvEA{^o~Zt8pj^w=#EVzlILWEuZO#%F#ml+WYrVBLb8>sDtB46pM85de(o*~~;v}z`ZGMNhoBuAm9lpvzdt70#IBJ$CyEuuM^GZ*g z@mvBSj}q+!9t!T(iUyutNZ|AIe}MOK^h|#qD!;KJdHYdz zKoAnZ_T=Ha^p4B*TI4Nu4~yn#janTV&z+r!b1yjMtu$CUxc66(kXuWz#*eh4E>ecY zi9%9%=%=Pj8bf^iUSj(AJr}c$vO@tJUg)JwKu5kgjVZ^Ih)29eJyp@fl(VKm!8~RC zCpyC8OHtS=xux(up98la$=Ljk3@;ONf(BJe*KL6^|JO|I5KGssbVv)mv~A+;h~nUo z{cGd*GKG#wO2>7-&aDJ?xUZ!$cvDaKzNiH!ignPRsI0omBTdky6PKJ9wqc>Iiw)A_!fnnU4^R_t+*z! zGXDO_LJDf1f0II+R)ehjAIg+xTCtJy6iW@3ja@Zt|6RJYxwrOTz8t`s>)&u&C7!yG z9H9RhHdL2lH1JX7~1!HG0*gjJ?j`;ZkGAUbtzx?qoOf(#uMXDsesN z>9{F-2O>FZ3^ATw9)ng?9n$r>|5s5~oRR(V_{dKzdGJ0jQH$-fakBfflR~=*r^l7@ zE}i;Pp*zFQZ~++otnk9e$2zCB-O!`!CC5FhLwtamWl6)((?Qnw=~&aTGu*jeiX%@< z#Qd-H8>xSQCj6ZDhK4nQu-ih8k#5$n*6%~X{{RY_l2NF$Snd_9%W&g{#^Q4HPG2Za zFq`g8iOmgc{E4j@4x{7UJQo=L1!6=iJFFq7cMqo=ro?XkURp+*aWi_?XnShTL|cOo zY545>#FZG}6yGEhY`>a5=jvNENd0Zl*ydbKv{W|^v0CsGL7ydzpC`|h>$A1XeLG*W zTo@*Nc)VzJaV+jhb=UQZ`;JQ>W}(D>eR7n#SSg2=#%zA9bv-xjJsO|mW55gAzcReu z>h?!f^{+IeIQ_!;;f3##is_2F z)c9Lz{zWZ8k>Dn2>|QY4i`reJ6yrSwO!)hXMAiJs`Pgs$bs{v>+ARMEc$G-9BQ4(} z!velCryVq9Ih(2ke(NE#ruk&p2;ZM8qlLZ)e|q{!QtoJw!Fcv+#~77XB_9(MqDd6B zD!}*ER#-oj%KMXs6*A@Ro%b@;C958oDYPJE{NlB()}ls0tcUfW~#N zI()T@hACHb59~dstyvC&GfKu!g^k43Ak4?pA1XJ~Dxyd~a+1U?_c0K1EtKN+nz8%? zd?HQy3|&Cu9WuU%=%XRo5a&EH6Q4ISzNGz*(?WG0uyav4?*AAmotGssd9TzG;v|TA zW@LpD1Z%G))-O!n>WrjL+Z@Y_4%h+iDeDKtxA&P6&y`Q_bl&!d!-*P&{~1^hH{M^LZZ>CNW@x8 zqE1;2o_WuAJ3SQ`E>QsC^CPQq=xg(_PdofiY7Oj( zo2;_Gf`Iq9tMcx<2~7yRCwBcnwAGu3+HuY)Lc06y00Xojn3lpXB7+G$(!>oyIiV$1 zx@~BT|~is{;}J zV`Z?ZEs0=CmD#<5DSPXA8x|s}z2CY-z>Q5PDPIFDC!Dlhebt_=d7a3z;yndJYq!>)Xr9KHl*z+?&K-0Xn&i1SEokC&BV6fB z+si~*|8;RSIS8#}$LYC2qDoYeGPjbM?7ci+Zl*QPCyP?*Aq_jmX&wIiU{{n@=0+>G zpuv@K_7OPPQ)T+?-TYd>@`G=VGNM7U=3{qeo3(+g9v|$s=*BvUd1@SHGPj zmNwx#Z@IlK*XHJYF6+Q0kFj38UUVaCVF&pB&3F-BZN}}XI+3I{hFPyBL20esX!vE- zulo%|)CY<`OVF^kv(%oLt4it=gsfdwvTshO>^#;M*3Lo^Cj%RQnm2hH@fygtjWG+< zStTwsZYoWaZ)Y4C9*?!(8>F(Jj%`)qHm2Zp*_FBgz3H`ysLj_>3s*0W?{XaZGrjem zKl}-jo$(y$5yvuhl`BCxa%qU8^iItgzdaWxAVui@HKRvi?QB>4FR|(QQj`y%A@Rn% zK+`da8@0mVp8~k8e<~8;Ki9Mng29*5_Sk-Y`tN=C5!uclK73Bk-;jPYdSdHb?665% z4dD>q4a8==c4xk#jdmgfa*ur9Ak!e*c?=Nx&Bo*$=%jEUd650hklP?UDFkuthPcXy z2-9FL;{1_SG9Bgvuk$YlYS-Ob`lw1CsIUVSm6YpoeolgOUqo#N)*PNI2 z_F40{s^$=d0|v<-7QamGdbb0e7(Z3}F|_(rH=V>Cb<@YZ=0t#?t{?L}^+sJ;z?<&g zP?K(h7FM`ke~od2^zS~_8>r#i^A7XHzk*qg)ou;xDx;_TOQ1$aH)Cg~D-)&TsWCfO z_<7W-V(vU|cRaW~&wkljuL1o`?V8l%krTBaPB_(DSZBM!hRJzH9?Y3B2G2eW_lO)?1oNf6(zm^L;rhkU{puIN6y?6q7v3xl*5xG4;&tM~C}FFp-YjI*xW zx#wJ|`K=*NHH6Y?yzfMRS{nx8TfXc*t@^Rgl+RR>HIHkc)7?OW^~cc7SU1xa7E3zs zjQ9um=rw9O^Q!u9ts~Eg4!pUzZ1j#<=JijmTjo$dsD9#6pGEy2mlPj`S>J4_a>tU* zUkXvE2#>90Yz_ zhGfp8o|D6M)q+lMnVQW^AQhoWe4eO#{!ZuSlBb82u9oNQ}#Zhp&UsRQ>e+eEGREcM5 zet%k=$xBmhVf*(Wu$&h3n9A@S#c*qJOC%dq`duH`F+%cH}>1sf&k>M(3Cv`;;VteV3aUv!TvEa7ZH zr&OWL=};KHL()j&Ik##_r&ZuL^9_hgH}hv`IJnkXAKt@a`46CFk84Wu@S=Elji1(Z zu;Cq2uX?dsvp_k|JO-`WmK{%Z)8(j&9w-l5n@0tg^$$MnuwRayaZ-)|!}G0t*9_TH zECim4=NA!dKmEo@)lw2zoj$wY$$0ol^9RWtW$b~lLzVAjPHT8mF87uuM*jW-M9#;( z<$89^xbcFbIwv1O8IwB}T`LlBj^6#9_+xQBB+wN;PRzHSpasjM*R|VFO(HLQvrzSZ zRS_i}K3?3?{>c5KgG*FQmKT4*TN%T3VKKcX$nXk2h!_+NJWBc7?OD@lI*@JK3RbCl z`1zA$=Wk_!rbB`eoeQgB!>M)|rk?RHg66hq8-HYQbC7D#p8pUOY%OR=w^D=+)^|GQ zy>n8Zo=8asZRf-9l>M1}i9)hRE-l7gW@g%)#5;cPEsc*o@c1geP7>?E{L?farkwT3 zLuS01$k-z9I*O6Iwn3n#lSFHBk)J4w%k{b3QvPJ!0s`^tB?gYrvKcUar6b_#& zhoi8qlE08sx+3}2W#P1-5 z6IUkHzFt`Y))#PFa1H*;(e!9k}g{ftCX~%cSEYY7fA1|!jxfnzo0=oa zn$WK#IITx@3B>YBSU;;J`r$<`W#{<~1#tum)r zJ+WxXX>yymOnRH8H&4pX24%82EqqnRQBH{u6);@wVgDtq^{6dbuV=J9X?Ip6X4lvM z($~0`UFYjyuG1R7{%hScNI5gjrcq}-FjcYxi$LSe6R{(nMF|?NiN&KD<%x_%of#1R)Q6(M2oX2A;s75z@dvg`l;h>Qg99t5P zz-EvD`TkDP$rXnF*&3|8x=K=ar9zKM8gSz8lvmzbDhqbjUuh@Ni2NEksnPbj=>=JP z?m3*Q#8@MIso^IWHSoo;l-$NR-_yPXg38OBNKL3fYg~E5IVg}4e*@F$=BKrnKPad4s)uLSwAMOV|BC6T@mg`srnHESiX>A zOL33wFB?8WmKp0J0v*jD0OTto_DiBpLD5CDl(LkLNut^NUBgzGzK+)lGrlMWh&rv^Zv@v9z zkK?J~h%ca&d5Vbb*(qgr6G}gsTU~WmI`o*70cXC8Sg<|*7+TY54I3kaLYvu*R4d-tkzXuAEE$SRK2p8x{GNe5 z|Gl{&6Xh9Xg4E80jW%;8-m3EVk>5wdO}98RQ4yiHtel_UiOb=awV8pe@;RzX*4h8>^SYO=ojNQRPVCk@mQU!1+uj-EwVc%g7Th|FtLX3xOm zQkfFS%K7=OKc}K9E`c^R`u(A>$eg1vUry`aVs@9f(+@R1eEor+acXyAzrr@AL~NTs;_wHn<@8Hs<=yj&j+DVe z|3^lV7d_TiCXI{8uaFh4kd0a3l2~Arik8tAgZ;S>J93qu^G&%Kj^Mm3CjmF0`BF=*c`~x4en~o8ayKylhG<1C zIKSMIvSU3(rFWPL^jNEJtkjPZy4CFE(cJWsjp4hn6y)Y=#JD!Nb83%U2(_{NhVKe2 z3x)_;3K`0Bkk9bajSQTuD&J-3Tl(QujD-=5*08?&2cUk}OV@TeB2HZhxoX%Qqswhv zd{!qwaCUUVm`g{SrXIFG=`hpi;IPKb*exb(u|k>^iRij%tF6VLA$ zYp*%fz2?Avge6Dr_=t}Lv%#N`sNEx$GM60JB!_M9Zw-Ei_PdI{zkF5vza0G^c}lsq zG?=!`QcHPPY7Dn74xghMtI(WqM&Xf0nak$+$mNqKL1FO^FrU-v@Lf>QjZ8Z>DjyUD zZ?n?ZeEO)z*Ac6CIe}N3-}@-3>m5;qQf&HKFSvBXjI%daciH_C%DPqegg2q6ke9AP z89#Q`WiGCejn$R^04R3le|g!7QSwieQWWifg{H(705p$Ot^X?xMSUZKR>-_&mtFa~ z!g1tBPxuw5IqYUi!%c(4X6sAa)&c4o^uz#kG|c~Uxc~pFpb-OzP%={s`j;LIa{r?- zMgQ+Y2Wy^}3Bkk4)SegT5^-LG3vrm(Uc$QM|~x zO}%h-L^h+H+K#tUd?5gXR+wS2)$CNwSG68o zO;1e3@a!eO96h79r6=Fp2ol*eCZLv1F@}JJm4{d4%*Uqw@RI+huzfCr{-+HU)2M6c zuNOpll_98P$RaY((YH_;ofGX_v(-PkS;)P>Bp_0G=ZUh*!06XktA)`mPR)VL?+t%> z{q`I=OInaK<=&RCbErMY{8nk7g7xjukp@$gGUOHaTTDydvKMyr?hQME$s{ZQ_j{t2bJagU z#Crs*6%D&@m9Wv`*Bo6lTHj|EA1s3tc}z@tK}>_N75xc4a6Jn3vQw!VWwny&UZ<#KGc<7Dl*&FW99_bmPg#=NB26UTSQYn!W zztFt8Bjq^3poWg9?4pLt=<2~Crsh55)}FUzmswr|Ls&NFAHIH*GkUm*ECpu-$fllp zVM6Y*rx5yj;vb;voww?BC#RHiwzt4V8`M6s6f;J=E}4?uk0ZOe=^wyo+kZWJ&Ty)u1B6o)ip}wJHD?gt&6+2BjV=v+I zna7r#%b^8qbR0@tP%F^Wk^tJR5qTkJCV43NNWYOJ52!jwKAqfF{lyT+3$SKe+tOdF zt<`X$7v#A)0CKt7dRfx*itISeFryF!Sz)|2IH?H}rYxvDp+{&tR*-Ds%O>_;3Ljj_4$Mw&R8oa#M>`S_gRC$E8OPVS>!^F2XntvpsNOQa#8#Cns3^6jU3?U5F z3#5Q`I-(T9E)%e~U@hgQVhvR-boTSMfq@KD5Lw{M>UN705feAG* zJRp<35>gXo{YX=73tOd>A+{M1KLH+OE1c^^ma$5Z*iMM)MZF^+dF+0?pj2c~Z&e)8 z1>OXpbZ^K}{M;kM+I7<^(|3}TRSc$1h$<+)C!R3;=lfPVXfR)wnexCceQgtROG%F| z&g5$q*=&XZOX~H9{DBX`BeZIoQ8&wBlJdfE_Ia^W?CNI_Ka%%c*;XI(n_xc$W- zMzwzjO)AeHFhl9eq^1@lg=XxecTFIi3Z8KnDY9i<&rgZIxH3UPEJ>8^i8j5QJ9ZXc zsxA)ILNTlOk#a`W%t5gmt=ARWC1^@k=Xh0#dU}D%vrk7qj~xKu?c*(PY?I1Z^LER# z8?aJE-g%$my-V{Auq)j(?gx{NnL}6^Z-rES<=pyn5nU&LW#W~R%eodC%HFJLrfdKa z*@C0Vha1kS!*VdLQG=bE9uWuiY#`(ADreEO_Q$$EUWpKxhaOjMHJ!^q0(+ItVMPBp z7$`;0P8~`yM|+^xCGx_x-sU{cvaz{mp1gWlRtVOxEHJW$Ky7c2y>hBp=FboE9JIuM1fXz33mTcQif zPTTWEtmyYH_i8I*tdKgk*~gkUy*bbGB`-n?n`b<)h^Pr-FT$BZ!T6#9kb-{!jC9}} z57RD?-oIz1JK~EnEo&(Hmh(LEV>snMz{he$ zy9imw*A4GMEL5%wW@H;=1HZo>z!Huz*7%YL+=Za$+3JEcq{W7H5*mHBxz~%VOx~iMC;qb7o3W)`tlY|MU=8?e`#(cXEPKvyVre0UpU;`^1jk4<+QY{M;%%?v^;0pCPh!!=J{dPB< zN9v7m&^eMJl3zQyoM{W^rXNfLVjmRe3g>5uPl-L(rU8}BZ+;Hi20_Pal1Kx&X`c4J zdGUy+dlE#*UblZFB@C+Ch`$}CaBarp8MP4bL1m_+makLgl}P7>uqqWtZ^8s$B`t@g z8`$S19k%W{c}MB?4Ou%s809DbP^;p(cL5upVOwG>B3ON9o~RTSU#P*UShfWAOlm1# zy#*#G1Xg3;%EFiwX^89QqVzhA-T>b)~cF`bEe-CT8FlN|YCs6>i5kNZlz zk$CtIZoP@24omn06Oj2z$@AQqSNwQ~9|aPe>d37&YzbIK-!d0Vq}nZOuy!}|`tRX= zC&{D4;L`j>Xt=p;dXdb-nF1}u&PdITGsVPm%;~zp#ZItQuzUR}1(IItR$3!atV7H` z40craC-foulZ*Q&t_TRF(;;Q7Nc&1w<;V;+nKTk`u3@z-fB!B0ps>Y#^a$k0Zi zF{!yZ-f`Ibl5E2`&(~09b>O`xEoWAzokqY$_J5tr33;RW-wL|UbSM_;RAR94wp@2G z+bP)-IZRm0Hc6&CGgl+ff2G+0?9;zKBqw-9om(M@R}z`1nt-VHkem$TKU|-VDpuZ&Hdfs=fJbya`HBgz86EK@;kALxWpPDY*;yt5*8MC3yFCo z`Bv)zMAvc8C9SLNdBeC_|Oi zB-Gmuwi=^HOH~{4>Dwv=jjuw!swn(ci;&Y{4N(&2sRJqH_jNE=b6DX=`Y9ghM7y-m zImlzs2x+j|cpWCLTi5WckG@l5qNk(8E550c1`6_4ZRQC2I0Z;K@Lddj%#Pe#MffFX!goapvFp?> z{B#c|as2?*)v$CA)$nqa2l<0DYd(e0=~AyK`M9?CYs-gyD}qJObV@JEW}m+Fre3$F zSk9Mdrkg?7Cyq%)y%LKfXLI1m?DLfpwy)iC`Vpg>*aOifK44#0bWhKfV(EEyxGOxy zT8JBItC~I)Cr~pXBq!z%_QM5!yDZQ+QJ~%*Jg~7In4td7`Nz}77wnOZah~)1@TN4x z3wJ5}0)tJvl3xaQ0bl(E_1BieQIPzHX?Bu9SG~WP-&Xw8CDMF=_umW7booQsVUeo7 zmKX-3@8i+Cp7G+U3!GBSIJRFoDie==WAjyG^5I+UsT#r8ZK4)zjwsdLsYzP6r{4)M zAeM_JF?F&_bSRwGg7JvpwE4s-0xht71YSCwigc(CuvA{OXoczmodelm7g;1goYGS? z!Q}WBn(J(fHbiLo-RlJd==ALRLqh* zc5nslu@P6|)X{;>V4E~aJc*6N8hx&3IkT0IYc;39^~+q@d?p`tY!EZr`*t~O@<^;e zbwZn&Wg)^wZ{Pa)go3w8l=IfQPMG;)-^#Ak2kC?|jiYt6Q7x4;$K#>f3xXAt5&_eW zTSitwSPq3W&$;6NqV^-u-@0UX3&cIXw5~}ay}6HPezoEQK6wCj{|n(`Rph!4PQJE6 z-wN>;yCeiDuSWzKlv2-XFO>v<0Vs(j9-HFOvb*Oh9hS~s4)a;#i#w*UQT3EPEvN0b zdY4@Z%dBzTA7#0g%g1CU?^ap1b^9b66{TUgn5Gk$BXVj|p+|tNJHV!0VO@iisw)M) z3USW5(+DU#CF;kTlrNy?WWejeXLX_!31293@6WVNf6%*6`gLu8p9Gbzjg3a_RY^?X z<|zo<=VQmH5O@q8M3BZPS)iBV!Ki=?IuEPgfS%_FuZOUlrzB7-KeF1+v@7Ur6X_}o zt3q))(-^QZ&_Gr+b9oWPz0<|E5-bDw>tmCrC0u>SAHkU-8 z>+kD;Gzom7XF9#P#+goe^5ioi!VktK-xirE5V5!{26E@Z746`uh!+e+3xZc{5>~yX zZ6X?8j`6MZi^m4qbwJ7K`~dkP^#Q82rDHKG+gS&6@^##v;t@T}=Wo>KWHHzczz8sH zQZtP~tq78}8f;pn5FLaex27Y^mRwztgi~6rl=?!odqBnxmw}WM@+@*x6Z6pDo5be; zUl=vw*1EcJ+P(v$0C=~D(iO)VNi+Mr<2LPwbS8ywsDz2$pRx{gkFBuT&wdCx#wVrP zC>yDYR_ermcU1aX)%8`CM?8m**dyju>&!&K(Kp`}-U>lnaVTbpd^N%wiN8XG=1-K* z6RmZGcx7>%3kpxbT}YQVQ8YOpn{Clqz!Oei2{_mu6$$i#pWuDCU!}2!H{4x)PG!^g~3yIOREZooC z=fJg%8^I%9vQsVhmqg8}8Q)aNYk~Y?A4Ni8g1fC-sOzO~~=nw{D&Nu_3>hd&TOy#6N7XUw3 zGkPVfE@s)>?3EK+t*(T>2E$G!yQaFV51lRkb(7F4jB4P`vDWc8JL8}ppK-O}ck}s$ zntM1oC6{oDv-;eZ%7x)KZrO3`jO=JqLuQS6UoM5K0;XBoa-1CT#FUGQvDCGPd~Y-Y z*0KIHPxc}=*hZ2QPL7i1Mw|#Dgd!|kBP=yfn|&1g?)nm|p0NU7G~ks4HN(3xqP{wFm1 z-DTeHfDrTz`v$Yde)JPbtZY8x?|RAQS5lws%b$T-?bz;0mG<73w5K13=SUAD_nTy) zxRPkNqz+zHzMo$nlQPCc>N@@&aNsaVIB6zDv~;pUpNN2&nlct9XK4ZJa@UElt1JlI z`^+s7Wk%GqmfWwW6FNI6{iqumQ`{p*g>s>vy!7xhycf0Iv?qw{_0tfCZRG5mPh2BP z6Es?napI2R?!EFX)BCh@n#Mj(5diuUN1nnnsH%S1vmfaX)s$L8~0ni(woIU_dB4QI>;$<-nljY|AuPsilw)*p~N=s%H_M%}>$-93Y$a4{WXZN?n-TQlzSc zmUio>0Vm1n>1iE*92m*KE|L0gW)DIuSkW&000G?Dp~0D1UVgjhiab|D)SmPLYosPgRYmHbeIK; zC8Z_R2~6-WrQWD6VI*b)ijd<9yV95Zj6Pf@JTGJ1LHKPE)DyKKcus6X8(Vb}Q}p8k zK@7`A-nieEB}QHlyf&!XW?PtVj;hCeQ#~V05sI@CQyRW_iWRPrFgGMwG1JPww3vUb z9>6Nlroj0C^m}kidRJCSe%>OESi@oeCQ+qs4KW%+M}Kqdm}cu%F%U7LPNIo?rM{8n zzCmv7Qr#)PCsk?)3(*dsbZB;&7jsuzEy3I}QLOekMeqtb{*;raVaG;tdH6tgr$6cy zB!q%s3{+1GZ0}5o@*{%}kI@j)y7x$YD($HUfrIclKI%8LuTjPvq9Q}<%z>R5d-mfl zn|`W%`24*q&76azc5l1&sa^gI5AFP0r(7H3COmoePS<%@45KHGZWA8It|MRGwiwis zSOt8EbU+7G4~wS<;<3p$-^15fC4K>y&U`%aJ5b9K-DidZ^9O1GEve|c!*l#NPWFjY zaF*jSftM&9kleamz6&PMFI^Q)W&mksNogmgjl928%3P2@`4fNeOtEh|{RAGbk!x!Y zXjg9$b#+=e13%Emq5)%KXDq6IDFybaBhmrOrW)|m;wB3VUpPPM`(vc&IBiGq9QW2Nwb3$K2c%A+Se2eEzcetXlpB z9R$3x_ky9fhImk%_rB8lSiI|Hv*mJr;OvDYT$jD>yHo6KuoNag-#yo^S6c}AV?|-Kp&;9KT1Da! z{_|SQp#p8})FWlGO`PxC*LzHRB$_ooa+5Q_=o{LMGA;7ZA1zY;W&1DPbo0tFJVit_ z!t|xIux!kJGK=lW&5Vmuvfr^!sY$`E!Mz67-D#Mrg|LJJoE%l&6G*~syF(d_U`BS< zX`G&&8G~xRl2S0FOo}oYkPA!_+=5B+4-r*Ps%HH_d@Sz3X6(M8lT~$(R=rawimgr! zqN-_jBNFji@cN#M>GQpb{e0~_F}Wfd--Kd-M;zvA@cOCT9m=X7AA6Y_+r^o&%F>PC zjxVULJ1*`;A9vF!`q2Vua#d2c3(TS) z&CGUXo){~^^V1iy4X_$&)(;rk&uSbz5cofjWpBj$ZFA4-8rMP^>q|P#_rdR#?Eh#5 z>S(h}=M3DH6=xk;G^aQ_dYjtV7O?7BEUb0brt~$;-21=9YvB};2P)b}QjGj^3bin1n!XQ=0)C5!kF+5~-TIfq7 zJ~LxD=qjM?M5 zr6LRF(wn@N#v4`j(&|o59)L_NT)>B!@<;d&OnLLpABa%d#ISP#5x& zHR14_7B(%CZxAU5WjReYUf+r`(yviY1fyarfaVm3(#GVtPCVi9qon6Gqr}*qr!hp* zy1C*|JV8T-nAq*8%P6!3!4;M$#NbH@dVy{Yt`AAWbC6SIb+w;fa4pZ#Nb?I^(m(PD zFZTx^v!I_kox@KJz4_XC25n%M0%}aPv_x6!@s-K03|J#)zV5Q2-(GE?r!{{trmZ!@ zQFr238(XT)NBDfnNv^IPmMqP5@{=1IL8RmIxx(W*&*Qax6?bn?IF1U7L9;1b-12t! zue>73-Ky6~Sb@wy)-6FN$_OhwO$YTs^j|*5&xe;jF^ESt})SLu3Za^@rnaobx6?(=Jn)>jcq8{6ajreEX^?qRJJ?&)Tv(}mIdQxU`)X|1NVj^}oL z*z;V#CF05EH`Aos!JNE;JP)3S(M*x!>=jiyT2)o$)8qZjO522#2?5`AbPLnjEB!Su zD$AK_B2n&rZ2ITPg3&x#+!vqeb?NJbNd(85)E!$Oa;1Uj5Uov|k&EoTcetwO=s^{` zTI>>aCIbq3*M@LFDiJm#x*v>B31$ARo>EOaW;B_cB?oa!zLq-=R%s zBl8-P`m2md)@0P+VBX~k?pU8*#pZ#*;aK^im=p~+ zA%ReclaJ}L$Uy(lAFGN;k@jH0uhgEbraKJr`3M({yr^w{41`og6_@zthotW+BR$*$(r<%ljV8&`DR{)6-Vg zzY=^K<;N*AkX9n*t3@)fKwTEh>z$HXDkx@0@I1o7x=CwZSMB!%(BZ-H2w22cejLJ{ zcrgYfr6;P|;@oZr)sdCNAHe&ZGY9wj33nd)dZp49^8~CkDTDXem)bMjhs#{K_1gYMK@MY?T9_8;NiB(K zk*6D_G9zom>RiHimI}P<$tv`AJGl)^qxLv5?pGM>Y-) zqL>WNa_l43ZKf|M37&DF72s8EO%ypKu(90!$&J6cuSZX%CXS8RMU~iwc|z*w@!+I; zkBpX+H0d97-Dh#G|Tt|MQm38N`60Ymq(bq3Sx1qhJaQdEn2>F>75NTIB%{beH2v;MJYTL5>> zbX~1Kc{0)S_4deabg_7x&nrwwYzeqlDCvaJcrLq1XV^OVfi&@lhEuIPQCw5Tqh$?u z?3f381pzRPZr^di=}i(5DVh~A<0zZf^=6HX;#R*onlX;%ZLI7eksApBcl@pA!?`c? zp68Y`KU&KJgWWbznW(A=*g;gJ!)_g#&Y?*xAAS+-$X*cIKNt%$!Q^Xu;Po)NZ|7Wt zqk+;EoN4tw$#C+$&g|w$Bw2VDUMc8r(uv|RFb6}$y3}BenQlF^+C(XqY*DeVlWUOb zsitWlWdyFq=s$oH#%6CU4!AKH*tP2RnQ1z~396`E%yHQL;U0v_QVv)ii#mPIilc}Q z;;CwFBlIxaE1Mme1Gt;2BDxJ~h5{G)+H^B7v{~#CSVH&g^SNM$mIrOhDxXJQ?+Ar) zQ=4aBbD>E0bpWr9uMWJ-uolLuUPTfdhUQV8S03d3-=IJ1XEq9F&>pUcig}(+jWu(g z;Kk~#^fxLpnaZiS-!wtBiJEqyQ;E80BaP3$s21wRt%`_pM-^5(*Rgx^#w^M&rcQy1!NsAIu^Xdm)h|OSj+!Om)-1(@KkjlbE3uKt>$D*hT&1&dvWDN* zBe^kgk)Pxb;}jUnrbCi_@n~P;K_)%dIJch2;f@zwp3!%vAOZ5!I>!mJB+4L85^Ph) ze&#+X@&>ck1QpUonfwjU&D&B{<3V)M^w|c!H79H3w6>DZZXLYkbfdjsJTA%42ARxW zvw6~D>5$!8I2&$_H~SSlyB0B$GpW%3ZUF09YGms)X?QF$3d8iKL+%gK;oS&%Z9nN< zb_FqJ%SCp5C^G69HbIYW3rdY;#Qj)zGJA@TwdYcHa${6)5Mdr&xXshkrD;1p zu|Pn42+Ud6#Q6a+J{-0MO9<%UcK)qjp=dLNA@|A}ES2?L4QkHtR)8(2SVO4RK7)4? z{F1D3Oa1LdjHh0$W^w~(>F}!8T!5xRVo-WOdgbCf`vN;fF)_Q;>VZ zj%LfaXBD3*oEm3LvJ`6Da~3JM=wRQXfroW}JaG4|nxfxkKU;9Wq@L{4zt>2chWip9 zIu1BEiE5G{f_7kX1w$nSE>Z zvx}aC{gdo^&hI~BOw6C&rD6D%qP+pOGZOcg%tOyHO>3^Tvo)(W_j(!wpkl!K#=}w%yRvW1JIT)RR&TXg_kxVV zn)j_^6XBqdT(-OovK9Djn}HD*niZ)7FrCZ-Y-S&ctFS9g)79*#nkNyD7G za-)_^MmPF34+uE1q}pu&iw9YlcZvlKOkj5Nt})dtn^tal^|_w5rNS4^6ojThonn^X z%r!;K_lpNWtPHxDqNhd6v?8R$TSy4CWidb|uN!y`2XVeOTkvo`=P->~V(->3Ad9{= z@P-Ylc6vOWWD*503wZDzwT4Mdd`l1gbcUKhq7!`2xU`>uDF<5v1};qLS0<+&+Fu+oeSg@K7CLCjOyA(1;x3vr7$Ej7 z{|KacKSf>lACtD^*HF{nC^hOeHaN|wEJgFVh0`6bLVYojmR{Lr!yf(?7<7rZsDFPx z!_*+@#r>;9yg7HDjG~j5olo~93_)EKC;lKeuhfV+jFCZ{-cYO*321uQP~I8dRsID? z0C%yg(4r`8n8Nmf*Bh35_Yd$tgeoo~6oCp=r2q{B{XaStiaCY`AZFl~BSLYhB4pEw zo9Owp`Yk+Wwl4m+NP!H)(*l0WK!#V?{{d}4lE2jVQ_gywsTEl)F)zdiDFTC(7!Fh) zm?NkDpWeed{pTcfti-9U!neJ$m?G{unBU!$#h&1$X)K_g+r%cfy^*vYXjEnVpxz*y z{{Yh(5S%T`3#WoquKhTb)9^_%Zt|NZkZ`tek<720Cx{^*^vszVEev+Kpz8W#^`#TPc*sazfN!!7pZ?Y@o;JgM;oc z#XK%#$-apcr59*+fPgK;w)c9O?>?!CiNzJKUaOG4vv*~fxC696x%yS)~u%9pR0fF}wZGRQk^EsEXY>qnWE#%vHCVcBM&W+@*lFy9#}XeW7f=x0n(-e(>FiQE#m z{w8Pm80V-W8Y#IDKO}Q=%-?6UI72Z(G2jlL`O&zV=~AU*o0LQ-x{kilvkvi6rz^r2 zmR1tX%UH6a+Wo^e*?uRu)l;Xm2C$vsR`O0Jn5G}RvAdVRFbGRinOgSb+81$h{{YHb znP>$te1;#wBZQ;^G@O%+$V;njZpVM0(2bzFo@*@dZQ% zdk$v%ltiy03MCe*vhGg0so2UTBqrjh4R69+Ek@#gKRa0oCB!bJD;4a~!sgFqcW z^A9&DnRKY5b2TvMqxbXyMHHUpQ_Mm*SIidH-h)cPm147vr9m^R(JO6_6Ib^_sBd@> zsF+0`_GW-)GA|J|%?(h*xhaQfEV$d^8|Vzh&$yh9(mUfY9`e}}6mf(C%6Hu5Uon1@ zlzKw;dzfK7Dlmxqxr&^;YGwZVb zo5U22X-_1(oWc01+Fv(wB!SM6+7C#{{RCJmoWTe zaMURtWi#v^X4Xq#fdgXwC!oXB**iEiO~UbWIYam=2JUexoMY6^KS(Lo-PT}Hi{zHs zBdLYfCB>L~Opq7i6$jl1La^C{0f9DE9@2$dcIb(AuX+%K>)c0vlkEEo<9xLl{37Qk zJ&-^w_=26}FE7MEv8jWY)3BHXPAL0Fc1J%7JO%lbY7S@^O#<^C%tmQerTqn(+-fv8 z^|#XlAVPYCPXaXs00ovT#S#FjWwDW>_OC=W@03w-$)ynPC3_ z>486Er~G*;F9~sOc7+t`HH+m;&2dd_bt=?P8em`yyL& zH;uY#U-9;J9w!vUB?dn9*I(Rcf5fa6;S*qGuJB4;_~*R8v$QLudxtZqUIRPNnT7+} zAyqX?nRLrr&$w+m5TSibrEwl38%}4a&>!#!~PjHakI6BoT;FGrT#ta=0!qXfI281gjpSf^xfN zaMZ!MRh0{0dG{cT!?A?Y0fS0Pcb0em01=t*(SvNuRh!aHB@9E^1dFN70d*^7n>`1- z2<3IRO^`DT;%gGR@zL#-na4vfj+HH)Pl^8DxLe3YBxsw8yGKlY;Mq@7_*r-2VkA{! z=8GQ_MLiAbVRNaJT*u7k670-;FiV#=j%Ds;sINh^WyUOEd*%_1KUeQh%jz7Wp@usdeZ}u3%4V&bnQ%m4j~N00vN%U_U=erfIzlx8lLGjxy}6u^ zK@DB%Z!ON_bGdUGa{}R#)F#jRL?tN91z$4^wFIcE8Rt22GeG5;Sc%Us1ma&( zT_ssAEZZ*~PkxNCtzlOeQdmWD$M>@_hs zmYvRJTP~(qo`Xi<9_DJBx(gOuV#SLuZ>nKJ0K~XLRw(Xb*N?FXTxcoAu)giY-3fS} zd7FEl;}0Wgg|ehqZ!-hhn6zcHkWEV)YZDi8N*C_U8Tf*c%zngXVTdj}6BqhT+A0~- z0hZR@(#@*Za>J5~K})_;u}Y=AMI9lqxrWl5^+oA1)0@Ph;Vls}IngX&!OU$%1!p2# zsJ4n6O!uh8xyy0DQm{%G52zECW$MMizoyLvZ^U-qWBE|$@dk+*Jzt?rWp{oi}}xi|buEl-;s~k{CjkE;uEN!@p>$gNcl$l0TgV zFa%5@B{P;N;grp#TywKrM7=Aag7G-4yLTN&+%eF;FtK9vSiLG5`jk$zK(7GsOOHGy zm!gMaZ`3$qO2F_=Xu+8O061n4)@21#h>$H@!RU$oJ-CXQ*8*@$0BLUFCf@2S(&tw# zE^Z-QH+~?^FiZqfHHal`)DFZ76D1Ijv$F77e8o1i;mE z<{LtS)J!39;_newN}LdATq&nuW->8-<#%Os9fZ8FdI(8fuAxya)3{}+oTwsjt6hn~ zi@qa9HQq1DEm&cryv~m3S#*11t0RfX2XbM%If-7 zEqFb~nxtcdHq$Wl%0)+Pr*WuQ_+P|PJ)V)h((E~55u2d~1||+z7UJnM6P*}7SVEgS zo0d_-LLIM$`Ha`JS(+oR>4^gVCu8@PEvL@SnwB1B8=rM7-lc5r9Ij}+<(J2Kbv)u_ zY~d1%nDlvr!b+D!uyJ!IDmBgsO@WhLmzRmfmUx9qK)e$Ve8E}fR5T`2Ogl4)vSba* z%)-{;xHd)>El2nIgd)MjsS|87I|;sizKbK=6urh~{X!=rIqI4QZY8Qb z%k#`rj7)s=#X{;>ieN^gT{#|Q{{Uk6{C0_=a!G`XHbN!IUZ?DpXKPb6>yNQOGl9yL zjkScQ%M-UNid^TWvXj(A6oJuwkQq{d-!FKvi`47pp#=l!)|SjERBP=bteOdY{70Cz zC<4@}oZ;_s+_h}VfX=-};FyKatHc)XJ6{n1$jxw00$iiQor$v*k<-kn3x`u3b29X> zW)Nuw720w~g8*gU#JzsWmo-thN~#IUmLNpq0;O&9cVLIT%go1vl!x6KW{0|`aIg)< zpdrd2)dFB8q8~h0MWug8pQ@ zjD;~N#Jid&tO2wr)y6jq&6C30L}}bLPSg93eh@QyoTehTutGGb-9xl7d&6F?n_;hi zOo$<*&!pVlGcHkWqM1^?%w)p4exM0(?&@cuzlo{^P`Q`dUNt2`4lt0t@PV`5J5DF; znE?dEoT0?$J($MK#>CU9&rT<4Vo4seOU$o0ltl+!|S1yhf@v+%f@{A>xAr0M0fLk9EpYuSLY7{kV^DvJl&5qG4K1 zI;G$-+iMxzUEe7?%*@ecGRtbK%;1fO3rrAPvrITyfVDT!X=3-t?!$?TLXk1w2oz&T z%oqF>4V@}Xh_W~vS3$+b=?QK^dYmE!4=_{l{nswB6<*t%YEYTn#4;uuu91i#uAYAx zS$clC$3cc@K!$!wVjg-9I}jR1%(EI<&qEyon2Nd$z?370(HYdcv58_w#N*RlKJgs@ zrTa&-ybx(QV2g*w?dTAP@D~k>%)XgSEy|VrZu)Q?;#dfkSH5EbW48!vscqvYU0&2jl_-pzx|A2Ob$q z%ok)b*JV%qSVhZ*y!m{dLHNZpDV2>R8hxcftU@CBT}98wC*HIBw!PqdcN>cZ^o1_~_t+UWBy8 z7@V-y5ZzlVFDH$5oI&})12E~t;&IZYD==7porUf6&eMZ6!w9G_dsIoa=%%af%{AAeXCE5sZ z(W>B`OWeB#q4R}4WyNK81>#rmwo{p_YE)l#S*?*ng}H&fJLsq~k_EH7b5n6%!eHC? zmYN^58rN}i9@WoaqFBWCxo|oXz5emZ4ktAUbp||Ir>0c{ysp@~W{9fY!#KDlrSKO3 z)S1b|Vzn@{9R-wNawSdTaU0?wurXK|1-v3NjgrB{N~VZ#jY>Oe6>S!j+Zz@q9+#y1{%?VR32sz)CC~`hwP6S!IO)HCkIAxH#mmn>!jED`eF3T#BpNTWM-UA zgAcnmpj>KR62Gcn%&t%Opt*cf7&8_ma(0R;vYN7O zWOKz+C44foXv-NZ6ETxOmk}sa1)Y-Rc_P;7ra8o`4kGXdm5G@wH3HMnnWriUT!5r= z?J+fVf(kRN+;Kkdn1dr>xNRlZ=cIw(Y4=fy-7?Jh1|=Z~Zy5NAs3KBe(I^nO%+ga6 z9~Ws(6OrE8&IdB+x+KX+r)d8G28>sn6DA^)#pU8(V(L2`<^KTQE-z+bA!*a{ps#$< z@1z7`*%AsDs-6?|!Kt~d2%fqaqF~-(123k?BI3?vv?BxC5e3neDLCmbAV0w^8R%;J zgS3p54WkjN9Uc6~Z&%_CLRnFk2Y+(GQ(vjM00nT4AqVi{6K_MRzNU*s#ydO?@mjRF zDlXEG#)!2lV|NhTdtTx*TFWvsi-+$r-+Rk7D3*2Z3wkSWmTYjjhIxxCLoKsXToUXl z@dCC}i-aoD*EyOCs1?klmRt3eDmzzbH}fb2XKFmc;w=r|v}+`zzMNP=j5(GOpyCUP zYUWApF(c+RMW;0xO{v61SSuXMm6^5L|mu3iEsumPIrK@`Up{D4U(v_NR z%&6|x%vGor9P2Y8He+xPx<|ORHkw00&uKvGBs}SdGoFxpOrldhT+6${%v*1HVch=! zdeq}H2bmZ}vI^;BpAecL=w5SNLM>F}ma%0pfz2)vu~3caHXWex58;x=dK(WCz_^0I zj>*XYuX^bSHSQ@Inxb{Dxe4;8GVN8lq71{bHgP*=m`Z?x0Mz+2F0N-iYHa9h`PBXX zm6q6XaYT5?EFFkh=Zi2~+~SVGRa1zBmKG5}3f725YU;hBGi8I)ZdAc-#ux5;ilw1p zxlP&S9o)A(VqM~gnZAc|*7vCKJFP>;GW<@=njx;sf@W?3O%Z8WrIkb8=3bi!_4L=w zwRnRsXlBL2!ITnvrah`#aQI1#oYnFrg4E^;_l)?>LPWt8y~}Jt67t4bmA)-;iz?Gz zUoh3`s{}_b^pwlB2HBL(r4@1a2bg%WMHoT8Q#x-5VSam$N4ydq@TZh&zF8%T{)FJ_ zNm8WJ451!!u7R3(gu+9AFq^@zRN^c_m;oBz`fHC#jmA(rarU;n!zi3mmr~&v%9K>8 z1rp71+7)xe{4Sh*!Jnv2Gk?CfS-sXLj3$|+%TdiF$+vL+8iCV^n}jg_R0q2HOwTL? zx4WlyYM8hd{C*G*?x=0^F2{WldH4()LAOLGS-%kJg96144qeMbIgaret#Z#oP7eI> zM**0?o%p=R%Z0_}3|Tv_Aoy8w>BZoVrL>7mM@zvidvO+0k_A&{D-;tiaP?qvl*r@h@O06$WsUobt0K;F@ia_YDs4-X;R(;8QHQo05~tS=K8VGCKrvtj2zUSpbZ3(gu!0C{AhKJ8hFqSOE@r&XPy-JrGWn!$6Q!KP) zhaNk`U_!(?UqdYXE}!qxlUx~l>0X8&m`xE0q}q$-awd;m0j{QJJvfXt`oUE$HcRV{ zr_A#X6}DTTp7e=;uRIcrtFrJ%OgL08 z46=z=HpA&46i^#UOLdJU2i<@g$9AWoL>{s_*6o*T{{W_4Yity}7(x!oc*8lQ@B||$ zrz<~6kZ@>-g_=r`?=G|0K`p;1ErN+C=1>MzP^c#p2QI%6lG_Fz>ELiehX#tgEGYN*Vj)y1EKL|c0X ziM3iWGYv#dKb4!|<(?eJr! z;$aiec&2z6=^*nf6B*geVGQ%}(Cqay^)+a_!p(dmoA1H7x0%KGpCl7qi`o>dK-?G0 z5CL22V^G~N=2#wLxbZ(k-#F=Q={MI!y}2dA9Srk*u|aMABBeC*D-r0`IfwDcLqq6_ zjBXuv;x_BID;er}_LrxKjwL6$sUCs3_cof`ca6Yyu||_vH&6igPtkVO;7_ zlLOgtaA-kQ*)!bDO3!ehyLN~vC}Ka*ou^z&fZg0&d26&i%2n=Y?qwGE7-@H|(xKr$ z5Yp!ehDVgob3;>g#JH|RBHwjWLC{=rm@C~l zjH+L}vDb=N#%L{;{;>}dq24<|J*!;cQDBDUAl~JI6F=f%>6S1Hiy?uy%51kix`PhW zE1#1Q>|&eMhY@8BbpHSYr%c4RS-80(`_(AZS5Dx zMC=yK-9b-wS9^d42&Y|+B*GtKGa{a*7BaCx$L{S6PdMUi z`yya@cqK#Hg~R~nhkzXWo5?O8W)3s~#J_gpc8(`D287s_S;M;ujiRW_DqC4kh>mkG zo?ShhFqkQCQ7Q;P zcAPaa_fBf2f@d)^_Z>!yOYtcufjFMy5ov5z{?I%0M%8Ds6N}8y6TEdtJU5Ak_Zn1? z0>w3kehfA7o71$uVCe_B3`Hv0I~+^u#!&Oo0CZAnZ2km#3`pRX2cMx@Cnmo{W9BW@ z$E0|CqiYDGynG=uI6I6g&>TQ@? zyi2=Aq-v5aVVac^WJ!$Wtb`|8@rtdqQBrO>vZpoE2}y_*6CL1a8M#ohDDa`t>*!GV z`A>2R>DvNgCcc@{X=mq60E7SwX8P!akqjK!%;Y$MHW=-F=Q1-iPqAPsjmM?mY5Az? zAx#wu&MulG@S!$6#xGFr8tGm0ZOaw#M_Gpuy)GljF$bAmW!_O6qTyMD%~LCBvLdM| zgE*BP1Hm1~gQop$CiG1nE^k8$i%Ik?ya?CXvE`J@4lBH*{2o~4-bPv?3=Q~AdmQ*C zQLKl%fG*>tmRt|oWtO?;J2`Bs*KtK9Vd56FzYHkO^B`8s6b5q+1{|Cb%x2g~g;==i zV7~C*xLdIYVYmPX62sP9w2v7*5t(VFfSuXB1#=H$@J1EOga#dAvy$zVfVe*46AOP3 z?{c#a@|?&u<}H^w3AfmfLY!#SF zKo>C3<8a(M8ZR>e7ug}vC#C=)*B=pZFh-d7m)-@_E!AG*c2~G;Zfo;DE?H2_$~XL! zT{;1-p68g|ZZ;ZCdeb@`4<^$R6gmSyML99sJ3iP17u`-VP|>nw%E4BodYSIJAppDfB0T`b<~z!fg2 zMJDZc00P|7kgOobfb-yiTwl0Au^pU38H^=(fc?e*=oo%kZ4Z%liY9&Lcp_a58Nv;! z;yI3Bu2&YGTZbHfYaF-av=5G8mv8--K z{>J$)@Q&NI2>$>R3C3|6cctFuN7)Nuh0SZ)c*v2aD#koUs547TKLuq#GHOtgl5OS@ zxf;5LOT1u8CJ*tR%rrda1EjE1vTY?L5{mFew9CZwSJ1j|9S${SX)JG;UHgDAO|F&+ zg1!AS_z;*tZ`1G~kt(3qnU$%;S+H{qraGC^1?h>~+$Q;SF_CTztX|^3f*w$ZE|=!? z;KxO)nZ(jdqJ0yRHopm{r%eU%HrufsoI$>W4986x=;I6bOg(Vp<%F}POc$(wexnCQ zQ=MiBLwElGgq7kR-U+F-Kue4RyAUyChXm8bOePf%;i54vKhl~C)svA&5RvUB?`RQV z7AxB=$YJmyH4F_~EE4pw^)!&LG0xJlfiE-eS&F=pD^GZ6gaB%m_RE$;Gata1aD2mW zvr>p=V`D|0rpMH({?V*(1&Zk0USl}tt4OC)9 z4gE^g=Gju2l}dw@=l=kNsb;dotLl|0hzsKdrbiA^;H7*KZNoDi8KrWv#1F)FUpP>k zt_o%yq0`<_P<gTLAwNE6(qC(=N4q~F6A4=$2i7Lj zQlQr0f37|ladBF^5P)tDZ2gEuJBDqBrul?r?}o{*_+ZAJ#c*f(LlkaoB28PzPSZH2 zXo6C+f527d#IxTWdMDh)X}v*wEB^38`9{irIvm?ZqSAf^N>jgRr3K-Cf-doUn~Ke) zv9|;%EHmi6unCo)khJwIbBmKF-4XrrtP+y~V+A z)XT>xQX(20wr(OS@`v=wM%mgGzUrnMqNc;nU-7zX?DUaAeS^)Tfu?WMVts*;S!3EYR-s_0OUfP-s48D+r?5 zk%3Ikg_(f0nYhTe%xZHpHdGYE9Tetg zw4Ix@i=;qp8q1c%Y%5w#O%9)_`Xg-dDIKHndMa>0+&G}iV`HQ5%p(ljDjp&IWtJs+ zb3YHJoE6aAd4unC*)r+t+#ImKY{cGvG`iakxFXch-4G2Yn zRj5qKvALcsm(MdQ5|;M;8u`t^bn!Xq8iH@(2to^l8qmUW=u)REGYCZAcsGvtfu`op zn#bkz+tujeZ@z$ys$`9P#C?hTpyHPh0~jS_-u62g%s_E_f%Xv9%>22;Y?89fS=xSN z{gX59U_Lr*bf1NE1)nS-1XN#Q<|a6b=kc=zlrJCKLH_`bLKTcX!d?u}eYoNW7R>(u z%%VD{dSsg9a_=2F*MS?Q)e_^kw9I0rHnH8~Ay^6GHcFLJf#BDfkQgWDqJ^pjLs^3Z z4$Tpa?#e+cQw8r2FGLr&4LFQhSm9M1605Lal3^LzyG<%o1843ME!32`-5F4G574t8 z3d>(<~aKs(xlXh8f|QdRgPN zv}00=x?=f=jrmAu^O;`VQ5q8QN@+q0RW7eYHW$E@ii&1Kn6uD=`Ni4HsXd{lr81%phV**qHDKriomlz-n&_saypRcFk%`Y7@f%b=VaIe3h)-XYaY@P`D<{{0@%j}6;;$@Wl$WR%~`=tC1 zf-5h#ZjBIxG)(tALxV^`&$Lp%391@@*kou4+Lr^t9pX`#;of-X+fmAA-9VWC0BDq% zt@whl0-EXE9KIti!M^gNR^`rW^7)E)0{4N0u=kXY`^>0TT}m}mbqOCDxfD#~TiS62 z2QFA;Lx}SpUqyV7(j346*(ld2+2U1vIhFqa$y~$8MrmzKtm`NjM%Z%2fzBeR-e{ID zfi9nVlxT@i^Ck?M`MsV-N>=Ui`9#s}0w97MKgzHkpI9Ed;jElvkH{ z2S|4iy;0gfcR3}=S!nSH8)P!ApAj-9&6Nq@176;lDqU_}%@W(9e2gDF5oF5*z!qPL zgN*IeDuy7Z(@%-b8m|T;8 zsZsC}hnalmoY0lf)j{l9i9+S*hax;OX~RY1`vmSjZ)mx!E3pyrvb##QaMZX}j31b# zX?@CN(S{4AD}_$dDuR{KsOGrC%Qg~Rww=sC=316TRH`f5Io!26;!DVJrdmu*nkGdrwX6UI9^i2F=F!sZx26hnW zXHnC%V`OE50Tk57H2qPTcpy|XPuDn`dQANgn-RJb^~Xo3?(Xo?ZxNT7X?`ZZa2nYF zJ>V?TSEl%n#5zc{^pwP$%$|s*GY^PCj-5jw0had&Hls)N*Y=_ftKQVZmZjEkTyE4- zpZXHH2y^Byigl;~%qtz`;$|8lGHJ0p#WFQ@7IJl{Rj3(A*I(>oH!8vivgt&7pRzcc z@W!H1FHvTkB}Ab#TWyTsX}4)!Tm)!~mhU$mMFyt-0GmCgvoK~VS~AMId6ur^@bZo) z3gN-HE6u(j${Ssh;yc8;*RnF(R$25;nGWfh?2JER zS?0A)!&b*5$KeDft(5aEY*Pn$OJL0ny>1CdLXiVvpRu^W64V-v?)|}FlnzNmt8S}s zNv@1RW<6fzo-qnsz1brV3Obn|OYx14+y_&+E>RN5Eh-3GNqGfyGWgDC(JJ%A0 zg@I5S0qP(DOv*DNsfxKmoxg)A;$|Tp1{!J1ZJU^_e^?o4i*tt=-EGW^=ZR(EZFY}a zUTYHWN`L#2YC*K3g_5juLu{a-qFZVj;#4sVN=S1a4he(TmH3x;%nW>UElAbU4u&cX z#dhuu`ZFu1K^^OYoW)gJcO8dXViA^FikPriY33@Gw=;?CNdEvWR7GG-JkH~CmdUPV zUVP)sQHsaygK2BWm`aT87;+p#i!?=Y+*V(<7}Eq5g;4q?m&~*b!OUaS6jW5>@rSxY zxiD^7L~{v>R-iydz}%~={{R`D>@^2~5R%DtGi$XT@|;98RAihcT;AC4QHhOu&8#9-sXv)L-TqP7F|RHW5-tC5{O=_F$;)I162&J<~EG+27_~NLATam zXXH&C7vuC1$gO)sUei~uhqR;ST#Hy@p#oHM%vPr`iiC4$@=VRgq4a;POYKmY;IEn3 zQ!1a@H6l0O5EXkSCdmF1YQ4(=>7ofa3B34%hcg1gu;LBn_eMLBPH{IWDyN`k&Q zf#A&I=0SGAv1g`ezV^d0NQU_D8eSE(C65ax*~qBediz-QE`8wz;LY8(XZCpgR+uY+?(CaCByio@i&CW5oy3dh~RrFHF8Y0OVYGfk#X5m}QIEKqw}OONM5r znP833pO+3^x8U@qV&z#a_aW)2qMnXbn{{Ls=2=iv0!2R~Dm zewa*A23%*3$_op`pdcnz;Z4Ka5}CSQo%&x z7G5Q6e$yhf5`x=N1sUWfFG7h{hXlw|6_#ht=W}iMwo{^7JaHNo5XqUd(YW7pw7b4l zEUanCWkKo66^7N03;;abNN77$H-6B}FDTSTE_vNc6>vu3E-jYGbcwuWFE1D)zkP+$ z>P^m&RxB9K%3MlecI^`G%cImSUog#?hcGQ3K8WeOFiRFJB31V?mx`$c{G!Q_c9h$4 zkiOt={{XR>>lUP;>bRE@4nY?Z-DZYk%|t*OmEkV8KRE@jY(ZqqOGntn14dcIYrXDf z;D!>-tE?jehYlRTh6zC%gVC);x~M0GkiqnxNh2p@KVzrh!eb|-1*o{&&}?-(5$^!= z7%wGE;g+RVaX&k*I(Rl{=tmWmD~oO0eN(a^#fx0Rt4&PCIsQyXDf*dM-H$iZJ z1Sja}U*w#1S2cTwE{CG)*B-5WCI;W)D4gJO^!@eB8aH*Td$;3bNcVu;Ar>(sgCxs`FwKi;H39l3VEmLxX>5W!F#|_iivAViUF`V!Y-Ip6s}1a55OK+{E9jZ!xNi zd$7R;p4^jtlAwgh3#jh$>54V<*E4bemMqgAFkC*eR{GQ~UGS$c&1 zGO2TQHTC+v&7e)DC*wt20p1{87acc?DjmB_eN?aP*FD4V34*!p8WYx{G=A*N7iTo_ z8y5GV+;G)4RZ5%4?8N^72(~Ch`!a#AX=s1~_k`g~SQ3!z&FUJKHwV|2Y1}flW&=hg z6m2=%;(=L_%#cr@B!2o`wN7KNFaDQSW)5Fx2yd^wcLv-eMO3_QsLBgC|FIj^5@H zIeJ#CTzG^r4GlmpD#cV?cD-5S&T0h2X}V77G; zXnJ8yHuhXFUJlJm>cd|%y-R!|v2M;260jh6s4ERP@f(2-E|h!@XPS0iNF2=PAux*E ztRZjNvob7OEX6_%!!nyIyBt6qAzK5zRk5gTxx@xx6HCMuLZCgV%5oZq{{Y&=MFGws zqW0z{H#SQIFmo&&y!=7z%2BwD3+KA2e%wQsl|O!k#k|fZC9w9f0bi(bV1^F8O2n%Tj!nfWk*A+<${Dg^ z01|G75k!vmO5`^8m6*-qS;G~1xP^@KnS{wZkruZLgew~{9arjdjQM4O)ILz}5CbGz zZ2L^g@`mbDfOf_uRni20QEGfl$qioVhU(8ZHpgeU!8b%6Ex3~HToJ;d zSmhM9Hz!nfwKA5MQ+$QJ$OGZIO?EL*8V9KCd4=Gm94dOd>97a^rY;s3w~)~0X1K68 zMFb%YmzV*WiN{1`(?5iE_cY2YMBAQ#%wA(<%Dbkq)Eg=ZRJPfylXKh?$4Z2qz0F>w zsxB*cL@kDiXVo}uQ#g+?S#$BGdrr|XULw>r^#zK72zCC+LFs3ppnl-b%o)4?0Bzzm zh9BFe#Uj_6%ob62GYbac+6LecWV7%mQFNrd?E%=$1@0&n3(RI)nG7>xq4$PPD#gIK z?z~3W+^%GN?@c_xhE!H_4O(}&8&pfex=|B$&_enI0*cZ>$BAqMGQfA7e&8xx*$m6e zEm|gZ+Y?|>cN~{FCTE?>=tNrt+lk|1dYdqF98(R-r0r|728hQFV0a0116hZ+Q%U9| zuqCeHryI<|#|%n5GXk36nPDJg4}l7YgicA9Pjga|%fj<4Sjgd*b`5bhaRgEzi!3+rtk88)WVKVJJz|DxXiR%SV(bI;0R5n5Q!VxAr8dEq^ zkXs#G^k(I9-N$jnAB5i=&0eL!sFhzsN2so+a3?F`U2MZB?}~xCM^6&*EMV2MiMch` zY&=G?#C0AfXd% zal|(aofA_ShZfOLTy-i;A8_L@%v7O2G8>D0y^r4MVjUhdR@PTkS-UP+a3C*qsCwb z-}jKjOl1$J^)#PyCO;&po!v-ctEOz`Ak+*~Qj+51a}wE;7X_4Sw0M|HzXlbqid~Y? zlcBUMV;n6Cn6}>}H12361!UQ-W@QJ6Q#IVVoKY=F<#SGIDpM^l1SLu(F%eFU0$iSR z1W$QFz6+Uh<62@}$F~sJJj5E^K#-eUMyFxTLu~zJN=%R-6{MC9vLUh?aV@Ha3@$A0 zmKD!PobqN9!xK=~ne_;@F#;uX1&0@-_#93(X zhI0UPb2R9KZVdE8`U#(?f+mOeF~h?SkMMq;(ZZ61TT`M&`65RXHemngF@F+r$Z;7_~68_{DPcTq;{_I_lvQ;Ca^%wjv_?f|c%7q7n6^;jKPIcBWN~$Yr z#ruv^u!D$>j`=W;J z6Es+72^&l_{1$jfnoc0$3sCP1wQdAe#mYX(MK;mJMbIueiG_U3;XUGLiM;IeBzu_( zzjDZncXP-OO6Jrt^p%(y}BnkmdN!=gavx^cer~%6i?d%3xh}BLNDDpVad_k+G`2NOb22YC~0`6 zTlX+hgGcuzh|Cp5*#^(xL8fK!bOuPM8OyYi{{X(?4P^HX0RI4Kkb~id0O;YCCJV(w zyl%oXDV)Qx0-_G&5YT(k1y8veQhfHI5opS4*_YrLF$0Hdlta~fq(xPS4k6$cj_9z% zwo0O%p_-tqMzt&&+`EBuEIgq^9!@$m)E^@c;#IKskzZ0M4aBdX66E?{L)B zjg^bQgj-&L2RFp0XjCSrmR`0A*6WW%!sZF@qyGH{dI-OS-}aUkT)U<=UG4e+rM9ey z%VfU3B3u_}PvEhZ(Dx&h1@1ssFf|=}m9z6O5gF|)8KkLpSJ{D$1Ve)7-GMIu0FT-e zI1%0$dx#z)dMVV|@0+PE7fA}cGxVt~sg;Z%tZZNQ^)lO0#W3 zu!7AHzV~X}tO3CV!i;RIRums6YdrG|1 zTrDY7WSZugeX3)Qs~SFHA-nz-tGq|hY>AlcnIGZYh~AF-CK`prF>0&Lq5D8jgrYbw zx=h5{g5y`Q5#WeqgpOy#R2k*@*_0IAYUCgQd)%}c#b}b+&gMHAiyvx~zTugZ9otNB zx2wwL3@Sbniok{VW0z2TqUG&p($onja@@8~o*?wFOb}RW!UXA8lCvp7C8vsUEYG+?LpbP~k+Ob>L5v{paW3-CaKahf&oVkp!^}gi zA}vqDgxL&!eADhFZe~|rJjHi3Kx(XkoCBq0g2z^rFaiv~>4Bh}y#-JlUAH!hLvVK| zkYO0yHMm32!3hk(-7N%%VX#18&=43TNO0F6gANcpSO^j{K+pgYa_4>D^PTUUd+w>a z|6kSBHPyZLT2FWH-Zj1VTF-+Leru_u^1+I(@roT_AuvCeGp5|T4gGTi2>Vu0%@x$DIFq%lsyxK`eZC?=%t$P`@JJUm zz8L3M9pMnjI5k#X+H!&5Iv5NbDbc-M@qhn(CFw9pZvrLhiCE7$Lw$8luh_XYEDLjD z?`2l0dfTeDc`et=TJ-QS5?fId>!;9)LRBMOUZ%4!>Ke-hU9n^)0$);-n=~8nl5k{zRq5VnV$>hHL64Pj>quv$?cKK9Uqve@ zT7s&M;#;m$hUWQL#bhIEYV0h#mdIeSq7*b&B9~uWhRUPcFQ;y8h+PqI}QmE34V|ui0 zeR@v$fZE^gch$CJ^fAnkiR<8<$mrF}Q#)!bRtkd7bCLCP1+`p@z=c<5aXE_hzKV#g ztTZZv)JyER8ZLl(Xeuqyw&&WZVN&KA=g;6y%sOFA_>@-=E%aKRlmcKaL!FW&tkP#% zP^r!`!bk>f`hd#A>&OQ!WJ6t#*vf(>?Isz#+;Jp@yMgI%LKDxjQs15D-D5DmZoYO+8*vI7toi>)p$>X|7`t9((--9 zg#6Hq@#H&ke`6`G1)U*i2(5+6IIoXfMaC(`oM@T=;5`T}UG*$6nj!zwjqndbHF8^E ztSWkDI$%if`wi`~kQMhSpqqYPI&bKim!lwgs@Nn$-vXRJHj^audjiJ5_P!ls8%3%e z7k`KbqjRp4a$6ko)$eqm(A@dG7KTP9&zS=EY>K#KB7r{Z{&C#zi^=6TA=T~0pXe_= zs#ud+B#oVBTGH66%;7)T^^HSED7szrS@>?f?47aMwuj5ZdCqz@7Nu+{9$Ry@yhXZp zBq*JsuxURDct;B+low}rmgSLQY=bF7Bk#z7MW25tf4&kq5%*aSR~cmSka$apEGFeF zm_||fVLeURs?^_m!Nc5oA`Hx-{FTQfiY!~j)*5OZZf*a3_kMJt;132c=2?fxduAxt zPfq7w^TtY-bB|8m#Lt7p)xy;eS*nG5T8SA9B*$^X-gdt6dG?s<72Q55i&zhfmyNdD z?#DaA&W6wAlQ!EVes}p8&!1cYWy~gA!NrAU0hJfL-cz$U6~e8{%-euWbCZz@7|=(2aN7W^n6(4=MC&U%>dhsy6Ecub`$T>Qymha>8(h)HD7cnncJNh z?ToQZzo?YuS^A~2hWown>!1Mzv#Qk#o?UeE&d6J6kmDH}J^bssN1m(eP;xd4Y@+@N$iS-!+3x?;KzYe(#UO z5=G}e?`sW56yy!Yr2c^NvQ^85#{z)6^&gZ}Opkux7-a)LCImmBIP?#57eX^U zBpi$o-BP)!oA0>1F`N(uwo_3R#bz}go33JD#oiOyLQ!Rdh4=}ay^52aaSNrfw{sVh z=)!6$-09obsb4FcqUsIc0q5e5H<4T7s&XjbR}y466D6z~w-m|B4Wp?E4jR8T_04h< z>>e)2<{h%)fqynt$~_8UK8sv9pw1Bl$~I(0o=6{l!@wi^gOT_it*AzfjV2Gmz(#A< zkzan0yCj>?eJ%IbkN>M}$E+mlSraKNnCr>^jfWjchH{!vh8f_Z%|7sr&;Kz76el=g z|GpEvY{wJ%q#Uo0N@HE@|Hz5a1__cjO?vjQpDJwZRL!`2{!JRIB+38pYnk?ZjQU;L z`%|uiyXU#)qoca~qT=Y%&UbjoB6xqQ$H|>US zc;M1@XZC-F8@$^$N3iZ*ga#`)a4SjDWoAWK45j~v{~A)PCS39)uJjitsm@qmPd*;4 zUR{Ez8?wg({_{>|Ip^1WZPID({GQ(ww&EE2>2t7{O3=vP1`~10^<6UBF_z!4I%(&A zG{HNulVe*bLVQZP{{`TDbHbcAHe9eT#1l@$_gdMc(<$spR(`O;-x#WJL~4%q4o^yl zv)9xzs|VxeZD2XSWhgxbdj12zlx25Cgsn^DyLjKiA&| z9ob9c?tNNE-LIwgshfJnvE*Fp(%V(vdiDM55y-SHJM8`ZSR?zkRLWI3i_i8I>$x>u zN*GwrG85SUbbr`v+a8&Jo6Kolgt?f$*c|(;o~(GH*>cJI<3JxYYP&uA1)% z@fI%k-yx=fM*<1S#fT%%nktdR+k;QujW=(-jZBW*7QgiTjp0GQDn$PO6!#q0XHzw^EF+CLC%=90um zpX6n@R=15)G{bioA3HHB#o2CL{~e$R0pspE;H-FC8TQF}!**wTACW#0;>*1hNX_;S z0`8A27t${C3YlGX5JY9!V7oI!vc4T&YWx%Jf10Y5BXiBIi5}E7e%OX4EXbf3fHK`x8&4Qm5_`C&7%!?F!+H;04)pp0_0Xv@KC$Ax3Y+%(>Lh+ zqSW#1UV^OJYBn^L+EnG+zbr04@V()AFAi6q?5eI0&(L0sh1_Wso_(O*bhCZ&umwU30wgD3xN_@#QP=5RDBb>qn>a2K_$xZ0@?{(;q83-nCLHze{JXAJYEirn0GdhUa0`t)rX~BZwg*#N4@#$?1cEUnc0!g zhU%1hQw%mX#8uK-mtQjUL|FhlygmOk|7$_sfDucH5R=TVn{R&u z_`n>x)v&b%aL>lLu8c9s(#k&n_6I}MLbB)XpI7O>c;VwKW#;TYCX^Rxmqf1LTmP3+ za(9*V%j|Mc^R(~*jQ0Js_sx+C5&s1EuX|SOC=jN>vYcLc;XtqRU$FkmHY&iCm+7xU z`VBfBs)J(o-}nEoXaD0jC?KkN%d8L?AWH9|q`- zCoNiZ{$bY?-1pz2|H}i~KzOI2xb>`2OW}Vpkn=AT#9c9^`*)N78HoATc0T@pH#j#G zmc03&t^N;=oPX%~-{Aev<7nYrPP91iKMarmDG!WEPQfmusAM3_VP|OX^S3}QngQ}L z`2-5o`YS#M82<-@LrwIm=?_Ly&wI{QkU@)~CL+({{gx{=SnIU}?4o}W)_1EDgGk^&58T(A4PS9z&0W_i&y{?w)UcuzL|MY0&;Vr; z_<_cWCAaQItODfIO-J;l@8%L870li0;KCLXXH(_meMMChmFp_$1OZi|Bao3Cxuf-VC-` zJV4QwQ=7Oa#E;(kh@c3J_`Y>$FMn!|<5?c0%~SI*awMu_uuYX0JWpzjn~e-;Q3j7R zy1e`Hiw!Xx=i*{$MV)8Pa*w82FK_ewMB*J~ zUH+6FwV_(z?E?$bSHUfxIEbiVd<}^2U=o;%3j!v-@m%S$4?fbyzVZX~sG^(*Hq{uk z4thBpPc3dmY=h+r2m{QN98|OB)1n{_5p5RXDOO&rKa#0Rx?|mVN`qq@;S%PZNBp~U z&jXC6zw!x~$q%;F*Qz@_}r%3duIu=Ztg6rr2BNJ_;lv)YzgZOC%eQ?yIh4Va0~hv>}O2S zF_bTvgW$wgg3)$u^3356wo4qw!W!Q#)W?1AfRyYWpqmdSfI^8fy2H^^Qe>T{^P4Ke zgYsyn_I8O90zo~A#46;&M1=8#)SxW>Z|aE+$naO`_R7O0{yA7G>V|5hY@GBZ8X0@U zR@L-v%Wfkrap9R+;dElc#1Cwc;MQ=6CY#Ee>c% zDcl<}jC8St0o>>lIEKiP!jO_vaYqyW_}Dn98$lr}{BDmHH-kL}6@x7(gq0wC3Qb8v zh967ehsI5-@W5leSMnq$mB^yA(zzFp(Gl8ouF=o{p-)VV4M<}m%hOR)YeEgEQI|a7 z<7b37d)V;2dKI^;&1~%>?>AGLFa$Q?u{HvfJaVwi&*6rboUHLPlGO<<5*lYosZdM# znn?N%d1a{4NLZTy!6-psxK3KPS~B$piB6HR_GfJv@2&wNnKeF#NIm{J-n+<{5;_3} zOC4j@hODk@!to;*Z#FGzJlMRVT)A3YIXvcRP>JqG#@ONDLsC*k=9%p0KtQPxYWO)1 zqZ<|J+#AlUEMy-)-sef`zK`fPj{k28-+wrK(E~V|!}lKw-@h1q(FDHaiUVl&ULk{X zJ0JFcbNG^@|J7--zC-85B$S4uSR;SsVJ$p>5F%zUf5PMCCf?Df24;;vA8Q1E?;tzm z$#@<=tq`{T!0t!n?R{JyluI+1aJQXV$5)lgiviN~bCQ&0|E{RW;GXj9C@iv)iRjGg zz_B4RNJMbtw$cPN_Qsw-h@TK{nHUWfAi5$m2YWAy#ozqFIFEWq2AZI`L9oOv0M6FQ z5C-l>N7;;c7HX@KdzdTqre+L~+F>u}wT?EvJzKCx15dWhV?bLv21o_F|KlDJPZ;t^ z2N3GnCKA40;dGHiBe-XPMYnb;H8U;2crmb#1%Qr&vE}Ngf!+i0XqD4LlzmWznhc{STX+5O$jvpSINXLof%RWg1eg>-CfqWZZuo)WMLF%~=I!%L9FV5G=? zXnHEH!Bgbty3Y~Se!rU~#7df#KRCjXa%>|HNv!S{@Hx}!>EDZ)p8Gg3S9ji}QdB6_ z!(j46-uW>vr5bKKUaclXY&%0AFVeB+b(vkVisfo?+wE1qH|*l6Qsr-gjC{R?eQ~EJ zSZ0-e`#o+-TRS4jRV{$xiy{wbO$hgiA`T z?;w?Uv#?`VNXoUtC{7%Qy|9RH^iE4%Al>5M$Sa6B`AIyu6H>l)D7`3~t&}*4vT*hs z1z~4ej==pT^avH^(jOrK&>uAB=#k z4*XMKY5m-kGx;(Xc5|g#TILw0KLIgEr4{0yvIB%a(@YtdvY;eUBO9|!%COCe7*|aR zYAqms8~~u@A52;WbG{$k&$(P*81=@XR|I437_4pMcw05j)%RrU;-J)&X=odu{2r4SUwx*rAC0qZscvB-e$V2lTURPbIb%BnjQaf)xbq2(tD~G9F8G;E?Y|<3K}(aLqBvJb{%VMc zokYB1_1H4JjgzUF7jx-*L}}HkyT5RK+7%?F<@iC zj*F0vGSovem4%ky7?!&hkiXZ7Gu7^YJS}hN{^(fkDS^r!bHiSq2hCX-KzmGZ7D63A zr)eQu@&_XmO1-1A$JOSmdk^{b#qx2-?KQ6Vwp$JQJDXU0!d~}hC%-X0Wc8K(-L#&0{`4vDEBDJ0UM(+$bA)cqyeTMXw5KA=B;8TcKL%yu z-KOs#o^CncShA;P0eM~`SBgi|CH;*}q8Ru=kKybJTH}7rLe5TNHDka%$AQFW)4avj z4cV%k#qos=%(ePYtDG7bSlI^*=J4#?Ddk3vPyq8`yY3DguR@eS1M>~PJ@E~H(oNEx zGAVnjMgJb_aEeAPRY=LqjU^No9?1Zy3VmP(xbw0UkQsE!AjE6%&#__y1v$8oA?#_a z^Pj)slU&xKwhCvX82lLB(RGGm#}03b*u)mNSidEBH(P>r<10dR!~w|4|3LmQ%Rttk zU_pAg6VHTGH+S~wwv3MpM769KrC>DpB~A)dR>ff9J5R16VYiUsJPP^&Aw!ZsnmLOx-;dEuto(81+P)Q#&yYAT}I{XP)@)2qu6&>g!B)uI-Ib({0U*U={ouD{sUBM=_20cYO;^5$IW$_470d!Cn~dcL;Dp#dxA zWZ-C%5sRRXbu>j6wT>`LTa(QvjIY{^Ej+akbSsuQYf7o~ViEFazL~(P#i1>ClS5il8|VmGgfPaG7y&2pzvN(o zzUM~U+nRT3y&Hap4G>jT6`$80H7pG@ez4YU)c7pV>61nd&#VthAm4kEb~0mDwS1jj zN^a0IS0sihMV*)J`zX*M3^e3>ic!FRjrVZLaTdxg6ECu|?m0V4AwfOnWwx8Dye!-4 z#?t?iA*hJ}X5NP~EJAX3YYDK-;C|xwvK^l#@^U<)@#5yOs|wH&ahTjR)JPf&YelI z(+JgI>@X-jGOD?9vc}x|(8yd~eTko-Tig(M8S^H=LNW}KED$<>C;A3rOtp(7vgIsK zQ#xa4%*pTwDI(`|!OSgf?O%PcAh3o)QVbvPD6Vy!o2hbsw0(6Ki<8}P{%!=kH@#d? z+@9MUvNaiCWV>7DA^KGBTu0^TKs7FZdL^B@@%6^`mE)ZUgerv;%}p3*En&GSo3pKO9MzZ~x{_cq{3GCR`m z(Y4xlsbU&d9blOxrWrEmC&S_>R<4d8JrSxIIueYkN)+@Rib!2W8THS6q{7r!6FyF& z(D1_PS}o+C0wq=|S2qV6gvQ~(hqv?6pNnI_g#)RH1eZ8TK7KHYarnr4WMFg;nZqWu z%px2pjq&0Ts|km3>(W<#`7G0^NCOGi5fc_xQ|lnwr|9N+Wvz|7gtPkDyu`}dV}nD$ zVHUZv(2ZF=ryf2WAMkstzF}aE^~c=)Ir&&&jwu1Hw`{KdkZ*6hXRMB5YcW^y`9?G> z0zlsdqxzui9;!SVBl?II$|B4k?Z1x#)dQ_H@T|$*`WJVS-n$gNikQXa6{=e2w0GXK z#5YuqF71$PND$a2Xct71M9tQf7E35_ikr-HG!Xv3&UWP|&?9C(y9sKsFG+>i2GxiGp+b6N+%fne;DaeuaQIJ?4iCOU_A!3A|C@ zodTXXoR9MJs*|!@^lix2Y%9ks0}a50{~=$xnaF`98Rg*!^RUz2YmK&DA7B1VoUTsr zF&E{h2?QAirga@47F)LjaCB%Pjt5?@m|S42l7#V*yY*6cP4EURrcN?;(Z1+VTZ$bk#&3_hm7mbp$HQp6nFO1qAF(~T`zyUtn52}o=DP)3WG&mE}= z3ynAO8CdTpuO+oxekw#wqEc6Zcq7uHDzpru$WYO@qje{G;lLp1A2IAIL$Iz(WOcwH zgHd^)YOj<~dJ=^cGJW-YWUH;hNcOdMZaKeGwlbq*ER4(klk22u$yqN-xhd7weApCs z#15xqs&Sj`Emh9q%$^l>9}jMWRBjDdJmg5cCQE5>62cjMO+J|X75i3=E{2K5?vry; z{6MJAZuNGWVv8>x$Q(^$IFqdM{T+^%xB(VYOMi^3EHY5TmCc9N7)QIKMHg&ac|_NR z>C2BHGa{tmE$minH(Md5j-Y!zjX}VOJ7h5qOW1e>^;UBCE31yLdOmL&)1yq!Pu)(F z?Xd7^_*^!o@)|}Vvi&1|{Oh)5-X)WTsHi84>Q1c4Ky>dww{$KyZKLbUoasJ9e>26* zAB-=93fl*TS=ZuYRy|d`@asTEhFHnUh@j;!$$E#@Hy}nUR>!yuLOSw}DJRo;j5b>n z`YM)J?B!7EIGJ35BW|X83PkLN>6i|_88f4ox$SJA8KFHfKZPk#ZdEVxqd%?&pdeS$ zA6+z4;yYtm5E=0O`J>oQZGGXQ9ljpy+}A;0CROQ_eof#7u$FjvZh7it^B!=Pk7J9( zez|65D<-A4GodT?-8R8wk7(xLA2&zSQK`y}FOTAwwwKJ3IBKct4%9zy=)5dVjuu(d zF{E^g?$i>(E#5FRt3^$uCCHNZN+-m8d{;WC_0 z*PMYn@Iir?h3|}E@4__PCKj~`HLs31;*2&SFhgCjKwq~0_HUv(6$E3(CCx~+n1wZh zM4p^Bdp|b>n)P8-qk)SL))p-!(g|&fh;~wbDs-2;i2`@;7!r?l}*T48W+x0TsI#v7EoLQ3S>b zJ-g24OmuL?Kom#e%@(2tTuyH*ZD?6{U8o<)Mq`xkFA?z$RjH75iQ!$c*a}!0`%fh~ zBn@C222GRA*g9tJ5)It|Q*kF54jQaA7rsF~*Xs{#A^5?m<496onz-1bO(7kzHR6mU zR&L#kBj-`ZTzG<`@Nqy49H7>JpXeULi6_K_Gl@t!-NSjZ*hgSdHjH@v(k1x(U$GCnPp#whU&OzFQO(l0H za?nVx54VusQo?8lcWAA56)FuJsN;zzf|9EOgF5dV%4E4;I!<)tr^wzl)k&IKeg>7B z`c^ZRUZg5#^z}pvf01g-QW#rwq#VL6Rn?qF?Ew~ZbwOD)O$gzrpQ97VruuqE!?<)48y91X|+4oR;|!;`4elxk9b-n(XlFi7QwDx>kAO_?DTn1#?hn zl`|Sc_(ZS8bc`Xo?}cMs#b-1Nu4#6n!b@o*rtWz1y{9)QQR6ffo5`|0NBK=PkXzI| zwMllcsK|FA6Ir6%S89Iz$OlEfz*Ou*9BSC7+w>U`s1t*Vh7X1NA=1pMz5}4OD#m6h z_p}U$3-w#1(zJn4Shr}LB9}IM0=F%HlE8gcNKv_sd`|36)E8SZTi0G_#3Ti!)?BHm z*4iq}ygo<4R)(orfQ3wXBnB1MJWT2u!HuTZ=2D3#!_TVC}mj@b%!xT z1$b59$#BJxpQV^^7slA<*2JdXL1&D<`2#$v0dOgNhYIm(-j#WRJh3;IGglVM8B`7O zBE#>Z>GjGnf6#=)T{}gprT+%X7CD}BKoi5y;HMB>gNuxQxC`$KG?y%{+aGU z@S>tt`6OX?)fy=DQGUT?oEtU<5_60>Z(-fZveDfNCVsuSW|kB}@NP4|gne^2?KZXT zT2R~;BhAUJ>?syNFLhICj)P%mTUdkjoNEFB*o298CE&DFUkWzaZXe`vbr@!l9SvM8q&`;DWSF)LLDT``q~Z)JNlA9{#QZE)-h*`g zqLr<<{KV?j`hlS0(lSD`@^Vroqm+I*q}Z_}$y~PmIE4l|-SG^IMmLo6OxpXC#tDd=%FO>|$ z&>u19e#RKJJn%BQR1;&*E-xn4n&Y`>tgtWMjJ3L|m>B#-8wm_b9+lRt+vL>da;|W21rmeypM)$%)*nZOpr~z<)dQVqQdN?SbA~n z!GUYude3P?mi4A*fqXD&CQXmbclKOu-EOupFk5JC)B8&U8Xxu|*$UE!KKA60m)4-N zeqS04{-n7S?y5EH1+dfDVECv-I$!(t1K1r0YMQO`XlrQ65;dmC$e);x(h$PWpBGTd zfYD+dSwgb*>_w0&AV>SmI?^`ki39jgU1~4f`7nrZxNd}mMa((HI@o2KlA_W-0c2^~ zHu*G{1uHu=u>mNdPH*s}Qc^m;1oDB7Fo*w;7XBU|#~ZqnIu+T47=zs`!RhgsjHBXRfgVuIb8#DuWVp%zB_2ysKN z5lmPUwxEGad9UJ#q%;m@QRkRSubf{fe7OpFr&x9!mv)<_xzZU)M{t-sYG$I7B5kEG z1Aw0clCksr6vS}@F)LN=u}F&7@tP)N*=?^eeM73E%5!`h6Ykb99o}^2l#5|nYwy+A zrAQs_g3{uxl6;ft?WyS+mOC{!+3zZtitJiJt*;eDD&M&wz2WdUkAjhNsYw248 zx?1R27+M(NQy+T^uBUXBs-4L7S&Hhxxm41*0R_F7@dsaqLbqV)hr4AtAm+TucIIN& z1VEFx`VRL2DbMJR6y@%-D`$@n0;f|g?XJQ|@%%k?LsN_IYE0v?TurXyeiyxpuO zzDFvYE3A78jnDLvR8dqNTPwqz>bLgp_#|z8xs4E6cltC;G(O-d!~DT*NAB$-&Fqc_7Csv|%; zf5v|dT}pWycusD-qC(-oZRHcKP$#YKN^t1>D$5}cP+-ai9Riz*5;Fin1GWJ+$~bl_ zfGdUw?l$!XH#_tE@5z`QWwL8@i#kl@Z&-hXz(Yyooiwj&e=40yN4Pjv2DRc$QJYj$ zx<*jgc~Y*G#xPly#aP2H>ZH?;;xm?YDOyt?yOKOFH8hg&lScT~@wYk6#oO@Apu(|B zCY+>0Qz~yA%Y$XZTZ*9;rc5sC-Y$d-g_g$RFBuL;Y0ziA_^z8w!CNoL;>` z8;u6*08x=zd`QpBmzV{o09toW>LzO5tEAAFqjsPVUQ$OWgn6BwWo}2L&!qG?P!LFm z4gHG1iQpz`YJ0ceh`Nf7YCEN}07Fe?2pDkB;`?K8O|vFzw|D8$$+I=;xLtWn$iZaI zaXKCXLqfMkyc(mr*V=qr{*^9C z+0RTAdXz3l09%(mQ?3NB#G|H&Ufn`HQbld-Qitms7mz99BP}+ytnA{gPb_ko7mSHJ z?V-Sz`U1Gv=Fo(e>%D@9B5ROu!5J^$aHCMlZ@?)cqd^uAC+9oSW8TMm=4@j-@t+oqB zx;`5qg~meE+o<`GUTIQ=+LhNiq?7s2pz@j)jgysY_BiE?*9+P!UWHVmBv_Oc1u+U} zhAQ`^d#)Z|V<8Mi<6Nb&Ahlld8s2h6j#Fb%__&*o*{@S?56N(??I4^WZ-jwd?%{LJ zel6>3JTfh7jjZAEhPv(6bPubG+J1?q8I$Kjoz;i|zdgLzPGw%amd+w17GF{r#A4rf zO#1V?5~)aGNvGnn0M*hj4`~{FxP5&hDPxvrPbV$}Id@x8wHv4e6UGGkcim-_7WUwB zl^UAKs?&R(R&3aMF>^ufgn)6Bsal+BP27i$m||ZzSB7iRcOZ${*A9~?dae?uyG~VS z;b<0XPxg;UJRi|E+22HSA-{#Pr8%0M ziFPT^BTv&>TJfyTz(pi&sxMh8_gb4UmcYssc7*FBEMDWXmRVr5O87V9_X4IgG`eT%T-7Q zf^hFn0f%TvnuXQ=UFijcS9WY0vo+{zrBzqznNkXQi*$zz?-La`!;FMJu(;@%gvOMK zH=x~a``SZwcaZraC9eN{NS!(uiIJbq!1x2sGQ2I2fO;y#fyw$^5v&bbpVdK8URj9? zHbNE_-6ZABYY<+N@X*)^RAN_5N0N5EwAD9clf?TkseC&5P(6{B<;W6p#Jf8VIy|y6 z^`7?ldY@cM(jYW%4S{jTHSZG$hH|ova!_idR-p;k#5s^ajw%0ni*DjW;b4tZ(@sDk zvbLGDZ;m3y+DfARkdRvXI1);yGeR`LyNJ%B+?T1<%xS8f-`3Ij2} zcM`nS1^-&mqq!#+ryu3rC%L_~YL`j7^a z0H1~+y>S|2+7NrYuY*aOd4s9dc~<~aQh9KrXlxH3<+<;b^s$5nmi1@(RF{#I**2tp zwbsH5oTg~bye?f`tR4=9SGRfTRE>4JLJ9B5!xt{JioB|E<;YjQQf8*vf6i0O7-vmD za7UnUF2&?|m=Z`TwVP(L zhfI(}fS8qB5U1re*(M%|{gZb|s?uj^Mubqo!>ajA8jHEDzR7SR9u~&4vQSAM6ZS4S`O@LnaWjqO!Yc3k)ml8$S5iJyM`;Lb zZTKXIb?|R8YLAlk;v7=MK)j8`#m0mQm0x9um0K{gluL-0=6PLmx-?mL?hv0f;ls`0 zfr~OJovl3MdN|6?>b$fq;c(m|KIV1bA};qKnn7_IS@MKSSH=8jxs#9Qcmyv#Bd3|w zZF}gy$8|7SaDmZ+@;MjA;@Dld8|KHS7+!o>aB>E6@rC!q-CD6Oh^5Tuq8_1)>2U-%Tg=m;eaV%{=GgUb|zEs$hz zM@wwc7uTA%FU?*^-brvXQv-&^yyRyv$99?FaBbuLwgFy_j!4<3zz=5N7KvXS_HG4} z0<}Xz;93M%zBe*O3hNqJjr<2ZKDaxE{dkzY1YcHI^LUAH1vAa`Fs|bjEer;$aE2j7 z?*?(y`?rn6^hcxbAs|n}5nTSFU7-(9+9*t54ctbj;sZ_zmzRZNz}IJt&C!#=>$i7TyGvUg z=C-c4qk86nQH+)i28k=-oUhwx2m6FK1E=wiDUC5{id4*?^nr{*0_NL!j-BPeus{QY za21NE7Z8h8KYbO~DC#+ONEntfc`yrx_z%S{hHV}rta3NACB~{k0w5ckfwfX?5s7Ya zx4L$HU$1sGe5C*AH`TTQ3r?r3Hc$|_rOt&9n0d*UBTNnA@nZ)MS4xvK5W9@=n8~xw zK=vHI-X?yI*4X2EQr7v_(D3&D5rT>JWs44a8fZ_BG2v3cDiA;vf{=-meEB^wFVGJ9 z`t>`bs@YWn1;zX%Cr>3?2;olC4aukV)s0{P;aYs z7RuaazPqZtPB;AIn1d&AU#`lK=vyGD5A!9&r7Z|*-WJ)U0j60uCJ9y;d0Fg6iokv{ zbj4>n1yxY5h{jLtfxAAOh+v4cdP1C}sqI4&!G1rqd9ygE1ZZf@Ng_q|R!OnAUIG)V zqM6O)tk__Dm=?Q9{T^{sbly`FDR?;=s+<9hHw)F{;FGNE@^)wP0Z4Ph+9i!3NHRuR zjK88W%DH~~8;*y;r|#ujT+-EUXUJDAxt6qH_a7livg zJ~Nu)MUmwt4k!ULOHW){{P*y(@=59llg$_Q0jwe%JeN|(Z-mR7y}J+I@T+RU37tiL zYFGBPpOehhBOTw;M+NlQ6(9VL=lB%C4MmV{(W?;AwnwO0l(1q?vL4G_KUmRG^&$C! zbhj4Zi4IGv2O>X9MH8)0@SP1&W~n{ql;(~F!{L&RNu<}gg54}E0+A+k zX~jN)xlxKk<1fZPcj}PkE*5*eW@z$y4lhY zBn7xv^#}(xlFT0gCu$|>$e&hG0XUt)brq2W-EIz+#Sv&{%jx-w(tYNIG{?G?Y8*W2*7$p(c19&Z+5vTw zSH7G5Bo^`O6kqk76(si4iuP_LG&#R989n+dXMU-0RunRb%3{7!8DZL;7I?-|&!SPJ zEwi)?7P9I}E*6R4F!078xZyRaSh#0Me8+yF-AlRB(hNo7#cfeYFson=mL9hlzqXf~ zuywEAjYFyb-bG#A#gsCXmTG)zj+sABI1({ptZbQ1s|)AU-jRgwIdQpPBvb(40_vYb zZlc^qzLt3rf;#oNc@4*M=b}jXvp7t(LOP#m*2AizlxTkrGk)bOuDR>X7qd)tj?D98 za!hMYWhbp`_4F6wd5gTu_Y}}F_u+*5BTG=qonZF1J9@aRSdJ%%Z)V%3tcON(g)gN? zz30Rty7kTS?7nZ`sV}z((+^YDa$l&x3oasWQagz~$9`I;&gr-|p0<(E4~Xs;^_?~|EJn_Y^wcnI+X`T8H!7d0#*Zsq({g~T zE8kJL@~?@hrTURiw3fMNf;i|EgafA=Yg-WrSY^*63NfQ`U}=fC={{vbDW7&FpIZXb zd$KCgiC)VYhI3jxHg-mWDbJU6T!DE?> zQm-RX>Cp2BNnu|CyD)EXSrd;<2oGY@N(*M!m&BcbhXB?hSLoE{j$3omDsEU|DrxqmW%nyG%+ z_kl6SWd{ybTgP*qR&Q00qF5HyJ|!#C0=7d!0lx33nT1q#@9rdJF>Wo0P$v0iv<;oA zzo@s>wL`e6L)V#_(k^2MRZ6^P`uUI9s2eU2RhEK}h=w=`5s!xUsdv@LY)4Uz@Wtyj zXsTR($6`c9Z7Fq&&WMZ@zEmWmny!gy=Uab5Y%07p9#=;)mWum>IMT_9FwKB$i~!h2 zHrGf}v`j}A6iiIj23&ZR8N&ul3T5`Z24SRbzpfJ3IEdiTx#^M~D7P&QViZvoE5uee zHXfhiP-PV%z~Pu%cHgWE`Z!Xr(mao)%oNrbvfdYnlw#X7#c0%RP@308fyI{FFeS!Q zJleLv9T~VJIP{C#1R=$4Sg#jSoDN7ORSAfhRv;-#;RO`Fqm+1IfRQp9x$^>%xl-?N zF8k&cyh_A&RI27^med7m#Os5nK4PVp`JkY9{fJ_?lY_WN>9x_rPNSWGz!_J9IngIl z^(-p`VN+fNP&fn*!XStxNl=gJK%YaTpiV`$1m>&qp%S zab6B()H#ImlY?snenWX$2*cVJh->R6a~y+Fx8Q)x5|XIO3%H5pdPDyJksJxC>eDd` zk>$)9G_mhwyhR_F)aJE>IUz+r5V16jbp#fvZ!1{**!nAEwL2f~i;)YM6fVhEj^PaA+Ll)8*?@>^Jh6?@ zrVVwjqe`=DD>7=Y$BAQ?4>*IaB<+fGEK$ObR$RthlQNR=bX>fPEe?o{saSm?tpXeE zmfeGqTHrr3P!_Mz5S}^pJC>sqNBaK&YE(5OX4d}zuepxEMPBm;$;b)5@?+NE;$8Gt zFaAUx+`XnIzlcF}M8AXfFD-}35D#*e?SVp7z6rF!`6X#vAv1C=6|_7OtN_0euqdsh z6?c3H`-3%8Cmb1MPT~~^;t=7sWbq~?)u6q4OnC*gS$K$IDQQJ`%4Cl58GSbD=tUfA z6Qc7I;h0QXgTR;z;7Z!PqEh6%_bFv*-^@bk6ix}0HpcXVEZF!%4oAKsQk7A^i0C^) z%T}d}9Ek0ls<>XImtw9e5Pqx56^^uw3piZs3OFcxbK)WN?>}-w)i8B4qW>qqM(^sWnr{QOYr?mGzH)x)o%R|jftS|qEt8< z-qcl;+twu@(?_1;L{YGOqb~q1bnyU%+bCJQdPSmHz$w+b{^gqK-Sq{TNbaSL)N4}y zL_(Vn^24A3tF6j;m;_ZkOd?}6a{&`ZEmE47DK314f2o8GCD7&-fQ~$im;DQZDYtLp z41gB>N`xX#D!=pQS)fy0Q4y}wL*8grj7#B@T=kE{b#0Xo0b1wkU_!Pgw6;u96-X%| za60n0F)l1Z;?x|M=&SyIrQKCut;Q>W-X=xDYku;=;b!+ih|e@iexok7s$CM&fs8Th z9P%nX(fEOL!PDB z;mQQII3T2O6&}~Yl&i!AJ3S;UiEUg{-onAUfEIHFVXHFAMa6@dg~P%?5EdxFD%OuO zfI+qa33n*-G1YYqs&gnYIGDt6O~TKi6W(NwkIcNC2(b51exdsZ$62kI4`EIRaX`$9 zOXNU?WGjpLmZTPWmv&yI=8As|#eLC14H)JN90@!zXb7Dz0DRLMe2oQ`U((_2?JuVc zy0X%ILUran^C;~wMz7c*M#anM;ymO0!EY=_=>Qv808faer~JyfV!Y@#^7*7tk;y8O)tIQ6IfyQ(Ztp%onW>vsZ&`Ay%;LmMw-HqyA&$ z*AX=#WqS7`7&ndczg7QI4A%`GJYBX4t({Wc-q#s0FE+rRRhzVIE2)I!>k3! zRq-($RNLt-RYXac&07hdQ4N}b0o?Q*72&K8vRc;l zm4*fb>O=l|sdTdtSDfGGmb9wvc$h1~=v~_#`DX5X#Y8pLB{HHIhH>mX@Owsdt}lXI zC9gCL0d_E%_lee^X;k0lDh1^^y~Fo@t5OI=qZK)na*P zfKAk*32WG5VlKxlwOCtyIFtt5#?9Bhp;7K%L&p#$u~7gADA8Y-D~oV9OGo92L>C_` zGi>F56JUCI_Kn?Yb;*B^X^C40*O;i5*2fOz4p?he?1%8Il%kkF7cMv;dP6wYBWRKS zjcpQTy58UBH*~%|Klur<9%DeZXxhP;sG}xrSzsHc%|DxfwN14ch3Ok}F&MOcN}Ez7 zH)ELHiz^OrL&fLn8p!%7=H+&b%jv05g@i%HG!Gbx0#q9t%ltC3;THFns$mb9@*ymm zw*mJMBVrph{Xn+pvRquN07CAj8K$a!#f)hhKG8DIS%@}Td4(?E<}JjdQ!CU0oS?H9 zvKHVV!4AnokjV7~>@_0ya_ct?Tu5U~Hf3f~#)X>%31a#~b7I5 zWw1$K;^yJCZqx#oce#r2K%uw+AJK}sgExos13n>IdbGCQVYAv~yhnNW`gK}*kRl{U z2+Nv@wQqB4 zg-PiuRXoZ}yWfHvpkQNX@j8L;FH;6A(!`!vfB~ke%FJYdv>d##fhpR>4{bu?JLF#j zALSa41W-cM^L9*}2Nms!XcJtamRN44t@CjznFSaj$tpgwjU2L-Bpo0>#0QWw?Li{} zoGoQdGda282CXgtIE`}vuQwb3P`4b*LKQz?UIUzoguVX)E;L2(Tpkj=Tl>BMr1W9VGRD)G4)W`7vxwq$BK`Tqdecv1mF zYUWh(>V3jkHFxMYE%zV}K{F_U4z3ZKem&-w92$5aA`RgDOo#Kw2lEQKVun%vW^8PE zAVY@o$qM8s~LsbMOq1gvK8kiv+ucK}*g278x%Oj%$EW9S3+IeL%8 zyB6AmGQ1^0bg7HD(ZOs5muj5B20DU>78OLIu?go!tfRTgSVKl*2k;?P=>kv;5NXK? zVH<81)!d0+09p;P9;j==KW$>C!SRV=)xAd}iq_EJRVlup*%KoI%WhZFF>H}uEZ5~0 zYkreMTLYp|&v1QVzN&;u+`6EAgcwrM{vx2}pNLBca~$HfP8bzR2Sn1K;5Z@d;AQP8LOh@Q9LF>6V2l8)HBi807B`4%twE)7 z7XBcV+@_>eiwYmMWZM?4Y#>9&`IlhH6;z_6u|dztGxgAUdyZ1y;l#|xI$W=?YTRot zu2{aVD-`ak4(>A2sY70etOG;0uk_8v9#@qlqaouL8vByp>Ib|w;4%E)#1aN6=_A#N-Ut-la+VEE*ht7L?Bwf5rW8dkufO}tyIRmYT1EPg5?Uk6A?vP zD1kUGpaKzN+Aj)59^hVL@K3!t^`DtR3;zHJ?~QXMTmYXiA!M@^`tq`R%XW+v0l7_7 zVJm8j!NCd7OYt>Uqh1bo6a+nJ4_Je$<1ENSvojSQ+&~xm)TBIv-eOm#a$LTQVb~hQ z?7JP~{%*UMw22lbmIJ!0sB4z_FCD}nHC^ViOU?Zv9=52?sys@D zw8cd@sC08Dq$z^{ZVXBwI&-m}?Z7goq9&@Pwucgju}l2~56phhh_b@wK^A9T$Ipna z>a}_n*k(~+!VzIhT&n=HCQV^7z%hNh1HY-u8m{~&H8SYMjN=iG0ly`HmkG0jS=2%y zVCMRK#n6qLxze(oSkKjb&AQoIxL}37D#~p=U@4nuM#x<9S1-&30+cw*9%#Tc+t0+q z_Pi2=+Daf@0*iD-23@Z`7>~gk6B9Dzt4c>diIepwdWF8MfWR^k#PDpN|?_>^r?N>90kCTKBH@ULBT31 zrRptBUF7F6#K8bZ2lob|sYU7-YeS88`c?eH%M^8!(k|f&CMw`vA>oB`kh8Zh*XCUK zP}-==5pF*c1Sz&(Z8zP;dHNpkiRi=q{{VM060Qn>PG$}1!wdxTU%uz3LG2Qw!XynB zR&CGCSG;<7Q-+@rY#i?NhXt0gdSM9`2)WMd+TUqcLTgSc1Xm+(#7+S%Xd;s3Q;Owd zC0I{ROZkslw7x0B^)gk33X~ITh~*U4{>dyz3JOria>Z@~mvL8}GdtNfBa)Ue_)aYX2*WotYn8H_mD&Y_SV$$H_NG3_r1%TUdYidC{Sdt%Sc;=7#f zEQEzyWW5fUVz-Tg@ch67aAtY9PXHhw>dG=1yTTlD#dgZP%B%s8vT^%9V2L?6{Yj+eq{raofCS7YFd+u2Yzl@txR7Mtzp4*FXgI%ymp0M zp|KmbK6M2KEWhGk%7vUa31DTHan#t)uKxg-YI!f(Va5aO-|;B9+-C7)rMZAEw*ZYO zC7NY+o0Z{=K)M(;;-Uhmw0U6DKu~PF_ZVPX9yo^yK|Sb>mny?MN}7n-O<&oCx(c~L zn1x94{$>?QBpG<95bq#9Ns8@^Gt?Htf?Vz-Y#;~}M2%KMAg+ky3Oc>PsURp^;fZ?T zw{s(_jEGK5WWub%U)yj>%nH>-^Dy$jkC#lzUrAVmf7`hIBp9X@K((MtoWwDW8Z~%Eq443K>Su*ilA7fdb0D?b*s* zg?xuljuqwun8ar3=rQ&MgVqo=hpa>k8r;!vi#y5-nm6D^&bHu9`DwFE!jA=TLUG6V zO58mJ*++>(0IoGCys~&AbmzG4P?nq&O>+9W0HE}sn_W~oE?LwEq5flQc5|@)qOc@G z(;q=EK(xhT@h~dg*1M<_BQ!eQz-q{ck#+V(V|S;dLG14ks+5~9rtn69WCNaK-&-y8 zM9u?y>I%&{Z<(RM-RXi1{{R5pTZS>F1pw4RMGS+F^oek< z3Y@AOI|*2o5##wxm$mtUh=0-4Wx#cC(Ds`@2)u-7VhxIW9;5vq%RC2kXHYE)H~f~0sFsY0{N1jZPs8>P`w``V|nh5=cHRdWLR5&Fuo zIfGHSrnf8D#eGb1{{W^Su5>V!`K-?uANeXrF;}4i>J2Z^5Vx<3m{!S-8r*!?GNcWq z*qy76XvGa;2xO-g_%H4^iv?#I9tSgRbVM2m6x-ZLuEAnfIXoFgmW?;e2_XxZkW+m6f)x+RN_+Nff+ze{$eSigkI1${G3<2I(p4tz*eA znGU0SeZMfV%Fgf(SUGPs%M1pVQ7&zzNJ|$?=tCZ9ZWcCSP!CkaM@Sroo-&U*MH-eBF>ZL4Q0Tjt)p9fN+-Y#7Z$bSj$C1=msxvZ7@+Ym;&%YgkSM25$To1QLp3l z7J%>eh^n;Gqhu|n0$X0N%Qej@Ou#(Lrny*X^yTG%XS%3?5H4yaPVNJU#{-|@b&OgG zwaVIvz!_&Oz9Dd;g0ssgITtXCmzWxcHN-WbI*h_CaNJex$K1!}I4lgZUkKD@$&5bb z?Ydu>Hw}mS#CI#v=tGg=9p+Y)=eW(;gGuIPEMqiWTCV}W5p4%F=3);hn%;~+tO>XP zfmK&a6b|5SZy18WtTQWkQJ1)2O4=sTG)fYk5LQL2smUx9PcTv~6in-@K578zNc&}S zNs)T%iFLFAey~tjYC^Ktaiy@5ZC)nos5ph8kFl z{O!@!2ou%4Iax2kaRdtH)8(0J;#6)CWl`}eDp`%SkL8vZ5K10%?>b)a*~-U68q^i& ztBj&|!19vdI)K+`>0^^oHxe^u$OA>QVapUX@Jr?aV)1#aSj|Gvy$~r9>}Y=y;JBw3 z%kvX%G&^#?xrn4t=!&9X(CnY@5h&F|Mdh34Nu;aaw4!YZ~7e&D#**b%N5 zVf;b}3q1F6L`JCeEP+o%#3net*+j8Rr+y>qTH1)Ex%T>j4iv-vedU#nJ?;HOM68oH z7&7U1F*Vlm!lG>t^DA}PM^O=hgl{L}zGW$2TN5-mk3;?XnZw4-Mlx0j%D5sD(2vYr ziw2ggIVD$Bp{2U`j0GI_pkqF{jc1@e^)8r*i@XC8V-ZhXOXNhP&dYoUyi}@KBZ*)S zR@cO>9&IHbkqNtB^A%>rW6e}g*mdE|Don0V5j}xoy4m{7R&A za~FbCGCzdK^p(sGboxXw@|umNjYZaQa}{>hU~1)d%B4buTtIAKh@e=nF=h0Y)t&p8 zSO{}@er6&A#%yKC7JE(1YB(VIpua^JAX?H{G!HI;^+u}_y17b1^TuE{J_ZjHL8L?@9)2N%{w6kp)@M25Xw6*f@D4kdZZxtR*=c#!qDZw3EbL&l3Ff9U*j?i-N9in1 zFFuejMxxd~_E@te5W1)`*D>rIGMsmaV1WcWywtfKPf~?o6$L^NEkf^X`JQB7xaGx_ z;w+gW-V4M9XLf|7Vd;0gz(N;eyk(RfljPCy6N=HT+;VZ1#^d>cG9$?W^=5IW36^J7IGS_*BhkpI zo-i}(G6YovWLXk6)A)wB5I8s>gGeniY!sLo^X(heQjUxP{Kq-uE{JNH2384yd^d(% zK=3fz_m6180&N)gq6haH+8B-pcPJY`uR1>wZ?SW-4x3{QxtKEGGU5%I)I3oi2)4&= z;S8`1v4T`I6sm3tG+m0(%*N#P(G4+Sl_WlrMyg6lG&mv5M(U`*tx?Hwb}TA35){#Fh?N1k$Ygi@Vbh* z-RcNYU6`zmxKcPfqkX~<&=M95Xm^t9?d}L$(`wKH+(`3q6MnSBT7p$zwAbsO2gz zq`mGDhR@7Rsv7D!W?h`0`1UdRqbgN+8{#^QveDJgHPs{j>iN75Jr7MpIM?Yk-v zdl;Eh9XGkAsj35<`a?~$))4pT{#bIkX1F0$RB})P_&qyg17YzJ()bH(9WyNaL}6Lf9zsrv8Yx_X0>{+=i)ka65#OaAt4F|n}3E7)Xv;u3d32gpfUFlN{s14dX{H` zv%cR^1*KkyrCYuRj@d}5s5>Azdp!tPNlC|<)Pb(e%dTk`)U~cl`$4m#s=dSp0ke-; zl#_x6SC2+gMRe2BB~`4-L$jrmef!CG#4z%nxRkNkj6?v6a^!ax@?seNAyv^$9UF_5 z&xui)8z5RS%nOf+*$)h*4%RBFtRd$Cq1AOQK&9o2rW30G3CjNfS1ZkumT%AEB3np< znJ>%$N~iXe0JK~|J6f4K;uuIg&@~zaDZ>D*CIT9{Qf-#;D(ue$Jca23n4=^|5dcWS zU~VDX$9Wv_A;%;+D7?`6eks!LbP;WBC6mAW{f$5aldB8gr z=G%i~1v3S4lDxxdXc1D~r{X#RTH*!j=sZR^=rs+a2cMZzJwZWI-9uh>1W3opsI|4Kq>XvY6XhtcImc5SM%Un#Xj6ll`HIU2X$75vRn}H!7wLW@W9I(=pbT7A z3-vEPNB%oDvxkhzTpsMgCopqKNpD@@h-hAs5NMMb;Fbgp14!Celvbj*YE@T=XlqvX z1C`<;jur;$jKC0Mpt+a}+KmShLxPwFtDk~pnc80$C;?HbM$)C3q&&oRB(Sz4{mK3kjnoIK4!K2s@mfy;mBN*M_`>>_z77P zP)Aw9%M@EE)t$wKS!sq3qA^y((*##z>x8J4TLOGXK@o?s{jtiGss=nh3oa=XWZb6A z2%jtSk7zd2fva}PC~{C;t}axn+yPjsOE9PP`IcmzTZ?)Y5i48!hS#er7E*5&2HgM+ zw7kn2YM6-5Pf&yT211litav?J=mV#|OgFa%zK{;``O+*1&j$W?aDDlEep zN>Hl5If}#)R_=^?RLD6u?Hx5!C1y~YiKJ>Pa4OBKRC{HO%|QcYf27nQXZVM+=BgI+y;!@*vq`7qMu?JMxk=csjWZ+ndLcp!tdG>Gl*?*4ivz= ztXx(lR)sGl%IxC;w^r02r~s~|gK-FZ{vmzriJK)#kgHCi6tEO}%O$gO!r#ySGj7z0 zjHZS-i%J(rmtW#618g7%f)@0#0I>8fAz`VyL(`qc0IOp``ekUg)~%iitq3unIK2>3 zl$Bl-K_)5!Ve>QlMd%v6N55dEnXK973FLe_iUy7xE-bNY&_lkt%bMc2&*D^}tUA3B z{d6XHCPKWfUE%Q^T?AuJb2O_XD=wBfiN-CZl>3jF)ChHgV3nB~mZ!?Mf@*zra2exq zmf9axn0&T*tY`2|tJ)BsFcrd9uQ31{>Ka#!`k@S=(Q8!2Ow|Z+v%F%GAyBu2%qa(Z z^UPxu0y`f(b1$etba$^#V^C#(GXV_+crb1*5U8ED%kcb1N(CpQ{Xqo#3*QZmJ3Eio-T=2ta1Nh&LLnr-VTj6Sdy;#%e%uq&kcK-$zxbwsu% z#b0ph)zqL$@a_uHL^1>hnQdGmz|_F&6#~0tHbt&w#GhE8@?@I8Rn#hB% z@&Y~&SHCj778d>^QCcl~>Sxdv(4o7fV+key=nr|`8AVzhFEx3;j29K=!&3Xl}-x0A~3bQRk04H%&?OluupTugF zQKDW&Ri9QX5L&IMqyWOTtPJ|$|7u`FrEVfm9c=B7E^H5d@L2`r>83B0(nPIi@1-X5Ca|T}(0wk-b#yTLP3a*;6orr?* z>hzYS_(B;tO({U!tELc+5alD-+vXKE!J5e0kkfpVZQQP<98GVDa3;BhI>f-rnqClS zW;N~#j>r1Uq1nm}vjq)J%Mq<0p%hf0IU1S&0HGLM8xQ6d>K{Y?OMY7VquYc@#G<8u zeW1Y5pB27kg@B^yF3{~&{A1=MIO58I$C!?!(&M#?I6Yubg>?PtmDQZDG1hpD7Z+4V z-+jsmA(~c>ns|V(ewSNM9Y(?S5$Im(0Z~vLugs_dYYJ3BW(JyibBfG#Fh^=&H3wyJ zS7?Q#dijE=43eV{m_P?0+i>ebqquU%Pz_(aM!*UjUFEx24JHP&d=Uof5}LgA2!S0t zqK0Z7wk=(q7v>6wKlp{VQ1C)t2)3f#d+sC*YNDB}SECfv&2QpVmzG0uOco*maKJK( zU9R3{b$Q<0O=io&;#pw8MY}voloSdCSCYM;H!sjmPPki`Q@~$vy61?9(#$9q#}mv7 zdJ_GS$|au=Sc2eIULcAJ2&-exHKVv-Hpd!Y_b}=U6;=*dvB9g|O*!dpD}v(a0HcDU zTE6QF=y}X`;ZzQo$3^GO{{WbY?A#XtwT^BhfUX`4ABc*96md*AMH#{ad|-zfBajIS z8x6&`$(cx$6|6<($~#NoJ_B(_=Hv{pCgdx8+b+&x9CIvz%6|bWb=&sMgUJ=>v@Tm4 zC)BHrg)lSVaTr2z;v1^Ci0?^Kbp<~!%-ZmjUl#~<+99O(a0(zR z_z?p^)EG^S5pJy9qR~bHf}h$5wL666Yiz5}0~jFr>L$8o452MQ>ZU9#QkXD4CT9q6 z7N94!$8IEPV6*I2F)1Gr3nEqZER1nrZHOKSLOKhVZ!kar5f-#YzqTq~lJly|>NRJp znTvRP%!Ad7xrouJSIT0jhp7vQ2*SsisMDFAZO8)IsGFkO*#7{K5oszVbt}-C{{Z}Y z{*-e9kug&Gp~_@Fu(FFzC%U7mEf_@)zxN$jh6`U-H(*)^f`<{>N@Hk6cw)vbM5Hb& zBY9V|p?)zbtN|@4(~2UD0mhYGJd-N;iV8lgOn{pLZ6c`^qe0+EJ!q>=SZ`9xh8#oK zWAvrwMIYQoMQF9qpzpY~2w}Mu#awW2Y$*h_v2?q3R2*!oOwXUF4!fQ=)8jfY6X>}+SpqmHxpJ`%b*H%O@ z08uQba;`*B(KM)`>ta+2f?qWS$}sPoXZeaxVqxE{%mxZ=x2&--O++6Q-FwSE*fI;< zrAI_7YS(=*Ef9rds7dgtZP_z7g4u^>4;50tNW?v-U=^yOp9);{N`FCR?1sw z2=jui#`lW;A!^l-T{N*3gg2g$F^OrI$XLF(sdi9u>%$VZAfR2o`aLF1JTDa9n7{=& zdKLUilrI8v0AijoTCU-d8nhPSZJ5|@R6(wT0nd%WZLYP!yh3a2H5rt(>0<*@0UetA zsfPey83q3U5i1t}qs&86Ajs&KRkntz=&aN08*)Ll#oCqs5Y{d*7VFKdwlVl}|($)7dH@048Rb?yWk+8 z^MmG$-**B77Cb~Os!G%qTION2F%}%HW_HI}WkU4LaTN+pva2_Rfmx8LGNYuC*_ezY=!G!XsKZqs3 z5mBcZ62Hu(vOqLH+&*T7)qDQ{Q9hKl=zEaN2&KR=cnDZ@fVAyE>MnlhYw+L4F_v9& zU@r9xj2MHLT}nYNQ}H19G7DC*RWcw34C_c78JibG(z44&q)~J1`Icq{he4JD>mq|e zy84yECcj_l7&l1GTq~7ys;Fy_3YSG0_xgs0aEK^0b(1@o8Vf@eQz)&-OFP^{^iNZ9 zEVx&aIywXD{{Tqe5*CDUbKy)>xs1gXK^ROQ-5rmmqt zQBwmBQz2WpRh>!9!6tQR{u0=gUoFIjw1h7pvEPZBGU5%M(3mp~1w&X{#d^a$oYzo* zRnUa0a|#lAkmd z+VMHJ;ap1_0$#6^d`deYH%l%pNmNpSz;_(;3QV9XxgxjH)=`K1g{29otLDFmtz0IE za*mwASAG=_3Ez2%yxs=5tbNRWlL(`ld5WP;I0nZ}`$hl?C{d1L=&UR?8cz5<|rmKcCpl8esK{+MVcopwK9s+7$T}Iw)>TZSCow~zyJX=TXcKJGh*!OP&Ugu z7|^82ggqgcS$V0l9SL#iL4-I3Z3kk!LE)g=>jlu>V7hzE zGKS%{&R7uLEOOP%=nev^JFyyx!v+^qR=~=tjxiMi5N7V;kP^im!1Ti!Lzt|+Si%>F z@e8aMn2aqmpH$gv5QQcjK>Q%b+$K$Ewhw3+^0Eq=U9g}DtJWW6N;gp&c&4H^;$qm` zKczh*knvG&F(?k;0pyAx;Jyh?17z`#{C~{OftoY8H#kneOZ^w|ES&EXnRxCym)HLQ z#mr0V^)W4%iEYciC7nz-LJcfcSkz&4Dv^z5 zCFiTubxn=UJ1;Kf6kLp?Yv4Lg0^f;-g)$dzW7}QjbDm^q_Yu2i@)v| ztimbDhO%?@GUwBi4QmwYHYgT~Z`H-XMq1$(98?M+MufcIv?}_6*^u^uDO_SPLs8ibnM2D7l#$F2?kUPaTh4ytIEL!i zPpqlZOgM_0#I*w6e{+bFB1MY0+!ce7x5RKuuv7qYWePDln0X41XNkcUWYT)kL**36 zIP(tngBbeYE%&5aRD%NoBQ9MCG)Cq}P#Th$>p)Hg_>NGn?%f}Kb zRMyumiOyvdc_ndEa|Nq%F{SURcF7rGTre0rn4`%VQI4g8&teKsZA!~b?HHGIPppG} zreWp^MlM{#gw%|yaMcpwCfKY}n|PLg7yE&@0YV|AjY~<@ub;m&Cbp{QkH4T)RI}g(Cb*mo%7{SR+l!zA8Ov>`)^crF||c@a{o6 zMiXozE*#*FEubO7VeLA3hji+kZ@9$+D;oy)G%7Z6&T%V1V#Fo6AMpkmb(AW+x`JwM z9`Xe+t4F|BT>DHn(!Os4&?(&Z(W#}l2v5d#aW>W_=?ajTOGo?_9m&y$E0yyJB4}b`5gWbdtWnk86};z*ZKfILiIvmX89TnUlx;t~GPr zVfTaoudOYG$C62YjACgU{~hSN(f zel7(P_Z`ESacm4(Fp|LDE*d5TTHtpt0Oa8>r)!jz33jxl3?R$5HO%+&qJquDQRZSy zHRUi?NbFwPeLxKOi(c}?H#UN@b3LS*qqxGmxPDMCMIozHwmO9Z1Wz4kmy>!THY08U z+E-i5t@eyVMdSWsHDXdm$rc_bs7ILi{R%rOw75`((wJhd3N5U|Mz;x2v1**=7T4>! zd`sqBzt-i;movmbE2DD#@qohY?+DLHo?_81a~p#-`dl**XzDh0vJ#%UiV!^|uHwC) z6D*LiFXSIXnEMZg*L0#NK@&mOTD9E26>&%Qx#<_14Z#^HS- zrY6R#aVIpcprX9ZJf%Yp#!^`EN##8NFeEnu`qD*ys{)`cJ;!)qtxreVC5m!o-^?gK zM*s@*aYJTeJXY(N@#$PKQ@u{&g1}jE?J3Pmgyhl_cA~9n)&LRf2v5FVjxG>cnqyM? zfOByQ{75b*2||TX0y?`OLx_}A3^N2Ry;9U`F3ZgAp(elQuL^A=&gJ4PxM~)KJ)&zf zWU2@$q|6a$%m!}DNFWf(pR~MN;w7;|ekcN{X{v)XYT$(i^%kXmm*RWNmP_JkM1Bfv zej#-ZdxLG*NlKd8WFGv3AJ2uQL=7dj_9RXcDY1Ee(4^ z_V;6q-x}kHJ4f@isnvQ+0S1&mpShUy;}3&6fV%;dU2}_pf}jAMLjeF`c&M4wEuqCg zD<(%pnBhwXF@46V8d%#gifWaR+s$Ij8e9cL#`u&|{S&h({{TS!%V4+|7dNBr8uZ(6 zBanqL+j)h9tib$5LB&kvG zGFbaVnfD>03us5sekG|5k90(e=ulUzMk_YHB`-Rd$-{A)fP(7by}(PD+lrzIt!=A^ z70J~~A)j&^MhvhC4dyxoJUh6`T7(9o!l1N6>pw(7X{GOSi85)M5SP%oS$67TniKU8 z`Pfu_#1c^{A;K(KVk=2ebpn)iFtt?z;pcHdYo*|qa5$!1P)`x-0qkLdm(g<|K&8S5 zbcJLgR_Gi?4$rcfVp5lj#JY1TjYol*tR(c6H5TIMp^OA?fu>#pJr*m49?~qb$B3>g z!w{IOg-4zpUSWyH=~d_S=2ou}wSPOb~tM-@Y!Yd49$MY9l3XS}b=4OSMU3ztJB$=ozK4E1OMB4o(Py{ZBDg|y8 zOrzp@ydQJIA^!kGfk-Eq-#?(C?-?N5F)>m0EeTbq>5otp@hT}oACV8qDnn}KOq(r> z>nR#oo441gWOaWLDXV-&pdF0WdK+>q9b8$kLRI)OSnou}nQC66&AYU~O zn;DUr_7Y7DG{UvJRzZ{^EF3HvtTQy^jYJZuhpe!{78MKEf(X=^WCQ}D<^$R_AkL|R zJFkXx;Mo$RNNcb-Osi>QuM+bHT}!Ea#kq9``DZfcR{vss2 zq%?x8(L1n&n$%(D2}jM8BRk= zLmzNv(yf&IL>P^PdU0QIRN%oPZmapsurxJ^`!Nu?3I_zac$ZLXWVyM?IhXozpVsr{ zT@v|>xo~cHm(%p#;vONO-61H*3l>Oi`;97M1X8zjDpQNT+JRYHzUG*JOO(g`M&&DF zT+4x*>pqd9n}p;%k;|pp?xET7&LEQ{Z^+SSm!l*!maV{|I8@Q~9K$j{~r8FY} zObfI07ltw^x$g~uK#U5voZc|d-%fKgSo>taHIm^X*)*(snEG&oBSPX|(BbhOa@9>B zgV2Hc=@bQE-*YcHrFf}qbT2Zc<&)YYCfaGt28C)D^sAJh+FSO4(hnpFFS`={?Rix$ zt^DRNPT-pbLzi;43p^~x(xQn_8i4PZ$m5;DlsGANwFik0%xolEi3|y z&**+7&mkMLxpOxuCT|k1c!T0zXQB-Bix)F&JBv7uEq1Vv2actCw80_3u=?x;f zg6JzN6CuUJY21&NR2?%zo6H!PH&VR!u+F24+YL4miqTz4@+Or`U8?YEc0E8U^Bsvp zD;Zf5%r*lL>M&^Jd``OkTER-cx)zjqA|m6$Uke*lvn7)An9+HYh6!0&YT-hLFWzRa zaWWVwW>!;o6r8Rc2ebYoLK|)TOt5MdOlpH`B_ACzW~}8zx7sULj+FX;xFW1JkUdZ8 zDmb!`IP7Y@<^9%xvGjTNo7N*pccIkgQe1W|sB!S*;gtzFD{vY+R4)->Z-9j{Q6#N0 z6Q~A?vl1f~etn>_u}Q^DN(r2a1}mW$(FYNih(6Ng+_!}aqUeLN(x}hqLOvu+rZ&V^ zfgw1I69Y?g3Gb(vtPm+w%T+oMzt>}$l2WPyi=d%&=%v71ypt)_$OQ%yuC#`~&;?jR79SRbFx`G+nxKM%UHR2~6a)PYUowStdutsMAt{lUA zg*vgb_DZO;O3Uo#Jh`;1Js`jWfDgnPFv6?yU(BrGBOBi@rdf7$UkfYIQKrvnM!ze? zdq8zJ)sY_m09OTTrwY`0LU|%Kri#Mhg1afKF&(c#=HWev? zO_ap+%)rhI(^AU~YJ#4PLPj3)#=Di7MObE6Xqnqz47F6OY`=(Of!S62Lm=SVB4zRu zXi!jNh)z7sz~}T`GjN8wj6$4=ca@Gm>(CUIK@^=~V(aeI{Kt*EaDCJbGyh7&0= z@3I887;Ftq zs!z!&egwq!l%sjXq#Tkn#{)dG;>02Zv{~|s5aBLZyX`;pqR=Oj7M6X*t%m}+zA~Ip zk-}2TIW8j3kw{La)@j5L)vUOP!b1Ty7c`q&KP>EvcOP2&m}3YQ!nP0dE(2ZMzN;`C z9l+m&n@TT1=zo~)BH2K%YJQl_*`zn*qun6O5oODICCfY6jK-ixz$!UPHHft!!82Zv z2T1HHJ9@_yP`mLe(6Cyi0u(ChYGqZ6iiSq)+)C&RX`)~zV?}yK6-OFc_1wCy-NL=K z00FqX4+)$0B}PTq1@?CQ#T3TWK4$ca1;tcx`Ys{*EKJLT;#^r+@RGOSf7w4vuo-6y zf%rzeRP2~Y;W%Mid5w#*3_x*)py)vb@%2Jw1`cgG$=6V^vlumEwO)JUu41^qdK^{rQ*wKeSq1Sr^|A*}vZGY6R;`x?k+7E}oN7RHL)%At7> znc2ScbyCSx&^nk>hfTtf&L~x47Brf+m~mwDhE`cLZ*+G9QFB=$!0>haM|zjjGnuGP zA?rE)7dV_pQG#m6v@_XeDhme@d-{-L+Gz6#r2@T0;3et!H=U9GJ0k(5|N%b9Y&S}uC0k+fM*EN+&E9zV5d3YoWZE(TuvxPTBh5M zNld6wL4d$Z{Rj%Uls;kW{=ou}PcW~4VbzVxfJ$YG#ve3Umk4RxU25rv+6y&YtdwPi zf!wqvB|-Z{-APHGc$Ov+%Rzpq`IQ8P@xO7>Ht1q6Q*#?ysvjB{l!6S}ue%)k#sh6= zE5`%%1Iu7<9QNS%NHo)`2iZ3-vc}9mag8e8YU5P6;lywQv4*M%rHL=btw#U_>gcXa zD~1TSqf1zT6cg|IjOHw5!Rz#OnSLFQKlcm$D5Up?O7h-(#^TPU{Gpp$cL1R&?pR|= zLeEdq*}+Vm%c$lL*|}m`tq_pYVCpr57jW!|Yv@#7Vw+|n7`6zPvBju{#Zv6`l>>Iz z_C<9tu25-5P`yDxEF&6b8aHs&zYydBpg-+LpnXU(SoR=CDAFqGc%&%cuPJ;Zv2w_+ z>}J6d%u+p!p`^bd_Y+eoPIvXDH6ZJ-r_z1E(IUfFqmP<^<7SCX@vO`TEk#4c40}t) zwQaD>=180LLHdhI37A#uY4JC6SV zL-kox9DbK@oTk_P(xhFML5!wO???!T)~`qugt>y~0aWZJFu2!>aw z--XRtq{MZ@95AG<$19m(hdYj}!M>+8%(AsMBBhHKE-jkif`p~6-}|&|53DggRuop( zwMO0olEE6W#06`)7aXO0z3`-9cC)r0ic>v6=na^d8=1S1p* zKkxVE;2CSDHZA`EQ9?z5Sq5I+bp@9)^22We?OdQ?5Uj&VYY$Kr8br($Wg^@px?21& zsyZVbOjf0uhz^L<1h>i$Kq`;^8mHSa0dt;0r&x^{sEfJ~6%_3h6x`I`2dM>DE4YQ@ z^{>>$0Byk)>vOvQ0N|PkI}$Jl7E}*?Mh~|$TvVWD_Y4K3J|Wcd%0*W4gHXOnK>D>D z*oP*i)({m2jK`r4+W}4p6~r_D0LFnsc_To}$f%O0@x-_aXmJcs4^;4Qk}pFk2_Mje z8$c5TArygt6bB#tDla%pp77Up8IPFvLITU)253m-*lo6^64@nagjVjRT}p2;Wf*4= zN6{-R(fGkdW@~?i3KEQTT5_Js$75@4e^! z?*0A0@7e6xvtrg-GtZheYvy^low;2BAWDdcivU1CKmc0658!ql@C*PA2?+%W0SyHO z1p@;O3y+Eb4+jU2g^cnT6%U&L9}gQBmyne12_Z2J2`(-LJ0%SRBMS=)!4pni4kjKt zW)`M9As{d?Fz|5jm{jZ37@dgARgsfq@VMK#@SekU(xb05|{;02t6( z5Wvq190C#y6a)%LME^74jspbrb`Ag!1_A&@1VaRZv+zIL{ckF`k5>LS&F_o09Noq5>I#-KjlrWB|Bx_T9hqaV9|)KpCKO}MPy1s#LS0Aqbl zLqRz2rCmN3tZ72`{^y3mj9@kpdr(Kvjb4%JFFW5&f(|ewTgf`L7gcZQPO)}CEZIGP zy$S2a&^{z^>Q>h7V!2vtkABxVW0g!W3s-BZ6Y3O%<%ZUs=85lWcoZ)1YsWzFg>3E+ z1bh=It17PfBio-~GBMoR8eVB5FbG~VSO@BG948QcO(JsqNS$+rgxv8w8VZxmI~>c4 zpg@qo;*Jq6H6XaFJ&>SVJlk}xlx)Z2UIDncv;1N>nscPAj)OO$XsQOy$92Smqmk3` zfRAgOTwy~bRal@rha{B&`#5hm=^v1zO_Lakwl^4Vm2;T)Qoa}77%dGB=WC=u5JcWw zP7N&NrL5$y3;@9Td?0#TbF1u4yK~iG8_cs#jcjhpJd8X z=sRaIv-ix<7b%PaR0(dWWOUPVPKU}fTib5^Ak=fh?A-snwdLtcma&C4r8lg>9ImlVov z;hQ^Ifq4XpZvDze;DGy1-}m%E)I$l%6R_a{tp2oC`!alYrlF}aZxCmC)8_fu3}4qg z!rZ5?MW=7vYDx*Box-OHB9_qYT*`(`Uu73}cJCbZ>Jb$1(_Ogbq?C+eUTZ2(nshjY zjzd9zBfHdF7fqWsEVA#e#m$^io`L1=WBT-<7}$xZ88o&@wpRGAv>0zD2=b&{P8@XZ z5>sZmttdOJZ;&cDGoMcC^|QJdRdL)b{ zGpHa}JUY$k%22*OA0k{{R*vczqrdVX9%v|8IdF{3Jy2^E^Q1JU3k%hPeCtAW33iX3 zVoMo*z1~!Wvwl&lNM2Kody4AlApoE_qUdi0nlt|(;h}uY=Yu(Qc~v1Jgt`jB@l*y; z-UpN2E60q|c^Njgyg=>WF47zY{e;U4E-k)GH?V69bz)Lt56aRc4!v{!|G5Y&(kWzJ zqbL*j)i_8v+si?>7{Xt1f2S@Q*|Ya|`2Qa7G^uH4PsS=Hi{?e7W) z=`N$o`_TyM(N}JdKiLMhJxb8gfILemDuy%$Zs&=2SGja5DZROH;l>Ti{|pNLDTK7{ z(FU^BT|2Z*&(_1$laJwq)HH4U<1NF@k8A9fq(Liy9lyU&H@gQ;U}qTDwYo#S@mYDT zn+JpO+2EaiVE&;hOM*7>lSp8FCj7af>$|MGA4m-2%M!P@guu|fzQ~Dg#)|+>ZB`_M z!TAj&YHH14QY4)4CI9HH2LhUb*y;yov9q=-sCX9tBWZ6a*)^1nF!5n7H<+nhI)4!rb*= z6RIoDVVVy)3M(w~_L2sGCQnbQeK)1w*j80_2iV#5>3I1c3pSX)8(u2_02`^)cBl8@ z`myu^!vOJI?hLha+=59*GPY?{+&)=JVJ~au5I>Q*v~4u27oa3wn62be>1$YAVhIH( zkghs|vZrI1&;Q&(;T!_(5Xbff_w)tb#8T#>vXMei%|l;7;>NbBsz(F>ROn>S>%W;m zWQ!deJm`KLa|@u8;2V3Q=o+ft69F6wG&92Qb^(8oHbj4{f!x;DnqQa?g50YcUT@n< z+r~+%MNLg&a)Zu4DejHhzh1_2W#7h_G}n;b`Sv(YmBsjN=atdbMqSj6P@JiWd7<|C z_S~`cb8Fym;n*sivMuyfr?Ga^S1EOu|2||?w7aDe;IV27^K!y755`cDPcOu{arYLW zVOSBX3WPJ>4C7N7DGG%_KcxVnE<->9yZ9Q_{CvHi=W{2h9@@p*F!P za1_kt{iJi|%?qVj?4rfwX5UWPbv82adMqSl5xUiJ0RnB0%5^s6Fn|H)Q-*(G@XI=E z%e>`g+O=%Oa*ul*@HO$QIi+3zP*(G0=Dfb}JZ{YvfqM#o`s=I+=|#bgNHb9XT?0&w z;mz2qw+{`0ZvQ>U0^Vp6+JYhD`k|eI&-?2~eXB0==9nd=l4>st+(eDWglp)Hqgi9v zCq|Fbn-y^+pSc2w{Mrf{U#~bjqBoj5&22<#g3faBzq;nDQn>`QT7H^O%G}>^D5_Xd zUpq?_96uV)`OVx13xAYU!fMbU?JZz+KM=pHa3NdaoViuJqp zy~}AUUJoP|XT2{7PieF+<)Y&5=`#DQI+wkBV!b}23FIPC1EwsGTll7fgIogIEv)8~ z3ZP{0E-*NyHD6R+f7$)+Szxp|gT|&mN9DT-cXI;vP`~VvhRn)$6j+Roo!k4sI|#Vc zh2gDE1=aMGk~;(QX}+4CoQBLMYSNAfyYT5ieQ8@E&1sdXC^zQ|>&n7vN{jq5iJJwk zv@C}()v-lcjOsJAZg=%>k;R1vu+$5O0iNUG@>P@(lB#NjBy~mF4+^o&=}aXxz`tw% z@dKPjNPW$Q?K3~aEz#xXPE;r&!^%OEyWc zKIn>%arC>x#}cl=4aC)w{=<||B;0Lp0o|r7>O)U=bEWlpP_JKAUqWm5OUSxIgUC_M zhz5Alr_<$GJ+J{l9{18m{P2527U#YB@da6-@YFZT$tI==y{0zUS6Q}Et}bC38>fkP z_em0u_HinBu7(}xzE0ZGeZA_&AxJms?|e?YJ>??kd>T4Sz&B=3`+nS-h0j%2 zI)1pycP?*Kf6wpY%Rbb5KFZhVH(CNL_^!IawZql_(!&5&N3DlHZ2fgUa%KVNV_sce z|MGAPrMbL07OjP(nu69xIJ2}$a#LV(rrlkOttq>7hgVhb4xk4PRb&Zp;qYHhH|^}? z?a;2}FdtO#&U^F~E+w~&Le=&10Te`3RlISGLPF#C*58U0dJ z=n^z@{JH%D>>T_$SxH`9Axi-%=@KLVlj8iM*U3gm?V$<9?@KC}ROeiR3LFm=i`UU# z(wcKx%bSC8xF+wE)Rj~)%qOW87C3$sSv7{P=rh?PI{BBbjtE?$e%?3$^k2s9#T^BBu1vM1(z`0)#39cggnKqyPvq44aST31!cvqvE?2<6Vjij1llP(O> zMQ|V7*T|BRih@AC)o(c^yd4H73Fd=JCt*(n_FL=Uw)|6X$LBy!a|JiP8xg2<0pLu# zA20j1sZT)Q;ri2nZL=(lFUW5mZ7;_FcX}alwZOHL!2zP?`O9e5Shh)q_4!bGiX-?t zJk`?b14BHHP^VwynaaTS9F=#yChqb?~r4&cB z1>*ao%iS<~reS#NltrPWnUU=8KzUn8nw1qXqor+IgNFv>G`l18S*^2UzHQo3>nphH(6cs^X(K=}>E~iSDFVFQwM}GG>`2~6P#AP%ArI8w-2EfL<2u;|8=Gub-MPc zt6S)j}6X6i3+!Gp+SMMURjGCIV5U^V( zRMV-cXMXw2RUY5@Y+d#w#xXKrextftczR?VU*LU*`RDtEmFN2MEW@bakmSqJ2yhj9 zTikGEQ_zUt_@v85dAQn!@Ln@;8GBn-aHsRvi%QdNvd-ft1}b`rU0hL>1y$xLN`%k` z5+}Hfm!H!$aauJVqlUDv`SZ56ZOV_ECA}x)gu%iplX_RStg)=kk}?cJ`vYZJakWoI zDii~INED;?2c{IJE@}BD;iyB(G8=89cT`*ov2$NV7UmSza?ZawMSf5UBDpmcS4Bm4 zY*v8Y7x_1e1ws+tvu*pQKW%@gKr_FM_S_zRIyho$hr0;H{%=&$1-{SBI|)i6?@>)Z z{H;Qg>Bq|P(-v^75%Jca&_m^iQ~rkjOAyiU>670HKXRVm@qYzBO$AT+jz`j0K)F^H z=l*=%x=R)I=>aPmi5u}(?fwD>>^O~fMtcuoxsJk|z*0KEkqR&u59 zzMl34q2qjf6K~JRHZa7_f6`g3V$rhe#v&^!BE2r$6 zO~;~cR5xm!`6p2Eqsg~j z)lXUK)30?6NVi!FW7nV0h1zQDh9*R(Ocg4J@|&<8IOekH$k?hDXtGGV04Xsxwn>u` zV^w#6az(77J&uG@Sf=UR(P!+j*j%w_P?~{An*ZVR1VG=UO5HW>SO%xZSZ*8lVjm4t zigj#$R%5?y3Wsa=1lqZr|J+hgk27)Vj=7DS{!qVnOfR99ZUvjcKCgVy;70bx$wj`Yvz-rZ`n&mFUAq{T4 zL?V#OIRBZQ@t1|Iu5m@%l2gG?iw}Ux?WA@y{h>OR4Im)Oy*fKt~PuTE>B3FVhJmTgFX) zuAEAILLZw}kL8@@%^*eF{IavBe{j>Vgh}QVHLnfR7g0#91hqGn!O!E<`-Xusnw4G` zW5rUe44{ZZYWw#{0(lGP!ewnLC$$C&pdeN9#pGf61T_t*d6j0#i#HAP1mZq>&688~ z!fK0L$jy0Bc0rg≠U)piavkeA)nZ_+7Mf$ZUUde0nmc!I11c8&^Af+F(khAB~FX%gPuxJ9u;Q8X2?AJ6OnUOd@W!B6AB!i36gzeJmV!tjCN7ADE-- z=XxWDQk*Lz3?#S)ll)&I;sRBE#o#xYEV5Q9M60Q|}n<)Ucy8A9J8O!*;Q$(7N z?odPkE?%4I=ZXOLGi~&b<9P}eickB76~dWcY#Np-z1}n|fKSEcxx>lmZS{V~-4p(P zkuMOp**C0SylIKD*7FsFN(9f_m=Y%((w>hy-f+jl2fzJO?#|PXytK`vd}UdVmTE=T z^BW@YHuCX>;aDDZ&TPxFhv^;^3%l-TNq*a0A$xBe>4rxZp?UpRrANGHUaP$kbA2Up zxKs;h79v*NM!MoTg``Y;(pz&CZub?PO4m?+z23pi52%9gb&`;mP31JuksgXEyMWls z!C!^6i32o-h15@kzZb8Xcs1y_@qR^pCkoA4ryY6C@9~a*0;hu=IU*BM?-Qb~kCP^t$JOI4%d(keLM2!ecE)eCCRV8#;hS+jD3 zv&=t#-pT_{=4=6N_IBqN{g;LTnpVN7ueUYpr%UbkN+OwBz;y=wu`2Vlx3}_S>U6Ag z`z$jW5M3TiS_VEY+F6{R<$8;^M7F@V+D+R?>lf4~LYOQv7WxKTv7GlMcBEsJ{O9fcAk`3t6>Muo zUGmP<#s?MWW#9CFG ze4cDj%y?i7erQ3yNOktKKFk>D*KW+%`f=Ms7rh9o{$9w2R8#a$i-o=oX%F^A$?Gs? z{gryhmoJ~0unbW<;gYv9J8^NSk$yKW5N{TeC6snOi@=m1ixE_?%UKCb*RLMMl=Oc` zO(fG5SmPxe4i?c`Ha5A9EPiihAu9`y^o8sNK z`~39BMLnvV;C>dcmb(TO2SKbR(_!NfZKEr+_@LhlN<2qC&WlvMd+-$N6yar)hC8pyXR?p$BQnjjE;W$F(G;6r;@FSB{K9o4Azmj;6~l? zN>X7ue5(?oaqX-H2|T%kqyvZ7!)&%(5ub0AZh7&QfjO%1u`$$U0QGsDSl0fVF7 zssn+T>$DXy=Er~PNHmUU9~l|b#-$_Apoq?deu;>xUSnht?m2887+z9;4PkdDynk}U zC5E=VY+N;#scc;RelErr#bVEQwZjkd$L!~n_KH*Tz6B8Gbjal3A0wX9cuwdRR2me| z7A|QC5j|mT>$kHuftRB6mNAjo%FabPjeYrXHDYy+6_PmVeK#YKEi%Skff#aV_(CWD zRn8u~GF5k+`fL%Ki7n>3KNGi#vXaPKR?|}IHg>_s+Pmh*M5nGejV|Q8S+PT%QoUHV zI>j?ZY*d3mB^!WXCUrwW;N8HDK&TwV9sTly6tHuIx!GkjppAX>NzGNX!3`nxdD!Oc z)!nFwdSgqT{BlG8xV8T$HCP^sQIpVL!&GlXB4c$0#AHr_LT(sqR;basD#uh9tE9m0 z3rG)S*L)fBU$A#%fg0#1555Ds_sPN;af2^snE0Qx*4vfKr#($I9bLlhEw5c9ra4O>Og@B8xMS#UE(Ulz zFh26asHo22mAvs}7l_>A#a^~8ku*;4A`Iei5-X3?CTkpWYoVFr}P5Tu|d&zIxz$)Er>y>E#@b5Zc0jen~9tT zGB2a!{;HzpQwYUmQ=AyXkUhW*N3JD2C^a;YQe+b`Vjv?E%jgH6=>JG><7&vMzJA_@eAn{e zP|a~J^FZu6wASJ@7Q3tfCLPf-LwHrfcEFH#h)@Td00iim?{&W7a%2kT(vLZ<5hOq* zDUWDZv_K56*H8Pt&w)?m>-SrR&*GVw1>KaDV$l3}tvFO=hPj1xXqtdQdk|$J8Zr}G zQb<`J&^#@ML6x1LRX1NGDqL^g7D2Lz6vFjX9=3J3=3wbVjO-INYMJM4VPD}rc zYnJ1$l^{rWcMC9So@;%AM$8GV@}UQ*Qyi%sGc+R5 z++`sAN-^_h}6aDFba;w-STel9A%c>`H5j>Vf(^~yY}?UYIE7wL9q-1lSH z1RO&JjRFE|KPAxdXHpS`y$6Ev9r-^ESmY?n0Vnsd!JiVvnL85;>m~LvMCC&bW72n< zh|q?St12P)9nyk(=DqmqP;mO^1G<8ik*1A(-cWbKn-)=lfLTe;-)}JE4S>5!`!?Am zW0F)z9^;LYHtkEJI9r}${e{K+x)6O)Lb9TFCPJKQZ)iL`Uxe6dE%3K!)T7wdo}JS+ z9>_XmyLL?t8Oa|`gh|U;6}7TsS_OUf_`}||(#DL(Nk|DZHi*W4+pEvMJtvJtRT4I& z!;s@y*rRqXc)BfX`12z}OT`|SlxC0q{ewozR6Up%@qI-54lQF>;9OK^Fd7h|=up?q z?;W!FheK{1-vT20Q4mnu2V%KIc`z%fk*D@VQC(6zdqS-OxNYHX0q<~b0eT)p3y;wm z7U{sP(1jf~q{o)$7ix~Gh36vAaYPa5Mq8t|SS)?D%Fc8xz<^#&57UUk<+ko_uvUoT zlLZoB4>SAu4Iww(x~g@SC><97zYXaCbA_!W@UYGC*+rVt;RYYJb^gD7<_T31@)o!qqc9nK=wWX2O2$H(GMvb&ovzqbI%*objG9y);sSRNHS}b{Bb#pJvF^pg zV}MJHR+!1AL_C*tmu$1>7)ozi*T%_%4T@VSlnc!Z(1JcFsjrr*^(?)h!y~px>${1m zYH0X*J3XY#^qkgWt!t-BYZu&AB0+n`qXqk5!~mNb2dqUUj&yw#Q0QwFP%+saHl=J! zeFv&F)3{*4jxummWHdCTDM3#v?BABFp64KYsS%- z4@^Sy_6*&rsx<(TAevJ`FcOIR`G>G{3qZS@B4@Ql8_WgA3*0t`I&<-J^A7v|7QCbE z7Oz|l=Snq_9raIp!m=!C=8k=x=JNNrE(*^+LzkM;Io!-0SIbV=AOC6EV%XN6l;XJ0 z5T6MylstHjd(gdGs7-#xdI(F5=8^~IjrQ%e_&dO8`qOzgwBe^E%{c_$n?FNrcaed< zWC5N_QQHI0r9$&{FfEP$v~o12w&YmN-+aKRK;N|7b&{S*9RI4=o-I8-w^a6HvILvF zGBuws#j86P`gI+8VllNebX@KFxpX10LG9Y5Yx2DJ-;+JESwzs5DBCYL+Vtv&Yv|X6 zoUkY(en11j0J1&2c!h)|-C?tY3P?r3bVWIgth`u-6oG+Uj>jbCEdl_G&@5p!P_{?0 z_P7v;iEI~u6~iIt&{42KGyiH5j-5klH3AA;7$B+r^sdbbcAQR`*S+JBM4y2(QZZ!; zbgdr7-NgGW2Bz|Ns&fe~@-mLIUnb~vB~Kn}iUg(1jN^~7es@{C-lI&GC^i8&aik3# zLfH*OUxhRoim`xMSyDNLmrpj=y`JLh4@U>_crlDV9}tZvj@0p!#iLYm=E&-C>c{-r zO4gIDk`W^+p$KgD8K0?(p8+f`a@|iHj|h3=Oja!77@e`QLuZ5#KC?lP<}>4CyV{fY zUzs$ai-H7^*R`$pfU(aDcX9Pqdsx_$%FQru{862Gr!P)hrgR4!Rr25BiUa zuNC_%Ej~8ab34?WIffP;#Xf|jCAP9=nfXX|Nq0+|`Q}Ls6XAt}Z`6LvXV6U%wbb9I z+gj<}v725<&v$7Yh zy$>I3r-Y7u4Lk&@bJ$#H7yaB*){_oWtp{^bqATKHH!;^phBb>}s}aTt zj>YOGISj+a=pyx4vRP*HlM<5Wx`BY_ z!*yA*Un^oh7Q|gC6Pv1EJav0B@p>`~9XJ|)o?<}~(BXZ$d$2X3-z_?p4=OQ!uBsG! z(kVj)+%_1iDvzUa6i&sQ<`}<{Qdlcem7j{uabL>? zkmy-pLZdL5S>Hz(oh>2~lzHJ`vc&uxe~M!U$4hHgEI&*8NGWNmrZIjW98AkXk~XD+ zBf%xLv7%9_sye_7VpltVW>zHWZ@-BGv$ zQzmqi6GAL>SfUj`!ffhxD??vB6K5rBj~o<=u}}warV`oaop27!B1sQ`>V+v0>Lpc- z=V7P$GpZWp7JEoV_I1EVE2-M8%a3ePOQTLkz>sgQgKupi(UF@fct`pM8RCl434jrP zZ6h6L%K}EF`wZ!)>;9{C?qF_y_Aa<7J_I+Xx#r7%wT8NZX-+GS34Iu=vPT?3o?c&< zcyk{l^xZ??vJ+9h`u*o4YYUT5H`_cK*DRi498Oa)x1Z6|UT_m7&!`1!Oy!9d7>SXv z&`7qJnvTqIKNhUV8LsDdQOmqoVe0*V!I}n36yB07Rbw5ncA6))Gh<9}sUp{SnAOt8 z*go5JZ)`mV4CvdorldQ$oG3me`s+o=3FzP?1V3b?+OVPTFTZD`2_A2J%vuM1*kMt( zc#pHz-&Bnz(_;Ie4J|zJTILKR6}$9FDaWBDV6c7ru07BiW!Mq{S}nuK4U+SIsgV0Cle{Sj?O|m8+CBfB0P&EB_R%q?i;oXEchWFR-q;eWias)UN(VFi zgnFy3>?6Y5hA`7q5f%faCQgs7Ow6a!_W09Wp+-X_uWdmFg&5jJ>dS!iD#Pz|ZQx_e zn(Ec3DdZ=`5i9|In8w8Nf^)*0N-3=J*f=9U)7=IQ8&cx-HCf?SQLa!k`a|V5%QHIa zsQeKU1~krmKs$~v#-I0LhYkwf70d8C_0O}N$1?igL)}yvjMhSkutzAGot z*hXs=J>LhB810wTq!4Mc6|#jkQ@wldMQya7+7Oei)-@?ITHC3_9wBUwXIm>56Kpe| z-&M00GG|=)%xFI}!M^yVt-g4i*fg}XKT&0-Ku6cl?BqISswu`=i%25O1X)k3aHJOE zTE2|~n3lzeP3U<<`KIHFdyq!E9NuLWKX&SLb$XgRhf4E=!oH5wq&;;FAvJ&AJO2Je z@-DMTeaI{}Yh4TJCc^9Hs3qnOEX+)Oc0u8};a)|e$8LB3JRSfQ4pR+dfLL!pRaVf( zH2!p#+VRXy!|AH)Bt7r8Da8zp98llz=Rq2n)uHu^CFNFG<67Ap1ZOHAkJft}C&CQ! z8aQxVqvg7ZdG)1QZz>`Tytd6s@F0(?!3TJExdbltNe3ai=Jxo=)=gj%T*mA?Klh0z z!G%^&ypfDspakO`#U02-V5}?xChOvl6noH~ zk*Q~hojz>8TPEsCG2j^d^~Rt{F)^OBIhNU4Z?D%KHLd(81oi&?_}fEA9yPH3@AGoz5`m{jK^zUFVrX#>_BfZZz9> z|D+I)$7-Wo#e4&NiV-CF5&)}KM1WADRjm|*mmAw|`cf$j)7%syFBHqzoT^{4z-zo4 zp+sMmL%X^dJ&i>_r>cmSE*I`OE?af1(W>86xvHru)3~sbs)iJL8i%IdTzqkc(azo|e;eJBE%>^E}Rgrd0G{udX*D355mh2O4C zmb6=`Sim8C(5|Clhwxh|UqHw4`p=9ha@M~O z7RKc8KKuGcR3L17_wEgX`_}{RUJCfzK%rW`FCxHko$SONn_&G$kv{8U1o#l^bAc;C zm;c2rAXakchK0ZTYvC)=yuZ5l<(#}x zHRv|B$Cp-3TT}(Fs$#7i@f7 zd(Wo){sk7`|7P-osH6iqaFGC@AP~QDfgouC5DBfmzv=>d$GNfEYO<$EQ?5{2pwkqH zZS+he32`*nhvk_Ni*d$k&?-MrkRtG98sJMbQ1FkTK%jx|(SQL#FaQ!bA~FgQBeU(h z55!C?Pi3ubJR_r`M?MXucrFzVX7Kh-7QVnaW>m@%I8rniN!!?)q(HbxD3W{Y z7^-9rb0||H=dm0ZR80ltH2FYAWM9)7P%L=C-Bo~gN0$Y2BZu!)jRkw}KEXt+!)UbO z?=r`5=$wTfCf1o11%yLXIZ6HvAQ;vdg13wl>D!B8d?&|X9z-7>uQu^mWmA|2hpuMj z(^Iy1MD*lHrWaoVaLEk)>nhs=%|T%5!AQe73lFr}WoD-PZklt))>nk==eYcS5Gk`*&%3|F%mg{$5L?QF~>_d?94 zsMa{X`|@3-aVm}3oS`HRTjE$(iLfx0oPpI6!@fbp7h`kE2y?mid%|F@-90BTJ)$q6 zo3FxE_yp~2Uf5Um3g`Gw5`c{5V^ap1$y<~t+07oa0LW?D{2zwinWK%cxMWTJlzgY4 zD?^w}Lc)Mynek478XdB98E(vViu5mmQpuGPcUaUr*U1m8=O;Um*c+X#kKvuj$ElK}u4U zU`6oo<4@Yfoz@NE!Rl%#TJs-3TBp` zVrHT4xw7D_W~M|_b@kfW^m}B6{BE-`>lS-%>9DoLUFxut6~V?=Fj6-sW;Ivz#eWpC z7QN-=bTmv@SM>RgBlrB^J7p+)t`m`#xx+9H~Jq^Xd3Hw2aEud)LleI_{| zup;Wfw%>-IUh=)T>yUY;{Hgg+Z(Z2nZU6%rlxv2TQx za{*N-rZ^{|0n3sPg}-}ajYSv+W5N@>%DJ7+g^!CoU;d!p*Zjgw3Du`fas1Exu@Cg% zjAIU4#9$7Tj$m}%BH!Wc{!&E9&+RbFDlt0-;ks0h76Byo>pO9fn&Wr>DByYL4uWHg zrlpvDE9VY!rxwT9NL=ZEEvSJY;Qy#fCmObI4E}X(@4Zr3)x=6+@+-L_C7$aM)My4Pf)9AhqpPUw z5>Gb+0nL%Joo2?+` zdlKY7k3F?4C&vyI#PivhooTF?RQ*8W#5L;>{O(K3+f-B^s@S8I@&j}CtHJFy`H9RL z$KcMt@4h&OwWlkI3nCN0a{agJa%S>o;-_Fso{5Whv*YgTpTF5}9HG)gDdX;uBW7+Y zE)EMr@@NX5Lv>dQ`K@?VXVJXem0&d)!f;deq5ERKqr0fj*WC+W3o9wv&$^!sImjt4 z88w*4l-FY3*LbQWqHgoHjW@{gJH2zrtt)umv>b!?N{^HwQ7ee^S-%}EELT?3y27xy zhNa$k-Y3+TYJuozuH+|M9JRV&bk19{)7Vui+@B6_!eK7Qk6{;960$bBSBCC%=`wbeR?CGmiN!f}xCkPy?c^KuiIGxk{GovxW1DiNssGW@ z&ZqQLe#DX?m>@nWCr@egJ~i>ERF(NJ(05b*_b*(Z~8BzAkeJ!!?LY~U+F)M+(Rz55B)-P#lNpVz3&yfLBg|Z?WhYIn} zqv5Ym-iKMa@o0BHx8_3%qbY(X=LMYf3x#Z4ND;o_S1jGL`&$Xuyl=*#AC1KLpaI0e zmA1h<3CO8|n!d`#$Bj_i5~pm}=W0m!CL>oip<9&AE>v-4_F)O&j9_c@&>Tnr95w=1 z5<*{U3%=h8acxu%3U(aFAR}FgAj0TSZ5+#MyafnR zS;)a~8_>*9eTmsACvv(yPNU5y1+=Vfwsft2n6@BI7gl(8zT3cZ}egQxD)=@4q zWpruLx@i_`IL?~LXPI=B;m@57pp+ut>l^5|jTHYP(w6PEXkA`_>s`u*MiOD))s}7Z zsBT6f?CCVJH9MrCD~H5a=&ZA#c%9cpnoj7AxS0-vb=R!G?P0cw3jxtKgI`Jps!5c@ zfo79h3JU6*gi_#oeJr7=CQvdEWSh2mGp8^46m+1>Tu|-BOU3JU6Qp_Cx>}hgTkdxf zlCNXX2s2$gmi;AS3pMZrhRx;u`ZQxYPXYD}t;8a&hxj%fr$UI1Yp0mjjkJi*O|@ZQbW_Zgebs-b|x{^cP3HfV%X;yaLtvX9QNdB zrN!Iz!Mm4tVkZgQGnExwZvr)B&#%brMgNSl5p3LAm3of=j7n;=EW2Nk7Qf-6e92ow ztN*|#+8Y!O{%joO$aoxkwD-3^)LVcAXNLq{Li%fwgsCvGpMM|YWcg_*9Tn%`rc|4H z@j?^QojH9>MM;1Aa}as8fxw{NNH=hrtfKpl`Ll8oYgW{6f0R+TfMc#zXXX@zznYjC zn?7>a+GGwiFDG%Pvw+X@J6uE<@kc{Mt8^a##MJCDXq@R)oNZo>IKrM_r;vYDEVpZIc2f5x~RBoqj@TYwTN++s5~4%hC}FjJ!*1ER32(h1jDN!VtG9ePsVRb z+7jl*(AGp$i^%@m`+-p*Q4EHmz;3heV<$c9xa_EEmu8o4h?lcM$!A*jZ`Ao9UpoN_ zj~s+8oGjdKW)T>|FgGLjR7}qDa%}_Gni2-%1G!-wLai~TrC8_ot92{r)X5uma3au% zJrISUxW-mNRbk5K5TuFoQ|-a7;$%-Lo3?yq4~Qq{UtX^I8*PF}t0F6>2vYQCm*DL= zl;Fwb!J@c!e48ZGVXZ2Suwec&`4^BBCm_V%_V-xM_CINc}!8d)ZU9eTh&H zPudn9IS*ve36IskzGuEL!G*Huz64^k2VeLv zL(`U-ZvhF>j~Dg*`WW0sR#oHF^##Y3AWjlqf1HIgR^-TFw(hJWk|Eyd zk@jKp@+{=GHl8e~x)dg6b9pm-qia|@a0}SFuj|ax&9s|rSHtK(wItJrllT}sUl~N) zI!QNi$@9x2-_acpvpWG)GjCdp)wn}d<+MbGa`(dquG zFGAzqrNHu~=aox}w;6@@J;O-7$*8_C;j4DcBvB#l=PdppF97pd(U|n8n`$*1G!KZ)h~q>?LKHCYh{0 zK#Nb}sG+u7aN!c65E6$8=@{c71wHcy9m_%3SLD2(`MYUREvPx0Rj>;^d7OtvL8@MI z=$6r2p;5y;&!#pubE04=31Muy$X>5#jHZcv;#cZkaMHG z5W_}M1zp}bu1xJ=hp_x|7;aluN~Ij5VU_5Vf5MrCbvQbSdB-g|6-fD^0F3?Tis*@q zthj~r4u4ZrotKKa61K&aJNft?G!w0toyI{rRIu;raEZmU{&$d_KBF2bADZPGTX0|w zfvxWfSg{OlCUzmV*^CAWIY^`jh=7WO6on#a9-W-pFFk!w@SNY9@}Qxj}~C?>V(g2EccX5gDjR5mfw&wmTF_0n>} z6Z}YlW?Etq>9%jC!Z5Bux4~QM$IW20>I0gjsxJeAcN&}zo{7m7N2DN!7#?5_ z&oQP~>GB(Oxs8T=%fh-AVLtmOXg>>`UCPTGFIMu+%d0F!nfU57B!}!pdrhI184M0` zsNgK$o7Vad3_KdR^leYDC%?c`0P1s(ClaR05_DCYwL?uV{aA~(F#jc}RpJm8StF-a zfIbC@jA$u9l-I-UNOBjKby382Lhi!tU8KK{+l(w>0bS&gqnI6IT>m$)v`GYwpm`KP z${JVuB8U(T}cs>HW|C8VD$UmvAJdeGP#eJU`onsG%41Hk6A-BbftanT5?l$TQw2W89i6la1)d$?6gDk)kGjwdz;GqY4f=USHD1XwDjy zyv%j^A_EMwuY|{|=PNC`T7I-+gg<%EM1nXhesVAB-$S7vnX>Cszbl(h$+~OlQ*C83 z=E*UfttyRIAQfUbhPpOm(kC?h=1NfYz@Y?nuFLgagMS)}!^f&d*vW$~qO|B;Xrs}& zs&W}-+aTmUql1@9F!c{Mpe6?s>!=K86V+1GjK%cCP4ds79w77w&pU|NebC>S$tHnb z{1T2vJBm!oI#dQ&TJ$ik%As|#H;q5QL>f@g5@nS2#O)LTw?+E}6fE|UQLcs!f!@Mw z4b#a2B;AZz# z5Eqz-0FSNRj(|^*;OcHH4vxex_wJ5wi!;Bpf5kKniw?Zr0HPuAI;=UN_C%u_<<)|BU=FbwDPMe(5I?BK|a zLrsoA!PzPbeP?%&YPo%wV)t#7qpr|V7*5pJpND7wJa~P0k!SFMTHwo7L|LCNb^Mh0 zf{vPp|AUWu92&XQW;4}CZ!(>o!ly($I)z**ijmqnhC!Gs=PcPAYlyMEADC$`Dxz6( zOvLz%FH)HjS}5gKauH>k233bsF22XRmHZ=bYJ-h3z74L(5^E4Aht4B{yK^fUS**2C zeL@oq@8J4uD|pT*k)*_v^t3Xi%ZxOhEq*RHqDR2voymQEetXd@c$5aZn~|%DZ}?y1 zm*w*sT*lm9C-xQzQB%DCbPIsQ?!jFv?R_miM3wakBNJ#Jy{Z`R0f*Bn@Cm|2@-3hs zrOoj@TnY+U=V;p}Y5mAFtX^u-@Vf)}Cln#aA}jQwHZ_3}FJdSy8tq<+Nqy{x5Eov4 zpVRMPw%pFc3j2(1Mk5%~ICbY4;n2_mWuuY|qV{vH9o0UwC8;t+ouei5`AUNutkuKx z>=anV7%O3^G5-sRNh=xrU9raVSWb(<2b5OJL%Q;QPI4N7Q%iagPy`ZbFXJ+9`Pv!zv7A?0t9WwdC zInX^ed>0g18WM{JG8USE;X`U;G7~LE)5+Z%LGO{ZvR)JEHk#}O+$aLaT5&cBymYQy zAG=0-FUn)4?SxEOD_7tPb&zYdq0jZkbMgA=`2$<75(l2RG+Km>MwcZM9wJnNKqG^q zE4__0v;d8IE3y*|y9}-kR0qP(rj@r(tk( zAzipVS<+Hh&xe(Z-i!?6+Y$heX#IhwyC$dUY1o;g`u4V#HgJm#N^Bpbh*5qgo zO$^g;9nIk8KUH%zn!piHCn2^|N6EcK6~2A}8Uy}GhIBsvgif{0$5~Ay-27Qm(fk#XJHvPkEmN&V!FiVG9 z(i@ddmPu*O9doKdQ4tO~uQBc4>Fkuxjq#l-r0+?frT>4_y$4uR+qN&BkPrd{NJ6iM z5SkQ2uWIO_O7BXME+Ab{z|gCd&=HVcMUkSSh!jCO(nJBJNLLX-Y*^kxJ^Q%#J^Ot3 z-v4{||K3Nwti@bo&bczzm}C4#nQK1SNXpv3+6s!ZWiyUcmwi!v=Z=$ksUT%#cMdal z>aw75=vciSzPqonm3JlL{J#ce4)r>3`}V7X*e9>ET)*?9LT^iG_W`auV=*KF)b9j| zpQbMc3MXD1xDFEr_>_%q(~dDo0IQ?F2(abmd*52TtmK|IKN~G3Nw4Dyd%Ye$olfs$ zR9P7&xK=mS?gohT)R8Ok0Mo9?oF5&fZTWVp>f26te4x3Z#%?Qvc#2D`F%v_sj*zG9 z*?ZU;uZz!+J4Q-1CtuFYp)_@M?+A0^{xt8eM?_F|UKfsDC4D*>kQa%UAj4Oo??X zZEySAICXbfC#h-*&t_LHfO-Uh*D5@O#~vy*l~$VwKJhRsq2=@k=aLzKjCygbaLO& zmFud<8Mvk}YdG`kWVL*XR(zr9)>HOV9^#RcSrh(dmhpzuCzIHk00%jnuEH@`N+Rc_*|v&04`DGefu6Ly z^bo_A+ZoP`@S?e6?g+>{-DUSg3CENq*}WhW#8a*LHpJQ1$`;e@pT|Th6`e-K6MA&8AT?F=I=Dz$%`mfL5Tx|@k%?q4x zW?>Q(yE}HqUDt?nBCdl`)pgKQlcy)w)y_=Yb~s}@(`VG^eE3}0o7wi&poxw;VdXQBP9ro}+Z(@X2j z_;A+Op4UfSnhpsk9)1({LG$s4BJ`}IwgCg9&Sl;sa$z(Qem=HWW>uTLCrukEG@nKj zbrKZvzJn6pZPWddP=VTc)7GOe0ORqGSz#2ExDs>tbDH{iHF;g9Xp;$^z}q}Fu_8LO zqmen3am}dfI?62rJ5#kJYp%So#YRrcnOMQ~+oo5Sh+mv+;1wUAWHNTio~Y*zJepyU zdrq|No4|L_rYpYi4cOV8#$Yk!{jGe)j@fAVo5a9ZrE6#kwI0tqq>{Bu`U06Lv<*ym z4X%3KsXImaOR;Wg$6jA7_@w+NmWtA0yn8K;BFAmM-NTqizr3QDkasVf4L9^ONlC|A z<#~bfgzA7OZs5YXO^>YbEqAm?b7+kzN3b=)@e$)}3u0)LKG^V?FjY2}d%80#zUG8? zV9>Mu`<^<_%2sqLXM(LYhH6b_3vk}d;6VoBAS_r+QndJnTf*y^ni;eG+vP;@v7HJN zF-0+KS8~;@^P;c$Js{_O-X%A-d z_aqPqXUxQ>d9EjX0zr0D!ptUSH9}6%c~=Y*u4~cXNS=YxFbj@9X*pOcEH`-GY{kncb7-=vr3j;-i4|b*i`gX>p1BYi@y}3oTUR&QVhdxWlm&! z>QO(BZY-dVd@8xyRcJHd>tvP3X{NJvH|y>>1%$kZZgq%0km&;PfY<|y)Y+1m@&k{_ zHLDwv{O3!>U(zwpiUCa-bE(yOxkL3d5=OrC$24B0iQG>Wo)&$QhrVaT8W@}SIvdE* zsiEhcl5LI@z&=U9+DJhz?6iwKULFztYNnDjC#z+3%El3mQ~0X{qLa35eKFDm|r@LdG38* zZsbd8m&s!10IQt*y(Rld(W_@N=zW8mr}n8cIHvC~?`f0^2@86%{XXfOyB_2P4pN)d zeaW)5a(PPKtZiCCA0eXZ>pfhC2gPv&*5!|b+iHePv*wfr3T}8zeUa=mENh%`Y#JjeU}aEYV1t$Cox>fmi@5bm=Ld(WWUhs1dbxFXO*#vG|G{(B101_EzpY z$V4IfO*qSAEA~Yo*UX%zUe8|G$iU6m#<=5HNZ;0clrXtW2JMsUpVV`$KC`0VieI~M zz3F-Ixo?NA3hS6YzAA}62>inV0oKDwx`%o)ugyMeunhA@_&5Mi<3LTC9Lw09+MJh` zdRXvq?Zg9KAc~!T&vmV)EwL&7%jU;qKxApvg-#v)&1SfeB%f;jsrK*T6(EWLBSG0% z9wzjZ*{!ZIL@igX73cmN&ix|xOI2MPpG2qM)bq>^SrU87vLa%9UkLayG0m+$*(?dU z$`(trygkK>s{JiJXTEKmV|RRBxuGzib}r>0|L4CU_WoTKA0W9m=Vea(9isOJ5Iyiz z616}*oY;Eipc6v=@N>9J|C;~fjQG>|ojuZcd|58oncelYdik~ZxemBvMy4iCzU?&V zhN#qi`QJJJzo2fOYgj!94-D1hSsLM+YWFAtoDY?NEd8Zl{`#=~WZ(e^9*x}LbZuoQ3Z`u&crY< zom+Zt@as%f*njR-D2fLndd8-CV)9NdyuX9l7>(A}K=*x}$>$WV-WBrYS1a_PNy0^Q zl3CQ8^4M(wU7hP^yGJSx!y7U;qi=b5T=Mr@Khzv3SK$%t!5~cAVA&*Hd2Wr4-<^E@ z`HLuCrG;lD? z*y6fxXNb^AQcqru`^|@&dJuG-3pe1zTA=8LhJ}hV$sC_v`VyslMW` zL6;AF*{mG%_C9$sd^}JtK6kbzF45GGBBD`{)<~PBz&QG05kNj^=u9UpY@7BJHtyVN zCUg06jQ4dT+#9v0|9XOK6)e5AAFPi#)htGxx<3tjp+)1#uI-IX!Oah|;z>^pnCO0_ zQ~hvD0oWn)!DhQNkh@eVXtsO!4f~XE!c^#V@JNlGLEY-z-asA4Ks%Y|*dPBMF$+#? zhzE4+zvN-=iGow2e=Bi*=iTCCRAFWq$|IihGNOv4hHUkS`B-WxS$n$D=BPmi-sb4i zF1^{(f&t zHqMykGC4WrV?>wX*Ts#HrcO0&xOUlyT8zo)(>M2ShyV@csU^^8#IW-S@wtf+{JO_? zT_a=3$PBH5IGU;}P4hn+l8i$$CDBMK8)`nXCauJM#78%iGPAWYUh~W*^L*`Bi5}DBgt5_KFv4XDUJG@N3`|L-7B%Ki+WvO7oHOtZ9=!Wm z8S586$^?iCtK8nhn!y|mVbxU{vUh&lL{s~wCxa_FS z>i^$h@qb8a9&nuG|J~~9U^eFb=CzDI_mI}BcE(0vTjr$NHQBqe`ccuUHkvJ1Ray^R zNH2=U%GX=WqW*CChiOrM^KSopicy^pIei3%##*VJIVQI{-A&SGkyW%wzD_!4=IYp1 zlFYXNBJzT-*HvnL&NL3aW!WL&te0l3luIvCBI7oO@$XF1~*AaRDVv zRKV5Sg=t`~b}sU*??W!(CYdeMYo7s&^r`o`Dr43Fn==L!Q7nv7x1?yi&QDRZ-N~`_ z4f0HK1=WmvT=43#F|mIxP%b_*YmFC%iQ+QCoeG<1ysQC2TJhV96sk`{<8alf{9sS8QeFZ1l;&a9^%5Cco$p%5E+!igBVnvE|fT^jGbYZhz9n{60b zO0Kucq=KinBg8fgMkYCw)(K`w_Qj)scHz+I5x1Q7Xc#D$956I5HmL4t5g4dcfeh20 zH)(2trF=#*J3bMTnyoQ_rTgk;%gkJrtU)wpG7B-*N_c5E)}#@3)lvq6)K^$pACYvt zXkk^)=&(zJ*>qpc^qU8a&07nN?wzN}Ov|EV$_pv+1}GQBlxHZ*XDDfE_9~if^Gvg3 z?BW`={~xn=P=>J2ddW72?|Jkh1pG275S<+w#$FGuN4hTJKMMS^H(MpU;a)1}Q|t_K z$-f05)Pv;4HT_Lm!3Eu1Y=9nGe3c(CISQDEfL(@oyCwl7;lhD*(bel#pEl28uPz-| z{Anlu1#SHcJafD=wvkG{uJIJvKd~AJ5*#2%rWA0ZtcLaBS4F@&mMv`#hu>o*RKaor z$A`1_&Z<9-+-$2t3~^>vn%$YH085v7l{)dvEuJ%7!xz)KaWOT%ZP_6cg2o;K5D)LuDqB+?{Fl1OT)F%7zzR_Hq~kw7EpWw8|CTp!~w znU_MmZS2IoA8l{>hjS=kAzOU1>HkhmaMvRquMifB0t=%lwvn7>rHz8l!g-OId7=)g z(Wy8lA$>u3oX|_t#{*YK1H8_O5$za+YF)QxTZ&bc1|E}cQ4_N{&u4@SEP2+te8@jn zI-#4@ylE!nrR#ai9&H?2FIP3Va5ay`5^VhKPNGK3)3!RefRTICh4VB%LUt;1_&9p> zkvFgZ@bm{7m^SEsxc?{npGim9fzY_ua%5}3r9zS2Ccz{q5IN3*E55uWL*1-OuA%!F zxFUVClW0&|Zj?luf9lrRt%1o+Cepy1ic4=q9v}h>-n^kVF8#3&tUPKW^>ziSo9v@td*E?f|PuSf0;Or47 zy<=^YKy9p_J5||#*tk6Ozevra3Y|0wRy_$cU2#|OPECMeS3<~3ce`hqJ$h}~nF~Zi zUiq_K_2uO?J%_czxdH0(G~QdZBA&dB8Q!%v;F!yet69mMhVTE(<9Az5!0mOjt0rUf zjgxAdO&6)8jpDu1Uf+GTJ&(TM!o8V1eJspyDau(KDFzj|@JKvGxkyAJ!L{OeuY~Bk zs*k<=MZk_eY!8~oue@N(K5z2nGk87%65@1R z-7o`&(`PCKjrpa7yRJ%3RmjPZ7PC2LjefLy2wb@mWX?RO{?|tSLx*(M?j`d^5#4w1 zAwE>r+fJQd4}I?T_qT$7S(5FtTs3bny^{1=MzrMHv4hm^f0(n(!qQ=C+HEKKsCPB% zryrlwjisrcj2Z3onb8vy(I0+rhV1`Feb!e5(l29st@_sT$XC_PC6qEt@{ff~Sei@% zgj(YHoX*N}{xu6zn;qBiYaf@4jtg}d6EO?GWhWTgey%`uCAPoNLZnvglhl3FIbWee zllH?1}3*P85nK%nj<8-n0cnl#mY03 zKoqcdq6t}7hjq*uX?$LXZ;+SlORdiG&^JaEC%lS@4IDHy-n8i>xCvyc#)?ueT7r*Rj6Ao?7h8~3QBN;M* zfKLR5eg}Uxzut=Ft}EjHwaPBi(dET?Bxon=EgRrENWg)=&Yp=e8E6y>8aXs-f+1-P zTLu?LM6S0TI2h4H$o|b~nyM@(>(>Rxiz-z>N%;+LRUnjO2X00=XUw^%s8F+~%)}En z^}k7&aXg|jY*RMmIk{V}m8)9atkmU~+r9QYspXk58}Vd~uV%g6-ZcRmpA~M+bIev$ z!!3V}?Fbv@8=zR2Vw5yFrUY#-eY|{@*VeZ#1Tw7j7MmrbFLvBaxu#=4d+s$YeUM_`}WSE1+L~n&AE43;_*9q1U*rAAUArKSi%w zg@#cTWH=W)bH=>hY2}v0d7r)O0*0#^9DnDh{r>>H4?>Wq+}Gledn zvpDm>TJv%Z1siknakszNe$Qdvk}=%lxo^C9mAZRY-CmDIp}m@mFA}%K{t=!<`@oGk z{XDGh)hHFAClkoyXU}$XudFV|oMseWh{5`qGZl8zxKH+v)dV&%dVLb~RrQNpx->RC zE1CUH!QbLTP)upbhpATjOoLrFn4?XL-VD>Ujt<;Ml7&Ls9(oxv(aP~94yYXR$rOfY3Kh?8*=&m{^|a2ck-;)L})q$ zTUjzlw@Vcc+}dJTztfApkR@1GT84_N%#9kxbX4L}+O%JE#DRKD{~AZbJ( zXo`qCwVPPIX}jX!xLvd?+v4d;;ypSsUS`HPk}xabUxv;O-=BeENh1yP`(ou=zMYF)-vr&3Hdw1}m(b8Ysgu%a zi)#I7&dJhN7W$2&pzI>s7X@3sD__n3tEX?zP}3R}T*nROK*7#B0$(y(?}DQ6J}4UN zWOBL`#}vPfyE%$gf%~5MVR8LMbhKU44H`5;?ZFgcgeSn!D8OO9p#)3zy| zXVQl+`6=AErX?%Wx7ypv^<qnqaO3H)H<$vru4+f!lC5*O_Dh?$W-}D<}ctS+y+eJek`+siY zbDZ}(==EtFu7fttPSe4r`#3m12ySv-=0HVTV`6F_-F!lcQMAu0Au z>K;xYB+^M0ha`9CWioYmgepJ8(_m#JL2$SvFB-0GFQDTeF(SZoI+qf~kq3f8*^vqM ztJ)(B^0};}Z!Tb4@k#=L5&w@e$*pF~qmh$&2&i7CdV@c1jjG_pS861*?|N4~zu%+# zH2?0eamLJbDBem?G-NCZx*Uh42<^1j&0Qd5usl*ZW=Rvk-Vs1thDn3QXrU`{ho#s3 zK_8*i5?)Zo6;hQ-0hM|R;WU8`*dlRFM^po@#bD42$Mj4M^#3P z5qO6Y@H!=z>YzMJl>}!T6E6r7O;Tk-s(@*7To|}uPsP3wL_7-(@V5DESQJ?ogo%M7 z391!&Q4gPC4aqKfAWD<_6R|td&DM3_L0$L12*O*R#pVs0qH67X?7lI72QAutLmnn8 z$oDs&kOiyu^%hWzeG&OVdhqQL$2%7R3J7L4UpwFb2R$PZ5fYJZ2?gbHfw!)I2hn^7 zZ374DNV#@KKer6&;WJmPV)K7?c+d)m2AM08y+*o6T&)2_F#u5Kmot6`N#v?slZsTo zc*Dm_2`)irv(G~qe>f4~_qlRg!x?o8o`2=O~4n&Ly_c~^f7-$q6k~CzRDxs}dJ*cNr(C$p2 z;f`}GmhIj_Gj`mAeCi79C|^}qle`pQVy?@bAntFNoeQ}Ung~HtSTUWsM!9}ygz*}s zpd^+(^Gs=eqvb1Y|NQ9Y4(_C7i+5Yxc`qYQDcNO|7WxQNq1o}SMez{}df~X%VQF0{ z&aK*X2L4LQFt1ajQ|A#h`<;0>_O((M!U~H}!6aL}?2FoK0XyJN6BM^sZYWHvgV-&) z)-k8^l`qAgKQ5>N!_wW}Oc>(U)?TmmMUOD1*f16bsFIu(rX28bwyx0l_vu2~QhFqc z>h~BIFacI*fP%z75KYz%I?ZIqUH^#Ow#s)4YNURmpPPcSMxs}{*C%DueU8aUo$lLf z#7OFeiTL(8lm^T5l}qZOT}@Bpr6(eVN^zKKX!ihp+KrpW;HRBTMv%bAtY=H%u6I(U zpk^K^>W>N}98|w;j2gzNa{Csb`M&7iYMNZmUq?|=Kqx>A*oO9rYz}97w+r`&lw0d) zUt8LFbnTn7&NQ@7#k{|Iq{SiZe`n#J`$9)|Mo{&|ymjwZo6#^dfU(&sC;JLpYl4UN z)4VA%EAvI27}|6!pHE!n2^-Tf&a4pr=ht};rV}L_5!z~O=z-5F=?byNfW5<`8SfLI zR;AB$Jd8=Xlb)Ld)qpP(83s$)8%opzAYQNb1eUUCM23&|HW;09zchWs{odPwQV}g- z8tS5S-rD4zr)9EdnQ&{gLqadNuC<;%d;KHdD}4eum(`y=&T0D^#^q&z&bls=5LL}5 z?ipZn*0n~C>7c1^GLeb9dfu%U^xveIns{|2v#EHcH&CW+>+%FVsT69vscQVe!uH0k z=`XTo1;^-8OJ^?})xKQ;R660nwGO(?mOK)w0sOibyNq?ikiN+aw3N)NxzGIGU!E^H zOkxfq++reY<47c=Ejy~?q5_EGC_4@)AZy!yM4u=N9OMkU*eTh3Es>(4kHyW<8EvHZ zAjLmZ4V}CjM%mqfSBOva`{&KR>?^-LY$|eEfoAPKGE=~}-=!!tr&xH6W$49%$cGKP z`#N7gt4Kd6UTI=`B6MB4_hnA=^RLu~rOxrxFFCNjQqk%l6<_hoLd9|tQ9Va%giwTv z1erv3D%UCNnhuDU0E2>~c+I+^Ej#sUNMtEZoDg%a>Pdp3Lt>CrS=q`v*{%2&&VBR! z_%m!kSPQY*)3i0+7Kl5H60HOtwT-{7aXT^%@XAAeWrTGMfU&~Z8o!gO2vvW(pC zqsG(VhI0&9&%K-vSv+i7W6Exb!yINIaX&(^={{l_!gvbs=^HLMb=V)Li%^eBexPWV zzX})Pv19J-)Cj4Rv%OdOVO=Ll<7AgX-;in;a?kO}rC=&Wp$tjFq>gVHU+qI^s|L$( zrDONbP{e~dWT?YcVN;(DFjU<~N;_AOV%a=$`2$9>YX-g{5S0Fz*RV?^`a1}Yo0mo_ zHhvcKzS>uA$Ba~L^fHc*(M-#m0+G|y^R=g!*!xTo(VZQr4}V;9T2zQupT$Oz0sYSYu#AO&#B_0{af#DRR$0+*_moQS*`CVZw4$ z5n%M_p@Skgh+8yBl*uChbl~93+3@6QkUAzl4S&0@jwkT+$kmXkRK*)>=F00<)bT4% zIACH-cqsgVh8-KVa=XXFLd)G>WMkh!(1>gT*T#m;51!)tWA5W=;v*fUpsMkc!4c5y z)n%bJ9;-v;GOtEO)Pmhb97F>+6B#z~lp(L8*Ggt=lik&tWB#jC(0&yT!2jypX z_#QcnLr>7#r^UlXA=>tntpw}&BbI^ZFXomD6d(?3Y2kV`y|uHEody)r`iylt1o$O2 z-ZEqU<5(%bA#ZM%0+pxgB^@8<{VuCQ@dY=vL|gl!q*Lx<0^Kbkj5Pr;gYKQNe&E%3 z9XMs75*;nBAQ!{W?-xd7prf>uG5ZgYc@zDHGfblwBr2lqaJUC!WCGguQxC#N6#`<9 z`9lyr%A$Xf!Hp=8CQ~WTRCjcUfmeebQw74Dp zIb(kt-OHecRVT^G1=3-tf;NRKGi;6S(2ATT1Ww_mhbX>pwisU56~ev17AZQFudI!s z!|5$H++@QEavk!Kh{7IWzVNkf{Wt_=KVW@@ zJ7M@x5{-*gvzcc@SSQBz5m(hyQ0#oLUF~*qVcQ%siV)ugJXvAoiCunlKoXflsT8ve z6194vaGSl?((<38&18bt3F2x9bauN;cpJNx z2oNOgXbe_8f%@YOd1j)8au>s^cwmdTrp5JVe!cT{Z#n-^2&8QS9b?0vd3N(R{`|$p z|D~b;*3KI~m)Cw*4H3I5SKNrP9f?&qPPBt@QJaRDnHhl^s*Wsf_R(>`waU}^Ml!;D zdEYSu7tAcLDOvThLq5y>P({3Ypz^hAY?_oL3cX`h^jz{ji`{YbT!Nra5|HcyZM5$Y z>0L-EUA`t@rm+!$VM##a{`OGdk2%WY7UhyomO$f71Tr7co~UY;tu#zu#Ymegdpx{E z;{@xApD;V!do_3}mE*>XABC20>v&}T+eOz}9}1l2Kd3%-PG25@*UJ44LR~q+INWjW zi_^X!TSDRdH@x9Of-d9==`w#mMc>6<0Cj%sPi}&zkS;z?emFU|hv7?iho^z4F%6mO zl{B%_(8a!8AG#`0jw|fBykhy9Sd($#Sgiuy)I({<+?Mf{bcPofF}!SWa@f-J$ST_aAp;8URPScJZgtiLShKB1%Jwy?*hJU#l|2g|Ni(kCnd6Lk~Uz|b3Ri= za|OpZcgI^d@~Lxx*_egKN#=ifK<&O7L*JB)5uvJ$c2d4~A83PRcJ@bGKaR^s8?uW- zxfH%;z<*!21EKfmkyf^H_{NH^-;}t-(=Zx)#Q7&rb z=S#Mv|7xr9w&n}FAO5#??7uK=e-z>Tv;S)M7Nj3qq&d7f^v3KY&l6dvf=KVdczIZo zY!gpq{IehfB<`OUWAW0k-us3W zY@cs+(p`^5SmZTyBTr943dTLSSN#QcDG13+XYtag3?zYPJl@anh<4|KF53w$k;95|Cm)ug&b)S(q(FdgJxf)w z2k>6_Lty6)P$H9(?gIHZQ<=1DpTr?i(_2~~7*+q3c8RNm5K49WcNedl9D@u+fPw+eT9rFszwo!bVH7Sr@*;;$~6$wexLrJ#w6a_Ldh_}05_Vb3vSqL0^3UhKNUr8u(U7n95QE~)+Id>1nX{}pLBB!a4m6M8dMvs2^d`>&}LE)^%wyqN{`Pk2>Q6petB zQ^Xiaa$NOBhbP%J^~nTSY{0g46U7qG)`V-_D$^T+2Vri%igY(Nq+Ho0f$;`KlE