From 98bbfb73d8c7ded641b1bedbd49f87c6ac8f99dd Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Sat, 30 Jul 2022 07:56:43 -1000 Subject: [PATCH 001/134] Enable printing of WiFi IP address by default --- Firmware/RTK_Surveyor/settings.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index cec82d09f..c841e3433 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -424,7 +424,7 @@ typedef struct { int8_t timeZoneSeconds = 0; //Debug settings - bool enablePrintWifiIpAddress = false; + bool enablePrintWifiIpAddress = true; bool enablePrintState = false; bool enablePrintWifiState = false; bool enablePrintNtripClientState = false; From 71744d7b2a9a662f5da8eb21f86d5ef65a4ebbf3 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Sat, 30 Jul 2022 18:41:36 -1000 Subject: [PATCH 002/134] Add printTimeStamp to support.ino --- Firmware/RTK_Surveyor/support.ino | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/Firmware/RTK_Surveyor/support.ino b/Firmware/RTK_Surveyor/support.ino index 247006f12..20369b17d 100644 --- a/Firmware/RTK_Surveyor/support.ino +++ b/Firmware/RTK_Surveyor/support.ino @@ -405,3 +405,29 @@ byte readLine(char* buffer, byte bufferLength, int numberOfSeconds) return readLength; } + +#define TIMESTAMP_INTERVAL 1000 //Milliseconds + +//Print the timestamp +void printTimeStamp() +{ + uint32_t currentMilliseconds; + static uint32_t previousMilliseconds; + + //Timestamp the messages + currentMilliseconds = millis(); + if ((currentMilliseconds - previousMilliseconds) >= TIMESTAMP_INTERVAL) + { + // 1 2 3 + //123456789012345678901234567890 + //YYYY-mm-dd HH:MM:SS.xxxrn0 + struct tm timeinfo = rtc.getTimeStruct(); + char timestamp[30]; + strftime(timestamp, sizeof(timestamp), "%Y-%m-%d %H:%M:%S", &timeinfo); + Serial.printf("%s.%03ld\r\n", timestamp, rtc.getMillis()); + + //Select the next time to display the timestamp + previousMilliseconds = currentMilliseconds; + } +} + From d869176f68ef20785e13d318082845033a7b21c9 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Sun, 31 Jul 2022 08:20:44 -1000 Subject: [PATCH 003/134] Add debug menu items to print messages Add debug menu items to print: * Battery messages * Rover Accuracy messages * Messages with bad checksums or CRCs * Log file messages * Ring buffer offsets * NTRIP server messages (already in debug menu) * NTRIP client messages * States of the main state machine * Duplicate states of the main state machine --- Firmware/RTK_Surveyor/NVM.ino | 34 +++++++++-- Firmware/RTK_Surveyor/menuSystem.ino | 87 ++++++++++++++++++++++++---- Firmware/RTK_Surveyor/settings.h | 11 +++- 3 files changed, 115 insertions(+), 17 deletions(-) diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index 24cf983b7..4380f2d44 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -238,9 +238,18 @@ void recordSystemSettingsToFile(File * settingsFile) settingsFile->printf("%s=%d\n\r", "enablePrintWifiState", settings.enablePrintWifiState); settingsFile->printf("%s=%d\n\r", "enablePrintNtripClientState", settings.enablePrintNtripClientState); settingsFile->printf("%s=%d\n\r", "enablePrintNtripServerState", settings.enablePrintNtripServerState); - settingsFile->printf("%s=%d\n\r", "enablePrintNtripServerRtcm", settings.enablePrintNtripServerRtcm); settingsFile->printf("%s=%d\n\r", "enablePrintPosition", settings.enablePrintPosition); settingsFile->printf("%s=%d\n\r", "enableMarksFile", settings.enableMarksFile); + settingsFile->printf("%s=%d\n\r", "enablePrintBatteryMessages", settings.enablePrintBatteryMessages); + settingsFile->printf("%s=%d\n\r", "enablePrintRoverAccuracy", settings.enablePrintRoverAccuracy); + settingsFile->printf("%s=%d\n\r", "enablePrintBadMessages", settings.enablePrintBadMessages); + settingsFile->printf("%s=%d\n\r", "enablePrintLogFileMessages", settings.enablePrintLogFileMessages); + settingsFile->printf("%s=%d\n\r", "enablePrintLogFileStatus", settings.enablePrintLogFileStatus); + settingsFile->printf("%s=%d\n\r", "enablePrintRingBufferOffsets", settings.enablePrintRingBufferOffsets); + settingsFile->printf("%s=%d\n\r", "enablePrintNtripServerRtcm", settings.enablePrintNtripServerRtcm); + settingsFile->printf("%s=%d\n\r", "enablePrintNtripClientRtcm", settings.enablePrintNtripClientRtcm); + settingsFile->printf("%s=%d\n\r", "enablePrintStates", settings.enablePrintStates); + settingsFile->printf("%s=%d\n\r", "enablePrintDuplicateStates", settings.enablePrintDuplicateStates); //Record constellation settings for (int x = 0 ; x < MAX_CONSTELLATIONS ; x++) @@ -809,11 +818,28 @@ bool parseLine(char* str, Settings *settings) settings->enablePrintNtripClientState = d; else if (strcmp(settingName, "enablePrintNtripServerState") == 0) settings->enablePrintNtripServerState = d; - else if (strcmp(settingName, "enablePrintNtripServerRtcm") == 0) - settings->enablePrintNtripServerRtcm = d; else if (strcmp(settingName, "enablePrintPosition") == 0) settings->enablePrintPosition = d; - + else if (strcmp(settingName, "enablePrintBatteryMessages") == 0) + settings->enablePrintBatteryMessages = d; + else if (strcmp(settingName, "enablePrintRoverAccuracy") == 0) + settings->enablePrintRoverAccuracy = d; + else if (strcmp(settingName, "enablePrintBadMessages") == 0) + settings->enablePrintBadMessages = d; + else if (strcmp(settingName, "enablePrintLogFileMessages") == 0) + settings->enablePrintLogFileMessages = d; + else if (strcmp(settingName, "enablePrintLogFileStatus") == 0) + settings->enablePrintLogFileStatus = d; + else if (strcmp(settingName, "enablePrintRingBufferOffsets") == 0) + settings->enablePrintRingBufferOffsets = d; + else if (strcmp(settingName, "enablePrintNtripServerRtcm") == 0) + settings->enablePrintNtripServerRtcm = d; + else if (strcmp(settingName, "enablePrintNtripClientRtcm") == 0) + settings->enablePrintNtripClientRtcm = d; + else if (strcmp(settingName, "enablePrintStates") == 0) + settings->enablePrintStates = d; + else if (strcmp(settingName, "enablePrintDuplicateStates") == 0) + settings->enablePrintDuplicateStates = d; //Check for bulk settings (constellations and message rates) //Must be last on else list else diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index f3cb70cd1..b5576be30 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -324,16 +324,43 @@ void menuDebug() Serial.print("14) Periodically print NTRIP server state: "); Serial.printf("%s\r\n", settings.enablePrintNtripServerState ? "Enabled" : "Disabled"); - Serial.print("15) Print GNSS --> NTRIP caster messages: "); - Serial.printf("%s\r\n", settings.enablePrintNtripServerRtcm ? "Enabled" : "Disabled"); - - Serial.print("16) Periodically print position: "); + Serial.print("15) Periodically print position: "); Serial.printf("%s\r\n", settings.enablePrintPosition ? "Enabled" : "Disabled"); - Serial.print("17) Periodically print CPU idle time: "); + Serial.print("16) Periodically print CPU idle time: "); Serial.printf("%s\r\n", settings.enablePrintIdleTime ? "Enabled" : "Disabled"); - Serial.println("18) Mirror ZED-F9x's UART1 settings to USB"); + Serial.println("17) Mirror ZED-F9x's UART1 settings to USB"); + + Serial.print("18) Print battery status messages: "); + Serial.printf("%s\r\n", settings.enablePrintBatteryMessages ? "Enabled" : "Disabled"); + + Serial.print("19) Print Rover accuracy messages: "); + Serial.printf("%s\r\n", settings.enablePrintRoverAccuracy ? "Enabled" : "Disabled"); + + Serial.print("20) Print messages with bad checksums or CRCs: "); + Serial.printf("%s\r\n", settings.enablePrintBadMessages ? "Enabled" : "Disabled"); + + Serial.print("21) Print log file messages: "); + Serial.printf("%s\r\n", settings.enablePrintLogFileMessages ? "Enabled" : "Disabled"); + + Serial.print("22) Print log file status: "); + Serial.printf("%s\r\n", settings.enablePrintLogFileStatus ? "Enabled" : "Disabled"); + + Serial.print("23) Print ring buffer offsets: "); + Serial.printf("%s\r\n", settings.enablePrintRingBufferOffsets ? "Enabled" : "Disabled"); + + Serial.print("24) Print GNSS --> NTRIP caster messages: "); + Serial.printf("%s\r\n", settings.enablePrintNtripServerRtcm ? "Enabled" : "Disabled"); + + Serial.print("25) Print NTRIP caster --> GNSS messages: "); + Serial.printf("%s\r\n", settings.enablePrintNtripClientRtcm ? "Enabled" : "Disabled"); + + Serial.print("26) Print states: "); + Serial.printf("%s\r\n", settings.enablePrintStates ? "Enabled" : "Disabled"); + + Serial.print("27) Print duplicate states: "); + Serial.printf("%s\r\n", settings.enablePrintDuplicateStates ? "Enabled" : "Disabled"); Serial.println("t) Enter Test Screen"); @@ -456,18 +483,14 @@ void menuDebug() settings.enablePrintNtripServerState ^= 1; } else if (incoming == 15) - { - settings.enablePrintNtripServerRtcm ^= 1; - } - else if (incoming == 16) { settings.enablePrintPosition ^= 1; } - else if (incoming == 17) + else if (incoming == 16) { settings.enablePrintIdleTime ^= 1; } - else if (incoming == 18) + else if (incoming == 17) { bool response = configureGNSSMessageRates(COM_PORT_USB, settings.ubxMessages); //Make sure the appropriate messages are enabled response &= i2cGNSS.setPortOutput(COM_PORT_USB, COM_TYPE_NMEA | COM_TYPE_UBX | COM_TYPE_RTCM3); //Duplicate UART1 @@ -477,6 +500,46 @@ void menuDebug() else Serial.println(F("USB messages successfully enabled")); } + else if (incoming == 18) + { + settings.enablePrintBatteryMessages ^= 1; + } + else if (incoming == 19) + { + settings.enablePrintRoverAccuracy ^= 1; + } + else if (incoming == 20) + { + settings.enablePrintBadMessages ^= 1; + } + else if (incoming == 21) + { + settings.enablePrintLogFileMessages ^= 1; + } + else if (incoming == 22) + { + settings.enablePrintLogFileStatus ^= 1; + } + else if (incoming == 23) + { + settings.enablePrintRingBufferOffsets ^= 1; + } + else if (incoming == 24) + { + settings.enablePrintNtripServerRtcm ^= 1; + } + else if (incoming == 25) + { + settings.enablePrintNtripClientRtcm ^= 1; + } + else if (incoming == 26) + { + settings.enablePrintStates ^= 1; + } + else if (incoming == 27) + { + settings.enablePrintDuplicateStates ^= 1; + } else printUnknown(incoming); } diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index fc5cbb378..d2e63a4cf 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -429,9 +429,18 @@ typedef struct { bool enablePrintWifiState = false; bool enablePrintNtripClientState = false; bool enablePrintNtripServerState = false; - bool enablePrintNtripServerRtcm = false; bool enablePrintPosition = false; bool enablePrintIdleTime = false; + bool enablePrintBatteryMessages = true; + bool enablePrintRoverAccuracy = true; + bool enablePrintBadMessages = false; + bool enablePrintLogFileMessages = false; + bool enablePrintLogFileStatus = true; + bool enablePrintRingBufferOffsets = false; + bool enablePrintNtripServerRtcm = false; + bool enablePrintNtripClientRtcm = false; + bool enablePrintStates = true; + bool enablePrintDuplicateStates = false; } Settings; Settings settings; From b2ae0db95e34cc5f52f5baf73a6912546ef403da Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Mon, 1 Aug 2022 15:44:54 -1000 Subject: [PATCH 004/134] Enable/disable printing of states and duplicate states --- Firmware/RTK_Surveyor/States.ino | 237 ++++++++++++++++--------------- 1 file changed, 122 insertions(+), 115 deletions(-) diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 21943d51b..784e46792 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -931,125 +931,132 @@ void changeState(SystemState newState) //Log the heap size at the state change reportHeapNow(); + //Debug print of new state, add leading asterisk for repeated states + if ((!settings.enablePrintDuplicateStates) && (newState == systemState)) + return; + + if (settings.enablePrintStates && (newState == systemState)) + Serial.print("*"); + //Set the new state systemState = newState; - //Debug print of new state, add leading asterisk for repeated states - if (newState == systemState) - Serial.print("*"); - switch (systemState) + if (settings.enablePrintStates) { - case (STATE_ROVER_NOT_STARTED): - Serial.print("State: Rover - Not Started"); - break; - case (STATE_ROVER_NO_FIX): - Serial.print("State: Rover - No Fix"); - break; - case (STATE_ROVER_FIX): - Serial.print("State: Rover - Fix"); - break; - case (STATE_ROVER_RTK_FLOAT): - Serial.print("State: Rover - RTK Float"); - break; - case (STATE_ROVER_RTK_FIX): - Serial.print("State: Rover - RTK Fix"); - break; - case (STATE_BASE_NOT_STARTED): - Serial.print("State: Base - Not Started"); - break; - case (STATE_BASE_TEMP_SETTLE): - Serial.print("State: Base-Temp - Settle"); - break; - case (STATE_BASE_TEMP_SURVEY_STARTED): - Serial.print("State: Base-Temp - Survey Started"); - break; - case (STATE_BASE_TEMP_TRANSMITTING): - Serial.print("State: Base-Temp - Transmitting"); - break; - case (STATE_BASE_FIXED_NOT_STARTED): - Serial.print("State: Base-Fixed - Not Started"); - break; - case (STATE_BASE_FIXED_TRANSMITTING): - Serial.print("State: Base-Fixed - Transmitting"); - break; - case (STATE_BUBBLE_LEVEL): - Serial.print("State: Bubble level"); - break; - case (STATE_MARK_EVENT): - Serial.print("State: Mark Event"); - break; - case (STATE_DISPLAY_SETUP): - Serial.print("State: Display Setup"); - break; - case (STATE_WIFI_CONFIG_NOT_STARTED): - Serial.print("State: WiFi Config Not Started"); - break; - case (STATE_WIFI_CONFIG): - Serial.print("State: WiFi Config"); - break; - case (STATE_TEST): - Serial.print("State: System Test Setup"); - break; - case (STATE_TESTING): - Serial.print("State: System Testing"); - break; - case (STATE_PROFILE): - Serial.print("State: Profile"); - break; - case (STATE_KEYS_STARTED): - Serial.print("State: Keys Started "); - break; - case (STATE_KEYS_NEEDED): - Serial.print("State: Keys Needed"); - break; - case (STATE_KEYS_WIFI_STARTED): - Serial.print("State: Keys WiFi Started"); - break; - case (STATE_KEYS_WIFI_CONNECTED): - Serial.print("State: Keys WiFi Connected"); - break; - case (STATE_KEYS_WIFI_TIMEOUT): - Serial.print("State: Keys WiFi Timeout"); - break; - case (STATE_KEYS_EXPIRED): - Serial.print("State: Keys Expired"); - break; - case (STATE_KEYS_DAYS_REMAINING): - Serial.print("State: Keys Days Remaining"); - break; - case (STATE_KEYS_LBAND_CONFIGURE): - Serial.print("State: Keys L-Band Configure"); - break; - case (STATE_KEYS_LBAND_ENCRYPTED): - Serial.print("State: Keys L-Band Encrypted"); - break; - case (STATE_KEYS_PROVISION_WIFI_STARTED): - Serial.print("State: Keys Provision - WiFi Started"); - break; - case (STATE_KEYS_PROVISION_WIFI_CONNECTED): - Serial.print("State: Keys Provision - WiFi Connected"); - break; - case (STATE_KEYS_PROVISION_WIFI_TIMEOUT): - Serial.print("State: Keys Provision - WiFi Timeout"); - break; - - case (STATE_SHUTDOWN): - Serial.print("State: Shut Down"); - break; - default: - Serial.printf("Change State Unknown: %d", systemState); - break; - } + switch (systemState) + { + case (STATE_ROVER_NOT_STARTED): + Serial.print("State: Rover - Not Started"); + break; + case (STATE_ROVER_NO_FIX): + Serial.print("State: Rover - No Fix"); + break; + case (STATE_ROVER_FIX): + Serial.print("State: Rover - Fix"); + break; + case (STATE_ROVER_RTK_FLOAT): + Serial.print("State: Rover - RTK Float"); + break; + case (STATE_ROVER_RTK_FIX): + Serial.print("State: Rover - RTK Fix"); + break; + case (STATE_BASE_NOT_STARTED): + Serial.print("State: Base - Not Started"); + break; + case (STATE_BASE_TEMP_SETTLE): + Serial.print("State: Base-Temp - Settle"); + break; + case (STATE_BASE_TEMP_SURVEY_STARTED): + Serial.print("State: Base-Temp - Survey Started"); + break; + case (STATE_BASE_TEMP_TRANSMITTING): + Serial.print("State: Base-Temp - Transmitting"); + break; + case (STATE_BASE_FIXED_NOT_STARTED): + Serial.print("State: Base-Fixed - Not Started"); + break; + case (STATE_BASE_FIXED_TRANSMITTING): + Serial.print("State: Base-Fixed - Transmitting"); + break; + case (STATE_BUBBLE_LEVEL): + Serial.print("State: Bubble level"); + break; + case (STATE_MARK_EVENT): + Serial.print("State: Mark Event"); + break; + case (STATE_DISPLAY_SETUP): + Serial.print("State: Display Setup"); + break; + case (STATE_WIFI_CONFIG_NOT_STARTED): + Serial.print("State: WiFi Config Not Started"); + break; + case (STATE_WIFI_CONFIG): + Serial.print("State: WiFi Config"); + break; + case (STATE_TEST): + Serial.print("State: System Test Setup"); + break; + case (STATE_TESTING): + Serial.print("State: System Testing"); + break; + case (STATE_PROFILE): + Serial.print("State: Profile"); + break; + case (STATE_KEYS_STARTED): + Serial.print("State: Keys Started "); + break; + case (STATE_KEYS_NEEDED): + Serial.print("State: Keys Needed"); + break; + case (STATE_KEYS_WIFI_STARTED): + Serial.print("State: Keys WiFi Started"); + break; + case (STATE_KEYS_WIFI_CONNECTED): + Serial.print("State: Keys WiFi Connected"); + break; + case (STATE_KEYS_WIFI_TIMEOUT): + Serial.print("State: Keys WiFi Timeout"); + break; + case (STATE_KEYS_EXPIRED): + Serial.print("State: Keys Expired"); + break; + case (STATE_KEYS_DAYS_REMAINING): + Serial.print("State: Keys Days Remaining"); + break; + case (STATE_KEYS_LBAND_CONFIGURE): + Serial.print("State: Keys L-Band Configure"); + break; + case (STATE_KEYS_LBAND_ENCRYPTED): + Serial.print("State: Keys L-Band Encrypted"); + break; + case (STATE_KEYS_PROVISION_WIFI_STARTED): + Serial.print("State: Keys Provision - WiFi Started"); + break; + case (STATE_KEYS_PROVISION_WIFI_CONNECTED): + Serial.print("State: Keys Provision - WiFi Connected"); + break; + case (STATE_KEYS_PROVISION_WIFI_TIMEOUT): + Serial.print("State: Keys Provision - WiFi Timeout"); + break; - if (online.rtc) - { - //Timestamp the state change - // 1 2 - //12345678901234567890123456 - //YYYY-mm-dd HH:MM:SS.xxxrn0 - struct tm timeinfo = rtc.getTimeStruct(); - char s[30]; - strftime(s, sizeof(s), "%Y-%m-%d %H:%M:%S", &timeinfo); - Serial.printf(", %s.%03ld\r\n", s, rtc.getMillis()); + case (STATE_SHUTDOWN): + Serial.print("State: Shut Down"); + break; + default: + Serial.printf("Change State Unknown: %d", systemState); + break; + } + + if (online.rtc) + { + //Timestamp the state change + // 1 2 + //12345678901234567890123456 + //YYYY-mm-dd HH:MM:SS.xxxrn0 + struct tm timeinfo = rtc.getTimeStruct(); + char s[30]; + strftime(s, sizeof(s), "%Y-%m-%d %H:%M:%S", &timeinfo); + Serial.printf(", %s.%03ld\r\n", s, rtc.getMillis()); + } } } From ee35cfb1a7b994c13adf8ff0b6fe79e450703d61 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Sun, 31 Jul 2022 08:39:32 -1000 Subject: [PATCH 005/134] Enable/disable printing of battery status messages --- Firmware/RTK_Surveyor/System.ino | 37 +++++++++++++++++--------------- 1 file changed, 20 insertions(+), 17 deletions(-) diff --git a/Firmware/RTK_Surveyor/System.ino b/Firmware/RTK_Surveyor/System.ino index 271ae9bcc..fb88b501f 100644 --- a/Firmware/RTK_Surveyor/System.ino +++ b/Firmware/RTK_Surveyor/System.ino @@ -346,25 +346,28 @@ void checkBatteryLevels() battVoltage = lipo.getVoltage(); battChangeRate = lipo.getChangeRate(); - Serial.printf("Batt (%d%%): Voltage: %0.02fV", battLevel, battVoltage); + if (settings.enablePrintBatteryMessages) + { + Serial.printf("Batt (%d%%): Voltage: %0.02fV", battLevel, battVoltage); - char tempStr[25]; - if (battChangeRate > 0) - sprintf(tempStr, "C"); - else - sprintf(tempStr, "Disc"); - Serial.printf(" %sharging: %0.02f%%/hr ", tempStr, battChangeRate); - - if (battLevel < 10) - sprintf(tempStr, "Red"); - else if (battLevel < 50) - sprintf(tempStr, "Yellow"); - else if (battLevel >= 50) - sprintf(tempStr, "Green"); - else - sprintf(tempStr, "No batt"); + char tempStr[25]; + if (battChangeRate > 0) + sprintf(tempStr, "C"); + else + sprintf(tempStr, "Disc"); + Serial.printf(" %sharging: %0.02f%%/hr ", tempStr, battChangeRate); + + if (battLevel < 10) + sprintf(tempStr, "Red"); + else if (battLevel < 50) + sprintf(tempStr, "Yellow"); + else if (battLevel >= 50) + sprintf(tempStr, "Green"); + else + sprintf(tempStr, "No batt"); - Serial.printf("%s\n\r", tempStr); + Serial.printf("%s\n\r", tempStr); + } if (productVariant == RTK_SURVEYOR) { From 5d7a211923026dfb3672ff31523ed0d26218ee4d Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Sun, 31 Jul 2022 08:43:20 -1000 Subject: [PATCH 006/134] Enable/disable printing of Rover Accuracy messages --- Firmware/RTK_Surveyor/Rover.ino | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/Firmware/RTK_Surveyor/Rover.ino b/Firmware/RTK_Surveyor/Rover.ino index 6dc05cf99..99dd6a4cb 100644 --- a/Firmware/RTK_Surveyor/Rover.ino +++ b/Firmware/RTK_Surveyor/Rover.ino @@ -269,9 +269,12 @@ void updateAccuracyLEDs() { if (horizontalAccuracy > 0) { - Serial.print("Rover Accuracy (m): "); - Serial.print(horizontalAccuracy, 4); // Print the accuracy with 4 decimal places - Serial.println(); + if (settings.enablePrintRoverAccuracy) + { + Serial.print("Rover Accuracy (m): "); + Serial.print(horizontalAccuracy, 4); // Print the accuracy with 4 decimal places + Serial.println(); + } if (productVariant == RTK_SURVEYOR) { @@ -301,7 +304,7 @@ void updateAccuracyLEDs() } } } - else + else if (settings.enablePrintRoverAccuracy) { Serial.print("Rover Accuracy: "); Serial.print(horizontalAccuracy); From b7dc1e2abf02b21e861df8a54f83c4123bdc5e90 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Mon, 1 Aug 2022 15:59:11 -1000 Subject: [PATCH 007/134] Enable/disable printing of log file status messages --- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 37 ++++++++++++++------------ 1 file changed, 20 insertions(+), 17 deletions(-) diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 35fecf979..36c79e289 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -675,7 +675,7 @@ void updateLogs() } //Report file sizes to show recording is working - if (millis() - lastFileReport > 5000) + if ((millis() - lastFileReport) > 5000) { long fileSize = 0; @@ -696,25 +696,28 @@ void updateLogs() if (fileSize > 0) { lastFileReport = millis(); - Serial.printf("UBX file size: %ld", fileSize); - - if ((systemTime_minutes - startLogTime_minutes) < settings.maxLogTime_minutes) + if (settings.enablePrintLogFileStatus) { - //Calculate generation and write speeds every 5 seconds - uint32_t fileSizeDelta = fileSize - lastLogSize; - Serial.printf(" - Generation rate: %0.1fkB/s", fileSizeDelta / 5.0 / 1000.0); - - if (totalWriteTime > 0) - Serial.printf(" - Write speed: %0.1fkB/s", fileSizeDelta / (totalWriteTime / 1000000.0) / 1000.0); + Serial.printf("UBX file size: %ld", fileSize); + + if ((systemTime_minutes - startLogTime_minutes) < settings.maxLogTime_minutes) + { + //Calculate generation and write speeds every 5 seconds + uint32_t fileSizeDelta = fileSize - lastLogSize; + Serial.printf(" - Generation rate: %0.1fkB/s", fileSizeDelta / 5.0 / 1000.0); + + if (totalWriteTime > 0) + Serial.printf(" - Write speed: %0.1fkB/s", fileSizeDelta / (totalWriteTime / 1000000.0) / 1000.0); + else + Serial.printf(" - Write speed: 0.0kB/s"); + } else - Serial.printf(" - Write speed: 0.0kB/s"); - } - else - { - Serial.printf(" reached max log time %d", settings.maxLogTime_minutes); - } + { + Serial.printf(" reached max log time %d", settings.maxLogTime_minutes); + } - Serial.println(); + Serial.println(); + } totalWriteTime = 0; //Reset write time every 5s From dd40f2b9d47ebbaa85e3540c2b32d612f80d2b29 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 2 Aug 2022 10:34:40 -0500 Subject: [PATCH 008/134] Create workflow for RC binary creation --- .github/workflows/compile-rc.yml | 73 ++++++++++++++++++++++++++ Firmware/RTK_Surveyor/RTK_Surveyor.ino | 15 ++---- Firmware/RTK_Surveyor/settings.h | 24 +++++++++ 3 files changed, 102 insertions(+), 10 deletions(-) create mode 100644 .github/workflows/compile-rc.yml diff --git a/.github/workflows/compile-rc.yml b/.github/workflows/compile-rc.yml new file mode 100644 index 000000000..b51df06a0 --- /dev/null +++ b/.github/workflows/compile-rc.yml @@ -0,0 +1,73 @@ +name: Build Release Candidate +on: + workflow_dispatch: + branches: + - release_candidate + +env: + FILENAME_PREFIX: RTK_Surveyor_Firmware_ + RC_PREFIX: RC- + POINTPERFECT_TOKEN: ${{ secrets.POINTPERFECT_TOKEN }} + +jobs: + build: + + name: Build + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@master + + - name: Setup Arduino CLI + uses: arduino/setup-arduino-cli@v1 + + #We limit the ESP32 core to v2.0.2 + - name: Install platform + run: arduino-cli core install esp32:esp32@2.0.2 + --additional-urls 'https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json' + + - name: Start config file + run: arduino-cli config init + + - name: Enable external libs + run: arduino-cli config set library.enable_unsafe_install true + + - name: Get Libraries + run: arduino-cli lib install --git-url + https://github.com/fbiego/ESP32Time.git + https://github.com/me-no-dev/ESPAsyncWebServer.git + https://github.com/me-no-dev/AsyncTCP.git + https://github.com/JChristensen/JC_Button.git + https://github.com/greiman/SdFat.git + https://github.com/sparkfun/SparkFun_u-blox_GNSS_Arduino_Library.git + https://github.com/sparkfun/SparkFun_MAX1704x_Fuel_Gauge_Arduino_Library.git + https://github.com/sparkfun/SparkFun_Qwiic_OLED_Arduino_Library.git + https://github.com/sparkfun/SparkFun_LIS2DH12_Arduino_Library.git + https://github.com/bblanchon/ArduinoJson.git + https://github.com/knolleary/pubsubclient.git + + - name: Compile Sketch + run: arduino-cli compile --fqbn esp32:esp32:esp32 ./Firmware/RTK_Surveyor/RTK_Surveyor.ino + --build-property build.partitions=partitions + --build-property upload.maximum_size=3145728 + --export-binaries + --build-property DebugLevel.debug.build.code_debug=4 + --build-property "compiler.cpp.extra_flags=\"-DPOINTPERFECT_TOKEN=$POINTPERFECT_TOKEN\"" + + - name: Get current date + id: date + run: echo "::set-output name=date::$(date +'%b_%d_%Y')" + + - name: Rename binary + run: | + cd Firmware/RTK_Surveyor + cd build + cd esp32.esp32.esp32 + mv RTK_Surveyor.ino.bin ${{ env.FILENAME_PREFIX }}${{ env.RC_PREFIX }}${{ steps.date.outputs.date }}.bin + + - name: Upload binary to action + uses: actions/upload-artifact@v3 + with: + name: ${{ env.FILENAME_PREFIX }}${{ env.RC_PREFIX }}${{ steps.date.outputs.date }} + path: ./Firmware/RTK_Surveyor/build/esp32.esp32.esp32/${{ env.FILENAME_PREFIX }}${{ env.RC_PREFIX }}${{ steps.date.outputs.date }}.bin diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index da1240e8e..413316763 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -324,18 +324,13 @@ unsigned long timeSinceLastIncomingSetting = 0; SFE_UBLOX_GNSS_ADD i2cLBand; // NEO-D9S const char* pointPerfectKeyTopic = "/pp/ubx/0236/Lb"; -#if __has_include("tokens.h") -#include "tokens.h" -#else -uint8_t pointPerfectTokenArray[] = {0xAA, 0xBB, 0xCC, 0xDD, 0x00, 0x11, 0x22, 0x33, 0x0A, 0x0B, 0x0C, 0x0D, 0x00, 0x01, 0x02, 0x03}; //Token in HEX form - -static const char *AWS_PUBLIC_CERT = R"=====( ------BEGIN CERTIFICATE----- -Certificate here ------END CERTIFICATE----- -)====="; +//The PointPerfect token is provided at compile time via build flags +#ifndef POINTPERFECT_TOKEN +#define POINTPERFECT_TOKEN 0xAA, 0xBB, 0xCC, 0xDD, 0x00, 0x11, 0x22, 0x33, 0x0A, 0x0B, 0x0C, 0x0D, 0x00, 0x01, 0x02, 0x03 #endif +uint8_t pointPerfectTokenArray[16] = {POINTPERFECT_TOKEN}; //Token in HEX form + const char* pointPerfectAPI = "https://api.thingstream.io/ztp/pointperfect/credentials"; void checkRXMCOR(UBX_RXM_COR_data_t *ubxDataStruct); float lBandEBNO = 0.0; //Used on system status menu diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index cec82d09f..7d16093df 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -454,3 +454,27 @@ struct struct_online { bool lbandCorrections = false; bool i2c = false; } online; + +//AWS certificate for PointPerfect API +static const char *AWS_PUBLIC_CERT = R"=====( +-----BEGIN CERTIFICATE----- +MIIDQTCCAimgAwIBAgITBmyfz5m/jAo54vB4ikPmljZbyjANBgkqhkiG9w0BAQsF +ADA5MQswCQYDVQQGEwJVUzEPMA0GA1UEChMGQW1hem9uMRkwFwYDVQQDExBBbWF6 +b24gUm9vdCBDQSAxMB4XDTE1MDUyNjAwMDAwMFoXDTM4MDExNzAwMDAwMFowOTEL +MAkGA1UEBhMCVVMxDzANBgNVBAoTBkFtYXpvbjEZMBcGA1UEAxMQQW1hem9uIFJv +b3QgQ0EgMTCCASIwDQYJKoZIhvcNAQEBBQADggEPADCCAQoCggEBALJ4gHHKeNXj +ca9HgFB0fW7Y14h29Jlo91ghYPl0hAEvrAIthtOgQ3pOsqTQNroBvo3bSMgHFzZM +9O6II8c+6zf1tRn4SWiw3te5djgdYZ6k/oI2peVKVuRF4fn9tBb6dNqcmzU5L/qw +IFAGbHrQgLKm+a/sRxmPUDgH3KKHOVj4utWp+UhnMJbulHheb4mjUcAwhmahRWa6 +VOujw5H5SNz/0egwLX0tdHA114gk957EWW67c4cX8jJGKLhD+rcdqsq08p8kDi1L +93FcXmn/6pUCyziKrlA4b9v7LWIbxcceVOF34GfID5yHI9Y/QCB/IIDEgEw+OyQm +jgSubJrIqg0CAwEAAaNCMEAwDwYDVR0TAQH/BAUwAwEB/zAOBgNVHQ8BAf8EBAMC +AYYwHQYDVR0OBBYEFIQYzIU07LwMlJQuCFmcx7IQTgoIMA0GCSqGSIb3DQEBCwUA +A4IBAQCY8jdaQZChGsV2USggNiMOruYou6r4lK5IpDB/G/wkjUu0yKGX9rbxenDI +U5PMCCjjmCXPI6T53iHTfIUJrU6adTrCC2qJeHZERxhlbI1Bjjt/msv0tadQ1wUs +N+gDS63pYaACbvXy8MWy7Vu33PqUXHeeE6V/Uq2V8viTO96LXFvKWlJbYK8U90vv +o/ufQJVtMVT8QtPHRh8jrdkPSHCa2XV4cdFyQzR1bldZwgJcJmApzyMZFo6IQ6XU +5MsI+yMRQ+hDKXJioaldXgjUkK642M4UwtBV8ob2xJNDd2ZhwLnoQdeXeGADbkpy +rqXRfboQnoZsG4q5WTP468SQvvG5 +-----END CERTIFICATE----- +)====="; From b7f129f126bd4b0e5e6e532a317601131acbf1c8 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 2 Aug 2022 10:43:27 -0500 Subject: [PATCH 009/134] Add partition file for workflow compilation --- Firmware/RTK_Surveyor/partitions.csv | 6 ++++++ 1 file changed, 6 insertions(+) create mode 100644 Firmware/RTK_Surveyor/partitions.csv diff --git a/Firmware/RTK_Surveyor/partitions.csv b/Firmware/RTK_Surveyor/partitions.csv new file mode 100644 index 000000000..7b89daee9 --- /dev/null +++ b/Firmware/RTK_Surveyor/partitions.csv @@ -0,0 +1,6 @@ +# Name, Type, SubType, Offset, Size, Flags +nvs, data, nvs, 0x9000, 0x5000, +otadata, data, ota, 0xe000, 0x2000, +app0, app, ota_0, 0x10000, 0x640000, +app1, app, ota_1, 0x650000,0x640000, +spiffs, data, spiffs, 0xc90000,0x370000, From e798f002009e09f8725d51765dee3f6dc3629c11 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Sat, 30 Jul 2022 16:11:30 -1000 Subject: [PATCH 010/134] Validate the RTCM length field --- Firmware/RTK_Surveyor/NtripServer.ino | 23 +++++++++++++++++------ 1 file changed, 17 insertions(+), 6 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 76b4742a2..0981b1f14 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -179,6 +179,23 @@ bool ntripServerRtcmMessage(uint8_t data) switch (crcState) { + //Read the upper two bits of the length + case RTCM_TRANSPORT_STATE_READ_LENGTH_1: + if (!(data & 3)) + { + length = data << 8; + crcState = RTCM_TRANSPORT_STATE_READ_LENGTH_2; + break; + } + + //Wait for the preamble byte + crcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; + + //Fall through + // | + // | + // V + //Wait for the preamble byte (0xd3) case RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3: sendMessage = false; @@ -189,12 +206,6 @@ bool ntripServerRtcmMessage(uint8_t data) } break; - //Read the upper two bits of the length - case RTCM_TRANSPORT_STATE_READ_LENGTH_1: - length = data << 8; - crcState = RTCM_TRANSPORT_STATE_READ_LENGTH_2; - break; - //Read the lower 8 bits of the length case RTCM_TRANSPORT_STATE_READ_LENGTH_2: length |= data; From 6f1cf9c83e99e8f4986a9a6a04db88b1530bba93 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Tue, 2 Aug 2022 18:30:56 -1000 Subject: [PATCH 011/134] Enable/disable the parser in the NTRIP server --- Firmware/RTK_Surveyor/NVM.ino | 4 ++++ Firmware/RTK_Surveyor/NtripServer.ino | 2 +- Firmware/RTK_Surveyor/menuSystem.ino | 7 +++++++ Firmware/RTK_Surveyor/settings.h | 1 + 4 files changed, 13 insertions(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index 4380f2d44..da26ad020 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -250,6 +250,7 @@ void recordSystemSettingsToFile(File * settingsFile) settingsFile->printf("%s=%d\n\r", "enablePrintNtripClientRtcm", settings.enablePrintNtripClientRtcm); settingsFile->printf("%s=%d\n\r", "enablePrintStates", settings.enablePrintStates); settingsFile->printf("%s=%d\n\r", "enablePrintDuplicateStates", settings.enablePrintDuplicateStates); + settingsFile->printf("%s=%d\n\r", "enableNtripServerMessageParsing", settings.enableNtripServerMessageParsing); //Record constellation settings for (int x = 0 ; x < MAX_CONSTELLATIONS ; x++) @@ -840,6 +841,9 @@ bool parseLine(char* str, Settings *settings) settings->enablePrintStates = d; else if (strcmp(settingName, "enablePrintDuplicateStates") == 0) settings->enablePrintDuplicateStates = d; + else if (strcmp(settingName, "enableNtripServerMessageParsing") == 0) + settings->enableNtripServerMessageParsing = d; + //Check for bulk settings (constellations and message rates) //Must be last on else list else diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 76b4742a2..e9fcbd218 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -352,7 +352,7 @@ void ntripServerProcessRTCM(uint8_t incoming) previousMilliseconds = currentMilliseconds; //Parse the RTCM message - if (ntripServerRtcmMessage(incoming)) + if ((!settings.enableNtripServerMessageParsing) || ntripServerRtcmMessage(incoming)) { ntripServer->write(incoming); //Send this byte to socket ntripServerBytesSent++; diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index 25a7616cb..82d5629dd 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -366,6 +366,9 @@ void menuDebug() Serial.print("27) Print duplicate states: "); Serial.printf("%s\r\n", settings.enablePrintDuplicateStates ? "Enabled" : "Disabled"); + Serial.print("28) NTRIP server message parser: "); + Serial.printf("%s\r\n", settings.enableNtripServerMessageParsing ? "Enabled" : "Disabled"); + Serial.println("t) Enter Test Screen"); Serial.println("e) Erase LittleFS"); @@ -544,6 +547,10 @@ void menuDebug() { settings.enablePrintDuplicateStates ^= 1; } + else if (incoming == 28) + { + settings.enableNtripServerMessageParsing ^= 1; + } else printUnknown(incoming); } diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 4a540654b..96aa2559d 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -441,6 +441,7 @@ typedef struct { bool enablePrintNtripClientRtcm = false; bool enablePrintStates = true; bool enablePrintDuplicateStates = false; + bool enableNtripServerMessageParsing = false; } Settings; Settings settings; From 78a9a689f5bd41df15cba6173721d3efb5f9d329 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Tue, 2 Aug 2022 18:34:29 -1000 Subject: [PATCH 012/134] Only process RTCM messages when the NTRIP server is in the casting state --- Firmware/RTK_Surveyor/NtripServer.ino | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 76b4742a2..bebf824d0 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -333,7 +333,7 @@ void ntripServerProcessRTCM(uint8_t incoming) } #ifdef COMPILE_WIFI - if (online.rtc) + if (online.rtc && (ntripServerState == NTRIP_SERVER_CASTING)) { //Timestamp the RTCM messages currentMilliseconds = millis(); @@ -359,11 +359,11 @@ void ntripServerProcessRTCM(uint8_t incoming) ntripServerTimer = millis(); online.txNtripDataCasting = true; } - - //Indicate that the GNSS is providing correction data - else if (ntripServerState == NTRIP_SERVER_WAIT_GNSS_DATA) - ntripServerSetState(NTRIP_SERVER_CONNECTING); } + + //Indicate that the GNSS is providing correction data + else if (ntripServerState == NTRIP_SERVER_WAIT_GNSS_DATA) + ntripServerSetState(NTRIP_SERVER_CONNECTING); #endif //COMPILE_WIFI } From 9a247285c7a291baf4d17c94c62359798f56bf2a Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Tue, 2 Aug 2022 18:38:41 -1000 Subject: [PATCH 013/134] Initialize the NTRIP server parser before entering the caster state --- Firmware/RTK_Surveyor/NtripServer.ino | 30 +++++++++++++++------------ 1 file changed, 17 insertions(+), 13 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index bebf824d0..538eddf32 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -154,11 +154,12 @@ void ntripServerResponse(char * response, size_t maxLength) *response = '\0'; } +static byte ntripServerCrcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; + //Parse the RTCM transport data bool ntripServerRtcmMessage(uint8_t data) { static uint16_t bytesRemaining; - static byte crcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; static uint16_t length; static uint16_t message; static bool sendMessage = false; @@ -177,14 +178,14 @@ bool ntripServerRtcmMessage(uint8_t data) // |<-------------------------------- CRC -------------------------------->| // - switch (crcState) + switch (ntripServerCrcState) { //Wait for the preamble byte (0xd3) case RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3: sendMessage = false; if (data == 0xd3) { - crcState = RTCM_TRANSPORT_STATE_READ_LENGTH_1; + ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_LENGTH_1; sendMessage = (ntripServerState == NTRIP_SERVER_CASTING); } break; @@ -192,57 +193,57 @@ bool ntripServerRtcmMessage(uint8_t data) //Read the upper two bits of the length case RTCM_TRANSPORT_STATE_READ_LENGTH_1: length = data << 8; - crcState = RTCM_TRANSPORT_STATE_READ_LENGTH_2; + ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_LENGTH_2; break; //Read the lower 8 bits of the length case RTCM_TRANSPORT_STATE_READ_LENGTH_2: length |= data; bytesRemaining = length; - crcState = RTCM_TRANSPORT_STATE_READ_MESSAGE_1; + ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_MESSAGE_1; break; //Read the upper 8 bits of the message number case RTCM_TRANSPORT_STATE_READ_MESSAGE_1: message = data << 4; bytesRemaining -= 1; - crcState = RTCM_TRANSPORT_STATE_READ_MESSAGE_2; + ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_MESSAGE_2; break; //Read the lower 4 bits of the message number case RTCM_TRANSPORT_STATE_READ_MESSAGE_2: message |= data >> 4; bytesRemaining -= 1; - crcState = RTCM_TRANSPORT_STATE_READ_DATA; + ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_DATA; break; //Read the rest of the message case RTCM_TRANSPORT_STATE_READ_DATA: bytesRemaining -= 1; if (bytesRemaining <= 0) - crcState = RTCM_TRANSPORT_STATE_READ_CRC_1; + ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_CRC_1; break; //Read the upper 8 bits of the CRC case RTCM_TRANSPORT_STATE_READ_CRC_1: - crcState = RTCM_TRANSPORT_STATE_READ_CRC_2; + ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_CRC_2; break; //Read the middle 8 bits of the CRC case RTCM_TRANSPORT_STATE_READ_CRC_2: - crcState = RTCM_TRANSPORT_STATE_READ_CRC_3; + ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_CRC_3; break; //Read the lower 8 bits of the CRC case RTCM_TRANSPORT_STATE_READ_CRC_3: - crcState = RTCM_TRANSPORT_STATE_CHECK_CRC; + ntripServerCrcState = RTCM_TRANSPORT_STATE_CHECK_CRC; break; } //Check the CRC - if (crcState == RTCM_TRANSPORT_STATE_CHECK_CRC) + if (ntripServerCrcState == RTCM_TRANSPORT_STATE_CHECK_CRC) { - crcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; + ntripServerCrcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; //Account for this message rtcmPacketsSent++; @@ -363,7 +364,10 @@ void ntripServerProcessRTCM(uint8_t incoming) //Indicate that the GNSS is providing correction data else if (ntripServerState == NTRIP_SERVER_WAIT_GNSS_DATA) + { ntripServerSetState(NTRIP_SERVER_CONNECTING); + ntripServerCrcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; + } #endif //COMPILE_WIFI } From f50732a407ea2619a3a9f5cd41ad0aa4dd48a0c5 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Tue, 2 Aug 2022 18:42:06 -1000 Subject: [PATCH 014/134] Update the NTRIP server printed messages --- Firmware/RTK_Surveyor/NtripServer.ino | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index e9fcbd218..a4b98c5a0 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -249,7 +249,10 @@ bool ntripServerRtcmMessage(uint8_t data) //Display the RTCM message header if (settings.enablePrintNtripServerRtcm && (!inMainMenu)) - Serial.printf (" Message %d, %2d bytes\r\n", message, 3 + 1 + length + 3); + { + printTimeStamp(); + Serial.printf (" Tx RTCM %d, %2d bytes\r\n", message, 3 + length + 3); + } } //Let the upper layer know if this message should be sent @@ -338,16 +341,18 @@ void ntripServerProcessRTCM(uint8_t incoming) //Timestamp the RTCM messages currentMilliseconds = millis(); if (settings.enablePrintNtripServerRtcm + && (!settings.enableNtripServerMessageParsing) && (!inMainMenu) - && ((currentMilliseconds - previousMilliseconds) > 1)) + && ((currentMilliseconds - previousMilliseconds) > 5)) { + printTimeStamp(); // 1 2 3 //123456789012345678901234567890 //YYYY-mm-dd HH:MM:SS.xxxrn0 struct tm timeinfo = rtc.getTimeStruct(); char timestamp[30]; strftime(timestamp, sizeof(timestamp), "%Y-%m-%d %H:%M:%S", &timeinfo); - Serial.printf("RTCM: %s.%03ld\r\n", timestamp, rtc.getMillis()); + Serial.printf(" Tx RTCM: %s.%03ld\r\n", timestamp, rtc.getMillis()); } previousMilliseconds = currentMilliseconds; From ef591331b56349a7fba9f90bdddca276dfe799d4 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 4 Aug 2022 09:35:26 -0500 Subject: [PATCH 015/134] Fix >= bugs in task circular buffer --- Firmware/RTK_Surveyor/Tasks.ino | 31 +++++++++++++++++++------------ 1 file changed, 19 insertions(+), 12 deletions(-) diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 80ab5946c..7b83dbc07 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -55,11 +55,11 @@ void F9PSerialReadTask(void *e) //---------------------------------------------------------------------- //The ESP32<->ZED-F9P serial connection is default 460,800bps to facilitate //10Hz fix rate with PPP Logging Defaults (NMEAx5 + RXMx2) messages enabled. - //ESP32 UART2 is begun with SERIAL_SIZE_RX size buffer. The circular buffer - //is SERIAL_SIZE_RX. At approximately 46.1K characters/second, a 6144 * 2 - //byte buffer should hold 267ms worth of serial data. Assuming SD writes are - //250ms worst case, we should record incoming all data. Bluetooth congestion - //or conflicts with the SD card semaphore should clear within this time. + //ESP32 UART2 is begun with SERIAL_SIZE_RX size buffer. The circular buffer + //is SERIAL_SIZE_RX. At approximately 46.1K characters/second, a 6144 * 2 + //byte buffer should hold 267ms worth of serial data. Assuming SD writes are + //250ms worst case, we should record incoming all data. Bluetooth congestion + //or conflicts with the SD card semaphore should clear within this time. // //Ring buffer empty when (dataHead == btTail) and (dataHead == sdTail) // @@ -125,7 +125,7 @@ void F9PSerialReadTask(void *e) availableBufferSpace -= 1; //Fill the buffer to the end and then start at the beginning - if ((dataHead + availableBufferSpace) > sizeof(rBuffer)) + if ((dataHead + availableBufferSpace) >= sizeof(rBuffer)) availableBufferSpace = sizeof(rBuffer) - dataHead; //If we have buffer space, read data from the GNSS into the buffer @@ -164,7 +164,7 @@ void F9PSerialReadTask(void *e) { //Reduce bytes to send if we have more to send then the end of the buffer //We'll wrap next loop - if ((btTail + btBytesToSend) > sizeof(rBuffer)) + if ((btTail + btBytesToSend) >= sizeof(rBuffer)) btBytesToSend = sizeof(rBuffer) - btTail; //Reduce bytes to send to match BT buffer size @@ -180,13 +180,20 @@ void F9PSerialReadTask(void *e) else { //Don't push data to BT SPP if there is congestion to prevent heap hits. - if (btBytesToSend < (sizeof(rBuffer) - 1)) - btBytesToSend = 0; - else + if (btBytesToSend == (sizeof(rBuffer) - 1)) + { + //Error - no more room in the buffer, drop a buffer's worth of data + btTail = dataHead; Serial.printf("ERROR - Congestion, dropped %d bytes: GNSS --> Bluetooth\r\n", btBytesToSend); + } + else + { + log_w("WARNING - BT failed to send, Tasks.ino line %d", __LINE__); + btBytesToSend = 0; + } } - //Account for the sent data or dropped + //Account for the sent or dropped data btTail += btBytesToSend; if (btTail >= sizeof(rBuffer)) btTail -= sizeof(rBuffer); @@ -211,7 +218,7 @@ void F9PSerialReadTask(void *e) { //Reduce bytes to send if we have more to send then the end of the buffer //We'll wrap next loop - if ((sdTail + sdBytesToRecord) > sizeof(rBuffer)) + if ((sdTail + sdBytesToRecord) >= sizeof(rBuffer)) sdBytesToRecord = sizeof(rBuffer) - sdTail; //Write the data to the file From b72165a0bdcb426fc0d69ebbeddb30bed720e291 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 4 Aug 2022 14:24:48 -0500 Subject: [PATCH 016/134] Correctly fail if LittleFS fails to start --- Firmware/RTK_Surveyor/Begin.ino | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index 931973247..141242f67 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -395,13 +395,15 @@ void beginFS() { if (online.fs == false) { - if (!LittleFS.begin(true)) //Format LittleFS if begin fails + if (LittleFS.begin(true) == false) //Format LittleFS if begin fails { - log_d("Error: LittleFS not online"); - return; + Serial.println("Error: LittleFS not online"); + } + else + { + Serial.println("LittleFS Started"); + online.fs = true; } - Serial.println("LittleFS Started"); - online.fs = true; } } From 3a8dd630808809b7cda8202fa93bdd2289a553b0 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 4 Aug 2022 14:52:47 -0500 Subject: [PATCH 017/134] Reduce BT SPP_TX_MAX buffer size, Decrease UART2 TX/RX buffers. Something is causing BT transmission congestion causing SPP to fail. I located the problem down to BluetoothSerial.cpp. --- Firmware/RTK_Surveyor/Bluetooth.ino | 4 ++-- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 4 ++-- Firmware/RTK_Surveyor/Tasks.ino | 21 +++++++++---------- .../src/BluetoothSerial/BluetoothSerial.cpp | 12 +++++++++-- 4 files changed, 24 insertions(+), 17 deletions(-) diff --git a/Firmware/RTK_Surveyor/Bluetooth.ino b/Firmware/RTK_Surveyor/Bluetooth.ino index 04c26ab8e..36a29dd67 100644 --- a/Firmware/RTK_Surveyor/Bluetooth.ino +++ b/Firmware/RTK_Surveyor/Bluetooth.ino @@ -40,14 +40,14 @@ static volatile byte bluetoothState = BT_OFF; //Used for updating the bluetoothState state machine void bluetoothCallback(esp_spp_cb_event_t event, esp_spp_cb_param_t *param) { if (event == ESP_SPP_SRV_OPEN_EVT) { - Serial.println("Client Connected"); + Serial.println("BT client Connected"); bluetoothState = BT_CONNECTED; if (productVariant == RTK_SURVEYOR) digitalWrite(pin_bluetoothStatusLED, HIGH); } if (event == ESP_SPP_CLOSE_EVT ) { - Serial.println("Client disconnected"); + Serial.println("BT client disconnected"); bluetoothState = BT_NOTCONNECTED; if (productVariant == RTK_SURVEYOR) digitalWrite(pin_bluetoothStatusLED, LOW); diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 8ac894549..f65721ceb 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -236,11 +236,11 @@ char platformPrefix[55] = "Surveyor"; //Sets the prefix for broadcast names HardwareSerial serialGNSS(2); //TX on 17, RX on 16 -#define SERIAL_SIZE_RX (1024 * 6) //Must be large enough to handle incoming ZED UART traffic. See F9PSerialReadTask(). +#define SERIAL_SIZE_RX (1024 * 4) //Must be large enough to handle incoming ZED UART traffic. See F9PSerialReadTask(). TaskHandle_t F9PSerialReadTaskHandle = NULL; //Store handles so that we can kill them if user goes into WiFi NTRIP Server mode const uint8_t F9PSerialReadTaskPriority = 1; //3 being the highest, and 0 being the lowest -#define SERIAL_SIZE_TX (1024 * 2) +#define SERIAL_SIZE_TX (1024 * 1) uint8_t wBuffer[SERIAL_SIZE_TX]; //Buffer for writing from incoming SPP to F9P TaskHandle_t F9PSerialWriteTaskHandle = NULL; //Store handles so that we can kill them if user goes into WiFi NTRIP Server mode const uint8_t F9PSerialWriteTaskPriority = 1; //3 being the highest, and 0 being the lowest diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 7b83dbc07..2a88e0b12 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -33,7 +33,7 @@ void F9PSerialWriteTask(void *e) //Task for reading data from the GNSS receiver. void F9PSerialReadTask(void *e) { - static uint8_t rBuffer[SERIAL_SIZE_RX]; //Buffer for reading from F9P to SPP + static uint8_t rBuffer[1024 * 6]; //Buffer for reading from F9P to SPP static uint16_t dataHead = 0; //Head advances as data comes in from GNSS's UART static uint16_t btTail = 0; //BT Tail advances as it is sent over BT static uint16_t sdTail = 0; //SD Tail advances as it is recorded to SD @@ -56,7 +56,7 @@ void F9PSerialReadTask(void *e) //The ESP32<->ZED-F9P serial connection is default 460,800bps to facilitate //10Hz fix rate with PPP Logging Defaults (NMEAx5 + RXMx2) messages enabled. //ESP32 UART2 is begun with SERIAL_SIZE_RX size buffer. The circular buffer - //is SERIAL_SIZE_RX. At approximately 46.1K characters/second, a 6144 * 2 + //is 1024*6. At approximately 46.1K characters/second, a 6144 * 2 //byte buffer should hold 267ms worth of serial data. Assuming SD writes are //250ms worst case, we should record incoming all data. Bluetooth congestion //or conflicts with the SD card semaphore should clear within this time. @@ -167,28 +167,27 @@ void F9PSerialReadTask(void *e) if ((btTail + btBytesToSend) >= sizeof(rBuffer)) btBytesToSend = sizeof(rBuffer) - btTail; - //Reduce bytes to send to match BT buffer size - if (btBytesToSend > settings.sppTxQueueSize) - btBytesToSend = settings.sppTxQueueSize; - if ((bluetoothIsCongested() == false) || (settings.throttleDuringSPPCongestion == false)) { //Push new data to BT SPP if not congested or not throttling btBytesToSend = bluetoothWriteBytes(&rBuffer[btTail], btBytesToSend); - online.txNtripDataCasting = true; + if (btBytesToSend > 0) + online.txNtripDataCasting = true; + else + log_w("WARNING - BT failed to send"); } else { //Don't push data to BT SPP if there is congestion to prevent heap hits. - if (btBytesToSend == (sizeof(rBuffer) - 1)) + if (btBytesToSend >= (sizeof(rBuffer) - 1)) { //Error - no more room in the buffer, drop a buffer's worth of data btTail = dataHead; - Serial.printf("ERROR - Congestion, dropped %d bytes: GNSS --> Bluetooth\r\n", btBytesToSend); + Serial.printf("ERROR - BT congestion dropped %d bytes: GNSS --> Bluetooth\r\n", btBytesToSend); } else { - log_w("WARNING - BT failed to send, Tasks.ino line %d", __LINE__); + log_w("WARNING - BT congestion delayed %d bytes, Tasks.ino line %d", btBytesToSend, __LINE__); btBytesToSend = 0; } } @@ -233,7 +232,7 @@ void F9PSerialReadTask(void *e) else { //Retry the semaphore a little later if possible - if (sdBytesToRecord == (sizeof(rBuffer) - 1)) + if (sdBytesToRecord >= (sizeof(rBuffer) - 1)) { //Error - no more room in the buffer, drop a buffer's worth of data sdTail = dataHead; diff --git a/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp b/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp index d1c0f22a6..b26c1fe7c 100644 --- a/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp +++ b/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp @@ -175,8 +175,16 @@ static esp_err_t _spp_queue_packet(uint8_t *data, size_t len){ //At ~50kBps heap lowest point is ~78k and stable //Above 50kbps it becomes unstable -//const uint16_t SPP_TX_MAX = 330; //Original -const uint16_t SPP_TX_MAX = 1024*4; //Should match the SERIAL_SIZE_RX buffer size in RTK_Surveyor.ino +const uint16_t SPP_TX_MAX = 330; //Original +//const uint16_t SPP_TX_MAX = 400; //Original +//const uint16_t SPP_TX_MAX = 1024*4; //Should match the SERIAL_SIZE_RX buffer size in RTK_Surveyor.ino + +/* +**Anything** other than 330 seems to cause the BT que to stop transmitting +This started with the addition of the circular que. Resorting to original BT lib helps but the congestion +is overwhelming. +*/ + static uint8_t _spp_tx_buffer[SPP_TX_MAX]; static uint16_t _spp_tx_buffer_len = 0; From e9334a6c3f21cddea98e3d5a6825ada3d2e91a56 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 4 Aug 2022 14:53:18 -0500 Subject: [PATCH 018/134] Increase timeout on debug menu --- Firmware/RTK_Surveyor/menuSystem.ino | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index 25a7616cb..932bcc65b 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -275,12 +275,14 @@ void menuSystem() //Toggle control of heap reports and I2C GNSS debug void menuDebug() { + int menuTimeoutExtended = 30; //Increase time needed as it's a large menu + while (1) { Serial.println(); Serial.println("Menu: Debug Menu"); - Serial.print("1) I2C Debugging Output: "); + Serial.print("1) u-blox I2C Debugging Output: "); if (settings.enableI2Cdebug == true) Serial.println("Enabled"); else Serial.println("Disabled"); @@ -375,7 +377,7 @@ void menuDebug() Serial.println("x) Exit"); int incoming; - int digits = getMenuChoice(&incoming, menuTimeout); //Timeout after x seconds + int digits = getMenuChoice(&incoming, menuTimeoutExtended); //Timeout after x seconds //Handle input timeout if (digits == GMCS_TIMEOUT) From 26903f91474e28e445fcd2be9eca54eb0ad8a842 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 4 Aug 2022 14:54:53 -0500 Subject: [PATCH 019/134] Increase max base position accuracy for survey in, for developer mode. --- Firmware/RTK_Surveyor/menuBase.ino | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Firmware/RTK_Surveyor/menuBase.ino b/Firmware/RTK_Surveyor/menuBase.ino index 3a289bdde..52c23c87f 100644 --- a/Firmware/RTK_Surveyor/menuBase.ino +++ b/Firmware/RTK_Surveyor/menuBase.ino @@ -168,7 +168,11 @@ void menuBase() { Serial.print("Enter the number of meters for survey-in required position accuracy (1.0 to 5.0m): "); float observationPositionAccuracy = getDouble(menuTimeout); //Timeout after x seconds +#ifdef ENABLE_DEVELOPER + if (observationPositionAccuracy < 1.0 || observationPositionAccuracy > 10.0) //Arbitrary 1m minimum +#else if (observationPositionAccuracy < 1.0 || observationPositionAccuracy > 5.0) //Arbitrary 1m minimum +#endif { Serial.println("Error: observation positional accuracy requirement out of range"); } From e053579ad3538e775b51f6b6d6153709bd97aa48 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 4 Aug 2022 16:30:37 -0500 Subject: [PATCH 020/134] Change Logging icon based on messages enabled Fix for issue #267 --- Firmware/RTK_Surveyor/Display.ino | 41 +++++-- Firmware/RTK_Surveyor/icons.h | 148 +++++++++++++++---------- Firmware/RTK_Surveyor/menuMessages.ino | 55 ++++++++- Graphics/Logging-Custom-1.bmp | Bin 0 -> 190 bytes Graphics/Logging-Custom-2.bmp | Bin 0 -> 190 bytes Graphics/Logging-Custom-3.bmp | Bin 0 -> 190 bytes Graphics/Logging-PPP-1.bmp | Bin 0 -> 190 bytes Graphics/Logging-PPP-2.bmp | Bin 0 -> 190 bytes Graphics/Logging-PPP-3.bmp | Bin 0 -> 190 bytes 9 files changed, 173 insertions(+), 71 deletions(-) create mode 100644 Graphics/Logging-Custom-1.bmp create mode 100644 Graphics/Logging-Custom-2.bmp create mode 100644 Graphics/Logging-Custom-3.bmp create mode 100644 Graphics/Logging-PPP-1.bmp create mode 100644 Graphics/Logging-PPP-2.bmp create mode 100644 Graphics/Logging-PPP-3.bmp diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index eb3da5799..6373d6b6e 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -857,14 +857,39 @@ void paintLogging() loggingIconDisplayed %= 4; //Wrap if (online.logging == true && logIncreasing == true) { - if (loggingIconDisplayed == 0) - displayBitmap(64 - Logging_0_Width, 48 - Logging_0_Height, Logging_0_Width, Logging_0_Height, Logging_0); - else if (loggingIconDisplayed == 1) - displayBitmap(64 - Logging_1_Width, 48 - Logging_1_Height, Logging_1_Width, Logging_1_Height, Logging_1); - else if (loggingIconDisplayed == 2) - displayBitmap(64 - Logging_2_Width, 48 - Logging_2_Height, Logging_2_Width, Logging_2_Height, Logging_2); - else if (loggingIconDisplayed == 3) - displayBitmap(64 - Logging_3_Width, 48 - Logging_3_Height, Logging_3_Width, Logging_3_Height, Logging_3); + if (loggingType == LOGGING_STANDARD) + { + if (loggingIconDisplayed == 0) + displayBitmap(64 - Logging_0_Width, 48 - Logging_0_Height, Logging_0_Width, Logging_0_Height, Logging_0); + else if (loggingIconDisplayed == 1) + displayBitmap(64 - Logging_1_Width, 48 - Logging_1_Height, Logging_1_Width, Logging_1_Height, Logging_1); + else if (loggingIconDisplayed == 2) + displayBitmap(64 - Logging_2_Width, 48 - Logging_2_Height, Logging_2_Width, Logging_2_Height, Logging_2); + else if (loggingIconDisplayed == 3) + displayBitmap(64 - Logging_3_Width, 48 - Logging_3_Height, Logging_3_Width, Logging_3_Height, Logging_3); + } + else if (loggingType == LOGGING_PPP) + { + if (loggingIconDisplayed == 0) + displayBitmap(64 - Logging_0_Width, 48 - Logging_0_Height, Logging_0_Width, Logging_0_Height, Logging_0); + else if (loggingIconDisplayed == 1) + displayBitmap(64 - Logging_1_Width, 48 - Logging_1_Height, Logging_1_Width, Logging_1_Height, Logging_PPP_1); + else if (loggingIconDisplayed == 2) + displayBitmap(64 - Logging_2_Width, 48 - Logging_2_Height, Logging_2_Width, Logging_2_Height, Logging_PPP_2); + else if (loggingIconDisplayed == 3) + displayBitmap(64 - Logging_3_Width, 48 - Logging_3_Height, Logging_3_Width, Logging_3_Height, Logging_PPP_3); + } + else if (loggingType == LOGGING_CUSTOM) + { + if (loggingIconDisplayed == 0) + displayBitmap(64 - Logging_0_Width, 48 - Logging_0_Height, Logging_0_Width, Logging_0_Height, Logging_0); + else if (loggingIconDisplayed == 1) + displayBitmap(64 - Logging_1_Width, 48 - Logging_1_Height, Logging_1_Width, Logging_1_Height, Logging_Custom_1); + else if (loggingIconDisplayed == 2) + displayBitmap(64 - Logging_2_Width, 48 - Logging_2_Height, Logging_2_Width, Logging_2_Height, Logging_Custom_2); + else if (loggingIconDisplayed == 3) + displayBitmap(64 - Logging_3_Width, 48 - Logging_3_Height, Logging_3_Width, Logging_3_Height, Logging_Custom_3); + } } else { diff --git a/Firmware/RTK_Surveyor/icons.h b/Firmware/RTK_Surveyor/icons.h index 789d2a792..d5ca49ff5 100644 --- a/Firmware/RTK_Surveyor/icons.h +++ b/Firmware/RTK_Surveyor/icons.h @@ -5,7 +5,7 @@ /* BT_Symbol [7, 14] - * + ** *** * * ** @@ -18,7 +18,7 @@ * * ** *** ** - * + */ uint8_t BT_Symbol [] = { @@ -36,9 +36,9 @@ int BT_Symbol_Width = 7; * * * * * *** * * * - * + *** - * + */ uint8_t WiFi_Symbol [] = { @@ -51,8 +51,8 @@ int WiFi_Symbol_Width = 13; /* CrossHair [15, 15] - * - * + + ******* * * * * * * @@ -64,8 +64,8 @@ int WiFi_Symbol_Width = 13; * * * * * * ******* - * - * + + */ uint8_t CrossHair [] = { @@ -78,8 +78,8 @@ int CrossHair_Width = 15; /* CrossHairDual [15, 15] - * - * + + ******* * * * * ***** * @@ -91,8 +91,8 @@ int CrossHair_Width = 15; * ***** * * * * ******* - * - * + + */ uint8_t CrossHairDual [] = { @@ -206,9 +206,9 @@ int Rover_Fusion_Empty_Width = 15; * ** ** * ***** *** * * *** ** - * - * - * + + + */ uint8_t BaseTemporary [] = { @@ -435,9 +435,38 @@ uint8_t Logging_0 [] = { 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, }; + int Logging_0_Height = 12; int Logging_0_Width = 9; +uint8_t Logging_PPP_3 [] = { + 0xFF, 0x01, 0xF9, 0x49, 0x49, 0x49, 0x33, 0x06, 0xFC, 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, + 0x08, 0x0F, +}; +uint8_t Logging_PPP_2 [] = { + 0xFF, 0x01, 0xF9, 0x41, 0x41, 0x41, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, + 0x08, 0x0F, +}; +uint8_t Logging_PPP_1 [] = { + 0xFF, 0x01, 0xC1, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, + 0x08, 0x0F, +}; + +uint8_t Logging_Custom_3 [] = { + 0xFF, 0x01, 0xF1, 0x09, 0x09, 0x09, 0x13, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, + 0x08, 0x0F, +}; +uint8_t Logging_Custom_2 [] = { + 0xFF, 0x01, 0xF1, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, + 0x08, 0x0F, +}; +uint8_t Logging_Custom_1 [] = { + 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, + 0x08, 0x0F, +}; + + + int DynamicModel_Height = 12; int DynamicModel_Width = 15; @@ -470,7 +499,7 @@ uint8_t DynamicModel_1_Portable [] = { ******* ***** *** - * + *** ***** ** * ** @@ -491,7 +520,7 @@ uint8_t DynamicModel_2_Stationary [] = { *** * * * * - * + ***** ** * ** * * @@ -533,7 +562,7 @@ uint8_t DynamicModel_4_Automotive [] = { DynamicModel_5_Sea [15, 12] - * + *** * * * * @@ -555,7 +584,7 @@ uint8_t DynamicModel_5_Sea [] = { DynamicModel_6_Airborne1g [15, 12] - * + ** *********** * * ** @@ -565,7 +594,7 @@ uint8_t DynamicModel_5_Sea [] = { ****** ***** * * * * - * + */ uint8_t DynamicModel_6_Airborne1g [] = { @@ -577,7 +606,7 @@ uint8_t DynamicModel_6_Airborne1g [] = { DynamicModel_7_Airborne2g [15, 12] - * + ** *********** * * ** @@ -587,7 +616,7 @@ uint8_t DynamicModel_6_Airborne1g [] = { ****** ***** * * * * - * + */ uint8_t DynamicModel_7_Airborne2g [] = { @@ -599,7 +628,7 @@ uint8_t DynamicModel_7_Airborne2g [] = { DynamicModel_8_Airborne4g [15, 12] - * + ** *********** * * ** @@ -609,7 +638,7 @@ uint8_t DynamicModel_7_Airborne2g [] = { ****** ***** * * * * - * + */ uint8_t DynamicModel_8_Airborne4g [] = { @@ -760,41 +789,42 @@ int UploadArrow_Width = 8; //SparkFun Electronics LOGO uint8_t logoSparkFun [] = { - // ROW0, BYTE0 to BYTE63 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0xF8, 0xFC, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0x0F, 0x07, 0x07, 0x06, 0x06, 0x00, 0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - - // ROW1, BYTE64 to BYTE127 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x81, 0x07, 0x0F, 0x3F, 0x3F, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFE, 0xFC, 0xFC, 0xFC, 0xFE, 0xFF, 0xFF, 0xFF, 0xFC, 0xF8, 0xE0, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - - // ROW2, BYTE128 to BYTE191 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFC, - 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF1, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xF0, 0xFD, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - - // ROW3, BYTE192 to BYTE255 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x3F, 0x1F, 0x07, 0x01, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - - // ROW4, BYTE256 to BYTE319 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, - 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x3F, 0x1F, 0x1F, 0x0F, 0x0F, 0x0F, 0x0F, - 0x0F, 0x0F, 0x0F, 0x0F, 0x07, 0x07, 0x07, 0x03, 0x03, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - - // ROW5, BYTE320 to BYTE383 - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, - 0x7F, 0x3F, 0x1F, 0x0F, 0x07, 0x03, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 + // ROW0, BYTE0 to BYTE63 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0xF8, 0xFC, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0x0F, 0x07, 0x07, 0x06, 0x06, 0x00, 0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + + // ROW1, BYTE64 to BYTE127 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x81, 0x07, 0x0F, 0x3F, 0x3F, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFE, 0xFC, 0xFC, 0xFC, 0xFE, 0xFF, 0xFF, 0xFF, 0xFC, 0xF8, 0xE0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + + // ROW2, BYTE128 to BYTE191 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFC, + 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF1, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xF0, 0xFD, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + + // ROW3, BYTE192 to BYTE255 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x3F, 0x1F, 0x07, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + + // ROW4, BYTE256 to BYTE319 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x3F, 0x1F, 0x1F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x07, 0x07, 0x07, 0x03, 0x03, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + + // ROW5, BYTE320 to BYTE383 + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, + 0x7F, 0x3F, 0x1F, 0x0F, 0x07, 0x03, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; int logoSparkFun_Height = 48; int logoSparkFun_Width = 64; +int ESPNOW_Symbol_Width = 8; diff --git a/Firmware/RTK_Surveyor/menuMessages.ino b/Firmware/RTK_Surveyor/menuMessages.ino index 228fa5b1e..b0583bf4f 100644 --- a/Firmware/RTK_Surveyor/menuMessages.ino +++ b/Firmware/RTK_Surveyor/menuMessages.ino @@ -140,7 +140,7 @@ void menuMessages() //We want GSV NMEA to be reported at 1Hz to avoid swamping SPP connection float measurementFrequency = (1000.0 / settings.measurementRate) / settings.navigationRate; - if(measurementFrequency < 1.0) measurementFrequency = 1.0; + if (measurementFrequency < 1.0) measurementFrequency = 1.0; setMessageRateByName("UBX_NMEA_GSV", measurementFrequency); //One report per second setMessageRateByName("UBX_NMEA_RMC", 1); @@ -152,10 +152,10 @@ void menuMessages() setMessageRateByName("UBX_NMEA_GGA", 1); setMessageRateByName("UBX_NMEA_GSA", 1); setMessageRateByName("UBX_NMEA_GST", 1); - + //We want GSV NMEA to be reported at 1Hz to avoid swamping SPP connection float measurementFrequency = (1000.0 / settings.measurementRate) / settings.navigationRate; - if(measurementFrequency < 1.0) measurementFrequency = 1.0; + if (measurementFrequency < 1.0) measurementFrequency = 1.0; setMessageRateByName("UBX_NMEA_GSV", measurementFrequency); //One report per second setMessageRateByName("UBX_NMEA_RMC", 1); @@ -200,6 +200,7 @@ void menuMessages() Serial.println("menuMessages: UART1 messages successfully enabled"); } + setLoggingType(); //Update Standard, PPP, or custom for icon selection } //Given a sub type (ie "RTCM", "NMEA") present menu showing messages with this subtype @@ -459,7 +460,7 @@ void endLogging(bool gotSemaphore, bool releaseSemaphore) //Attempt to write to file system. This avoids collisions with file writing from other functions like recordSystemSettingsToFile() //Wait up to 1000ms if (gotSemaphore - || (xSemaphoreTake(sdCardSemaphore, 1000 / portTICK_PERIOD_MS) == pdPASS)) + || (xSemaphoreTake(sdCardSemaphore, 1000 / portTICK_PERIOD_MS) == pdPASS)) { if (sdPresent()) { @@ -610,3 +611,49 @@ bool setMessageRateByName(const char *msgName, uint8_t msgRate) Serial.printf("setMessageRateByName: %s not found\n\r", msgName); return (false); } + +//Given the name of a message, find it, and return the rate +uint8_t getMessageRateByName(const char *msgName) +{ + for (int x = 0 ; x < MAX_UBX_MSG ; x++) + { + if (strcmp(settings.ubxMessages[x].msgTextName, msgName) == 0) + return (settings.ubxMessages[x].msgRate); + } + + Serial.printf("getMessageRateByName: %s not found\n\r", msgName); + return (0); +} + +//Determine logging type +//If user is logging basic 5 sentences, this is 'S'tandard logging +//If user is logging 7 PPP sentences, this is 'P'PP logging +//If user has other setences turned on, it's custom logging +//This controls the type of icon displayed +void setLoggingType() +{ + loggingType = LOGGING_CUSTOM; + + int messageCount = getActiveMessageCount(); + Serial.printf("message count %d\n\r", messageCount); + + if (messageCount == 5 || messageCount == 7) + { + if (getMessageRateByName("UBX_NMEA_GGA") > 0 + && getMessageRateByName("UBX_NMEA_GSA") > 0 + && getMessageRateByName("UBX_NMEA_GST") > 0 + && getMessageRateByName("UBX_NMEA_GSV") > 0 + && getMessageRateByName("UBX_NMEA_RMC") > 0 + ) + { + loggingType = LOGGING_STANDARD; + Serial.println("Logging type standard"); + + if (getMessageRateByName("UBX_RXM_RAWX") > 0 && getMessageRateByName("UBX_RXM_SFRBX") > 0) + { + loggingType = LOGGING_PPP; + Serial.println("Logging type PPP"); + } + } + } +} diff --git a/Graphics/Logging-Custom-1.bmp b/Graphics/Logging-Custom-1.bmp new file mode 100644 index 0000000000000000000000000000000000000000..2b4e3a7e4e44e96dca28e3c97cfd9c323464aa71 GIT binary patch literal 190 zcmZ?r-Nyg{c0fu4h&h2+0EihGSb!u19N}YN0AVH|7leV}KL`i{0Z1(_8mtmXFai~T d*o*=U5Smet5zL2)6Q)7dfXo5A4Pq1n0|3JP3#tGB literal 0 HcmV?d00001 diff --git a/Graphics/Logging-Custom-2.bmp b/Graphics/Logging-Custom-2.bmp new file mode 100644 index 0000000000000000000000000000000000000000..7c37e16a1077ac7585a3de2da811603861b07fd7 GIT binary patch literal 190 zcmZ?r-Nyg{c0fu4h&h2+0EihGSb!u19N}YN0AVH|7leV}KL`i{0Z1(_8mtmXFai~T f*o*=U5Smet5zGfl;H6>uAl87)0lN)i6axbQwml1K literal 0 HcmV?d00001 diff --git a/Graphics/Logging-Custom-3.bmp b/Graphics/Logging-Custom-3.bmp new file mode 100644 index 0000000000000000000000000000000000000000..efaa4b195b1f82da9e4d280b234f5d90bb33ac0b GIT binary patch literal 190 zcmZ{eF%Ez*3G6(E75ECQ-0Kj?+oB#j- literal 0 HcmV?d00001 diff --git a/Graphics/Logging-PPP-2.bmp b/Graphics/Logging-PPP-2.bmp new file mode 100644 index 0000000000000000000000000000000000000000..1e9be2ee4d511ee3a146c493903e33a89ff8daec GIT binary patch literal 190 zcmZ?r-Nyg{c0fu4h&h2+0EihGSb!u19N}YN0AVH|7leV}KL`i{0Z1(_8mtmXFai~T b*o;61RvKsoR&khmh&3Q{z-|K>1+o_awOtEZ literal 0 HcmV?d00001 diff --git a/Graphics/Logging-PPP-3.bmp b/Graphics/Logging-PPP-3.bmp new file mode 100644 index 0000000000000000000000000000000000000000..ffb05bfcf628e39dc15fb73861d12986fced545b GIT binary patch literal 190 zcmZ?r-Nyg{c0fu4h&h2+0EihGSb!u19N}YN0AVH|7leV}KL`i{0Z1(_8mtmXFai~T d*o;61RvKsoRGblohKWP00ht4K8^|b-y#THt3n%~p literal 0 HcmV?d00001 From d57a0b18354f62620ce27db80cebfb20bea44ebc Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 5 Aug 2022 10:06:19 -0500 Subject: [PATCH 021/134] Fix a few wifi state changes to use setState --- Firmware/RTK_Surveyor/Form.ino | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Firmware/RTK_Surveyor/Form.ino b/Firmware/RTK_Surveyor/Form.ino index 786ed4fb1..c0f964730 100644 --- a/Firmware/RTK_Surveyor/Form.ino +++ b/Firmware/RTK_Surveyor/Form.ino @@ -144,7 +144,7 @@ void startWebServer() #endif #endif - wifiState = WIFI_NOTCONNECTED; + wifiSetState(WIFI_NOTCONNECTED); } void stopWebServer() @@ -262,11 +262,11 @@ void onWsEvent(AsyncWebSocket * server, AsyncWebSocketClient * client, AwsEventT createSettingsString(settingsCSV); log_d("Sending command: %s\n\r", settingsCSV); client->text(settingsCSV); - wifiState = WIFI_CONNECTED; + wifiSetState(WIFI_CONNECTED); } else if (type == WS_EVT_DISCONNECT) { log_d("Websocket client disconnected"); - wifiState = WIFI_NOTCONNECTED; + wifiSetState(WIFI_NOTCONNECTED); } else if (type == WS_EVT_DATA) { for (int i = 0; i < len; i++) { From 3ecc49d2400ca7a131459637cdb036a58359d828 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 5 Aug 2022 10:09:05 -0500 Subject: [PATCH 022/134] Separate WiFi BT stop/start --- Firmware/RTK_Surveyor/Bluetooth.ino | 3 --- Firmware/RTK_Surveyor/WiFi.ino | 9 ++++----- 2 files changed, 4 insertions(+), 8 deletions(-) diff --git a/Firmware/RTK_Surveyor/Bluetooth.ino b/Firmware/RTK_Surveyor/Bluetooth.ino index 36a29dd67..ad4d2731e 100644 --- a/Firmware/RTK_Surveyor/Bluetooth.ino +++ b/Firmware/RTK_Surveyor/Bluetooth.ino @@ -105,9 +105,6 @@ bool bluetoothRxDataAvailable() //This allows multiple units to be on at same time void bluetoothStart() { - ntripClientStop(true); - ntripServerStop(true); - wifiStop(); #ifdef COMPILE_BT if (bluetoothState == BT_OFF) { diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 7a858f4c1..2b65f585e 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -192,11 +192,7 @@ bool wifiConnectionTimeout() void wifiStart(char* ssid, char* pw) { -#ifdef COMPILE_WIFI - if (wifiState == WIFI_OFF) - //Turn off Bluetooth - bluetoothStop(); - +#ifdef COMPILE_WIFI if ((wifiState == WIFI_OFF) || (wifiState == WIFI_ON)) { Serial.printf("Wi-Fi connecting to %s\r\n", ssid); @@ -214,6 +210,9 @@ void wifiStart(char* ssid, char* pw) //See WiFiBluetoothSwitch sketch for more info void wifiStop() { + ntripClientStop(true); + ntripServerStop(true); + #ifdef COMPILE_WIFI stopWebServer(); if (wifiState == WIFI_NOTCONNECTED || wifiState == WIFI_CONNECTED) From 2fcc8d7e7e880cbb31c7d8f58c041025e68dadf4 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 5 Aug 2022 10:11:59 -0500 Subject: [PATCH 023/134] Add ESP NOW support --- Firmware/RTK_Surveyor/Base.ino | 16 ++ Firmware/RTK_Surveyor/Begin.ino | 15 ++ Firmware/RTK_Surveyor/Display.ino | 142 +++++++++++--- Firmware/RTK_Surveyor/ESPNOW.ino | 250 +++++++++++++++++++++++++ Firmware/RTK_Surveyor/NVM.ino | 49 ++++- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 73 +++++++- Firmware/RTK_Surveyor/States.ino | 22 ++- Firmware/RTK_Surveyor/WiFi.ino | 36 +++- Firmware/RTK_Surveyor/icons.h | 14 ++ Firmware/RTK_Surveyor/menuMain.ino | 62 +++++- Firmware/RTK_Surveyor/menuMessages.ino | 6 - Firmware/RTK_Surveyor/settings.h | 13 ++ Firmware/RTK_Surveyor/support.ino | 6 +- Graphics/ESP NOW Symbol-0.bmp | Bin 0 -> 126 bytes Graphics/ESP NOW Symbol-1.bmp | Bin 0 -> 126 bytes Graphics/ESP NOW Symbol-2.bmp | Bin 0 -> 126 bytes Graphics/ESP NOW Symbol-3.bmp | Bin 0 -> 126 bytes 17 files changed, 657 insertions(+), 47 deletions(-) create mode 100644 Firmware/RTK_Surveyor/ESPNOW.ino create mode 100644 Graphics/ESP NOW Symbol-0.bmp create mode 100644 Graphics/ESP NOW Symbol-1.bmp create mode 100644 Graphics/ESP NOW Symbol-2.bmp create mode 100644 Graphics/ESP NOW Symbol-3.bmp diff --git a/Firmware/RTK_Surveyor/Base.ino b/Firmware/RTK_Surveyor/Base.ino index 125d6ca9b..b208014b2 100644 --- a/Firmware/RTK_Surveyor/Base.ino +++ b/Firmware/RTK_Surveyor/Base.ino @@ -228,4 +228,20 @@ bool startFixedBase() void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming) { ntripServerProcessRTCM(incoming); + + if (wifiState == WIFI_ESPNOW_PAIRED) + { + //Move this byte into ESP NOW to send buffer + espnowOutgoing[espnowOutgoingSpot++] = incoming; + espnowLastAdd = millis(); + + if (espnowOutgoingSpot == sizeof(espnowOutgoing)) + { + espnowOutgoingSpot = 0; //Wrap +#ifdef COMPILE_WIFI + esp_now_send(0, (uint8_t *) &espnowOutgoing, sizeof(espnowOutgoing)); //Send packet to all peers + log_d("ESPNOW: Sending %d bytes", sizeof(espnowOutgoing)); +#endif + } + } } diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index 141242f67..e8504dd72 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -834,3 +834,18 @@ void beginI2C() else Serial.println("Error: I2C Bus Not Responding"); } + +//Depending on radio selection, begin hardware +void beginRadio() +{ + if (settings.radioType == RADIO_EXTERNAL) + { + wifiStop(); + + //Nothing to start. UART2 of ZED is connected to external Radio port and is configured at configureUbloxModule() + } + else if (settings.radioType == RADIO_ESPNOW) + { + espnowStart(); + } +} diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 6373d6b6e..723be50dc 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -2,37 +2,44 @@ // Constants //---------------------------------------- +//A bitfield is used to flag which icon needs to be illuminated +//systemState will dictate most of the icons needed + //Left top -#define ICON_WIFI_SYMBOL_LEFT 1 // 0, 0 -#define ICON_DOWN_ARROW 2 // 16, 0 -#define ICON_UP_ARROW 4 // 16, 0 -#define ICON_BT_SYMBOL 8 // 4, 0 -#define ICON_MAC_ADDRESS 0x10 // 0, 3 +#define ICON_WIFI_SYMBOL_LEFT (1<<0) // 0, 0 +#define ICON_DOWN_ARROW (1<<1) // 16, 0 +#define ICON_UP_ARROW (1<<2) // 16, 0 +#define ICON_BT_SYMBOL (1<<3) // 4, 0 +#define ICON_MAC_ADDRESS (1<<4) // 0, 3 +#define ICON_MAC_ADDRESS_2DIGIT (1<<5) // TODO 0, 3 +#define ICON_ESPNOW_SYMBOL (1<<6) // TODO 0, 3 +#define ICON_BT_SYMBOL_RIGHT (1<<7) // TODO 4, 0 //Center top -#define ICON_WIFI_SYMBOL_CENTER 0x20 // center, 0 -#define ICON_BASE_TEMPORARY 0x40 // 27, 0 -#define ICON_BASE_FIXED 0x80 // 27, 0 -#define ICON_ROVER_FUSION 0x100 // 27, 2 -#define ICON_ROVER_FUSION_EMPTY 0x200 // 27, 2 -#define ICON_DYNAMIC_MODEL 0x400 // 27, 0 +#define ICON_WIFI_SYMBOL_CENTER (1<<8) // center, 0 +#define ICON_BASE_TEMPORARY (1<<9) // 27, 0 +#define ICON_BASE_FIXED (1<<10) // 27, 0 +#define ICON_ROVER_FUSION (1<<11) // 27, 2 +#define ICON_ROVER_FUSION_EMPTY (1<<12) // 27, 2 +#define ICON_DYNAMIC_MODEL (1<<13) // 27, 0 //Right top -#define ICON_BATTERY 0x800 // 45, 0 +#define ICON_BATTERY (1<<14) // 45, 0 //Left center -#define ICON_CROSS_HAIR 0x1000 // 0, 18 -#define ICON_CROSS_HAIR_DUAL 0x2000 // 0, 18 +#define ICON_CROSS_HAIR (1<<15) // 0, 18 +#define ICON_CROSS_HAIR_DUAL (1<<16) // 0, 18 //Right center -#define ICON_HORIZONTAL_ACCURACY 0x4000 // 16, 20 +#define ICON_HORIZONTAL_ACCURACY (1<<17) // 16, 20 //Left bottom -#define ICON_SIV_ANTENNA 0x8000 // 2, 35 -#define ICON_SIV_ANTENNA_LBAND 0x10000 // 2, 35 +#define ICON_SIV_ANTENNA (1<<18) // 2, 35 +#define ICON_SIV_ANTENNA_LBAND (1<<19) // 2, 35 //Right bottom -#define ICON_LOGGING 0x20000 // right, bottom +#define ICON_LOGGING (1<<20) // right, bottom + //---------------------------------------- // Locals @@ -322,6 +329,7 @@ void updateDisplay() } //Top left corner + //This is not as if/else if. A variety of symbols may be mixed/matched if (icons & ICON_WIFI_SYMBOL_LEFT) { displayBitmap(0, 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol); @@ -333,7 +341,7 @@ void updateDisplay() else if (icons & ICON_UP_ARROW) displayBitmap(16, 0, UploadArrow_Width, UploadArrow_Height, UploadArrow); } - else if (icons & ICON_BT_SYMBOL) + if (icons & ICON_BT_SYMBOL) { displayBitmap(4, 0, BT_Symbol_Width, BT_Symbol_Height, BT_Symbol); if (bluetoothGetState() == BT_CONNECTED) @@ -347,7 +355,12 @@ void updateDisplay() displayBitmap(16, 0, UploadArrow_Width, UploadArrow_Height, UploadArrow); } } - else if (icons & ICON_MAC_ADDRESS) + if (icons & ICON_BT_SYMBOL_RIGHT) + { + //Moved to right to give space for ESP NOW icon on far left + displayBitmap(10, 0, BT_Symbol_Width, BT_Symbol_Height, BT_Symbol); + } + if (icons & ICON_MAC_ADDRESS) { char macAddress[5]; #ifdef COMPILE_BT @@ -359,6 +372,21 @@ void updateDisplay() oled.setCursor(0, 3); oled.print(macAddress); } + if (icons & ICON_MAC_ADDRESS_2DIGIT) + { + char macAddress[5]; + //Print only last two digits of MAC +#ifdef COMPILE_BT + sprintf(macAddress, "%02X", unitMACAddress[5]); +#else + sprintf(macAddress, "%02X", 0, 0); //If BT is not available, print zeroes +#endif + oled.setFont(QW_FONT_5X7); //Set font to smallest + oled.setCursor(9, 3); + oled.print(macAddress); + } + if (icons & ICON_ESPNOW_SYMBOL) + paintESPNOW(); //Paint animated icon for tx, static icon for rx based on RSSI //Top center if (icons & ICON_WIFI_SYMBOL_CENTER) @@ -571,7 +599,7 @@ void paintBatteryLevel() 8| * ** */ -//Display Bluetooth icon, Bluetooth MAC, or WiFi depending on connection state +//Display Bluetooth icon, Bluetooth MAC, WiFi, or ESP NOW depending on connection state uint32_t paintWirelessIcon() { uint32_t icons; @@ -581,7 +609,7 @@ uint32_t paintWirelessIcon() if (online.display == true) { //Bluetooth icon if paired, or Bluetooth MAC address if not paired - if (bluetoothGetState() == BT_CONNECTED) + if (bluetoothGetState() == BT_CONNECTED && wifiState == WIFI_OFF) { icons = ICON_BT_SYMBOL; if (systemState <= STATE_BASE_NOT_STARTED) @@ -609,6 +637,39 @@ uint32_t paintWirelessIcon() else if (online.ntripServer == true) icons |= ICON_UP_ARROW; } + else if (wifiState == WIFI_ESPNOW_PAIRED) + { + //If ESPNOW is on, and we are in base mode, show animated icon + if(systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) + { + //Display ESPNOW and BT (either MAC or symbol) + icons = ICON_ESPNOW_SYMBOL; + if (bluetoothGetState() == BT_CONNECTED) + icons |= ICON_BT_SYMBOL_RIGHT; + else + icons |= ICON_MAC_ADDRESS_2DIGIT; + } + + //If ESPNOW is on, and we've received a packet, move BT to make room + else if (espnowRSSI > -255) + { + //Display ESPNOW and BT (either MAC or symbol) + icons = ICON_ESPNOW_SYMBOL; + if (bluetoothGetState() == BT_CONNECTED) + icons |= ICON_BT_SYMBOL_RIGHT; + else + icons |= ICON_MAC_ADDRESS_2DIGIT; //Display 2 digit MAC + } + + //No ESPNOW icon + else + { + if (bluetoothGetState() == BT_CONNECTED) + icons = ICON_BT_SYMBOL; + else + icons = ICON_MAC_ADDRESS; //Display full MAC + } + } else icons = ICON_MAC_ADDRESS; } @@ -907,6 +968,43 @@ void paintLogging() } } +//Animate the ESP NOW icon if we are actively transmitting +//Otherwise, show static icon with level indicating RSSI +void paintESPNOW() +{ + const uint8_t x = 0; + + //Determine if we transitting or receiving + if (millis() - espnowLastAdd < 1000) + { + //We are actively sending out bytes, animate the icon + //Animate icon to show data is being transmitted + espnowIconDisplayed++; //Goto next icon + espnowIconDisplayed %= 4; //Wrap + + if (espnowIconDisplayed == 0) + displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_0); + else if (espnowIconDisplayed == 1) + displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_1); + else if (espnowIconDisplayed == 2) + displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_2); + else if (espnowIconDisplayed == 3) + displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); + } + else + { + //We are receiving data, adjust icon according to RSSI + if (espnowRSSI >= -40) + displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); + else if (espnowRSSI >= -60) + displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_2); + else if (espnowRSSI >= -80) + displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_1); + else if (espnowRSSI > -255) + displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_0); + } +} + //Survey in is running. Show 3D Mean and elapsed time. void paintBaseTempSurveyStarted() { diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino new file mode 100644 index 000000000..a3b4c6142 --- /dev/null +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -0,0 +1,250 @@ +/* + Use ESP NOW protocol to transmit RTCM between RTK Products via 2.4GHz + + How pairing works: + 1. Device enters pairing mode + 2. Device adds the broadcast MAC (all 0xFFs) as peer + 3. Device waits for incoming pairing packet from remote + 4. If valid pairing packet received, add peer, immediately transmit a pairing packet to that peer and exit. + + ESP NOW is bare metal, there is no guaranteed packet delivery. For RTCM byte transmissions using ESP NOW: + We don't care about dropped packets or packets out of order. The ZED will check the integrity of the RTCM packet. + We don't care if the ESP NOW packet is corrupt or not. RTCM has its own CRC. RTK needs valid RTCM once every + few seconds so a single dropped frame is not critical. +*/ + + +//Create a struct for ESP NOW pairing +typedef struct PairMessage { + uint8_t macAddress[6]; + bool encrypt; + uint8_t channel; + uint8_t crc; //Simple check - add MAC together and limit to 8 bit +} PairMessage; + +// Callback when data is sent +#ifdef COMPILE_WIFI +void espnowOnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) +{ + // Serial.print("Last Packet Send Status: "); + // if (status == ESP_NOW_SEND_SUCCESS) + // Serial.println("Delivery Success"); + // else + // Serial.println("Delivery Fail"); +} +#endif + +// Callback when data is received +void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int len) +{ +#ifdef COMPILE_WIFI + if (wifiState == WIFI_ESPNOW_PAIRING) + { + if (len == sizeof(PairMessage)) //First error check + { + PairMessage pairMessage; + memcpy(&pairMessage, incomingData, sizeof(pairMessage)); + + //Check CRC + uint8_t tempCRC = 0; + for (int x = 0 ; x < 6 ; x++) + tempCRC += pairMessage.macAddress[x]; + + if (tempCRC == pairMessage.crc) //2nd error check + { + //Record this MAC to peer list + memcpy(settings.espnowPeers[settings.espnowPeerCount++], &pairMessage.macAddress, 6); + settings.espnowPeerCount %= ESPNOW_MAX_PEERS; + + wifiSetState(WIFI_ESPNOW_MAC_RECEIVED); + } + //else Pair CRC failed + } + } + else + { + espnowRSSI = packetRSSI; //Record this packets RSSI as an ESP NOW packet + + //Pass RTCM bytes (presumably) from ESP NOW out ESP32-UART2 to ZED-UART1 + serialGNSS.write(incomingData, len); + log_d("ESPNOW: Rececived %d bytes, RSSI: %d", len, espnowRSSI); + + online.rxRtcmCorrectionData = true; + lastEspnowRssiUpdate = millis(); + } +#endif +} + +// Callback for all RX Packets +// Get RSSI of all incoming management packets: https://esp32.com/viewtopic.php?t=13889 +#ifdef COMPILE_WIFI +void promiscuous_rx_cb(void *buf, wifi_promiscuous_pkt_type_t type) +{ + // All espnow traffic uses action frames which are a subtype of the mgmnt frames so filter out everything else. + if (type != WIFI_PKT_MGMT) + return; + + const wifi_promiscuous_pkt_t *ppkt = (wifi_promiscuous_pkt_t *)buf; + packetRSSI = ppkt->rx_ctrl.rssi; +} +#endif + +void espnowStart() +{ +#ifdef COMPILE_WIFI + // If we are in WIFI_OFF or WIFI_ON, CONNECTED, NOTCONNECTED, doesn't matter + // General WiFi will be turned off/disconnected and replaced by ESP NOW + + // Set device as a Wi-Fi Station + WiFi.mode(WIFI_STA); + + // Enable long range, PHY rate of ESP32 will be 512Kbps or 256Kbps + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_LR); + + // Init ESP-NOW + if (esp_now_init() != ESP_OK) { + Serial.println("Error initializing ESP-NOW"); + return; + } + + // Use promiscuous callback to capture RSSI of packet + esp_wifi_set_promiscuous(true); + esp_wifi_set_promiscuous_rx_cb(&promiscuous_rx_cb); + + // Register send callbacks + esp_now_register_send_cb(espnowOnDataSent); + esp_now_register_recv_cb(espnowOnDataRecieved); + + if (settings.espnowPeerCount == 0) + { + wifiSetState(WIFI_ESPNOW_ON); + } + else + { + //If we already have peers, move to paired state + wifiSetState(WIFI_ESPNOW_PAIRED); + + log_d("Adding %d espnow peers", settings.espnowPeerCount); + for (int x = 0 ; x < settings.espnowPeerCount ; x++) + { + esp_err_t result = espnowAddPeer(settings.espnowPeers[x]); // Enable encryption to peers + if (result != ESP_OK) + log_d("Failed to add peer #%d\n\r", x); + } + } + +#else + Serial.println("Error - WiFi not compiled"); +#endif +} + +//Begin broadcasting our MAC and wait for remote unit to respond +void espnowBeginPairing() +{ +#ifndef COMPILE_WIFI + return; +#endif + + if (wifiState != WIFI_ESPNOW_ON + || wifiState != WIFI_ESPNOW_PAIRING + || wifiState != WIFI_ESPNOW_MAC_RECEIVED + || wifiState != WIFI_ESPNOW_PAIRED + ) + { + espnowStart(); + } + + // To begin pairing, we must add the broadcast MAC to the peer list + uint8_t broadcastMac[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; + espnowAddPeer(broadcastMac, false); // Encryption is not supported for multicast addresses + + wifiSetState(WIFI_ESPNOW_PAIRING); + + //Begin sending our MAC every 250ms until a remote device sends us there info + randomSeed(millis()); + + Serial.println("Begin pairing. Place other unit in pairing mode. Press any key to exit."); + while (Serial.available()) Serial.read(); + + while (1) + { + if (Serial.available()) break; + + int timeout = 1000 + random(0, 100); //Delay 1000 to 1100ms + for (int x = 0 ; x < timeout ; x++) + { + delay(1); + + if (wifiState == WIFI_ESPNOW_MAC_RECEIVED) + { + //Add new peer to system + espnowAddPeer(settings.espnowPeers[settings.espnowPeerCount - 1]); + + //Send message directly to the last peer stored (not unicast), then exit + espnowSendPairMessage(settings.espnowPeers[settings.espnowPeerCount - 1]); + + wifiSetState(WIFI_ESPNOW_PAIRED); + Serial.println("Pairing compete"); + return; + } + } + + uint8_t broadcastMac[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; + espnowSendPairMessage(broadcastMac); //Send unit's MAC address over broadcast, no ack, no encryption + + Serial.println("Scanning for other radio..."); + } + + Serial.println("User pressed button. Pairing canceled."); +} + +//Create special pair packet to a given MAC +esp_err_t espnowSendPairMessage(uint8_t *sendToMac) +{ +#ifdef COMPILE_WIFI + // Assemble message to send + PairMessage pairMessage; + + //Get unit MAC address + uint8_t unitMACAddress[6]; + esp_read_mac(unitMACAddress, ESP_MAC_WIFI_STA); + memcpy(pairMessage.macAddress, unitMACAddress, 6); + pairMessage.encrypt = false; + pairMessage.channel = 0; + + pairMessage.crc = 0; //Calculate CRC + for (int x = 0 ; x < 6 ; x++) + pairMessage.crc += unitMACAddress[x]; + + return (esp_now_send(sendToMac, (uint8_t *) &pairMessage, sizeof(pairMessage))); //Send packet to given MAC +#else + return (ESP_OK); +#endif +} + +//Add a given MAC address to the peer list +esp_err_t espnowAddPeer(uint8_t *peerMac) +{ + return (espnowAddPeer(peerMac, true)); //Encrypt by default +} + +esp_err_t espnowAddPeer(uint8_t *peerMac, bool encrypt) +{ +#ifdef COMPILE_WIFI + esp_now_peer_info_t peerInfo; + + memcpy(peerInfo.peer_addr, peerMac, 6); + peerInfo.channel = 0; + peerInfo.ifidx = WIFI_IF_STA; + //memcpy(peerInfo.lmk, "RTKProductsLMK56", 16); + //peerInfo.encrypt = true; + peerInfo.encrypt = false; + + esp_err_t result = esp_now_add_peer(&peerInfo); + if (result != ESP_OK) + log_d("Failed to add peer"); + return (result); +#else + return (ESP_OK); +#endif +} diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index 4380f2d44..890477f5c 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -250,6 +250,22 @@ void recordSystemSettingsToFile(File * settingsFile) settingsFile->printf("%s=%d\n\r", "enablePrintNtripClientRtcm", settings.enablePrintNtripClientRtcm); settingsFile->printf("%s=%d\n\r", "enablePrintStates", settings.enablePrintStates); settingsFile->printf("%s=%d\n\r", "enablePrintDuplicateStates", settings.enablePrintDuplicateStates); + settingsFile->printf("%s=%d\n\r", "radioType", settings.radioType); + //Record peer MAC addresses + for (int x = 0 ; x < settings.espnowPeerCount ; x++) + { + char tempString[50]; //espnowPeers.1=B4,C1,33,42,DE,01, + sprintf(tempString, "espnowPeers.%d=%02X,%02X,%02X,%02X,%02X,%02X,", x, + settings.espnowPeers[x][0], + settings.espnowPeers[x][1], + settings.espnowPeers[x][2], + settings.espnowPeers[x][3], + settings.espnowPeers[x][4], + settings.espnowPeers[x][5] + ); + settingsFile->println(tempString); + } + settingsFile->printf("%s=%d\n\r", "espnowPeerCount", settings.espnowPeerCount); //Record constellation settings for (int x = 0 ; x < MAX_CONSTELLATIONS ; x++) @@ -840,7 +856,12 @@ bool parseLine(char* str, Settings *settings) settings->enablePrintStates = d; else if (strcmp(settingName, "enablePrintDuplicateStates") == 0) settings->enablePrintDuplicateStates = d; - //Check for bulk settings (constellations and message rates) + else if (strcmp(settingName, "radioType") == 0) + settings->radioType = (radioType_e)d; + else if (strcmp(settingName, "espnowPeerCount") == 0) + settings->espnowPeerCount = d; + + //Check for bulk settings (constellations, message rates, ESPNOW Peers) //Must be last on else list else { @@ -890,6 +911,32 @@ bool parseLine(char* str, Settings *settings) } } + //Scan for ESPNOW peers + if (knownSetting == false) + { + for (int x = 0 ; x < ESPNOW_MAX_PEERS ; x++) + { + char tempString[50]; //espnowPeers.1=B4,C1,33,42,DE,01, + sprintf(tempString, "espnowPeers.%d", x); + + if (strcmp(settingName, tempString) == 0) + { + uint8_t macAddress[6]; + uint8_t macByte = 0; + + char* token = strtok(settingValue, ","); //Break string up on , + while(token != NULL && macByte < sizeof(macAddress)) + { + settings->espnowPeers[x][macByte++] = (uint8_t)strtol(token, NULL, 16); + token = strtok(NULL, ","); + } + + knownSetting = true; + break; + } + } + } + //Last catch if (knownSetting == false) { diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index f65721ceb..036f79112 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -8,7 +8,7 @@ Compiled with Arduino v1.8.15 with ESP32 core v2.0.2. - For compilation instructions see https://sparkfun.github.io/SparkFun_RTK_Firmware/firmware_update/#compiling-from-source + For compilation instructions see https://docs.sparkfun.com/SparkFun_RTK_Firmware/firmware_update/#compiling-source Special thanks to Avinab Malla for guidance on getting xTasks implemented. @@ -23,12 +23,12 @@ */ const int FIRMWARE_VERSION_MAJOR = 2; -const int FIRMWARE_VERSION_MINOR = 3; +const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_WIFI //Comment out to remove WiFi functionality #define COMPILE_BT //Comment out to remove Bluetooth functionality #define COMPILE_AP //Comment out to remove Access Point functionality -//#define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) +#define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) //Define the RTK board identifier: // This is an int which is unique to this variant of the RTK Surveyor hardware which allows us @@ -130,6 +130,15 @@ const TickType_t fatSemaphore_longWait_ms = 200 / portTICK_PERIOD_MS; uint32_t sdCardSizeMB = 0; uint32_t sdFreeSpaceMB = 0; uint32_t sdUsedSpaceMB = 0; + +//Controls Logging Icon type +typedef enum LoggingType { + LOGGING_UNKNOWN = 0, + LOGGING_STANDARD, + LOGGING_PPP, + LOGGING_CUSTOM +} LoggingType; +LoggingType loggingType = LOGGING_UNKNOWN; //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- //Connection settings to NTRIP Caster @@ -336,6 +345,26 @@ void checkRXMCOR(UBX_RXM_COR_data_t *ubxDataStruct); float lBandEBNO = 0.0; //Used on system status menu //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= +//ESP NOW for multipoint wireless broadcasting over 2.4GHz +//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- +#ifdef COMPILE_WIFI + +#include +#include "esp_wifi.h" //Needed for esp_wifi_set_protocol() + +#endif + +uint8_t espnowOutgoing[250]; //ESP NOW has max of 250 characters +unsigned long espnowLastAdd; //Tracks how long since last byte was added to the outgoing buffer +uint8_t espnowOutgoingSpot = 0; + +int espnowRSSI = 0; +int packetRSSI = 0; +unsigned long lastEspnowRssiUpdate = 0; + +const uint8_t ESPNOW_MAX_PEERS = 5; //Maximum of 5 rovers +//-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- + //Global variables //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- uint8_t unitMACAddress[6]; //Use MAC address in BT broadcast and display @@ -364,7 +393,8 @@ uint32_t lastPrintPosition = 0; //For periodic display of the position uint32_t lastBaseIconUpdate = 0; bool baseIconDisplayed = false; //Toggles as lastBaseIconUpdate goes above 1000ms -int loggingIconDisplayed = 0; //Increases every 500ms while logging +uint8_t loggingIconDisplayed = 0; //Increases every 500ms while logging +uint8_t espnowIconDisplayed = 0; //Increases every 500ms while transmitting uint64_t lastLogSize = 0; bool logIncreasing = false; //Goes true when log file is greater than lastLogSize @@ -425,7 +455,6 @@ uint32_t max_idle_count = MAX_IDLE_TIME_COUNT; uint64_t uptime; uint32_t previousMilliseconds; - //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- /* +---------------------------------------+ +----------+ @@ -538,6 +567,8 @@ void setup() beginSystemState(); //Determine initial system state. Start task for button monitoring. + beginRadio(); //Start internal radio if enabled + updateRTC(); //The GNSS likely has time/date. Update ESP32 RTC to match. Needed for PointPerfect key expiration. Serial.flush(); //Complete any previous prints @@ -576,6 +607,8 @@ void loop() updateLBand(); //Check if we've recently received PointPerfect corrections or not + updateRadio(); //Check if we need to finish sending any RTCM over link radio + //Periodically print the position if (settings.enablePrintPosition && ((millis() - lastPrintPosition) > 15000)) { @@ -597,6 +630,8 @@ void updateLogs() if (online.logging == false && settings.enableLogging == true) { beginLogging(); + + setLoggingType(); //Determine if we are standard, PPP, or custom. Changes logging icon accordingly. } else if (online.logging == true && settings.enableLogging == false) { @@ -791,7 +826,31 @@ void updateRTC() } //End online.rtc } -void printElapsedTime(const char* title) +//Called from main loop +//Control incoming/outgoing RTCM data from: +//External radio - this is normally a serial telemetry radio hung off the RADIO port +//Internal ESP NOW radio - Use the ESP32 to directly transmit/receive RTCM over 2.4GHz (no WiFi needed) +void updateRadio() { - Serial.printf("%s: %ld\n\r", title, millis() - startTime); + if (settings.radioType == RADIO_ESPNOW) + { + if (wifiState == WIFI_ESPNOW_PAIRED) + { + //If it's been longer than a few ms since we last added a byte to the buffer + //then we've reached the end of the RTCM stream. Send partial buffer. + if (espnowOutgoingSpot > 0 && (millis() - espnowLastAdd) > 50) + { +#ifdef COMPILE_WIFI + esp_now_send(0, (uint8_t *) &espnowOutgoing, espnowOutgoingSpot); //Send partial packet to all peers + log_d("ESPNOW: Sending %d bytes", espnowOutgoingSpot); +#endif + espnowOutgoingSpot = 0; //Reset + } + + //If we don't receive an ESP NOW packet after some time, set RSSI to very negative + //This removes the ESPNOW icon from the display when the link goes down + if (millis() - lastEspnowRssiUpdate > 5000 && espnowRSSI > -255) + espnowRSSI = -255; + } + } } diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 784e46792..bbba8e0f9 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -28,7 +28,7 @@ void updateSystemState() if (settings.enablePrintState && ((millis() - lastStateTime) > 15000)) { - changeState (systemState); + changeState(systemState); lastStateTime = millis(); } @@ -332,6 +332,12 @@ void updateSystemState() ntripServerStart(); } + //TODO select either or WiFi or ESP NOW + if (settings.radioType == RADIO_ESPNOW) + { + espnowStart(); + } + rtcmPacketsSent = 0; //Reset any previous number changeState(STATE_BASE_TEMP_TRANSMITTING); } @@ -357,7 +363,7 @@ void updateSystemState() } break; - //Leave base temp transmitting if user has enabled WiFi/NTRIP + //Leave base temp transmitting over external radio, or WiFi/NTRIP, or ESP NOW case (STATE_BASE_TEMP_TRANSMITTING): { } @@ -391,6 +397,14 @@ void updateSystemState() if (productVariant == RTK_SURVEYOR) digitalWrite(pin_baseStatusLED, HIGH); //Turn on base LED + //TODO shouldn't NtripServer be here? + + //TODO select either or WiFi or ESP NOW + if (settings.radioType == RADIO_ESPNOW) + { + espnowStart(); + } + changeState(STATE_BASE_FIXED_TRANSMITTING); } else @@ -738,7 +752,7 @@ void updateSystemState() byte wifiStatus = wifiGetStatus(); if (wifiStatus == WL_CONNECTED) { - wifiState = WIFI_CONNECTED; + wifiSetState(WIFI_CONNECTED); changeState(STATE_KEYS_WIFI_CONNECTED); } @@ -848,7 +862,7 @@ void updateSystemState() byte wifiStatus = wifiGetStatus(); if (wifiStatus == WL_CONNECTED) { - wifiState = WIFI_CONNECTED; + wifiSetState(WIFI_CONNECTED); changeState(STATE_KEYS_PROVISION_WIFI_CONNECTED); } diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 2b65f585e..47968c4d2 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -1,5 +1,5 @@ /*=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= -WiFi Status Values: + WiFi Status Values: WL_CONNECTED: assigned when connected to a WiFi network WL_CONNECTION_LOST: assigned when the connection is lost WL_CONNECT_FAILED: assigned when the connection fails for all the attempts @@ -12,7 +12,7 @@ WiFi Status Values: WL_NO_SSID_AVAIL: assigned when no SSID are available WL_SCAN_COMPLETED: assigned when the scan networks is completed -WiFi Station States: + WiFi Station States: WIFI_OFF (Using Bluetooth) | ^ @@ -38,7 +38,7 @@ WiFi Station States: v | WIFI_CONNECTED -=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=*/ + =-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=*/ //---------------------------------------- // Constants @@ -128,7 +128,19 @@ void wifiSetState (byte newState) case WIFI_CONNECTED: Serial.println("WIFI_CONNECTED"); break; - } + case WIFI_ESPNOW_ON: + Serial.println("WIFI_ESPNOW_ON"); + break; + case WIFI_ESPNOW_PAIRING: + Serial.println("WIFI_ESPNOW_PAIRING"); + break; + case WIFI_ESPNOW_MAC_RECEIVED: + Serial.println("WIFI_ESPNOW_MAC_RECEIVED"); + break; + case WIFI_ESPNOW_PAIRED: + Serial.println("WIFI_ESPNOW_PAIRED"); + break; + } } //---------------------------------------- @@ -145,6 +157,9 @@ void wifiStartAP() #define WIFI_PASSWORD "parachutes" WiFi.mode(WIFI_STA); + // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); + WiFi.begin(WIFI_SSID, WIFI_PASSWORD); Serial.print("Wi-Fi connecting to"); while (wifiGetStatus() != WL_CONNECTED) @@ -158,6 +173,9 @@ void wifiStartAP() //Start in AP mode WiFi.mode(WIFI_AP); + // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); + IPAddress local_IP(192, 168, 4, 1); IPAddress gateway(192, 168, 1, 1); IPAddress subnet(255, 255, 0, 0); @@ -215,7 +233,15 @@ void wifiStop() #ifdef COMPILE_WIFI stopWebServer(); - if (wifiState == WIFI_NOTCONNECTED || wifiState == WIFI_CONNECTED) + + //If the WiFi is in a state where WiFi has been configured/on, turn it off + if (wifiState == WIFI_NOTCONNECTED + || wifiState == WIFI_CONNECTED + || wifiState == WIFI_ESPNOW_ON + || wifiState == WIFI_ESPNOW_PAIRING + || wifiState == WIFI_ESPNOW_MAC_RECEIVED + || wifiState == WIFI_ESPNOW_PAIRED + ) { WiFi.mode(WIFI_OFF); wifiSetState(WIFI_OFF); diff --git a/Firmware/RTK_Surveyor/icons.h b/Firmware/RTK_Surveyor/icons.h index d5ca49ff5..85e00d67f 100644 --- a/Firmware/RTK_Surveyor/icons.h +++ b/Firmware/RTK_Surveyor/icons.h @@ -827,4 +827,18 @@ uint8_t logoSparkFun [] = { }; int logoSparkFun_Height = 48; int logoSparkFun_Width = 64; + +uint8_t ESPNOW_Symbol_3 [] = { + 0xE0, 0x40, 0x10, 0xE4, 0x09, 0xF2, 0x04, 0xF8, 0x00, 0x00, 0x01, 0x04, 0x12, 0x09, 0x04, 0x03 +}; +uint8_t ESPNOW_Symbol_2 [] = { + 0xE0, 0x40, 0x10, 0xE4, 0x08, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x02, 0x01, 0x00, 0x00 +}; +uint8_t ESPNOW_Symbol_1 [] = { + 0xE0, 0x40, 0x10, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00 +}; +uint8_t ESPNOW_Symbol_0 [] = { + 0xE0, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 +}; +int ESPNOW_Symbol_Height = 13; int ESPNOW_Symbol_Width = 8; diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index 92505e297..1b8eeb9d8 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -53,6 +53,8 @@ void menuMain() Serial.println("p) Configure Profiles"); + Serial.println("r) Configure Radios"); + if (online.lband == true) Serial.println("P) Configure PointPerfect"); @@ -83,6 +85,8 @@ void menuMain() menuUserProfiles(); else if (incoming == 'P' && online.lband == true) menuPointPerfect(); + else if (incoming == 'r') + menuRadio(); else if (incoming == 'f' && binCount > 0) menuFirmware(); else if (incoming == 'x') @@ -258,7 +262,7 @@ void factoryReset() { displaySytemReset(); //Display friendly message on OLED - Serial.println("Formatting settings file system..."); + Serial.println("Formatting file system..."); LittleFS.format(); //Attempt to write to file system. This avoids collisions with file writing from other functions like recordSystemSettingsToFile() and F9PSerialReadTask() @@ -286,3 +290,59 @@ void factoryReset() delay(2000); ESP.restart(); } + +//Configure the internal radio, if available +void menuRadio() +{ + int menuTimeoutExtended = 30; //Increase time needed for complex data entry (mount point ID, ECEF coords, etc). + + while (1) + { + Serial.println(); + Serial.println("Menu: Radio Menu"); + + Serial.print("1) Select Radio Type: "); + if (settings.radioType == RADIO_EXTERNAL) Serial.println("External only"); + else if (settings.radioType == RADIO_ESPNOW) Serial.println("Internal ESP NOW"); + + if (settings.radioType == RADIO_ESPNOW) + { + //Pretty print the MAC of paired radios + for (int x = 0 ; x < settings.espnowPeerCount ; x++) + { + Serial.printf("\tPaired Radio %d: ", x); + for (int y = 0 ; y < 5 ; y++) + Serial.printf("%02X:", settings.espnowPeers[x][y]); + Serial.printf("%02X\n\r", settings.espnowPeers[x][5]); + } + + Serial.println("2) Pair radios"); + } + + Serial.println("x) Exit"); + + int incoming = getNumber(menuTimeout); //Timeout after x seconds + + if (incoming == 1) + { + if (settings.radioType == RADIO_EXTERNAL) settings.radioType = RADIO_ESPNOW; + else if (settings.radioType == RADIO_ESPNOW) settings.radioType = RADIO_EXTERNAL; + } + else if (settings.radioType == RADIO_ESPNOW && incoming == 2) + { + Serial.println("Begin ESP NOW Pairing"); + espnowBeginPairing(); + } + + else if (incoming == STATUS_PRESSED_X) + break; + else if (incoming == STATUS_GETNUMBER_TIMEOUT) + break; + else + printUnknown(incoming); + } + + beginRadio(); + + while (Serial.available()) Serial.read(); //Empty buffer of any newline chars +} diff --git a/Firmware/RTK_Surveyor/menuMessages.ino b/Firmware/RTK_Surveyor/menuMessages.ino index b0583bf4f..4b23b6264 100644 --- a/Firmware/RTK_Surveyor/menuMessages.ino +++ b/Firmware/RTK_Surveyor/menuMessages.ino @@ -635,8 +635,6 @@ void setLoggingType() loggingType = LOGGING_CUSTOM; int messageCount = getActiveMessageCount(); - Serial.printf("message count %d\n\r", messageCount); - if (messageCount == 5 || messageCount == 7) { if (getMessageRateByName("UBX_NMEA_GGA") > 0 @@ -647,13 +645,9 @@ void setLoggingType() ) { loggingType = LOGGING_STANDARD; - Serial.println("Logging type standard"); if (getMessageRateByName("UBX_RXM_RAWX") > 0 && getMessageRateByName("UBX_RXM_SFRBX") > 0) - { loggingType = LOGGING_PPP; - Serial.println("Logging type PPP"); - } } } } diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 4a540654b..60062616a 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -108,6 +108,10 @@ enum WiFiState WIFI_ON, WIFI_NOTCONNECTED, WIFI_CONNECTED, + WIFI_ESPNOW_ON, + WIFI_ESPNOW_PAIRING, + WIFI_ESPNOW_MAC_RECEIVED, + WIFI_ESPNOW_PAIRED, }; volatile byte wifiState = WIFI_OFF; @@ -149,6 +153,12 @@ enum RtcmTransportState RTCM_TRANSPORT_STATE_CHECK_CRC }; +typedef enum radioType_e +{ + RADIO_EXTERNAL = 0, + RADIO_ESPNOW, +} radioType_e; + //Radio status LED goes from off (LED off), no connection (blinking), to connected (solid) enum BTState { @@ -441,6 +451,9 @@ typedef struct { bool enablePrintNtripClientRtcm = false; bool enablePrintStates = true; bool enablePrintDuplicateStates = false; + radioType_e radioType = RADIO_EXTERNAL; + uint8_t espnowPeers[5][6]; //Max of 5 peers. Contains the MAC addresses (6 bytes) of paired units + uint8_t espnowPeerCount; } Settings; Settings settings; diff --git a/Firmware/RTK_Surveyor/support.ino b/Firmware/RTK_Surveyor/support.ino index 20369b17d..d57e1b3c6 100644 --- a/Firmware/RTK_Surveyor/support.ino +++ b/Firmware/RTK_Surveyor/support.ino @@ -1,3 +1,8 @@ +void printElapsedTime(const char* title) +{ + Serial.printf("%s: %ld\n\r", title, millis() - startTime); +} + void printDebug(String thingToPrint) { if (settings.printDebugMessages == true) @@ -430,4 +435,3 @@ void printTimeStamp() previousMilliseconds = currentMilliseconds; } } - diff --git a/Graphics/ESP NOW Symbol-0.bmp b/Graphics/ESP NOW Symbol-0.bmp new file mode 100644 index 0000000000000000000000000000000000000000..3e85c99db49be42818c041ee21c770c3a0262a41 GIT binary patch literal 126 zcmZ?rtz&=yJ0PV2#2i2@0K|+8EI<+hj_@%sfG`t~3&Q__07OA#ag!i(1c4YtV*>!H CQV3-L literal 0 HcmV?d00001 diff --git a/Graphics/ESP NOW Symbol-1.bmp b/Graphics/ESP NOW Symbol-1.bmp new file mode 100644 index 0000000000000000000000000000000000000000..6a390c4e5bd264f502c64277f75aee8e677e181f GIT binary patch literal 126 zcmZ?rtz&=yJ0PV2#2i2@0K|+8EI<+hj_@%sfG`t~3&Q__07OA#agabm1Q;0@1c4Yt JgAGMf3IMJH2#5dx literal 0 HcmV?d00001 diff --git a/Graphics/ESP NOW Symbol-2.bmp b/Graphics/ESP NOW Symbol-2.bmp new file mode 100644 index 0000000000000000000000000000000000000000..33e157be722ff027b12d0951af25fbf8c9a03569 GIT binary patch literal 126 zcmZ?rtz&=yJ0PV2#2i2@0K|+8EI<+hj_@%sfG`t~3&Q__07OA#(MU!RA83LABM>n% Q2m&#P2Jyk-V0nlh0I~ZBuK)l5 literal 0 HcmV?d00001 diff --git a/Graphics/ESP NOW Symbol-3.bmp b/Graphics/ESP NOW Symbol-3.bmp new file mode 100644 index 0000000000000000000000000000000000000000..88b9b60bcb71839631a9f5c14044f94ea238152f GIT binary patch literal 126 zcmZ?rtz&=yJ0PV2#2i2@0K|+8EI<+hj_@%sfG`t~3&Q__07OA#VI)KsP$Q5b03;b1 UfrwEMh(R=n4;BZ@1DQZ&0J%O0_y7O^ literal 0 HcmV?d00001 From c8ba55027dc50199fa7bb34ed2db628bfc572e01 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 5 Aug 2022 11:08:13 -0500 Subject: [PATCH 024/134] Ignore duplicate ESP NOW peers --- Firmware/RTK_Surveyor/ESPNOW.ino | 46 +++++++++++++++++++------- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 3 +- 2 files changed, 36 insertions(+), 13 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index a3b4c6142..adb17298c 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -52,10 +52,7 @@ void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int l if (tempCRC == pairMessage.crc) //2nd error check { - //Record this MAC to peer list - memcpy(settings.espnowPeers[settings.espnowPeerCount++], &pairMessage.macAddress, 6); - settings.espnowPeerCount %= ESPNOW_MAX_PEERS; - + memcpy(&receivedMAC, pairMessage.macAddress, 6); wifiSetState(WIFI_ESPNOW_MAC_RECEIVED); } //else Pair CRC failed @@ -66,10 +63,10 @@ void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int l espnowRSSI = packetRSSI; //Record this packets RSSI as an ESP NOW packet //Pass RTCM bytes (presumably) from ESP NOW out ESP32-UART2 to ZED-UART1 - serialGNSS.write(incomingData, len); + //serialGNSS.write(incomingData, len); log_d("ESPNOW: Rececived %d bytes, RSSI: %d", len, espnowRSSI); - online.rxRtcmCorrectionData = true; + //online.rxRtcmCorrectionData = true; lastEspnowRssiUpdate = millis(); } #endif @@ -141,7 +138,7 @@ void espnowStart() //Begin broadcasting our MAC and wait for remote unit to respond void espnowBeginPairing() { -#ifndef COMPILE_WIFI +#ifndef COMPILE_WIFI return; #endif @@ -177,11 +174,24 @@ void espnowBeginPairing() if (wifiState == WIFI_ESPNOW_MAC_RECEIVED) { - //Add new peer to system - espnowAddPeer(settings.espnowPeers[settings.espnowPeerCount - 1]); + //Remove broadcast peer + espnowRemovePeer(broadcastMac); + + if (esp_now_is_peer_exist(receivedMAC) == true) + log_d("Peer already exists"); + else + { + //Add new peer to system + espnowAddPeer(receivedMAC); + + //Record this MAC to peer list + memcpy(settings.espnowPeers[settings.espnowPeerCount], receivedMAC, 6); + settings.espnowPeerCount++; + settings.espnowPeerCount %= ESPNOW_MAX_PEERS; + } - //Send message directly to the last peer stored (not unicast), then exit - espnowSendPairMessage(settings.espnowPeers[settings.espnowPeerCount - 1]); + //Send message directly to the received MAC (not unicast), then exit + espnowSendPairMessage(receivedMAC); wifiSetState(WIFI_ESPNOW_PAIRED); Serial.println("Pairing compete"); @@ -189,7 +199,6 @@ void espnowBeginPairing() } } - uint8_t broadcastMac[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; espnowSendPairMessage(broadcastMac); //Send unit's MAC address over broadcast, no ack, no encryption Serial.println("Scanning for other radio..."); @@ -248,3 +257,16 @@ esp_err_t espnowAddPeer(uint8_t *peerMac, bool encrypt) return (ESP_OK); #endif } + +//Remove a given MAC address from the peer list +esp_err_t espnowRemovePeer(uint8_t *peerMac) +{ +#ifdef COMPILE_WIFI + esp_err_t result = esp_now_del_peer(peerMac); + if (result != ESP_OK) + log_d("Failed to remove peer"); + return (result); +#else + return (ESP_OK); +#endif +} diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 036f79112..420e9f1dd 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -26,7 +26,7 @@ const int FIRMWARE_VERSION_MAJOR = 2; const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_WIFI //Comment out to remove WiFi functionality -#define COMPILE_BT //Comment out to remove Bluetooth functionality +//#define COMPILE_BT //Comment out to remove Bluetooth functionality #define COMPILE_AP //Comment out to remove Access Point functionality #define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) @@ -357,6 +357,7 @@ float lBandEBNO = 0.0; //Used on system status menu uint8_t espnowOutgoing[250]; //ESP NOW has max of 250 characters unsigned long espnowLastAdd; //Tracks how long since last byte was added to the outgoing buffer uint8_t espnowOutgoingSpot = 0; +uint8_t receivedMAC[6]; //Holds the broadcast MAC during pairing int espnowRSSI = 0; int packetRSSI = 0; From c353544c1c6ba9ecca59cf5e02bd79cabe1eb317 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 5 Aug 2022 14:24:37 -0500 Subject: [PATCH 025/134] Update radio menu. Prevent adding of multiple peers. --- Firmware/RTK_Surveyor/Base.ino | 3 +- Firmware/RTK_Surveyor/Begin.ino | 2 ++ Firmware/RTK_Surveyor/ESPNOW.ino | 29 ++++++++++------- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 4 +-- Firmware/RTK_Surveyor/menuMain.ino | 44 ++++++++++++++++++++++---- 5 files changed, 60 insertions(+), 22 deletions(-) diff --git a/Firmware/RTK_Surveyor/Base.ino b/Firmware/RTK_Surveyor/Base.ino index b208014b2..ef007c099 100644 --- a/Firmware/RTK_Surveyor/Base.ino +++ b/Firmware/RTK_Surveyor/Base.ino @@ -240,7 +240,8 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming) espnowOutgoingSpot = 0; //Wrap #ifdef COMPILE_WIFI esp_now_send(0, (uint8_t *) &espnowOutgoing, sizeof(espnowOutgoing)); //Send packet to all peers - log_d("ESPNOW: Sending %d bytes", sizeof(espnowOutgoing)); + delay(10); //We need a small delay between sending multiple packets + //log_d("ESPNOW: Sending %d bytes", sizeof(espnowOutgoing)); #endif } } diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index e8504dd72..f815b1a70 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -715,6 +715,8 @@ bool beginExternalTriggers() //Check if NEO-D9S is connected. Configure if available. void beginLBand() { + if(settings.enablePointPerfectCorrections == false) return; //If user has turned off PointPerfect, skip everything + if (i2cLBand.begin(Wire, 0x43) == false) //Connect to the u-blox NEO-D9S using Wire port. The D9S default I2C address is 0x43 (not 0x42) { log_d("L-Band not detected"); diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index adb17298c..233819973 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -26,11 +26,11 @@ typedef struct PairMessage { #ifdef COMPILE_WIFI void espnowOnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) { - // Serial.print("Last Packet Send Status: "); - // if (status == ESP_NOW_SEND_SUCCESS) - // Serial.println("Delivery Success"); - // else - // Serial.println("Delivery Fail"); +// Serial.print("Last Packet Send Status: "); +// if (status == ESP_NOW_SEND_SUCCESS) +// Serial.println("Delivery Success"); +// else +// Serial.println("Delivery Fail"); } #endif @@ -63,10 +63,10 @@ void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int l espnowRSSI = packetRSSI; //Record this packets RSSI as an ESP NOW packet //Pass RTCM bytes (presumably) from ESP NOW out ESP32-UART2 to ZED-UART1 - //serialGNSS.write(incomingData, len); - log_d("ESPNOW: Rececived %d bytes, RSSI: %d", len, espnowRSSI); + serialGNSS.write(incomingData, len); + log_d("ESPNOW: Received %d bytes, RSSI: %d", len, espnowRSSI); - //online.rxRtcmCorrectionData = true; + online.rxRtcmCorrectionData = true; lastEspnowRssiUpdate = millis(); } #endif @@ -109,7 +109,7 @@ void espnowStart() esp_wifi_set_promiscuous_rx_cb(&promiscuous_rx_cb); // Register send callbacks - esp_now_register_send_cb(espnowOnDataSent); + //esp_now_register_send_cb(espnowOnDataSent); esp_now_register_recv_cb(espnowOnDataRecieved); if (settings.espnowPeerCount == 0) @@ -124,9 +124,14 @@ void espnowStart() log_d("Adding %d espnow peers", settings.espnowPeerCount); for (int x = 0 ; x < settings.espnowPeerCount ; x++) { - esp_err_t result = espnowAddPeer(settings.espnowPeers[x]); // Enable encryption to peers - if (result != ESP_OK) - log_d("Failed to add peer #%d\n\r", x); + if (esp_now_is_peer_exist(settings.espnowPeers[x]) == true) + log_d("Peer already exists"); + else + { + esp_err_t result = espnowAddPeer(settings.espnowPeers[x]); + if (result != ESP_OK) + log_d("Failed to add peer #%d\n\r", x); + } } } diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 420e9f1dd..90d9b75c9 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -26,7 +26,7 @@ const int FIRMWARE_VERSION_MAJOR = 2; const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_WIFI //Comment out to remove WiFi functionality -//#define COMPILE_BT //Comment out to remove Bluetooth functionality +#define COMPILE_BT //Comment out to remove Bluetooth functionality #define COMPILE_AP //Comment out to remove Access Point functionality #define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) @@ -843,7 +843,7 @@ void updateRadio() { #ifdef COMPILE_WIFI esp_now_send(0, (uint8_t *) &espnowOutgoing, espnowOutgoingSpot); //Send partial packet to all peers - log_d("ESPNOW: Sending %d bytes", espnowOutgoingSpot); + //log_d("ESPNOW: Sending %d bytes", espnowOutgoingSpot); #endif espnowOutgoingSpot = 0; //Reset } diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index 1b8eeb9d8..c84f380ec 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -307,16 +307,34 @@ void menuRadio() if (settings.radioType == RADIO_ESPNOW) { - //Pretty print the MAC of paired radios - for (int x = 0 ; x < settings.espnowPeerCount ; x++) + //Pretty print the MAC of all radios + + //Get unit MAC address + uint8_t unitMACAddress[6]; + esp_read_mac(unitMACAddress, ESP_MAC_WIFI_STA); + + Serial.print(" Radio MAC: "); + for (int x = 0 ; x < 5 ; x++) + Serial.printf("%02X:", unitMACAddress[x]); + Serial.printf("%02X\n\r", unitMACAddress[5]); + + if (settings.espnowPeerCount > 0) { - Serial.printf("\tPaired Radio %d: ", x); - for (int y = 0 ; y < 5 ; y++) - Serial.printf("%02X:", settings.espnowPeers[x][y]); - Serial.printf("%02X\n\r", settings.espnowPeers[x][5]); + Serial.println(" Paired Radios: "); + for (int x = 0 ; x < settings.espnowPeerCount ; x++) + { + Serial.print(" "); + for (int y = 0 ; y < 5 ; y++) + Serial.printf("%02X:", settings.espnowPeers[x][y]); + Serial.printf("%02X\n\r", settings.espnowPeers[x][5]); + } } + else + Serial.println(" No Paired Radios"); + Serial.println("2) Pair radios"); + Serial.println("3) Forget all radios"); } Serial.println("x) Exit"); @@ -333,6 +351,18 @@ void menuRadio() Serial.println("Begin ESP NOW Pairing"); espnowBeginPairing(); } + else if (settings.radioType == RADIO_ESPNOW && incoming == 3) + { + Serial.println("\r\nForgetting all paired radios. Press 'y' to confirm:"); + byte bContinue = getByteChoice(menuTimeout); + if (bContinue == 'y') + { + for (int x = 0 ; x < settings.espnowPeerCount ; x++) + espnowRemovePeer(settings.espnowPeers[x]); + settings.espnowPeerCount = 0; + Serial.println("Radios forgotten"); + } + } else if (incoming == STATUS_PRESSED_X) break; @@ -343,6 +373,6 @@ void menuRadio() } beginRadio(); - + while (Serial.available()) Serial.read(); //Empty buffer of any newline chars } From e1a25639f1deea80a394fed7f6e1d3775473f919 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 6 Aug 2022 14:11:49 -0500 Subject: [PATCH 026/134] Fix PR #251 --- Firmware/RTK_Surveyor/NtripServer.ino | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index ddf90038f..d1822d5a7 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -185,12 +185,12 @@ bool ntripServerRtcmMessage(uint8_t data) if (!(data & 3)) { length = data << 8; - crcState = RTCM_TRANSPORT_STATE_READ_LENGTH_2; + ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_LENGTH_2; break; } //Wait for the preamble byte - crcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; + ntripServerCrcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; //Fall through // | From 3f5223fd6737f095b595dde3b8a756562445c83a Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 6 Aug 2022 15:58:23 -0500 Subject: [PATCH 027/134] Decouple WiFi and ESPNOW states. Make wifiStart/Stop and esnowStart/Stop friendly and independent. --- Firmware/RTK_Surveyor/Base.ino | 2 +- Firmware/RTK_Surveyor/Begin.ino | 2 +- Firmware/RTK_Surveyor/Display.ino | 89 +++++++++------- Firmware/RTK_Surveyor/ESPNOW.ino | 139 +++++++++++++++++++------ Firmware/RTK_Surveyor/RTK_Surveyor.ino | 4 +- Firmware/RTK_Surveyor/WiFi.ino | 55 +++++----- Firmware/RTK_Surveyor/settings.h | 17 ++- 7 files changed, 204 insertions(+), 104 deletions(-) diff --git a/Firmware/RTK_Surveyor/Base.ino b/Firmware/RTK_Surveyor/Base.ino index ef007c099..ec4a265ae 100644 --- a/Firmware/RTK_Surveyor/Base.ino +++ b/Firmware/RTK_Surveyor/Base.ino @@ -229,7 +229,7 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming) { ntripServerProcessRTCM(incoming); - if (wifiState == WIFI_ESPNOW_PAIRED) + if (wifiState == ESPNOW_PAIRED) { //Move this byte into ESP NOW to send buffer espnowOutgoing[espnowOutgoingSpot++] = incoming; diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index f815b1a70..46d82e2ad 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -842,7 +842,7 @@ void beginRadio() { if (settings.radioType == RADIO_EXTERNAL) { - wifiStop(); + espnowStop(); //Nothing to start. UART2 of ZED is connected to external Radio port and is configured at configureUbloxModule() } diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 723be50dc..ed67643c3 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -2,7 +2,7 @@ // Constants //---------------------------------------- -//A bitfield is used to flag which icon needs to be illuminated +//A bitfield is used to flag which icon needs to be illuminated //systemState will dictate most of the icons needed //Left top @@ -602,16 +602,26 @@ void paintBatteryLevel() //Display Bluetooth icon, Bluetooth MAC, WiFi, or ESP NOW depending on connection state uint32_t paintWirelessIcon() { - uint32_t icons; + uint32_t icons = 0; //TODO resolve if both BT and WiFi are on/connected icons = 0; if (online.display == true) { + //Deal with each icon individiually + //The ESPNOW_PAIRED is the only state where data is moving between units, + //and thus is the only state that affects icon placement + //Bluetooth icon if paired, or Bluetooth MAC address if not paired - if (bluetoothGetState() == BT_CONNECTED && wifiState == WIFI_OFF) + if (bluetoothGetState() == BT_CONNECTED) { - icons = ICON_BT_SYMBOL; + if (espnowState != ESPNOW_PAIRED) + icons |= ICON_BT_SYMBOL; + else + icons |= ICON_BT_SYMBOL_RIGHT; + + //TODO deal with arrows when ESP Now paired + if (systemState <= STATE_BASE_NOT_STARTED) { if (online.rxRtcmCorrectionData) @@ -620,16 +630,39 @@ uint32_t paintWirelessIcon() else if (systemState <= STATE_BUBBLE_LEVEL) icons |= ICON_UP_ARROW; } - else if (wifiState == WIFI_NOTCONNECTED) + else + { + if (espnowState != ESPNOW_PAIRED) + icons |= ICON_MAC_ADDRESS; + else + icons |= ICON_MAC_ADDRESS_2DIGIT; + } + + if (wifiState == WIFI_NOTCONNECTED) { //Blink WiFi icon - blinking_icons ^= ICON_WIFI_SYMBOL_LEFT; - if (blinking_icons & ICON_WIFI_SYMBOL_LEFT) - icons = ICON_WIFI_SYMBOL_LEFT; + if (espnowState != ESPNOW_PAIRED) + { + blinking_icons ^= ICON_WIFI_SYMBOL_LEFT; + if (blinking_icons & ICON_WIFI_SYMBOL_LEFT) + icons |= ICON_WIFI_SYMBOL_LEFT; + } + else + { + //Move to center + blinking_icons ^= ICON_WIFI_SYMBOL_CENTER; + if (blinking_icons & ICON_WIFI_SYMBOL_CENTER) + icons |= ICON_WIFI_SYMBOL_CENTER; + } } else if (wifiState == WIFI_CONNECTED) { - icons = ICON_WIFI_SYMBOL_LEFT; + if (espnowState != ESPNOW_PAIRED) + icons |= ICON_WIFI_SYMBOL_LEFT; + else + icons |= ICON_WIFI_SYMBOL_CENTER; + + //TODO deal with arrows when ESP now paired //If we are connected to NTRIP Client, show download arrow if ((online.ntripClient == true) && online.rxRtcmCorrectionData) @@ -637,41 +670,17 @@ uint32_t paintWirelessIcon() else if (online.ntripServer == true) icons |= ICON_UP_ARROW; } - else if (wifiState == WIFI_ESPNOW_PAIRED) + + if (espnowState == ESPNOW_PAIRED) { - //If ESPNOW is on, and we are in base mode, show animated icon - if(systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) - { - //Display ESPNOW and BT (either MAC or symbol) - icons = ICON_ESPNOW_SYMBOL; - if (bluetoothGetState() == BT_CONNECTED) - icons |= ICON_BT_SYMBOL_RIGHT; - else - icons |= ICON_MAC_ADDRESS_2DIGIT; - } - + //If ESPNOW is paired, and we are in base mode, show animated icon + if (systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) + icons |= ICON_ESPNOW_SYMBOL; + //If ESPNOW is on, and we've received a packet, move BT to make room else if (espnowRSSI > -255) - { - //Display ESPNOW and BT (either MAC or symbol) - icons = ICON_ESPNOW_SYMBOL; - if (bluetoothGetState() == BT_CONNECTED) - icons |= ICON_BT_SYMBOL_RIGHT; - else - icons |= ICON_MAC_ADDRESS_2DIGIT; //Display 2 digit MAC - } - - //No ESPNOW icon - else - { - if (bluetoothGetState() == BT_CONNECTED) - icons = ICON_BT_SYMBOL; - else - icons = ICON_MAC_ADDRESS; //Display full MAC - } + icons |= ICON_ESPNOW_SYMBOL; } - else - icons = ICON_MAC_ADDRESS; } return icons; } diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 233819973..4a927f4b3 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -26,11 +26,11 @@ typedef struct PairMessage { #ifdef COMPILE_WIFI void espnowOnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) { -// Serial.print("Last Packet Send Status: "); -// if (status == ESP_NOW_SEND_SUCCESS) -// Serial.println("Delivery Success"); -// else -// Serial.println("Delivery Fail"); + // Serial.print("Last Packet Send Status: "); + // if (status == ESP_NOW_SEND_SUCCESS) + // Serial.println("Delivery Success"); + // else + // Serial.println("Delivery Fail"); } #endif @@ -38,7 +38,7 @@ void espnowOnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int len) { #ifdef COMPILE_WIFI - if (wifiState == WIFI_ESPNOW_PAIRING) + if (espnowState == ESPNOW_PAIRING) { if (len == sizeof(PairMessage)) //First error check { @@ -53,7 +53,7 @@ void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int l if (tempCRC == pairMessage.crc) //2nd error check { memcpy(&receivedMAC, pairMessage.macAddress, 6); - wifiSetState(WIFI_ESPNOW_MAC_RECEIVED); + espnowSetState(ESPNOW_MAC_RECEIVED); } //else Pair CRC failed } @@ -86,17 +86,29 @@ void promiscuous_rx_cb(void *buf, wifi_promiscuous_pkt_type_t type) } #endif +//If WiFi is already enabled, simply add the LR protocol +//If the radio is off entirely, start the radio, turn on only the LR protocol void espnowStart() { #ifdef COMPILE_WIFI - // If we are in WIFI_OFF or WIFI_ON, CONNECTED, NOTCONNECTED, doesn't matter - // General WiFi will be turned off/disconnected and replaced by ESP NOW - // Set device as a Wi-Fi Station - WiFi.mode(WIFI_STA); - - // Enable long range, PHY rate of ESP32 will be 512Kbps or 256Kbps - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_LR); + if (wifiState == WIFI_OFF && espnowState == ESPNOW_OFF) + { + //Radio is off, turn it on + WiFi.mode(WIFI_STA); + } + //If WiFi is on but ESP NOW is off, then enable LR protocol + else if (wifiState > WIFI_OFF && espnowState == ESPNOW_OFF) + { + //Enable WiFi + ESP-Now + // Enable long range, PHY rate of ESP32 will be 512Kbps or 256Kbps + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); + } + //If ESP-Now is active, WiFi is active, do nothing + else + { + Serial.println("Wi-Fi on, ESP-Now on"); + } // Init ESP-NOW if (esp_now_init() != ESP_OK) { @@ -108,18 +120,18 @@ void espnowStart() esp_wifi_set_promiscuous(true); esp_wifi_set_promiscuous_rx_cb(&promiscuous_rx_cb); - // Register send callbacks + // Register callbacks //esp_now_register_send_cb(espnowOnDataSent); esp_now_register_recv_cb(espnowOnDataRecieved); if (settings.espnowPeerCount == 0) { - wifiSetState(WIFI_ESPNOW_ON); + espnowSetState(ESPNOW_ON); } else { //If we already have peers, move to paired state - wifiSetState(WIFI_ESPNOW_PAIRED); + espnowSetState(ESPNOW_PAIRED); log_d("Adding %d espnow peers", settings.espnowPeerCount); for (int x = 0 ; x < settings.espnowPeerCount ; x++) @@ -140,27 +152,60 @@ void espnowStart() #endif } -//Begin broadcasting our MAC and wait for remote unit to respond -void espnowBeginPairing() +//If WiFi is already enabled, simply remove the LR protocol +//If WiFi is off, stop the radio entirely +void espnowStop() { -#ifndef COMPILE_WIFI - return; -#endif +#ifdef COMPILE_WIFI + if(espnowState == ESPNOW_OFF) return; - if (wifiState != WIFI_ESPNOW_ON - || wifiState != WIFI_ESPNOW_PAIRING - || wifiState != WIFI_ESPNOW_MAC_RECEIVED - || wifiState != WIFI_ESPNOW_PAIRED - ) + if (wifiState > WIFI_OFF) { - espnowStart(); + //Radio is on, turn it off entirely + WiFi.mode(WIFI_OFF); + Serial.println("WiFi Radio off entirely"); + } + //If WiFi is on, then disable LR protocol + else if (wifiState > WIFI_OFF) + { + // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); + Serial.println("WiFi protocol on, LR protocol off"); + } + + // Turn off promiscuous WiFi mode + esp_wifi_set_promiscuous(false); + esp_wifi_set_promiscuous_rx_cb(NULL); + + // Deregister callbacks + //esp_now_unregister_send_cb(); + esp_now_unregister_recv_cb(); + + // Deinit ESP-NOW + if (esp_now_deinit() != ESP_OK) { + Serial.println("Error deinitializing ESP-NOW"); + return; } + espnowSetState(ESPNOW_OFF); + + Serial.println("ESP NOW Off"); +#else + Serial.println("Error - WiFi not compiled"); +#endif +} + +//Begin broadcasting our MAC and wait for remote unit to respond +void espnowBeginPairing() +{ +#ifdef COMPILE_WIFI + espnowStart(); + // To begin pairing, we must add the broadcast MAC to the peer list uint8_t broadcastMac[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; espnowAddPeer(broadcastMac, false); // Encryption is not supported for multicast addresses - wifiSetState(WIFI_ESPNOW_PAIRING); + espnowSetState(ESPNOW_PAIRING); //Begin sending our MAC every 250ms until a remote device sends us there info randomSeed(millis()); @@ -177,7 +222,7 @@ void espnowBeginPairing() { delay(1); - if (wifiState == WIFI_ESPNOW_MAC_RECEIVED) + if (espnowState == ESPNOW_MAC_RECEIVED) { //Remove broadcast peer espnowRemovePeer(broadcastMac); @@ -198,7 +243,7 @@ void espnowBeginPairing() //Send message directly to the received MAC (not unicast), then exit espnowSendPairMessage(receivedMAC); - wifiSetState(WIFI_ESPNOW_PAIRED); + espnowSetState(ESPNOW_PAIRED); Serial.println("Pairing compete"); return; } @@ -210,6 +255,9 @@ void espnowBeginPairing() } Serial.println("User pressed button. Pairing canceled."); +#else + Serial.println("WiFi not compiled"); +#endif } //Create special pair packet to a given MAC @@ -275,3 +323,32 @@ esp_err_t espnowRemovePeer(uint8_t *peerMac) return (ESP_OK); #endif } + +//Update the state of the ESP Now state machine +void espnowSetState (byte newState) +{ + if (espnowState == newState) + Serial.print("*"); + espnowState = newState; + switch (newState) + { + default: + Serial.printf("Unknown ESPNOW state: %d\r\n", newState); + break; + case ESPNOW_OFF: + Serial.println("ESPNOW_OFF"); + break; + case ESPNOW_ON: + Serial.println("ESPNOW_ON"); + break; + case ESPNOW_PAIRING: + Serial.println("ESPNOW_PAIRING"); + break; + case ESPNOW_MAC_RECEIVED: + Serial.println("ESPNOW_MAC_RECEIVED"); + break; + case ESPNOW_PAIRED: + Serial.println("ESPNOW_PAIRED"); + break; + } +} diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 90d9b75c9..8e8711955 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -26,7 +26,7 @@ const int FIRMWARE_VERSION_MAJOR = 2; const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_WIFI //Comment out to remove WiFi functionality -#define COMPILE_BT //Comment out to remove Bluetooth functionality +//#define COMPILE_BT //Comment out to remove Bluetooth functionality #define COMPILE_AP //Comment out to remove Access Point functionality #define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) @@ -835,7 +835,7 @@ void updateRadio() { if (settings.radioType == RADIO_ESPNOW) { - if (wifiState == WIFI_ESPNOW_PAIRED) + if (espnowState == ESPNOW_PAIRED) { //If it's been longer than a few ms since we last added a byte to the buffer //then we've reached the end of the RTCM stream. Send partial buffer. diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 47968c4d2..4a7fefbbc 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -128,18 +128,6 @@ void wifiSetState (byte newState) case WIFI_CONNECTED: Serial.println("WIFI_CONNECTED"); break; - case WIFI_ESPNOW_ON: - Serial.println("WIFI_ESPNOW_ON"); - break; - case WIFI_ESPNOW_PAIRING: - Serial.println("WIFI_ESPNOW_PAIRING"); - break; - case WIFI_ESPNOW_MAC_RECEIVED: - Serial.println("WIFI_ESPNOW_MAC_RECEIVED"); - break; - case WIFI_ESPNOW_PAIRED: - Serial.println("WIFI_ESPNOW_PAIRED"); - break; } } @@ -208,11 +196,20 @@ bool wifiConnectionTimeout() return true; } +//If radio is off entirely, start WiFi +//If ESP-Now is active, only add the LR protocol void wifiStart(char* ssid, char* pw) { #ifdef COMPILE_WIFI if ((wifiState == WIFI_OFF) || (wifiState == WIFI_ON)) { + //If ESP-Now is active, reconfigure protocols + if (espnowState > ESPNOW_OFF) + { + //Enable WiFi + ESP-Now + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); + } + Serial.printf("Wi-Fi connecting to %s\r\n", ssid); WiFi.begin(ssid, pw); wifiTimer = millis(); @@ -226,30 +223,38 @@ void wifiStart(char* ssid, char* pw) //Stop WiFi and release all resources //See WiFiBluetoothSwitch sketch for more info +//If ESP NOW is active, leave WiFi on enough for ESP NOW void wifiStop() { - ntripClientStop(true); - ntripServerStop(true); - #ifdef COMPILE_WIFI stopWebServer(); - //If the WiFi is in a state where WiFi has been configured/on, turn it off - if (wifiState == WIFI_NOTCONNECTED - || wifiState == WIFI_CONNECTED - || wifiState == WIFI_ESPNOW_ON - || wifiState == WIFI_ESPNOW_PAIRING - || wifiState == WIFI_ESPNOW_MAC_RECEIVED - || wifiState == WIFI_ESPNOW_PAIRED - ) + if (wifiState == WIFI_OFF) + { + //Do nothing + } + //If WiFi is on but ESP NOW is off, then turn off radio entirely + else if (espnowState == ESPNOW_OFF) { WiFi.mode(WIFI_OFF); wifiSetState(WIFI_OFF); Serial.println("Wi-Fi Stopped"); + } + //If ESP-Now is active, change protocol to only Long Range + else if (espnowState > ESPNOW_OFF) + { + WiFi.mode(WIFI_STA); - //Display the heap state - reportHeapNow(); + // Enable long range, PHY rate of ESP32 will be 512Kbps or 256Kbps + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_LR); + + wifiSetState(WIFI_OFF); + + Serial.println("Wi-Fi disabled, ESP-Now left in place"); } + + //Display the heap state + reportHeapNow(); #endif //COMPILE_WIFI } diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 0fa711d9b..7d1051896 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -102,19 +102,28 @@ typedef enum ERROR_GPS_CONFIG_FAIL, } t_errorNumber; +//Even though WiFi and ESP-Now operate on the same radio, we treat +//then as different states so that we can leave the radio on if +//either WiFi or ESP-Now are active enum WiFiState { WIFI_OFF = 0, WIFI_ON, WIFI_NOTCONNECTED, WIFI_CONNECTED, - WIFI_ESPNOW_ON, - WIFI_ESPNOW_PAIRING, - WIFI_ESPNOW_MAC_RECEIVED, - WIFI_ESPNOW_PAIRED, }; volatile byte wifiState = WIFI_OFF; +enum ESPNOWState +{ + ESPNOW_OFF, + ESPNOW_ON, + ESPNOW_PAIRING, + ESPNOW_MAC_RECEIVED, + ESPNOW_PAIRED, +}; +volatile byte espnowState = ESPNOW_OFF; + enum NTRIPClientState { NTRIP_CLIENT_OFF = 0, //Using Bluetooth or NTRIP server From 5ca7d766c5709b417bfe9e8c0f193ed90381f486 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 6 Aug 2022 15:59:53 -0500 Subject: [PATCH 028/134] Remove ntripServerStart before base is complete. --- Firmware/RTK_Surveyor/States.ino | 31 ++++++------------------------- 1 file changed, 6 insertions(+), 25 deletions(-) diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index bbba8e0f9..833749a17 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -247,23 +247,9 @@ void updateSystemState() displayBaseSuccess(500); //Show 'Base Started' if (settings.fixedBase == false) - { - //Restart Bluetooth with 'Base' name - //We start BT regardless of Ntrip Server in case user wants to transmit survey-in stats over BT - if (settings.ntripServer_StartAtSurveyIn) - ntripServerStart(); - else - bluetoothStart(); changeState(STATE_BASE_TEMP_SETTLE); - } else if (settings.fixedBase == true) - { - if (settings.enableNtripServer) - ntripServerStart(); - else - bluetoothStart(); changeState(STATE_BASE_FIXED_NOT_STARTED); - } } else { @@ -326,17 +312,12 @@ void updateSystemState() digitalWrite(pin_baseStatusLED, HIGH); //Indicate survey complete //Start the NTRIP server if requested - if ((settings.ntripServer_StartAtSurveyIn == false) - && (settings.enableNtripServer == true)) - { + if (settings.enableNtripServer == true) ntripServerStart(); - } - //TODO select either or WiFi or ESP NOW + //Start ESP-Now if requested if (settings.radioType == RADIO_ESPNOW) - { espnowStart(); - } rtcmPacketsSent = 0; //Reset any previous number changeState(STATE_BASE_TEMP_TRANSMITTING); @@ -397,13 +378,13 @@ void updateSystemState() if (productVariant == RTK_SURVEYOR) digitalWrite(pin_baseStatusLED, HIGH); //Turn on base LED - //TODO shouldn't NtripServer be here? + //Start the NTRIP server if requested + if (settings.enableNtripServer) + ntripServerStart(); - //TODO select either or WiFi or ESP NOW + //Start ESP-Now if requested if (settings.radioType == RADIO_ESPNOW) - { espnowStart(); - } changeState(STATE_BASE_FIXED_TRANSMITTING); } From e1d47d1a75f0145dd065e616cdb3a2147253cebc Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sun, 7 Aug 2022 13:31:07 -0500 Subject: [PATCH 029/134] Fix compiler errors in v2.0.4 core --- Firmware/RTK_Surveyor/Begin.ino | 1 - Firmware/RTK_Surveyor/Display.ino | 2 +- Firmware/RTK_Surveyor/Form.ino | 23 +++-------------------- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 3 --- Firmware/RTK_Surveyor/States.ino | 2 +- Firmware/RTK_Surveyor/menuMain.ino | 2 -- Firmware/RTK_Surveyor/menuPP.ino | 4 ++-- Firmware/RTK_Surveyor/menuSystem.ino | 4 ++-- 8 files changed, 9 insertions(+), 32 deletions(-) diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index 46d82e2ad..f752d5ab6 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -828,7 +828,6 @@ void beginI2C() //SCL/GND shorted: 1000ms, response 5 //SDA/VCC shorted: 1000ms, reponse 5 //SDA/GND shorted: 14ms, response 5 - unsigned long startTime = millis(); Wire.beginTransmission(0x15); //Dummy address int endValue = Wire.endTransmission(); if (endValue == 2) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index ed67643c3..60d5a3745 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -379,7 +379,7 @@ void updateDisplay() #ifdef COMPILE_BT sprintf(macAddress, "%02X", unitMACAddress[5]); #else - sprintf(macAddress, "%02X", 0, 0); //If BT is not available, print zeroes + sprintf(macAddress, "%02X", 0); //If BT is not available, print zeroes #endif oled.setFont(QW_FONT_5X7); //Set font to smallest oled.setCursor(9, 3); diff --git a/Firmware/RTK_Surveyor/Form.ino b/Firmware/RTK_Surveyor/Form.ino index c0f964730..0af0aa45b 100644 --- a/Firmware/RTK_Surveyor/Form.ino +++ b/Firmware/RTK_Surveyor/Form.ino @@ -1,8 +1,6 @@ //Once connected to the access point for WiFi Config, the ESP32 sends current setting values in one long string to websocket //After user clicks 'save', data is validated via main.js and a long string of values is returned. -static uint8_t bootProfileNumber; - //Start webserver in AP mode void startWebServer() { @@ -288,7 +286,7 @@ void createSettingsString(char* settingsCSV) //System Info stringRecord(settingsCSV, "platformPrefix", platformPrefix); - char apRtkFirmwareVersion[50]; + char apRtkFirmwareVersion[86]; sprintf(apRtkFirmwareVersion, "RTK %s Firmware: v%d.%d-%s", platformPrefix, FIRMWARE_VERSION_MAJOR, FIRMWARE_VERSION_MINOR, __DATE__); stringRecord(settingsCSV, "rtkFirmwareVersion", apRtkFirmwareVersion); @@ -298,7 +296,7 @@ void createSettingsString(char* settingsCSV) else if (zedModuleType == PLATFORM_F9R) strcpy(apZedPlatform, "ZED-F9R"); - char apZedFirmwareVersion[50]; + char apZedFirmwareVersion[80]; sprintf(apZedFirmwareVersion, "%s Firmware: %s", apZedPlatform, zedFirmwareVersion); stringRecord(settingsCSV, "zedFirmwareVersion", apZedFirmwareVersion); @@ -418,8 +416,6 @@ void createSettingsString(char* settingsCSV) sprintf(nameText, "%d: %s", index + 1, profileNames[index]); stringRecord(settingsCSV, tagText, nameText); } - bootProfileNumber = profileNumber + 1; - stringRecord(settingsCSV, "bootProfileNumber", bootProfileNumber); stringRecord(settingsCSV, "activeProfiles", activeProfiles); //New settings not yet integrated @@ -517,14 +513,6 @@ void updateSettingWithValue(const char *settingName, const char* settingValueStr recordProfileNumber(profileNumber); } } - else if (strcmp(settingName, "bootProfileNumber") == 0) - { - if ((sscanf(settingValueStr, "%d", &bootProfileNumber) != 1) - || (bootProfileNumber < 1) - || (bootProfileNumber > (MAX_PROFILE_COUNT + 1))) - bootProfileNumber = 1; - Serial.printf("bootProfileNumber: %d\r\n", bootProfileNumber); - } else if (strcmp(settingName, "enableNtripServer") == 0) settings.enableNtripServer = settingValueBool; else if (strcmp(settingName, "ntripServer_CasterHost") == 0) @@ -600,11 +588,6 @@ void updateSettingWithValue(const char *settingName, const char* settingValueStr { if (newAPSettings == true) recordSystemSettings(); //If we've recieved settings, record before restart - //Determine which profile to boot - bootProfileNumber -= 1; - if (bootProfileNumber != profileNumber) - recordProfileNumber(bootProfileNumber); - //Reboot the machine ESP.restart(); } @@ -726,7 +709,7 @@ void stringRecord(char* settingsCSV, const char *id, char* settingValue) void stringRecord(char* settingsCSV, const char *id, uint64_t settingValue) { char record[100]; - sprintf(record, "%s,%ld,", id, settingValue); + sprintf(record, "%s,%lld,", id, settingValue); strcat(settingsCSV, record); } diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 8e8711955..63b89d82a 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -581,9 +581,6 @@ void setup() void loop() { - uint32_t delayTime; - uint32_t currentMilliseconds; - if (online.gnss == true) { i2cGNSS.checkUblox(); //Regularly poll to get latest data and any RTCM diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 833749a17..7031b983f 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -807,7 +807,7 @@ void updateSystemState() if (online.rtc == true) { - uint8_t daysRemaining = daysFromEpoch(settings.pointPerfectNextKeyStart + settings.pointPerfectNextKeyDuration + 1); + int daysRemaining = daysFromEpoch(settings.pointPerfectNextKeyStart + settings.pointPerfectNextKeyDuration + 1); if (daysRemaining >= 0) { diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index c84f380ec..f70727a90 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -294,8 +294,6 @@ void factoryReset() //Configure the internal radio, if available void menuRadio() { - int menuTimeoutExtended = 30; //Increase time needed for complex data entry (mount point ID, ECEF coords, etc). - while (1) { Serial.println(); diff --git a/Firmware/RTK_Surveyor/menuPP.ino b/Firmware/RTK_Surveyor/menuPP.ino index e958e8126..82e55597f 100644 --- a/Firmware/RTK_Surveyor/menuPP.ino +++ b/Firmware/RTK_Surveyor/menuPP.ino @@ -594,7 +594,7 @@ bool getDate(uint8_t &dd, uint8_t &mm, uint16_t &yy) } //Given an epoch in ms, return the number of days from given and Epoch now -uint8_t daysFromEpoch(long long endEpoch) +int daysFromEpoch(long long endEpoch) { endEpoch /= 1000; //Convert PointPerfect ms Epoch to s @@ -603,7 +603,7 @@ uint8_t daysFromEpoch(long long endEpoch) long delta = endEpoch - localEpoch; //number of s between dates delta /= (60 * 60); //hours delta /= 24; //days - return ((uint8_t)delta); + return ((int)delta); } //Given the key's starting epoch time, and the key's duration diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index c98c9f2d5..c1d5a5ac4 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -129,7 +129,7 @@ void menuSystem() uptimeSeconds += 1; } Serial.print("Uptime: "); - Serial.printf("%d %02d:%02d:%02d.%03ld\r\n", + Serial.printf("%d %02d:%02d:%02d.%03lld\r\n", uptimeDays, uptimeHours, uptimeMinutes, @@ -461,7 +461,7 @@ void menuDebug() else if (incoming == 9) { Serial.print("Enter GNSS Serial Timeout in milliseconds (0 to 1000): "); - uint16_t serialTimeoutGNSS = getNumber(menuTimeout); //Timeout after x seconds + int16_t serialTimeoutGNSS = getNumber(menuTimeout); //Timeout after x seconds if (serialTimeoutGNSS < 0 || serialTimeoutGNSS > 1000) //Arbitrary 1s limit { Serial.println("Error: Timeout is out of range"); From 86bc849cd8c08f4be38c0a8383dfd8e698e73dac Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Mon, 8 Aug 2022 10:08:38 -0500 Subject: [PATCH 030/134] Add compile gates to ESP Now functions --- Firmware/RTK_Surveyor/Base.ino | 4 +- Firmware/RTK_Surveyor/Begin.ino | 6 +- Firmware/RTK_Surveyor/Display.ino | 422 +++++++++++------- Firmware/RTK_Surveyor/ESPNOW.ino | 56 +-- Firmware/RTK_Surveyor/NVM.ino | 2 + Firmware/RTK_Surveyor/RTK_Surveyor.ino | 20 +- Firmware/RTK_Surveyor/States.ino | 14 +- Firmware/RTK_Surveyor/Tasks.ino | 6 +- Firmware/RTK_Surveyor/menuMain.ino | 6 +- Firmware/RTK_Surveyor/menuMessages.ino | 2 +- .../src/BluetoothSerial/BluetoothSerial.cpp | 11 +- 11 files changed, 322 insertions(+), 227 deletions(-) diff --git a/Firmware/RTK_Surveyor/Base.ino b/Firmware/RTK_Surveyor/Base.ino index ec4a265ae..7c7f50f7a 100644 --- a/Firmware/RTK_Surveyor/Base.ino +++ b/Firmware/RTK_Surveyor/Base.ino @@ -229,6 +229,7 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming) { ntripServerProcessRTCM(incoming); +#ifdef COMPILE_ESPNOW if (wifiState == ESPNOW_PAIRED) { //Move this byte into ESP NOW to send buffer @@ -238,11 +239,10 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming) if (espnowOutgoingSpot == sizeof(espnowOutgoing)) { espnowOutgoingSpot = 0; //Wrap -#ifdef COMPILE_WIFI esp_now_send(0, (uint8_t *) &espnowOutgoing, sizeof(espnowOutgoing)); //Send packet to all peers delay(10); //We need a small delay between sending multiple packets //log_d("ESPNOW: Sending %d bytes", sizeof(espnowOutgoing)); -#endif } } +#endif } diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index f752d5ab6..cc3b269c4 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -202,7 +202,7 @@ void beginSD() else if (xSemaphoreTake(sdCardSemaphore, fatSemaphore_shortWait_ms) != pdPASS) { //This is OK since a retry will occur next loop - log_d("sdCardSemaphore failed to yield, Begin.ino line %d\r\n", __LINE__); + log_d("sdCardSemaphore failed to yield, Begin.ino line %d", __LINE__); break; } gotSemaphore = true; @@ -837,8 +837,9 @@ void beginI2C() } //Depending on radio selection, begin hardware -void beginRadio() +void radioStart() { +#ifdef COMPILE_ESPNOW if (settings.radioType == RADIO_EXTERNAL) { espnowStop(); @@ -849,4 +850,5 @@ void beginRadio() { espnowStart(); } +#endif } diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 60d5a3745..850805e8f 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -5,40 +5,46 @@ //A bitfield is used to flag which icon needs to be illuminated //systemState will dictate most of the icons needed -//Left top +//The radio area (top left corner of display) has three spots for icons +//Left/Center/Right +//Left Radio spot #define ICON_WIFI_SYMBOL_LEFT (1<<0) // 0, 0 -#define ICON_DOWN_ARROW (1<<1) // 16, 0 -#define ICON_UP_ARROW (1<<2) // 16, 0 -#define ICON_BT_SYMBOL (1<<3) // 4, 0 -#define ICON_MAC_ADDRESS (1<<4) // 0, 3 -#define ICON_MAC_ADDRESS_2DIGIT (1<<5) // TODO 0, 3 -#define ICON_ESPNOW_SYMBOL (1<<6) // TODO 0, 3 -#define ICON_BT_SYMBOL_RIGHT (1<<7) // TODO 4, 0 - -//Center top -#define ICON_WIFI_SYMBOL_CENTER (1<<8) // center, 0 -#define ICON_BASE_TEMPORARY (1<<9) // 27, 0 -#define ICON_BASE_FIXED (1<<10) // 27, 0 -#define ICON_ROVER_FUSION (1<<11) // 27, 2 -#define ICON_ROVER_FUSION_EMPTY (1<<12) // 27, 2 -#define ICON_DYNAMIC_MODEL (1<<13) // 27, 0 +#define ICON_BT_SYMBOL_LEFT (1<<1) // 4, 0 +#define ICON_MAC_ADDRESS (1<<2) // 0, 3 +#define ICON_ESPNOW_SYMBOL_LEFT (1<<3) // TODO 0, 3 + +//Center Radio spot +#define ICON_MAC_ADDRESS_2DIGIT (1<<4) // TODO 0, 3 +#define ICON_BT_SYMBOL_CENTER (1<<5) // TODO 4, 0 +#define ICON_WIFI_SYMBOL_CENTER (1<<6) // TODO 0, 0 + +//Right Radio Spot +#define ICON_WIFI_SYMBOL_RIGHT (1<<7) // center, 0 +#define ICON_BASE_TEMPORARY (1<<8) // 27, 0 +#define ICON_BASE_FIXED (1<<9) // 27, 0 +#define ICON_ROVER_FUSION (1<<10) // 27, 2 +#define ICON_ROVER_FUSION_EMPTY (1<<11) // 27, 2 +#define ICON_DYNAMIC_MODEL (1<<12) // 27, 0 + +#define ICON_DOWN_ARROW (1<<13) // 16, 0 +#define ICON_UP_ARROW (1<<14) // 16, 0 //Right top -#define ICON_BATTERY (1<<14) // 45, 0 +#define ICON_BATTERY (1<<15) // 45, 0 //Left center -#define ICON_CROSS_HAIR (1<<15) // 0, 18 -#define ICON_CROSS_HAIR_DUAL (1<<16) // 0, 18 +#define ICON_CROSS_HAIR (1<<16) // 0, 18 +#define ICON_CROSS_HAIR_DUAL (1<<17) // 0, 18 //Right center -#define ICON_HORIZONTAL_ACCURACY (1<<17) // 16, 20 +#define ICON_HORIZONTAL_ACCURACY (1<<18) // 16, 20 //Left bottom -#define ICON_SIV_ANTENNA (1<<18) // 2, 35 -#define ICON_SIV_ANTENNA_LBAND (1<<19) // 2, 35 +#define ICON_SIV_ANTENNA (1<<19) // 2, 35 +#define ICON_SIV_ANTENNA_LBAND (1<<20) // 2, 35 //Right bottom -#define ICON_LOGGING (1<<20) // right, bottom +#define ICON_LOGGING (1<<21) // right, bottom //---------------------------------------- @@ -165,7 +171,7 @@ void updateDisplay() */ case (STATE_ROVER_NOT_STARTED): - icons = paintWirelessIcon() //Top left + icons = paintRadioIcons() //Top left | ICON_BATTERY //Top right | ICON_CROSS_HAIR //Center left | ICON_HORIZONTAL_ACCURACY //Center right @@ -173,7 +179,7 @@ void updateDisplay() | ICON_LOGGING; //Bottom right break; case (STATE_ROVER_NO_FIX): - icons = paintWirelessIcon() //Top left + icons = paintRadioIcons() //Top left | ICON_DYNAMIC_MODEL //Top center | ICON_BATTERY //Top right | ICON_CROSS_HAIR //Center left @@ -182,7 +188,7 @@ void updateDisplay() | ICON_LOGGING; //Bottom right break; case (STATE_ROVER_FIX): - icons = paintWirelessIcon() //Top left + icons = paintRadioIcons() //Top left | ICON_DYNAMIC_MODEL //Top center | ICON_BATTERY //Top right | ICON_CROSS_HAIR //Center left @@ -192,7 +198,7 @@ void updateDisplay() break; case (STATE_ROVER_RTK_FLOAT): blinking_icons ^= ICON_CROSS_HAIR_DUAL; - icons = paintWirelessIcon() //Top left + icons = paintRadioIcons() //Top left | ICON_DYNAMIC_MODEL //Top center | ICON_BATTERY //Top right | (blinking_icons & ICON_CROSS_HAIR_DUAL) //Center left @@ -201,7 +207,7 @@ void updateDisplay() | ICON_LOGGING; //Bottom right break; case (STATE_ROVER_RTK_FIX): - icons = paintWirelessIcon() //Top left + icons = paintRadioIcons() //Top left | ICON_DYNAMIC_MODEL //Top center | ICON_BATTERY //Top right | ICON_CROSS_HAIR_DUAL//Center left @@ -219,8 +225,7 @@ void updateDisplay() //Blink crosshair icon until we have we have horz accuracy < user defined level case (STATE_BASE_TEMP_SETTLE): blinking_icons ^= ICON_BASE_TEMPORARY | ICON_CROSS_HAIR; - icons = paintWirelessIcon() //Top left - | (blinking_icons & ICON_BASE_TEMPORARY) //Top center + icons = paintRadioIcons() //Top left | ICON_BATTERY //Top right | (blinking_icons & ICON_CROSS_HAIR) //Center left | ICON_HORIZONTAL_ACCURACY //Center right @@ -229,25 +234,25 @@ void updateDisplay() break; case (STATE_BASE_TEMP_SURVEY_STARTED): blinking_icons ^= ICON_BASE_TEMPORARY; - icons = paintWirelessIcon() //Top left + icons = paintRadioIcons() //Top left | (blinking_icons & ICON_BASE_TEMPORARY) //Top center | ICON_BATTERY //Top right | ICON_LOGGING; //Bottom right paintBaseTempSurveyStarted(); break; case (STATE_BASE_TEMP_TRANSMITTING): - icons = paintWirelessIcon() //Top left + icons = paintRadioIcons() //Top left | ICON_BASE_TEMPORARY //Top center | ICON_BATTERY //Top right | ICON_LOGGING; //Bottom right paintRTCM(); break; case (STATE_BASE_FIXED_NOT_STARTED): - icons = paintWirelessIcon() //Top left + icons = paintRadioIcons() //Top left | ICON_BATTERY; //Top right break; case (STATE_BASE_FIXED_TRANSMITTING): - icons = paintWirelessIcon() //Top left + icons = paintRadioIcons() //Top left | ICON_BASE_FIXED //Top center | ICON_BATTERY //Top right | ICON_LOGGING; //Bottom right @@ -285,11 +290,11 @@ void updateDisplay() //Do nothing. Quick, fall through state. break; case (STATE_KEYS_WIFI_STARTED): - icons = paintWirelessIcon(); //Top left + icons = paintRadioIcons(); //Top left paintGettingKeys(); break; case (STATE_KEYS_WIFI_CONNECTED): - icons = paintWirelessIcon(); //Top left + icons = paintRadioIcons(); //Top left paintGettingKeys(); break; case (STATE_KEYS_WIFI_TIMEOUT): @@ -308,11 +313,11 @@ void updateDisplay() //Do nothing. Quick, fall through state. break; case (STATE_KEYS_PROVISION_WIFI_STARTED): - icons = paintWirelessIcon(); //Top left + icons = paintRadioIcons(); //Top left paintGettingKeys(); break; case (STATE_KEYS_PROVISION_WIFI_CONNECTED): - icons = paintWirelessIcon(); //Top left + icons = paintRadioIcons(); //Top left paintGettingKeys(); break; case (STATE_KEYS_PROVISION_WIFI_TIMEOUT): @@ -341,23 +346,24 @@ void updateDisplay() else if (icons & ICON_UP_ARROW) displayBitmap(16, 0, UploadArrow_Width, UploadArrow_Height, UploadArrow); } - if (icons & ICON_BT_SYMBOL) + if (icons & ICON_WIFI_SYMBOL_RIGHT) + { + displayBitmap(0, 10, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol); + // if (icons & ICON_DOWN_ARROW) + // { + // displayBitmap(16, 0, DownloadArrow_Width, DownloadArrow_Height, DownloadArrow); + // online.rxRtcmCorrectionData = false; + // } + // else if (icons & ICON_UP_ARROW) + // displayBitmap(16, 0, UploadArrow_Width, UploadArrow_Height, UploadArrow); + } + if (icons & ICON_BT_SYMBOL_LEFT) { displayBitmap(4, 0, BT_Symbol_Width, BT_Symbol_Height, BT_Symbol); - if (bluetoothGetState() == BT_CONNECTED) - { - if (icons & ICON_DOWN_ARROW) - { - displayBitmap(16, 0, DownloadArrow_Width, DownloadArrow_Height, DownloadArrow); - online.rxRtcmCorrectionData = false; - } - else if (icons & ICON_UP_ARROW) - displayBitmap(16, 0, UploadArrow_Width, UploadArrow_Height, UploadArrow); - } } - if (icons & ICON_BT_SYMBOL_RIGHT) + if (icons & ICON_BT_SYMBOL_CENTER) { - //Moved to right to give space for ESP NOW icon on far left + //Moved to center to give space for ESP NOW icon on far left displayBitmap(10, 0, BT_Symbol_Width, BT_Symbol_Height, BT_Symbol); } if (icons & ICON_MAC_ADDRESS) @@ -382,11 +388,11 @@ void updateDisplay() sprintf(macAddress, "%02X", 0); //If BT is not available, print zeroes #endif oled.setFont(QW_FONT_5X7); //Set font to smallest - oled.setCursor(9, 3); + oled.setCursor(13, 3); oled.print(macAddress); } - if (icons & ICON_ESPNOW_SYMBOL) - paintESPNOW(); //Paint animated icon for tx, static icon for rx based on RSSI + if (icons & ICON_ESPNOW_SYMBOL_LEFT) + displayBitmap(0, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); //Top center if (icons & ICON_WIFI_SYMBOL_CENTER) @@ -599,92 +605,235 @@ void paintBatteryLevel() 8| * ** */ -//Display Bluetooth icon, Bluetooth MAC, WiFi, or ESP NOW depending on connection state -uint32_t paintWirelessIcon() +//Display Bluetooth, WiFi, ESP Now, and Mode indicators (Mac, Blinking, Arrows, etc) depending on connection state +uint32_t paintRadioIcons() { uint32_t icons = 0; - //TODO resolve if both BT and WiFi are on/connected - icons = 0; if (online.display == true) { - //Deal with each icon individiually - //The ESPNOW_PAIRED is the only state where data is moving between units, - //and thus is the only state that affects icon placement - - //Bluetooth icon if paired, or Bluetooth MAC address if not paired - if (bluetoothGetState() == BT_CONNECTED) - { - if (espnowState != ESPNOW_PAIRED) - icons |= ICON_BT_SYMBOL; - else - icons |= ICON_BT_SYMBOL_RIGHT; + //There are three spots for icons in the Wireless area, left/center/right + //Center is normally used to indicate base/rover status. + //There are three radios that could be active: Bluetooth (always indicated), WiFi (if enabled), ESP-Now (if enabled) + //Because of lack of space we will indicate the Base/Rover if only two radios or less are active - //TODO deal with arrows when ESP Now paired + uint8_t numberOfRadios = 1; //Bluetooth always indicated + if (wifiState > WIFI_OFF) numberOfRadios++; + if (espnowState > ESPNOW_OFF) numberOfRadios++; - if (systemState <= STATE_BASE_NOT_STARTED) - { - if (online.rxRtcmCorrectionData) - icons |= ICON_DOWN_ARROW; - } - else if (systemState <= STATE_BUBBLE_LEVEL) - icons |= ICON_UP_ARROW; - } - else + //Bluetooth only + if (numberOfRadios == 1) { - if (espnowState != ESPNOW_PAIRED) - icons |= ICON_MAC_ADDRESS; - else - icons |= ICON_MAC_ADDRESS_2DIGIT; - } + icons |= paintBluetoothIcon_OneRadio(); - if (wifiState == WIFI_NOTCONNECTED) - { - //Blink WiFi icon - if (espnowState != ESPNOW_PAIRED) - { - blinking_icons ^= ICON_WIFI_SYMBOL_LEFT; - if (blinking_icons & ICON_WIFI_SYMBOL_LEFT) - icons |= ICON_WIFI_SYMBOL_LEFT; - } - else - { - //Move to center - blinking_icons ^= ICON_WIFI_SYMBOL_CENTER; - if (blinking_icons & ICON_WIFI_SYMBOL_CENTER) - icons |= ICON_WIFI_SYMBOL_CENTER; - } + icons |= paintModeIcon(); //Turn on Rover/Base type icons } - else if (wifiState == WIFI_CONNECTED) + + else if (numberOfRadios == 2) { - if (espnowState != ESPNOW_PAIRED) - icons |= ICON_WIFI_SYMBOL_LEFT; - else - icons |= ICON_WIFI_SYMBOL_CENTER; + icons |= paintBluetoothIcon_TwoRadios(); - //TODO deal with arrows when ESP now paired + //Do we have WiFi or ESP + if (wifiState > WIFI_OFF) + icons |= paintWiFiIcon_TwoRadios(); + else if (espnowState > ESPNOW_OFF) + icons |= paintESPNowIcon_TwoRadios(); - //If we are connected to NTRIP Client, show download arrow - if ((online.ntripClient == true) && online.rxRtcmCorrectionData) - icons |= ICON_DOWN_ARROW; - else if (online.ntripServer == true) - icons |= ICON_UP_ARROW; + icons |= paintModeIcon(); //Turn on Rover/Base type icons } - if (espnowState == ESPNOW_PAIRED) + else if (numberOfRadios == 3) { - //If ESPNOW is paired, and we are in base mode, show animated icon - if (systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) - icons |= ICON_ESPNOW_SYMBOL; + //Bluetooth is center + icons |= paintBluetoothIcon_TwoRadios(); - //If ESPNOW is on, and we've received a packet, move BT to make room - else if (espnowRSSI > -255) - icons |= ICON_ESPNOW_SYMBOL; + //ESP Now is left + icons |= paintESPNowIcon_TwoRadios(); + + //WiFi is right + icons |= paintWiFiIcon_ThreeRadios(); + + //No Rover/Base icons } } + + return icons; +} + +//Bluetooth is in left position +//Paint Bluetooth icons (MAC, Connected, arrows) in left position +uint32_t paintBluetoothIcon_OneRadio() +{ + uint32_t icons = 0; + + //Covers spots Left and Center + if (bluetoothGetState() != BT_CONNECTED) + icons |= ICON_MAC_ADDRESS; + else if (bluetoothGetState() == BT_CONNECTED) + icons |= ICON_BT_SYMBOL_LEFT; + + return icons; +} + +//Bluetooth is in center position +//Paint Bluetooth icons (MAC, Connected, arrows) in left position +uint32_t paintBluetoothIcon_TwoRadios() +{ + uint32_t icons = 0; + + if (bluetoothGetState() != BT_CONNECTED) + icons |= ICON_MAC_ADDRESS_2DIGIT; + else if (bluetoothGetState() == BT_CONNECTED) + icons |= ICON_BT_SYMBOL_CENTER; + + return icons; +} + +//Bluetooth is in center position +//Paint ESP Now icon (Solid, arrows, blinking) in left position +uint32_t paintESPNowIcon_TwoRadios() +{ + uint32_t icons = 0; + +#ifdef COMPILE_ESPNOW + + //If ESPNOW is paired, and we are in base mode, show animated icon + if (systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) + icons |= ICON_ESPNOW_SYMBOL_LEFT; + + //If ESPNOW is on, and we've received a packet, move BT to make room + else if (espnowRSSI > -255) + icons |= ICON_ESPNOW_SYMBOL_LEFT; + + + //Determine if we transitting or receiving + // if (millis() - espnowLastAdd < 1000) + // { + // //We are actively sending out bytes, animate the icon + // //Animate icon to show data is being transmitted + // espnowIconDisplayed++; //Goto next icon + // espnowIconDisplayed %= 4; //Wrap + // + // if (espnowIconDisplayed == 0) + // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_0); + // else if (espnowIconDisplayed == 1) + // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_1); + // else if (espnowIconDisplayed == 2) + // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_2); + // else if (espnowIconDisplayed == 3) + // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); + // } + // else + // { + // //We are receiving data, adjust icon according to RSSI + // if (espnowRSSI >= -40) + // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); + // else if (espnowRSSI >= -60) + // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_2); + // else if (espnowRSSI >= -80) + // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_1); + // else if (espnowRSSI > -255) + // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_0); + // } +#endif //ifdef COMPILE_ESPNOW + return icons; } +//Bluetooth is in center position +//Paint WiFi icon (Solid, arrows, blinking) in left position +uint32_t paintWiFiIcon_TwoRadios() +{ + uint32_t icons = 0; + + icons |= ICON_WIFI_SYMBOL_LEFT; + + //TODO Need blinking + // blinking_icons ^= ICON_WIFI_SYMBOL_LEFT; + // if (blinking_icons & ICON_WIFI_SYMBOL_LEFT) + // icons |= ICON_WIFI_SYMBOL_LEFT; + + //TODO Deal with arrows + // if (systemState <= STATE_BASE_NOT_STARTED) + // { + // if (online.rxRtcmCorrectionData) + // icons |= ICON_DOWN_ARROW; + // } + // else if (systemState <= STATE_BUBBLE_LEVEL) + // icons |= ICON_UP_ARROW; + return (icons); +} + +//Bluetooth is in center position +//Paint WiFi icon (Solid, arrows, blinking) in right position +uint32_t paintWiFiIcon_ThreeRadios() +{ + uint32_t icons = 0; + + icons |= ICON_WIFI_SYMBOL_RIGHT; + + //TODO Need blinking + // blinking_icons ^= ICON_WIFI_SYMBOL_LEFT; + // if (blinking_icons & ICON_WIFI_SYMBOL_LEFT) + // icons |= ICON_WIFI_SYMBOL_LEFT; + + //TODO Deal with arrows + // if (systemState <= STATE_BASE_NOT_STARTED) + // { + // if (online.rxRtcmCorrectionData) + // icons |= ICON_DOWN_ARROW; + // } + // else if (systemState <= STATE_BUBBLE_LEVEL) + // icons |= ICON_UP_ARROW; + return (icons); +} + +//Based on system state, turn on the various Rover, Base, Fixed Base icons +uint32_t paintModeIcon() +{ + uint32_t icons = 0; + switch (systemState) + { + case (STATE_ROVER_NOT_STARTED): + break; + case (STATE_ROVER_NO_FIX): + icons |= ICON_DYNAMIC_MODEL; + break; + case (STATE_ROVER_FIX): + icons |= ICON_DYNAMIC_MODEL; + break; + case (STATE_ROVER_RTK_FLOAT): + icons |= ICON_DYNAMIC_MODEL; + break; + case (STATE_ROVER_RTK_FIX): + icons |= ICON_DYNAMIC_MODEL; + break; + + case (STATE_BASE_NOT_STARTED): + //Do nothing. Static display shown during state change. + break; + + case (STATE_BASE_TEMP_SETTLE): + break; + case (STATE_BASE_TEMP_SURVEY_STARTED): + //TODO need blinking + icons |= ICON_BASE_TEMPORARY; + break; + case (STATE_BASE_TEMP_TRANSMITTING): + icons |= ICON_BASE_TEMPORARY; + break; + case (STATE_BASE_FIXED_NOT_STARTED): + break; + case (STATE_BASE_FIXED_TRANSMITTING): + icons |= ICON_BASE_FIXED; + break; + + default: + break; + } + return (icons); +} + /* 111111111122222222223333333333444444444455555555556666 0123456789012345678901234567890123456789012345678901234567890123 @@ -977,43 +1126,6 @@ void paintLogging() } } -//Animate the ESP NOW icon if we are actively transmitting -//Otherwise, show static icon with level indicating RSSI -void paintESPNOW() -{ - const uint8_t x = 0; - - //Determine if we transitting or receiving - if (millis() - espnowLastAdd < 1000) - { - //We are actively sending out bytes, animate the icon - //Animate icon to show data is being transmitted - espnowIconDisplayed++; //Goto next icon - espnowIconDisplayed %= 4; //Wrap - - if (espnowIconDisplayed == 0) - displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_0); - else if (espnowIconDisplayed == 1) - displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_1); - else if (espnowIconDisplayed == 2) - displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_2); - else if (espnowIconDisplayed == 3) - displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); - } - else - { - //We are receiving data, adjust icon according to RSSI - if (espnowRSSI >= -40) - displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); - else if (espnowRSSI >= -60) - displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_2); - else if (espnowRSSI >= -80) - displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_1); - else if (espnowRSSI > -255) - displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_0); - } -} - //Survey in is running. Show 3D Mean and elapsed time. void paintBaseTempSurveyStarted() { diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 4a927f4b3..6ee453b0e 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -12,7 +12,7 @@ We don't care if the ESP NOW packet is corrupt or not. RTCM has its own CRC. RTK needs valid RTCM once every few seconds so a single dropped frame is not critical. */ - +#ifdef COMPILE_ESPNOW //Create a struct for ESP NOW pairing typedef struct PairMessage { @@ -23,7 +23,6 @@ typedef struct PairMessage { } PairMessage; // Callback when data is sent -#ifdef COMPILE_WIFI void espnowOnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) { // Serial.print("Last Packet Send Status: "); @@ -32,12 +31,10 @@ void espnowOnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) // else // Serial.println("Delivery Fail"); } -#endif // Callback when data is received void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int len) { -#ifdef COMPILE_WIFI if (espnowState == ESPNOW_PAIRING) { if (len == sizeof(PairMessage)) //First error check @@ -69,12 +66,10 @@ void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int l online.rxRtcmCorrectionData = true; lastEspnowRssiUpdate = millis(); } -#endif } // Callback for all RX Packets // Get RSSI of all incoming management packets: https://esp32.com/viewtopic.php?t=13889 -#ifdef COMPILE_WIFI void promiscuous_rx_cb(void *buf, wifi_promiscuous_pkt_type_t type) { // All espnow traffic uses action frames which are a subtype of the mgmnt frames so filter out everything else. @@ -84,18 +79,17 @@ void promiscuous_rx_cb(void *buf, wifi_promiscuous_pkt_type_t type) const wifi_promiscuous_pkt_t *ppkt = (wifi_promiscuous_pkt_t *)buf; packetRSSI = ppkt->rx_ctrl.rssi; } -#endif //If WiFi is already enabled, simply add the LR protocol //If the radio is off entirely, start the radio, turn on only the LR protocol void espnowStart() { -#ifdef COMPILE_WIFI - if (wifiState == WIFI_OFF && espnowState == ESPNOW_OFF) { //Radio is off, turn it on WiFi.mode(WIFI_STA); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_LR); + Serial.println("WiFi off, ESP-Now added to protocols"); } //If WiFi is on but ESP NOW is off, then enable LR protocol else if (wifiState > WIFI_OFF && espnowState == ESPNOW_OFF) @@ -103,6 +97,7 @@ void espnowStart() //Enable WiFi + ESP-Now // Enable long range, PHY rate of ESP32 will be 512Kbps or 256Kbps esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); + Serial.println("Wi-Fi on, ESP-Now added to protocols"); } //If ESP-Now is active, WiFi is active, do nothing else @@ -115,6 +110,8 @@ void espnowStart() Serial.println("Error initializing ESP-NOW"); return; } + else + Serial.println("ESP-NOW Initialized"); // Use promiscuous callback to capture RSSI of packet esp_wifi_set_promiscuous(true); @@ -146,22 +143,17 @@ void espnowStart() } } } - -#else - Serial.println("Error - WiFi not compiled"); -#endif } //If WiFi is already enabled, simply remove the LR protocol //If WiFi is off, stop the radio entirely void espnowStop() { -#ifdef COMPILE_WIFI if(espnowState == ESPNOW_OFF) return; - if (wifiState > WIFI_OFF) + if (wifiState == WIFI_OFF) { - //Radio is on, turn it off entirely + //ESP Now is the only thing using the radio, turn it off entirely WiFi.mode(WIFI_OFF); Serial.println("WiFi Radio off entirely"); } @@ -170,7 +162,7 @@ void espnowStop() { // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); - Serial.println("WiFi protocol on, LR protocol off"); + Serial.println("WiFi protocols on, LR protocol off"); } // Turn off promiscuous WiFi mode @@ -190,16 +182,13 @@ void espnowStop() espnowSetState(ESPNOW_OFF); Serial.println("ESP NOW Off"); -#else - Serial.println("Error - WiFi not compiled"); -#endif } //Begin broadcasting our MAC and wait for remote unit to respond void espnowBeginPairing() { -#ifdef COMPILE_WIFI espnowStart(); + Serial.println("1"); // To begin pairing, we must add the broadcast MAC to the peer list uint8_t broadcastMac[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; @@ -255,15 +244,11 @@ void espnowBeginPairing() } Serial.println("User pressed button. Pairing canceled."); -#else - Serial.println("WiFi not compiled"); -#endif } //Create special pair packet to a given MAC esp_err_t espnowSendPairMessage(uint8_t *sendToMac) { -#ifdef COMPILE_WIFI // Assemble message to send PairMessage pairMessage; @@ -279,9 +264,6 @@ esp_err_t espnowSendPairMessage(uint8_t *sendToMac) pairMessage.crc += unitMACAddress[x]; return (esp_now_send(sendToMac, (uint8_t *) &pairMessage, sizeof(pairMessage))); //Send packet to given MAC -#else - return (ESP_OK); -#endif } //Add a given MAC address to the peer list @@ -292,7 +274,6 @@ esp_err_t espnowAddPeer(uint8_t *peerMac) esp_err_t espnowAddPeer(uint8_t *peerMac, bool encrypt) { -#ifdef COMPILE_WIFI esp_now_peer_info_t peerInfo; memcpy(peerInfo.peer_addr, peerMac, 6); @@ -306,35 +287,25 @@ esp_err_t espnowAddPeer(uint8_t *peerMac, bool encrypt) if (result != ESP_OK) log_d("Failed to add peer"); return (result); -#else - return (ESP_OK); -#endif } //Remove a given MAC address from the peer list esp_err_t espnowRemovePeer(uint8_t *peerMac) { -#ifdef COMPILE_WIFI esp_err_t result = esp_now_del_peer(peerMac); if (result != ESP_OK) log_d("Failed to remove peer"); return (result); -#else - return (ESP_OK); -#endif } //Update the state of the ESP Now state machine -void espnowSetState (byte newState) +void espnowSetState(byte newState) { if (espnowState == newState) Serial.print("*"); espnowState = newState; switch (newState) { - default: - Serial.printf("Unknown ESPNOW state: %d\r\n", newState); - break; case ESPNOW_OFF: Serial.println("ESPNOW_OFF"); break; @@ -350,5 +321,10 @@ void espnowSetState (byte newState) case ESPNOW_PAIRED: Serial.println("ESPNOW_PAIRED"); break; + default: + Serial.printf("Unknown ESPNOW state: %d\r\n", newState); + break; } } + +#endif //ifdef COMPILE_ESPNOW diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index fae9d05fd..acf67ed83 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -915,6 +915,7 @@ bool parseLine(char* str, Settings *settings) } //Scan for ESPNOW peers +#ifdef COMPILE_ESPNOW if (knownSetting == false) { for (int x = 0 ; x < ESPNOW_MAX_PEERS ; x++) @@ -939,6 +940,7 @@ bool parseLine(char* str, Settings *settings) } } } +#endif //ifdef COMPILE_ESPNOW //Last catch if (knownSetting == false) diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 63b89d82a..54035de9e 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -26,8 +26,9 @@ const int FIRMWARE_VERSION_MAJOR = 2; const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_WIFI //Comment out to remove WiFi functionality -//#define COMPILE_BT //Comment out to remove Bluetooth functionality +#define COMPILE_BT //Comment out to remove Bluetooth functionality #define COMPILE_AP //Comment out to remove Access Point functionality +//#define COMPILE_ESPNOW //Comment out to remove ESP-Now functionality #define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) //Define the RTK board identifier: @@ -347,13 +348,11 @@ float lBandEBNO = 0.0; //Used on system status menu //ESP NOW for multipoint wireless broadcasting over 2.4GHz //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- -#ifdef COMPILE_WIFI +#ifdef COMPILE_ESPNOW #include #include "esp_wifi.h" //Needed for esp_wifi_set_protocol() -#endif - uint8_t espnowOutgoing[250]; //ESP NOW has max of 250 characters unsigned long espnowLastAdd; //Tracks how long since last byte was added to the outgoing buffer uint8_t espnowOutgoingSpot = 0; @@ -364,6 +363,7 @@ int packetRSSI = 0; unsigned long lastEspnowRssiUpdate = 0; const uint8_t ESPNOW_MAX_PEERS = 5; //Maximum of 5 rovers +#endif //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- //Global variables @@ -568,8 +568,6 @@ void setup() beginSystemState(); //Determine initial system state. Start task for button monitoring. - beginRadio(); //Start internal radio if enabled - updateRTC(); //The GNSS likely has time/date. Update ESP32 RTC to match. Needed for PointPerfect key expiration. Serial.flush(); //Complete any previous prints @@ -669,7 +667,7 @@ void updateLogs() { //This is OK because in the interim more data will be written to the log //and the log file will eventually be synced by the next call in loop - log_d("sdCardSemaphore failed to yield, RTK_Surveyor.ino line %d\r\n", __LINE__); + log_d("sdCardSemaphore failed to yield, RTK_Surveyor.ino line %d", __LINE__); } } @@ -697,7 +695,7 @@ void updateLogs() //While a retry does occur during the next loop, it is possible to loose //trigger events if they occur too rapidly or if the log file is closed //before the trigger event is written! - log_w("sdCardSemaphore failed to yield, RTK_Surveyor.ino line %d\r\n", __LINE__); + log_w("sdCardSemaphore failed to yield, RTK_Surveyor.ino line %d", __LINE__); } } @@ -717,7 +715,7 @@ void updateLogs() { //This is OK because outputting this message is not critical to the RTK //operation and the message will be output by the next call in loop - log_d("sdCardSemaphore failed to yield, RTK_Surveyor.ino line %d\r\n", __LINE__); + log_d("sdCardSemaphore failed to yield, RTK_Surveyor.ino line %d", __LINE__); } if (fileSize > 0) @@ -830,6 +828,7 @@ void updateRTC() //Internal ESP NOW radio - Use the ESP32 to directly transmit/receive RTCM over 2.4GHz (no WiFi needed) void updateRadio() { +#ifdef COMPILE_ESPNOW if (settings.radioType == RADIO_ESPNOW) { if (espnowState == ESPNOW_PAIRED) @@ -838,10 +837,8 @@ void updateRadio() //then we've reached the end of the RTCM stream. Send partial buffer. if (espnowOutgoingSpot > 0 && (millis() - espnowLastAdd) > 50) { -#ifdef COMPILE_WIFI esp_now_send(0, (uint8_t *) &espnowOutgoing, espnowOutgoingSpot); //Send partial packet to all peers //log_d("ESPNOW: Sending %d bytes", espnowOutgoingSpot); -#endif espnowOutgoingSpot = 0; //Reset } @@ -851,4 +848,5 @@ void updateRadio() espnowRSSI = -255; } } +#endif } diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 7031b983f..f96d9e3c6 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -116,7 +116,10 @@ void updateSystemState() i2cGNSS.enableRTCMmessage(UBX_RTCM_1230, COM_PORT_UART2, 0); //Disable RTCM sentences + wifiStop(); //Stop WiFi, ntripClient will start as needed. bluetoothStart(); //Turn on Bluetooth with 'Rover' name + radioStart(); //Start internal radio if enabled, otherwise disable + startUART2Tasks(); //Start monitoring the UART1 from ZED for NMEA and UBX data (enables logging) settings.updateZEDSettings = false; //On the next boot, no need to update the ZED on this profile @@ -315,9 +318,7 @@ void updateSystemState() if (settings.enableNtripServer == true) ntripServerStart(); - //Start ESP-Now if requested - if (settings.radioType == RADIO_ESPNOW) - espnowStart(); + radioStart(); //Start internal radio if enabled, otherwise disable rtcmPacketsSent = 0; //Reset any previous number changeState(STATE_BASE_TEMP_TRANSMITTING); @@ -382,9 +383,7 @@ void updateSystemState() if (settings.enableNtripServer) ntripServerStart(); - //Start ESP-Now if requested - if (settings.radioType == RADIO_ESPNOW) - espnowStart(); + radioStart(); //Start internal radio if enabled, otherwise disable changeState(STATE_BASE_FIXED_TRANSMITTING); } @@ -595,6 +594,9 @@ void updateSystemState() displayWiFiConfigNotStarted(); //Display immediately during SD cluster pause bluetoothStop(); +#ifdef COMPILE_ESPNOW + espnowStop(); +#endif stopUART2Tasks(); //Delete F9 serial tasks if running startWebServer(); //Start in AP mode and show config html page diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 2a88e0b12..67015d3c0 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -174,7 +174,7 @@ void F9PSerialReadTask(void *e) if (btBytesToSend > 0) online.txNtripDataCasting = true; else - log_w("WARNING - BT failed to send"); + log_w("BT failed to send"); } else { @@ -187,7 +187,7 @@ void F9PSerialReadTask(void *e) } else { - log_w("WARNING - BT congestion delayed %d bytes, Tasks.ino line %d", btBytesToSend, __LINE__); + log_w("BT congestion delayed %d bytes, Tasks.ino line %d", btBytesToSend, __LINE__); btBytesToSend = 0; } } @@ -240,7 +240,7 @@ void F9PSerialReadTask(void *e) Serial.printf("ERROR - Dropped %d bytes: GNSS --> log file\r\n", sdBytesToRecord); } else - log_w("WARNING - sdCardSemaphore failed to yield, Tasks.ino line %d", __LINE__); + log_w("sdCardSemaphore failed to yield, Tasks.ino line %d", __LINE__); } } //End maxLogTime } //End logging diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index f70727a90..c80008dd2 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -85,8 +85,10 @@ void menuMain() menuUserProfiles(); else if (incoming == 'P' && online.lband == true) menuPointPerfect(); +#ifdef COMPILE_ESPNOW else if (incoming == 'r') menuRadio(); +#endif else if (incoming == 'f' && binCount > 0) menuFirmware(); else if (incoming == 'x') @@ -294,6 +296,7 @@ void factoryReset() //Configure the internal radio, if available void menuRadio() { +#ifdef COMPILE_ESPNOW while (1) { Serial.println(); @@ -370,7 +373,8 @@ void menuRadio() printUnknown(incoming); } - beginRadio(); + radioStart(); while (Serial.available()) Serial.read(); //Empty buffer of any newline chars +#endif } diff --git a/Firmware/RTK_Surveyor/menuMessages.ino b/Firmware/RTK_Surveyor/menuMessages.ino index 4b23b6264..d96ca31a9 100644 --- a/Firmware/RTK_Surveyor/menuMessages.ino +++ b/Firmware/RTK_Surveyor/menuMessages.ino @@ -485,7 +485,7 @@ void endLogging(bool gotSemaphore, bool releaseSemaphore) { //This is OK because in the interim more data will be written to the log //and the log file will eventually be closed by the next call in loop - log_d("sdCardSemaphore failed to yield, menuMessages.ino line %d\r\n", __LINE__); + log_d("sdCardSemaphore failed to yield, menuMessages.ino line %d", __LINE__); } } } diff --git a/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp b/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp index b26c1fe7c..ab70d3024 100644 --- a/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp +++ b/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp @@ -175,14 +175,13 @@ static esp_err_t _spp_queue_packet(uint8_t *data, size_t len){ //At ~50kBps heap lowest point is ~78k and stable //Above 50kbps it becomes unstable -const uint16_t SPP_TX_MAX = 330; //Original -//const uint16_t SPP_TX_MAX = 400; //Original -//const uint16_t SPP_TX_MAX = 1024*4; //Should match the SERIAL_SIZE_RX buffer size in RTK_Surveyor.ino +//const uint16_t SPP_TX_MAX = 330; //Original +const uint16_t SPP_TX_MAX = 1024*4; //Should match the SERIAL_SIZE_RX buffer size in RTK_Surveyor.ino /* -**Anything** other than 330 seems to cause the BT que to stop transmitting -This started with the addition of the circular que. Resorting to original BT lib helps but the congestion -is overwhelming. +During ESP Now development the hardware got into a very bad state and Bluetooth was acting very +oddly. Eventually, WiFi would not connect (Reason: 202 - AUTH_FAIL) even using stock examples. +The solution was, unexplicably, a full flash erase. Everything worked after that. */ static uint8_t _spp_tx_buffer[SPP_TX_MAX]; From db1412fb643555a8f027412f7f2479851cfa1a39 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Mon, 8 Aug 2022 10:08:55 -0500 Subject: [PATCH 031/134] Add gates to ESP Now functions --- Firmware/RTK_Surveyor/WiFi.ino | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 4a7fefbbc..7d6d99249 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -145,8 +145,10 @@ void wifiStartAP() #define WIFI_PASSWORD "parachutes" WiFi.mode(WIFI_STA); +#ifdef COMPILE_ESPNOW // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); +#endif WiFi.begin(WIFI_SSID, WIFI_PASSWORD); Serial.print("Wi-Fi connecting to"); @@ -161,8 +163,10 @@ void wifiStartAP() //Start in AP mode WiFi.mode(WIFI_AP); +#ifdef COMPILE_ESPNOW // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); +#endif IPAddress local_IP(192, 168, 4, 1); IPAddress gateway(192, 168, 1, 1); @@ -203,12 +207,20 @@ void wifiStart(char* ssid, char* pw) #ifdef COMPILE_WIFI if ((wifiState == WIFI_OFF) || (wifiState == WIFI_ON)) { +#ifdef COMPILE_ESPNOW //If ESP-Now is active, reconfigure protocols if (espnowState > ESPNOW_OFF) { + Serial.println("Mixing WiFi into ESPNOW setup"); //Enable WiFi + ESP-Now esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); } + else + { + //Radio is off, turn it on + WiFi.mode(WIFI_STA); + } +#endif Serial.printf("Wi-Fi connecting to %s\r\n", ssid); WiFi.begin(ssid, pw); @@ -233,6 +245,8 @@ void wifiStop() { //Do nothing } + +#ifdef COMPILE_ESPNOW //If WiFi is on but ESP NOW is off, then turn off radio entirely else if (espnowState == ESPNOW_OFF) { @@ -252,6 +266,12 @@ void wifiStop() Serial.println("Wi-Fi disabled, ESP-Now left in place"); } +#else + //Turn off radio + WiFi.mode(WIFI_OFF); + wifiSetState(WIFI_OFF); + Serial.println("Wi-Fi Stopped"); +#endif //Display the heap state reportHeapNow(); From 40b3d29f4995adfbccfc4c61eb729fc64c1c011c Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Mon, 8 Aug 2022 10:27:52 -0500 Subject: [PATCH 032/134] Fix uptime --- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 2 -- Firmware/RTK_Surveyor/menuSystem.ino | 7 ++++--- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 54035de9e..764f3b813 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -454,8 +454,6 @@ unsigned long rtcWaitTime = 0; //At poweron, we give the RTC a few seconds to up TaskHandle_t idleTaskHandle[MAX_CPU_CORES]; uint32_t max_idle_count = MAX_IDLE_TIME_COUNT; -uint64_t uptime; -uint32_t previousMilliseconds; //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- /* +---------------------------------------+ +----------+ diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index c1d5a5ac4..d0c593e84 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -107,7 +107,7 @@ void menuSystem() Serial.println(); //Display the uptime - uint64_t uptimeMilliseconds = uptime; + uint64_t uptimeMilliseconds = millis(); uint32_t uptimeDays = 0; while (uptimeMilliseconds >= MILLISECONDS_IN_A_DAY) { uptimeMilliseconds -= MILLISECONDS_IN_A_DAY; @@ -129,12 +129,13 @@ void menuSystem() uptimeSeconds += 1; } Serial.print("Uptime: "); - Serial.printf("%d %02d:%02d:%02d.%03lld\r\n", + Serial.printf("%d %02d:%02d:%02d.%03lld (Resets: %d)\r\n", uptimeDays, uptimeHours, uptimeMinutes, uptimeSeconds, - uptimeMilliseconds); + uptimeMilliseconds, + settings.resetCount); if (settings.enableSD == true) { From 0ecf8eabed46da64e2d870c9cad9c361f1e49805 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Mon, 8 Aug 2022 06:53:43 -1000 Subject: [PATCH 033/134] Add define for COMPILE_L_BAND, move L-Band related items into menuPP.ino The following items were moved into menuPP.ino * L-Band variables * beginLBand routine --- Firmware/RTK_Surveyor/Begin.ino | 83 ------ Firmware/RTK_Surveyor/RTK_Surveyor.ino | 13 +- Firmware/RTK_Surveyor/States.ino | 4 + Firmware/RTK_Surveyor/menuPP.ino | 395 ++++++++++++++++--------- 4 files changed, 264 insertions(+), 231 deletions(-) diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index 931973247..60547cc76 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -710,89 +710,6 @@ bool beginExternalTriggers() return (response); } -//Check if NEO-D9S is connected. Configure if available. -void beginLBand() -{ - if (i2cLBand.begin(Wire, 0x43) == false) //Connect to the u-blox NEO-D9S using Wire port. The D9S default I2C address is 0x43 (not 0x42) - { - log_d("L-Band not detected"); - return; - } - - //Check the firmware version of the NEO-D9S. Based on Example21_ModuleInfo. - if (i2cLBand.getModuleInfo(1100) == true) // Try to get the module info - { - //i2cLBand.minfo.extension[1] looks like 'FWVER=HPG 1.12' - strcpy(neoFirmwareVersion, i2cLBand.minfo.extension[1]); - - //Remove 'FWVER='. It's extraneous and = causes settings file parsing issues - char *ptr = strstr(neoFirmwareVersion, "FWVER="); - if (ptr != NULL) - strcpy(neoFirmwareVersion, ptr + strlen("FWVER=")); - - printNEOInfo(); //Print module firmware version - } - - if (online.gnss == true) - { - i2cGNSS.checkUblox(); //Regularly poll to get latest data and any RTCM - i2cGNSS.checkCallbacks(); //Process any callbacks: ie, eventTriggerReceived - } - - //If we have a fix, check which frequency to use - if (fixType == 2 || fixType == 3 || fixType == 4 || fixType == 5) //2D, 3D, 3D+DR, or Time - { - if ( (longitude > -125 && longitude < -67) && (latitude > -90 && latitude < 90)) - { - log_d("Setting L-Band to US"); - settings.LBandFreq = 1556290000; //We are in US band - } - else if ( (longitude > -25 && longitude < 70) && (latitude > -90 && latitude < 90)) - { - log_d("Setting L-Band to EU"); - settings.LBandFreq = 1545260000; //We are in EU band - } - else - { - Serial.println("Unknown band area"); - settings.LBandFreq = 1556290000; //Default to US - } - recordSystemSettings(); - } - else - log_d("No fix available for L-Band frequency determination"); - - bool response = true; - response &= i2cLBand.setVal32(UBLOX_CFG_PMP_CENTER_FREQUENCY, settings.LBandFreq); // Default 1539812500 Hz - response &= i2cLBand.setVal16(UBLOX_CFG_PMP_SEARCH_WINDOW, 2200); // Default 2200 Hz - response &= i2cLBand.setVal8(UBLOX_CFG_PMP_USE_SERVICE_ID, 0); // Default 1 - response &= i2cLBand.setVal16(UBLOX_CFG_PMP_SERVICE_ID, 21845); // Default 50821 - response &= i2cLBand.setVal16(UBLOX_CFG_PMP_DATA_RATE, 2400); // Default 2400 bps - response &= i2cLBand.setVal8(UBLOX_CFG_PMP_USE_DESCRAMBLER, 1); // Default 1 - response &= i2cLBand.setVal16(UBLOX_CFG_PMP_DESCRAMBLER_INIT, 26969); // Default 23560 - response &= i2cLBand.setVal8(UBLOX_CFG_PMP_USE_PRESCRAMBLING, 0); // Default 0 - response &= i2cLBand.setVal64(UBLOX_CFG_PMP_UNIQUE_WORD, 16238547128276412563ull); - response &= i2cLBand.setVal(UBLOX_CFG_MSGOUT_UBX_RXM_PMP_I2C, 1); // Ensure UBX-RXM-PMP is enabled on the I2C port - response &= i2cLBand.setVal(UBLOX_CFG_MSGOUT_UBX_RXM_PMP_UART1, 1); // Output UBX-RXM-PMP on UART1 - response &= i2cLBand.setVal(UBLOX_CFG_UART2OUTPROT_UBX, 1); // Enable UBX output on UART2 - response &= i2cLBand.setVal(UBLOX_CFG_MSGOUT_UBX_RXM_PMP_UART2, 1); // Output UBX-RXM-PMP on UART2 - response &= i2cLBand.setVal32(UBLOX_CFG_UART1_BAUDRATE, 38400); // match baudrate with ZED default - response &= i2cLBand.setVal32(UBLOX_CFG_UART2_BAUDRATE, 38400); // match baudrate with ZED default - - if (response == false) - Serial.println("L-Band failed to configure"); - - i2cLBand.softwareResetGNSSOnly(); // Do a restart - - i2cLBand.setRXMPMPmessageCallbackPtr(&pushRXMPMP); // Call pushRXMPMP when new PMP data arrives. Push it to the GNSS - - i2cGNSS.setRXMCORcallbackPtr(&checkRXMCOR); // Check if the PMP data is being decrypted successfully - - log_d("L-Band online"); - - online.lband = true; -} - void beginIdleTasks() { char taskName[32]; diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 8ac894549..23050f1c7 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -28,6 +28,7 @@ const int FIRMWARE_VERSION_MINOR = 3; #define COMPILE_WIFI //Comment out to remove WiFi functionality #define COMPILE_BT //Comment out to remove Bluetooth functionality #define COMPILE_AP //Comment out to remove Access Point functionality +#define COMPILE_L_BAND //Comment out to remove L-Band functionality //#define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) //Define the RTK board identifier: @@ -321,18 +322,6 @@ unsigned long timeSinceLastIncomingSetting = 0; //PointPerfect Corrections //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= -SFE_UBLOX_GNSS_ADD i2cLBand; // NEO-D9S -const char* pointPerfectKeyTopic = "/pp/ubx/0236/Lb"; - -//The PointPerfect token is provided at compile time via build flags -#ifndef POINTPERFECT_TOKEN -#define POINTPERFECT_TOKEN 0xAA, 0xBB, 0xCC, 0xDD, 0x00, 0x11, 0x22, 0x33, 0x0A, 0x0B, 0x0C, 0x0D, 0x00, 0x01, 0x02, 0x03 -#endif - -uint8_t pointPerfectTokenArray[16] = {POINTPERFECT_TOKEN}; //Token in HEX form - -const char* pointPerfectAPI = "https://api.thingstream.io/ztp/pointperfect/credentials"; -void checkRXMCOR(UBX_RXM_COR_data_t *ubxDataStruct); float lBandEBNO = 0.0; //Used on system status menu //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 784e46792..21f789544 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -655,6 +655,7 @@ void updateSystemState() } break; +#ifdef COMPILE_L_BAND case (STATE_KEYS_STARTED): { if (rtcWaitTime == 0) rtcWaitTime = millis(); @@ -898,6 +899,7 @@ void updateSystemState() changeState(settings.lastState); //Go to either rover or base } break; +#endif //COMPILE_L_BAND case (STATE_SHUTDOWN): { @@ -1002,6 +1004,7 @@ void changeState(SystemState newState) case (STATE_PROFILE): Serial.print("State: Profile"); break; +#ifdef COMPILE_L_BAND case (STATE_KEYS_STARTED): Serial.print("State: Keys Started "); break; @@ -1038,6 +1041,7 @@ void changeState(SystemState newState) case (STATE_KEYS_PROVISION_WIFI_TIMEOUT): Serial.print("State: Keys Provision - WiFi Timeout"); break; +#endif //COMPILE_L_BAND case (STATE_SHUTDOWN): Serial.print("State: Shut Down"); diff --git a/Firmware/RTK_Surveyor/menuPP.ino b/Firmware/RTK_Surveyor/menuPP.ino index e958e8126..b59cf7ccc 100644 --- a/Firmware/RTK_Surveyor/menuPP.ino +++ b/Firmware/RTK_Surveyor/menuPP.ino @@ -1,133 +1,30 @@ -//Set 'home' WiFi credentials -//Provision device on ThingStream -//Download keys -void menuPointPerfect() -{ - int menuTimeoutExtended = 30; //Increase time needed for complex data entry (mount point ID, caster credentials, etc). - - while (1) - { - Serial.println(); - Serial.println("Menu: PointPerfect Corrections"); - - char hardwareID[13]; - sprintf(hardwareID, "%02X%02X%02X%02X%02X%02X", unitMACAddress[0], unitMACAddress[1], unitMACAddress[2], unitMACAddress[3], unitMACAddress[4], unitMACAddress[5]); //Get ready for JSON - Serial.printf("Device ID: %s\n\r", hardwareID); - - Serial.print("Days until keys expire: "); - if (strlen(settings.pointPerfectCurrentKey) > 0) - { - uint8_t daysRemaining = daysFromEpoch(settings.pointPerfectNextKeyStart + settings.pointPerfectNextKeyDuration + 1); - Serial.println(daysRemaining); - } - else - Serial.println("No keys"); - - Serial.print("1) Use PointPerfect Corrections: "); - if (settings.enablePointPerfectCorrections == true) Serial.println("Enabled"); - else Serial.println("Disabled"); - - Serial.print("2) Set Home WiFi SSID: "); - Serial.println(settings.home_wifiSSID); - - Serial.print("3) Set Home WiFi PW: "); - Serial.println(settings.home_wifiPW); - - Serial.print("4) Toggle Auto Key Renewal: "); - if (settings.autoKeyRenewal == true) Serial.println("Enabled"); - else Serial.println("Disabled"); - - if (strlen(settings.pointPerfectCurrentKey) == 0 || strlen(settings.pointPerfectLBandTopic) == 0) - Serial.println("5) Provision Device"); - else - Serial.println("5) Update Keys"); - - Serial.println("k) Manual Key Entry"); +#ifdef COMPILE_L_BAND - Serial.println("x) Exit"); +//---------------------------------------- +// Locals - compiled out +//---------------------------------------- - byte incoming = getByteChoice(menuTimeout); //Timeout after x seconds - - if (incoming == '1') - { - settings.enablePointPerfectCorrections ^= 1; - } - else if (incoming == '2') - { - Serial.print("Enter Home WiFi SSID: "); - readLine(settings.home_wifiSSID, sizeof(settings.home_wifiSSID), menuTimeoutExtended); - } - else if (incoming == '3') - { - Serial.printf("Enter password for Home WiFi network %s: ", settings.home_wifiSSID); - readLine(settings.home_wifiPW, sizeof(settings.home_wifiPW), menuTimeoutExtended); - } - else if (incoming == '4') - { - settings.autoKeyRenewal ^= 1; - } - else if (incoming == '5') - { -#ifdef COMPILE_WIFI - wifiStart(settings.home_wifiSSID, settings.home_wifiPW); - - unsigned long startTime = millis(); - while (wifiGetStatus() != WL_CONNECTED) - { - delay(500); - Serial.print("."); - if (millis() - startTime > 8000) break; //Give up after 8 seconds - } +static SFE_UBLOX_GNSS_ADD i2cLBand; // NEO-D9S +static const char* pointPerfectKeyTopic = "/pp/ubx/0236/Lb"; - if (wifiGetStatus() == WL_CONNECTED) - { +//The PointPerfect token is provided at compile time via build flags +#ifndef POINTPERFECT_TOKEN +#define POINTPERFECT_TOKEN 0xAA, 0xBB, 0xCC, 0xDD, 0x00, 0x11, 0x22, 0x33, 0x0A, 0x0B, 0x0C, 0x0D, 0x00, 0x01, 0x02, 0x03 +#endif - Serial.println(); - Serial.print("WiFi connected: "); - Serial.println(wifiGetIpAddress()); +static uint8_t pointPerfectTokenArray[16] = {POINTPERFECT_TOKEN}; //Token in HEX form - //Check if we have certificates - char fileName[80]; - sprintf(fileName, "/%s_%s_%d.txt", platformFilePrefix, "certificate", profileNumber); - if (LittleFS.exists(fileName) == false) - { - provisionDevice(); //Connect to ThingStream API and get keys - } - else if (strlen(settings.pointPerfectCurrentKey) == 0 || strlen(settings.pointPerfectLBandTopic) == 0) - { - provisionDevice(); //Connect to ThingStream API and get keys - } - else - updatePointPerfectKeys(); - } +static const char* pointPerfectAPI = "https://api.thingstream.io/ztp/pointperfect/credentials"; - bluetoothStart(); -#endif - } - else if (incoming == '6') - { - LittleFS.format(); - log_d("Formatted"); - } - else if (incoming == 'k') - { - menuPointPerfectKeys(); - } - else if (incoming == 'x') - break; - else if (incoming == STATUS_GETBYTE_TIMEOUT) - break; - else - printUnknown(incoming); - } +//---------------------------------------- +// Forward declarations - compiled out +//---------------------------------------- - if (strlen(settings.pointPerfectClientID) > 0) - { - applyLBandKeys(); - } +void checkRXMCOR(UBX_RXM_COR_data_t *ubxDataStruct); - while (Serial.available()) Serial.read(); //Empty buffer of any newline chars -} +//---------------------------------------- +// L-Band Routines - compiled out +//---------------------------------------- void menuPointPerfectKeys() { @@ -776,20 +673,6 @@ long gpsToMjd(long GpsCycle, long GpsWeek, long GpsSeconds) return dateToMjd(1980, 1, 6) + GpsDays; } -//Process any new L-Band from I2C -//If a certain amount of time has elapsed between last decryption, turn off L-Band icon -void updateLBand() -{ - if (online.lbandCorrections == true) - { - i2cLBand.checkUblox(); // Check for the arrival of new PMP data and process it. - i2cLBand.checkCallbacks(); // Check if any L-Band callbacks are waiting to be processed. - - if (lbandCorrectionsReceived == true && millis() - lastLBandDecryption > 5000) - lbandCorrectionsReceived = false; - } -} - //When new PMP message arrives from NEO-D9S push it back to ZED-F9P void pushRXMPMP(UBX_RXM_PMP_message_data_t *pmpData) { @@ -879,3 +762,243 @@ void checkRXMCOR(UBX_RXM_COR_data_t *ubxDataStruct) log_d("PMP decryption failed"); } } + +#endif //COMPILE_L_BAND + +//---------------------------------------- +// Global L-Band Routines +//---------------------------------------- + +//Check if NEO-D9S is connected. Configure if available. +void beginLBand() +{ +#ifdef COMPILE_L_BAND + if (i2cLBand.begin(Wire, 0x43) == false) //Connect to the u-blox NEO-D9S using Wire port. The D9S default I2C address is 0x43 (not 0x42) + { + log_d("L-Band not detected"); + return; + } + + //Check the firmware version of the NEO-D9S. Based on Example21_ModuleInfo. + if (i2cLBand.getModuleInfo(1100) == true) // Try to get the module info + { + //i2cLBand.minfo.extension[1] looks like 'FWVER=HPG 1.12' + strcpy(neoFirmwareVersion, i2cLBand.minfo.extension[1]); + + //Remove 'FWVER='. It's extraneous and = causes settings file parsing issues + char *ptr = strstr(neoFirmwareVersion, "FWVER="); + if (ptr != NULL) + strcpy(neoFirmwareVersion, ptr + strlen("FWVER=")); + + printNEOInfo(); //Print module firmware version + } + + if (online.gnss == true) + { + i2cGNSS.checkUblox(); //Regularly poll to get latest data and any RTCM + i2cGNSS.checkCallbacks(); //Process any callbacks: ie, eventTriggerReceived + } + + //If we have a fix, check which frequency to use + if (fixType == 2 || fixType == 3 || fixType == 4 || fixType == 5) //2D, 3D, 3D+DR, or Time + { + if ( (longitude > -125 && longitude < -67) && (latitude > -90 && latitude < 90)) + { + log_d("Setting L-Band to US"); + settings.LBandFreq = 1556290000; //We are in US band + } + else if ( (longitude > -25 && longitude < 70) && (latitude > -90 && latitude < 90)) + { + log_d("Setting L-Band to EU"); + settings.LBandFreq = 1545260000; //We are in EU band + } + else + { + Serial.println("Unknown band area"); + settings.LBandFreq = 1556290000; //Default to US + } + recordSystemSettings(); + } + else + log_d("No fix available for L-Band frequency determination"); + + bool response = true; + response &= i2cLBand.setVal32(UBLOX_CFG_PMP_CENTER_FREQUENCY, settings.LBandFreq); // Default 1539812500 Hz + response &= i2cLBand.setVal16(UBLOX_CFG_PMP_SEARCH_WINDOW, 2200); // Default 2200 Hz + response &= i2cLBand.setVal8(UBLOX_CFG_PMP_USE_SERVICE_ID, 0); // Default 1 + response &= i2cLBand.setVal16(UBLOX_CFG_PMP_SERVICE_ID, 21845); // Default 50821 + response &= i2cLBand.setVal16(UBLOX_CFG_PMP_DATA_RATE, 2400); // Default 2400 bps + response &= i2cLBand.setVal8(UBLOX_CFG_PMP_USE_DESCRAMBLER, 1); // Default 1 + response &= i2cLBand.setVal16(UBLOX_CFG_PMP_DESCRAMBLER_INIT, 26969); // Default 23560 + response &= i2cLBand.setVal8(UBLOX_CFG_PMP_USE_PRESCRAMBLING, 0); // Default 0 + response &= i2cLBand.setVal64(UBLOX_CFG_PMP_UNIQUE_WORD, 16238547128276412563ull); + response &= i2cLBand.setVal(UBLOX_CFG_MSGOUT_UBX_RXM_PMP_I2C, 1); // Ensure UBX-RXM-PMP is enabled on the I2C port + response &= i2cLBand.setVal(UBLOX_CFG_MSGOUT_UBX_RXM_PMP_UART1, 1); // Output UBX-RXM-PMP on UART1 + response &= i2cLBand.setVal(UBLOX_CFG_UART2OUTPROT_UBX, 1); // Enable UBX output on UART2 + response &= i2cLBand.setVal(UBLOX_CFG_MSGOUT_UBX_RXM_PMP_UART2, 1); // Output UBX-RXM-PMP on UART2 + response &= i2cLBand.setVal32(UBLOX_CFG_UART1_BAUDRATE, 38400); // match baudrate with ZED default + response &= i2cLBand.setVal32(UBLOX_CFG_UART2_BAUDRATE, 38400); // match baudrate with ZED default + + if (response == false) + Serial.println("L-Band failed to configure"); + + i2cLBand.softwareResetGNSSOnly(); // Do a restart + + i2cLBand.setRXMPMPmessageCallbackPtr(&pushRXMPMP); // Call pushRXMPMP when new PMP data arrives. Push it to the GNSS + + i2cGNSS.setRXMCORcallbackPtr(&checkRXMCOR); // Check if the PMP data is being decrypted successfully + + log_d("L-Band online"); + + online.lband = true; +#endif //COMPILE_L_BAND +} + +//Set 'home' WiFi credentials +//Provision device on ThingStream +//Download keys +void menuPointPerfect() +{ +#ifdef COMPILE_L_BAND + int menuTimeoutExtended = 30; //Increase time needed for complex data entry (mount point ID, caster credentials, etc). + + while (1) + { + Serial.println(); + Serial.println("Menu: PointPerfect Corrections"); + + char hardwareID[13]; + sprintf(hardwareID, "%02X%02X%02X%02X%02X%02X", unitMACAddress[0], unitMACAddress[1], unitMACAddress[2], unitMACAddress[3], unitMACAddress[4], unitMACAddress[5]); //Get ready for JSON + Serial.printf("Device ID: %s\n\r", hardwareID); + + Serial.print("Days until keys expire: "); + if (strlen(settings.pointPerfectCurrentKey) > 0) + { + uint8_t daysRemaining = daysFromEpoch(settings.pointPerfectNextKeyStart + settings.pointPerfectNextKeyDuration + 1); + Serial.println(daysRemaining); + } + else + Serial.println("No keys"); + + Serial.print("1) Use PointPerfect Corrections: "); + if (settings.enablePointPerfectCorrections == true) Serial.println("Enabled"); + else Serial.println("Disabled"); + + Serial.print("2) Set Home WiFi SSID: "); + Serial.println(settings.home_wifiSSID); + + Serial.print("3) Set Home WiFi PW: "); + Serial.println(settings.home_wifiPW); + + Serial.print("4) Toggle Auto Key Renewal: "); + if (settings.autoKeyRenewal == true) Serial.println("Enabled"); + else Serial.println("Disabled"); + + if (strlen(settings.pointPerfectCurrentKey) == 0 || strlen(settings.pointPerfectLBandTopic) == 0) + Serial.println("5) Provision Device"); + else + Serial.println("5) Update Keys"); + + Serial.println("k) Manual Key Entry"); + + Serial.println("x) Exit"); + + byte incoming = getByteChoice(menuTimeout); //Timeout after x seconds + + if (incoming == '1') + { + settings.enablePointPerfectCorrections ^= 1; + } + else if (incoming == '2') + { + Serial.print("Enter Home WiFi SSID: "); + readLine(settings.home_wifiSSID, sizeof(settings.home_wifiSSID), menuTimeoutExtended); + } + else if (incoming == '3') + { + Serial.printf("Enter password for Home WiFi network %s: ", settings.home_wifiSSID); + readLine(settings.home_wifiPW, sizeof(settings.home_wifiPW), menuTimeoutExtended); + } + else if (incoming == '4') + { + settings.autoKeyRenewal ^= 1; + } + else if (incoming == '5') + { +#ifdef COMPILE_WIFI + wifiStart(settings.home_wifiSSID, settings.home_wifiPW); + + unsigned long startTime = millis(); + while (wifiGetStatus() != WL_CONNECTED) + { + delay(500); + Serial.print("."); + if (millis() - startTime > 8000) break; //Give up after 8 seconds + } + + if (wifiGetStatus() == WL_CONNECTED) + { + + Serial.println(); + Serial.print("WiFi connected: "); + Serial.println(wifiGetIpAddress()); + + //Check if we have certificates + char fileName[80]; + sprintf(fileName, "/%s_%s_%d.txt", platformFilePrefix, "certificate", profileNumber); + if (LittleFS.exists(fileName) == false) + { + provisionDevice(); //Connect to ThingStream API and get keys + } + else if (strlen(settings.pointPerfectCurrentKey) == 0 || strlen(settings.pointPerfectLBandTopic) == 0) + { + provisionDevice(); //Connect to ThingStream API and get keys + } + else + updatePointPerfectKeys(); + } + + bluetoothStart(); +#endif + } + else if (incoming == '6') + { + LittleFS.format(); + log_d("Formatted"); + } + else if (incoming == 'k') + { + menuPointPerfectKeys(); + } + else if (incoming == 'x') + break; + else if (incoming == STATUS_GETBYTE_TIMEOUT) + break; + else + printUnknown(incoming); + } + + if (strlen(settings.pointPerfectClientID) > 0) + { + applyLBandKeys(); + } + + while (Serial.available()) Serial.read(); //Empty buffer of any newline chars +#endif //COMPILE_L_BAND +} + +//Process any new L-Band from I2C +//If a certain amount of time has elapsed between last decryption, turn off L-Band icon +void updateLBand() +{ +#ifdef COMPILE_L_BAND + if (online.lbandCorrections == true) + { + i2cLBand.checkUblox(); // Check for the arrival of new PMP data and process it. + i2cLBand.checkCallbacks(); // Check if any L-Band callbacks are waiting to be processed. + + if (lbandCorrectionsReceived == true && millis() - lastLBandDecryption > 5000) + lbandCorrectionsReceived = false; + } +#endif //COMPILE_L_BAND +} From 262ab2fe3afbfb95c381bc9351ac5999a9bfca0a Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Mon, 8 Aug 2022 14:19:07 -0500 Subject: [PATCH 034/134] Always update resetCount to aid uptime print --- Firmware/RTK_Surveyor/Begin.ino | 22 ++++++---------------- 1 file changed, 6 insertions(+), 16 deletions(-) diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index cc3b269c4..f2f066fd6 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -147,28 +147,16 @@ void beginBoard() unitMACAddress[5] += 2; //Convert MAC address to Bluetooth MAC (add 2): https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/system/system.html#mac-address //For all boards, check reset reason. If reset was due to wdt or panic, append last log + loadSettingsPartial(); //Get resetCount if (esp_reset_reason() == ESP_RST_POWERON) { reuseLastLog = false; //Start new log - - loadSettingsPartial(); - if (settings.enableResetDisplay == true) - { - settings.resetCount = 0; - recordSystemSettings(); //Record to NVM - } + settings.resetCount = 0; } else { reuseLastLog = true; //Attempt to reuse previous log - - loadSettingsPartial(); - if (settings.enableResetDisplay == true) - { - settings.resetCount++; - Serial.printf("resetCount: %d\n\r", settings.resetCount); - recordSystemSettings(); //Record to NVM - } + settings.resetCount++; Serial.print("Reset reason: "); switch (esp_reset_reason()) @@ -186,6 +174,8 @@ void beginBoard() default : Serial.println("Unknown"); } } + + recordSystemSettings(); //Record resetCount to NVM } void beginSD() @@ -715,7 +705,7 @@ bool beginExternalTriggers() //Check if NEO-D9S is connected. Configure if available. void beginLBand() { - if(settings.enablePointPerfectCorrections == false) return; //If user has turned off PointPerfect, skip everything + if (settings.enablePointPerfectCorrections == false) return; //If user has turned off PointPerfect, skip everything if (i2cLBand.begin(Wire, 0x43) == false) //Connect to the u-blox NEO-D9S using Wire port. The D9S default I2C address is 0x43 (not 0x42) { From 764349748356b8c8ba402c513a122c29c74c707e Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Mon, 8 Aug 2022 14:23:40 -0500 Subject: [PATCH 035/134] NTRIP Client bug fixes and GGA add Add min bytes received before reading response. Add GGA sending. Add WiFi RSSI printing. Fix comments I believe the client was parsing a partial response from the server when ntripClientReceiveDataAvailable() returned something less than strlen("ICY 200 OK"). Also, the coffee shop AP seems to be blocking or throttling port 2101. When in doubt, test with a cell phone hotspot or other device that guarantees 2101. --- Firmware/RTK_Surveyor/NtripClient.ino | 68 +++++++++++++++++++++----- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 2 + 2 files changed, 59 insertions(+), 11 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripClient.ino b/Firmware/RTK_Surveyor/NtripClient.ino index f52137019..3bcb0eaa5 100644 --- a/Firmware/RTK_Surveyor/NtripClient.ino +++ b/Firmware/RTK_Surveyor/NtripClient.ino @@ -1,6 +1,6 @@ /*=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= -NTRIP Client States: - NTRIP_CLIENT_OFF: Using Bluetooth or NTRIP server + NTRIP Client States: + NTRIP_CLIENT_OFF: WiFi off or or NTRIP server NTRIP_CLIENT_ON: WIFI_ON state NTRIP_CLIENT_WIFI_CONNECTING: Connecting to WiFi access point NTRIP_CLIENT_WIFI_CONNECTED: WiFi connected to an access point @@ -29,7 +29,7 @@ NTRIP Client States: v Fail | NTRIP_CLIENT_CONNECTED -----------' -=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=*/ + =-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=*/ //---------------------------------------- // Constants - compiled out @@ -44,7 +44,7 @@ static const int CREDENTIALS_BUFFER_SIZE = 512; static const int MAX_NTRIP_CLIENT_CONNECTION_ATTEMPTS = 3; //NTRIP caster response timeout -static const uint32_t NTRIP_CLIENT_RESPONSE_TIMEOUT = 5 * 1000; //Milliseconds +static const uint32_t NTRIP_CLIENT_RESPONSE_TIMEOUT = 10 * 1000; //Milliseconds //NTRIP client receive data timeout static const uint32_t NTRIP_CLIENT_RECEIVE_DATA_TIMEOUT = 10 * 1000; //Milliseconds @@ -73,6 +73,9 @@ static uint32_t ntripClientTimer; //Last time the NTRIP client state was displayed static uint32_t lastNtripClientState = 0; +//Throttle GGA transmission to Caster to 1 report every 5 seconds +unsigned long lastGGAPush = 0; + //---------------------------------------- // NTRIP Client Routines - compiled out //---------------------------------------- @@ -85,7 +88,7 @@ void ntripClientAllowMoreConnections() bool ntripClientConnect() { if ((!ntripClient) - || (!ntripClient->connect(settings.ntripClient_CasterHost, settings.ntripClient_CasterPort))) + || (!ntripClient->connect(settings.ntripClient_CasterHost, settings.ntripClient_CasterPort))) return false; Serial.printf("NTRIP Client connected to %s:%d\n\r", settings.ntripClient_CasterHost, settings.ntripClient_CasterPort); @@ -280,6 +283,10 @@ void ntripClientStop(bool done) if (ntripClientState > NTRIP_CLIENT_ON) wifiStop(); + // Return the Main Talker ID to "GN". + i2cGNSS.setMainTalkerID(SFE_UBLOX_MAIN_TALKER_ID_GN); + i2cGNSS.setNMEAGPGGAcallbackPtr(NULL); // Remove callback + //Determine the next NTRIP client state ntripClientSetState((ntripClient && (!done)) ? NTRIP_CLIENT_ON : NTRIP_CLIENT_OFF); online.ntripClient = false; @@ -320,6 +327,8 @@ void ntripClientUpdate() if (ntripClientConnectLimitReached()) //Display the WiFi failure paintNtripWiFiFail(4000, true); + + //TODO WiFi not available, give up, disable future attempts } } else @@ -346,7 +355,7 @@ void ntripClientUpdate() case NTRIP_CLIENT_CONNECTING: //Check for no response from the caster service - if (ntripClientReceiveDataAvailable() == 0) + if (ntripClientReceiveDataAvailable() < strlen("ICY 200 OK")) //Wait until at least a few bytes have arrived { //Check for response timeout if (millis() - ntripClientTimer > NTRIP_CLIENT_RESPONSE_TIMEOUT) @@ -362,6 +371,8 @@ void ntripClientUpdate() char response[512]; ntripClientResponse(&response[0], sizeof(response)); + //Serial.printf("Response: %s\n\r", response); + //Look for '200 OK' if (strstr(response, "200") == NULL) { @@ -378,6 +389,16 @@ void ntripClientUpdate() //Connection is now open, start the NTRIP receive data timer ntripClientTimer = millis(); + // Set the Main Talker ID to "GP". The NMEA GGA messages will be GPGGA instead of GNGGA + i2cGNSS.setMainTalkerID(SFE_UBLOX_MAIN_TALKER_ID_GP); + i2cGNSS.setNMEAGPGGAcallbackPtr(&pushGPGGA); // Set up the callback for GPGGA + + float measurementFrequency = (1000.0 / settings.measurementRate) / settings.navigationRate; + if (measurementFrequency < 0.2) measurementFrequency = 0.2; //0.2Hz * 5 = 1 measurement every 5 seconds + i2cGNSS.enableNMEAMessage(UBX_NMEA_GGA, COM_PORT_I2C, measurementFrequency * 5); // Enable GGA over I2C. Tell the module to output GGA every 5 seconds + + lastGGAPush = millis(); + //We don't use a task because we use I2C hardware (and don't have a semphore). online.ntripClient = true; ntripClientAllowMoreConnections(); @@ -402,14 +423,13 @@ void ntripClientUpdate() if ((millis() - ntripClientTimer) > NTRIP_CLIENT_RECEIVE_DATA_TIMEOUT) { //Timeout receiving NTRIP data, retry the NTRIP client connection - Serial.println("NTRIP Client timeout"); + Serial.println("NTRIP Client: No data received timeout"); ntripClientStop(false); } } else { - //Received data from the NTRIP server - //5 RTCM messages take approximately ~300ms to arrive at 115200bps + //Receive data from the NTRIP Caster uint8_t rtcmData[RTCM_DATA_SIZE]; size_t rtcmCount = 0; @@ -428,10 +448,36 @@ void ntripClientUpdate() i2cGNSS.pushRawData(rtcmData, rtcmCount); online.rxRtcmCorrectionData = true; - //log_d("NTRIP Client pushed %d RTCM bytes to ZED", rtcmCount); + log_d("NTRIP Client pushed %d RTCM bytes to ZED", rtcmCount); } } + + if (millis() - lastRSSIUpdate > 5000) + { + lastRSSIUpdate = millis(); + Serial.printf("WiFi RSSI: %d\n\r", WiFi.RSSI()); + } + break; } - #endif //COMPILE_WIFI +#endif //COMPILE_WIFI +} + +void pushGPGGA(NMEA_GGA_data_t *nmeaData) +{ +#ifdef COMPILE_WIFI + //Provide the caster with our current position as needed + if ((ntripClient->connected() == true) && (settings.ntripClient_TransmitGGA == true)) + { + if (millis() - lastGGAPush > 5000) + { + lastGGAPush = millis(); + //Serial.print(F("Pushing GGA to server: ")); + //Serial.print((const char *)nmeaData->nmea); // .nmea is printable (NULL-terminated) and already has \r\n on the end + + //Push our current GGA sentence to caster + ntripClient->print((const char *)nmeaData->nmea); + } + } +#endif } diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 764f3b813..cd67aa3b9 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -454,6 +454,8 @@ unsigned long rtcWaitTime = 0; //At poweron, we give the RTC a few seconds to up TaskHandle_t idleTaskHandle[MAX_CPU_CORES]; uint32_t max_idle_count = MAX_IDLE_TIME_COUNT; +unsigned long lastRSSIUpdate = 0; //Print RSSI when connected every few seconds + //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- /* +---------------------------------------+ +----------+ From 68243068db5d80865ee6ca173fe46aa279c249da Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Mon, 8 Aug 2022 15:27:08 -0500 Subject: [PATCH 036/134] Fix NTRIP Server Add strlen() check of response Fix RTCM packet counting if checker turned off Add RSSI print during NTRIP I believe the NTRIP_SERVER_AUTHORIZATION was failing because the ntripServer->available() needs to be large enough for an ICY 200 OK check. Additionally, an AP that correctly forward port 2101 is needed. RTCM counting was not working if the checker was turned off. Fix: if checker is disabled, RTCM count is increased with every byte. --- Firmware/RTK_Surveyor/NtripClient.ino | 6 +-- Firmware/RTK_Surveyor/NtripServer.ino | 66 ++++++++++++++++---------- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 2 +- 3 files changed, 44 insertions(+), 30 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripClient.ino b/Firmware/RTK_Surveyor/NtripClient.ino index 3bcb0eaa5..92f36c65b 100644 --- a/Firmware/RTK_Surveyor/NtripClient.ino +++ b/Firmware/RTK_Surveyor/NtripClient.ino @@ -452,10 +452,10 @@ void ntripClientUpdate() } } - if (millis() - lastRSSIUpdate > 5000) + if (millis() - lastWifiRSSIUpdate > 5000) { - lastRSSIUpdate = millis(); - Serial.printf("WiFi RSSI: %d\n\r", WiFi.RSSI()); + lastWifiRSSIUpdate = millis(); + Serial.printf("NTRIP WiFi RSSI: %d\n\r", WiFi.RSSI()); } break; diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index d1822d5a7..10def7dae 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -1,5 +1,5 @@ /*=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= -NTRIP Server States: + NTRIP Server States: NTRIP_SERVER_OFF: Using Bluetooth or NTRIP server NTRIP_SERVER_ON: WIFI_ON state NTRIP_SERVER_WIFI_CONNECTING: Connecting to WiFi access point @@ -44,7 +44,7 @@ NTRIP Server States: | | Close Server connection '------------------' -=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=*/ + =-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=*/ //---------------------------------------- // Constants - compiled out @@ -99,7 +99,7 @@ bool ntripServerConnectCaster() //Note the connection to the NTRIP caster Serial.printf("Connected to %s:%d\n\r", settings.ntripServer_CasterHost, - settings.ntripServer_CasterPort); + settings.ntripServer_CasterPort); //Build the authorization credentials message // * Mount point @@ -192,10 +192,10 @@ bool ntripServerRtcmMessage(uint8_t data) //Wait for the preamble byte ntripServerCrcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; - //Fall through - // | - // | - // V + //Fall through + // | + // | + // V //Wait for the preamble byte (0xd3) case RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3: @@ -368,8 +368,16 @@ void ntripServerProcessRTCM(uint8_t incoming) } previousMilliseconds = currentMilliseconds; - //Parse the RTCM message - if ((!settings.enableNtripServerMessageParsing) || ntripServerRtcmMessage(incoming)) + //Pass this message to the RTCM checker + bool passAlongIncomingByte = true; + + //Check this byte with RTCM checker if enabled + if (settings.enableNtripServerMessageParsing == true) + passAlongIncomingByte &= ntripServerRtcmMessage(incoming); + else + rtcmPacketsSent++; //If not checking RTCM CRC, count every byte + + if (passAlongIncomingByte) { ntripServer->write(incoming); //Send this byte to socket ntripServerBytesSent++; @@ -396,7 +404,7 @@ void ntripServerStart() //Start the NTRIP server if enabled if ((settings.ntripServer_StartAtSurveyIn == true) - || (settings.enableNtripServer == true)) + || (settings.enableNtripServer == true)) { //Display the heap state reportHeapNow(); @@ -487,7 +495,7 @@ void ntripServerUpdate() ntripServerSetState(NTRIP_SERVER_WIFI_CONNECTED); // Start the SD card server -// sdCardServerBegin(&server, true, true); + // sdCardServerBegin(&server, true, true); } break; @@ -510,27 +518,27 @@ void ntripServerUpdate() //Initiate the connection to the NTRIP caster case NTRIP_SERVER_CONNECTING: - //Attempt a connection to the NTRIP caster - if (!ntripServerConnectCaster()) - { - log_d("NTRIP Server caster failed to connect. Trying again."); + //Attempt a connection to the NTRIP caster + if (!ntripServerConnectCaster()) + { + log_d("NTRIP Server caster failed to connect. Trying again."); - //Assume service not available - if (ntripServerConnectLimitReached()) - Serial.println("NTRIP Server failed to connect! Do you have your caster address and port correct?"); - } - else - { - //Connection open to NTRIP caster, wait for the authorization response - ntripServerTimer = millis(); - ntripServerSetState(NTRIP_SERVER_AUTHORIZATION); - } + //Assume service not available + if (ntripServerConnectLimitReached()) + Serial.println("NTRIP Server failed to connect! Do you have your caster address and port correct?"); + } + else + { + //Connection open to NTRIP caster, wait for the authorization response + ntripServerTimer = millis(); + ntripServerSetState(NTRIP_SERVER_AUTHORIZATION); + } break; //Wait for authorization response case NTRIP_SERVER_AUTHORIZATION: //Check if caster service responded - if (ntripServer->available() == 0) + if (ntripServer->available() < strlen("ICY 200 OK")) //Wait until at least a few bytes have arrived { //Check for response timeout if (millis() - ntripServerTimer > 5000) @@ -590,6 +598,12 @@ void ntripServerUpdate() } else cyclePositionLEDs(); + + if (millis() - lastWifiRSSIUpdate > 5000) + { + lastWifiRSSIUpdate = millis(); + Serial.printf("NTRIP WiFi RSSI: %d\n\r", WiFi.RSSI()); + } break; } #endif //COMPILE_WIFI diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index cd67aa3b9..b1e549469 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -454,7 +454,7 @@ unsigned long rtcWaitTime = 0; //At poweron, we give the RTC a few seconds to up TaskHandle_t idleTaskHandle[MAX_CPU_CORES]; uint32_t max_idle_count = MAX_IDLE_TIME_COUNT; -unsigned long lastRSSIUpdate = 0; //Print RSSI when connected every few seconds +unsigned long lastWifiRSSIUpdate = 0; //Print RSSI when connected every few seconds //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- /* From d3f94bf3342747cf8981d68626859bb3ee64e86b Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 9 Aug 2022 20:45:22 -0600 Subject: [PATCH 037/134] Fix ESPNOW state change error --- Firmware/RTK_Surveyor/Base.ino | 4 ++-- Firmware/RTK_Surveyor/ESPNOW.ino | 4 ++-- Firmware/RTK_Surveyor/settings.h | 6 +++--- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/Firmware/RTK_Surveyor/Base.ino b/Firmware/RTK_Surveyor/Base.ino index 7c7f50f7a..2e394d9fe 100644 --- a/Firmware/RTK_Surveyor/Base.ino +++ b/Firmware/RTK_Surveyor/Base.ino @@ -230,7 +230,7 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming) ntripServerProcessRTCM(incoming); #ifdef COMPILE_ESPNOW - if (wifiState == ESPNOW_PAIRED) + if (espnowState == ESPNOW_PAIRED) { //Move this byte into ESP NOW to send buffer espnowOutgoing[espnowOutgoingSpot++] = incoming; @@ -241,7 +241,7 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming) espnowOutgoingSpot = 0; //Wrap esp_now_send(0, (uint8_t *) &espnowOutgoing, sizeof(espnowOutgoing)); //Send packet to all peers delay(10); //We need a small delay between sending multiple packets - //log_d("ESPNOW: Sending %d bytes", sizeof(espnowOutgoing)); + log_d("ESPNOW: Sending %d bytes", sizeof(espnowOutgoing)); } } #endif diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 6ee453b0e..114556039 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -102,7 +102,7 @@ void espnowStart() //If ESP-Now is active, WiFi is active, do nothing else { - Serial.println("Wi-Fi on, ESP-Now on"); + Serial.println("Wi-Fi already on, ESP-Now already on"); } // Init ESP-NOW @@ -299,7 +299,7 @@ esp_err_t espnowRemovePeer(uint8_t *peerMac) } //Update the state of the ESP Now state machine -void espnowSetState(byte newState) +void espnowSetState(ESPNOWState newState) { if (espnowState == newState) Serial.print("*"); diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 7d1051896..44efe19e9 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -114,15 +114,15 @@ enum WiFiState }; volatile byte wifiState = WIFI_OFF; -enum ESPNOWState +typedef enum ESPNOWState { ESPNOW_OFF, ESPNOW_ON, ESPNOW_PAIRING, ESPNOW_MAC_RECEIVED, ESPNOW_PAIRED, -}; -volatile byte espnowState = ESPNOW_OFF; +} ESPNOWState; +volatile ESPNOWState espnowState = ESPNOW_OFF; enum NTRIPClientState { From ccd25d636a197b56df2c4eb257b359f5cb9d7cd3 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 9 Aug 2022 20:51:19 -0600 Subject: [PATCH 038/134] Gate idle time calculations --- Firmware/RTK_Surveyor/Begin.ino | 31 ++++++++++++++------------ Firmware/RTK_Surveyor/RTK_Surveyor.ino | 2 +- 2 files changed, 18 insertions(+), 15 deletions(-) diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index f2f066fd6..02451f9b3 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -789,20 +789,23 @@ void beginLBand() void beginIdleTasks() { - char taskName[32]; - - for (int index = 0; index < MAX_CPU_CORES; index++) - { - sprintf(taskName, "IdleTask%d", index); - if (idleTaskHandle[index] == NULL) - xTaskCreatePinnedToCore( - idleTask, - taskName, //Just for humans - 2000, //Stack Size - NULL, //Task input parameter - 0, // Priority, with 3 (configMAX_PRIORITIES - 1) being the highest, and 0 being the lowest - &idleTaskHandle[index], //Task handle - index); //Core where task should run, 0=core, 1=Arduino + if (settings.enablePrintIdleTime == true) + { + char taskName[32]; + + for (int index = 0; index < MAX_CPU_CORES; index++) + { + sprintf(taskName, "IdleTask%d", index); + if (idleTaskHandle[index] == NULL) + xTaskCreatePinnedToCore( + idleTask, + taskName, //Just for humans + 2000, //Stack Size + NULL, //Task input parameter + 0, // Priority, with 3 (configMAX_PRIORITIES - 1) being the highest, and 0 being the lowest + &idleTaskHandle[index], //Task handle + index); //Core where task should run, 0=core, 1=Arduino + } } } diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index b1e549469..2662e7e0f 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -534,7 +534,7 @@ void setup() { Serial.begin(115200); //UART0 for programming and debugging - beginIdleTasks(); + beginIdleTasks(); //Enable processor load calculations beginI2C(); From 0011f9930c8e1625780129de9b44b5554addbf09 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 10 Aug 2022 09:37:41 -0600 Subject: [PATCH 039/134] Move idleTask start after settings are loaded --- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 2662e7e0f..3cc9c4391 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -534,8 +534,6 @@ void setup() { Serial.begin(115200); //UART0 for programming and debugging - beginIdleTasks(); //Enable processor load calculations - beginI2C(); beginDisplay(); //Start display first to be able to display any errors @@ -554,6 +552,8 @@ void setup() loadSettings(); //Attempt to load settings after SD is started so we can read the settings file if available + beginIdleTasks(); //Enable processor load calculations + beginUART2(); //Start UART2 on core 0, used to receive serial from ZED and pass out over SPP beginFuelGauge(); //Configure battery fuel guage monitor From ba5fa4033efd46dae7ff1e0014c629909905bb0d Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 10 Aug 2022 11:15:42 -0600 Subject: [PATCH 040/134] Add stop if NTRIP Server is disabled. Separate Bluetooth start/stop from WiFi and ntripServer. --- Firmware/RTK_Surveyor/NtripServer.ino | 62 ++++++++++----------------- Firmware/RTK_Surveyor/States.ino | 6 ++- Firmware/RTK_Surveyor/WiFi.ino | 4 +- 3 files changed, 29 insertions(+), 43 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 10def7dae..588f91be2 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -1,6 +1,6 @@ /*=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= NTRIP Server States: - NTRIP_SERVER_OFF: Using Bluetooth or NTRIP server + NTRIP_SERVER_OFF: WiFi OFF or using NTRIP Client NTRIP_SERVER_ON: WIFI_ON state NTRIP_SERVER_WIFI_CONNECTING: Connecting to WiFi access point NTRIP_SERVER_WIFI_CONNECTED: WiFi connected to an access point @@ -80,12 +80,6 @@ static uint32_t ntripServerTimer; // NTRIP Server Routines - compiled out //---------------------------------------- -//Determine if more connections are allowed -void ntripServerAllowMoreConnections() -{ - ntripServerConnectionAttempts = 0; -} - //Initiate a connection to the NTRIP caster bool ntripServerConnectCaster() { @@ -122,18 +116,20 @@ bool ntripServerConnectCaster() bool ntripServerConnectLimitReached() { //Shutdown the NTRIP server - ntripServerStop(false); + ntripServerStop(false); //Allocate new wifiClient //Retry the connection a few times - bool limitReached = (ntripServerConnectionAttempts++ >= MAX_NTRIP_SERVER_CONNECTION_ATTEMPTS); + bool limitReached = false; + if (ntripServerConnectionAttempts++ >= MAX_NTRIP_SERVER_CONNECTION_ATTEMPTS) limitReached = true; + if (!limitReached) //Display the heap state reportHeapNow(); else { - //No more connection attempts, switching to Bluetooth + //No more connection attempts Serial.println("NTRIP Server connection attempts exceeded!"); - ntripServerSwitchToBluetooth(); + ntripServerStop(true); //Don't allocate new wifiClient } return limitReached; } @@ -308,19 +304,6 @@ void ntripServerSetState(byte newState) break; } } - -//Switch to Bluetooth operation -void ntripServerSwitchToBluetooth() -{ - Serial.println("NTRIP Server failure, switching to Bluetooth!"); - - //Stop WiFi operations - ntripServerStop(true); - - //Turn on Bluetooth with 'Rover' name - bluetoothStart(); -} - #endif // COMPILE_WIFI //---------------------------------------- @@ -370,7 +353,7 @@ void ntripServerProcessRTCM(uint8_t incoming) //Pass this message to the RTCM checker bool passAlongIncomingByte = true; - + //Check this byte with RTCM checker if enabled if (settings.enableNtripServerMessageParsing == true) passAlongIncomingByte &= ntripServerRtcmMessage(incoming); @@ -400,7 +383,7 @@ void ntripServerStart() { #ifdef COMPILE_WIFI //Stop NTRIP server and WiFi - ntripServerStop(true); + ntripServerStop(true); //Don't allocate new wifiClient //Start the NTRIP server if enabled if ((settings.ntripServer_StartAtSurveyIn == true) @@ -408,7 +391,6 @@ void ntripServerStart() { //Display the heap state reportHeapNow(); - Serial.println("NTRIP Server start"); //Allocate the ntripServer structure ntripServer = new WiFiClient(); @@ -418,14 +400,12 @@ void ntripServerStart() ntripServerSetState(NTRIP_SERVER_ON); } - //Only fallback to Bluetooth once, then try WiFi again. This enables changes - //to the WiFi SSID and password to properly restart the WiFi. - ntripServerAllowMoreConnections(); + ntripServerConnectionAttempts = 0; #endif //COMPILE_WIFI } //Stop the NTRIP server -void ntripServerStop(bool done) +void ntripServerStop(bool wifiClientAllocated) { #ifdef COMPILE_WIFI if (ntripServer) @@ -439,7 +419,7 @@ void ntripServerStop(bool done) ntripServer = NULL; //Allocate the NTRIP server structure if not done - if (!done) + if (wifiClientAllocated == false) ntripServer = new WiFiClient(); } @@ -448,7 +428,7 @@ void ntripServerStop(bool done) wifiStop(); //Determine the next NTRIP server state - ntripServerSetState((ntripServer && (!done)) ? NTRIP_SERVER_ON : NTRIP_SERVER_OFF); + ntripServerSetState((ntripServer && (wifiClientAllocated == false)) ? NTRIP_SERVER_ON : NTRIP_SERVER_OFF); online.ntripServer = false; #endif //COMPILE_WIFI } @@ -464,10 +444,13 @@ void ntripServerUpdate() ntripServerStateLastDisplayed = millis(); } + //If user turns off NTRIP Server via settings, stop server + if (settings.enableNtripServer == false) + ntripServerStop(true); //Don't allocate new wifiClient + //Enable WiFi and the NTRIP server if requested switch (ntripServerState) { - //Bluetooth enabled case NTRIP_SERVER_OFF: break; @@ -485,8 +468,10 @@ void ntripServerUpdate() { //Assume AP weak signal, the AP is unable to respond successfully if (ntripServerConnectLimitReached()) + { //Display the WiFi failure paintNtripWiFiFail(4000, false); + } } } else @@ -560,8 +545,7 @@ void ntripServerUpdate() //Look for '401 Unauthorized' Serial.printf("NTRIP Server caster responded with bad news: %s. Are you sure your caster credentials are correct?\n\r", response); - //Switch to Bluetooth operation - ntripServerSwitchToBluetooth(); + ntripServerStop(true); //Don't allocate new wifiClient } else { @@ -575,7 +559,7 @@ void ntripServerUpdate() //We don't use a task because we use I2C hardware (and don't have a semphore). online.ntripServer = true; - ntripServerAllowMoreConnections(); + ntripServerConnectionAttempts = 0; ntripServerSetState(NTRIP_SERVER_CASTING); } } @@ -588,13 +572,13 @@ void ntripServerUpdate() { //Broken connection, retry the NTRIP server connection Serial.println("NTRIP Server connection dropped"); - ntripServerStop(false); + ntripServerStop(false); //Allocate new wifiClient } else if ((millis() - ntripServerTimer) > 1000) { //GNSS stopped sending RTCM correction data Serial.println("NTRIP Server breaking caster connection due to lack of RTCM data!"); - ntripServerStop(false); + ntripServerStop(false); //Allocate new wifiClient } else cyclePositionLEDs(); diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index f96d9e3c6..0b6338b0d 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -236,9 +236,11 @@ void updateSystemState() displayBaseStart(0); //Show 'Base' - //Stop all WiFi and BT. Re-enable in each specific base start state. - wifiStop(); + wifiStop(); //Stop WiFi. Re-enable in each specific base start state. + bluetoothStop(); + bluetoothStart(); //Restart Bluetooth with 'Base' identifier + startUART2Tasks(); //Start monitoring the UART1 from ZED for NMEA and UBX data (enables logging) if (configureUbloxModuleBase() == true) diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 7d6d99249..f0520efed 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -14,9 +14,9 @@ WiFi Station States: - WIFI_OFF (Using Bluetooth) + WIFI_OFF | ^ - Use WiFi | | Use Bluetooth + Use WiFi | | | | WL_CONNECT_FAILED (Bad password) | | WL_NO_SSID_AVAIL (Out of range) v | From 900eb53c30b477ce13aead18202456f7f841f06d Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 10 Aug 2022 11:15:53 -0600 Subject: [PATCH 041/134] Turn off menu print if ESP Now not compiled --- Firmware/RTK_Surveyor/menuMain.ino | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index c80008dd2..9d8b83bbb 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -53,7 +53,9 @@ void menuMain() Serial.println("p) Configure Profiles"); +#ifdef COMPILE_ESPNOW Serial.println("r) Configure Radios"); +#endif if (online.lband == true) Serial.println("P) Configure PointPerfect"); From 1347cfbb130b1b5b84ba2e938d29e6343171757d Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 10 Aug 2022 15:13:45 -0600 Subject: [PATCH 042/134] ESP Now working. Fix Radio icons. Added support for ESP Now Add WiFi RSSI to WiFi icon Add ESP Now RSSI to ESP Now Icon Add Up/Down arrow indication of RTCM to WiFi, BT, and ESP Now --- Firmware/RTK_Surveyor/Base.ino | 15 +- Firmware/RTK_Surveyor/Bluetooth.ino | 2 +- Firmware/RTK_Surveyor/Display.ino | 667 +++++++++++++++++-------- Firmware/RTK_Surveyor/ESPNOW.ino | 22 +- Firmware/RTK_Surveyor/NtripClient.ino | 4 +- Firmware/RTK_Surveyor/NtripServer.ino | 4 +- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 21 +- Firmware/RTK_Surveyor/Tasks.ino | 10 +- Firmware/RTK_Surveyor/WiFi.ino | 6 +- Firmware/RTK_Surveyor/icons.h | 14 +- Firmware/RTK_Surveyor/settings.h | 2 - Graphics/WiFi Symbol-0.bmp | Bin 0 -> 190 bytes Graphics/WiFi Symbol-1.bmp | Bin 0 -> 190 bytes Graphics/WiFi Symbol-2.bmp | Bin 0 -> 190 bytes Graphics/WiFi Symbol-3.bmp | Bin 0 -> 190 bytes Graphics/icon.h | 6 +- 16 files changed, 524 insertions(+), 249 deletions(-) create mode 100644 Graphics/WiFi Symbol-0.bmp create mode 100644 Graphics/WiFi Symbol-1.bmp create mode 100644 Graphics/WiFi Symbol-2.bmp create mode 100644 Graphics/WiFi Symbol-3.bmp diff --git a/Firmware/RTK_Surveyor/Base.ino b/Firmware/RTK_Surveyor/Base.ino index 2e394d9fe..c39615874 100644 --- a/Firmware/RTK_Surveyor/Base.ino +++ b/Firmware/RTK_Surveyor/Base.ino @@ -230,19 +230,6 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming) ntripServerProcessRTCM(incoming); #ifdef COMPILE_ESPNOW - if (espnowState == ESPNOW_PAIRED) - { - //Move this byte into ESP NOW to send buffer - espnowOutgoing[espnowOutgoingSpot++] = incoming; - espnowLastAdd = millis(); - - if (espnowOutgoingSpot == sizeof(espnowOutgoing)) - { - espnowOutgoingSpot = 0; //Wrap - esp_now_send(0, (uint8_t *) &espnowOutgoing, sizeof(espnowOutgoing)); //Send packet to all peers - delay(10); //We need a small delay between sending multiple packets - log_d("ESPNOW: Sending %d bytes", sizeof(espnowOutgoing)); - } - } + espnowProcessRTCM(incoming); #endif } diff --git a/Firmware/RTK_Surveyor/Bluetooth.ino b/Firmware/RTK_Surveyor/Bluetooth.ino index ad4d2731e..07d6659df 100644 --- a/Firmware/RTK_Surveyor/Bluetooth.ino +++ b/Firmware/RTK_Surveyor/Bluetooth.ino @@ -183,7 +183,7 @@ void bluetoothStop() reportHeapNow(); } #endif //COMPILE_BT - online.rxRtcmCorrectionData = false; + bluetoothIncomingRTCM = false; } //Write data to the Bluetooth device diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 850805e8f..e23a7ba48 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -8,44 +8,56 @@ //The radio area (top left corner of display) has three spots for icons //Left/Center/Right //Left Radio spot -#define ICON_WIFI_SYMBOL_LEFT (1<<0) // 0, 0 -#define ICON_BT_SYMBOL_LEFT (1<<1) // 4, 0 -#define ICON_MAC_ADDRESS (1<<2) // 0, 3 -#define ICON_ESPNOW_SYMBOL_LEFT (1<<3) // TODO 0, 3 +#define ICON_WIFI_SYMBOL_0_LEFT (1<<0) // 0, 0 +#define ICON_WIFI_SYMBOL_1_LEFT (1<<1) // 0, 0 +#define ICON_WIFI_SYMBOL_2_LEFT (1<<2) // 0, 0 +#define ICON_WIFI_SYMBOL_3_LEFT (1<<3) // 0, 0 +#define ICON_BT_SYMBOL_LEFT (1<<4) // 0, 0 +#define ICON_MAC_ADDRESS (1<<5) // 0, 3 +#define ICON_ESPNOW_SYMBOL_0_LEFT (1<<6) // 0, 0 +#define ICON_ESPNOW_SYMBOL_1_LEFT (1<<7) // 0, 0 +#define ICON_ESPNOW_SYMBOL_2_LEFT (1<<8) // 0, 0 +#define ICON_ESPNOW_SYMBOL_3_LEFT (1<<9) // 0, 0 +#define ICON_DOWN_ARROW_LEFT (1<<10) // 0, 0 +#define ICON_UP_ARROW_LEFT (1<<11) // 0, 0 +#define ICON_BLANK_LEFT (1<<12) // 0, 0 //Center Radio spot -#define ICON_MAC_ADDRESS_2DIGIT (1<<4) // TODO 0, 3 -#define ICON_BT_SYMBOL_CENTER (1<<5) // TODO 4, 0 -#define ICON_WIFI_SYMBOL_CENTER (1<<6) // TODO 0, 0 +#define ICON_MAC_ADDRESS_2DIGIT (1<<13) // 13, 3 +#define ICON_BT_SYMBOL_CENTER (1<<14) // 10, 0 +#define ICON_DOWN_ARROW_CENTER (1<<15) // 0, 0 +#define ICON_UP_ARROW_CENTER (1<<16) // 0, 0 //Right Radio Spot -#define ICON_WIFI_SYMBOL_RIGHT (1<<7) // center, 0 -#define ICON_BASE_TEMPORARY (1<<8) // 27, 0 -#define ICON_BASE_FIXED (1<<9) // 27, 0 -#define ICON_ROVER_FUSION (1<<10) // 27, 2 -#define ICON_ROVER_FUSION_EMPTY (1<<11) // 27, 2 -#define ICON_DYNAMIC_MODEL (1<<12) // 27, 0 - -#define ICON_DOWN_ARROW (1<<13) // 16, 0 -#define ICON_UP_ARROW (1<<14) // 16, 0 +#define ICON_WIFI_SYMBOL_0_RIGHT (1<<17) // center, 0 +#define ICON_WIFI_SYMBOL_1_RIGHT (1<<18) // center, 0 +#define ICON_WIFI_SYMBOL_2_RIGHT (1<<19) // center, 0 +#define ICON_WIFI_SYMBOL_3_RIGHT (1<<20) // center, 0 +#define ICON_BASE_TEMPORARY (1<<21) // center, 0 +#define ICON_BASE_FIXED (1<<22) // center, 0 +#define ICON_ROVER_FUSION (1<<23) // center, 2 +#define ICON_ROVER_FUSION_EMPTY (1<<24) // center, 2 +#define ICON_DYNAMIC_MODEL (1<<25) // 27, 0 +#define ICON_DOWN_ARROW_RIGHT (1<<26) // center, 0 +#define ICON_UP_ARROW_RIGHT (1<<27) // center, 0 +#define ICON_BLANK_RIGHT (1<<28) // center, 0 //Right top -#define ICON_BATTERY (1<<15) // 45, 0 +#define ICON_BATTERY (1<<0) // 45, 0 //Left center -#define ICON_CROSS_HAIR (1<<16) // 0, 18 -#define ICON_CROSS_HAIR_DUAL (1<<17) // 0, 18 +#define ICON_CROSS_HAIR (1<<1) // 0, 18 +#define ICON_CROSS_HAIR_DUAL (1<<2) // 0, 18 //Right center -#define ICON_HORIZONTAL_ACCURACY (1<<18) // 16, 20 +#define ICON_HORIZONTAL_ACCURACY (1<<3) // 16, 20 //Left bottom -#define ICON_SIV_ANTENNA (1<<19) // 2, 35 -#define ICON_SIV_ANTENNA_LBAND (1<<20) // 2, 35 +#define ICON_SIV_ANTENNA (1<<4) // 2, 35 +#define ICON_SIV_ANTENNA_LBAND (1<<5) // 2, 35 //Right bottom -#define ICON_LOGGING (1<<21) // right, bottom - +#define ICON_LOGGING (1<<6) // right, bottom //---------------------------------------- // Locals @@ -54,6 +66,7 @@ static QwiicMicroOLED oled; static uint32_t blinking_icons; static uint32_t icons; +static uint32_t iconsRadio; // Fonts #include @@ -171,49 +184,45 @@ void updateDisplay() */ case (STATE_ROVER_NOT_STARTED): - icons = paintRadioIcons() //Top left - | ICON_BATTERY //Top right + icons = ICON_BATTERY //Top right | ICON_CROSS_HAIR //Center left | ICON_HORIZONTAL_ACCURACY //Center right | paintSIV() //Bottom left | ICON_LOGGING; //Bottom right + iconsRadio = setRadioIcons(); //Top left break; case (STATE_ROVER_NO_FIX): - icons = paintRadioIcons() //Top left - | ICON_DYNAMIC_MODEL //Top center - | ICON_BATTERY //Top right + icons = ICON_BATTERY //Top right | ICON_CROSS_HAIR //Center left | ICON_HORIZONTAL_ACCURACY //Center right | paintSIV() //Bottom left | ICON_LOGGING; //Bottom right + iconsRadio = setRadioIcons(); //Top left break; case (STATE_ROVER_FIX): - icons = paintRadioIcons() //Top left - | ICON_DYNAMIC_MODEL //Top center - | ICON_BATTERY //Top right + icons = ICON_BATTERY //Top right | ICON_CROSS_HAIR //Center left | ICON_HORIZONTAL_ACCURACY //Center right | paintSIV() //Bottom left | ICON_LOGGING; //Bottom right + iconsRadio = setRadioIcons(); //Top left break; case (STATE_ROVER_RTK_FLOAT): blinking_icons ^= ICON_CROSS_HAIR_DUAL; - icons = paintRadioIcons() //Top left - | ICON_DYNAMIC_MODEL //Top center - | ICON_BATTERY //Top right + icons = ICON_BATTERY //Top right | (blinking_icons & ICON_CROSS_HAIR_DUAL) //Center left | ICON_HORIZONTAL_ACCURACY //Center right | paintSIV() //Bottom left | ICON_LOGGING; //Bottom right + iconsRadio = setRadioIcons(); //Top left break; case (STATE_ROVER_RTK_FIX): - icons = paintRadioIcons() //Top left - | ICON_DYNAMIC_MODEL //Top center - | ICON_BATTERY //Top right + icons = ICON_BATTERY //Top right | ICON_CROSS_HAIR_DUAL//Center left | ICON_HORIZONTAL_ACCURACY //Center right | paintSIV() //Bottom left | ICON_LOGGING; //Bottom right + iconsRadio = setRadioIcons(); //Top left break; case (STATE_BASE_NOT_STARTED): @@ -224,38 +233,34 @@ void updateDisplay() //Screen is displayed while we are waiting for horz accuracy to drop to appropriate level //Blink crosshair icon until we have we have horz accuracy < user defined level case (STATE_BASE_TEMP_SETTLE): - blinking_icons ^= ICON_BASE_TEMPORARY | ICON_CROSS_HAIR; - icons = paintRadioIcons() //Top left - | ICON_BATTERY //Top right + blinking_icons ^= ICON_CROSS_HAIR; + icons = ICON_BATTERY //Top right | (blinking_icons & ICON_CROSS_HAIR) //Center left | ICON_HORIZONTAL_ACCURACY //Center right | paintSIV() //Bottom left | ICON_LOGGING; //Bottom right + iconsRadio = setRadioIcons(); //Top left break; case (STATE_BASE_TEMP_SURVEY_STARTED): - blinking_icons ^= ICON_BASE_TEMPORARY; - icons = paintRadioIcons() //Top left - | (blinking_icons & ICON_BASE_TEMPORARY) //Top center - | ICON_BATTERY //Top right + icons = ICON_BATTERY //Top right | ICON_LOGGING; //Bottom right + iconsRadio = setRadioIcons(); //Top left paintBaseTempSurveyStarted(); break; case (STATE_BASE_TEMP_TRANSMITTING): - icons = paintRadioIcons() //Top left - | ICON_BASE_TEMPORARY //Top center - | ICON_BATTERY //Top right + icons = ICON_BATTERY //Top right | ICON_LOGGING; //Bottom right + iconsRadio = setRadioIcons(); //Top left paintRTCM(); break; case (STATE_BASE_FIXED_NOT_STARTED): - icons = paintRadioIcons() //Top left - | ICON_BATTERY; //Top right + icons = ICON_BATTERY; //Top right + iconsRadio = setRadioIcons(); //Top left break; case (STATE_BASE_FIXED_TRANSMITTING): - icons = paintRadioIcons() //Top left - | ICON_BASE_FIXED //Top center - | ICON_BATTERY //Top right + icons = ICON_BATTERY //Top right | ICON_LOGGING; //Bottom right + iconsRadio = setRadioIcons(); //Top left paintRTCM(); break; case (STATE_BUBBLE_LEVEL): @@ -274,6 +279,7 @@ void updateDisplay() displayWiFiConfigNotStarted(); //Display 'WiFi Config' break; case (STATE_WIFI_CONFIG): + //TODO Remove radio icons from displayWiFi config icons = displayWiFiConfig(); //Display SSID and IP break; case (STATE_TEST): @@ -290,11 +296,11 @@ void updateDisplay() //Do nothing. Quick, fall through state. break; case (STATE_KEYS_WIFI_STARTED): - icons = paintRadioIcons(); //Top left + iconsRadio = setRadioIcons(); //Top left paintGettingKeys(); break; case (STATE_KEYS_WIFI_CONNECTED): - icons = paintRadioIcons(); //Top left + iconsRadio = setRadioIcons(); //Top left paintGettingKeys(); break; case (STATE_KEYS_WIFI_TIMEOUT): @@ -313,11 +319,11 @@ void updateDisplay() //Do nothing. Quick, fall through state. break; case (STATE_KEYS_PROVISION_WIFI_STARTED): - icons = paintRadioIcons(); //Top left + iconsRadio = setRadioIcons(); //Top left paintGettingKeys(); break; case (STATE_KEYS_PROVISION_WIFI_CONNECTED): - icons = paintRadioIcons(); //Top left + iconsRadio = setRadioIcons(); //Top left paintGettingKeys(); break; case (STATE_KEYS_PROVISION_WIFI_TIMEOUT): @@ -333,40 +339,16 @@ void updateDisplay() break; } - //Top left corner - //This is not as if/else if. A variety of symbols may be mixed/matched - if (icons & ICON_WIFI_SYMBOL_LEFT) - { - displayBitmap(0, 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol); - if (icons & ICON_DOWN_ARROW) - { - displayBitmap(16, 0, DownloadArrow_Width, DownloadArrow_Height, DownloadArrow); - online.rxRtcmCorrectionData = false; - } - else if (icons & ICON_UP_ARROW) - displayBitmap(16, 0, UploadArrow_Width, UploadArrow_Height, UploadArrow); - } - if (icons & ICON_WIFI_SYMBOL_RIGHT) - { - displayBitmap(0, 10, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol); - // if (icons & ICON_DOWN_ARROW) - // { - // displayBitmap(16, 0, DownloadArrow_Width, DownloadArrow_Height, DownloadArrow); - // online.rxRtcmCorrectionData = false; - // } - // else if (icons & ICON_UP_ARROW) - // displayBitmap(16, 0, UploadArrow_Width, UploadArrow_Height, UploadArrow); - } - if (icons & ICON_BT_SYMBOL_LEFT) - { - displayBitmap(4, 0, BT_Symbol_Width, BT_Symbol_Height, BT_Symbol); - } - if (icons & ICON_BT_SYMBOL_CENTER) - { - //Moved to center to give space for ESP NOW icon on far left - displayBitmap(10, 0, BT_Symbol_Width, BT_Symbol_Height, BT_Symbol); - } - if (icons & ICON_MAC_ADDRESS) + //Top left corner - Radio icon indicators take three spots (left/center/right) + //Allowed icon combinations: + //Bluetooth + Rover/Base + //WiFi + Bluetooth + Rover/Base + //ESP-Now + Bluetooth + Rover/Base + //ESP-Now + Bluetooth + WiFi + //See setRadioIcons() for the icon selection logic + + //Left spot + if (iconsRadio & ICON_MAC_ADDRESS) { char macAddress[5]; #ifdef COMPILE_BT @@ -378,7 +360,40 @@ void updateDisplay() oled.setCursor(0, 3); oled.print(macAddress); } - if (icons & ICON_MAC_ADDRESS_2DIGIT) + else if (iconsRadio & ICON_BT_SYMBOL_LEFT) + displayBitmap(1, 0, BT_Symbol_Width, BT_Symbol_Height, BT_Symbol); + else if (iconsRadio & ICON_WIFI_SYMBOL_0_LEFT) + displayBitmap(0, 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol_0); + else if (iconsRadio & ICON_WIFI_SYMBOL_1_LEFT) + displayBitmap(0, 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol_1); + else if (iconsRadio & ICON_WIFI_SYMBOL_2_LEFT) + displayBitmap(0, 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol_2); + else if (iconsRadio & ICON_WIFI_SYMBOL_3_LEFT) + displayBitmap(0, 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol_3); + else if (iconsRadio & ICON_ESPNOW_SYMBOL_0_LEFT) + displayBitmap(0, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_0); + else if (iconsRadio & ICON_ESPNOW_SYMBOL_1_LEFT) + displayBitmap(0, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_1); + else if (iconsRadio & ICON_ESPNOW_SYMBOL_2_LEFT) + displayBitmap(0, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_2); + else if (iconsRadio & ICON_ESPNOW_SYMBOL_3_LEFT) + displayBitmap(0, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); + else if (iconsRadio & ICON_DOWN_ARROW_LEFT) + displayBitmap(1, 0, DownloadArrow_Width, DownloadArrow_Height, DownloadArrow); + else if (iconsRadio & ICON_UP_ARROW_LEFT) + displayBitmap(1, 0, UploadArrow_Width, UploadArrow_Height, UploadArrow); + else if (iconsRadio & ICON_BLANK_LEFT) + { + ; + } + + //Center radio spots + if (iconsRadio & ICON_BT_SYMBOL_CENTER) + { + //Moved to center to give space for ESP NOW icon on far left + displayBitmap(16, 0, BT_Symbol_Width, BT_Symbol_Height, BT_Symbol); + } + else if (iconsRadio & ICON_MAC_ADDRESS_2DIGIT) { char macAddress[5]; //Print only last two digits of MAC @@ -388,21 +403,37 @@ void updateDisplay() sprintf(macAddress, "%02X", 0); //If BT is not available, print zeroes #endif oled.setFont(QW_FONT_5X7); //Set font to smallest - oled.setCursor(13, 3); + oled.setCursor(14, 3); oled.print(macAddress); } - if (icons & ICON_ESPNOW_SYMBOL_LEFT) - displayBitmap(0, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); - - //Top center - if (icons & ICON_WIFI_SYMBOL_CENTER) - displayBitmap((oled.getWidth() / 2) - (WiFi_Symbol_Width / 2), 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol); - else if ((icons & ICON_DYNAMIC_MODEL) && (online.gnss == true)) + else if (iconsRadio & ICON_DOWN_ARROW_CENTER) + displayBitmap(16, 0, DownloadArrow_Width, DownloadArrow_Height, DownloadArrow); + else if (iconsRadio & ICON_UP_ARROW_CENTER) + displayBitmap(16, 0, UploadArrow_Width, UploadArrow_Height, UploadArrow); + + //Radio third spot + if (iconsRadio & ICON_WIFI_SYMBOL_0_RIGHT) + displayBitmap(28, 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol_0); + else if (iconsRadio & ICON_WIFI_SYMBOL_1_RIGHT) + displayBitmap(28, 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol_1); + else if (iconsRadio & ICON_WIFI_SYMBOL_2_RIGHT) + displayBitmap(28, 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol_2); + else if (iconsRadio & ICON_WIFI_SYMBOL_3_RIGHT) + displayBitmap(28, 0, WiFi_Symbol_Width, WiFi_Symbol_Height, WiFi_Symbol_3); + else if ((iconsRadio & ICON_DYNAMIC_MODEL) && (online.gnss == true)) paintDynamicModel(); - else if (icons & ICON_BASE_TEMPORARY) - displayBitmap(27, 0, BaseTemporary_Width, BaseTemporary_Height, BaseTemporary); - else if (icons & ICON_BASE_FIXED) - displayBitmap(27, 0, BaseFixed_Width, BaseFixed_Height, BaseFixed); //true - blend with other pixels + else if (iconsRadio & ICON_BASE_TEMPORARY) + displayBitmap(28, 0, BaseTemporary_Width, BaseTemporary_Height, BaseTemporary); + else if (iconsRadio & ICON_BASE_FIXED) + displayBitmap(28, 0, BaseFixed_Width, BaseFixed_Height, BaseFixed); //true - blend with other pixels + else if (iconsRadio & ICON_DOWN_ARROW_RIGHT) + displayBitmap(31, 0, DownloadArrow_Width, DownloadArrow_Height, DownloadArrow); + else if (iconsRadio & ICON_UP_ARROW_RIGHT) + displayBitmap(31, 0, UploadArrow_Width, UploadArrow_Height, UploadArrow); + else if (iconsRadio & ICON_BLANK_RIGHT) + { + ; + } //Top right corner if (icons & ICON_BATTERY) @@ -605,18 +636,21 @@ void paintBatteryLevel() 8| * ** */ -//Display Bluetooth, WiFi, ESP Now, and Mode indicators (Mac, Blinking, Arrows, etc) depending on connection state -uint32_t paintRadioIcons() +//Set bits to turn on various icons in the Radio area +//ie: Bluetooth, WiFi, ESP Now, Mode indicators, as well as sub states of each (MAC, Blinking, Arrows, etc), depending on connection state +//This function has all the logic to determine how a shared icon spot should act. ie: if we need an up arrow, blink the ESP Now icon, etc. +//This function merely sets the bits to what should be displayed. The main updateDisplay() function pushes bits to screen. +uint32_t setRadioIcons() { uint32_t icons = 0; if (online.display == true) { //There are three spots for icons in the Wireless area, left/center/right - //Center is normally used to indicate base/rover status. //There are three radios that could be active: Bluetooth (always indicated), WiFi (if enabled), ESP-Now (if enabled) //Because of lack of space we will indicate the Base/Rover if only two radios or less are active + //Count the number of radios in use uint8_t numberOfRadios = 1; //Bluetooth always indicated if (wifiState > WIFI_OFF) numberOfRadios++; if (espnowState > ESPNOW_OFF) numberOfRadios++; @@ -624,34 +658,34 @@ uint32_t paintRadioIcons() //Bluetooth only if (numberOfRadios == 1) { - icons |= paintBluetoothIcon_OneRadio(); + icons |= setBluetoothIcon_OneRadio(); - icons |= paintModeIcon(); //Turn on Rover/Base type icons + icons |= setModeIcon(); //Turn on Rover/Base type icons } else if (numberOfRadios == 2) { - icons |= paintBluetoothIcon_TwoRadios(); + icons |= setBluetoothIcon_TwoRadios(); //Do we have WiFi or ESP if (wifiState > WIFI_OFF) - icons |= paintWiFiIcon_TwoRadios(); + icons |= setWiFiIcon_TwoRadios(); else if (espnowState > ESPNOW_OFF) - icons |= paintESPNowIcon_TwoRadios(); + icons |= setESPNowIcon_TwoRadios(); - icons |= paintModeIcon(); //Turn on Rover/Base type icons + icons |= setModeIcon(); //Turn on Rover/Base type icons } else if (numberOfRadios == 3) { //Bluetooth is center - icons |= paintBluetoothIcon_TwoRadios(); + icons |= setBluetoothIcon_TwoRadios(); //ESP Now is left - icons |= paintESPNowIcon_TwoRadios(); + icons |= setESPNowIcon_TwoRadios(); //WiFi is right - icons |= paintWiFiIcon_ThreeRadios(); + icons |= setWiFiIcon_ThreeRadios(); //No Rover/Base icons } @@ -661,135 +695,334 @@ uint32_t paintRadioIcons() } //Bluetooth is in left position -//Paint Bluetooth icons (MAC, Connected, arrows) in left position -uint32_t paintBluetoothIcon_OneRadio() +//Set Bluetooth icons (MAC, Connected, arrows) in left position +uint32_t setBluetoothIcon_OneRadio() { uint32_t icons = 0; - //Covers spots Left and Center if (bluetoothGetState() != BT_CONNECTED) icons |= ICON_MAC_ADDRESS; else if (bluetoothGetState() == BT_CONNECTED) - icons |= ICON_BT_SYMBOL_LEFT; + { + //Limit how often we update this spot + if (millis() - firstRadioSpotTimer > 2000) + { + firstRadioSpotTimer = millis(); + + if (bluetoothIncomingRTCM == true || bluetoothOutgoingRTCM == true) + firstRadioSpotBlink ^= 1; //Share the spot + else + firstRadioSpotBlink = false; + } + + if (firstRadioSpotBlink == false) + icons |= ICON_BT_SYMBOL_LEFT; + else + { + //Share the spot. Determine if we need to indicate Up, or Down + if (bluetoothIncomingRTCM == true) + { + icons |= ICON_DOWN_ARROW_LEFT; + bluetoothIncomingRTCM = false; //Reset, set during UART RX task. + } + else if (bluetoothOutgoingRTCM == true) + { + icons |= ICON_UP_ARROW_LEFT; + bluetoothOutgoingRTCM = false; //Reset, set during UART BT send bytes task. + } + else + icons |= ICON_BT_SYMBOL_LEFT; + } + } return icons; } //Bluetooth is in center position -//Paint Bluetooth icons (MAC, Connected, arrows) in left position -uint32_t paintBluetoothIcon_TwoRadios() +//Set Bluetooth icons (MAC, Connected, arrows) in left position +uint32_t setBluetoothIcon_TwoRadios() { uint32_t icons = 0; if (bluetoothGetState() != BT_CONNECTED) icons |= ICON_MAC_ADDRESS_2DIGIT; else if (bluetoothGetState() == BT_CONNECTED) - icons |= ICON_BT_SYMBOL_CENTER; + { + //Limit how often we update this spot + if (millis() - secondRadioSpotTimer > 2000) + { + secondRadioSpotTimer = millis(); + + if (bluetoothIncomingRTCM == true || bluetoothOutgoingRTCM == true) + secondRadioSpotBlink ^= 1; //Share the spot + else + secondRadioSpotBlink = false; + } + + if (secondRadioSpotBlink == false) + icons |= ICON_BT_SYMBOL_CENTER; + else + { + //Share the spot. Determine if we need to indicate Up, or Down + if (bluetoothIncomingRTCM == true) + { + icons |= ICON_DOWN_ARROW_CENTER; + bluetoothIncomingRTCM = false; //Reset, set during UART RX task. + } + else if (bluetoothOutgoingRTCM == true) + { + icons |= ICON_UP_ARROW_CENTER; + bluetoothOutgoingRTCM = false; //Reset, set during UART BT send bytes task. + } + else + icons |= ICON_BT_SYMBOL_CENTER; + } + } return icons; } //Bluetooth is in center position -//Paint ESP Now icon (Solid, arrows, blinking) in left position -uint32_t paintESPNowIcon_TwoRadios() +//Set ESP Now icon (Solid, arrows, blinking) in left position +uint32_t setESPNowIcon_TwoRadios() { uint32_t icons = 0; #ifdef COMPILE_ESPNOW - //If ESPNOW is paired, and we are in base mode, show animated icon - if (systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) - icons |= ICON_ESPNOW_SYMBOL_LEFT; - - //If ESPNOW is on, and we've received a packet, move BT to make room - else if (espnowRSSI > -255) - icons |= ICON_ESPNOW_SYMBOL_LEFT; - - - //Determine if we transitting or receiving - // if (millis() - espnowLastAdd < 1000) - // { - // //We are actively sending out bytes, animate the icon - // //Animate icon to show data is being transmitted - // espnowIconDisplayed++; //Goto next icon - // espnowIconDisplayed %= 4; //Wrap - // - // if (espnowIconDisplayed == 0) - // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_0); - // else if (espnowIconDisplayed == 1) - // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_1); - // else if (espnowIconDisplayed == 2) - // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_2); - // else if (espnowIconDisplayed == 3) - // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); - // } - // else - // { - // //We are receiving data, adjust icon according to RSSI - // if (espnowRSSI >= -40) - // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_3); - // else if (espnowRSSI >= -60) - // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_2); - // else if (espnowRSSI >= -80) - // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_1); - // else if (espnowRSSI > -255) - // displayBitmap(x, 0, ESPNOW_Symbol_Width, ESPNOW_Symbol_Height, ESPNOW_Symbol_0); - // } + if (espnowState == ESPNOW_PAIRED) + { + //Limit how often we update this spot + if (millis() - firstRadioSpotTimer > 2000) + { + firstRadioSpotTimer = millis(); + + if (espnowIncomingRTCM == true || espnowOutgoingRTCM == true) + firstRadioSpotBlink ^= 1; //Share the spot + else + firstRadioSpotBlink = false; + } + + if (firstRadioSpotBlink == false) + { + if (espnowIncomingRTCM == true) + { + //Based on RSSI, select icon + if (espnowRSSI >= -40) + icons |= ICON_ESPNOW_SYMBOL_3_LEFT; + else if (espnowRSSI >= -60) + icons |= ICON_ESPNOW_SYMBOL_2_LEFT; + else if (espnowRSSI >= -80) + icons |= ICON_ESPNOW_SYMBOL_1_LEFT; + else if (espnowRSSI > -255) + icons |= ICON_ESPNOW_SYMBOL_0_LEFT; + } + else //ESP radio is active, but not receiving RTCM + { + icons |= ICON_ESPNOW_SYMBOL_3_LEFT; //Full symbol + } + } + else + { + //Share the spot. Determine if we need to indicate Up, or Down + if (espnowIncomingRTCM == true) + { + icons |= ICON_DOWN_ARROW_LEFT; + espnowIncomingRTCM = false; //Reset, set during ESP Now data received call back + } + else if (espnowOutgoingRTCM == true) + { + icons |= ICON_UP_ARROW_LEFT; + espnowOutgoingRTCM = false; //Reset, set during espnowProcessRTCM() + } + else + { + icons |= ICON_ESPNOW_SYMBOL_3_LEFT; //Full symbol + + //TODO catch RSSI here + } + } + } + + else //We are not paired, blink icon + { + //Limit how often we update this spot + if (millis() - firstRadioSpotTimer > 2000) + { + firstRadioSpotTimer = millis(); + firstRadioSpotBlink ^= 1; //Share the spot + } + + if (firstRadioSpotBlink == false) + icons |= ICON_ESPNOW_SYMBOL_3_LEFT; //Full symbol + else + icons |= ICON_BLANK_LEFT; + } #endif //ifdef COMPILE_ESPNOW return icons; } //Bluetooth is in center position -//Paint WiFi icon (Solid, arrows, blinking) in left position -uint32_t paintWiFiIcon_TwoRadios() +//Set WiFi icon (Solid, arrows, blinking) in left position +uint32_t setWiFiIcon_TwoRadios() { uint32_t icons = 0; - icons |= ICON_WIFI_SYMBOL_LEFT; - - //TODO Need blinking - // blinking_icons ^= ICON_WIFI_SYMBOL_LEFT; - // if (blinking_icons & ICON_WIFI_SYMBOL_LEFT) - // icons |= ICON_WIFI_SYMBOL_LEFT; - - //TODO Deal with arrows - // if (systemState <= STATE_BASE_NOT_STARTED) - // { - // if (online.rxRtcmCorrectionData) - // icons |= ICON_DOWN_ARROW; - // } - // else if (systemState <= STATE_BUBBLE_LEVEL) - // icons |= ICON_UP_ARROW; + if (wifiState == WIFI_CONNECTED) + { + //Limit how often we update this spot + if (millis() - firstRadioSpotTimer > 2000) + { + firstRadioSpotTimer = millis(); + + if (wifiIncomingRTCM == true || wifiOutgoingRTCM == true) + firstRadioSpotBlink ^= 1; //Share the spot + else + firstRadioSpotBlink = false; + } + + if (firstRadioSpotBlink == false) + { + int wifiRSSI = WiFi.RSSI(); + //Based on RSSI, select icon + if (wifiRSSI >= -40) + icons |= ICON_WIFI_SYMBOL_3_LEFT; + else if (wifiRSSI >= -60) + icons |= ICON_WIFI_SYMBOL_2_LEFT; + else if (wifiRSSI >= -80) + icons |= ICON_WIFI_SYMBOL_1_LEFT; + else + icons |= ICON_WIFI_SYMBOL_0_LEFT; + } + else + { + //Share the spot. Determine if we need to indicate Up, or Down + if (wifiIncomingRTCM == true) + { + icons |= ICON_DOWN_ARROW_LEFT; + wifiIncomingRTCM = false; //Reset, set during NTRIP Client + } + else if (wifiOutgoingRTCM == true) + { + icons |= ICON_UP_ARROW_LEFT; + wifiOutgoingRTCM = false; //Reset, set during NTRIP Server + } + else + { + int wifiRSSI = WiFi.RSSI(); + //Based on RSSI, select icon + if (wifiRSSI >= -40) + icons |= ICON_WIFI_SYMBOL_3_LEFT; + else if (wifiRSSI >= -60) + icons |= ICON_WIFI_SYMBOL_2_LEFT; + else if (wifiRSSI >= -80) + icons |= ICON_WIFI_SYMBOL_1_LEFT; + else + icons |= ICON_WIFI_SYMBOL_0_LEFT; + } + } + } + + else //We are not paired, blink icon + { + //Limit how often we update this spot + if (millis() - firstRadioSpotTimer > 2000) + { + firstRadioSpotTimer = millis(); + firstRadioSpotBlink ^= 1; //Share the spot + } + + if (firstRadioSpotBlink == false) + icons |= ICON_WIFI_SYMBOL_3_LEFT; //Full symbol + else + icons |= ICON_BLANK_LEFT; + } + return (icons); } //Bluetooth is in center position -//Paint WiFi icon (Solid, arrows, blinking) in right position -uint32_t paintWiFiIcon_ThreeRadios() +//Set WiFi icon (Solid, arrows, blinking) in right position +uint32_t setWiFiIcon_ThreeRadios() { uint32_t icons = 0; - icons |= ICON_WIFI_SYMBOL_RIGHT; - - //TODO Need blinking - // blinking_icons ^= ICON_WIFI_SYMBOL_LEFT; - // if (blinking_icons & ICON_WIFI_SYMBOL_LEFT) - // icons |= ICON_WIFI_SYMBOL_LEFT; - - //TODO Deal with arrows - // if (systemState <= STATE_BASE_NOT_STARTED) - // { - // if (online.rxRtcmCorrectionData) - // icons |= ICON_DOWN_ARROW; - // } - // else if (systemState <= STATE_BUBBLE_LEVEL) - // icons |= ICON_UP_ARROW; + if (wifiState == WIFI_CONNECTED) + { + //Limit how often we update this spot + if (millis() - thirdRadioSpotTimer > 2000) + { + thirdRadioSpotTimer = millis(); + + if (wifiIncomingRTCM == true || wifiOutgoingRTCM == true) + thirdRadioSpotBlink ^= 1; //Share the spot + else + thirdRadioSpotBlink = false; + } + + if (thirdRadioSpotBlink == false) + { + int wifiRSSI = WiFi.RSSI(); + //Based on RSSI, select icon + if (wifiRSSI >= -40) + icons |= ICON_WIFI_SYMBOL_3_RIGHT; + else if (wifiRSSI >= -60) + icons |= ICON_WIFI_SYMBOL_2_RIGHT; + else if (wifiRSSI >= -80) + icons |= ICON_WIFI_SYMBOL_1_RIGHT; + else + icons |= ICON_WIFI_SYMBOL_0_RIGHT; + } + else + { + //Share the spot. Determine if we need to indicate Up, or Down + if (wifiIncomingRTCM == true) + { + icons |= ICON_DOWN_ARROW_RIGHT; + wifiIncomingRTCM = false; //Reset, set during NTRIP Client + } + else if (wifiOutgoingRTCM == true) + { + icons |= ICON_UP_ARROW_RIGHT; + wifiOutgoingRTCM = false; //Reset, set during NTRIP Server + } + else + { + int wifiRSSI = WiFi.RSSI(); + //Based on RSSI, select icon + if (wifiRSSI >= -40) + icons |= ICON_WIFI_SYMBOL_3_RIGHT; + else if (wifiRSSI >= -60) + icons |= ICON_WIFI_SYMBOL_2_RIGHT; + else if (wifiRSSI >= -80) + icons |= ICON_WIFI_SYMBOL_1_RIGHT; + else + icons |= ICON_WIFI_SYMBOL_0_RIGHT; + } + } + } + + else //We are not paired, blink icon + { + //Limit how often we update this spot + if (millis() - thirdRadioSpotTimer > 2000) + { + thirdRadioSpotTimer = millis(); + thirdRadioSpotBlink ^= 1; //Share the spot + } + + if (thirdRadioSpotBlink == false) + icons |= ICON_WIFI_SYMBOL_3_RIGHT; //Full symbol + else + icons |= ICON_BLANK_RIGHT; + } + return (icons); } //Based on system state, turn on the various Rover, Base, Fixed Base icons -uint32_t paintModeIcon() +uint32_t setModeIcon() { uint32_t icons = 0; switch (systemState) @@ -912,19 +1145,19 @@ void paintDynamicModel() switch (settings.dynamicModel) { case (DYN_MODEL_PORTABLE): - displayBitmap(27, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_1_Portable); + displayBitmap(28, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_1_Portable); break; case (DYN_MODEL_STATIONARY): - displayBitmap(27, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_2_Stationary); + displayBitmap(28, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_2_Stationary); break; case (DYN_MODEL_PEDESTRIAN): - displayBitmap(27, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_3_Pedestrian); + displayBitmap(28, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_3_Pedestrian); break; case (DYN_MODEL_AUTOMOTIVE): //Normal rover for ZED-F9P, fusion rover for ZED-F9R if (zedModuleType == PLATFORM_F9P) { - displayBitmap(27, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_4_Automotive); + displayBitmap(28, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_4_Automotive); } else if (zedModuleType == PLATFORM_F9R) { @@ -940,7 +1173,7 @@ void paintDynamicModel() baseIconDisplayed = true; //Draw the icon - displayBitmap(27, 2, Rover_Fusion_Width, Rover_Fusion_Height, Rover_Fusion); + displayBitmap(28, 2, Rover_Fusion_Width, Rover_Fusion_Height, Rover_Fusion); } else baseIconDisplayed = false; @@ -949,32 +1182,32 @@ void paintDynamicModel() else if (i2cGNSS.packetUBXESFSTATUS->data.fusionMode == 1) //Calibrated { //Solid fusion rover - displayBitmap(27, 2, Rover_Fusion_Width, Rover_Fusion_Height, Rover_Fusion); + displayBitmap(28, 2, Rover_Fusion_Width, Rover_Fusion_Height, Rover_Fusion); } else if (i2cGNSS.packetUBXESFSTATUS->data.fusionMode == 2 || i2cGNSS.packetUBXESFSTATUS->data.fusionMode == 3) //Suspended or disabled { //Empty rover - displayBitmap(27, 2, Rover_Fusion_Empty_Width, Rover_Fusion_Empty_Height, Rover_Fusion_Empty); + displayBitmap(28, 2, Rover_Fusion_Empty_Width, Rover_Fusion_Empty_Height, Rover_Fusion_Empty); } } break; case (DYN_MODEL_SEA): - displayBitmap(27, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_5_Sea); + displayBitmap(28, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_5_Sea); break; case (DYN_MODEL_AIRBORNE1g): - displayBitmap(27, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_6_Airborne1g); + displayBitmap(28, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_6_Airborne1g); break; case (DYN_MODEL_AIRBORNE2g): - displayBitmap(27, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_7_Airborne2g); + displayBitmap(28, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_7_Airborne2g); break; case (DYN_MODEL_AIRBORNE4g): - displayBitmap(27, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_8_Airborne4g); + displayBitmap(28, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_8_Airborne4g); break; case (DYN_MODEL_WRIST): - displayBitmap(27, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_9_Wrist); + displayBitmap(28, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_9_Wrist); break; case (DYN_MODEL_BIKE): - displayBitmap(27, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_10_Bike); + displayBitmap(28, 0, DynamicModel_Width, DynamicModel_Height, DynamicModel_10_Bike); break; } } @@ -1183,8 +1416,9 @@ void paintRTCM() } //Determine if correction data has been sent recently - if (online.txNtripDataCasting) + if (bluetoothOutgoingRTCM == true || wifiOutgoingRTCM == true || espnowOutgoingRTCM == true) lastCorrectionDataSeen = millis(); + if ((millis() - lastCorrectionDataSeen) >= 5000) { //No correction data seen @@ -1204,7 +1438,6 @@ void paintRTCM() oled.setFont(QW_FONT_8X16); //Set font to type 1: 8x16 oled.print(rtcmPacketsSent); //rtcmPacketsSent is controlled in processRTCM() - online.txNtripDataCasting = false; } paintResets(); @@ -1379,12 +1612,12 @@ uint32_t displayWiFiConfig() if (wifiState == WIFI_NOTCONNECTED) { //Blink WiFi icon - blinking_icons ^= ICON_WIFI_SYMBOL_LEFT; - if (blinking_icons & ICON_WIFI_SYMBOL_LEFT) - icons = ICON_WIFI_SYMBOL_CENTER; + blinking_icons ^= ICON_WIFI_SYMBOL_3_RIGHT; + if (blinking_icons & ICON_WIFI_SYMBOL_3_RIGHT) + icons = ICON_WIFI_SYMBOL_3_RIGHT; } else if (wifiState == WIFI_CONNECTED) - icons = ICON_WIFI_SYMBOL_CENTER; + icons = ICON_WIFI_SYMBOL_3_RIGHT; int yPos = WiFi_Symbol_Height + 2; int fontHeight = 8; diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 114556039..37c2e074b 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -63,7 +63,7 @@ void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int l serialGNSS.write(incomingData, len); log_d("ESPNOW: Received %d bytes, RSSI: %d", len, espnowRSSI); - online.rxRtcmCorrectionData = true; + espnowIncomingRTCM = true; lastEspnowRssiUpdate = millis(); } } @@ -327,4 +327,24 @@ void espnowSetState(ESPNOWState newState) } } +void espnowProcessRTCM(byte incoming) +{ + if (espnowState == ESPNOW_PAIRED) + { + //Move this byte into ESP NOW to send buffer + espnowOutgoing[espnowOutgoingSpot++] = incoming; + espnowLastAdd = millis(); + + if (espnowOutgoingSpot == sizeof(espnowOutgoing)) + { + espnowOutgoingSpot = 0; //Wrap + esp_now_send(0, (uint8_t *) &espnowOutgoing, sizeof(espnowOutgoing)); //Send packet to all peers + delay(10); //We need a small delay between sending multiple packets + log_d("ESPNOW: Sending %d bytes", sizeof(espnowOutgoing)); + + espnowOutgoingRTCM = true; + } + } +} + #endif //ifdef COMPILE_ESPNOW diff --git a/Firmware/RTK_Surveyor/NtripClient.ino b/Firmware/RTK_Surveyor/NtripClient.ino index 92f36c65b..d1a521377 100644 --- a/Firmware/RTK_Surveyor/NtripClient.ino +++ b/Firmware/RTK_Surveyor/NtripClient.ino @@ -290,7 +290,7 @@ void ntripClientStop(bool done) //Determine the next NTRIP client state ntripClientSetState((ntripClient && (!done)) ? NTRIP_CLIENT_ON : NTRIP_CLIENT_OFF); online.ntripClient = false; - online.rxRtcmCorrectionData = false; + wifiIncomingRTCM = false; #endif //COMPILE_WIFI } @@ -446,7 +446,7 @@ void ntripClientUpdate() //Push RTCM to GNSS module over I2C i2cGNSS.pushRawData(rtcmData, rtcmCount); - online.rxRtcmCorrectionData = true; + wifiIncomingRTCM = true; log_d("NTRIP Client pushed %d RTCM bytes to ZED", rtcmCount); } diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 588f91be2..dfecd0013 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -365,7 +365,7 @@ void ntripServerProcessRTCM(uint8_t incoming) ntripServer->write(incoming); //Send this byte to socket ntripServerBytesSent++; ntripServerTimer = millis(); - online.txNtripDataCasting = true; + wifiOutgoingRTCM = true; } } @@ -445,7 +445,7 @@ void ntripServerUpdate() } //If user turns off NTRIP Server via settings, stop server - if (settings.enableNtripServer == false) + if (settings.enableNtripServer == false && ntripServerState > NTRIP_SERVER_OFF) ntripServerStop(true); //Don't allocate new wifiClient //Enable WiFi and the NTRIP server if requested diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 3cc9c4391..f2fb0a2ed 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -28,7 +28,7 @@ const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_WIFI //Comment out to remove WiFi functionality #define COMPILE_BT //Comment out to remove Bluetooth functionality #define COMPILE_AP //Comment out to remove Access Point functionality -//#define COMPILE_ESPNOW //Comment out to remove ESP-Now functionality +#define COMPILE_ESPNOW //Comment out to remove ESP-Now functionality #define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) //Define the RTK board identifier: @@ -151,6 +151,8 @@ LoggingType loggingType = LOGGING_UNKNOWN; #include //Built-in. #include //Built-in. Used for MQTT obtaining of keys +#include "esp_wifi.h" //Needed for esp_wifi_set_protocol() + #include "base64.h" //Built-in. Needed for NTRIP Client credential encoding. #endif @@ -351,7 +353,6 @@ float lBandEBNO = 0.0; //Used on system status menu #ifdef COMPILE_ESPNOW #include -#include "esp_wifi.h" //Needed for esp_wifi_set_protocol() uint8_t espnowOutgoing[250]; //ESP NOW has max of 250 characters unsigned long espnowLastAdd; //Tracks how long since last byte was added to the outgoing buffer @@ -456,6 +457,20 @@ uint32_t max_idle_count = MAX_IDLE_TIME_COUNT; unsigned long lastWifiRSSIUpdate = 0; //Print RSSI when connected every few seconds +bool firstRadioSpotBlink = false; //Controls when the shared icon space is toggled +unsigned long firstRadioSpotTimer = 0; +bool secondRadioSpotBlink = false; //Controls when the shared icon space is toggled +unsigned long secondRadioSpotTimer = 0; +bool thirdRadioSpotBlink = false; //Controls when the shared icon space is toggled +unsigned long thirdRadioSpotTimer = 0; + +bool bluetoothIncomingRTCM = false; +bool bluetoothOutgoingRTCM = false; +bool wifiIncomingRTCM = false; +bool wifiOutgoingRTCM = false; +bool espnowIncomingRTCM = false; +bool espnowOutgoingRTCM = false; + //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- /* +---------------------------------------+ +----------+ @@ -552,7 +567,7 @@ void setup() loadSettings(); //Attempt to load settings after SD is started so we can read the settings file if available - beginIdleTasks(); //Enable processor load calculations + //beginIdleTasks(); //Enable processor load calculations beginUART2(); //Start UART2 on core 0, used to receive serial from ZED and pass out over SPP diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 67015d3c0..6d035fa66 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -14,8 +14,10 @@ void F9PSerialWriteTask(void *e) { //Pass bytes to GNSS receiver int s = bluetoothReadBytes(wBuffer, sizeof(wBuffer)); + + //TODO - control if this RTCM source should be listened to or not serialGNSS.write(wBuffer, s); - online.rxRtcmCorrectionData = true; + bluetoothIncomingRTCM = true; if (settings.enableTaskReports == true) Serial.printf("SerialWriteTask High watermark: %d\n\r", uxTaskGetStackHighWaterMark(NULL)); @@ -172,7 +174,11 @@ void F9PSerialReadTask(void *e) //Push new data to BT SPP if not congested or not throttling btBytesToSend = bluetoothWriteBytes(&rBuffer[btTail], btBytesToSend); if (btBytesToSend > 0) - online.txNtripDataCasting = true; + { + //If we are in base mode, assume part of the outgoing data is RTCM + if(systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) + bluetoothOutgoingRTCM = true; + } else log_w("BT failed to send"); } diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index f0520efed..12a5a0ec5 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -16,7 +16,7 @@ WIFI_OFF | ^ - Use WiFi | | + Use WiFi | | | | WL_CONNECT_FAILED (Bad password) | | WL_NO_SSID_AVAIL (Out of range) v | @@ -219,7 +219,11 @@ void wifiStart(char* ssid, char* pw) { //Radio is off, turn it on WiFi.mode(WIFI_STA); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); } +#else + //Be sure the standard protocols are turned on. ESP Now have have previously turned them off. + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); #endif Serial.printf("Wi-Fi connecting to %s\r\n", ssid); diff --git a/Firmware/RTK_Surveyor/icons.h b/Firmware/RTK_Surveyor/icons.h index 85e00d67f..ddcf99727 100644 --- a/Firmware/RTK_Surveyor/icons.h +++ b/Firmware/RTK_Surveyor/icons.h @@ -41,10 +41,22 @@ int BT_Symbol_Width = 7; */ -uint8_t WiFi_Symbol [] = { +uint8_t WiFi_Symbol_3 [] = { 0x08, 0x04, 0x12, 0x09, 0x25, 0x95, 0xD5, 0x95, 0x25, 0x09, 0x12, 0x04, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, }; +uint8_t WiFi_Symbol_2 [] = { + 0x00, 0x00, 0x10, 0x08, 0x24, 0x94, 0xD4, 0x94, 0x24, 0x08, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +}; +uint8_t WiFi_Symbol_1 [] = { + 0x00, 0x00, 0x00, 0x00, 0x20, 0x90, 0xD0, 0x90, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +}; +uint8_t WiFi_Symbol_0 [] = { + 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0xC0, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +}; int WiFi_Symbol_Height = 9; int WiFi_Symbol_Width = 13; diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 44efe19e9..974435ee5 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -479,9 +479,7 @@ struct struct_online { bool battery = false; bool accelerometer = false; bool ntripClient = false; - bool rxRtcmCorrectionData = false; bool ntripServer = false; - bool txNtripDataCasting = false; bool lband = false; bool lbandCorrections = false; bool i2c = false; diff --git a/Graphics/WiFi Symbol-0.bmp b/Graphics/WiFi Symbol-0.bmp new file mode 100644 index 0000000000000000000000000000000000000000..c4620a85a27d9ef6d5945976647b1f34b5894251 GIT binary patch literal 190 zcmZ?r-Nyg{c0fu4hUgl0|~700Krq2o1Ip I$|Rlw0PtG~s{jB1 literal 0 HcmV?d00001 diff --git a/Graphics/WiFi Symbol-1.bmp b/Graphics/WiFi Symbol-1.bmp new file mode 100644 index 0000000000000000000000000000000000000000..ad3b848e9ff98d3f938480f4df061b768435750a GIT binary patch literal 190 zcmZ?r-Nyg{c0fu4hUgl0|~700Krq2o1Ip O$P|Dw;Nnne>=Xd_mI&Pd literal 0 HcmV?d00001 diff --git a/Graphics/WiFi Symbol-2.bmp b/Graphics/WiFi Symbol-2.bmp new file mode 100644 index 0000000000000000000000000000000000000000..dc6494cc8a3fa5c0ccb40f6f13a22d088d88fe0b GIT binary patch literal 190 zcmZ?r-Nyg{c0fu4hUgl0|~700Krq2o1Ip Z$P|Du1c2fYM*!Uc0)m224PYLO0004-2{8Zw literal 0 HcmV?d00001 diff --git a/Graphics/WiFi Symbol-3.bmp b/Graphics/WiFi Symbol-3.bmp new file mode 100644 index 0000000000000000000000000000000000000000..d0be0258dc18cee731e71f773b992688e8a29767 GIT binary patch literal 190 zcmbV`!4ZHk2n50Ls{>tFMIQOvvM>8Gd(eS5v)m;l1M_~YHLwc~2yok}t@kt&8%OaW fS$BU`jX<95HIf(|f_q+sYmb0T Date: Wed, 10 Aug 2022 20:23:26 -0600 Subject: [PATCH 043/134] Fix compile gates --- Firmware/RTK_Surveyor/Display.ino | 70 ++++++++++++++++----------- Firmware/RTK_Surveyor/Form.ino | 5 +- Firmware/RTK_Surveyor/NtripServer.ino | 6 +-- Firmware/RTK_Surveyor/settings.h | 2 + 4 files changed, 51 insertions(+), 32 deletions(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index e23a7ba48..9391799f6 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -185,43 +185,43 @@ void updateDisplay() case (STATE_ROVER_NOT_STARTED): icons = ICON_BATTERY //Top right - | ICON_CROSS_HAIR //Center left - | ICON_HORIZONTAL_ACCURACY //Center right - | paintSIV() //Bottom left - | ICON_LOGGING; //Bottom right + | ICON_CROSS_HAIR //Center left + | ICON_HORIZONTAL_ACCURACY //Center right + | paintSIV() //Bottom left + | ICON_LOGGING; //Bottom right iconsRadio = setRadioIcons(); //Top left break; case (STATE_ROVER_NO_FIX): icons = ICON_BATTERY //Top right - | ICON_CROSS_HAIR //Center left - | ICON_HORIZONTAL_ACCURACY //Center right - | paintSIV() //Bottom left - | ICON_LOGGING; //Bottom right + | ICON_CROSS_HAIR //Center left + | ICON_HORIZONTAL_ACCURACY //Center right + | paintSIV() //Bottom left + | ICON_LOGGING; //Bottom right iconsRadio = setRadioIcons(); //Top left break; case (STATE_ROVER_FIX): icons = ICON_BATTERY //Top right - | ICON_CROSS_HAIR //Center left - | ICON_HORIZONTAL_ACCURACY //Center right - | paintSIV() //Bottom left - | ICON_LOGGING; //Bottom right + | ICON_CROSS_HAIR //Center left + | ICON_HORIZONTAL_ACCURACY //Center right + | paintSIV() //Bottom left + | ICON_LOGGING; //Bottom right iconsRadio = setRadioIcons(); //Top left break; case (STATE_ROVER_RTK_FLOAT): blinking_icons ^= ICON_CROSS_HAIR_DUAL; icons = ICON_BATTERY //Top right - | (blinking_icons & ICON_CROSS_HAIR_DUAL) //Center left - | ICON_HORIZONTAL_ACCURACY //Center right - | paintSIV() //Bottom left - | ICON_LOGGING; //Bottom right + | (blinking_icons & ICON_CROSS_HAIR_DUAL) //Center left + | ICON_HORIZONTAL_ACCURACY //Center right + | paintSIV() //Bottom left + | ICON_LOGGING; //Bottom right iconsRadio = setRadioIcons(); //Top left break; case (STATE_ROVER_RTK_FIX): icons = ICON_BATTERY //Top right - | ICON_CROSS_HAIR_DUAL//Center left - | ICON_HORIZONTAL_ACCURACY //Center right - | paintSIV() //Bottom left - | ICON_LOGGING; //Bottom right + | ICON_CROSS_HAIR_DUAL//Center left + | ICON_HORIZONTAL_ACCURACY //Center right + | paintSIV() //Bottom left + | ICON_LOGGING; //Bottom right iconsRadio = setRadioIcons(); //Top left break; @@ -235,21 +235,21 @@ void updateDisplay() case (STATE_BASE_TEMP_SETTLE): blinking_icons ^= ICON_CROSS_HAIR; icons = ICON_BATTERY //Top right - | (blinking_icons & ICON_CROSS_HAIR) //Center left - | ICON_HORIZONTAL_ACCURACY //Center right - | paintSIV() //Bottom left - | ICON_LOGGING; //Bottom right + | (blinking_icons & ICON_CROSS_HAIR) //Center left + | ICON_HORIZONTAL_ACCURACY //Center right + | paintSIV() //Bottom left + | ICON_LOGGING; //Bottom right iconsRadio = setRadioIcons(); //Top left break; case (STATE_BASE_TEMP_SURVEY_STARTED): icons = ICON_BATTERY //Top right - | ICON_LOGGING; //Bottom right + | ICON_LOGGING; //Bottom right iconsRadio = setRadioIcons(); //Top left paintBaseTempSurveyStarted(); break; case (STATE_BASE_TEMP_TRANSMITTING): icons = ICON_BATTERY //Top right - | ICON_LOGGING; //Bottom right + | ICON_LOGGING; //Bottom right iconsRadio = setRadioIcons(); //Top left paintRTCM(); break; @@ -259,7 +259,7 @@ void updateDisplay() break; case (STATE_BASE_FIXED_TRANSMITTING): icons = ICON_BATTERY //Top right - | ICON_LOGGING; //Bottom right + | ICON_LOGGING; //Bottom right iconsRadio = setRadioIcons(); //Top left paintRTCM(); break; @@ -884,7 +884,11 @@ uint32_t setWiFiIcon_TwoRadios() if (firstRadioSpotBlink == false) { +#ifdef COMPILE_WIFI int wifiRSSI = WiFi.RSSI(); +#else + int wifiRSSI = -40; //Dummy +#endif //Based on RSSI, select icon if (wifiRSSI >= -40) icons |= ICON_WIFI_SYMBOL_3_LEFT; @@ -910,7 +914,11 @@ uint32_t setWiFiIcon_TwoRadios() } else { +#ifdef COMPILE_WIFI int wifiRSSI = WiFi.RSSI(); +#else + int wifiRSSI = -40; //Dummy +#endif //Based on RSSI, select icon if (wifiRSSI >= -40) icons |= ICON_WIFI_SYMBOL_3_LEFT; @@ -963,7 +971,11 @@ uint32_t setWiFiIcon_ThreeRadios() if (thirdRadioSpotBlink == false) { +#ifdef COMPILE_WIFI int wifiRSSI = WiFi.RSSI(); +#else + int wifiRSSI = -40; //Dummy +#endif //Based on RSSI, select icon if (wifiRSSI >= -40) icons |= ICON_WIFI_SYMBOL_3_RIGHT; @@ -989,7 +1001,11 @@ uint32_t setWiFiIcon_ThreeRadios() } else { +#ifdef COMPILE_WIFI int wifiRSSI = WiFi.RSSI(); +#else + int wifiRSSI = -40; //Dummy +#endif //Based on RSSI, select icon if (wifiRSSI >= -40) icons |= ICON_WIFI_SYMBOL_3_RIGHT; diff --git a/Firmware/RTK_Surveyor/Form.ino b/Firmware/RTK_Surveyor/Form.ino index 0af0aa45b..bffdd2ec0 100644 --- a/Firmware/RTK_Surveyor/Form.ino +++ b/Firmware/RTK_Surveyor/Form.ino @@ -139,10 +139,11 @@ void startWebServer() log_d("Web Server Started"); reportHeapNow(); -#endif -#endif +#endif //COMPILE_AP wifiSetState(WIFI_NOTCONNECTED); +#endif //COMPILE_WIFI + } void stopWebServer() diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index dfecd0013..d2e405732 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -313,9 +313,6 @@ void ntripServerSetState(byte newState) //This function gets called as each RTCM byte comes in void ntripServerProcessRTCM(uint8_t incoming) { - uint32_t currentMilliseconds; - static uint32_t previousMilliseconds = 0; - //Check for too many digits if (settings.enableResetDisplay == true) { @@ -331,6 +328,9 @@ void ntripServerProcessRTCM(uint8_t incoming) } #ifdef COMPILE_WIFI + uint32_t currentMilliseconds; + static uint32_t previousMilliseconds = 0; + if (online.rtc && (ntripServerState == NTRIP_SERVER_CASTING)) { //Timestamp the RTCM messages diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 974435ee5..f046ec1d5 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -485,6 +485,7 @@ struct struct_online { bool i2c = false; } online; +#ifdef COMPILE_WIFI //AWS certificate for PointPerfect API static const char *AWS_PUBLIC_CERT = R"=====( -----BEGIN CERTIFICATE----- @@ -508,3 +509,4 @@ o/ufQJVtMVT8QtPHRh8jrdkPSHCa2XV4cdFyQzR1bldZwgJcJmApzyMZFo6IQ6XU rqXRfboQnoZsG4q5WTP468SQvvG5 -----END CERTIFICATE----- )====="; +#endif From d621185573d6e0db5adb96f2eab99895f9eafdab Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 10 Aug 2022 20:57:09 -0600 Subject: [PATCH 044/134] Fix issue #274 Don't strtod if value contains non alpha/number characters. --- Firmware/RTK_Surveyor/NVM.ino | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index acf67ed83..6d41c6dc5 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -456,6 +456,9 @@ bool parseLine(char* str, Settings *settings) } else { + //if (strcmp(settingName, "ntripServer_CasterHost") == 0) //Debug + // Serial.printf("Found problem spot raw: %s\n\r", str); + //Assume the value is a string such as 8d8a48b. The leading number causes skipSpace to fail. //If settingValue has a mix of letters and numbers, just convert to string sprintf(settingValue, "%s", str); @@ -463,15 +466,20 @@ bool parseLine(char* str, Settings *settings) //Check if string is mixed bool isNumber = false; bool isLetter = false; + bool isOther = false; for (int x = 0 ; x < strlen(settingValue) ; x++) { - if (isAlpha(settingValue[x])) isLetter = true; if (isDigit(settingValue[x])) isNumber = true; + else if (isAlpha(settingValue[x])) isLetter = true; + else isOther = true; } - if (isLetter && isNumber) + if ( (isLetter && isNumber) || isOther) //See issue: https://github.com/sparkfun/SparkFun_RTK_Firmware/issues/274 { //It's a mix. Skip strtod. + + //if (strcmp(settingName, "ntripServer_CasterHost") == 0) //Debug + // Serial.printf("Skipping strtod - settingValue: %s\n\r", settingValue); } else { @@ -927,12 +935,12 @@ bool parseLine(char* str, Settings *settings) { uint8_t macAddress[6]; uint8_t macByte = 0; - + char* token = strtok(settingValue, ","); //Break string up on , - while(token != NULL && macByte < sizeof(macAddress)) + while (token != NULL && macByte < sizeof(macAddress)) { settings->espnowPeers[x][macByte++] = (uint8_t)strtol(token, NULL, 16); - token = strtok(NULL, ","); + token = strtok(NULL, ","); } knownSetting = true; From dd9642b279f8afe4803c74948128e6c65c7d9bb4 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 10 Aug 2022 21:38:45 -0600 Subject: [PATCH 045/134] Better scanning of variable input --- Firmware/RTK_Surveyor/NVM.ino | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index 6d41c6dc5..a64c05cd5 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -463,18 +463,19 @@ bool parseLine(char* str, Settings *settings) //If settingValue has a mix of letters and numbers, just convert to string sprintf(settingValue, "%s", str); - //Check if string is mixed - bool isNumber = false; - bool isLetter = false; - bool isOther = false; + //Check if string is mixed: 8a011EF, 192.168.1.1, -102.4, t6-h4$, etc. + bool hasSymbol = false; + int decimalCount = 0; for (int x = 0 ; x < strlen(settingValue) ; x++) { - if (isDigit(settingValue[x])) isNumber = true; - else if (isAlpha(settingValue[x])) isLetter = true; - else isOther = true; + if (settingValue[x] == '.') decimalCount++; + else if (x == 0 && settingValue[x] == '-') {;} //Do nothing + else if (isAlpha(settingValue[x])) hasSymbol = true; + else if(isDigit(settingValue[x]) == false) hasSymbol = true; } - if ( (isLetter && isNumber) || isOther) //See issue: https://github.com/sparkfun/SparkFun_RTK_Firmware/issues/274 + //See issue: https://github.com/sparkfun/SparkFun_RTK_Firmware/issues/274 + if (hasSymbol || decimalCount > 1) { //It's a mix. Skip strtod. From eb5a3aecd6f58e3da69cfe34f789220b1adfb361 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 10 Aug 2022 21:39:41 -0600 Subject: [PATCH 046/134] Update NVM.ino --- Firmware/RTK_Surveyor/NVM.ino | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index a64c05cd5..734cc3c14 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -469,9 +469,12 @@ bool parseLine(char* str, Settings *settings) for (int x = 0 ; x < strlen(settingValue) ; x++) { if (settingValue[x] == '.') decimalCount++; - else if (x == 0 && settingValue[x] == '-') {;} //Do nothing + else if (x == 0 && settingValue[x] == '-') + { + ; //Do nothing + } else if (isAlpha(settingValue[x])) hasSymbol = true; - else if(isDigit(settingValue[x]) == false) hasSymbol = true; + else if (isDigit(settingValue[x]) == false) hasSymbol = true; } //See issue: https://github.com/sparkfun/SparkFun_RTK_Firmware/issues/274 From 20f3b780be8d550a1ee019705b37ff29a44490df Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 10 Aug 2022 21:56:11 -0600 Subject: [PATCH 047/134] Enable station mode when starting WiFi --- Firmware/RTK_Surveyor/WiFi.ino | 15 ++++----------- 1 file changed, 4 insertions(+), 11 deletions(-) diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 12a5a0ec5..5d9b465e4 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -207,20 +207,13 @@ void wifiStart(char* ssid, char* pw) #ifdef COMPILE_WIFI if ((wifiState == WIFI_OFF) || (wifiState == WIFI_ON)) { + WiFi.mode(WIFI_STA); + #ifdef COMPILE_ESPNOW - //If ESP-Now is active, reconfigure protocols if (espnowState > ESPNOW_OFF) - { - Serial.println("Mixing WiFi into ESPNOW setup"); - //Enable WiFi + ESP-Now - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); - } + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); //Enable WiFi + ESP-Now else - { - //Radio is off, turn it on - WiFi.mode(WIFI_STA); - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); - } + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Set basic WiFi protocols #else //Be sure the standard protocols are turned on. ESP Now have have previously turned them off. esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); From 8f37b54471236c3dfe28cea4b7c45a84d29bc0b7 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 11 Aug 2022 15:42:15 -0600 Subject: [PATCH 048/134] Fix bug in startup battery check The battery gauge was being checked before it was marked as online. Dummy values were returned, causing the low battery check to inaccurately pass. This would lead to very low voltage units into a rolling reset if voltage was too low. --- Firmware/RTK_Surveyor/Begin.ino | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index 02451f9b3..9a29c85be 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -544,6 +544,8 @@ void beginFuelGauge() return; } + online.battery = true; + //Always use hibernate mode if (lipo.getHIBRTActThr() < 0xFF) lipo.setHIBRTActThr((uint8_t)0xFF); if (lipo.getHIBRTHibThr() < 0xFF) lipo.setHIBRTHibThr((uint8_t)0xFF); @@ -553,7 +555,7 @@ void beginFuelGauge() checkBatteryLevels(); //Force check so you see battery level immediately at power on //Check to see if we are dangerously low - if (battLevel < 5 && battChangeRate < 0) //5% and not charging + if (battLevel < 5 && battChangeRate < 0.5) //5% and not charging { Serial.println("Battery too low. Please charge. Shutting down..."); @@ -565,7 +567,6 @@ void beginFuelGauge() powerDown(false); //Don't display 'Shutting Down' } - online.battery = true; } //Begin accelerometer if available From bd320d9cdee477ed0e59b3da3a1b19866bde8017 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 11 Aug 2022 21:11:58 -0600 Subject: [PATCH 049/134] Clear icons during setup menu --- Firmware/RTK_Surveyor/Display.ino | 1 + 1 file changed, 1 insertion(+) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 9391799f6..061bdca3a 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -126,6 +126,7 @@ void updateDisplay() oled.erase(); icons = 0; + iconsRadio = 0; switch (systemState) { From c505ef77759dad6454252140c1ec4e20572069ea Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 11 Aug 2022 21:12:38 -0600 Subject: [PATCH 050/134] Add WiFi RSSI to System menu if connected --- Firmware/RTK_Surveyor/NtripClient.ino | 6 ------ Firmware/RTK_Surveyor/NtripServer.ino | 5 ----- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 2 -- Firmware/RTK_Surveyor/WiFi.ino | 6 ++++-- Firmware/RTK_Surveyor/menuSystem.ino | 5 +++++ 5 files changed, 9 insertions(+), 15 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripClient.ino b/Firmware/RTK_Surveyor/NtripClient.ino index d1a521377..0814c6558 100644 --- a/Firmware/RTK_Surveyor/NtripClient.ino +++ b/Firmware/RTK_Surveyor/NtripClient.ino @@ -452,12 +452,6 @@ void ntripClientUpdate() } } - if (millis() - lastWifiRSSIUpdate > 5000) - { - lastWifiRSSIUpdate = millis(); - Serial.printf("NTRIP WiFi RSSI: %d\n\r", WiFi.RSSI()); - } - break; } #endif //COMPILE_WIFI diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index d2e405732..4ec0918d7 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -583,11 +583,6 @@ void ntripServerUpdate() else cyclePositionLEDs(); - if (millis() - lastWifiRSSIUpdate > 5000) - { - lastWifiRSSIUpdate = millis(); - Serial.printf("NTRIP WiFi RSSI: %d\n\r", WiFi.RSSI()); - } break; } #endif //COMPILE_WIFI diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index f2fb0a2ed..cce862cb1 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -455,8 +455,6 @@ unsigned long rtcWaitTime = 0; //At poweron, we give the RTC a few seconds to up TaskHandle_t idleTaskHandle[MAX_CPU_CORES]; uint32_t max_idle_count = MAX_IDLE_TIME_COUNT; -unsigned long lastWifiRSSIUpdate = 0; //Print RSSI when connected every few seconds - bool firstRadioSpotBlink = false; //Controls when the shared icon space is toggled unsigned long firstRadioSpotTimer = 0; bool secondRadioSpotBlink = false; //Controls when the shared icon space is toggled diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 5d9b465e4..a4895f6f6 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -70,8 +70,10 @@ static uint32_t lastWifiState = 0; void wifiDisplayIpAddress() { - Serial.print("Wi-Fi IP address: "); - Serial.println(WiFi.localIP()); + Serial.print("WiFi IP address: "); + Serial.print(WiFi.localIP()); + Serial.printf(" RSSI: %d\n\r", WiFi.RSSI()); + wifiTimer = millis(); } diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index d0c593e84..ce1e42e26 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -106,6 +106,11 @@ void menuSystem() } Serial.println(); +#ifdef COMPILE_WIFI + if (wifiState == WIFI_CONNECTED) + wifiDisplayIpAddress(); +#endif + //Display the uptime uint64_t uptimeMilliseconds = millis(); uint32_t uptimeDays = 0; From c7b5c30450d278c25f9be1175dcbfb14b6ece9c3 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 11 Aug 2022 21:46:01 -0600 Subject: [PATCH 051/134] Add power down and display to system test sketch --- .../Test Sketches/System_Check/Buttons.ino | 25 +++++++++ .../Test Sketches/System_Check/Display.ino | 53 +++++++++++++++++++ .../System_Check/System_Check.ino | 15 ++++-- .../Test Sketches/System_Check/menuSystem.ino | 7 +++ 4 files changed, 96 insertions(+), 4 deletions(-) create mode 100644 Firmware/Test Sketches/System_Check/Buttons.ino diff --git a/Firmware/Test Sketches/System_Check/Buttons.ino b/Firmware/Test Sketches/System_Check/Buttons.ino new file mode 100644 index 000000000..5eb051769 --- /dev/null +++ b/Firmware/Test Sketches/System_Check/Buttons.ino @@ -0,0 +1,25 @@ +//If we have a power button tap, or if the display is not yet started (no I2C!) +//then don't display a shutdown screen +void powerDown(bool displayInfo) +{ + //Disable SD card use + //endSD(false, false); + + //Prevent other tasks from logging, even if access to the microSD card was denied + online.logging = false; + + if (displayInfo == true) + { + //displayShutdown(); + //delay(2000); + } + + pinMode(pin_powerSenseAndControl, OUTPUT); + digitalWrite(pin_powerSenseAndControl, LOW); + + pinMode(pin_powerFastOff, OUTPUT); + digitalWrite(pin_powerFastOff, LOW); + + while (1) + delay(1); +} diff --git a/Firmware/Test Sketches/System_Check/Display.ino b/Firmware/Test Sketches/System_Check/Display.ino index df093942c..166f91fbb 100644 --- a/Firmware/Test Sketches/System_Check/Display.ino +++ b/Firmware/Test Sketches/System_Check/Display.ino @@ -25,3 +25,56 @@ void beginDisplay() } } } + +//Attempt to send to display regardless of its online status +//The I2C bus may allow it even if bus is misbehaving +void displayHelloWorld() +{ + //if (online.display == true) + //{ + oled.erase(); + + uint8_t fontHeight = 15; + uint8_t yPos = oled.getHeight() / 2 - fontHeight; + + printTextCenter("Accel", yPos, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted + printTextCenter("Failed", yPos + fontHeight, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted + + oled.display(); + +// delay(displayTime); + //} +} + +//Given text, and location, print text center of the screen +void printTextCenter(const char *text, uint8_t yPos, QwiicFont & fontType, uint8_t kerning, bool highlight) //text, y, font type, kearning, inverted +{ + oled.setFont(fontType); + oled.setDrawMode(grROPXOR); + + uint8_t fontWidth = fontType.width; + if (fontWidth == 8) fontWidth = 7; //8x16, but widest character is only 7 pixels. + + uint8_t xStart = (oled.getWidth() / 2) - ((strlen(text) * (fontWidth + kerning)) / 2) + 1; + + uint8_t xPos = xStart; + for (int x = 0 ; x < strlen(text) ; x++) + { + oled.setCursor(xPos, yPos); + oled.print(text[x]); + xPos += fontWidth + kerning; + } + + if (highlight) //Draw a box, inverted over text + { + uint8_t textPixelWidth = strlen(text) * (fontWidth + kerning); + + //Error check + int xBoxStart = xStart - 5; + if (xBoxStart < 0) xBoxStart = 0; + int xBoxEnd = textPixelWidth + 9; + if (xBoxEnd > oled.getWidth() - 1) xBoxEnd = oled.getWidth() - 1; + + oled.rectangleFill(xBoxStart, yPos, xBoxEnd, 12, 1); //x, y, width, height, color + } +} diff --git a/Firmware/Test Sketches/System_Check/System_Check.ino b/Firmware/Test Sketches/System_Check/System_Check.ino index 3e079e9c5..7942a4e2d 100644 --- a/Firmware/Test Sketches/System_Check/System_Check.ino +++ b/Firmware/Test Sketches/System_Check/System_Check.ino @@ -147,6 +147,10 @@ float battChangeRate = 0.0; //External Display //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= #include //http://librarymanager/All#SparkFun_Qwiic_Graphic_OLED + +#include +#include +#include //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= //microSD Interface @@ -175,7 +179,6 @@ uint32_t sdFreeSpaceMB = 0; uint32_t sdUsedSpaceMB = 0; //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- - //Hardware serial and BT buffers //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= HardwareSerial serialGNSS(2); //TX on 17, RX on 16 @@ -190,8 +193,6 @@ unsigned long splashStart = 0; //Controls how long the splash is displayed for. char platformPrefix[40] = "Surveyor"; //Sets the prefix for broadcast names bool zedUartPassed = false; //Goes true during testing if ESP can communicate with ZED over UART - -bool i2cBorked = false; //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- void setup() @@ -244,7 +245,10 @@ void setup() Wire.beginTransmission(0x15); //Dummy address int endValue = Wire.endTransmission(); Serial.printf("Response time: %d endValue: %d\n\r", millis() - startTime, endValue); - if(endValue == 2) online.i2c = true; + if(endValue == 2) + online.i2c = true; + else if (endValue == 5) + Serial.println("It appears something is shorting the I2C lines."); beginBoard(); //Determine what hardware platform we are running on and check on button @@ -259,6 +263,9 @@ void setup() beginSD(); //Test if SD is present + beginDisplay(); //Start display first to be able to display any errors + displayHelloWorld(); //Display something, ignore I2C bus status + menuSystem(); } diff --git a/Firmware/Test Sketches/System_Check/menuSystem.ino b/Firmware/Test Sketches/System_Check/menuSystem.ino index 7b379cb84..8bc9d4e8f 100644 --- a/Firmware/Test Sketches/System_Check/menuSystem.ino +++ b/Firmware/Test Sketches/System_Check/menuSystem.ino @@ -143,6 +143,7 @@ void menuSystem() Serial.println(F("S) Verbose scan of I2C")); Serial.println(F("t) Toggle pin")); Serial.println(F("r) Reset")); + Serial.println(F("p) Power Down")); byte incoming = getByteChoice(menuTimeout); //Timeout after x seconds @@ -259,6 +260,12 @@ void menuSystem() ESP.restart(); } } + else if (incoming == 'p') + { + Serial.println("Power down"); + + powerDown(false); //No display + } else if (incoming == STATUS_GETBYTE_TIMEOUT) { //break; From d9c1ba0f71baa79005266904b2e80021cdaeab07 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 11 Aug 2022 21:46:36 -0600 Subject: [PATCH 052/134] Reset NTRIP connection attempts every 6 hours --- Firmware/RTK_Surveyor/NtripServer.ino | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 4ec0918d7..c6002fce0 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -76,6 +76,11 @@ static uint32_t ntripServerStateLastDisplayed = 0; // * Receive RTCM correction data timeout static uint32_t ntripServerTimer; +//Record last connection attempt +//After 6 hours, reset the connectionAttempts to enable +//multi week/month base installations +static uint32_t lastConnectionAttempt = 0; + //---------------------------------------- // NTRIP Server Routines - compiled out //---------------------------------------- @@ -508,6 +513,8 @@ void ntripServerUpdate() { log_d("NTRIP Server caster failed to connect. Trying again."); + lastConnectionAttempt = millis(); + //Assume service not available if (ntripServerConnectLimitReached()) Serial.println("NTRIP Server failed to connect! Do you have your caster address and port correct?"); @@ -581,8 +588,19 @@ void ntripServerUpdate() ntripServerStop(false); //Allocate new wifiClient } else + { + //All is well cyclePositionLEDs(); + //There may be intermintant disconnects over days or weeks + //Reset the reconnect attempts every 6 hours + if (ntripServerConnectionAttempts > 0 && (millis() - lastConnectionAttempt) > (1000L * 60 * 60 * 6)) + { + ntripServerConnectionAttempts = 0; + log_d("Resetting connection attempts"); + } + } + break; } #endif //COMPILE_WIFI From 4b24eeb4707d73200d0c8d1e01500f26e807cca5 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 12 Aug 2022 10:43:26 -0600 Subject: [PATCH 053/134] Adding Pair submenu --- Firmware/RTK_Surveyor/Display.ino | 24 ++++++++++++++++++++++++ Firmware/RTK_Surveyor/ESPNOW.ino | 1 - Firmware/RTK_Surveyor/States.ino | 15 +++++++++++++++ Firmware/RTK_Surveyor/Tasks.ino | 8 ++++++++ Firmware/RTK_Surveyor/settings.h | 1 + 5 files changed, 48 insertions(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 061bdca3a..12245a901 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -331,6 +331,10 @@ void updateDisplay() //Do nothing. Quick, fall through state. break; + case (STATE_ESPNOW_PAIR): + paintEspNowPair(); + break; + case (STATE_SHUTDOWN): displayShutdown(); break; @@ -2147,6 +2151,13 @@ void paintDisplaySetup() printTextCenter("Bubble", 12 * 2, QW_FONT_8X16, 1, false); printTextCenter("Config", 12 * 3, QW_FONT_8X16, 1, true); } + else if (setupState == STATE_ESPNOW_PAIR) + { + printTextCenter("Base", 12 * 0, QW_FONT_8X16, 1, false); + printTextCenter("Bubble", 12 * 1, QW_FONT_8X16, 1, false); + printTextCenter("Config", 12 * 2, QW_FONT_8X16, 1, false); + printTextCenter("Pair", 12 * 3, QW_FONT_8X16, 1, true); + } else if (setupState == STATE_PROFILE) paintDisplaySetupProfile("Base"); } //end type F9P @@ -2180,6 +2191,13 @@ void paintDisplaySetup() printTextCenter("Bubble", 12 * 2, QW_FONT_8X16, 1, false); printTextCenter("Config", 12 * 3, QW_FONT_8X16, 1, true); } + else if (setupState == STATE_ESPNOW_PAIR) + { + printTextCenter("Rover", 12 * 0, QW_FONT_8X16, 1, false); + printTextCenter("Bubble", 12 * 1, QW_FONT_8X16, 1, false); + printTextCenter("Config", 12 * 2, QW_FONT_8X16, 1, false); + printTextCenter("Pair", 12 * 3, QW_FONT_8X16, 1, true); + } else if (setupState == STATE_PROFILE) paintDisplaySetupProfile("Rover"); } //end type F9R @@ -2501,3 +2519,9 @@ void paintKeyProvisionFail(uint16_t displayTime) delay(displayTime); } } + +//Show screen while ESP-Now is pairing +void paintEspNowPair() +{ + displayMessage("ESP-Now Pairing", 0); +} diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 37c2e074b..e0a6b20d9 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -188,7 +188,6 @@ void espnowStop() void espnowBeginPairing() { espnowStart(); - Serial.println("1"); // To begin pairing, we must add the broadcast MAC to the peer list uint8_t broadcastMac[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 0b6338b0d..8d2c3cbc8 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -898,6 +898,17 @@ void updateSystemState() } break; + case (STATE_ESPNOW_PAIR): + { + if(espnowState == ESPNOW_OFF) + { + espnowBeginPairing(); + } + + //Display 'ESP-Now Pairing' while we wait + } + break; + case (STATE_SHUTDOWN): { forceDisplayUpdate = true; @@ -1038,6 +1049,10 @@ void changeState(SystemState newState) Serial.print("State: Keys Provision - WiFi Timeout"); break; + case (STATE_ESPNOW_PAIR): + Serial.print("State: ESP-Now Pair"); + break; + case (STATE_SHUTDOWN): Serial.print("State: Shut Down"); break; diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 6d035fa66..2815ce9d4 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -412,6 +412,7 @@ void ButtonCheckTask(void *e) case STATE_BUBBLE_LEVEL: case STATE_WIFI_CONFIG_NOT_STARTED: case STATE_WIFI_CONFIG: + case STATE_ESPNOW_PAIR: lastSystemState = systemState; //Remember this state to return after we mark an event requestChangeState(STATE_DISPLAY_SETUP); setupState = STATE_MARK_EVENT; @@ -463,6 +464,9 @@ void ButtonCheckTask(void *e) setupState = STATE_WIFI_CONFIG_NOT_STARTED; break; case STATE_WIFI_CONFIG_NOT_STARTED: + setupState = STATE_ESPNOW_PAIR; + break; + case STATE_ESPNOW_PAIR: //If only one active profile do not show any profiles index = getProfileNumberFromUnit(0); displayProfile = getProfileNumberFromUnit(1); @@ -527,6 +531,7 @@ void ButtonCheckTask(void *e) case STATE_BUBBLE_LEVEL: case STATE_WIFI_CONFIG_NOT_STARTED: case STATE_WIFI_CONFIG: + case STATE_ESPNOW_PAIR: lastSystemState = systemState; //Remember this state to return after we mark an event requestChangeState(STATE_DISPLAY_SETUP); setupState = STATE_MARK_EVENT; @@ -578,6 +583,9 @@ void ButtonCheckTask(void *e) setupState = STATE_WIFI_CONFIG_NOT_STARTED; break; case STATE_WIFI_CONFIG_NOT_STARTED: + setupState = STATE_ESPNOW_PAIR; + break; + case STATE_ESPNOW_PAIR: //If only one active profile do not show any profiles index = getProfileNumberFromUnit(0); displayProfile = getProfileNumberFromUnit(1); diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index f046ec1d5..6da21e836 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -33,6 +33,7 @@ typedef enum STATE_KEYS_PROVISION_WIFI_STARTED, STATE_KEYS_PROVISION_WIFI_CONNECTED, STATE_KEYS_PROVISION_WIFI_TIMEOUT, + STATE_ESPNOW_PAIR, STATE_SHUTDOWN, } SystemState; volatile SystemState systemState = STATE_ROVER_NOT_STARTED; From 459f5433138ed0a05dfb2e710270ca65a3d3f17d Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 12 Aug 2022 13:15:08 -0600 Subject: [PATCH 054/134] Begin adding Pair submenu --- Firmware/RTK_Surveyor/ESPNOW.ino | 66 ++++++++++---------------- Firmware/RTK_Surveyor/NtripServer.ino | 2 +- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 2 +- Firmware/RTK_Surveyor/States.ino | 6 +-- Firmware/RTK_Surveyor/Tasks.ino | 5 ++ Firmware/RTK_Surveyor/menuMain.ino | 28 ++++++++++- 6 files changed, 60 insertions(+), 49 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index e0a6b20d9..64b825cec 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -149,7 +149,7 @@ void espnowStart() //If WiFi is off, stop the radio entirely void espnowStop() { - if(espnowState == ESPNOW_OFF) return; + if (espnowState == ESPNOW_OFF) return; if (wifiState == WIFI_OFF) { @@ -184,7 +184,7 @@ void espnowStop() Serial.println("ESP NOW Off"); } -//Begin broadcasting our MAC and wait for remote unit to respond +//Start ESP-Now if needed, put ESP-Now into broadcast state void espnowBeginPairing() { espnowStart(); @@ -194,55 +194,37 @@ void espnowBeginPairing() espnowAddPeer(broadcastMac, false); // Encryption is not supported for multicast addresses espnowSetState(ESPNOW_PAIRING); +} - //Begin sending our MAC every 250ms until a remote device sends us there info - randomSeed(millis()); - - Serial.println("Begin pairing. Place other unit in pairing mode. Press any key to exit."); - while (Serial.available()) Serial.read(); - - while (1) +//Regularly call during pairing to see if we've received a Pairing message +bool espnowIsPaired() +{ + if (espnowState == ESPNOW_MAC_RECEIVED) { - if (Serial.available()) break; + //Remove broadcast peer + espnowRemovePeer(broadcastMac); - int timeout = 1000 + random(0, 100); //Delay 1000 to 1100ms - for (int x = 0 ; x < timeout ; x++) + if (esp_now_is_peer_exist(receivedMAC) == true) + log_d("Peer already exists"); + else { - delay(1); + //Add new peer to system + espnowAddPeer(receivedMAC); - if (espnowState == ESPNOW_MAC_RECEIVED) - { - //Remove broadcast peer - espnowRemovePeer(broadcastMac); - - if (esp_now_is_peer_exist(receivedMAC) == true) - log_d("Peer already exists"); - else - { - //Add new peer to system - espnowAddPeer(receivedMAC); - - //Record this MAC to peer list - memcpy(settings.espnowPeers[settings.espnowPeerCount], receivedMAC, 6); - settings.espnowPeerCount++; - settings.espnowPeerCount %= ESPNOW_MAX_PEERS; - } - - //Send message directly to the received MAC (not unicast), then exit - espnowSendPairMessage(receivedMAC); - - espnowSetState(ESPNOW_PAIRED); - Serial.println("Pairing compete"); - return; - } + //Record this MAC to peer list + memcpy(settings.espnowPeers[settings.espnowPeerCount], receivedMAC, 6); + settings.espnowPeerCount++; + settings.espnowPeerCount %= ESPNOW_MAX_PEERS; } - espnowSendPairMessage(broadcastMac); //Send unit's MAC address over broadcast, no ack, no encryption + //Send message directly to the received MAC (not unicast), then exit + espnowSendPairMessage(receivedMAC); - Serial.println("Scanning for other radio..."); + espnowSetState(ESPNOW_PAIRED); + Serial.println("Pairing compete"); + return(true); } - - Serial.println("User pressed button. Pairing canceled."); + return(false); } //Create special pair packet to a given MAC diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index c6002fce0..0deed7f31 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -581,7 +581,7 @@ void ntripServerUpdate() Serial.println("NTRIP Server connection dropped"); ntripServerStop(false); //Allocate new wifiClient } - else if ((millis() - ntripServerTimer) > 1000) + else if ((millis() - ntripServerTimer) > 3000) { //GNSS stopped sending RTCM correction data Serial.println("NTRIP Server breaking caster connection due to lack of RTCM data!"); diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 7f1bcb4fd..37f205d1b 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -467,7 +467,7 @@ bool espnowOutgoingRTCM = false; | RTCM |--->|-->| |--------->| |-->|----->|TXD, MISO | | | | | | Bluetooth | | UART 2 | | | UART1 | | | NMEA + RTCM |<---|<--| |<-------+-| |<--|<-----|RXD, MOSI |<----' - +-------------+ | '-----------' | '--------' |28 42| | + +-------------+ | '-----------' | '--------' |28 43| | | | | | | .---------+ | | | | | / uSD Card | | | | | | diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 480ca78c8..3a55051cf 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -902,10 +902,8 @@ void updateSystemState() case (STATE_ESPNOW_PAIR): { - if(espnowState == ESPNOW_OFF) - { - espnowBeginPairing(); - } + +espnowIsPaired() //Display 'ESP-Now Pairing' while we wait } diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 2815ce9d4..44e5122f8 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -618,6 +618,11 @@ void ButtonCheckTask(void *e) } } +TODO once a user has selected 'Pair', send this once + //Start ESP-Now if needed, put ESP-Now into broadcast state + espnowBeginPairing(); + + void idleTask(void *e) { int cpu = xPortGetCoreID(); diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index 9d8b83bbb..5460fa34c 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -334,7 +334,7 @@ void menuRadio() } else Serial.println(" No Paired Radios"); - + Serial.println("2) Pair radios"); Serial.println("3) Forget all radios"); @@ -352,7 +352,33 @@ void menuRadio() else if (settings.radioType == RADIO_ESPNOW && incoming == 2) { Serial.println("Begin ESP NOW Pairing"); + + //Start ESP-Now if needed, put ESP-Now into broadcast state espnowBeginPairing(); + + //Begin sending our MAC every 250ms until a remote device sends us there info + randomSeed(millis()); + + Serial.println("Begin pairing. Place other unit in pairing mode. Press any key to exit."); + while (Serial.available()) Serial.read(); + + while (1) + { + if (Serial.available()) break; + + int timeout = 1000 + random(0, 100); //Delay 1000 to 1100ms + for (int x = 0 ; x < timeout ; x++) + { + delay(1); + if (espnowIsPaired()) break; //Check if we've received a pairing message + } + + espnowSendPairMessage(broadcastMac); //Send unit's MAC address over broadcast, no ack, no encryption + + Serial.println("Scanning for other radio..."); + } + + Serial.println("User pressed button. Pairing canceled."); } else if (settings.radioType == RADIO_ESPNOW && incoming == 3) { From b6d23e518c32753d5ef736b921d67a729372ad85 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Fri, 12 Aug 2022 09:32:00 -1000 Subject: [PATCH 055/134] Add define to RTK_Surveyor to enable/disable compiling of idle tasks --- Firmware/RTK_Surveyor/Begin.ino | 2 ++ Firmware/RTK_Surveyor/RTK_Surveyor.ino | 1 + Firmware/RTK_Surveyor/Tasks.ino | 3 +++ 3 files changed, 6 insertions(+) diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index ffc96ad4b..f64b9c2c0 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -705,6 +705,7 @@ bool beginExternalTriggers() void beginIdleTasks() { +#ifdef COMPILE_IDLE_TASKS if (settings.enablePrintIdleTime == true) { char taskName[32]; @@ -723,6 +724,7 @@ void beginIdleTasks() index); //Core where task should run, 0=core, 1=Arduino } } +#endif //COMPILE_IDLE_TASKS } void beginI2C() diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 7f1bcb4fd..5b7b7f38f 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -30,6 +30,7 @@ const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_AP //Comment out to remove Access Point functionality #define COMPILE_L_BAND //Comment out to remove L-Band functionality #define COMPILE_ESPNOW //Comment out to remove ESP-Now functionality +#define COMPILE_IDLE_TASKS //Comment out to remove idle tasks #define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) //Define the RTK board identifier: diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 2815ce9d4..b2381b451 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -618,6 +618,7 @@ void ButtonCheckTask(void *e) } } +#ifdef COMPILE_IDLE_TASKS void idleTask(void *e) { int cpu = xPortGetCoreID(); @@ -667,3 +668,5 @@ void idleTask(void *e) taskYIELD(); } } +#endif //COMPILE_IDLE_TASKS + From d5dcdca66a8fe9504877d37c8691729a7670b4b8 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Fri, 12 Aug 2022 09:38:43 -1000 Subject: [PATCH 056/134] Increase NTRIP server no RTCM data timeout from 1 second to 3 seconds --- Firmware/RTK_Surveyor/NtripServer.ino | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index c6002fce0..862c2de9f 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -581,7 +581,7 @@ void ntripServerUpdate() Serial.println("NTRIP Server connection dropped"); ntripServerStop(false); //Allocate new wifiClient } - else if ((millis() - ntripServerTimer) > 1000) + else if ((millis() - ntripServerTimer) > (3 * 1000)) { //GNSS stopped sending RTCM correction data Serial.println("NTRIP Server breaking caster connection due to lack of RTCM data!"); From 50922b4ef8f999a02270dec36b70105845197c25 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Fri, 12 Aug 2022 15:20:14 -1000 Subject: [PATCH 057/134] Move the icon width and height to above the icon data, add const Make the width and height easily found for each icon by generically searching for _Width and _Height before the icon data. If width and height not found, use previous width and height. Move the icons, widths and heights from RAM into flash. --- Firmware/RTK_Surveyor/Display.ino | 4 +- Firmware/RTK_Surveyor/icons.h | 181 +++++++++++++++--------------- 2 files changed, 92 insertions(+), 93 deletions(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 12245a901..bcd00552d 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -2287,9 +2287,9 @@ void paintResets() } //Wrapper to avoid needing to pass width/height data twice -void displayBitmap(uint8_t x, uint8_t y, uint8_t imageWidth, uint8_t imageHeight, uint8_t *imageData) +void displayBitmap(uint8_t x, uint8_t y, uint8_t imageWidth, uint8_t imageHeight, const uint8_t *imageData) { - oled.bitmap(x, y, x + imageWidth, y + imageHeight, imageData, imageWidth, imageHeight); + oled.bitmap(x, y, x + imageWidth, y + imageHeight, (uint8_t *)imageData, imageWidth, imageHeight); } void displayKeysUpdated() diff --git a/Firmware/RTK_Surveyor/icons.h b/Firmware/RTK_Surveyor/icons.h index ddcf99727..646a5a6cf 100644 --- a/Firmware/RTK_Surveyor/icons.h +++ b/Firmware/RTK_Surveyor/icons.h @@ -21,11 +21,11 @@ */ -uint8_t BT_Symbol [] = { +const int BT_Symbol_Height = 14; +const int BT_Symbol_Width = 7; +const uint8_t BT_Symbol [] = { 0x18, 0x30, 0xE0, 0xFF, 0xE6, 0x3C, 0x18, 0x06, 0x03, 0x01, 0x3F, 0x19, 0x0F, 0x06, }; -int BT_Symbol_Height = 14; -int BT_Symbol_Width = 7; /* WiFi_Symbol [13, 9] @@ -41,24 +41,24 @@ int BT_Symbol_Width = 7; */ -uint8_t WiFi_Symbol_3 [] = { +const int WiFi_Symbol_Height = 9; +const int WiFi_Symbol_Width = 13; +const uint8_t WiFi_Symbol_3 [] = { 0x08, 0x04, 0x12, 0x09, 0x25, 0x95, 0xD5, 0x95, 0x25, 0x09, 0x12, 0x04, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, }; -uint8_t WiFi_Symbol_2 [] = { +const uint8_t WiFi_Symbol_2 [] = { 0x00, 0x00, 0x10, 0x08, 0x24, 0x94, 0xD4, 0x94, 0x24, 0x08, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, }; -uint8_t WiFi_Symbol_1 [] = { +const uint8_t WiFi_Symbol_1 [] = { 0x00, 0x00, 0x00, 0x00, 0x20, 0x90, 0xD0, 0x90, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, }; -uint8_t WiFi_Symbol_0 [] = { +const uint8_t WiFi_Symbol_0 [] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0xC0, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, }; -int WiFi_Symbol_Height = 9; -int WiFi_Symbol_Width = 13; /* CrossHair [15, 15] @@ -80,12 +80,12 @@ int WiFi_Symbol_Width = 13; */ -uint8_t CrossHair [] = { +const int CrossHair_Height = 15; +const int CrossHair_Width = 15; +const uint8_t CrossHair [] = { 0x80, 0x80, 0xF0, 0x88, 0x84, 0x84, 0x84, 0x7F, 0x84, 0x84, 0x84, 0x88, 0xF0, 0x80, 0x80, 0x00, 0x00, 0x07, 0x08, 0x10, 0x10, 0x10, 0x7F, 0x10, 0x10, 0x10, 0x08, 0x07, 0x00, 0x00, }; -int CrossHair_Height = 15; -int CrossHair_Width = 15; /* CrossHairDual [15, 15] @@ -107,12 +107,12 @@ int CrossHair_Width = 15; */ -uint8_t CrossHairDual [] = { +const int CrossHairDual_Height = 15; +const int CrossHairDual_Width = 15; +const uint8_t CrossHairDual [] = { 0x80, 0x80, 0xF0, 0x88, 0xE4, 0x94, 0x94, 0x7F, 0x94, 0x94, 0xE4, 0x88, 0xF0, 0x80, 0x80, 0x00, 0x00, 0x07, 0x08, 0x13, 0x14, 0x14, 0x7F, 0x14, 0x14, 0x13, 0x08, 0x07, 0x00, 0x00, }; -int CrossHairDual_Height = 15; -int CrossHairDual_Width = 15; /* SIV_Antenna [12, 13] @@ -132,12 +132,12 @@ int CrossHairDual_Width = 15; ****** */ -uint8_t SIV_Antenna [] = { +const int SIV_Antenna_Height = 13; +const int SIV_Antenna_Width = 12; +const uint8_t SIV_Antenna [] = { 0x00, 0x1E, 0x62, 0x84, 0x08, 0x10, 0x20, 0x50, 0x88, 0x00, 0x00, 0x00, 0x00, 0x10, 0x10, 0x1F, 0x1F, 0x12, 0x12, 0x04, 0x04, 0x05, 0x06, 0x00, }; -int SIV_Antenna_Height = 13; -int SIV_Antenna_Width = 12; /* SIV_Antenna_LBand [12, 13] @@ -157,12 +157,12 @@ int SIV_Antenna_Width = 12; ****** */ -uint8_t SIV_Antenna_LBand [] = { +const int SIV_Antenna_LBand_Height = 13; +const int SIV_Antenna_LBand_Width = 12; +const uint8_t SIV_Antenna_LBand [] = { 0x00, 0x1E, 0x62, 0x84, 0x08, 0x14, 0x22, 0x50, 0x88, 0x40, 0x20, 0x00, 0x00, 0x10, 0x10, 0x1F, 0x1F, 0x12, 0x12, 0x04, 0x04, 0x05, 0x06, 0x00, }; -int SIV_Antenna_LBand_Height = 13; -int SIV_Antenna_LBand_Width = 12; /* Rover_Fusion [15, 9] @@ -178,12 +178,12 @@ int SIV_Antenna_LBand_Width = 12; ** ** */ -uint8_t Rover_Fusion [] = { +const int Rover_Fusion_Height = 9; +const int Rover_Fusion_Width = 15; +const uint8_t Rover_Fusion [] = { 0x3E, 0xC1, 0x21, 0x21, 0xC1, 0x7D, 0x55, 0x55, 0x45, 0x41, 0xC2, 0x24, 0x24, 0xC4, 0x3C, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, }; -int Rover_Fusion_Height = 9; -int Rover_Fusion_Width = 15; /* Rover_Fusion_Empty [15, 9] @@ -199,12 +199,12 @@ int Rover_Fusion_Width = 15; ** ** */ -uint8_t Rover_Fusion_Empty [] = { +const int Rover_Fusion_Empty_Height = 9; +const int Rover_Fusion_Empty_Width = 15; +const uint8_t Rover_Fusion_Empty [] = { 0x3E, 0xC1, 0x21, 0x21, 0xC1, 0x41, 0x41, 0x41, 0x41, 0x41, 0xC2, 0x24, 0x24, 0xC4, 0x3C, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, }; -int Rover_Fusion_Empty_Height = 9; -int Rover_Fusion_Empty_Width = 15; /* BaseTemporary [14, 12] @@ -223,12 +223,12 @@ int Rover_Fusion_Empty_Width = 15; */ -uint8_t BaseTemporary [] = { +const int BaseTemporary_Height = 12; +const int BaseTemporary_Width = 14; +const uint8_t BaseTemporary [] = { 0x00, 0xFF, 0x99, 0x99, 0xE7, 0xCE, 0x32, 0x32, 0xE7, 0xE7, 0x99, 0x32, 0xFE, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, }; -int BaseTemporary_Height = 12; -int BaseTemporary_Width = 14; /* BaseFixed [14, 12] @@ -247,12 +247,12 @@ int BaseTemporary_Width = 14; ****** ****** */ -uint8_t BaseFixed [] = { +const int BaseFixed_Height = 12; +const int BaseFixed_Width = 14; +const uint8_t BaseFixed [] = { 0x00, 0xFF, 0x01, 0x0F, 0x01, 0x8F, 0x88, 0x88, 0x8F, 0x01, 0x0F, 0x01, 0xFF, 0x00, 0x0E, 0x09, 0x08, 0x08, 0x08, 0x0F, 0x00, 0x00, 0x0F, 0x08, 0x08, 0x08, 0x09, 0x0E, }; -int BaseFixed_Height = 12; -int BaseFixed_Width = 14; /* Battery_3 [19, 12] @@ -271,13 +271,13 @@ int BaseFixed_Width = 14; ***************** */ -uint8_t Battery_3 [] = { +const int Battery_3_Height = 12; +const int Battery_3_Width = 19; +const uint8_t Battery_3 [] = { 0xFF, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x0F, 0x08, 0xF8, 0x0F, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x0F, 0x01, 0x01, }; -int Battery_3_Height = 12; -int Battery_3_Width = 19; /* Battery_2 [19, 12] @@ -296,13 +296,13 @@ int Battery_3_Width = 19; ***************** */ -uint8_t Battery_2 [] = { +const int Battery_2_Height = 12; +const int Battery_2_Width = 19; +const uint8_t Battery_2 [] = { 0xFF, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x0F, 0x08, 0xF8, 0x0F, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, 0x01, 0x01, }; -int Battery_2_Height = 12; -int Battery_2_Width = 19; /* Battery_1 [19, 12] @@ -321,13 +321,13 @@ int Battery_2_Width = 19; ***************** */ -uint8_t Battery_1 [] = { +const int Battery_1_Height = 12; +const int Battery_1_Width = 19; +const uint8_t Battery_1 [] = { 0xFF, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x0F, 0x08, 0xF8, 0x0F, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, 0x01, 0x01, }; -int Battery_1_Height = 12; -int Battery_1_Width = 19; /* Battery_0 [19, 12] @@ -346,13 +346,13 @@ int Battery_1_Width = 19; ***************** */ -uint8_t Battery_0 [] = { +const int Battery_0_Height = 12; +const int Battery_0_Width = 19; +const uint8_t Battery_0 [] = { 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x0F, 0x08, 0xF8, 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, 0x01, 0x01, }; -int Battery_0_Height = 12; -int Battery_0_Width = 19; /* Logging_3 [9, 12] @@ -371,12 +371,12 @@ int Battery_0_Width = 19; ********* */ -uint8_t Logging_3 [] = { +const int Logging_3_Height = 12; +const int Logging_3_Width = 9; +const uint8_t Logging_3 [] = { 0xFF, 0x01, 0x51, 0x51, 0x51, 0x51, 0x53, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x09, 0x09, 0x09, 0x09, 0x08, 0x0F, }; -int Logging_3_Height = 12; -int Logging_3_Width = 9; /* Logging_2 [9, 12] @@ -395,12 +395,12 @@ int Logging_3_Width = 9; ********* */ -uint8_t Logging_2 [] = { +const int Logging_2_Height = 12; +const int Logging_2_Width = 9; +const uint8_t Logging_2 [] = { 0xFF, 0x01, 0x41, 0x41, 0x41, 0x41, 0x43, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x09, 0x09, 0x09, 0x09, 0x08, 0x0F, }; -int Logging_2_Height = 12; -int Logging_2_Width = 9; /* Logging_1 [9, 12] @@ -419,12 +419,12 @@ int Logging_2_Width = 9; ********* */ -uint8_t Logging_1 [] = { +const int Logging_1_Height = 12; +const int Logging_1_Width = 9; +const uint8_t Logging_1 [] = { 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x09, 0x09, 0x09, 0x09, 0x08, 0x0F, }; -int Logging_1_Height = 12; -int Logging_1_Width = 9; /* Logging_0 [9, 12] @@ -443,44 +443,43 @@ int Logging_1_Width = 9; ********* */ -uint8_t Logging_0 [] = { +const int Logging_0_Height = 12; +const int Logging_0_Width = 9; +const uint8_t Logging_0 [] = { 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, }; -int Logging_0_Height = 12; -int Logging_0_Width = 9; - -uint8_t Logging_PPP_3 [] = { +const uint8_t Logging_PPP_3 [] = { 0xFF, 0x01, 0xF9, 0x49, 0x49, 0x49, 0x33, 0x06, 0xFC, 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, }; -uint8_t Logging_PPP_2 [] = { +const uint8_t Logging_PPP_2 [] = { 0xFF, 0x01, 0xF9, 0x41, 0x41, 0x41, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, }; -uint8_t Logging_PPP_1 [] = { +const uint8_t Logging_PPP_1 [] = { 0xFF, 0x01, 0xC1, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, }; -uint8_t Logging_Custom_3 [] = { +const uint8_t Logging_Custom_3 [] = { 0xFF, 0x01, 0xF1, 0x09, 0x09, 0x09, 0x13, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, 0x08, 0x0F, }; -uint8_t Logging_Custom_2 [] = { +const uint8_t Logging_Custom_2 [] = { 0xFF, 0x01, 0xF1, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, 0x08, 0x0F, }; -uint8_t Logging_Custom_1 [] = { +const uint8_t Logging_Custom_1 [] = { 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, 0x08, 0x0F, }; -int DynamicModel_Height = 12; -int DynamicModel_Width = 15; +const int DynamicModel_Height = 12; +const int DynamicModel_Width = 15; /* DynamicModel_1_Portable [15, 12] @@ -499,7 +498,7 @@ int DynamicModel_Width = 15; ****** */ -uint8_t DynamicModel_1_Portable [] = { +const uint8_t DynamicModel_1_Portable [] = { 0x00, 0xF0, 0x00, 0xF8, 0x04, 0x34, 0x34, 0x37, 0x37, 0x04, 0xF8, 0x00, 0xF0, 0x00, 0x00, 0x00, 0x03, 0x00, 0x07, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x07, 0x00, 0x03, 0x00, 0x00, }; @@ -521,7 +520,7 @@ uint8_t DynamicModel_1_Portable [] = { */ -uint8_t DynamicModel_2_Stationary [] = { +const uint8_t DynamicModel_2_Stationary [] = { 0x00, 0x00, 0x00, 0x00, 0x82, 0xC6, 0x6E, 0xFE, 0x6E, 0xC6, 0x82, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x06, 0x03, 0x01, 0x00, 0x00, 0x07, 0x00, 0x00, 0x01, 0x03, 0x06, 0x04, 0x00, }; @@ -543,7 +542,7 @@ uint8_t DynamicModel_2_Stationary [] = { */ -uint8_t DynamicModel_3_Pedestrian [] = { +const uint8_t DynamicModel_3_Pedestrian [] = { 0x00, 0x00, 0x00, 0x00, 0x20, 0x32, 0x95, 0xF9, 0x95, 0x32, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x06, 0x03, 0x01, 0x00, 0x01, 0x07, 0x04, 0x00, 0x00, 0x00, 0x00, }; @@ -565,7 +564,7 @@ uint8_t DynamicModel_3_Pedestrian [] = { */ -uint8_t DynamicModel_4_Automotive [] = { +const uint8_t DynamicModel_4_Automotive [] = { 0x78, 0x84, 0x44, 0x44, 0x84, 0x84, 0x84, 0x84, 0x84, 0x84, 0x88, 0x50, 0x50, 0x90, 0x70, 0x00, 0x01, 0x02, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x02, 0x01, 0x00, }; @@ -587,7 +586,7 @@ uint8_t DynamicModel_4_Automotive [] = { */ -uint8_t DynamicModel_5_Sea [] = { +const uint8_t DynamicModel_5_Sea [] = { 0x00, 0x60, 0xE0, 0x3C, 0x26, 0x3C, 0x20, 0x20, 0x20, 0xA0, 0xA0, 0x20, 0xE0, 0x60, 0x00, 0x00, 0x00, 0x03, 0x06, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x06, 0x03, 0x00, 0x00, }; @@ -609,7 +608,7 @@ uint8_t DynamicModel_5_Sea [] = { */ -uint8_t DynamicModel_6_Airborne1g [] = { +const uint8_t DynamicModel_6_Airborne1g [] = { 0x00, 0xFE, 0x0C, 0xF8, 0x08, 0x08, 0x88, 0x88, 0x88, 0x28, 0x08, 0x18, 0xB0, 0xE0, 0x00, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x07, 0x08, 0x07, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, }; @@ -631,7 +630,7 @@ uint8_t DynamicModel_6_Airborne1g [] = { */ -uint8_t DynamicModel_7_Airborne2g [] = { +const uint8_t DynamicModel_7_Airborne2g [] = { 0x00, 0xFE, 0x0C, 0xF8, 0x08, 0x08, 0x88, 0xA8, 0x88, 0x28, 0x08, 0x18, 0xB0, 0xE0, 0x00, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x07, 0x08, 0x07, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, }; @@ -653,7 +652,7 @@ uint8_t DynamicModel_7_Airborne2g [] = { */ -uint8_t DynamicModel_8_Airborne4g [] = { +const uint8_t DynamicModel_8_Airborne4g [] = { 0x00, 0xFE, 0x0C, 0xF8, 0x08, 0x28, 0x88, 0xA8, 0x88, 0x28, 0x08, 0x18, 0xB0, 0xE0, 0x00, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x07, 0x08, 0x07, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, }; @@ -675,7 +674,7 @@ uint8_t DynamicModel_8_Airborne4g [] = { *** */ -uint8_t DynamicModel_9_Wrist [] = { +const uint8_t DynamicModel_9_Wrist [] = { 0x00, 0x00, 0x00, 0xE0, 0x10, 0x08, 0x4F, 0x4F, 0x4F, 0x08, 0x10, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x1E, 0x1E, 0x1E, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, }; @@ -697,7 +696,7 @@ uint8_t DynamicModel_9_Wrist [] = { */ -uint8_t DynamicModel_10_Bike [] = { +const uint8_t DynamicModel_10_Bike [] = { 0x00, 0x80, 0x40, 0x50, 0x90, 0xB0, 0xC0, 0xC0, 0xC0, 0xA0, 0x98, 0x4C, 0x4C, 0x80, 0x00, 0x00, 0x01, 0x02, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x02, 0x01, 0x00, }; @@ -716,11 +715,11 @@ uint8_t DynamicModel_10_Bike [] = { ** */ -uint8_t DownloadArrow [] = { +const int DownloadArrow_Height = 9; +const int DownloadArrow_Width = 8; +const uint8_t DownloadArrow [] = { 0x20, 0x60, 0xC0, 0xFF, 0xFF, 0xC0, 0x60, 0x20, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00 }; -int DownloadArrow_Height = 9; -int DownloadArrow_Width = 8; /* UploadArrow [8, 9] @@ -736,11 +735,11 @@ int DownloadArrow_Width = 8; ** */ -uint8_t UploadArrow [] = { +const int UploadArrow_Height = 9; +const int UploadArrow_Width = 8; +const uint8_t UploadArrow [] = { 0x08, 0x0C, 0x06, 0xFF, 0xFF, 0x06, 0x0C, 0x08, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00 }; -int UploadArrow_Height = 9; -int UploadArrow_Width = 8; /* logoSparkFun [64, 48] @@ -800,7 +799,9 @@ int UploadArrow_Width = 8; */ //SparkFun Electronics LOGO -uint8_t logoSparkFun [] = { +const int logoSparkFun_Height = 48; +const int logoSparkFun_Width = 64; +const uint8_t logoSparkFun [] = { // ROW0, BYTE0 to BYTE63 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0xF8, 0xFC, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, @@ -837,20 +838,18 @@ uint8_t logoSparkFun [] = { 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; -int logoSparkFun_Height = 48; -int logoSparkFun_Width = 64; -uint8_t ESPNOW_Symbol_3 [] = { +const int ESPNOW_Symbol_Height = 13; +const int ESPNOW_Symbol_Width = 8; +const uint8_t ESPNOW_Symbol_3 [] = { 0xE0, 0x40, 0x10, 0xE4, 0x09, 0xF2, 0x04, 0xF8, 0x00, 0x00, 0x01, 0x04, 0x12, 0x09, 0x04, 0x03 }; -uint8_t ESPNOW_Symbol_2 [] = { +const uint8_t ESPNOW_Symbol_2 [] = { 0xE0, 0x40, 0x10, 0xE4, 0x08, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x02, 0x01, 0x00, 0x00 }; -uint8_t ESPNOW_Symbol_1 [] = { +const uint8_t ESPNOW_Symbol_1 [] = { 0xE0, 0x40, 0x10, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00 }; -uint8_t ESPNOW_Symbol_0 [] = { +const uint8_t ESPNOW_Symbol_0 [] = { 0xE0, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; -int ESPNOW_Symbol_Height = 13; -int ESPNOW_Symbol_Width = 8; From 923050b3800fddd0dd500bc14037675e78625ddc Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Fri, 12 Aug 2022 15:17:42 -1000 Subject: [PATCH 058/134] Add program to draw pictures from the icon data Build the program: gcc -i Icons Icons.c Execute the program: Icons ../Firmware/RTK_Surveyor/icons.h Outputs a new version of the icons.h file --- C/Icons.c | 547 ++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 547 insertions(+) create mode 100644 C/Icons.c diff --git a/C/Icons.c b/C/Icons.c new file mode 100644 index 000000000..d053adee8 --- /dev/null +++ b/C/Icons.c @@ -0,0 +1,547 @@ +#include +#include +#include +#include +#include +#include + +#define ALPHABETICAL_ORDER 0 +#define DISPLAY_COMMENT 1 +#define DISPLAY_VARIABLES 1 +#define DRAW_OUTLINE 1 +#define PRINT_FILE_LINES 0 +#define PRINT_HEIGHT 0 +#define PRINT_SYMBOL 0 +#define PRINT_VALUES 0 +#define PRINT_WIDTH 0 +#define WRAP_AT_16 0 +#define USE_UPPERCASE_A 1 +#define ADD_TRAILING_COMMA 0 + +typedef struct _ICON_ENTRY { + struct _ICON_ENTRY * next; + const char * name; + int height; + const char * height_name; + int width; + const char * width_name; + int bytes_high; + int bytes_wide; + uint8_t data[]; +} ICON_ENTRY; + +int height; +char * icon_text; +ICON_ENTRY * icon_list; +int width; + +// Replace CR and LF with zeros +char * +terminate_end_of_line ( + char * text, + char * text_end + ) +{ + // Locate the end of line + while ((text < text_end) && (*text != '\r') && (*text != '\n')) + text++; + + // Skip over the end of line + while ((text < text_end) && (*text == '\r') || (*text == '\n')) + *text++ = 0; + + // Return the start of the next line + return text; +} + +// Skip over white space +char * +skip_white_space ( + char * text, + char * text_end + ) +{ + // Locate the first non-white space character + while ((text < text_end) && ((*text == ' ') || (*text == '\t'))) + text++; + + // Return the address of the first non-white space character + return text; +} + +// Find the icon name +char * +find_icon_data ( + char * text, + char * text_end + ) +{ + // Locate the end of the icon symbol name + while ((text < text_end) && (*text != ' ') && (*text != '\t') && (*text != '[')) + text++; + + // Zero terminate the symbol name + if (text < text_end) + *text++ = 0; + + // Locate the beginning of the icon data + while ((text < text_end) && (*text != '{')) + text++; + + // Skip over the left parenthesis + if (text < text_end) + text++; + + // Return the beginning of the data + return skip_white_space (text, text_end); +} + +void +add_entry ( + ICON_ENTRY * new_entry + ) +{ + ICON_ENTRY * next_entry; + + if (ALPHABETICAL_ORDER) { + // Add to the head of the list + if ((icon_list == NULL) || (strcasecmp(icon_list->name, new_entry->name) > 0)) { + new_entry->next = icon_list; + icon_list = new_entry; + } else { + + // Locate the point in the list to insert the new entry + next_entry = icon_list; + while (next_entry->next && (strcasecmp(next_entry->next->name, new_entry->name) < 0)) + next_entry = next_entry->next; + + new_entry->next = next_entry->next; + next_entry->next = new_entry; + } + } else { + // Add to the head of the list + if (icon_list == NULL) { + new_entry->next = icon_list; + icon_list = new_entry; + } else { + + // Locate the point in the list to insert the new entry + next_entry = icon_list; + while (next_entry->next) + next_entry = next_entry->next; + + new_entry->next = next_entry->next; + next_entry->next = new_entry; + } + } +} + +char * +read_icon_data ( + char * name, + char * height_name, + char * width_name, + char * text, + char * text_end + ) +{ + int bytes_high; + int bytes_wide; + int data_bytes; + ICON_ENTRY * icon_entry; + int index; + char * number; + int value; + int x; + int y; + + // Allocate the data structure + bytes_high = (height + 7) / 8; + bytes_wide = width; + data_bytes = width * bytes_high; + icon_entry = malloc (sizeof(*icon_entry) + data_bytes); + if (icon_entry) { + icon_entry->name = name; + icon_entry->height = height; + icon_entry->height_name = height_name; + icon_entry->width = width; + icon_entry->width_name = width_name; + icon_entry->bytes_high = bytes_high; + icon_entry->bytes_wide = bytes_wide; + add_entry (icon_entry); + + // Read the data bytes + for (y = 0; y < bytes_high; y++) { + for (x = 0; x < bytes_wide; x++) { + + // Skip any white space + while ((text < text_end) && (*text != '0')) { + // Treat comments as white space + if ((*text != '/') || ((text[1] != '/') && (text[1] != '*'))) + text++; + else { + // Skip over C++ style comment // + if (text[1] == '/') + while ((*text != '\r') && (*text != '\n')) + text++; + // Skip over the C style comment /* .. */ + else { + text += 2; + while ((*text != '*') && (text[1] != '/')) + text++; + } + } + } + + // Save the number location + number = text; + + // Zero terminate the number + while (((*text >= '0') && (*text <= '9')) + || ((*text >= 'a') && (*text <= 'f')) + || ((*text >= 'A') && (*text <= 'F')) + || (*text == 'x') || (*text == 'X')) + text++; + *text++ = 0; + + // Get the value + sscanf (number, "0x%x", &value); + + // Display the value if requested + if (PRINT_VALUES) + printf("0x%02x\r\n", value); + + // Place the value in the array + index = (y * bytes_wide) + x; + icon_entry->data[index] = value; + icon_entry->data[(y * bytes_wide) + x] = value; + } + } + } + + // Skip over the data + return text; +} + +const char * +display_name ( + ICON_ENTRY * icon + ) +{ + return icon ? icon->name : "NULL"; +} + +int +process_data ( + int icon_file, + ssize_t valid_data + ) +{ + char * data; + char * data_end; + char * height_name; + const char * height_string = "_Height = "; + int height_string_length; + const char * int_string = "const int "; + int int_string_length; + char * name; + char * next_line; + int status; + int temp; + char * text; + const char * uint8_t_string = "const uint8_t "; + int uint8_t_string_length; + char * width_name; + const char * width_string = "_Width = "; + int width_string_length; + + data = icon_text; + data_end = &data[valid_data]; + status = -1; + height_string_length = strlen (height_string); + int_string_length = strlen (int_string); + uint8_t_string_length = strlen (uint8_t_string); + width_string_length = strlen (width_string); + width_name = NULL; + height_name = NULL; + while (data < data_end) { + text = data; + next_line = terminate_end_of_line (text, data_end); + + // Display the line if requested + if (PRINT_FILE_LINES) + printf ("%s\r\n", text); + + // Locate the text at the beginning of the line + text = skip_white_space (text, data_end); + + // Determine if this is a width or height line + if (strncmp (text, int_string, int_string_length) == 0) + { + text = skip_white_space (&text[int_string_length], data_end); + name = text; + while (1) { + // Locate the underscore + while (*text && (*text != '_')) + text++; + + // Not a width or height line when end of line is reached + if (!*text) + break; + + // Determine if this is a height line + if (strncmp (text, height_string, height_string_length) == 0) + { + // Zero terminate the name + name[&text[height_string_length] - 3 - name] = 0; + height_name = name; + + // Skip over any additional white space + text = skip_white_space (&text[height_string_length], data_end); + + // Get the height + if (sscanf (text, "%d", &temp) == 1) + { + height = temp; + if (PRINT_HEIGHT) + printf ("Height: %d\r\n", height); + } + break; + } + + // Determine if this is a width line + else if (strncmp (text, width_string, width_string_length) == 0) + { + // Zero terminate the name + name[&text[width_string_length] - 3 - name] = 0; + width_name = name; + + // Skip over any additional white space + text = skip_white_space (&text[width_string_length], data_end); + + // Get the width + if (sscanf (text, "%d", &temp) == 1) + { + width = temp; + if (PRINT_WIDTH) + printf ("Width: %d\r\n", width); + } + break; + } + + // Continue the underscore search + text++; + } + } + + // Determine if this is an icon line + else if (strncmp (text, uint8_t_string, uint8_t_string_length) == 0) + { + // Skip over any additional white space + text = skip_white_space (&text[uint8_t_string_length], data_end); + name = text; + + // Locate the beginning of the data + text = find_icon_data (text, data_end); + + // Print the symbol name if requested + if (PRINT_SYMBOL) + printf ("Symbol: %s\r\n", name); + + // Read the icon data + text = read_icon_data (name, height_name, width_name, text, data_end); + height_name = NULL; + width_name = NULL; + } + + // Skip to the next line + data = next_line; + } + if (data >= data_end) + status = 0; + return status; +} + +void +display_icon ( + ICON_ENTRY * icon + ) +{ + int bit; + int display_width; + const char * indent = " "; + int index; + int max_index; + int x; + int y; + + /* + 0x20, 0x60, 0xC0, 0xFF, 0xFF, 0xC0, 0x60, 0x20, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00 + + ** + ** + ** + ** + ** + ** ** ** + ****** + **** + ** + */ + + printf ("/*\r\n"); + printf (" %s [%d, %d]\r\n", icon->name, icon->width, icon->height); + printf ("\r\n"); + if (DRAW_OUTLINE) { + if (icon->width > 9) { + printf ("%s ", indent); + for (x = 1; x <= icon->width; x++) + printf ("%c", (x % 10) ? ' ' : ('0' + (x / 10))); + printf ("\r\n"); + } + printf ("%s ", indent); + for (x = 1; x <= icon->width; x++) + printf ("%d", x % 10); + printf ("\r\n"); + printf ("%s .", indent); + for (x = 0; x < icon->width; x++) + printf ("-"); + printf (".\r\n"); + } + for (y = 0; y < icon->height; y++) { + printf ("%s", indent); + if (DRAW_OUTLINE) + printf ("0x%02x|", 1 << (y & 7)); + for (x = 0; x < icon->width; x++) { + bit = icon->data[((y >> 3) * icon->bytes_wide) + x]; + bit >>= y & 7; + printf ("%c", (bit & 1) ? '*' : ' '); + } + if (DRAW_OUTLINE) + printf ("|"); + printf ("\r\n"); + } + if (DRAW_OUTLINE) { + printf ("%s '", indent); + for (x = 0; x < icon->width; x++) + printf ("-"); + printf ("'\r\n"); + } + printf ("*/\r\n"); + printf ("\r\n"); + + // Display the symbols if requested + if (DISPLAY_VARIABLES) { + if (icon->height_name) + printf ("const int %s = %d;\r\n", icon->height_name, icon->height); + if (icon->width_name) + printf ("const int %s = %d;\r\n", icon->width_name, icon->width); + printf ("const uint8_t %s [] = {", icon->name); + display_width = icon->bytes_wide; + if (WRAP_AT_16 || (display_width > 20)) + display_width = 16; + max_index = icon->bytes_high * icon->bytes_wide; + for (index = 0; index < max_index; index++) { + if ((index % display_width) == 0) + printf ("\r\n "); + if (USE_UPPERCASE_A) + printf (" 0x%02X", icon->data[index]); + else + printf (" 0x%02x", icon->data[index]); + if (index != (max_index - 1)) + printf (","); + } + if (ADD_TRAILING_COMMA) + printf (","); + printf ("\r\n"); + printf ("};\r\n"); + printf ("\r\n"); + } +} + +int +main ( + int argc, + char ** argv + ) +{ + char * filename; + ICON_ENTRY * icon; + char * icon_name; + int icon_file; + off_t file_length; + int status; + ssize_t valid_data; + + do { + // Assume failure + icon_file = -1; + status = -1; + + // Get the icon name + if (argc != 2) { + fprintf (stderr, "ERROR - Icon file name not specified!\r\n"); + break; + } + filename = argv[1]; + + // Open the icon file + icon_file = open (filename, O_RDONLY); + if (icon_file < 0) { + perror("ERROR - File open failed!"); + break; + } + + // Determine the length of the file + file_length = lseek (icon_file, 0, SEEK_END); + + // Go the the beginning of the file + lseek (icon_file, 0, SEEK_SET); + + // Allocate the buffer + icon_text = malloc (file_length + 1); + if (!icon_text) { + fprintf (stderr, "ERROR - Failed to allocate icon buffer!\r\n"); + break; + } + + // Zero terminate the last line in the file + icon_text[file_length] = 0; + + // Fill the buffer + valid_data = read(icon_file, icon_text, file_length); + if (valid_data < 0) { + fprintf (stderr, "ERROR - File read failed!\r\n"); + break; + } + + // Process the data + if (valid_data) + if (process_data(icon_file, valid_data)) + break; + + // Display the initial comment + if (DISPLAY_COMMENT) { + printf ("//Create a bitmap then use http://en.radzio.dxp.pl/bitmap_converter/ to generate output\r\n"); + printf ("//Make sure the bitmap is n*8 pixels tall (pad white pixels to lower area as needed)\r\n"); + printf ("//Otherwise the bitmap bitmap_converter will compress some of the bytes together\r\n"); + printf ("\r\n"); + } + + // Display the icon names + icon = icon_list; + while (icon) { + display_icon (icon); + icon = icon->next; + } + + // Indicate success + status = 0; + } while (0); + + // Close the file + if (icon_file >= 0) + close(icon_file); + + return status; +} From dfc6ac853b8757101cacabdbf1d05ad806b674c2 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Fri, 12 Aug 2022 15:24:36 -1000 Subject: [PATCH 059/134] Update the icon drawings --- Firmware/RTK_Surveyor/icons.h | 1286 +++++++++++++++++++++------------ 1 file changed, 828 insertions(+), 458 deletions(-) diff --git a/Firmware/RTK_Surveyor/icons.h b/Firmware/RTK_Surveyor/icons.h index 646a5a6cf..bc178b627 100644 --- a/Firmware/RTK_Surveyor/icons.h +++ b/Firmware/RTK_Surveyor/icons.h @@ -5,746 +5,1036 @@ /* BT_Symbol [7, 14] - - ** - *** - * * ** - ** * ** - ***** - *** - *** - ***** - ** * ** - * * ** - *** - ** - + 1234567 + .-------. + 0x01| * | + 0x02| ** | + 0x04| *** | + 0x08|* * **| + 0x10|** * **| + 0x20| ***** | + 0x40| *** | + 0x80| *** | + 0x01| ***** | + 0x02|** * **| + 0x04|* * **| + 0x08| *** | + 0x10| ** | + 0x20| * | + '-------' */ const int BT_Symbol_Height = 14; const int BT_Symbol_Width = 7; const uint8_t BT_Symbol [] = { - 0x18, 0x30, 0xE0, 0xFF, 0xE6, 0x3C, 0x18, 0x06, 0x03, 0x01, 0x3F, 0x19, 0x0F, 0x06, + 0x18, 0x30, 0xE0, 0xFF, 0xE6, 0x3C, 0x18, + 0x06, 0x03, 0x01, 0x3F, 0x19, 0x0F, 0x06 }; /* - WiFi_Symbol [13, 9] - - ******* - * * - * ***** * - * * * * - * *** * - * * - - *** - + WiFi_Symbol_3 [13, 9] + + 1 + 1234567890123 + .-------------. + 0x01| ******* | + 0x02| * * | + 0x04| * ***** * | + 0x08|* * * *| + 0x10| * *** * | + 0x20| * * | + 0x40| * | + 0x80| *** | + 0x01| * | + '-------------' */ const int WiFi_Symbol_Height = 9; const int WiFi_Symbol_Width = 13; const uint8_t WiFi_Symbol_3 [] = { - 0x08, 0x04, 0x12, 0x09, 0x25, 0x95, 0xD5, 0x95, 0x25, 0x09, 0x12, 0x04, 0x08, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x08, 0x04, 0x12, 0x09, 0x25, 0x95, 0xD5, 0x95, 0x25, 0x09, 0x12, 0x04, 0x08, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; + +/* + WiFi_Symbol_2 [13, 9] + + 1 + 1234567890123 + .-------------. + 0x01| | + 0x02| | + 0x04| ***** | + 0x08| * * | + 0x10| * *** * | + 0x20| * * | + 0x40| * | + 0x80| *** | + 0x01| * | + '-------------' +*/ + const uint8_t WiFi_Symbol_2 [] = { - 0x00, 0x00, 0x10, 0x08, 0x24, 0x94, 0xD4, 0x94, 0x24, 0x08, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x10, 0x08, 0x24, 0x94, 0xD4, 0x94, 0x24, 0x08, 0x10, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; + +/* + WiFi_Symbol_1 [13, 9] + + 1 + 1234567890123 + .-------------. + 0x01| | + 0x02| | + 0x04| | + 0x08| | + 0x10| *** | + 0x20| * * | + 0x40| * | + 0x80| *** | + 0x01| * | + '-------------' +*/ + const uint8_t WiFi_Symbol_1 [] = { - 0x00, 0x00, 0x00, 0x00, 0x20, 0x90, 0xD0, 0x90, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x20, 0x90, 0xD0, 0x90, 0x20, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; + +/* + WiFi_Symbol_0 [13, 9] + + 1 + 1234567890123 + .-------------. + 0x01| | + 0x02| | + 0x04| | + 0x08| | + 0x10| | + 0x20| | + 0x40| * | + 0x80| *** | + 0x01| * | + '-------------' +*/ + const uint8_t WiFi_Symbol_0 [] = { - 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0xC0, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0xC0, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; /* CrossHair [15, 15] - - - ******* - * * * - * * * - * * * - * * * - ******* ******* - * * * - * * * - * * * - * * * - ******* - - + 1 + 123456789012345 + .---------------. + 0x01| * | + 0x02| * | + 0x04| ******* | + 0x08| * * * | + 0x10| * * * | + 0x20| * * * | + 0x40| * * * | + 0x80|******* *******| + 0x01| * * * | + 0x02| * * * | + 0x04| * * * | + 0x08| * * * | + 0x10| ******* | + 0x20| * | + 0x40| * | + '---------------' */ const int CrossHair_Height = 15; const int CrossHair_Width = 15; const uint8_t CrossHair [] = { - 0x80, 0x80, 0xF0, 0x88, 0x84, 0x84, 0x84, 0x7F, 0x84, 0x84, 0x84, 0x88, 0xF0, 0x80, 0x80, 0x00, - 0x00, 0x07, 0x08, 0x10, 0x10, 0x10, 0x7F, 0x10, 0x10, 0x10, 0x08, 0x07, 0x00, 0x00, + 0x80, 0x80, 0xF0, 0x88, 0x84, 0x84, 0x84, 0x7F, 0x84, 0x84, 0x84, 0x88, 0xF0, 0x80, 0x80, + 0x00, 0x00, 0x07, 0x08, 0x10, 0x10, 0x10, 0x7F, 0x10, 0x10, 0x10, 0x08, 0x07, 0x00, 0x00 }; /* CrossHairDual [15, 15] - - - ******* - * * * - * ***** * - * * * * * - * * * * * - ******* ******* - * * * * * - * * * * * - * ***** * - * * * - ******* - - + 1 + 123456789012345 + .---------------. + 0x01| * | + 0x02| * | + 0x04| ******* | + 0x08| * * * | + 0x10| * ***** * | + 0x20| * * * * * | + 0x40| * * * * * | + 0x80|******* *******| + 0x01| * * * * * | + 0x02| * * * * * | + 0x04| * ***** * | + 0x08| * * * | + 0x10| ******* | + 0x20| * | + 0x40| * | + '---------------' */ const int CrossHairDual_Height = 15; const int CrossHairDual_Width = 15; const uint8_t CrossHairDual [] = { - 0x80, 0x80, 0xF0, 0x88, 0xE4, 0x94, 0x94, 0x7F, 0x94, 0x94, 0xE4, 0x88, 0xF0, 0x80, 0x80, 0x00, - 0x00, 0x07, 0x08, 0x13, 0x14, 0x14, 0x7F, 0x14, 0x14, 0x13, 0x08, 0x07, 0x00, 0x00, + 0x80, 0x80, 0xF0, 0x88, 0xE4, 0x94, 0x94, 0x7F, 0x94, 0x94, 0xE4, 0x88, 0xF0, 0x80, 0x80, + 0x00, 0x00, 0x07, 0x08, 0x13, 0x14, 0x14, 0x7F, 0x14, 0x14, 0x13, 0x08, 0x07, 0x00, 0x00 }; /* SIV_Antenna [12, 13] - - ** - * * - * * * - * * * - * * - * * - * * - ** * - **** * - ** **** - ** - ****** + 1 + 123456789012 + .------------. + 0x01| | + 0x02| ** | + 0x04| * * | + 0x08| * * * | + 0x10| * * * | + 0x20| * * | + 0x40| * * | + 0x80| * * | + 0x01| ** * | + 0x02| **** * | + 0x04| ** **** | + 0x08| ** | + 0x10| ****** | + '------------' */ const int SIV_Antenna_Height = 13; const int SIV_Antenna_Width = 12; const uint8_t SIV_Antenna [] = { - 0x00, 0x1E, 0x62, 0x84, 0x08, 0x10, 0x20, 0x50, 0x88, 0x00, 0x00, 0x00, 0x00, 0x10, 0x10, 0x1F, - 0x1F, 0x12, 0x12, 0x04, 0x04, 0x05, 0x06, 0x00, + 0x00, 0x1E, 0x62, 0x84, 0x08, 0x10, 0x20, 0x50, 0x88, 0x00, 0x00, 0x00, + 0x00, 0x10, 0x10, 0x1F, 0x1F, 0x12, 0x12, 0x04, 0x04, 0x05, 0x06, 0x00 }; /* SIV_Antenna_LBand [12, 13] - - ** * - * * * - * * * - * * * - * * * - * * * - * * - ** * - **** * - ** **** - ** - ****** + 1 + 123456789012 + .------------. + 0x01| | + 0x02| ** * | + 0x04| * * * | + 0x08| * * * | + 0x10| * * * | + 0x20| * * * | + 0x40| * * * | + 0x80| * * | + 0x01| ** * | + 0x02| **** * | + 0x04| ** **** | + 0x08| ** | + 0x10| ****** | + '------------' */ const int SIV_Antenna_LBand_Height = 13; const int SIV_Antenna_LBand_Width = 12; const uint8_t SIV_Antenna_LBand [] = { - 0x00, 0x1E, 0x62, 0x84, 0x08, 0x14, 0x22, 0x50, 0x88, 0x40, 0x20, 0x00, 0x00, 0x10, 0x10, 0x1F, - 0x1F, 0x12, 0x12, 0x04, 0x04, 0x05, 0x06, 0x00, + 0x00, 0x1E, 0x62, 0x84, 0x08, 0x14, 0x22, 0x50, 0x88, 0x40, 0x20, 0x00, + 0x00, 0x10, 0x10, 0x1F, 0x1F, 0x12, 0x12, 0x04, 0x04, 0x05, 0x06, 0x00 }; /* Rover_Fusion [15, 9] - ********* - * * - * **** **** - * * * - * *** * - * ** * ** * - * ******* * - * * * * - ** ** + 1 + 123456789012345 + .---------------. + 0x01| ********* | + 0x02|* * | + 0x04|* **** ****| + 0x08|* * *| + 0x10|* *** *| + 0x20|* ** * ** *| + 0x40| * ******* * | + 0x80| * * * * | + 0x01| ** ** | + '---------------' */ const int Rover_Fusion_Height = 9; const int Rover_Fusion_Width = 15; const uint8_t Rover_Fusion [] = { - 0x3E, 0xC1, 0x21, 0x21, 0xC1, 0x7D, 0x55, 0x55, 0x45, 0x41, 0xC2, 0x24, 0x24, 0xC4, 0x3C, 0x00, - 0x00, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, + 0x3E, 0xC1, 0x21, 0x21, 0xC1, 0x7D, 0x55, 0x55, 0x45, 0x41, 0xC2, 0x24, 0x24, 0xC4, 0x3C, + 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00 }; /* Rover_Fusion_Empty [15, 9] - ********* - * * - * **** - * * - * * - * ** ** * - * ******* * - * * * * - ** ** + 1 + 123456789012345 + .---------------. + 0x01| ********* | + 0x02|* * | + 0x04|* ****| + 0x08|* *| + 0x10|* *| + 0x20|* ** ** *| + 0x40| * ******* * | + 0x80| * * * * | + 0x01| ** ** | + '---------------' */ const int Rover_Fusion_Empty_Height = 9; const int Rover_Fusion_Empty_Width = 15; const uint8_t Rover_Fusion_Empty [] = { - 0x3E, 0xC1, 0x21, 0x21, 0xC1, 0x41, 0x41, 0x41, 0x41, 0x41, 0xC2, 0x24, 0x24, 0xC4, 0x3C, 0x00, - 0x00, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, + 0x3E, 0xC1, 0x21, 0x21, 0xC1, 0x41, 0x41, 0x41, 0x41, 0x41, 0xC2, 0x24, 0x24, 0xC4, 0x3C, + 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00 }; /* BaseTemporary [14, 12] - **** *** - * ****** ** - * ** ** * - *** * * * - *** ** *** - * * **** ** - * ** ** * - ***** *** * - * *** ** - - - + 1 + 12345678901234 + .--------------. + 0x01| **** *** | + 0x02| * ****** ** | + 0x04| * ** ** * | + 0x08| *** * * * | + 0x10| *** ** *** | + 0x20| * * **** ** | + 0x40| * ** ** * | + 0x80| ***** *** * | + 0x01| * *** ** | + 0x02| * | + 0x04| * | + 0x08| * | + '--------------' */ const int BaseTemporary_Height = 12; const int BaseTemporary_Width = 14; const uint8_t BaseTemporary [] = { - 0x00, 0xFF, 0x99, 0x99, 0xE7, 0xCE, 0x32, 0x32, 0xE7, 0xE7, 0x99, 0x32, 0xFE, 0x00, 0x00, 0x1F, - 0x00, 0x00, 0x00, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, + 0x00, 0xFF, 0x99, 0x99, 0xE7, 0xCE, 0x32, 0x32, 0xE7, 0xE7, 0x99, 0x32, 0xFE, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00 }; /* BaseFixed [14, 12] - ***** ***** - * * * * * * - * * * * * * - * * **** * * - * * - * * - * * - * **** * - * * * * - * * * * - * * * * - ****** ****** + 1 + 12345678901234 + .--------------. + 0x01| ***** ***** | + 0x02| * * * * * * | + 0x04| * * * * * * | + 0x08| * * **** * * | + 0x10| * * | + 0x20| * * | + 0x40| * * | + 0x80| * **** * | + 0x01| * * * * | + 0x02|* * * *| + 0x04|* * * *| + 0x08|****** ******| + '--------------' */ const int BaseFixed_Height = 12; const int BaseFixed_Width = 14; const uint8_t BaseFixed [] = { - 0x00, 0xFF, 0x01, 0x0F, 0x01, 0x8F, 0x88, 0x88, 0x8F, 0x01, 0x0F, 0x01, 0xFF, 0x00, 0x0E, 0x09, - 0x08, 0x08, 0x08, 0x0F, 0x00, 0x00, 0x0F, 0x08, 0x08, 0x08, 0x09, 0x0E, + 0x00, 0xFF, 0x01, 0x0F, 0x01, 0x8F, 0x88, 0x88, 0x8F, 0x01, 0x0F, 0x01, 0xFF, 0x00, + 0x0E, 0x09, 0x08, 0x08, 0x08, 0x0F, 0x00, 0x00, 0x0F, 0x08, 0x08, 0x08, 0x09, 0x0E }; /* Battery_3 [19, 12] - ***************** - * * - * *** *** *** * - * *** *** *** *** - * *** *** *** * - * *** *** *** * - * *** *** *** * - * *** *** *** * - * *** *** *** *** - * *** *** *** * - * * - ***************** + 1 + 1234567890123456789 + .-------------------. + 0x01|***************** | + 0x02|* * | + 0x04|* *** *** *** * | + 0x08|* *** *** *** ***| + 0x10|* *** *** *** *| + 0x20|* *** *** *** *| + 0x40|* *** *** *** *| + 0x80|* *** *** *** *| + 0x01|* *** *** *** ***| + 0x02|* *** *** *** * | + 0x04|* * | + 0x08|***************** | + '-------------------' */ const int Battery_3_Height = 12; const int Battery_3_Width = 19; const uint8_t Battery_3 [] = { - 0xFF, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0xFD, 0xFD, 0xFD, 0x01, - 0x0F, 0x08, 0xF8, 0x0F, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x0B, - 0x0B, 0x0B, 0x08, 0x0F, 0x01, 0x01, + 0xFF, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x0F, 0x08, 0xF8, + 0x0F, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x0F, 0x01, 0x01 }; /* Battery_2 [19, 12] - ***************** - * * - * *** *** * - * *** *** *** - * *** *** * - * *** *** * - * *** *** * - * *** *** * - * *** *** *** - * *** *** * - * * - ***************** + 1 + 1234567890123456789 + .-------------------. + 0x01|***************** | + 0x02|* * | + 0x04|* *** *** * | + 0x08|* *** *** ***| + 0x10|* *** *** *| + 0x20|* *** *** *| + 0x40|* *** *** *| + 0x80|* *** *** *| + 0x01|* *** *** ***| + 0x02|* *** *** * | + 0x04|* * | + 0x08|***************** | + '-------------------' */ const int Battery_2_Height = 12; const int Battery_2_Width = 19; const uint8_t Battery_2 [] = { - 0xFF, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, - 0x0F, 0x08, 0xF8, 0x0F, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x08, - 0x08, 0x08, 0x08, 0x0F, 0x01, 0x01, + 0xFF, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x0F, 0x08, 0xF8, + 0x0F, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, 0x01, 0x01 }; /* Battery_1 [19, 12] - ***************** - * * - * *** * - * *** *** - * *** * - * *** * - * *** * - * *** * - * *** *** - * *** * - * * - ***************** + 1 + 1234567890123456789 + .-------------------. + 0x01|***************** | + 0x02|* * | + 0x04|* *** * | + 0x08|* *** ***| + 0x10|* *** *| + 0x20|* *** *| + 0x40|* *** *| + 0x80|* *** *| + 0x01|* *** ***| + 0x02|* *** * | + 0x04|* * | + 0x08|***************** | + '-------------------' */ const int Battery_1_Height = 12; const int Battery_1_Width = 19; const uint8_t Battery_1 [] = { - 0xFF, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, - 0x0F, 0x08, 0xF8, 0x0F, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, - 0x08, 0x08, 0x08, 0x0F, 0x01, 0x01, + 0xFF, 0x01, 0xFD, 0xFD, 0xFD, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x0F, 0x08, 0xF8, + 0x0F, 0x08, 0x0B, 0x0B, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, 0x01, 0x01 }; /* Battery_0 [19, 12] - ***************** - * * - * * - * *** - * * - * * - * * - * * - * *** - * * - * * - ***************** + 1 + 1234567890123456789 + .-------------------. + 0x01|***************** | + 0x02|* * | + 0x04|* * | + 0x08|* ***| + 0x10|* *| + 0x20|* *| + 0x40|* *| + 0x80|* *| + 0x01|* ***| + 0x02|* * | + 0x04|* * | + 0x08|***************** | + '-------------------' */ const int Battery_0_Height = 12; const int Battery_0_Width = 19; const uint8_t Battery_0 [] = { - 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, - 0x0F, 0x08, 0xF8, 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, - 0x08, 0x08, 0x08, 0x0F, 0x01, 0x01, + 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x0F, 0x08, 0xF8, + 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F, 0x01, 0x01 }; /* Logging_3 [9, 12] - ******* - * ** - * ** - * * - * ***** * - * * - * ***** * - * * - * ***** * - * * - * * - ********* + 123456789 + .---------. + 0x01|******* | + 0x02|* ** | + 0x04|* **| + 0x08|* *| + 0x10|* ***** *| + 0x20|* *| + 0x40|* ***** *| + 0x80|* *| + 0x01|* ***** *| + 0x02|* *| + 0x04|* *| + 0x08|*********| + '---------' */ const int Logging_3_Height = 12; const int Logging_3_Width = 9; const uint8_t Logging_3 [] = { - 0xFF, 0x01, 0x51, 0x51, 0x51, 0x51, 0x53, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x09, 0x09, 0x09, 0x09, - 0x08, 0x0F, + 0xFF, 0x01, 0x51, 0x51, 0x51, 0x51, 0x53, 0x06, 0xFC, + 0x0F, 0x08, 0x09, 0x09, 0x09, 0x09, 0x09, 0x08, 0x0F }; /* Logging_2 [9, 12] - ******* - * ** - * ** - * * - * * - * * - * ***** * - * * - * ***** * - * * - * * - ********* + 123456789 + .---------. + 0x01|******* | + 0x02|* ** | + 0x04|* **| + 0x08|* *| + 0x10|* *| + 0x20|* *| + 0x40|* ***** *| + 0x80|* *| + 0x01|* ***** *| + 0x02|* *| + 0x04|* *| + 0x08|*********| + '---------' */ const int Logging_2_Height = 12; const int Logging_2_Width = 9; const uint8_t Logging_2 [] = { - 0xFF, 0x01, 0x41, 0x41, 0x41, 0x41, 0x43, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x09, 0x09, 0x09, 0x09, - 0x08, 0x0F, + 0xFF, 0x01, 0x41, 0x41, 0x41, 0x41, 0x43, 0x06, 0xFC, + 0x0F, 0x08, 0x09, 0x09, 0x09, 0x09, 0x09, 0x08, 0x0F }; /* Logging_1 [9, 12] - ******* - * ** - * ** - * * - * * - * * - * * - * * - * ***** * - * * - * * - ********* + 123456789 + .---------. + 0x01|******* | + 0x02|* ** | + 0x04|* **| + 0x08|* *| + 0x10|* *| + 0x20|* *| + 0x40|* *| + 0x80|* *| + 0x01|* ***** *| + 0x02|* *| + 0x04|* *| + 0x08|*********| + '---------' */ const int Logging_1_Height = 12; const int Logging_1_Width = 9; const uint8_t Logging_1 [] = { - 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x09, 0x09, 0x09, 0x09, - 0x08, 0x0F, + 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, + 0x0F, 0x08, 0x09, 0x09, 0x09, 0x09, 0x09, 0x08, 0x0F }; /* Logging_0 [9, 12] - ******* - * ** - * ** - * * - * * - * * - * * - * * - * * - * * - * * - ********* + 123456789 + .---------. + 0x01|******* | + 0x02|* ** | + 0x04|* **| + 0x08|* *| + 0x10|* *| + 0x20|* *| + 0x40|* *| + 0x80|* *| + 0x01|* *| + 0x02|* *| + 0x04|* *| + 0x08|*********| + '---------' */ const int Logging_0_Height = 12; const int Logging_0_Width = 9; const uint8_t Logging_0 [] = { - 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, - 0x08, 0x0F, + 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, + 0x0F, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F }; +/* + Logging_PPP_3 [9, 12] + + 123456789 + .---------. + 0x01|******* | + 0x02|* ** | + 0x04|* **| + 0x08|* **** *| + 0x10|* * * *| + 0x20|* * * *| + 0x40|* **** *| + 0x80|* * *| + 0x01|* * *| + 0x02|* * *| + 0x04|* *| + 0x08|*********| + '---------' +*/ + const uint8_t Logging_PPP_3 [] = { - 0xFF, 0x01, 0xF9, 0x49, 0x49, 0x49, 0x33, 0x06, 0xFC, 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, - 0x08, 0x0F, + 0xFF, 0x01, 0xF9, 0x49, 0x49, 0x49, 0x33, 0x06, 0xFC, + 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F }; + +/* + Logging_PPP_2 [9, 12] + + 123456789 + .---------. + 0x01|******* | + 0x02|* ** | + 0x04|* **| + 0x08|* * *| + 0x10|* * *| + 0x20|* * *| + 0x40|* **** *| + 0x80|* * *| + 0x01|* * *| + 0x02|* * *| + 0x04|* *| + 0x08|*********| + '---------' +*/ + const uint8_t Logging_PPP_2 [] = { - 0xFF, 0x01, 0xF9, 0x41, 0x41, 0x41, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, - 0x08, 0x0F, + 0xFF, 0x01, 0xF9, 0x41, 0x41, 0x41, 0x03, 0x06, 0xFC, + 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F }; + +/* + Logging_PPP_1 [9, 12] + + 123456789 + .---------. + 0x01|******* | + 0x02|* ** | + 0x04|* **| + 0x08|* *| + 0x10|* *| + 0x20|* *| + 0x40|* * *| + 0x80|* * *| + 0x01|* * *| + 0x02|* * *| + 0x04|* *| + 0x08|*********| + '---------' +*/ + const uint8_t Logging_PPP_1 [] = { - 0xFF, 0x01, 0xC1, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, - 0x08, 0x0F, + 0xFF, 0x01, 0xC1, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, + 0x0F, 0x08, 0x0B, 0x08, 0x08, 0x08, 0x08, 0x08, 0x0F }; +/* + Logging_Custom_3 [9, 12] + + 123456789 + .---------. + 0x01|******* | + 0x02|* ** | + 0x04|* **| + 0x08|* *** *| + 0x10|* * * *| + 0x20|* * *| + 0x40|* * *| + 0x80|* * *| + 0x01|* * * *| + 0x02|* *** *| + 0x04|* *| + 0x08|*********| + '---------' +*/ + const uint8_t Logging_Custom_3 [] = { - 0xFF, 0x01, 0xF1, 0x09, 0x09, 0x09, 0x13, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, - 0x08, 0x0F, + 0xFF, 0x01, 0xF1, 0x09, 0x09, 0x09, 0x13, 0x06, 0xFC, + 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, 0x08, 0x0F }; + +/* + Logging_Custom_2 [9, 12] + + 123456789 + .---------. + 0x01|******* | + 0x02|* ** | + 0x04|* **| + 0x08|* *| + 0x10|* * *| + 0x20|* * *| + 0x40|* * *| + 0x80|* * *| + 0x01|* * * *| + 0x02|* *** *| + 0x04|* *| + 0x08|*********| + '---------' +*/ + const uint8_t Logging_Custom_2 [] = { - 0xFF, 0x01, 0xF1, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, - 0x08, 0x0F, -}; -const uint8_t Logging_Custom_1 [] = { - 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, - 0x08, 0x0F, + 0xFF, 0x01, 0xF1, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, + 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, 0x08, 0x0F }; +/* + Logging_Custom_1 [9, 12] + + 123456789 + .---------. + 0x01|******* | + 0x02|* ** | + 0x04|* **| + 0x08|* *| + 0x10|* *| + 0x20|* *| + 0x40|* *| + 0x80|* *| + 0x01|* * * *| + 0x02|* *** *| + 0x04|* *| + 0x08|*********| + '---------' +*/ - -const int DynamicModel_Height = 12; -const int DynamicModel_Width = 15; +const uint8_t Logging_Custom_1 [] = { + 0xFF, 0x01, 0x01, 0x01, 0x01, 0x01, 0x03, 0x06, 0xFC, + 0x0F, 0x08, 0x09, 0x0A, 0x0A, 0x0A, 0x09, 0x08, 0x0F +}; /* DynamicModel_1_Portable [15, 12] - ** - ** - ****** - * * - * * **** * * - * * **** * * - * * * * - * * * * - * * * * - * * * * - * * - ****** + 1 + 123456789012345 + .---------------. + 0x01| ** | + 0x02| ** | + 0x04| ****** | + 0x08| * * | + 0x10| * * **** * * | + 0x20| * * **** * * | + 0x40| * * * * | + 0x80| * * * * | + 0x01| * * * * | + 0x02| * * * * | + 0x04| * * | + 0x08| ****** | + '---------------' */ +const int DynamicModel_Height = 12; +const int DynamicModel_Width = 15; const uint8_t DynamicModel_1_Portable [] = { - 0x00, 0xF0, 0x00, 0xF8, 0x04, 0x34, 0x34, 0x37, 0x37, 0x04, 0xF8, 0x00, 0xF0, 0x00, 0x00, 0x00, - 0x03, 0x00, 0x07, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x07, 0x00, 0x03, 0x00, 0x00, + 0x00, 0xF0, 0x00, 0xF8, 0x04, 0x34, 0x34, 0x37, 0x37, 0x04, 0xF8, 0x00, 0xF0, 0x00, 0x00, + 0x00, 0x03, 0x00, 0x07, 0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x07, 0x00, 0x03, 0x00, 0x00 }; /* DynamicModel_2_Stationary [15, 12] - - ******* - ***** - *** - - *** - ***** - ** * ** - ** * ** - ** * ** - ** * ** - + 1 + 123456789012345 + .---------------. + 0x01| | + 0x02| ******* | + 0x04| ***** | + 0x08| *** | + 0x10| * | + 0x20| *** | + 0x40| ***** | + 0x80| ** * ** | + 0x01| ** * ** | + 0x02| ** * ** | + 0x04| ** * ** | + 0x08| | + '---------------' */ const uint8_t DynamicModel_2_Stationary [] = { - 0x00, 0x00, 0x00, 0x00, 0x82, 0xC6, 0x6E, 0xFE, 0x6E, 0xC6, 0x82, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x04, 0x06, 0x03, 0x01, 0x00, 0x00, 0x07, 0x00, 0x00, 0x01, 0x03, 0x06, 0x04, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x82, 0xC6, 0x6E, 0xFE, 0x6E, 0xC6, 0x82, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x04, 0x06, 0x03, 0x01, 0x00, 0x00, 0x07, 0x00, 0x00, 0x01, 0x03, 0x06, 0x04, 0x00 }; /* DynamicModel_3_Pedestrian [15, 12] - *** - * * - * * - - ***** - ** * ** - * * - *** - ** ** - ** * - ** ** - + 1 + 123456789012345 + .---------------. + 0x01| *** | + 0x02| * * | + 0x04| * * | + 0x08| * | + 0x10| ***** | + 0x20| ** * ** | + 0x40| * * | + 0x80| *** | + 0x01| ** ** | + 0x02| ** * | + 0x04| ** ** | + 0x08| | + '---------------' */ const uint8_t DynamicModel_3_Pedestrian [] = { - 0x00, 0x00, 0x00, 0x00, 0x20, 0x32, 0x95, 0xF9, 0x95, 0x32, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x04, 0x06, 0x03, 0x01, 0x00, 0x01, 0x07, 0x04, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x20, 0x32, 0x95, 0xF9, 0x95, 0x32, 0x60, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x04, 0x06, 0x03, 0x01, 0x00, 0x01, 0x07, 0x04, 0x00, 0x00, 0x00, 0x00 }; /* DynamicModel_4_Automotive [15, 12] - - - ********* - * * - * **** - * * - * ** ** * - * ******* * - * * * * - ** ** - - + 1 + 123456789012345 + .---------------. + 0x01| | + 0x02| | + 0x04| ********* | + 0x08|* * | + 0x10|* ****| + 0x20|* *| + 0x40|* ** ** *| + 0x80| * ******* * | + 0x01| * * * * | + 0x02| ** ** | + 0x04| | + 0x08| | + '---------------' */ const uint8_t DynamicModel_4_Automotive [] = { - 0x78, 0x84, 0x44, 0x44, 0x84, 0x84, 0x84, 0x84, 0x84, 0x84, 0x88, 0x50, 0x50, 0x90, 0x70, 0x00, - 0x01, 0x02, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x02, 0x01, 0x00, + 0x78, 0x84, 0x44, 0x44, 0x84, 0x84, 0x84, 0x84, 0x84, 0x84, 0x88, 0x50, 0x50, 0x90, 0x70, + 0x00, 0x01, 0x02, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x02, 0x01, 0x00 }; /* DynamicModel_5_Sea [15, 12] - - - *** - * * - * * - ************* - ** ** - * ** * - * * - ** ** - ********* - + 1 + 123456789012345 + .---------------. + 0x01| | + 0x02| * | + 0x04| *** | + 0x08| * * | + 0x10| * * | + 0x20| ************* | + 0x40| ** ** | + 0x80| * ** * | + 0x01| * * | + 0x02| ** ** | + 0x04| ********* | + 0x08| | + '---------------' */ const uint8_t DynamicModel_5_Sea [] = { - 0x00, 0x60, 0xE0, 0x3C, 0x26, 0x3C, 0x20, 0x20, 0x20, 0xA0, 0xA0, 0x20, 0xE0, 0x60, 0x00, 0x00, - 0x00, 0x03, 0x06, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x06, 0x03, 0x00, 0x00, + 0x00, 0x60, 0xE0, 0x3C, 0x26, 0x3C, 0x20, 0x20, 0x20, 0xA0, 0xA0, 0x20, 0xE0, 0x60, 0x00, + 0x00, 0x00, 0x03, 0x06, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x06, 0x03, 0x00, 0x00 }; /* DynamicModel_6_Airborne1g [15, 12] - - - ** - *********** - * * ** - * * * ** - * * * - * * *** ** - ****** ***** - * * - * * - + 1 + 123456789012345 + .---------------. + 0x01| | + 0x02| * | + 0x04| ** | + 0x08| *********** | + 0x10| * * ** | + 0x20| * * * ** | + 0x40| * * * | + 0x80| * * *** ** | + 0x01| ****** ***** | + 0x02| * * | + 0x04| * * | + 0x08| * | + '---------------' */ const uint8_t DynamicModel_6_Airborne1g [] = { - 0x00, 0xFE, 0x0C, 0xF8, 0x08, 0x08, 0x88, 0x88, 0x88, 0x28, 0x08, 0x18, 0xB0, 0xE0, 0x00, 0x00, - 0x01, 0x01, 0x01, 0x01, 0x01, 0x07, 0x08, 0x07, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, + 0x00, 0xFE, 0x0C, 0xF8, 0x08, 0x08, 0x88, 0x88, 0x88, 0x28, 0x08, 0x18, 0xB0, 0xE0, 0x00, + 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x07, 0x08, 0x07, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00 }; /* DynamicModel_7_Airborne2g [15, 12] - - - ** - *********** - * * ** - * * * * ** - * * * - * * *** ** - ****** ***** - * * - * * - + 1 + 123456789012345 + .---------------. + 0x01| | + 0x02| * | + 0x04| ** | + 0x08| *********** | + 0x10| * * ** | + 0x20| * * * * ** | + 0x40| * * * | + 0x80| * * *** ** | + 0x01| ****** ***** | + 0x02| * * | + 0x04| * * | + 0x08| * | + '---------------' */ const uint8_t DynamicModel_7_Airborne2g [] = { - 0x00, 0xFE, 0x0C, 0xF8, 0x08, 0x08, 0x88, 0xA8, 0x88, 0x28, 0x08, 0x18, 0xB0, 0xE0, 0x00, 0x00, - 0x01, 0x01, 0x01, 0x01, 0x01, 0x07, 0x08, 0x07, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, + 0x00, 0xFE, 0x0C, 0xF8, 0x08, 0x08, 0x88, 0xA8, 0x88, 0x28, 0x08, 0x18, 0xB0, 0xE0, 0x00, + 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x07, 0x08, 0x07, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00 }; /* DynamicModel_8_Airborne4g [15, 12] - - - ** - *********** - * * ** - * * * * * ** - * * * - * * *** ** - ****** ***** - * * - * * - + 1 + 123456789012345 + .---------------. + 0x01| | + 0x02| * | + 0x04| ** | + 0x08| *********** | + 0x10| * * ** | + 0x20| * * * * * ** | + 0x40| * * * | + 0x80| * * *** ** | + 0x01| ****** ***** | + 0x02| * * | + 0x04| * * | + 0x08| * | + '---------------' */ const uint8_t DynamicModel_8_Airborne4g [] = { - 0x00, 0xFE, 0x0C, 0xF8, 0x08, 0x28, 0x88, 0xA8, 0x88, 0x28, 0x08, 0x18, 0xB0, 0xE0, 0x00, 0x00, - 0x01, 0x01, 0x01, 0x01, 0x01, 0x07, 0x08, 0x07, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, + 0x00, 0xFE, 0x0C, 0xF8, 0x08, 0x28, 0x88, 0xA8, 0x88, 0x28, 0x08, 0x18, 0xB0, 0xE0, 0x00, + 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x07, 0x08, 0x07, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00 }; /* DynamicModel_9_Wrist [15, 12] - *** - *** - *** - ***** - * * - * * - * *** * - * * - * * - ***** - *** - *** + 1 + 123456789012345 + .---------------. + 0x01| *** | + 0x02| *** | + 0x04| *** | + 0x08| ***** | + 0x10| * * | + 0x20| * * | + 0x40| * *** * | + 0x80| * * | + 0x01| * * | + 0x02| ***** | + 0x04| *** | + 0x08| *** | + '---------------' */ const uint8_t DynamicModel_9_Wrist [] = { - 0x00, 0x00, 0x00, 0xE0, 0x10, 0x08, 0x4F, 0x4F, 0x4F, 0x08, 0x10, 0xE0, 0x00, 0x00, 0x00, 0x00, - 0x00, 0x00, 0x00, 0x01, 0x02, 0x1E, 0x1E, 0x1E, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xE0, 0x10, 0x08, 0x4F, 0x4F, 0x4F, 0x08, 0x10, 0xE0, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x1E, 0x1E, 0x1E, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00 }; /* DynamicModel_10_Bike [15, 12] - - - ** - *** - *** * - * * - ** *** ** - * ******* * - * * * * - ** ** - - + 1 + 123456789012345 + .---------------. + 0x01| | + 0x02| | + 0x04| ** | + 0x08| *** | + 0x10| *** * | + 0x20| * * | + 0x40| ** *** ** | + 0x80| * ******* * | + 0x01| * * * * | + 0x02| ** ** | + 0x04| | + 0x08| | + '---------------' */ const uint8_t DynamicModel_10_Bike [] = { - 0x00, 0x80, 0x40, 0x50, 0x90, 0xB0, 0xC0, 0xC0, 0xC0, 0xA0, 0x98, 0x4C, 0x4C, 0x80, 0x00, 0x00, - 0x01, 0x02, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x02, 0x01, 0x00, + 0x00, 0x80, 0x40, 0x50, 0x90, 0xB0, 0xC0, 0xC0, 0xC0, 0xA0, 0x98, 0x4C, 0x4C, 0x80, 0x00, + 0x00, 0x01, 0x02, 0x02, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x02, 0x01, 0x00 }; /* DownloadArrow [8, 9] - ** - ** - ** - ** - ** - ** ** ** - ****** - **** - ** + 12345678 + .--------. + 0x01| ** | + 0x02| ** | + 0x04| ** | + 0x08| ** | + 0x10| ** | + 0x20|** ** **| + 0x40| ****** | + 0x80| **** | + 0x01| ** | + '--------' */ const int DownloadArrow_Height = 9; const int DownloadArrow_Width = 8; const uint8_t DownloadArrow [] = { - 0x20, 0x60, 0xC0, 0xFF, 0xFF, 0xC0, 0x60, 0x20, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00 + 0x20, 0x60, 0xC0, 0xFF, 0xFF, 0xC0, 0x60, 0x20, + 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00 }; /* UploadArrow [8, 9] - ** - **** - ****** - ** ** ** - ** - ** - ** - ** - ** + 12345678 + .--------. + 0x01| ** | + 0x02| **** | + 0x04| ****** | + 0x08|** ** **| + 0x10| ** | + 0x20| ** | + 0x40| ** | + 0x80| ** | + 0x01| ** | + '--------' */ const int UploadArrow_Height = 9; const int UploadArrow_Width = 8; const uint8_t UploadArrow [] = { - 0x08, 0x0C, 0x06, 0xFF, 0xFF, 0x06, 0x0C, 0x08, 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00 + 0x08, 0x0C, 0x06, 0xFF, 0xFF, 0x06, 0x0C, 0x08, + 0x00, 0x00, 0x00, 0x01, 0x01, 0x00, 0x00, 0x00 }; /* logoSparkFun [64, 48] - 1 2 3 4 5 6 + 1 2 3 4 5 6 1234567890123456789012345678901234567890123456789012345678901234 .----------------------------------------------------------------. 0x01| ********** | @@ -798,58 +1088,138 @@ const uint8_t UploadArrow [] = { '----------------------------------------------------------------' */ -//SparkFun Electronics LOGO const int logoSparkFun_Height = 48; const int logoSparkFun_Width = 64; const uint8_t logoSparkFun [] = { - // ROW0, BYTE0 to BYTE63 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xE0, 0xF8, 0xFC, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x0F, 0x07, 0x07, 0x06, 0x06, 0x00, 0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - - // ROW1, BYTE64 to BYTE127 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x81, 0x07, 0x0F, 0x3F, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFE, 0xFC, 0xFC, 0xFC, 0xFE, 0xFF, 0xFF, 0xFF, 0xFC, 0xF8, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - - // ROW2, BYTE128 to BYTE191 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFC, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF1, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xF0, 0xFD, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - - // ROW3, BYTE192 to BYTE255 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x3F, 0x1F, 0x07, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - - // ROW4, BYTE256 to BYTE319 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x3F, 0x1F, 0x1F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x07, 0x07, 0x07, 0x03, 0x03, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, - - // ROW5, BYTE320 to BYTE383 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0x7F, 0x3F, 0x1F, 0x0F, 0x07, 0x03, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; +/* + ESPNOW_Symbol_3 [8, 13] + + 12345678 + .--------. + 0x01| * | + 0x02| * | + 0x04| * * | + 0x08| * *| + 0x10| * * *| + 0x20|* * * *| + 0x40|** * * *| + 0x80|* * * *| + 0x01| * * *| + 0x02| * *| + 0x04| * * | + 0x08| * | + 0x10| * | + '--------' +*/ + const int ESPNOW_Symbol_Height = 13; const int ESPNOW_Symbol_Width = 8; const uint8_t ESPNOW_Symbol_3 [] = { - 0xE0, 0x40, 0x10, 0xE4, 0x09, 0xF2, 0x04, 0xF8, 0x00, 0x00, 0x01, 0x04, 0x12, 0x09, 0x04, 0x03 + 0xE0, 0x40, 0x10, 0xE4, 0x09, 0xF2, 0x04, 0xF8, + 0x00, 0x00, 0x01, 0x04, 0x12, 0x09, 0x04, 0x03 }; + +/* + ESPNOW_Symbol_2 [8, 13] + + 12345678 + .--------. + 0x01| | + 0x02| | + 0x04| * | + 0x08| * | + 0x10| * * | + 0x20|* * * | + 0x40|** * * | + 0x80|* * * | + 0x01| * * | + 0x02| * | + 0x04| * | + 0x08| | + 0x10| | + '--------' +*/ + const uint8_t ESPNOW_Symbol_2 [] = { - 0xE0, 0x40, 0x10, 0xE4, 0x08, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x02, 0x01, 0x00, 0x00 + 0xE0, 0x40, 0x10, 0xE4, 0x08, 0xF0, 0x00, 0x00, + 0x00, 0x00, 0x01, 0x04, 0x02, 0x01, 0x00, 0x00 }; + +/* + ESPNOW_Symbol_1 [8, 13] + + 12345678 + .--------. + 0x01| | + 0x02| | + 0x04| | + 0x08| | + 0x10| * | + 0x20|* * | + 0x40|** * | + 0x80|* * | + 0x01| * | + 0x02| | + 0x04| | + 0x08| | + 0x10| | + '--------' +*/ + const uint8_t ESPNOW_Symbol_1 [] = { - 0xE0, 0x40, 0x10, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00 + 0xE0, 0x40, 0x10, 0xE0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00 }; + +/* + ESPNOW_Symbol_0 [8, 13] + + 12345678 + .--------. + 0x01| | + 0x02| | + 0x04| | + 0x08| | + 0x10| | + 0x20|* | + 0x40|** | + 0x80|* | + 0x01| | + 0x02| | + 0x04| | + 0x08| | + 0x10| | + '--------' +*/ + const uint8_t ESPNOW_Symbol_0 [] = { - 0xE0, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 + 0xE0, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 }; + From 2f7ea43e77762f5b711df1c7aade83830f5ddf53 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 12 Aug 2022 21:07:41 -0600 Subject: [PATCH 060/134] Add pairing states --- Firmware/RTK_Surveyor/Base.ino | 2 - Firmware/RTK_Surveyor/Display.ino | 17 ++++++--- Firmware/RTK_Surveyor/ESPNOW.ino | 51 +++++++++++++++++++------- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 8 ++-- Firmware/RTK_Surveyor/States.ino | 38 ++++++++++++++++--- Firmware/RTK_Surveyor/Tasks.ino | 19 ++++------ Firmware/RTK_Surveyor/WiFi.ino | 18 ++++----- Firmware/RTK_Surveyor/menuMain.ino | 28 ++++++++++---- Firmware/RTK_Surveyor/settings.h | 5 ++- 9 files changed, 127 insertions(+), 59 deletions(-) diff --git a/Firmware/RTK_Surveyor/Base.ino b/Firmware/RTK_Surveyor/Base.ino index c39615874..41e68589c 100644 --- a/Firmware/RTK_Surveyor/Base.ino +++ b/Firmware/RTK_Surveyor/Base.ino @@ -229,7 +229,5 @@ void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming) { ntripServerProcessRTCM(incoming); -#ifdef COMPILE_ESPNOW espnowProcessRTCM(incoming); -#endif } diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 12245a901..d9669ea37 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -331,8 +331,11 @@ void updateDisplay() //Do nothing. Quick, fall through state. break; - case (STATE_ESPNOW_PAIR): - paintEspNowPair(); + case (STATE_ESPNOW_PAIRING_NOT_STARTED): + paintEspNowPairing(); + break; + case (STATE_ESPNOW_PAIRING): + paintEspNowPairing(); break; case (STATE_SHUTDOWN): @@ -2151,7 +2154,7 @@ void paintDisplaySetup() printTextCenter("Bubble", 12 * 2, QW_FONT_8X16, 1, false); printTextCenter("Config", 12 * 3, QW_FONT_8X16, 1, true); } - else if (setupState == STATE_ESPNOW_PAIR) + else if (setupState == STATE_ESPNOW_PAIRING_NOT_STARTED) { printTextCenter("Base", 12 * 0, QW_FONT_8X16, 1, false); printTextCenter("Bubble", 12 * 1, QW_FONT_8X16, 1, false); @@ -2191,7 +2194,7 @@ void paintDisplaySetup() printTextCenter("Bubble", 12 * 2, QW_FONT_8X16, 1, false); printTextCenter("Config", 12 * 3, QW_FONT_8X16, 1, true); } - else if (setupState == STATE_ESPNOW_PAIR) + else if (setupState == STATE_ESPNOW_PAIRING_NOT_STARTED) { printTextCenter("Rover", 12 * 0, QW_FONT_8X16, 1, false); printTextCenter("Bubble", 12 * 1, QW_FONT_8X16, 1, false); @@ -2521,7 +2524,11 @@ void paintKeyProvisionFail(uint16_t displayTime) } //Show screen while ESP-Now is pairing -void paintEspNowPair() +void paintEspNowPairing() { displayMessage("ESP-Now Pairing", 0); } +void paintEspNowPaired() +{ + displayMessage("ESP-Now Paired", 2000); +} diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 64b825cec..3029229fc 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -12,7 +12,6 @@ We don't care if the ESP NOW packet is corrupt or not. RTCM has its own CRC. RTK needs valid RTCM once every few seconds so a single dropped frame is not critical. */ -#ifdef COMPILE_ESPNOW //Create a struct for ESP NOW pairing typedef struct PairMessage { @@ -23,6 +22,7 @@ typedef struct PairMessage { } PairMessage; // Callback when data is sent +#ifdef COMPILE_ESPNOW void espnowOnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) { // Serial.print("Last Packet Send Status: "); @@ -31,10 +31,12 @@ void espnowOnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) // else // Serial.println("Delivery Fail"); } +#endif // Callback when data is received void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int len) { +#ifdef COMPILE_ESPNOW if (espnowState == ESPNOW_PAIRING) { if (len == sizeof(PairMessage)) //First error check @@ -66,10 +68,12 @@ void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int l espnowIncomingRTCM = true; lastEspnowRssiUpdate = millis(); } +#endif } // Callback for all RX Packets // Get RSSI of all incoming management packets: https://esp32.com/viewtopic.php?t=13889 +#ifdef COMPILE_ESPNOW void promiscuous_rx_cb(void *buf, wifi_promiscuous_pkt_type_t type) { // All espnow traffic uses action frames which are a subtype of the mgmnt frames so filter out everything else. @@ -79,11 +83,13 @@ void promiscuous_rx_cb(void *buf, wifi_promiscuous_pkt_type_t type) const wifi_promiscuous_pkt_t *ppkt = (wifi_promiscuous_pkt_t *)buf; packetRSSI = ppkt->rx_ctrl.rssi; } +#endif //If WiFi is already enabled, simply add the LR protocol //If the radio is off entirely, start the radio, turn on only the LR protocol void espnowStart() { +#ifdef COMPILE_ESPNOW if (wifiState == WIFI_OFF && espnowState == ESPNOW_OFF) { //Radio is off, turn it on @@ -97,21 +103,19 @@ void espnowStart() //Enable WiFi + ESP-Now // Enable long range, PHY rate of ESP32 will be 512Kbps or 256Kbps esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); - Serial.println("Wi-Fi on, ESP-Now added to protocols"); + Serial.println("WiFi on, ESP-Now added to protocols"); } //If ESP-Now is active, WiFi is active, do nothing else { - Serial.println("Wi-Fi already on, ESP-Now already on"); + Serial.println("WiFi already on, ESP-Now already on"); } // Init ESP-NOW if (esp_now_init() != ESP_OK) { - Serial.println("Error initializing ESP-NOW"); + Serial.println("Error starting ESP-Now"); return; } - else - Serial.println("ESP-NOW Initialized"); // Use promiscuous callback to capture RSSI of packet esp_wifi_set_promiscuous(true); @@ -143,12 +147,16 @@ void espnowStart() } } } + + Serial.println("ESP-Now Started"); +#endif } //If WiFi is already enabled, simply remove the LR protocol //If WiFi is off, stop the radio entirely void espnowStop() { +#ifdef COMPILE_ESPNOW if (espnowState == ESPNOW_OFF) return; if (wifiState == WIFI_OFF) @@ -178,10 +186,8 @@ void espnowStop() Serial.println("Error deinitializing ESP-NOW"); return; } - +#endif espnowSetState(ESPNOW_OFF); - - Serial.println("ESP NOW Off"); } //Start ESP-Now if needed, put ESP-Now into broadcast state @@ -199,9 +205,11 @@ void espnowBeginPairing() //Regularly call during pairing to see if we've received a Pairing message bool espnowIsPaired() { +#ifdef COMPILE_ESPNOW if (espnowState == ESPNOW_MAC_RECEIVED) { //Remove broadcast peer + uint8_t broadcastMac[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; espnowRemovePeer(broadcastMac); if (esp_now_is_peer_exist(receivedMAC) == true) @@ -221,15 +229,16 @@ bool espnowIsPaired() espnowSendPairMessage(receivedMAC); espnowSetState(ESPNOW_PAIRED); - Serial.println("Pairing compete"); - return(true); + return (true); } - return(false); +#endif + return (false); } //Create special pair packet to a given MAC esp_err_t espnowSendPairMessage(uint8_t *sendToMac) { +#ifdef COMPILE_ESPNOW // Assemble message to send PairMessage pairMessage; @@ -245,6 +254,9 @@ esp_err_t espnowSendPairMessage(uint8_t *sendToMac) pairMessage.crc += unitMACAddress[x]; return (esp_now_send(sendToMac, (uint8_t *) &pairMessage, sizeof(pairMessage))); //Send packet to given MAC +#else + return (ESP_OK); +#endif } //Add a given MAC address to the peer list @@ -255,6 +267,7 @@ esp_err_t espnowAddPeer(uint8_t *peerMac) esp_err_t espnowAddPeer(uint8_t *peerMac, bool encrypt) { +#ifdef COMPILE_ESPNOW esp_now_peer_info_t peerInfo; memcpy(peerInfo.peer_addr, peerMac, 6); @@ -268,15 +281,23 @@ esp_err_t espnowAddPeer(uint8_t *peerMac, bool encrypt) if (result != ESP_OK) log_d("Failed to add peer"); return (result); +#else + return (ESP_OK); +#endif } //Remove a given MAC address from the peer list esp_err_t espnowRemovePeer(uint8_t *peerMac) { +#ifdef COMPILE_ESPNOW esp_err_t result = esp_now_del_peer(peerMac); if (result != ESP_OK) log_d("Failed to remove peer"); return (result); +#else + return (ESP_OK); +#endif + } //Update the state of the ESP Now state machine @@ -285,6 +306,8 @@ void espnowSetState(ESPNOWState newState) if (espnowState == newState) Serial.print("*"); espnowState = newState; + + Serial.print("espnowState: "); switch (newState) { case ESPNOW_OFF: @@ -310,6 +333,7 @@ void espnowSetState(ESPNOWState newState) void espnowProcessRTCM(byte incoming) { +#ifdef COMPILE_ESPNOW if (espnowState == ESPNOW_PAIRED) { //Move this byte into ESP NOW to send buffer @@ -326,6 +350,5 @@ void espnowProcessRTCM(byte incoming) espnowOutgoingRTCM = true; } } +#endif } - -#endif //ifdef COMPILE_ESPNOW diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 37f205d1b..ba88d8b7f 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -26,10 +26,10 @@ const int FIRMWARE_VERSION_MAJOR = 2; const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_WIFI //Comment out to remove WiFi functionality -#define COMPILE_BT //Comment out to remove Bluetooth functionality -#define COMPILE_AP //Comment out to remove Access Point functionality -#define COMPILE_L_BAND //Comment out to remove L-Band functionality -#define COMPILE_ESPNOW //Comment out to remove ESP-Now functionality +//#define COMPILE_AP //Requires WiFi. Comment out to remove Access Point functionality +//#define COMPILE_ESPNOW //Requires WiFi. Comment out to remove ESP-Now functionality. +//#define COMPILE_BT //Comment out to remove Bluetooth functionality +//#define COMPILE_L_BAND //Comment out to remove L-Band functionality #define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) //Define the RTK board identifier: diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 3a55051cf..d8043d4fe 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -240,7 +240,7 @@ void updateSystemState() bluetoothStop(); bluetoothStart(); //Restart Bluetooth with 'Base' identifier - + startUART2Tasks(); //Start monitoring the UART1 from ZED for NMEA and UBX data (enables logging) if (configureUbloxModuleBase() == true) @@ -900,12 +900,35 @@ void updateSystemState() break; #endif //COMPILE_L_BAND - case (STATE_ESPNOW_PAIR): + case (STATE_ESPNOW_PAIRING_NOT_STARTED): { +#ifdef COMPILE_ESPNOW + paintEspNowPairing(); -espnowIsPaired() + //Start ESP-Now if needed, put ESP-Now into broadcast state + espnowBeginPairing(); - //Display 'ESP-Now Pairing' while we wait + changeState(STATE_ESPNOW_PAIRING); +#else + changeState(STATE_ROVER_NOT_STARTED); +#endif + } + break; + + case (STATE_ESPNOW_PAIRING): + { +#ifdef COMPILE_ESPNOW + if (espnowIsPaired() == true) + { + paintEspNowPaired(); + changeState(STATE_ROVER_NOT_STARTED); + } + else + { + uint8_t broadcastMac[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; + espnowSendPairMessage(broadcastMac); //Send unit's MAC address over broadcast, no ack, no encryption + } +#endif } break; @@ -1051,8 +1074,11 @@ void changeState(SystemState newState) break; #endif //COMPILE_L_BAND - case (STATE_ESPNOW_PAIR): - Serial.print("State: ESP-Now Pair"); + case (STATE_ESPNOW_PAIRING_NOT_STARTED): + Serial.print("State: ESP-Now Pairing Not Started"); + break; + case (STATE_ESPNOW_PAIRING): + Serial.print("State: ESP-Now Pairing"); break; case (STATE_SHUTDOWN): diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 44e5122f8..6e44c7fac 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -412,7 +412,8 @@ void ButtonCheckTask(void *e) case STATE_BUBBLE_LEVEL: case STATE_WIFI_CONFIG_NOT_STARTED: case STATE_WIFI_CONFIG: - case STATE_ESPNOW_PAIR: + case STATE_ESPNOW_PAIRING_NOT_STARTED: + case STATE_ESPNOW_PAIRING: lastSystemState = systemState; //Remember this state to return after we mark an event requestChangeState(STATE_DISPLAY_SETUP); setupState = STATE_MARK_EVENT; @@ -464,9 +465,9 @@ void ButtonCheckTask(void *e) setupState = STATE_WIFI_CONFIG_NOT_STARTED; break; case STATE_WIFI_CONFIG_NOT_STARTED: - setupState = STATE_ESPNOW_PAIR; + setupState = STATE_ESPNOW_PAIRING_NOT_STARTED; break; - case STATE_ESPNOW_PAIR: + case STATE_ESPNOW_PAIRING_NOT_STARTED: //If only one active profile do not show any profiles index = getProfileNumberFromUnit(0); displayProfile = getProfileNumberFromUnit(1); @@ -531,7 +532,8 @@ void ButtonCheckTask(void *e) case STATE_BUBBLE_LEVEL: case STATE_WIFI_CONFIG_NOT_STARTED: case STATE_WIFI_CONFIG: - case STATE_ESPNOW_PAIR: + case STATE_ESPNOW_PAIRING_NOT_STARTED: + case STATE_ESPNOW_PAIRING: lastSystemState = systemState; //Remember this state to return after we mark an event requestChangeState(STATE_DISPLAY_SETUP); setupState = STATE_MARK_EVENT; @@ -583,9 +585,9 @@ void ButtonCheckTask(void *e) setupState = STATE_WIFI_CONFIG_NOT_STARTED; break; case STATE_WIFI_CONFIG_NOT_STARTED: - setupState = STATE_ESPNOW_PAIR; + setupState = STATE_ESPNOW_PAIRING_NOT_STARTED; break; - case STATE_ESPNOW_PAIR: + case STATE_ESPNOW_PAIRING_NOT_STARTED: //If only one active profile do not show any profiles index = getProfileNumberFromUnit(0); displayProfile = getProfileNumberFromUnit(1); @@ -618,11 +620,6 @@ void ButtonCheckTask(void *e) } } -TODO once a user has selected 'Pair', send this once - //Start ESP-Now if needed, put ESP-Now into broadcast state - espnowBeginPairing(); - - void idleTask(void *e) { int cpu = xPortGetCoreID(); diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index a4895f6f6..96c882669 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -153,13 +153,13 @@ void wifiStartAP() #endif WiFi.begin(WIFI_SSID, WIFI_PASSWORD); - Serial.print("Wi-Fi connecting to"); + Serial.print("WiFi connecting to"); while (wifiGetStatus() != WL_CONNECTED) { Serial.print("."); delay(500); } - Serial.print("Wi-Fi connected with IP: "); + Serial.print("WiFi connected with IP: "); Serial.println(WiFi.localIP()); #else //LOCAL_WIFI_TESTING //Start in AP mode @@ -177,10 +177,10 @@ void wifiStartAP() WiFi.softAPConfig(local_IP, gateway, subnet); if (WiFi.softAP("RTK Config") == false) //Must be short enough to fit OLED Width { - Serial.println("Wi-Fi AP failed to start"); + Serial.println("WiFi AP failed to start"); return; } - Serial.print("Wi-Fi AP Started with IP: "); + Serial.print("WiFi AP Started with IP: "); Serial.println(WiFi.softAPIP()); #endif //LOCAL_WIFI_TESTING } @@ -197,7 +197,7 @@ bool wifiConnectionTimeout() #ifdef COMPILE_WIFI if ((millis() - wifiTimer) <= WIFI_CONNECTION_TIMEOUT) return false; - Serial.println("Wi-Fi connection timeout!"); + Serial.println("WiFi connection timeout!"); #endif //COMPILE_WIFI return true; } @@ -221,7 +221,7 @@ void wifiStart(char* ssid, char* pw) esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); #endif - Serial.printf("Wi-Fi connecting to %s\r\n", ssid); + Serial.printf("WiFi connecting to %s\r\n", ssid); WiFi.begin(ssid, pw); wifiTimer = millis(); wifiSetState(WIFI_NOTCONNECTED); @@ -251,7 +251,7 @@ void wifiStop() { WiFi.mode(WIFI_OFF); wifiSetState(WIFI_OFF); - Serial.println("Wi-Fi Stopped"); + Serial.println("WiFi Stopped"); } //If ESP-Now is active, change protocol to only Long Range else if (espnowState > ESPNOW_OFF) @@ -263,13 +263,13 @@ void wifiStop() wifiSetState(WIFI_OFF); - Serial.println("Wi-Fi disabled, ESP-Now left in place"); + Serial.println("WiFi disabled, ESP-Now left in place"); } #else //Turn off radio WiFi.mode(WIFI_OFF); wifiSetState(WIFI_OFF); - Serial.println("Wi-Fi Stopped"); + Serial.println("WiFi Stopped"); #endif //Display the heap state diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index 5460fa34c..480255596 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -362,23 +362,34 @@ void menuRadio() Serial.println("Begin pairing. Place other unit in pairing mode. Press any key to exit."); while (Serial.available()) Serial.read(); - while (1) + uint8_t broadcastMac[6] = {0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF}; + + bool exitPair = false; + while (exitPair == false) { - if (Serial.available()) break; + if (Serial.available()) + { + Serial.println("User pressed button. Pairing canceled."); + break; + } int timeout = 1000 + random(0, 100); //Delay 1000 to 1100ms for (int x = 0 ; x < timeout ; x++) { delay(1); - if (espnowIsPaired()) break; //Check if we've received a pairing message + + if (espnowIsPaired() == true) //Check if we've received a pairing message + { + Serial.println("Pairing compete"); + exitPair = true; + break; + } } espnowSendPairMessage(broadcastMac); //Send unit's MAC address over broadcast, no ack, no encryption Serial.println("Scanning for other radio..."); } - - Serial.println("User pressed button. Pairing canceled."); } else if (settings.radioType == RADIO_ESPNOW && incoming == 3) { @@ -386,8 +397,11 @@ void menuRadio() byte bContinue = getByteChoice(menuTimeout); if (bContinue == 'y') { - for (int x = 0 ; x < settings.espnowPeerCount ; x++) - espnowRemovePeer(settings.espnowPeers[x]); + if (espnowState > ESPNOW_OFF) + { + for (int x = 0 ; x < settings.espnowPeerCount ; x++) + espnowRemovePeer(settings.espnowPeers[x]); + } settings.espnowPeerCount = 0; Serial.println("Radios forgotten"); } diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 6da21e836..893ca13be 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -33,7 +33,8 @@ typedef enum STATE_KEYS_PROVISION_WIFI_STARTED, STATE_KEYS_PROVISION_WIFI_CONNECTED, STATE_KEYS_PROVISION_WIFI_TIMEOUT, - STATE_ESPNOW_PAIR, + STATE_ESPNOW_PAIRING_NOT_STARTED, + STATE_ESPNOW_PAIRING, STATE_SHUTDOWN, } SystemState; volatile SystemState systemState = STATE_ROVER_NOT_STARTED; @@ -487,6 +488,7 @@ struct struct_online { } online; #ifdef COMPILE_WIFI +#ifdef COMPILE_L_BAND //AWS certificate for PointPerfect API static const char *AWS_PUBLIC_CERT = R"=====( -----BEGIN CERTIFICATE----- @@ -511,3 +513,4 @@ rqXRfboQnoZsG4q5WTP468SQvvG5 -----END CERTIFICATE----- )====="; #endif +#endif From d0803284547ee3ff3f072da04439982d880a0bb7 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 13 Aug 2022 14:19:10 -0600 Subject: [PATCH 061/134] Fix L_Band compile guard --- Firmware/RTK_Surveyor/Form.ino | 2 ++ Firmware/RTK_Surveyor/RTK_Surveyor.ino | 6 +++--- Firmware/RTK_Surveyor/States.ino | 3 +-- 3 files changed, 6 insertions(+), 5 deletions(-) diff --git a/Firmware/RTK_Surveyor/Form.ino b/Firmware/RTK_Surveyor/Form.ino index bffdd2ec0..d4036c292 100644 --- a/Firmware/RTK_Surveyor/Form.ino +++ b/Firmware/RTK_Surveyor/Form.ino @@ -387,8 +387,10 @@ void createSettingsString(char* settingsCSV) char apDaysRemaining[20]; if (strlen(settings.pointPerfectCurrentKey) > 0) { +#ifdef COMPILE_L_BAND uint8_t daysRemaining = daysFromEpoch(settings.pointPerfectNextKeyStart + settings.pointPerfectNextKeyDuration + 1); sprintf(apDaysRemaining, "%d", daysRemaining); +#endif } else sprintf(apDaysRemaining, "No Keys"); diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index ba88d8b7f..42343e7fb 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -27,9 +27,9 @@ const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_WIFI //Comment out to remove WiFi functionality //#define COMPILE_AP //Requires WiFi. Comment out to remove Access Point functionality -//#define COMPILE_ESPNOW //Requires WiFi. Comment out to remove ESP-Now functionality. -//#define COMPILE_BT //Comment out to remove Bluetooth functionality -//#define COMPILE_L_BAND //Comment out to remove L-Band functionality +#define COMPILE_ESPNOW //Requires WiFi. Comment out to remove ESP-Now functionality. +#define COMPILE_BT //Comment out to remove Bluetooth functionality +#define COMPILE_L_BAND //Comment out to remove L-Band functionality #define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) //Define the RTK board identifier: diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index d8043d4fe..417d1b2c6 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -596,9 +596,8 @@ void updateSystemState() displayWiFiConfigNotStarted(); //Display immediately during SD cluster pause bluetoothStop(); -#ifdef COMPILE_ESPNOW espnowStop(); -#endif + stopUART2Tasks(); //Delete F9 serial tasks if running startWebServer(); //Start in AP mode and show config html page From 5c50fa78826be966d7e3f3c9f0f465519bf074a8 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 13 Aug 2022 15:35:24 -0600 Subject: [PATCH 062/134] Change menu name to E-Pair Differentiate this radio from other future radios --- Firmware/RTK_Surveyor/Display.ino | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index d9669ea37..53683b2bb 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -2159,7 +2159,7 @@ void paintDisplaySetup() printTextCenter("Base", 12 * 0, QW_FONT_8X16, 1, false); printTextCenter("Bubble", 12 * 1, QW_FONT_8X16, 1, false); printTextCenter("Config", 12 * 2, QW_FONT_8X16, 1, false); - printTextCenter("Pair", 12 * 3, QW_FONT_8X16, 1, true); + printTextCenter("E-Pair", 12 * 3, QW_FONT_8X16, 1, true); } else if (setupState == STATE_PROFILE) paintDisplaySetupProfile("Base"); @@ -2199,7 +2199,7 @@ void paintDisplaySetup() printTextCenter("Rover", 12 * 0, QW_FONT_8X16, 1, false); printTextCenter("Bubble", 12 * 1, QW_FONT_8X16, 1, false); printTextCenter("Config", 12 * 2, QW_FONT_8X16, 1, false); - printTextCenter("Pair", 12 * 3, QW_FONT_8X16, 1, true); + printTextCenter("E-Pair", 12 * 3, QW_FONT_8X16, 1, true); } else if (setupState == STATE_PROFILE) paintDisplaySetupProfile("Rover"); From eb3e4e5d586eff7c58d4a3aa251ed6d5e18f685b Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 13 Aug 2022 21:45:51 -0600 Subject: [PATCH 063/134] Malloc large arrays to free RAM. Move large arrays to reduce RAM footprint. This allowed WiFi casting to work when all subsystems are compiled. Fix WiFi subnet --- Firmware/RTK_Surveyor/Form.ino | 4 +++- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 8 ++++---- Firmware/RTK_Surveyor/States.ino | 2 +- Firmware/RTK_Surveyor/WiFi.ino | 4 ++-- 4 files changed, 10 insertions(+), 8 deletions(-) diff --git a/Firmware/RTK_Surveyor/Form.ino b/Firmware/RTK_Surveyor/Form.ino index d4036c292..72b3a2d09 100644 --- a/Firmware/RTK_Surveyor/Form.ino +++ b/Firmware/RTK_Surveyor/Form.ino @@ -33,8 +33,10 @@ void startWebServer() ntripClientStop(true); wifiStartAP(); + incomingSettings = (char*)malloc(AP_CONFIG_SETTING_SIZE); + //Clear any garbage from settings array - memset(incomingSettings, 0, sizeof(incomingSettings)); + memset(incomingSettings, 0, AP_CONFIG_SETTING_SIZE); ws.onEvent(onWsEvent); server.addHandler(&ws); diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 865878b2c..594ab03a7 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -26,7 +26,7 @@ const int FIRMWARE_VERSION_MAJOR = 2; const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_WIFI //Comment out to remove WiFi functionality -//#define COMPILE_AP //Requires WiFi. Comment out to remove Access Point functionality +#define COMPILE_AP //Requires WiFi. Comment out to remove Access Point functionality #define COMPILE_ESPNOW //Requires WiFi. Comment out to remove ESP-Now functionality. #define COMPILE_BT //Comment out to remove Bluetooth functionality #define COMPILE_L_BAND //Comment out to remove L-Band functionality @@ -159,8 +159,8 @@ LoggingType loggingType = LOGGING_UNKNOWN; #endif -char certificateContents[2000]; //Holds the contents of the keys prior to MQTT connection -char keyContents[2000]; +char *certificateContents; //Holds the contents of the keys prior to MQTT connection +char *keyContents; //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= //GNSS configuration @@ -328,7 +328,7 @@ AsyncWebSocket ws("/ws"); //Because the incoming string is longer than max len, there are multiple callbacks so we //use a global to combine the incoming #define AP_CONFIG_SETTING_SIZE 5000 -char incomingSettings[AP_CONFIG_SETTING_SIZE]; +char *incomingSettings; int incomingSettingsSpot = 0; unsigned long timeSinceLastIncomingSetting = 0; //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 417d1b2c6..75d34f54b 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -622,7 +622,7 @@ void updateSystemState() //Clear buffer incomingSettingsSpot = 0; - memset(incomingSettings, 0, sizeof(incomingSettings)); + memset(incomingSettings, 0, AP_CONFIG_SETTING_SIZE); } } } diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 96c882669..e146ae3ab 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -167,12 +167,12 @@ void wifiStartAP() #ifdef COMPILE_ESPNOW // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); + esp_wifi_set_protocol(WIFI_IF_AP, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); #endif IPAddress local_IP(192, 168, 4, 1); IPAddress gateway(192, 168, 1, 1); - IPAddress subnet(255, 255, 0, 0); + IPAddress subnet(255, 255, 255, 0); WiFi.softAPConfig(local_IP, gateway, subnet); if (WiFi.softAP("RTK Config") == false) //Must be short enough to fit OLED Width From 95e26efd4e6e212f70b3f644ebbd6b35ef0c1ea2 Mon Sep 17 00:00:00 2001 From: burnsed Date: Tue, 19 Jul 2022 15:35:15 -0700 Subject: [PATCH 064/134] Add BLE Support. See setting menu to enable --- Firmware/RTK_Surveyor/Begin.ino | 2 +- Firmware/RTK_Surveyor/Bluetooth.ino | 33 ++-- Firmware/RTK_Surveyor/NVM.ino | 3 + Firmware/RTK_Surveyor/RTK_Surveyor.ino | 10 +- Firmware/RTK_Surveyor/bluetoothSelect.h | 161 +++++++++++++++ Firmware/RTK_Surveyor/menuBluetooth.ino | 45 +++++ Firmware/RTK_Surveyor/menuMain.ino | 4 + Firmware/RTK_Surveyor/settings.h | 2 + .../RTK_Surveyor/src/BleSerial/BleSerial.cpp | 184 ++++++++++++++++++ .../RTK_Surveyor/src/BleSerial/BleSerial.h | 76 ++++++++ .../src/BleSerial/ByteRingBuffer.h | 45 +++++ 11 files changed, 550 insertions(+), 15 deletions(-) create mode 100644 Firmware/RTK_Surveyor/bluetoothSelect.h create mode 100644 Firmware/RTK_Surveyor/menuBluetooth.ino create mode 100644 Firmware/RTK_Surveyor/src/BleSerial/BleSerial.cpp create mode 100644 Firmware/RTK_Surveyor/src/BleSerial/BleSerial.h create mode 100644 Firmware/RTK_Surveyor/src/BleSerial/ByteRingBuffer.h diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index f64b9c2c0..e1aa45311 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -338,7 +338,7 @@ void pinUART2Task( void *pvParameters ) vTaskDelete( NULL ); //Delete task once it has run once } -//Serial Read/Write tasks for the F9P must be started after BT is up and running otherwise SerialBT.available will cause reboot +//Serial Read/Write tasks for the F9P must be started after BT is up and running otherwise SerialBT->available will cause reboot void startUART2Tasks() { //Start the tasks for handling incoming and outgoing BT bytes to/from ZED-F9P diff --git a/Firmware/RTK_Surveyor/Bluetooth.ino b/Firmware/RTK_Surveyor/Bluetooth.ino index 07d6659df..d56d381cd 100644 --- a/Firmware/RTK_Surveyor/Bluetooth.ino +++ b/Firmware/RTK_Surveyor/Bluetooth.ino @@ -28,8 +28,7 @@ Bluetooth States: //---------------------------------------- #ifdef COMPILE_BT - -static BluetoothSerial bluetoothSerial; +BTSerialInterface *bluetoothSerial; static volatile byte bluetoothState = BT_OFF; //---------------------------------------- @@ -74,7 +73,7 @@ byte bluetoothGetState() bool bluetoothIsCongested() { #ifdef COMPILE_BT - return bluetoothSerial.isCongested(); + return bluetoothSerial->isCongested(); #else //COMPILE_BT return false; #endif //COMPILE_BT @@ -84,7 +83,7 @@ bool bluetoothIsCongested() int bluetoothReadBytes(uint8_t * buffer, int length) { #ifdef COMPILE_BT - return bluetoothSerial.readBytes(buffer, length); + return bluetoothSerial->readBytes(buffer, length); #else //COMPILE_BT return 0; #endif //COMPILE_BT @@ -94,7 +93,7 @@ int bluetoothReadBytes(uint8_t * buffer, int length) bool bluetoothRxDataAvailable() { #ifdef COMPILE_BT - return bluetoothSerial.available(); + return bluetoothSerial->available(); #else //COMPILE_BT return false; #endif //COMPILE_BT @@ -116,7 +115,15 @@ void bluetoothStart() sprintf(deviceName, "%s %s%02X%02X", platformPrefix, stateName, unitMACAddress[4], unitMACAddress[5]); - if (bluetoothSerial.begin(deviceName, false, settings.sppRxQueueSize, settings.sppTxQueueSize) == false) //localName, isMaster, rxBufferSize, txBufferSize + // BLE vs Bluetooth Classic + if (settings.enableBLE) + bluetoothSerial = new BTLESerial(); + else + { + bluetoothSerial = new BTClassicSerial(); + } + + if (bluetoothSerial->begin(deviceName, false, settings.sppRxQueueSize, settings.sppTxQueueSize) == false) //localName, isMaster, rxBufferSize, txBufferSize { Serial.println("An error occurred initializing Bluetooth"); @@ -145,8 +152,8 @@ void bluetoothStart() esp_bt_gap_set_pin(pin_type, 4, pin_code); //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- - bluetoothSerial.register_callback(bluetoothCallback); //Controls BT Status LED on Surveyor - bluetoothSerial.setTimeout(250); + bluetoothSerial->register_callback(bluetoothCallback); //Controls BT Status LED on Surveyor + bluetoothSerial->setTimeout(250); Serial.print("Bluetooth broadcasting as: "); Serial.println(deviceName); @@ -172,10 +179,10 @@ void bluetoothStop() #ifdef COMPILE_BT if (bluetoothState == BT_NOTCONNECTED || bluetoothState == BT_CONNECTED) { - bluetoothSerial.register_callback(NULL); - bluetoothSerial.flush(); //Complete any transfers - bluetoothSerial.disconnect(); //Drop any clients - bluetoothSerial.end(); //bluetoothSerial.end() will release significant RAM (~100k!) but a bluetoothSerial.start will crash. + bluetoothSerial->register_callback(NULL); + bluetoothSerial->flush(); //Complete any transfers + bluetoothSerial->disconnect(); //Drop any clients + bluetoothSerial->end(); //bluetoothSerial->end() will release significant RAM (~100k!) but a bluetoothSerial->start will crash. log_d("Bluetooth turned off"); @@ -191,7 +198,7 @@ int bluetoothWriteBytes(const uint8_t * buffer, int length) { #ifdef COMPILE_BT //Push new data to BT SPP - return bluetoothSerial.write(buffer, length); + return bluetoothSerial->write(buffer, length); #else //COMPILE_BT return 0; #endif //COMPILE_BT diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index 734cc3c14..cf2c3d6d6 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -267,6 +267,7 @@ void recordSystemSettingsToFile(File * settingsFile) } settingsFile->printf("%s=%d\n\r", "espnowPeerCount", settings.espnowPeerCount); settingsFile->printf("%s=%d\n\r", "enableNtripServerMessageParsing", settings.enableNtripServerMessageParsing); + settingsFile->printf("%s=%d\n\r", "enableBLE", settings.enableBLE); //Record constellation settings for (int x = 0 ; x < MAX_CONSTELLATIONS ; x++) @@ -875,6 +876,8 @@ bool parseLine(char* str, Settings *settings) settings->espnowPeerCount = d; else if (strcmp(settingName, "enableNtripServerMessageParsing") == 0) settings->enableNtripServerMessageParsing = d; + else if (strcmp(settingName, "enableBLE") == 0) + settings->enableBLE = d; //Check for bulk settings (constellations, message rates, ESPNOW Peers) //Must be last on else list diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 594ab03a7..ee76c394e 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -242,8 +242,16 @@ float battChangeRate = 0.0; //Hardware serial and BT buffers //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= #ifdef COMPILE_BT +// See bluetoothSelect.h for implemenation +#include "bluetoothSelect.h" + //We use a local copy of the BluetoothSerial library so that we can increase the RX buffer. See issue: https://github.com/sparkfun/SparkFun_RTK_Firmware/issues/23 -#include "src/BluetoothSerial/BluetoothSerial.h" +// #include "src/BluetoothSerial/BluetoothSerial.h" +// BluetoothSerial SerialBT; + +// BLE Support originally from https://github.com/avinabmalla/ESP32_BleSerial/tree/bad5ff841800853a61e431ea751f8ea9d7a1df21 +// #include "src/BleSerial/BleSerial.h" +// BleSerial SerialBLE; #endif char platformPrefix[55] = "Surveyor"; //Sets the prefix for broadcast names diff --git a/Firmware/RTK_Surveyor/bluetoothSelect.h b/Firmware/RTK_Surveyor/bluetoothSelect.h new file mode 100644 index 000000000..af708a904 --- /dev/null +++ b/Firmware/RTK_Surveyor/bluetoothSelect.h @@ -0,0 +1,161 @@ +#ifdef COMPILE_BT + +#include "src/BluetoothSerial/BluetoothSerial.h" +#include "src/BleSerial/BleSerial.h" + +class BTSerialInterface +{ + public: + virtual bool begin(String deviceName, bool isMaster, uint16_t rxQueueSize, uint16_t txQueueSize) = 0; + virtual void disconnect() = 0; + virtual void end() = 0; + virtual esp_err_t register_callback(esp_spp_cb_t * callback) = 0; + virtual void setTimeout(unsigned long timeout) = 0; + + virtual int available() = 0; + virtual size_t readBytes(uint8_t *buffer, size_t bufferSize) = 0; + + virtual bool isCongested() = 0; + virtual size_t write(const uint8_t *buffer, size_t size) = 0; + virtual void flush() = 0; +}; + + +class BTClassicSerial : public virtual BTSerialInterface, public BluetoothSerial +{ + // Everything is already implemented in BluetoothSerial since the code was + // originally written using that class + public: + bool begin(String deviceName, bool isMaster, uint16_t rxQueueSize, uint16_t txQueueSize) + { + return BluetoothSerial::begin(deviceName, isMaster, rxQueueSize, txQueueSize); + } + + void disconnect() + { + BluetoothSerial::disconnect(); + } + + void end() + { + BluetoothSerial::end(); + } + + esp_err_t register_callback(esp_spp_cb_t * callback) + { + return BluetoothSerial::register_callback(callback); + } + + void setTimeout(unsigned long timeout) + { + BluetoothSerial::setTimeout(timeout); + } + + int available() + { + return BluetoothSerial::available(); + } + + size_t readBytes(uint8_t *buffer, size_t bufferSize) + { + return BluetoothSerial::readBytes(buffer, bufferSize); + } + + bool isCongested() + { + return BluetoothSerial::isCongested(); + } + + size_t write(const uint8_t *buffer, size_t size) + { + return BluetoothSerial::write(buffer, size); + } + + void flush() + { + BluetoothSerial::flush(); + } +}; + + +class BTLESerial: public virtual BTSerialInterface, public BleSerial +{ + public: + // Missing from BleSerial + bool begin(String deviceName, bool isMaster, uint16_t rxQueueSuze, uint16_t txQueueSize) + { + // Curretnly ignoring rxQueueSize + // transmitBufferLength = txQueueSize; + BleSerial::begin(deviceName.c_str()); + return true; + } + + void disconnect() + { + Server->disconnect(Server->getConnId()); + } + + void end() + { + BleSerial::end(); + } + + esp_err_t register_callback(esp_spp_cb_t * callback) + { + connectionCallback = callback; + return ESP_OK; + } + + void setTimeout(unsigned long timeout) + { + BleSerial::setTimeout(timeout); + } + + int available() + { + return BleSerial::available(); + } + + size_t readBytes(uint8_t *buffer, size_t bufferSize) + { + return BleSerial::readBytes(buffer, bufferSize); + } + + bool isCongested() + { + // not currently supported in this implementation + return false; + } + + size_t write(const uint8_t *buffer, size_t size) + { + return BleSerial::write(buffer, size); + } + + void flush() + { + BleSerial::flush(); + } + + // override BLEServerCallbacks + void onConnect(BLEServer *pServer) + { + bleConnected = true; + connectionCallback(ESP_SPP_SRV_OPEN_EVT, nullptr); + } + + void onDisconnect(BLEServer *pServer) + { + bleConnected = false; + connectionCallback(ESP_SPP_CLOSE_EVT, nullptr); + Server->startAdvertising(); + } + + private: + esp_spp_cb_t * connectionCallback; + +}; + + +#endif + diff --git a/Firmware/RTK_Surveyor/menuBluetooth.ino b/Firmware/RTK_Surveyor/menuBluetooth.ino new file mode 100644 index 000000000..e63d93187 --- /dev/null +++ b/Firmware/RTK_Surveyor/menuBluetooth.ino @@ -0,0 +1,45 @@ +void menuBluetooth() +{ + while (1) + { + Serial.println(); + Serial.println(F("Menu: Blueooth Menu")); + + Serial.println(); + Serial.print(F("Current Bluetooth Mode: ")); + if (settings.enableBLE == true) + Serial.println(F("BLE")); + else + Serial.println(F("Classic")); + + Serial.println(); + Serial.println(F("1) Set Bluetooth Mode to Classic")); + Serial.println(F("2) Set Bluetooth Mode to BLE")); + Serial.println(F("x) Exit")); + + byte incoming = getByteChoice(menuTimeout); + if (incoming == '1') + { + // Restart Bluetooth + bluetoothStop(); + settings.enableBLE = false; + bluetoothStart(); + } + else if (incoming == '2') + { + // restart Bluetooth + bluetoothStop(); + settings.enableBLE = true; + bluetoothStart(); + } + else if (incoming == 'x') + break; + else if (incoming == STATUS_GETBYTE_TIMEOUT) + break; + else + printUnknown(incoming); + } + + while (Serial.available()) Serial.read(); +} + diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index 480255596..50f5f5836 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -51,6 +51,8 @@ void menuMain() Serial.println("5) Configure Logging"); + Serial.println("6) Configure Bluetooth"); + Serial.println("p) Configure Profiles"); #ifdef COMPILE_ESPNOW @@ -81,6 +83,8 @@ void menuMain() menuPorts(); else if (incoming == '5') menuLog(); + else if (incoming == '6') + menuBluetooth(); else if (incoming == 's') menuSystem(); else if (incoming == 'p') diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 893ca13be..cc06b8c60 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -278,6 +278,8 @@ typedef struct { bool enableExternalHardwareEventLogging = false; //Log when INT/TM2 pin goes low bool enableMarksFile = false; //Log marks to the marks file + bool enableBLE = false; + ubxMsg ubxMessages[MAX_UBX_MSG] = //Report rates for all known messages { //NMEA diff --git a/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.cpp b/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.cpp new file mode 100644 index 000000000..bcb5cb620 --- /dev/null +++ b/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.cpp @@ -0,0 +1,184 @@ +#include "BleSerial.h" +using namespace std; + +bool BleSerial::connected() +{ + return Server->getConnectedCount() > 0; +} + +void BleSerial::onConnect(BLEServer *pServer) +{ + bleConnected = true; + if(ENABLE_LED) digitalWrite(BLUE_LED, HIGH); +} + +void BleSerial::onDisconnect(BLEServer *pServer) +{ + bleConnected = false; + if(ENABLE_LED) digitalWrite(BLUE_LED, LOW); + Server->startAdvertising(); +} + +int BleSerial::read() +{ + uint8_t result = this->receiveBuffer.pop(); + if (result == (uint8_t)'\n') + { + this->numAvailableLines--; + } + return result; +} + +size_t BleSerial::readBytes(uint8_t *buffer, size_t bufferSize) +{ + int i = 0; + while (i < bufferSize && available()) + { + buffer[i] = this->receiveBuffer.pop(); + i++; + } + return i; +} + +int BleSerial::peek() +{ + if (this->receiveBuffer.getLength() == 0) + return -1; + return this->receiveBuffer.get(0); +} + +int BleSerial::available() +{ + return this->receiveBuffer.getLength(); +} + +size_t BleSerial::print(const char *str) +{ + if (Server->getConnectedCount() <= 0) + { + return 0; + } + + size_t written = 0; + for (size_t i = 0; str[i] != '\0'; i++) + { + written += this->write(str[i]); + } + flush(); + return written; +} + +size_t BleSerial::write(const uint8_t *buffer, size_t bufferSize) +{ + if (Server->getConnectedCount() <= 0) + { + return 0; + } + size_t written = 0; + for (int i = 0; i < bufferSize; i++) + { + written += this->write(buffer[i]); + } + flush(); + return written; +} + +size_t BleSerial::write(uint8_t byte) +{ + if (Server->getConnectedCount() <= 0) + { + return 0; + } + this->transmitBuffer[this->transmitBufferLength] = byte; + this->transmitBufferLength++; + if (this->transmitBufferLength == sizeof(this->transmitBuffer)) + { + flush(); + } + return 1; +} + +void BleSerial::flush() +{ + if (this->transmitBufferLength > 0) + { + TxCharacteristic->setValue(this->transmitBuffer, this->transmitBufferLength); + this->transmitBufferLength = 0; + } + this->lastFlushTime = millis(); + TxCharacteristic->notify(true); +} + +void BleSerial::begin(const char *name) +{ + //characteristic property is what the other device does. + + ConnectedDeviceCount = 0; + BLEDevice::init(name); + //BLEDevice::setEncryptionLevel(ESP_BLE_SEC_ENCRYPT); + + Server = BLEDevice::createServer(); + Server->setCallbacks(this); + + SetupSerialService(); + + pAdvertising = BLEDevice::getAdvertising(); + pAdvertising->addServiceUUID(BLE_SERIAL_SERVICE_UUID); + pAdvertising->setScanResponse(true); + pAdvertising->setMinPreferred(0x06); // functions that help with iPhone connections issue + pAdvertising->setMinPreferred(0x12); + pAdvertising->start(); + + //pSecurity = new BLESecurity(); + + //Set static pin + //uint32_t passkey = 123456; + //esp_ble_gap_set_security_param(ESP_BLE_SM_SET_STATIC_PASSKEY, &passkey, sizeof(uint32_t)); + //pSecurity->setCapability(ESP_IO_CAP_OUT); +} + +void BleSerial::end() +{ + BLEDevice::deinit(); +} + +void BleSerial::onWrite(BLECharacteristic *pCharacteristic) +{ + if (pCharacteristic->getUUID().toString() == BLE_RX_UUID) + { + std::string value = pCharacteristic->getValue(); + + if (value.length() > 0) + { + for (int i = 0; i < value.length(); i++) + receiveBuffer.add(value[i]); + } + } +} + +void BleSerial::SetupSerialService() +{ + SerialService = Server->createService(BLE_SERIAL_SERVICE_UUID); + + RxCharacteristic = SerialService->createCharacteristic( + BLE_RX_UUID, BLECharacteristic::PROPERTY_WRITE); + + TxCharacteristic = SerialService->createCharacteristic( + BLE_TX_UUID, BLECharacteristic::PROPERTY_NOTIFY); + + TxCharacteristic->setAccessPermissions(ESP_GATT_PERM_READ_ENCRYPTED); + RxCharacteristic->setAccessPermissions(ESP_GATT_PERM_WRITE_ENCRYPTED); + + TxCharacteristic->addDescriptor(new BLE2902()); + RxCharacteristic->addDescriptor(new BLE2902()); + + TxCharacteristic->setReadProperty(true); + RxCharacteristic->setWriteProperty(true); + RxCharacteristic->setCallbacks(this); + SerialService->start(); +} + +BleSerial::BleSerial() +{ +} + diff --git a/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.h b/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.h new file mode 100644 index 000000000..13d4cd3cd --- /dev/null +++ b/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.h @@ -0,0 +1,76 @@ +#pragma once +#include + +#include +#include +#include +#include +#include "ByteRingBuffer.h" + +//Connection status LED +#define ENABLE_LED 0 +#define BLUE_LED 13 + +#define BLE_BUFFER_SIZE 500 //must be greater than MTU, less than ESP_GATT_MAX_ATTR_LEN + + + +class BleSerial : public BLECharacteristicCallbacks, public BLEServerCallbacks, public Stream +{ +public: + BleSerial(); + + void begin(const char *name); + void end(); + void onWrite(BLECharacteristic *pCharacteristic); + int available(); + int read(); + size_t readBytes(uint8_t *buffer, size_t bufferSize); + int peek(); + size_t write(uint8_t byte); + void flush(); + size_t write(const uint8_t *buffer, size_t bufferSize); + size_t print(const char *value); + void onConnect(BLEServer *pServer); + void onDisconnect(BLEServer *pServer); + + bool connected(); + + BLEServer *Server; + + BLEAdvertising *pAdvertising; + //BLESecurity *pSecurity; + + //Services + BLEService *SerialService; + + //Serial Characteristics + BLECharacteristic *TxCharacteristic; + BLECharacteristic *RxCharacteristic; + +protected: + size_t transmitBufferLength; + bool bleConnected; + +private: + BleSerial(BleSerial const &other) = delete; // disable copy constructor + void operator=(BleSerial const &other) = delete; // disable assign constructor + + ByteRingBuffer receiveBuffer; + size_t numAvailableLines; + + unsigned long long lastFlushTime; + uint8_t transmitBuffer[BLE_BUFFER_SIZE]; + + int ConnectedDeviceCount; + void SetupSerialService(); + + /* + Bluetooth LE GATT UUIDs for the Nordic UART profile + Change UUID here if required + */ + const char *BLE_SERIAL_SERVICE_UUID = "6e400001-b5a3-f393-e0a9-e50e24dcca9e"; + const char *BLE_RX_UUID = "6e400002-b5a3-f393-e0a9-e50e24dcca9e"; + const char *BLE_TX_UUID = "6e400003-b5a3-f393-e0a9-e50e24dcca9e"; +}; + diff --git a/Firmware/RTK_Surveyor/src/BleSerial/ByteRingBuffer.h b/Firmware/RTK_Surveyor/src/BleSerial/ByteRingBuffer.h new file mode 100644 index 000000000..aaa81184a --- /dev/null +++ b/Firmware/RTK_Surveyor/src/BleSerial/ByteRingBuffer.h @@ -0,0 +1,45 @@ +#pragma once +#include + + +template +class ByteRingBuffer +{ +private: + uint8_t ringBuffer[N]; + size_t newestIndex = 0; + size_t length = 0; + +public: + void add(uint8_t value) + { + ringBuffer[newestIndex] = value; + newestIndex = (newestIndex + 1) % N; + length = min(length + 1, N); + } + uint8_t pop() + { // pops the oldest value off the ring buffer + if (length == 0) + { + return -1; + } + uint8_t result = ringBuffer[(N + newestIndex - length) % N]; + length -= 1; + return result; + } + void clear() + { + newestIndex = 0; + length = 0; + } + uint8_t get(size_t index) + { // this.get(0) is the oldest value, this.get(this.getLength() - 1) is the newest value + if (index < 0 || index >= length) + { + return -1; + } + return ringBuffer[(N + newestIndex - length + index) % N]; + } + size_t getLength() { return length; } +}; + From c1a8c09f43d1faa3b9b5cd4c45fc509bbd96304b Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sun, 14 Aug 2022 20:57:21 -0600 Subject: [PATCH 065/134] Remove BleSerial driver and link to library instead. --- Firmware/RTK_Surveyor/bluetoothSelect.h | 3 +- .../RTK_Surveyor/src/BleSerial/BleSerial.cpp | 184 ------------------ .../RTK_Surveyor/src/BleSerial/BleSerial.h | 76 -------- .../src/BleSerial/ByteRingBuffer.h | 45 ----- 4 files changed, 1 insertion(+), 307 deletions(-) delete mode 100644 Firmware/RTK_Surveyor/src/BleSerial/BleSerial.cpp delete mode 100644 Firmware/RTK_Surveyor/src/BleSerial/BleSerial.h delete mode 100644 Firmware/RTK_Surveyor/src/BleSerial/ByteRingBuffer.h diff --git a/Firmware/RTK_Surveyor/bluetoothSelect.h b/Firmware/RTK_Surveyor/bluetoothSelect.h index af708a904..dd65a3682 100644 --- a/Firmware/RTK_Surveyor/bluetoothSelect.h +++ b/Firmware/RTK_Surveyor/bluetoothSelect.h @@ -1,7 +1,7 @@ #ifdef COMPILE_BT #include "src/BluetoothSerial/BluetoothSerial.h" -#include "src/BleSerial/BleSerial.h" +#include // Click here to get the library: http://librarymanager/All#ESP32_BleSerial by Avinab Malla class BTSerialInterface { @@ -158,4 +158,3 @@ class BTLESerial: public virtual BTSerialInterface, public BleSerial #endif - diff --git a/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.cpp b/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.cpp deleted file mode 100644 index bcb5cb620..000000000 --- a/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.cpp +++ /dev/null @@ -1,184 +0,0 @@ -#include "BleSerial.h" -using namespace std; - -bool BleSerial::connected() -{ - return Server->getConnectedCount() > 0; -} - -void BleSerial::onConnect(BLEServer *pServer) -{ - bleConnected = true; - if(ENABLE_LED) digitalWrite(BLUE_LED, HIGH); -} - -void BleSerial::onDisconnect(BLEServer *pServer) -{ - bleConnected = false; - if(ENABLE_LED) digitalWrite(BLUE_LED, LOW); - Server->startAdvertising(); -} - -int BleSerial::read() -{ - uint8_t result = this->receiveBuffer.pop(); - if (result == (uint8_t)'\n') - { - this->numAvailableLines--; - } - return result; -} - -size_t BleSerial::readBytes(uint8_t *buffer, size_t bufferSize) -{ - int i = 0; - while (i < bufferSize && available()) - { - buffer[i] = this->receiveBuffer.pop(); - i++; - } - return i; -} - -int BleSerial::peek() -{ - if (this->receiveBuffer.getLength() == 0) - return -1; - return this->receiveBuffer.get(0); -} - -int BleSerial::available() -{ - return this->receiveBuffer.getLength(); -} - -size_t BleSerial::print(const char *str) -{ - if (Server->getConnectedCount() <= 0) - { - return 0; - } - - size_t written = 0; - for (size_t i = 0; str[i] != '\0'; i++) - { - written += this->write(str[i]); - } - flush(); - return written; -} - -size_t BleSerial::write(const uint8_t *buffer, size_t bufferSize) -{ - if (Server->getConnectedCount() <= 0) - { - return 0; - } - size_t written = 0; - for (int i = 0; i < bufferSize; i++) - { - written += this->write(buffer[i]); - } - flush(); - return written; -} - -size_t BleSerial::write(uint8_t byte) -{ - if (Server->getConnectedCount() <= 0) - { - return 0; - } - this->transmitBuffer[this->transmitBufferLength] = byte; - this->transmitBufferLength++; - if (this->transmitBufferLength == sizeof(this->transmitBuffer)) - { - flush(); - } - return 1; -} - -void BleSerial::flush() -{ - if (this->transmitBufferLength > 0) - { - TxCharacteristic->setValue(this->transmitBuffer, this->transmitBufferLength); - this->transmitBufferLength = 0; - } - this->lastFlushTime = millis(); - TxCharacteristic->notify(true); -} - -void BleSerial::begin(const char *name) -{ - //characteristic property is what the other device does. - - ConnectedDeviceCount = 0; - BLEDevice::init(name); - //BLEDevice::setEncryptionLevel(ESP_BLE_SEC_ENCRYPT); - - Server = BLEDevice::createServer(); - Server->setCallbacks(this); - - SetupSerialService(); - - pAdvertising = BLEDevice::getAdvertising(); - pAdvertising->addServiceUUID(BLE_SERIAL_SERVICE_UUID); - pAdvertising->setScanResponse(true); - pAdvertising->setMinPreferred(0x06); // functions that help with iPhone connections issue - pAdvertising->setMinPreferred(0x12); - pAdvertising->start(); - - //pSecurity = new BLESecurity(); - - //Set static pin - //uint32_t passkey = 123456; - //esp_ble_gap_set_security_param(ESP_BLE_SM_SET_STATIC_PASSKEY, &passkey, sizeof(uint32_t)); - //pSecurity->setCapability(ESP_IO_CAP_OUT); -} - -void BleSerial::end() -{ - BLEDevice::deinit(); -} - -void BleSerial::onWrite(BLECharacteristic *pCharacteristic) -{ - if (pCharacteristic->getUUID().toString() == BLE_RX_UUID) - { - std::string value = pCharacteristic->getValue(); - - if (value.length() > 0) - { - for (int i = 0; i < value.length(); i++) - receiveBuffer.add(value[i]); - } - } -} - -void BleSerial::SetupSerialService() -{ - SerialService = Server->createService(BLE_SERIAL_SERVICE_UUID); - - RxCharacteristic = SerialService->createCharacteristic( - BLE_RX_UUID, BLECharacteristic::PROPERTY_WRITE); - - TxCharacteristic = SerialService->createCharacteristic( - BLE_TX_UUID, BLECharacteristic::PROPERTY_NOTIFY); - - TxCharacteristic->setAccessPermissions(ESP_GATT_PERM_READ_ENCRYPTED); - RxCharacteristic->setAccessPermissions(ESP_GATT_PERM_WRITE_ENCRYPTED); - - TxCharacteristic->addDescriptor(new BLE2902()); - RxCharacteristic->addDescriptor(new BLE2902()); - - TxCharacteristic->setReadProperty(true); - RxCharacteristic->setWriteProperty(true); - RxCharacteristic->setCallbacks(this); - SerialService->start(); -} - -BleSerial::BleSerial() -{ -} - diff --git a/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.h b/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.h deleted file mode 100644 index 13d4cd3cd..000000000 --- a/Firmware/RTK_Surveyor/src/BleSerial/BleSerial.h +++ /dev/null @@ -1,76 +0,0 @@ -#pragma once -#include - -#include -#include -#include -#include -#include "ByteRingBuffer.h" - -//Connection status LED -#define ENABLE_LED 0 -#define BLUE_LED 13 - -#define BLE_BUFFER_SIZE 500 //must be greater than MTU, less than ESP_GATT_MAX_ATTR_LEN - - - -class BleSerial : public BLECharacteristicCallbacks, public BLEServerCallbacks, public Stream -{ -public: - BleSerial(); - - void begin(const char *name); - void end(); - void onWrite(BLECharacteristic *pCharacteristic); - int available(); - int read(); - size_t readBytes(uint8_t *buffer, size_t bufferSize); - int peek(); - size_t write(uint8_t byte); - void flush(); - size_t write(const uint8_t *buffer, size_t bufferSize); - size_t print(const char *value); - void onConnect(BLEServer *pServer); - void onDisconnect(BLEServer *pServer); - - bool connected(); - - BLEServer *Server; - - BLEAdvertising *pAdvertising; - //BLESecurity *pSecurity; - - //Services - BLEService *SerialService; - - //Serial Characteristics - BLECharacteristic *TxCharacteristic; - BLECharacteristic *RxCharacteristic; - -protected: - size_t transmitBufferLength; - bool bleConnected; - -private: - BleSerial(BleSerial const &other) = delete; // disable copy constructor - void operator=(BleSerial const &other) = delete; // disable assign constructor - - ByteRingBuffer receiveBuffer; - size_t numAvailableLines; - - unsigned long long lastFlushTime; - uint8_t transmitBuffer[BLE_BUFFER_SIZE]; - - int ConnectedDeviceCount; - void SetupSerialService(); - - /* - Bluetooth LE GATT UUIDs for the Nordic UART profile - Change UUID here if required - */ - const char *BLE_SERIAL_SERVICE_UUID = "6e400001-b5a3-f393-e0a9-e50e24dcca9e"; - const char *BLE_RX_UUID = "6e400002-b5a3-f393-e0a9-e50e24dcca9e"; - const char *BLE_TX_UUID = "6e400003-b5a3-f393-e0a9-e50e24dcca9e"; -}; - diff --git a/Firmware/RTK_Surveyor/src/BleSerial/ByteRingBuffer.h b/Firmware/RTK_Surveyor/src/BleSerial/ByteRingBuffer.h deleted file mode 100644 index aaa81184a..000000000 --- a/Firmware/RTK_Surveyor/src/BleSerial/ByteRingBuffer.h +++ /dev/null @@ -1,45 +0,0 @@ -#pragma once -#include - - -template -class ByteRingBuffer -{ -private: - uint8_t ringBuffer[N]; - size_t newestIndex = 0; - size_t length = 0; - -public: - void add(uint8_t value) - { - ringBuffer[newestIndex] = value; - newestIndex = (newestIndex + 1) % N; - length = min(length + 1, N); - } - uint8_t pop() - { // pops the oldest value off the ring buffer - if (length == 0) - { - return -1; - } - uint8_t result = ringBuffer[(N + newestIndex - length) % N]; - length -= 1; - return result; - } - void clear() - { - newestIndex = 0; - length = 0; - } - uint8_t get(size_t index) - { // this.get(0) is the oldest value, this.get(this.getLength() - 1) is the newest value - if (index < 0 || index >= length) - { - return -1; - } - return ringBuffer[(N + newestIndex - length + index) % N]; - } - size_t getLength() { return length; } -}; - From df5cf920f5dd3a338c3a79f7265fbc8cd94a5cda Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sun, 14 Aug 2022 21:13:39 -0600 Subject: [PATCH 066/134] Move BLE control to system menu --- Firmware/RTK_Surveyor/Bluetooth.ino | 2 - Firmware/RTK_Surveyor/bluetoothSelect.h | 272 ++++++++++++------------ Firmware/RTK_Surveyor/menuBluetooth.ino | 45 ---- Firmware/RTK_Surveyor/menuMain.ino | 4 - Firmware/RTK_Surveyor/menuSystem.ino | 17 ++ Firmware/RTK_Surveyor/settings.h | 3 +- 6 files changed, 154 insertions(+), 189 deletions(-) delete mode 100644 Firmware/RTK_Surveyor/menuBluetooth.ino diff --git a/Firmware/RTK_Surveyor/Bluetooth.ino b/Firmware/RTK_Surveyor/Bluetooth.ino index d56d381cd..7a8359590 100644 --- a/Firmware/RTK_Surveyor/Bluetooth.ino +++ b/Firmware/RTK_Surveyor/Bluetooth.ino @@ -119,9 +119,7 @@ void bluetoothStart() if (settings.enableBLE) bluetoothSerial = new BTLESerial(); else - { bluetoothSerial = new BTClassicSerial(); - } if (bluetoothSerial->begin(deviceName, false, settings.sppRxQueueSize, settings.sppTxQueueSize) == false) //localName, isMaster, rxBufferSize, txBufferSize { diff --git a/Firmware/RTK_Surveyor/bluetoothSelect.h b/Firmware/RTK_Surveyor/bluetoothSelect.h index dd65a3682..fe7d8b8c1 100644 --- a/Firmware/RTK_Surveyor/bluetoothSelect.h +++ b/Firmware/RTK_Surveyor/bluetoothSelect.h @@ -5,19 +5,19 @@ class BTSerialInterface { - public: - virtual bool begin(String deviceName, bool isMaster, uint16_t rxQueueSize, uint16_t txQueueSize) = 0; - virtual void disconnect() = 0; - virtual void end() = 0; - virtual esp_err_t register_callback(esp_spp_cb_t * callback) = 0; - virtual void setTimeout(unsigned long timeout) = 0; - - virtual int available() = 0; - virtual size_t readBytes(uint8_t *buffer, size_t bufferSize) = 0; - - virtual bool isCongested() = 0; - virtual size_t write(const uint8_t *buffer, size_t size) = 0; - virtual void flush() = 0; + public: + virtual bool begin(String deviceName, bool isMaster, uint16_t rxQueueSize, uint16_t txQueueSize) = 0; + virtual void disconnect() = 0; + virtual void end() = 0; + virtual esp_err_t register_callback(esp_spp_cb_t * callback) = 0; + virtual void setTimeout(unsigned long timeout) = 0; + + virtual int available() = 0; + virtual size_t readBytes(uint8_t *buffer, size_t bufferSize) = 0; + + virtual bool isCongested() = 0; + virtual size_t write(const uint8_t *buffer, size_t size) = 0; + virtual void flush() = 0; }; @@ -25,134 +25,134 @@ class BTClassicSerial : public virtual BTSerialInterface, public BluetoothSerial { // Everything is already implemented in BluetoothSerial since the code was // originally written using that class - public: - bool begin(String deviceName, bool isMaster, uint16_t rxQueueSize, uint16_t txQueueSize) - { - return BluetoothSerial::begin(deviceName, isMaster, rxQueueSize, txQueueSize); - } - - void disconnect() - { - BluetoothSerial::disconnect(); - } - - void end() - { - BluetoothSerial::end(); - } - - esp_err_t register_callback(esp_spp_cb_t * callback) - { - return BluetoothSerial::register_callback(callback); - } - - void setTimeout(unsigned long timeout) - { - BluetoothSerial::setTimeout(timeout); - } - - int available() - { - return BluetoothSerial::available(); - } - - size_t readBytes(uint8_t *buffer, size_t bufferSize) - { - return BluetoothSerial::readBytes(buffer, bufferSize); - } - - bool isCongested() - { - return BluetoothSerial::isCongested(); - } - - size_t write(const uint8_t *buffer, size_t size) - { - return BluetoothSerial::write(buffer, size); - } - - void flush() - { - BluetoothSerial::flush(); - } + public: + bool begin(String deviceName, bool isMaster, uint16_t rxQueueSize, uint16_t txQueueSize) + { + return BluetoothSerial::begin(deviceName, isMaster, rxQueueSize, txQueueSize); + } + + void disconnect() + { + BluetoothSerial::disconnect(); + } + + void end() + { + BluetoothSerial::end(); + } + + esp_err_t register_callback(esp_spp_cb_t * callback) + { + return BluetoothSerial::register_callback(callback); + } + + void setTimeout(unsigned long timeout) + { + BluetoothSerial::setTimeout(timeout); + } + + int available() + { + return BluetoothSerial::available(); + } + + size_t readBytes(uint8_t *buffer, size_t bufferSize) + { + return BluetoothSerial::readBytes(buffer, bufferSize); + } + + bool isCongested() + { + return BluetoothSerial::isCongested(); + } + + size_t write(const uint8_t *buffer, size_t size) + { + return BluetoothSerial::write(buffer, size); + } + + void flush() + { + BluetoothSerial::flush(); + } }; class BTLESerial: public virtual BTSerialInterface, public BleSerial { - public: - // Missing from BleSerial - bool begin(String deviceName, bool isMaster, uint16_t rxQueueSuze, uint16_t txQueueSize) - { - // Curretnly ignoring rxQueueSize - // transmitBufferLength = txQueueSize; - BleSerial::begin(deviceName.c_str()); - return true; - } - - void disconnect() - { - Server->disconnect(Server->getConnId()); - } - - void end() - { - BleSerial::end(); - } - - esp_err_t register_callback(esp_spp_cb_t * callback) - { - connectionCallback = callback; - return ESP_OK; - } - - void setTimeout(unsigned long timeout) - { - BleSerial::setTimeout(timeout); - } - - int available() - { - return BleSerial::available(); - } - - size_t readBytes(uint8_t *buffer, size_t bufferSize) - { - return BleSerial::readBytes(buffer, bufferSize); - } - - bool isCongested() - { - // not currently supported in this implementation - return false; - } - - size_t write(const uint8_t *buffer, size_t size) - { - return BleSerial::write(buffer, size); - } - - void flush() - { - BleSerial::flush(); - } - - // override BLEServerCallbacks - void onConnect(BLEServer *pServer) - { - bleConnected = true; - connectionCallback(ESP_SPP_SRV_OPEN_EVT, nullptr); - } - - void onDisconnect(BLEServer *pServer) - { - bleConnected = false; - connectionCallback(ESP_SPP_CLOSE_EVT, nullptr); - Server->startAdvertising(); - } - - private: - esp_spp_cb_t * connectionCallback; + public: + // Missing from BleSerial + bool begin(String deviceName, bool isMaster, uint16_t rxQueueSuze, uint16_t txQueueSize) + { + // Curretnly ignoring rxQueueSize + // transmitBufferLength = txQueueSize; + BleSerial::begin(deviceName.c_str()); + return true; + } + + void disconnect() + { + Server->disconnect(Server->getConnId()); + } + + void end() + { + BleSerial::end(); + } + + esp_err_t register_callback(esp_spp_cb_t * callback) + { + connectionCallback = callback; + return ESP_OK; + } + + void setTimeout(unsigned long timeout) + { + BleSerial::setTimeout(timeout); + } + + int available() + { + return BleSerial::available(); + } + + size_t readBytes(uint8_t *buffer, size_t bufferSize) + { + return BleSerial::readBytes(buffer, bufferSize); + } + + bool isCongested() + { + // not currently supported in this implementation + return false; + } + + size_t write(const uint8_t *buffer, size_t size) + { + return BleSerial::write(buffer, size); + } + + void flush() + { + BleSerial::flush(); + } + + // override BLEServerCallbacks + void onConnect(BLEServer *pServer) + { + bleConnected = true; + connectionCallback(ESP_SPP_SRV_OPEN_EVT, nullptr); + } + + void onDisconnect(BLEServer *pServer) + { + bleConnected = false; + connectionCallback(ESP_SPP_CLOSE_EVT, nullptr); + Server->startAdvertising(); + } + + private: + esp_spp_cb_t * connectionCallback; }; diff --git a/Firmware/RTK_Surveyor/menuBluetooth.ino b/Firmware/RTK_Surveyor/menuBluetooth.ino deleted file mode 100644 index e63d93187..000000000 --- a/Firmware/RTK_Surveyor/menuBluetooth.ino +++ /dev/null @@ -1,45 +0,0 @@ -void menuBluetooth() -{ - while (1) - { - Serial.println(); - Serial.println(F("Menu: Blueooth Menu")); - - Serial.println(); - Serial.print(F("Current Bluetooth Mode: ")); - if (settings.enableBLE == true) - Serial.println(F("BLE")); - else - Serial.println(F("Classic")); - - Serial.println(); - Serial.println(F("1) Set Bluetooth Mode to Classic")); - Serial.println(F("2) Set Bluetooth Mode to BLE")); - Serial.println(F("x) Exit")); - - byte incoming = getByteChoice(menuTimeout); - if (incoming == '1') - { - // Restart Bluetooth - bluetoothStop(); - settings.enableBLE = false; - bluetoothStart(); - } - else if (incoming == '2') - { - // restart Bluetooth - bluetoothStop(); - settings.enableBLE = true; - bluetoothStart(); - } - else if (incoming == 'x') - break; - else if (incoming == STATUS_GETBYTE_TIMEOUT) - break; - else - printUnknown(incoming); - } - - while (Serial.available()) Serial.read(); -} - diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index 50f5f5836..480255596 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -51,8 +51,6 @@ void menuMain() Serial.println("5) Configure Logging"); - Serial.println("6) Configure Bluetooth"); - Serial.println("p) Configure Profiles"); #ifdef COMPILE_ESPNOW @@ -83,8 +81,6 @@ void menuMain() menuPorts(); else if (incoming == '5') menuLog(); - else if (incoming == '6') - menuBluetooth(); else if (incoming == 's') menuSystem(); else if (incoming == 'p') diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index ce1e42e26..10559dd37 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -152,6 +152,12 @@ void menuSystem() Serial.printf("m) Set time zone minutes: %d\r\n", settings.timeZoneMinutes); Serial.printf("s) Set time zone seconds: %d\r\n", settings.timeZoneSeconds); + Serial.print(F("b) Set Bluetooth Mode: ")); + if (settings.enableBLE == true) + Serial.println(F("BLE")); + else + Serial.println(F("Classic")); + Serial.println("r) Reset all settings to default"); // Support mode switching @@ -205,6 +211,17 @@ void menuSystem() updateRTC(); } } + else if (incoming == 'b') + { + // Restart Bluetooth + bluetoothStop(); + if (settings.enableBLE == false) + settings.enableBLE = true; + else + settings.enableBLE = false; + bluetoothStart(); + + } else if (incoming == 'r') { Serial.println("\r\nResetting to factory defaults. Press 'y' to confirm:"); diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index cc06b8c60..46983abc9 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -278,8 +278,6 @@ typedef struct { bool enableExternalHardwareEventLogging = false; //Log when INT/TM2 pin goes low bool enableMarksFile = false; //Log marks to the marks file - bool enableBLE = false; - ubxMsg ubxMessages[MAX_UBX_MSG] = //Report rates for all known messages { //NMEA @@ -468,6 +466,7 @@ typedef struct { uint8_t espnowPeers[5][6]; //Max of 5 peers. Contains the MAC addresses (6 bytes) of paired units uint8_t espnowPeerCount; bool enableNtripServerMessageParsing = false; + bool enableBLE = false; } Settings; Settings settings; From bc01e6ec26eba81ddac769bf28f10be6ab08c383 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sun, 14 Aug 2022 21:31:38 -0600 Subject: [PATCH 067/134] Remove incompatible BleSerial code Hoping we get PR #2 accepted so that we can directly compile using workflows. --- Firmware/RTK_Surveyor/bluetoothSelect.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/bluetoothSelect.h b/Firmware/RTK_Surveyor/bluetoothSelect.h index fe7d8b8c1..29780f48b 100644 --- a/Firmware/RTK_Surveyor/bluetoothSelect.h +++ b/Firmware/RTK_Surveyor/bluetoothSelect.h @@ -140,13 +140,13 @@ class BTLESerial: public virtual BTSerialInterface, public BleSerial // override BLEServerCallbacks void onConnect(BLEServer *pServer) { - bleConnected = true; + //bleConnected = true; Removed until PR is accepted connectionCallback(ESP_SPP_SRV_OPEN_EVT, nullptr); } void onDisconnect(BLEServer *pServer) { - bleConnected = false; + //bleConnected = false; Removed until PR is accepted connectionCallback(ESP_SPP_CLOSE_EVT, nullptr); Server->startAdvertising(); } From a732e80ea4bb688f5b1f9c680f252df9e1cf5ea4 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sun, 14 Aug 2022 22:18:09 -0600 Subject: [PATCH 068/134] Update compile-rc.yml --- .github/workflows/compile-rc.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/compile-rc.yml b/.github/workflows/compile-rc.yml index b51df06a0..308cdbbfd 100644 --- a/.github/workflows/compile-rc.yml +++ b/.github/workflows/compile-rc.yml @@ -46,7 +46,8 @@ jobs: https://github.com/sparkfun/SparkFun_LIS2DH12_Arduino_Library.git https://github.com/bblanchon/ArduinoJson.git https://github.com/knolleary/pubsubclient.git - + https://github.com/avinabmalla/ESP32_BleSerial.git + - name: Compile Sketch run: arduino-cli compile --fqbn esp32:esp32:esp32 ./Firmware/RTK_Surveyor/RTK_Surveyor.ino --build-property build.partitions=partitions From b28cffd7bb4c13fcd60ca6ae7c48fc2105c89a1d Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 17 Aug 2022 16:33:28 -0600 Subject: [PATCH 069/134] Return to built-in BluetoothSerial library. Congestion testing was causing problems. The current library works well at 10Hz. --- Firmware/RTK_Surveyor/Bluetooth.ino | 5 +- Firmware/RTK_Surveyor/bluetoothSelect.h | 19 +- .../src/BluetoothSerial/BTAddress.cpp | 96 -- .../src/BluetoothSerial/BTAddress.h | 36 - .../src/BluetoothSerial/BTAdvertisedDevice.h | 65 -- .../BluetoothSerial/BTAdvertisedDeviceSet.cpp | 78 -- .../RTK_Surveyor/src/BluetoothSerial/BTScan.h | 42 - .../src/BluetoothSerial/BTScanResultsSet.cpp | 95 -- .../src/BluetoothSerial/BluetoothSerial.cpp | 1040 ----------------- .../src/BluetoothSerial/BluetoothSerial.h | 90 -- 10 files changed, 13 insertions(+), 1553 deletions(-) delete mode 100644 Firmware/RTK_Surveyor/src/BluetoothSerial/BTAddress.cpp delete mode 100644 Firmware/RTK_Surveyor/src/BluetoothSerial/BTAddress.h delete mode 100644 Firmware/RTK_Surveyor/src/BluetoothSerial/BTAdvertisedDevice.h delete mode 100644 Firmware/RTK_Surveyor/src/BluetoothSerial/BTAdvertisedDeviceSet.cpp delete mode 100644 Firmware/RTK_Surveyor/src/BluetoothSerial/BTScan.h delete mode 100644 Firmware/RTK_Surveyor/src/BluetoothSerial/BTScanResultsSet.cpp delete mode 100644 Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp delete mode 100644 Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.h diff --git a/Firmware/RTK_Surveyor/Bluetooth.ino b/Firmware/RTK_Surveyor/Bluetooth.ino index 7a8359590..408d13eb3 100644 --- a/Firmware/RTK_Surveyor/Bluetooth.ino +++ b/Firmware/RTK_Surveyor/Bluetooth.ino @@ -73,7 +73,8 @@ byte bluetoothGetState() bool bluetoothIsCongested() { #ifdef COMPILE_BT - return bluetoothSerial->isCongested(); + //return bluetoothSerial->isCongested(); + return false; #else //COMPILE_BT return false; #endif //COMPILE_BT @@ -121,7 +122,7 @@ void bluetoothStart() else bluetoothSerial = new BTClassicSerial(); - if (bluetoothSerial->begin(deviceName, false, settings.sppRxQueueSize, settings.sppTxQueueSize) == false) //localName, isMaster, rxBufferSize, txBufferSize + if (bluetoothSerial->begin(deviceName) == false) { Serial.println("An error occurred initializing Bluetooth"); diff --git a/Firmware/RTK_Surveyor/bluetoothSelect.h b/Firmware/RTK_Surveyor/bluetoothSelect.h index 29780f48b..decd4d855 100644 --- a/Firmware/RTK_Surveyor/bluetoothSelect.h +++ b/Firmware/RTK_Surveyor/bluetoothSelect.h @@ -1,12 +1,12 @@ #ifdef COMPILE_BT -#include "src/BluetoothSerial/BluetoothSerial.h" +#include "BluetoothSerial.h" #include // Click here to get the library: http://librarymanager/All#ESP32_BleSerial by Avinab Malla class BTSerialInterface { public: - virtual bool begin(String deviceName, bool isMaster, uint16_t rxQueueSize, uint16_t txQueueSize) = 0; + virtual bool begin(String deviceName) = 0; virtual void disconnect() = 0; virtual void end() = 0; virtual esp_err_t register_callback(esp_spp_cb_t * callback) = 0; @@ -15,7 +15,7 @@ class BTSerialInterface virtual int available() = 0; virtual size_t readBytes(uint8_t *buffer, size_t bufferSize) = 0; - virtual bool isCongested() = 0; + //virtual bool isCongested() = 0; virtual size_t write(const uint8_t *buffer, size_t size) = 0; virtual void flush() = 0; }; @@ -26,9 +26,9 @@ class BTClassicSerial : public virtual BTSerialInterface, public BluetoothSerial // Everything is already implemented in BluetoothSerial since the code was // originally written using that class public: - bool begin(String deviceName, bool isMaster, uint16_t rxQueueSize, uint16_t txQueueSize) + bool begin(String deviceName) { - return BluetoothSerial::begin(deviceName, isMaster, rxQueueSize, txQueueSize); + return BluetoothSerial::begin(deviceName); } void disconnect() @@ -63,7 +63,10 @@ class BTClassicSerial : public virtual BTSerialInterface, public BluetoothSerial bool isCongested() { - return BluetoothSerial::isCongested(); + // Removed congestion testing in v2.4 + // TODO Remove settings and checking + return(false); + //return BluetoothSerial::isCongested(); } size_t write(const uint8_t *buffer, size_t size) @@ -82,10 +85,8 @@ class BTLESerial: public virtual BTSerialInterface, public BleSerial { public: // Missing from BleSerial - bool begin(String deviceName, bool isMaster, uint16_t rxQueueSuze, uint16_t txQueueSize) + bool begin(String deviceName) { - // Curretnly ignoring rxQueueSize - // transmitBufferLength = txQueueSize; BleSerial::begin(deviceName.c_str()); return true; } diff --git a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAddress.cpp b/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAddress.cpp deleted file mode 100644 index 7ef1eb1a8..000000000 --- a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAddress.cpp +++ /dev/null @@ -1,96 +0,0 @@ -/* - * BTAddress.cpp - * - * Created on: Jul 2, 2017 - * Author: kolban - * Ported on: Feb 5, 2021 - * Author: Thomas M. (ArcticSnowSky) - */ -#include "sdkconfig.h" -#if defined(CONFIG_BT_ENABLED) && defined(CONFIG_BLUEDROID_ENABLED) - -#include "BTAddress.h" -#include -#include -#include -#include -#include -#include -#ifdef ARDUINO_ARCH_ESP32 -#include "esp32-hal-log.h" -#endif - - -/** - * @brief Create an address from the native ESP32 representation. - * @param [in] address The native representation. - */ -BTAddress::BTAddress(esp_bd_addr_t address) { - memcpy(m_address, address, ESP_BD_ADDR_LEN); -} // BTAddress - - -/** - * @brief Create an address from a hex string - * - * A hex string is of the format: - * ``` - * 00:00:00:00:00:00 - * ``` - * which is 17 characters in length. - * - * @param [in] stringAddress The hex representation of the address. - */ -BTAddress::BTAddress(std::string stringAddress) { - if (stringAddress.length() != 17) return; - - int data[6]; - sscanf(stringAddress.c_str(), "%x:%x:%x:%x:%x:%x", &data[0], &data[1], &data[2], &data[3], &data[4], &data[5]); - m_address[0] = (uint8_t) data[0]; - m_address[1] = (uint8_t) data[1]; - m_address[2] = (uint8_t) data[2]; - m_address[3] = (uint8_t) data[3]; - m_address[4] = (uint8_t) data[4]; - m_address[5] = (uint8_t) data[5]; -} // BTAddress - - -/** - * @brief Determine if this address equals another. - * @param [in] otherAddress The other address to compare against. - * @return True if the addresses are equal. - */ -bool BTAddress::equals(BTAddress otherAddress) { - return memcmp(otherAddress.getNative(), m_address, 6) == 0; -} // equals - - -/** - * @brief Return the native representation of the address. - * @return The native representation of the address. - */ -esp_bd_addr_t *BTAddress::getNative() { - return &m_address; -} // getNative - - -/** - * @brief Convert a BT address to a string. - * - * A string representation of an address is in the format: - * - * ``` - * xx:xx:xx:xx:xx:xx - * ``` - * - * @return The string representation of the address. - */ -std::string BTAddress::toString() { - auto size = 18; - char *res = (char*)malloc(size); - snprintf(res, size, "%02x:%02x:%02x:%02x:%02x:%02x", m_address[0], m_address[1], m_address[2], m_address[3], m_address[4], m_address[5]); - std::string ret(res); - free(res); - return ret; -} // toString -#endif diff --git a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAddress.h b/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAddress.h deleted file mode 100644 index 6213d01fd..000000000 --- a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAddress.h +++ /dev/null @@ -1,36 +0,0 @@ -/* - * BTAddress.h - * - * Created on: Jul 2, 2017 - * Author: kolban - * Ported on: Feb 5, 2021 - * Author: Thomas M. (ArcticSnowSky) - */ - -#ifndef COMPONENTS_CPP_UTILS_BTADDRESS_H_ -#define COMPONENTS_CPP_UTILS_BTADDRESS_H_ -#include "sdkconfig.h" -#if defined(CONFIG_BT_ENABLED) && defined(CONFIG_BLUEDROID_ENABLED) -#include // ESP32 BT -#include - - -/** - * @brief A %BT device address. - * - * Every %BT device has a unique address which can be used to identify it and form connections. - */ -class BTAddress { -public: - BTAddress(esp_bd_addr_t address); - BTAddress(std::string stringAddress); - bool equals(BTAddress otherAddress); - esp_bd_addr_t* getNative(); - std::string toString(); - -private: - esp_bd_addr_t m_address; -}; - -#endif /* CONFIG_BT_ENABLED */ -#endif /* COMPONENTS_CPP_UTILS_BTADDRESS_H_ */ diff --git a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAdvertisedDevice.h b/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAdvertisedDevice.h deleted file mode 100644 index 07e93622e..000000000 --- a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAdvertisedDevice.h +++ /dev/null @@ -1,65 +0,0 @@ -/* - * BTAdvertisedDevice.h - * - * Created on: Feb 5, 2021 - * Author: Thomas M. (ArcticSnowSky) - */ - -#ifndef __BTADVERTISEDDEVICE_H__ -#define __BTADVERTISEDDEVICE_H__ - -#include "BTAddress.h" - - -class BTAdvertisedDevice { -public: - virtual ~BTAdvertisedDevice() = default; - - virtual BTAddress getAddress(); - virtual uint32_t getCOD(); - virtual std::string getName(); - virtual int8_t getRSSI(); - - - virtual bool haveCOD(); - virtual bool haveName(); - virtual bool haveRSSI(); - - virtual std::string toString(); -}; - -class BTAdvertisedDeviceSet : public virtual BTAdvertisedDevice { -public: - BTAdvertisedDeviceSet(); - //~BTAdvertisedDeviceSet() = default; - - - BTAddress getAddress(); - uint32_t getCOD(); - std::string getName(); - int8_t getRSSI(); - - - bool haveCOD(); - bool haveName(); - bool haveRSSI(); - - std::string toString(); - - void setAddress(BTAddress address); - void setCOD(uint32_t cod); - void setName(std::string name); - void setRSSI(int8_t rssi); - - bool m_haveCOD; - bool m_haveName; - bool m_haveRSSI; - - - BTAddress m_address = BTAddress((uint8_t*)"\0\0\0\0\0\0"); - uint32_t m_cod; - std::string m_name; - int8_t m_rssi; -}; - -#endif \ No newline at end of file diff --git a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAdvertisedDeviceSet.cpp b/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAdvertisedDeviceSet.cpp deleted file mode 100644 index c8f28e9c3..000000000 --- a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTAdvertisedDeviceSet.cpp +++ /dev/null @@ -1,78 +0,0 @@ -/* - * BTAdvertisedDeviceSet.cpp - * - * Created on: Feb 5, 2021 - * Author: Thomas M. (ArcticSnowSky) - */ - -#include "sdkconfig.h" -#if defined(CONFIG_BT_ENABLED) && defined(CONFIG_BLUEDROID_ENABLED) - -//#include - -#include "BTAdvertisedDevice.h" -//#include "BTScan.h" - - -BTAdvertisedDeviceSet::BTAdvertisedDeviceSet() { - m_cod = 0; - m_name = ""; - m_rssi = 0; - - m_haveCOD = false; - m_haveName = false; - m_haveRSSI = false; -} // BTAdvertisedDeviceSet - -BTAddress BTAdvertisedDeviceSet::getAddress() { return m_address; } -uint32_t BTAdvertisedDeviceSet::getCOD() { return m_cod; } -std::string BTAdvertisedDeviceSet::getName() { return m_name; } -int8_t BTAdvertisedDeviceSet::getRSSI() { return m_rssi; } - - -bool BTAdvertisedDeviceSet::haveCOD() { return m_haveCOD; } -bool BTAdvertisedDeviceSet::haveName() { return m_haveName; } -bool BTAdvertisedDeviceSet::haveRSSI() { return m_haveRSSI; } - -/** - * @brief Create a string representation of this device. - * @return A string representation of this device. - */ -std::string BTAdvertisedDeviceSet::toString() { - std::string res = "Name: " + getName() + ", Address: " + getAddress().toString(); - if (haveCOD()) { - char val[6]; - snprintf(val, sizeof(val), "%d", getCOD()); - res += ", cod: "; - res += val; - } - if (haveRSSI()) { - char val[6]; - snprintf(val, sizeof(val), "%d", (int8_t)getRSSI()); - res += ", rssi: "; - res += val; - } - return res; -} // toString - - -void BTAdvertisedDeviceSet::setAddress(BTAddress address) { - m_address = address; -} - -void BTAdvertisedDeviceSet::setCOD(uint32_t cod) { - m_cod = cod; - m_haveCOD = true; -} - -void BTAdvertisedDeviceSet::setName(std::string name) { - m_name = name; - m_haveName = true; -} - -void BTAdvertisedDeviceSet::setRSSI(int8_t rssi) { - m_rssi = rssi; - m_haveRSSI = true; -} - -#endif /* CONFIG_BT_ENABLED */ diff --git a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTScan.h b/Firmware/RTK_Surveyor/src/BluetoothSerial/BTScan.h deleted file mode 100644 index 3650d4162..000000000 --- a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTScan.h +++ /dev/null @@ -1,42 +0,0 @@ -/* - * BTScan.h - * - * Created on: Feb 5, 2021 - * Author: Thomas M. (ArcticSnowSky) - */ - -#ifndef __BTSCAN_H__ -#define __BTSCAN_H__ - -#include -#include -#include -#include "BTAddress.h" -#include "BTAdvertisedDevice.h" - -class BTAdvertisedDevice; -class BTAdvertisedDeviceSet; - - -class BTScanResults { -public: - virtual ~BTScanResults() = default; - - virtual void dump(Print *print = nullptr); - virtual int getCount(); - virtual BTAdvertisedDevice* getDevice(uint32_t i); -}; - -class BTScanResultsSet : public BTScanResults { -public: - void dump(Print *print = nullptr); - int getCount(); - BTAdvertisedDevice* getDevice(uint32_t i); - - bool add(BTAdvertisedDeviceSet advertisedDevice, bool unique = true); - void clear(); - - std::map m_vectorAdvertisedDevices; -}; - -#endif \ No newline at end of file diff --git a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTScanResultsSet.cpp b/Firmware/RTK_Surveyor/src/BluetoothSerial/BTScanResultsSet.cpp deleted file mode 100644 index 79d23e463..000000000 --- a/Firmware/RTK_Surveyor/src/BluetoothSerial/BTScanResultsSet.cpp +++ /dev/null @@ -1,95 +0,0 @@ -/* - * BTScanResultsSet.cpp - * - * Created on: Feb 5, 2021 - * Author: Thomas M. (ArcticSnowSky) - */ - -#include "sdkconfig.h" -#if defined(CONFIG_BT_ENABLED) && defined(CONFIG_BLUEDROID_ENABLED) - - -#include - -#include "BTAdvertisedDevice.h" -#include "BTScan.h" -//#include "GeneralUtils.h" -#include "esp32-hal-log.h" - - -class BTAdvertisedDevice; - -/** - * @brief Dump the scan results to the log. - */ -void BTScanResultsSet::dump(Print *print) { - int cnt = getCount(); - if (print == nullptr) { - log_v(">> Dump scan results : %d", cnt); - for (int i=0; i < cnt; i++) { - BTAdvertisedDevice* dev = getDevice(i); - if (dev) - log_d("- %d: %s\n", i+1, dev->toString().c_str()); - else - log_d("- %d is null\n", i+1); - } - log_v("-- dump finished --"); - } else { - print->printf(">> Dump scan results: %d\n", cnt); - for (int i=0; i < cnt; i++) { - BTAdvertisedDevice* dev = getDevice(i); - if (dev) - print->printf("- %d: %s\n", i+1, dev->toString().c_str()); - else - print->printf("- %d is null\n", i+1); - } - print->println("-- Dump finished --"); - } -} // dump - - -/** - * @brief Return the count of devices found in the last scan. - * @return The number of devices found in the last scan. - */ -int BTScanResultsSet::getCount() { - return m_vectorAdvertisedDevices.size(); -} // getCount - - -/** - * @brief Return the specified device at the given index. - * The index should be between 0 and getCount()-1. - * @param [in] i The index of the device. - * @return The device at the specified index. - */ -BTAdvertisedDevice* BTScanResultsSet::getDevice(uint32_t i) { - if (i < 0) - return nullptr; - - uint32_t x = 0; - BTAdvertisedDeviceSet* pDev = &m_vectorAdvertisedDevices.begin()->second; - for (auto it = m_vectorAdvertisedDevices.begin(); it != m_vectorAdvertisedDevices.end(); it++) { - pDev = &it->second; - if (x==i) break; - x++; - } - return x==i ? pDev : nullptr; -} - -void BTScanResultsSet::clear() { - //for(auto _dev : m_vectorAdvertisedDevices) - // delete _dev.second; - m_vectorAdvertisedDevices.clear(); -} - -bool BTScanResultsSet::add(BTAdvertisedDeviceSet advertisedDevice, bool unique) { - std::string key = advertisedDevice.getAddress().toString(); - if (!unique || m_vectorAdvertisedDevices.count(key) == 0) { - m_vectorAdvertisedDevices.insert(std::pair(key, advertisedDevice)); - return true; - } else - return false; -} - -#endif \ No newline at end of file diff --git a/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp b/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp deleted file mode 100644 index ab70d3024..000000000 --- a/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.cpp +++ /dev/null @@ -1,1040 +0,0 @@ -// Copyright 2018 Evandro Luis Copercini -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "sdkconfig.h" -#include -#include -#include -#include -#include "freertos/FreeRTOS.h" -#include "freertos/task.h" - - -#if defined(CONFIG_BT_ENABLED) && defined(CONFIG_BLUEDROID_ENABLED) - -#ifdef ARDUINO_ARCH_ESP32 -#include "esp32-hal-log.h" -#endif - -#include "BluetoothSerial.h" - -#include "esp_bt.h" -#include "esp_bt_main.h" -#include "esp_gap_bt_api.h" -#include "esp_bt_device.h" -#include "esp_spp_api.h" -#include - -#include "esp32-hal-log.h" - -const char * _spp_server_name = "ESP32SPP"; - -//Now passed in during begin() -//#define RX_QUEUE_SIZE 512 //Original -//#define TX_QUEUE_SIZE 32 - -#define SPP_TX_QUEUE_TIMEOUT 1000 -#define SPP_TX_DONE_TIMEOUT 1000 -#define SPP_CONGESTED_TIMEOUT 1000 - -static uint32_t _spp_client = 0; -static xQueueHandle _spp_rx_queue = NULL; -static xQueueHandle _spp_tx_queue = NULL; -static SemaphoreHandle_t _spp_tx_done = NULL; -static TaskHandle_t _spp_task_handle = NULL; -static EventGroupHandle_t _spp_event_group = NULL; -static EventGroupHandle_t _bt_event_group = NULL; -static boolean secondConnectionAttempt; -static esp_spp_cb_t * custom_spp_callback = NULL; -static BluetoothSerialDataCb custom_data_callback = NULL; -static esp_bd_addr_t current_bd_addr; -static ConfirmRequestCb confirm_request_callback = NULL; -static AuthCompleteCb auth_complete_callback = NULL; - -#define INQ_LEN 0x10 -#define INQ_NUM_RSPS 20 -#define READY_TIMEOUT (10 * 1000) -#define SCAN_TIMEOUT (INQ_LEN * 2 * 1000) -static esp_bd_addr_t _peer_bd_addr; -static char _remote_name[ESP_BT_GAP_MAX_BDNAME_LEN + 1]; -static bool _isRemoteAddressSet; -static bool _isMaster; -static esp_bt_pin_code_t _pin_code; -static int _pin_len; -static bool _isPinSet; -static bool _enableSSP; - -static BTScanResultsSet scanResults; -static BTAdvertisedDeviceCb advertisedDeviceCb = nullptr; - -#define SPP_RUNNING 0x01 -#define SPP_CONNECTED 0x02 -#define SPP_CONGESTED 0x04 -#define SPP_DISCONNECTED 0x08 - -#define BT_DISCOVERY_RUNNING 0x01 -#define BT_DISCOVERY_COMPLETED 0x02 - - -typedef struct { - size_t len; - uint8_t data[]; -} spp_packet_t; - -#if (ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_INFO) -static char *bda2str(esp_bd_addr_t bda, char *str, size_t size) -{ - if (bda == NULL || str == NULL || size < 18) { - return NULL; - } - - uint8_t *p = bda; - sprintf(str, "%02x:%02x:%02x:%02x:%02x:%02x", - p[0], p[1], p[2], p[3], p[4], p[5]); - return str; -} -#endif - -static bool get_name_from_eir(uint8_t *eir, char *bdname, uint8_t *bdname_len) -{ - if (!eir || !bdname || !bdname_len) { - return false; - } - - uint8_t *rmt_bdname, rmt_bdname_len; - *bdname = *bdname_len = rmt_bdname_len = 0; - - rmt_bdname = esp_bt_gap_resolve_eir_data(eir, ESP_BT_EIR_TYPE_CMPL_LOCAL_NAME, &rmt_bdname_len); - if (!rmt_bdname) { - rmt_bdname = esp_bt_gap_resolve_eir_data(eir, ESP_BT_EIR_TYPE_SHORT_LOCAL_NAME, &rmt_bdname_len); - } - if (rmt_bdname) { - rmt_bdname_len = rmt_bdname_len > ESP_BT_GAP_MAX_BDNAME_LEN ? ESP_BT_GAP_MAX_BDNAME_LEN : rmt_bdname_len; - memcpy(bdname, rmt_bdname, rmt_bdname_len); - bdname[rmt_bdname_len] = 0; - *bdname_len = rmt_bdname_len; - return true; - } - return false; -} - -static bool btSetPin() { - esp_bt_pin_type_t pin_type; - if (_isPinSet) { - if (_pin_len) { - log_i("pin set"); - pin_type = ESP_BT_PIN_TYPE_FIXED; - } else { - _isPinSet = false; - log_i("pin reset"); - pin_type = ESP_BT_PIN_TYPE_VARIABLE; // pin_code would be ignored (default) - } - return (esp_bt_gap_set_pin(pin_type, _pin_len, _pin_code) == ESP_OK); - } - return false; -} - -static esp_err_t _spp_queue_packet(uint8_t *data, size_t len){ - if(!data || !len){ - log_w("No data provided"); - return ESP_OK; - } - spp_packet_t * packet = (spp_packet_t*)malloc(sizeof(spp_packet_t) + len); - if(!packet){ - log_e("SPP TX Packet Malloc Failed!"); - return ESP_FAIL; - } - packet->len = len; - memcpy(packet->data, data, len); - if (!_spp_tx_queue || xQueueSend(_spp_tx_queue, &packet, SPP_TX_QUEUE_TIMEOUT) != pdPASS) { - log_e("SPP TX Queue Send Failed!"); - free(packet); - return ESP_FAIL; - } - return ESP_OK; -} - -//SPP_TX_MAX seems to default to a lower amount (330) until there is congestion it then -//tries to catch up but at 330, it cannot and the heap begins to take the hit. -//Increasing the max to 2048 we see normal verbose xfers of 512 until congestion -//when it increases briefly to 2048 then returns to 512 with no heap hit. -//The rate at which we congest is dependant on how much we are attempting to TX and -//how much is coming in RX from the phone. -//At ~25kBps heap lowest point is 100k and stable -//At ~50kBps heap lowest point is ~78k and stable -//Above 50kbps it becomes unstable - -//const uint16_t SPP_TX_MAX = 330; //Original -const uint16_t SPP_TX_MAX = 1024*4; //Should match the SERIAL_SIZE_RX buffer size in RTK_Surveyor.ino - -/* -During ESP Now development the hardware got into a very bad state and Bluetooth was acting very -oddly. Eventually, WiFi would not connect (Reason: 202 - AUTH_FAIL) even using stock examples. -The solution was, unexplicably, a full flash erase. Everything worked after that. -*/ - -static uint8_t _spp_tx_buffer[SPP_TX_MAX]; -static uint16_t _spp_tx_buffer_len = 0; - -static bool _spp_send_buffer(){ - if((xEventGroupWaitBits(_spp_event_group, SPP_CONGESTED, pdFALSE, pdTRUE, SPP_CONGESTED_TIMEOUT) & SPP_CONGESTED) != 0){ - if(!_spp_client){ - log_v("SPP Client Gone!"); - return false; - } - log_v("SPP Write %u", _spp_tx_buffer_len); - esp_err_t err = esp_spp_write(_spp_client, _spp_tx_buffer_len, _spp_tx_buffer); - if(err != ESP_OK){ - log_e("SPP Write Failed! [0x%X]", err); - return false; - } - _spp_tx_buffer_len = 0; - if(xSemaphoreTake(_spp_tx_done, SPP_TX_DONE_TIMEOUT) != pdTRUE){ - log_e("SPP Ack Failed!"); - return false; - } - return true; - } - log_e("SPP Write Congested!"); - return false; -} - -static void _spp_tx_task(void * arg){ - spp_packet_t *packet = NULL; - size_t len = 0, to_send = 0; - uint8_t * data = NULL; - for (;;) { - if(_spp_tx_queue && xQueueReceive(_spp_tx_queue, &packet, portMAX_DELAY) == pdTRUE && packet){ - if(packet->len <= (SPP_TX_MAX - _spp_tx_buffer_len)){ - memcpy(_spp_tx_buffer+_spp_tx_buffer_len, packet->data, packet->len); - _spp_tx_buffer_len+=packet->len; - free(packet); - packet = NULL; - if(SPP_TX_MAX == _spp_tx_buffer_len || uxQueueMessagesWaiting(_spp_tx_queue) == 0){ - _spp_send_buffer(); - } - } else { - len = packet->len; - data = packet->data; - to_send = SPP_TX_MAX - _spp_tx_buffer_len; - memcpy(_spp_tx_buffer+_spp_tx_buffer_len, data, to_send); - _spp_tx_buffer_len = SPP_TX_MAX; - data += to_send; - len -= to_send; - if(!_spp_send_buffer()){ - len = 0; - } - while(len >= SPP_TX_MAX){ - memcpy(_spp_tx_buffer, data, SPP_TX_MAX); - _spp_tx_buffer_len = SPP_TX_MAX; - data += SPP_TX_MAX; - len -= SPP_TX_MAX; - if(!_spp_send_buffer()){ - len = 0; - break; - } - } - if(len){ - memcpy(_spp_tx_buffer, data, len); - _spp_tx_buffer_len += len; - if(uxQueueMessagesWaiting(_spp_tx_queue) == 0){ - _spp_send_buffer(); - } - } - free(packet); - packet = NULL; - } - } else { - log_e("Something went horribly wrong"); - } - } - vTaskDelete(NULL); - _spp_task_handle = NULL; -} - -static void esp_spp_cb(esp_spp_cb_event_t event, esp_spp_cb_param_t *param) -{ - switch (event) - { - case ESP_SPP_INIT_EVT: - log_i("ESP_SPP_INIT_EVT"); -#ifdef ESP_IDF_VERSION_MAJOR - esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); -#else - esp_bt_gap_set_scan_mode(ESP_BT_SCAN_MODE_CONNECTABLE_DISCOVERABLE); -#endif - if (!_isMaster) { - log_i("ESP_SPP_INIT_EVT: slave: start"); - esp_spp_start_srv(ESP_SPP_SEC_NONE, ESP_SPP_ROLE_SLAVE, 0, _spp_server_name); - } - xEventGroupSetBits(_spp_event_group, SPP_RUNNING); - break; - - case ESP_SPP_SRV_OPEN_EVT://Server connection open - if (param->srv_open.status == ESP_SPP_SUCCESS) { - log_i("ESP_SPP_SRV_OPEN_EVT: %u", _spp_client); - if (!_spp_client){ - _spp_client = param->srv_open.handle; - _spp_tx_buffer_len = 0; - } else { - secondConnectionAttempt = true; - esp_spp_disconnect(param->srv_open.handle); - } - xEventGroupClearBits(_spp_event_group, SPP_DISCONNECTED); - xEventGroupSetBits(_spp_event_group, SPP_CONNECTED); - } else { - log_e("ESP_SPP_SRV_OPEN_EVT Failed!, status:%d", param->srv_open.status); - } - break; - - case ESP_SPP_CLOSE_EVT://Client connection closed - if ((param->close.async == false && param->close.status == ESP_SPP_SUCCESS) || param->close.async) { - log_i("ESP_SPP_CLOSE_EVT: %u", secondConnectionAttempt); - if(secondConnectionAttempt) { - secondConnectionAttempt = false; - } else { - _spp_client = 0; - xEventGroupSetBits(_spp_event_group, SPP_DISCONNECTED); - xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); - } - xEventGroupClearBits(_spp_event_group, SPP_CONNECTED); - } else { - log_e("ESP_SPP_CLOSE_EVT failed!, status:%d", param->close.status); - } - break; - - case ESP_SPP_CONG_EVT://connection congestion status changed - if(param->cong.cong){ - xEventGroupClearBits(_spp_event_group, SPP_CONGESTED); - } else { - xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); - } - log_v("ESP_SPP_CONG_EVT: %s", param->cong.cong?"CONGESTED":"FREE"); - break; - - case ESP_SPP_WRITE_EVT://write operation completed - if (param->write.status == ESP_SPP_SUCCESS) { - if(param->write.cong){ - xEventGroupClearBits(_spp_event_group, SPP_CONGESTED); - } - log_v("ESP_SPP_WRITE_EVT: %u %s", param->write.len, param->write.cong?"CONGESTED":""); - } else { - log_e("ESP_SPP_WRITE_EVT failed!, status:%d", param->write.status); - } - xSemaphoreGive(_spp_tx_done);//we can try to send another packet - break; - - case ESP_SPP_DATA_IND_EVT://connection received data - log_v("ESP_SPP_DATA_IND_EVT len=%d handle=%d", param->data_ind.len, param->data_ind.handle); - //esp_log_buffer_hex("",param->data_ind.data,param->data_ind.len); //for low level debug - //ets_printf("r:%u\n", param->data_ind.len); - - if(custom_data_callback){ - custom_data_callback(param->data_ind.data, param->data_ind.len); - } else if (_spp_rx_queue != NULL){ - for (int i = 0; i < param->data_ind.len; i++){ - if(xQueueSend(_spp_rx_queue, param->data_ind.data + i, (TickType_t)0) != pdTRUE){ - log_e("RX Full! Discarding %u bytes", param->data_ind.len - i); - break; - } - } - } - break; - - case ESP_SPP_DISCOVERY_COMP_EVT://discovery complete - log_i("ESP_SPP_DISCOVERY_COMP_EVT"); - if (param->disc_comp.status == ESP_SPP_SUCCESS) { - log_i("ESP_SPP_DISCOVERY_COMP_EVT: spp connect to remote"); - esp_spp_connect(ESP_SPP_SEC_AUTHENTICATE, ESP_SPP_ROLE_MASTER, param->disc_comp.scn[0], _peer_bd_addr); - } else { - log_e("ESP_SPP_DISCOVERY_COMP_EVT failed!, status:%d", param->disc_comp.status); - } - break; - - case ESP_SPP_OPEN_EVT://Client connection open - log_i("ESP_SPP_OPEN_EVT"); - if (!_spp_client){ - _spp_client = param->open.handle; - } else { - secondConnectionAttempt = true; - esp_spp_disconnect(param->open.handle); - } - xEventGroupClearBits(_spp_event_group, SPP_DISCONNECTED); - xEventGroupSetBits(_spp_event_group, SPP_CONNECTED); - xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); - break; - - case ESP_SPP_START_EVT://server started - log_i("ESP_SPP_START_EVT"); - break; - - case ESP_SPP_CL_INIT_EVT://client initiated a connection - log_i("ESP_SPP_CL_INIT_EVT"); - break; - - default: - break; - } - if(custom_spp_callback)(*custom_spp_callback)(event, param); -} - -void BluetoothSerial::onData(BluetoothSerialDataCb cb){ - custom_data_callback = cb; -} - -static void esp_bt_gap_cb(esp_bt_gap_cb_event_t event, esp_bt_gap_cb_param_t *param) -{ - switch(event){ - case ESP_BT_GAP_DISC_RES_EVT: { - log_i("ESP_BT_GAP_DISC_RES_EVT"); -#if (ARDUHAL_LOG_LEVEL >= ARDUHAL_LOG_LEVEL_INFO) - char bda_str[18]; - log_i("Scanned device: %s", bda2str(param->disc_res.bda, bda_str, 18)); -#endif - BTAdvertisedDeviceSet advertisedDevice; - uint8_t peer_bdname_len = 0; - char peer_bdname[ESP_BT_GAP_MAX_BDNAME_LEN + 1]; - for (int i = 0; i < param->disc_res.num_prop; i++) { - switch(param->disc_res.prop[i].type) { - case ESP_BT_GAP_DEV_PROP_EIR: - if (get_name_from_eir((uint8_t*)param->disc_res.prop[i].val, peer_bdname, &peer_bdname_len)) { - log_i("ESP_BT_GAP_DISC_RES_EVT : EIR : %s : %d", peer_bdname, peer_bdname_len); - if (strlen(_remote_name) == peer_bdname_len - && strncmp(peer_bdname, _remote_name, peer_bdname_len) == 0) { - log_v("ESP_BT_GAP_DISC_RES_EVT : SPP_START_DISCOVERY_EIR : %s", peer_bdname, peer_bdname_len); - _isRemoteAddressSet = true; - memcpy(_peer_bd_addr, param->disc_res.bda, ESP_BD_ADDR_LEN); - esp_bt_gap_cancel_discovery(); - esp_spp_start_discovery(_peer_bd_addr); - } - } - break; - - case ESP_BT_GAP_DEV_PROP_BDNAME: - peer_bdname_len = param->disc_res.prop[i].len; - memcpy(peer_bdname, param->disc_res.prop[i].val, peer_bdname_len); - peer_bdname_len--; // len includes 0 terminator - log_v("ESP_BT_GAP_DISC_RES_EVT : BDNAME : %s : %d", peer_bdname, peer_bdname_len); - if (strlen(_remote_name) == peer_bdname_len - && strncmp(peer_bdname, _remote_name, peer_bdname_len) == 0) { - log_i("ESP_BT_GAP_DISC_RES_EVT : SPP_START_DISCOVERY_BDNAME : %s", peer_bdname); - _isRemoteAddressSet = true; - memcpy(_peer_bd_addr, param->disc_res.bda, ESP_BD_ADDR_LEN); - esp_bt_gap_cancel_discovery(); - esp_spp_start_discovery(_peer_bd_addr); - } - break; - - case ESP_BT_GAP_DEV_PROP_COD: - log_d("ESP_BT_GAP_DEV_PROP_COD"); - if (param->disc_res.prop[i].len <= sizeof(int)) { - uint32_t cod = 0; - memcpy(&cod, param->disc_res.prop[i].val, param->disc_res.prop[i].len); - advertisedDevice.setCOD(cod); - } else { - log_d("Value size larger than integer"); - } - break; - - case ESP_BT_GAP_DEV_PROP_RSSI: - log_d("ESP_BT_GAP_DEV_PROP_RSSI"); - if (param->disc_res.prop[i].len <= sizeof(int)) { - uint8_t rssi = 0; - memcpy(&rssi, param->disc_res.prop[i].val, param->disc_res.prop[i].len); - advertisedDevice.setRSSI(rssi); - } else { - log_d("Value size larger than integer"); - } - break; - - default: - break; - } - if (_isRemoteAddressSet) - break; - } - if (peer_bdname_len) - advertisedDevice.setName(peer_bdname); - esp_bd_addr_t addr; - memcpy(addr, param->disc_res.bda, ESP_BD_ADDR_LEN); - advertisedDevice.setAddress(BTAddress(addr)); - if (scanResults.add(advertisedDevice) && advertisedDeviceCb) - advertisedDeviceCb(&advertisedDevice); - } - break; - - case ESP_BT_GAP_DISC_STATE_CHANGED_EVT: - log_i("ESP_BT_GAP_DISC_STATE_CHANGED_EVT"); - if (param->disc_st_chg.state == ESP_BT_GAP_DISCOVERY_STOPPED) { - xEventGroupClearBits(_bt_event_group, BT_DISCOVERY_RUNNING); - xEventGroupSetBits(_bt_event_group, BT_DISCOVERY_COMPLETED); - } else { // ESP_BT_GAP_DISCOVERY_STARTED - xEventGroupClearBits(_bt_event_group, BT_DISCOVERY_COMPLETED); - xEventGroupSetBits(_bt_event_group, BT_DISCOVERY_RUNNING); - } - break; - - case ESP_BT_GAP_RMT_SRVCS_EVT: - log_i( "ESP_BT_GAP_RMT_SRVCS_EVT: status = %d, num_uuids = %d", param->rmt_srvcs.stat, param->rmt_srvcs.num_uuids); - break; - - case ESP_BT_GAP_RMT_SRVC_REC_EVT: - log_i("ESP_BT_GAP_RMT_SRVC_REC_EVT: status = %d", param->rmt_srvc_rec.stat); - break; - - case ESP_BT_GAP_AUTH_CMPL_EVT: - if (param->auth_cmpl.stat == ESP_BT_STATUS_SUCCESS) { - log_v("authentication success: %s", param->auth_cmpl.device_name); - if (auth_complete_callback) { - auth_complete_callback(true); - } - } else { - log_e("authentication failed, status:%d", param->auth_cmpl.stat); - if (auth_complete_callback) { - auth_complete_callback(false); - } - } - break; - - case ESP_BT_GAP_PIN_REQ_EVT: - // default pairing pins - log_i("ESP_BT_GAP_PIN_REQ_EVT min_16_digit:%d", param->pin_req.min_16_digit); - if (param->pin_req.min_16_digit) { - log_i("Input pin code: 0000 0000 0000 0000"); - esp_bt_pin_code_t pin_code; - memset(pin_code, '0', ESP_BT_PIN_CODE_LEN); - esp_bt_gap_pin_reply(param->pin_req.bda, true, 16, pin_code); - } else { - log_i("Input pin code: 1234"); - esp_bt_pin_code_t pin_code; - memcpy(pin_code, "1234", 4); - esp_bt_gap_pin_reply(param->pin_req.bda, true, 4, pin_code); - } - break; - - case ESP_BT_GAP_CFM_REQ_EVT: - log_i("ESP_BT_GAP_CFM_REQ_EVT Please compare the numeric value: %d", param->cfm_req.num_val); - if (confirm_request_callback) { - memcpy(current_bd_addr, param->cfm_req.bda, sizeof(esp_bd_addr_t)); - confirm_request_callback(param->cfm_req.num_val); - } - else { - esp_bt_gap_ssp_confirm_reply(param->cfm_req.bda, true); - } - break; - - case ESP_BT_GAP_KEY_NOTIF_EVT: - log_i("ESP_BT_GAP_KEY_NOTIF_EVT passkey:%d", param->key_notif.passkey); - break; - - case ESP_BT_GAP_KEY_REQ_EVT: - log_i("ESP_BT_GAP_KEY_REQ_EVT Please enter passkey!"); - break; - - default: - break; - } -} - -//static bool _init_bt(const char *deviceName) -static bool _init_bt(const char *deviceName, uint16_t rxQueueSize, uint16_t txQueueSize) -{ - if(!_bt_event_group){ - _bt_event_group = xEventGroupCreate(); - if(!_bt_event_group){ - log_e("BT Event Group Create Failed!"); - return false; - } - xEventGroupClearBits(_bt_event_group, 0xFFFFFF); - } - if(!_spp_event_group){ - _spp_event_group = xEventGroupCreate(); - if(!_spp_event_group){ - log_e("SPP Event Group Create Failed!"); - return false; - } - xEventGroupClearBits(_spp_event_group, 0xFFFFFF); - xEventGroupSetBits(_spp_event_group, SPP_CONGESTED); - xEventGroupSetBits(_spp_event_group, SPP_DISCONNECTED); - } - if (_spp_rx_queue == NULL){ - //_spp_rx_queue = xQueueCreate(RX_QUEUE_SIZE, sizeof(uint8_t)); //initialize the queue - _spp_rx_queue = xQueueCreate(rxQueueSize, sizeof(uint8_t)); //initialize the queue - if (_spp_rx_queue == NULL){ - log_e("RX Queue Create Failed"); - return false; - } - } - if (_spp_tx_queue == NULL){ - //_spp_tx_queue = xQueueCreate(TX_QUEUE_SIZE, sizeof(spp_packet_t*)); //initialize the queue - _spp_tx_queue = xQueueCreate(txQueueSize, sizeof(spp_packet_t*)); //initialize the queue - if (_spp_tx_queue == NULL){ - log_e("TX Queue Create Failed"); - return false; - } - } - if(_spp_tx_done == NULL){ - _spp_tx_done = xSemaphoreCreateBinary(); - if (_spp_tx_done == NULL){ - log_e("TX Semaphore Create Failed"); - return false; - } - xSemaphoreTake(_spp_tx_done, 0); - } - - if(!_spp_task_handle){ - xTaskCreatePinnedToCore(_spp_tx_task, "spp_tx", 4096, NULL, 10, &_spp_task_handle, 0); - if(!_spp_task_handle){ - log_e("Network Event Task Start Failed!"); - return false; - } - } - - if (!btStarted() && !btStart()){ - log_e("initialize controller failed"); - return false; - } - - esp_bluedroid_status_t bt_state = esp_bluedroid_get_status(); - if (bt_state == ESP_BLUEDROID_STATUS_UNINITIALIZED){ - if (esp_bluedroid_init()) { - log_e("initialize bluedroid failed"); - return false; - } - } - - if (bt_state != ESP_BLUEDROID_STATUS_ENABLED){ - if (esp_bluedroid_enable()) { - log_e("enable bluedroid failed"); - return false; - } - } - - // Why only master need this? Slave need this during pairing as well -// if (_isMaster && esp_bt_gap_register_callback(esp_bt_gap_cb) != ESP_OK) { - if (esp_bt_gap_register_callback(esp_bt_gap_cb) != ESP_OK) { - log_e("gap register failed"); - return false; - } - - if (esp_spp_register_callback(esp_spp_cb) != ESP_OK){ - log_e("spp register failed"); - return false; - } - - if (esp_spp_init(ESP_SPP_MODE_CB) != ESP_OK){ - log_e("spp init failed"); - return false; - } - - // if (esp_bt_sleep_disable() != ESP_OK){ - // log_e("esp_bt_sleep_disable failed"); - // } - - log_i("device name set"); - esp_bt_dev_set_device_name(deviceName); - - if (_isPinSet) { - btSetPin(); - } - - if (_enableSSP) { - log_i("Simple Secure Pairing"); - esp_bt_sp_param_t param_type = ESP_BT_SP_IOCAP_MODE; - esp_bt_io_cap_t iocap = ESP_BT_IO_CAP_IO; - esp_bt_gap_set_security_param(param_type, &iocap, sizeof(uint8_t)); - } - - // the default BTA_DM_COD_LOUDSPEAKER does not work with the macOS BT stack - esp_bt_cod_t cod; - cod.major = 0b00001; - cod.minor = 0b000100; - cod.service = 0b00000010110; - if (esp_bt_gap_set_cod(cod, ESP_BT_INIT_COD) != ESP_OK) { - log_e("set cod failed"); - return false; - } - return true; -} - -static bool _stop_bt() -{ - if (btStarted()){ - if(_spp_client) - esp_spp_disconnect(_spp_client); - esp_spp_deinit(); - esp_bluedroid_disable(); - esp_bluedroid_deinit(); - btStop(); - } - _spp_client = 0; - if(_spp_task_handle){ - vTaskDelete(_spp_task_handle); - _spp_task_handle = NULL; - } - if(_spp_event_group){ - vEventGroupDelete(_spp_event_group); - _spp_event_group = NULL; - } - if(_spp_rx_queue){ - vQueueDelete(_spp_rx_queue); - //ToDo: clear RX queue when in packet mode - _spp_rx_queue = NULL; - } - if(_spp_tx_queue){ - spp_packet_t *packet = NULL; - while(xQueueReceive(_spp_tx_queue, &packet, 0) == pdTRUE){ - free(packet); - } - vQueueDelete(_spp_tx_queue); - _spp_tx_queue = NULL; - } - if (_spp_tx_done) { - vSemaphoreDelete(_spp_tx_done); - _spp_tx_done = NULL; - } - if (_bt_event_group) { - vEventGroupDelete(_bt_event_group); - _bt_event_group = NULL; - } - return true; -} - -static bool waitForConnect(int timeout) { - TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; - return (xEventGroupWaitBits(_spp_event_group, SPP_CONNECTED, pdFALSE, pdTRUE, xTicksToWait) & SPP_CONNECTED) != 0; -} - -static bool waitForDiscovered(int timeout) { - TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; - return (xEventGroupWaitBits(_spp_event_group, BT_DISCOVERY_COMPLETED, pdFALSE, pdTRUE, xTicksToWait) & BT_DISCOVERY_COMPLETED) != 0; -} - -/* - * Serial Bluetooth Arduino - * - * */ - -BluetoothSerial::BluetoothSerial() -{ - local_name = "ESP32"; //default bluetooth name -} - -BluetoothSerial::~BluetoothSerial(void) -{ - _stop_bt(); -} - -//bool BluetoothSerial::begin(String localName, bool isMaster) -bool BluetoothSerial::begin(String localName, bool isMaster, uint16_t rxQueueSize, uint16_t txQueueSize) -{ - _isMaster = isMaster; - if (localName.length()){ - local_name = localName; - } - //return _init_bt(local_name.c_str()); - return _init_bt(local_name.c_str(), rxQueueSize, txQueueSize); -} - -int BluetoothSerial::available(void) -{ - if (_spp_rx_queue == NULL){ - return 0; - } - return uxQueueMessagesWaiting(_spp_rx_queue); -} - -int BluetoothSerial::peek(void) -{ - uint8_t c; - if (_spp_rx_queue && xQueuePeek(_spp_rx_queue, &c, 0)){ - return c; - } - return -1; -} - -bool BluetoothSerial::hasClient(void) -{ - return _spp_client > 0; -} - -int BluetoothSerial::read(void) -{ - - uint8_t c = 0; - if (_spp_rx_queue && xQueueReceive(_spp_rx_queue, &c, 0)){ - return c; - } - return -1; -} - -size_t BluetoothSerial::write(uint8_t c) -{ - return write(&c, 1); -} - -size_t BluetoothSerial::write(const uint8_t *buffer, size_t size) -{ - if (!_spp_client){ - return 0; - } - return (_spp_queue_packet((uint8_t *)buffer, size) == ESP_OK) ? size : 0; -} - -void BluetoothSerial::flush() -{ - if (_spp_tx_queue != NULL){ - while(uxQueueMessagesWaiting(_spp_tx_queue) > 0){ - delay(100); - } - } -} - -void BluetoothSerial::end() -{ - _stop_bt(); -} - -void BluetoothSerial::onConfirmRequest(ConfirmRequestCb cb) -{ - confirm_request_callback = cb; -} - -void BluetoothSerial::onAuthComplete(AuthCompleteCb cb) -{ - auth_complete_callback = cb; -} - -void BluetoothSerial::confirmReply(boolean confirm) -{ - esp_bt_gap_ssp_confirm_reply(current_bd_addr, confirm); -} - - -esp_err_t BluetoothSerial::register_callback(esp_spp_cb_t * callback) -{ - custom_spp_callback = callback; - return ESP_OK; -} - -//Simple Secure Pairing -void BluetoothSerial::enableSSP() { - _enableSSP = true; -} -/* - * Set default parameters for Legacy Pairing - * Use fixed pin code -*/ -bool BluetoothSerial::setPin(const char *pin) { - bool isEmpty = !(pin && *pin); - if (isEmpty && !_isPinSet) { - return true; // nothing to do - } else if (!isEmpty){ - _pin_len = strlen(pin); - memcpy(_pin_code, pin, _pin_len); - } else { - _pin_len = 0; // resetting pin to none (default) - } - _pin_code[_pin_len] = 0; - _isPinSet = true; - if (isReady(false, READY_TIMEOUT)) { - btSetPin(); - } - return true; -} - -bool BluetoothSerial::connect(String remoteName) -{ - if (!isReady(true, READY_TIMEOUT)) return false; - if (remoteName && remoteName.length() < 1) { - log_e("No remote name is provided"); - return false; - } - disconnect(); - _isRemoteAddressSet = false; - strncpy(_remote_name, remoteName.c_str(), ESP_BT_GAP_MAX_BDNAME_LEN); - _remote_name[ESP_BT_GAP_MAX_BDNAME_LEN] = 0; - log_i("master : remoteName"); - // will first resolve name to address -#ifdef ESP_IDF_VERSION_MAJOR - esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); -#else - esp_bt_gap_set_scan_mode(ESP_BT_SCAN_MODE_CONNECTABLE_DISCOVERABLE); -#endif - if (esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, INQ_LEN, INQ_NUM_RSPS) == ESP_OK) { - return waitForConnect(SCAN_TIMEOUT); - } - return false; -} - -bool BluetoothSerial::connect(uint8_t remoteAddress[]) -{ - if (!isReady(true, READY_TIMEOUT)) return false; - if (!remoteAddress) { - log_e("No remote address is provided"); - return false; - } - disconnect(); - _remote_name[0] = 0; - _isRemoteAddressSet = true; - memcpy(_peer_bd_addr, remoteAddress, ESP_BD_ADDR_LEN); - log_i("master : remoteAddress"); - if (esp_spp_start_discovery(_peer_bd_addr) == ESP_OK) { - return waitForConnect(READY_TIMEOUT); - } - return false; -} - -bool BluetoothSerial::connect() -{ - if (!isReady(true, READY_TIMEOUT)) return false; - if (_isRemoteAddressSet){ - disconnect(); - // use resolved or set address first - log_i("master : remoteAddress"); - if (esp_spp_start_discovery(_peer_bd_addr) == ESP_OK) { - return waitForConnect(READY_TIMEOUT); - } - return false; - } else if (_remote_name[0]) { - disconnect(); - log_i("master : remoteName"); - // will resolve name to address first - it may take a while -#ifdef ESP_IDF_VERSION_MAJOR - esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); -#else - esp_bt_gap_set_scan_mode(ESP_BT_SCAN_MODE_CONNECTABLE_DISCOVERABLE); -#endif - if (esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, INQ_LEN, INQ_NUM_RSPS) == ESP_OK) { - return waitForConnect(SCAN_TIMEOUT); - } - return false; - } - log_e("Neither Remote name nor address was provided"); - return false; -} - -bool BluetoothSerial::disconnect() { - if (_spp_client) { - flush(); - log_i("disconnecting"); - if (esp_spp_disconnect(_spp_client) == ESP_OK) { - TickType_t xTicksToWait = READY_TIMEOUT / portTICK_PERIOD_MS; - return (xEventGroupWaitBits(_spp_event_group, SPP_DISCONNECTED, pdFALSE, pdTRUE, xTicksToWait) & SPP_DISCONNECTED) != 0; - } - } - return false; -} - -bool BluetoothSerial::unpairDevice(uint8_t remoteAddress[]) { - if (isReady(false, READY_TIMEOUT)) { - log_i("removing bonded device"); - return (esp_bt_gap_remove_bond_device(remoteAddress) == ESP_OK); - } - return false; -} - -bool BluetoothSerial::connected(int timeout) { - return waitForConnect(timeout); -} - -bool BluetoothSerial::isReady(bool checkMaster, int timeout) { - if (checkMaster && !_isMaster) { - log_e("Master mode is not active. Call begin(localName, true) to enable Master mode"); - return false; - } - if (!btStarted()) { - log_e("BT is not initialized. Call begin() first"); - return false; - } - TickType_t xTicksToWait = timeout / portTICK_PERIOD_MS; - return (xEventGroupWaitBits(_spp_event_group, SPP_RUNNING, pdFALSE, pdTRUE, xTicksToWait) & SPP_RUNNING) != 0; -} - - -/** - * @brief RemoteName or address are not allowed to be set during discovery - * (otherwhise it might connect automatically and stop discovery) - * @param[in] timeoutMs can range from MIN_INQ_TIME to MAX_INQ_TIME - * @return in case of Error immediately Empty ScanResults. - */ -BTScanResults* BluetoothSerial::discover(int timeoutMs) { - scanResults.clear(); - if (timeoutMs < MIN_INQ_TIME || timeoutMs > MAX_INQ_TIME || strlen(_remote_name) || _isRemoteAddressSet) - return nullptr; - int timeout = timeoutMs / INQ_TIME; - log_i("discover::disconnect"); - disconnect(); - log_i("discovering"); - // will resolve name to address first - it may take a while - esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); - if (esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, timeout, 0) == ESP_OK) { - waitForDiscovered(timeoutMs); - esp_bt_gap_cancel_discovery(); - } - return &scanResults; -} - -/** - * @brief RemoteName or address are not allowed to be set during discovery - * (otherwhise it might connect automatically and stop discovery) - * @param[in] cb called when a [b]new[/b] device has been discovered - * @param[in] timeoutMs can be 0 or range from MIN_INQ_TIME to MAX_INQ_TIME - * - * @return Wheter start was successfull or problems with params - */ -bool BluetoothSerial::discoverAsync(BTAdvertisedDeviceCb cb, int timeoutMs) { - scanResults.clear(); - if (strlen(_remote_name) || _isRemoteAddressSet) - return false; - int timeout = timeoutMs / INQ_TIME; - disconnect(); - advertisedDeviceCb = cb; - log_i("discovering"); - // will resolve name to address first - it may take a while - esp_bt_gap_set_scan_mode(ESP_BT_CONNECTABLE, ESP_BT_GENERAL_DISCOVERABLE); - if (timeout > 0) - return esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, timeout, 0) == ESP_OK; - else return esp_bt_gap_start_discovery(ESP_BT_INQ_MODE_GENERAL_INQUIRY, ESP_BT_GAP_MAX_INQ_LEN, 0) == ESP_OK; -} - -/** @brief Stops the asynchronous discovery and clears the callback */ -void BluetoothSerial::discoverAsyncStop() { - esp_bt_gap_cancel_discovery(); - advertisedDeviceCb = nullptr; -} - -/** @brief Clears scanresult entries */ -void BluetoothSerial::discoverClear() { - scanResults.clear(); -} - -/** @brief Can be used while discovering asynchronously - * Will be returned also on synchronous discovery. - * - * @return BTScanResults contains several information of found devices - */ -BTScanResults* BluetoothSerial::getScanResults() { - return &scanResults; -} - -BluetoothSerial::operator bool() const -{ - return true; -} - -bool BluetoothSerial::isCongested(){ - return(!(xEventGroupGetBits(_spp_event_group) & SPP_CONGESTED)); -} -#endif diff --git a/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.h b/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.h deleted file mode 100644 index 174faf31d..000000000 --- a/Firmware/RTK_Surveyor/src/BluetoothSerial/BluetoothSerial.h +++ /dev/null @@ -1,90 +0,0 @@ -// Copyright 2018 Evandro Luis Copercini -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at - -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#ifndef _BLUETOOTH_SERIAL_H_ -#define _BLUETOOTH_SERIAL_H_ - -#include "sdkconfig.h" - -#if defined(CONFIG_BT_ENABLED) && defined(CONFIG_BLUEDROID_ENABLED) - -#include "Arduino.h" -#include "Stream.h" -#include -#include -#include -#include "BTScan.h" - -typedef std::function BluetoothSerialDataCb; -typedef std::function ConfirmRequestCb; -typedef std::function AuthCompleteCb; -typedef std::function BTAdvertisedDeviceCb; - -class BluetoothSerial: public Stream -{ - public: - - BluetoothSerial(void); - ~BluetoothSerial(void); - - bool begin(String localName=String(), bool isMaster=false, uint16_t rxQueueSize = 512 * 4, uint16_t txQueueSize = 512); - bool begin(unsigned long baud){//compatibility - return begin(); - } - int available(void); - int peek(void); - bool hasClient(void); - int read(void); - size_t write(uint8_t c); - size_t write(const uint8_t *buffer, size_t size); - void flush(); - void end(void); - void onData(BluetoothSerialDataCb cb); - esp_err_t register_callback(esp_spp_cb_t * callback); - - void onConfirmRequest(ConfirmRequestCb cb); - void onAuthComplete(AuthCompleteCb cb); - void confirmReply(boolean confirm); - - void enableSSP(); - bool setPin(const char *pin); - bool connect(String remoteName); - bool connect(uint8_t remoteAddress[]); - bool connect(); - bool connected(int timeout=0); - bool isReady(bool checkMaster=false, int timeout=0); - bool disconnect(); - bool unpairDevice(uint8_t remoteAddress[]); - - BTScanResults* discover(int timeout=0x30*1280); - bool discoverAsync(BTAdvertisedDeviceCb cb, int timeout=0x30*1280); - void discoverAsyncStop(); - void discoverClear(); - BTScanResults* getScanResults(); - - const int INQ_TIME = 1280; // Inquire Time unit 1280 ms - const int MIN_INQ_TIME = (ESP_BT_GAP_MIN_INQ_LEN * INQ_TIME); - const int MAX_INQ_TIME = (ESP_BT_GAP_MAX_INQ_LEN * INQ_TIME); - - operator bool() const; - - bool isCongested(); - private: - String local_name; - -}; - -#endif - -#endif From 4fe6ab9489f6041c81704ba6e998913740810cfe Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 17 Aug 2022 16:49:27 -0600 Subject: [PATCH 070/134] Display hello world --- Firmware/Test Sketches/System_Check/Display.ino | 14 +++++--------- .../Test Sketches/System_Check/System_Check.ino | 6 ++---- 2 files changed, 7 insertions(+), 13 deletions(-) diff --git a/Firmware/Test Sketches/System_Check/Display.ino b/Firmware/Test Sketches/System_Check/Display.ino index 166f91fbb..a54eb8698 100644 --- a/Firmware/Test Sketches/System_Check/Display.ino +++ b/Firmware/Test Sketches/System_Check/Display.ino @@ -26,24 +26,20 @@ void beginDisplay() } } -//Attempt to send to display regardless of its online status -//The I2C bus may allow it even if bus is misbehaving void displayHelloWorld() { - //if (online.display == true) - //{ + if (online.display == true) + { oled.erase(); uint8_t fontHeight = 15; uint8_t yPos = oled.getHeight() / 2 - fontHeight; - printTextCenter("Accel", yPos, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted - printTextCenter("Failed", yPos + fontHeight, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted + printTextCenter("Hello", yPos, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted + printTextCenter("World", yPos + fontHeight, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted oled.display(); - -// delay(displayTime); - //} + } } //Given text, and location, print text center of the screen diff --git a/Firmware/Test Sketches/System_Check/System_Check.ino b/Firmware/Test Sketches/System_Check/System_Check.ino index 7942a4e2d..3e11f1b62 100644 --- a/Firmware/Test Sketches/System_Check/System_Check.ino +++ b/Firmware/Test Sketches/System_Check/System_Check.ino @@ -245,7 +245,7 @@ void setup() Wire.beginTransmission(0x15); //Dummy address int endValue = Wire.endTransmission(); Serial.printf("Response time: %d endValue: %d\n\r", millis() - startTime, endValue); - if(endValue == 2) + if (endValue == 2) online.i2c = true; else if (endValue == 5) Serial.println("It appears something is shorting the I2C lines."); @@ -257,15 +257,13 @@ void setup() beginGNSS(); //Connect to GNSS to get module type beginDisplay(); //Start display first to be able to display any errors + displayHelloWorld(); //Display something beginFuelGauge(); //Configure battery fuel guage monitor } beginSD(); //Test if SD is present - beginDisplay(); //Start display first to be able to display any errors - displayHelloWorld(); //Display something, ignore I2C bus status - menuSystem(); } From 2bd75083c7db55e8fe85bb30d7d80d838405d952 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 17 Aug 2022 16:53:14 -0600 Subject: [PATCH 071/134] Add blinking icon during AP config --- Firmware/RTK_Surveyor/Display.ino | 58 ++++++++++++++++++++----------- 1 file changed, 38 insertions(+), 20 deletions(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 53683b2bb..8640d30b2 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -280,8 +280,8 @@ void updateDisplay() displayWiFiConfigNotStarted(); //Display 'WiFi Config' break; case (STATE_WIFI_CONFIG): - //TODO Remove radio icons from displayWiFi config - icons = displayWiFiConfig(); //Display SSID and IP + iconsRadio = setWiFiIcon(); //Blink WiFi in center + displayWiFiConfig(); //Display SSID and IP break; case (STATE_TEST): paintSystemTest(); @@ -297,11 +297,11 @@ void updateDisplay() //Do nothing. Quick, fall through state. break; case (STATE_KEYS_WIFI_STARTED): - iconsRadio = setRadioIcons(); //Top left + iconsRadio = setWiFiIcon(); //Blink WiFi in center paintGettingKeys(); break; case (STATE_KEYS_WIFI_CONNECTED): - iconsRadio = setRadioIcons(); //Top left + iconsRadio = setWiFiIcon(); //Blink WiFi in center paintGettingKeys(); break; case (STATE_KEYS_WIFI_TIMEOUT): @@ -320,11 +320,11 @@ void updateDisplay() //Do nothing. Quick, fall through state. break; case (STATE_KEYS_PROVISION_WIFI_STARTED): - iconsRadio = setRadioIcons(); //Top left + iconsRadio = setWiFiIcon(); //Blink WiFi in center paintGettingKeys(); break; case (STATE_KEYS_PROVISION_WIFI_CONNECTED): - iconsRadio = setRadioIcons(); //Top left + iconsRadio = setWiFiIcon(); //Blink WiFi in center paintGettingKeys(); break; case (STATE_KEYS_PROVISION_WIFI_TIMEOUT): @@ -1045,6 +1045,37 @@ uint32_t setWiFiIcon_ThreeRadios() return (icons); } +//Bluetooth and ESP Now icons off. WiFi in middle. +//Blink while no clients are connected +uint32_t setWiFiIcon() +{ + uint32_t icons = 0; + + if (online.display == true) + { + if (wifiState == WIFI_CONNECTED) + { + icons |= ICON_WIFI_SYMBOL_3_RIGHT; + } + else + { + //Limit how often we update this spot + if (millis() - thirdRadioSpotTimer > 1000) + { + thirdRadioSpotTimer = millis(); + thirdRadioSpotBlink ^= 1; //Blink this icon + } + + if (thirdRadioSpotBlink == false) + icons |= ICON_BLANK_RIGHT; + else + icons |= ICON_WIFI_SYMBOL_3_RIGHT; + } + } + + return (icons); +} + //Based on system state, turn on the various Rover, Base, Fixed Base icons uint32_t setModeIcon() { @@ -1627,22 +1658,10 @@ void displayWiFiConfigNotStarted() displayMessage("WiFi Config", 0); } -uint32_t displayWiFiConfig() +void displayWiFiConfig() { uint32_t icons; - //Draw the WiFi icon - icons = 0; - if (wifiState == WIFI_NOTCONNECTED) - { - //Blink WiFi icon - blinking_icons ^= ICON_WIFI_SYMBOL_3_RIGHT; - if (blinking_icons & ICON_WIFI_SYMBOL_3_RIGHT) - icons = ICON_WIFI_SYMBOL_3_RIGHT; - } - else if (wifiState == WIFI_CONNECTED) - icons = ICON_WIFI_SYMBOL_3_RIGHT; - int yPos = WiFi_Symbol_Height + 2; int fontHeight = 8; @@ -1656,7 +1675,6 @@ uint32_t displayWiFiConfig() yPos = yPos + fontHeight + 1; printTextCenter("192.168.4.1", yPos, QW_FONT_5X7, 1, false); - return icons; } //When user does a factory reset, let us know From 17d727df8f7da123962eaa8858eef83ec42062e7 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 17 Aug 2022 16:57:39 -0600 Subject: [PATCH 072/134] Remove requirement for Client mountpoint PW Many mountpoints do not need a password for client access --- Firmware/RTK_Surveyor/AP-Config/src/main.js | 1 - Firmware/RTK_Surveyor/form.h | 10 ---------- 2 files changed, 11 deletions(-) diff --git a/Firmware/RTK_Surveyor/AP-Config/src/main.js b/Firmware/RTK_Surveyor/AP-Config/src/main.js index 5ccabeba0..8798dc22d 100644 --- a/Firmware/RTK_Surveyor/AP-Config/src/main.js +++ b/Firmware/RTK_Surveyor/AP-Config/src/main.js @@ -232,7 +232,6 @@ function validateFields() { checkElementString("ntripClient_CasterHost", 1, 30, "Must be 1 to 30 characters", "collapseGNSSConfig"); checkElementValue("ntripClient_CasterPort", 1, 99999, "Must be 1 to 99999", "collapseGNSSConfig"); checkElementString("ntripClient_MountPoint", 1, 30, "Must be 1 to 30 characters", "collapseGNSSConfig"); - checkElementString("ntripClient_MountPointPW", 1, 30, "Must be 1 to 30 characters", "collapseGNSSConfig"); } else { clearElement("ntripClient_wifiSSID", "TRex"); diff --git a/Firmware/RTK_Surveyor/form.h b/Firmware/RTK_Surveyor/form.h index 6c6750151..f0de15f0c 100644 --- a/Firmware/RTK_Surveyor/form.h +++ b/Firmware/RTK_Surveyor/form.h @@ -255,7 +255,6 @@ function validateFields() { checkElementString("ntripClient_CasterHost", 1, 30, "Must be 1 to 30 characters", "collapseGNSSConfig"); checkElementValue("ntripClient_CasterPort", 1, 99999, "Must be 1 to 99999", "collapseGNSSConfig"); checkElementString("ntripClient_MountPoint", 1, 30, "Must be 1 to 30 characters", "collapseGNSSConfig"); - checkElementString("ntripClient_MountPointPW", 1, 30, "Must be 1 to 30 characters", "collapseGNSSConfig"); } else { clearElement("ntripClient_wifiSSID", "TRex"); @@ -715,19 +714,10 @@ function firmwareUploadComplete() { document.addEventListener("DOMContentLoaded", (event) => { - //https://stackoverflow.com/questions/23835150/how-can-i-add-an-event-listener-for-multiple-buttons-with-same-class-name var radios = document.querySelectorAll('input[name=profileRadio]'); for(var i = 0, max = radios.length; i < max; i++) { radios[i].onclick = function() { - - console.log("Profile number: " + this.value); - - //Validate. If fail, reset radio button value to original changeConfig(); - - //Record previous settings to unit - - //Request unit for new settings } } From a4a4ebf2f6413622e4cbd6c48bbda149332ef5af Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 17 Aug 2022 17:09:52 -0600 Subject: [PATCH 073/134] Condense timezone menu --- Firmware/RTK_Surveyor/menuSystem.ino | 57 ++++++++++++---------------- 1 file changed, 24 insertions(+), 33 deletions(-) diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index 10559dd37..145e9682a 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -148,9 +148,8 @@ void menuSystem() } Serial.println("d) Configure Debug"); - Serial.printf("h) Set time zone hours: %d\r\n", settings.timeZoneHours); - Serial.printf("m) Set time zone minutes: %d\r\n", settings.timeZoneMinutes); - Serial.printf("s) Set time zone seconds: %d\r\n", settings.timeZoneSeconds); + + Serial.printf("z) Set time zone offset: %02d:%02d:%02d\r\n", settings.timeZoneHours, settings.timeZoneMinutes, settings.timeZoneSeconds); Serial.print(F("b) Set Bluetooth Mode: ")); if (settings.enableBLE == true) @@ -172,7 +171,7 @@ void menuSystem() if (incoming == 'd') menuDebug(); - else if (incoming == 'h') + else if (incoming == 'z') { Serial.print("Enter time zone hour offset (-23 <= offset <= 23): "); int64_t value = getNumber(menuTimeout); @@ -181,35 +180,27 @@ void menuSystem() else { settings.timeZoneHours = value; - online.rtc = false; - updateRTC(); - } - } - else if (incoming == 'm') - { - Serial.print("Enter time zone minute offset (-59 <= offset <= 59): "); - int64_t value = getNumber(menuTimeout); - if (value < -59 || value > 59) - Serial.println("Error: -60 < minutes < 60"); - else - { - settings.timeZoneMinutes = value; - online.rtc = false; - updateRTC(); - } - } - else if (incoming == 's') - { - Serial.print("Enter time zone second offset (-59 <= offset <= 59): "); - int64_t value = getNumber(menuTimeout); - if (value < -59 || value > 59) - Serial.println("Error: -60 < seconds < 60"); - else - { - settings.timeZoneSeconds = value; - online.rtc = false; - updateRTC(); - } + + Serial.print("Enter time zone minute offset (-59 <= offset <= 59): "); + int64_t value = getNumber(menuTimeout); + if (value < -59 || value > 59) + Serial.println("Error: -60 < minutes < 60"); + else + { + settings.timeZoneMinutes = value; + + Serial.print("Enter time zone second offset (-59 <= offset <= 59): "); + int64_t value = getNumber(menuTimeout); + if (value < -59 || value > 59) + Serial.println("Error: -60 < seconds < 60"); + else + { + settings.timeZoneSeconds = value; + online.rtc = false; + updateRTC(); + } //Succesful seconds + } //Succesful minute + } //Succesful hours } else if (incoming == 'b') { From 97319bf27cca61634a884a33a7acb061a6436bef Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 17 Aug 2022 17:15:17 -0600 Subject: [PATCH 074/134] Fix debug level --- .github/workflows/compile-rc.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/compile-rc.yml b/.github/workflows/compile-rc.yml index 308cdbbfd..fa614c9b6 100644 --- a/.github/workflows/compile-rc.yml +++ b/.github/workflows/compile-rc.yml @@ -53,7 +53,7 @@ jobs: --build-property build.partitions=partitions --build-property upload.maximum_size=3145728 --export-binaries - --build-property DebugLevel.debug.build.code_debug=4 + --build-property DebugLevel=debug --build-property "compiler.cpp.extra_flags=\"-DPOINTPERFECT_TOKEN=$POINTPERFECT_TOKEN\"" - name: Get current date From 07e0eb4e5a029cce8329ad87c00347ee444a62b1 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 17 Aug 2022 17:23:30 -0600 Subject: [PATCH 075/134] Update compile-rc.yml --- .github/workflows/compile-rc.yml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/.github/workflows/compile-rc.yml b/.github/workflows/compile-rc.yml index fa614c9b6..dbf71cff4 100644 --- a/.github/workflows/compile-rc.yml +++ b/.github/workflows/compile-rc.yml @@ -49,11 +49,10 @@ jobs: https://github.com/avinabmalla/ESP32_BleSerial.git - name: Compile Sketch - run: arduino-cli compile --fqbn esp32:esp32:esp32 ./Firmware/RTK_Surveyor/RTK_Surveyor.ino + run: arduino-cli compile --fqbn esp32:esp32:esp32:DebugLevel=debug ./Firmware/RTK_Surveyor/RTK_Surveyor.ino --build-property build.partitions=partitions --build-property upload.maximum_size=3145728 --export-binaries - --build-property DebugLevel=debug --build-property "compiler.cpp.extra_flags=\"-DPOINTPERFECT_TOKEN=$POINTPERFECT_TOKEN\"" - name: Get current date From 69f251e6db95928d77d69dccceed1a49d6296a6e Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Wed, 17 Aug 2022 09:34:39 -1000 Subject: [PATCH 076/134] Update the Linux build instructions Specify version 2.0.2 for the ESP32 version Specify the 16MB partition file Use 230400 for the upload speed, works on older platforms On Linux, the arduino application has a lower case 'a' --- docs/firmware_update.md | 42 ++++++++++++++++++++++------------------- 1 file changed, 23 insertions(+), 19 deletions(-) diff --git a/docs/firmware_update.md b/docs/firmware_update.md index 9b49b9dc2..0895a814f 100644 --- a/docs/firmware_update.md +++ b/docs/firmware_update.md @@ -341,9 +341,9 @@ Insert the following text into the file: # 1: ttyUSBn # 2: Firmware file # - sudo python3 ~/.arduino15/packages/esp32/tools/esptool_py/*/esptool.py --chip esp32 --port /dev/$1 --baud 921600 --before default_reset --after hard_reset write_flash -z --flash_mode dio --flash_freq 80m --flash_size detect \ + sudo python3 ~/.arduino15/packages/esp32/tools/esptool_py/*/esptool.py --chip esp32 --port /dev/$1 --baud 230400 --before default_reset --after hard_reset write_flash -z --flash_mode dio --flash_freq 80m --flash_size detect \ 0x1000 ~/SparkFun/RTK/Binaries/bin/RTK_Surveyor.ino.bootloader.bin \ - 0x8000 ~/SparkFun/RTK/Binaries/bin/RTK_Surveyor.ino.partitions.bin \ + 0x8000 ~/SparkFun/RTK/Binaries/bin/RTK_Surveyor_Partitions_16MB.bin \ 0xe000 ~/SparkFun/RTK/Binaries/bin/boot_app0.bin \ 0x10000 $2 @@ -366,7 +366,7 @@ Install the Arduino IDE Add the ESP32 support -24. Arduino +24. arduino 1. Click on File in the menu bar 2. Click on Preferences 3. Go down to the Additional Boards Manager URLs text box @@ -394,7 +394,7 @@ Connect the Config ESP32 port of the RTK to a USB port on the computer Enable the libraries in the Arduino IDE -34. Arduino +34. arduino 1. From the menu, click on File 2. Click on Open... 3. Select the ~/SparkFun/RTK/Firmware/RTK_Surveyor/RTK_Surveyor.ino file @@ -406,12 +406,13 @@ Enable the libraries in the Arduino IDE 6. Click on Board 7. Click on Board Manager… 8. Click on esp32 - 9. Click on the Install button in the lower right - 10. Close the Board Manager... - 11. From the menu, click on Tools - 12. Click on Board - 13. Click on ESP32 Arduino - 14. Click on ESP32 Dev Module + 9. Select version 2.0.2 + 10. Click on the Install button in the lower right + 11. Close the Board Manager... + 12. From the menu, click on Tools + 13. Click on Board + 14. Click on ESP32 Arduino + 15. Click on ESP32 Dev Module Load the required libraries @@ -426,6 +427,7 @@ Enable the libraries in the Arduino IDE * ArduinoJson * ESP32Time + * ESP32_BleSerial * JC_Button * MAX17048 - Used for “Test Sketch/Batt_Monitor” * PubSubClient @@ -442,17 +444,19 @@ Enable the libraries in the Arduino IDE 19. From the menu, click on Tools 20. Click on Port, Select the port that was displayed in step 38 above 21. Select /dev/ttyUSB0 + 22. Click on Upload Speed + 23. Select 230400 Setup the partitions for the 16 MB flash - 22. From the menu, click on Tools - 23. Click on Flash Size - 24. Select 16MB - 25. From the menu, click on Tools - 26. Click on Partition Scheme - 27. Click on 16M Flash (3MB APP/9MB FATFS) - 28. From the menu click on File - 29. Click on Quit + 24. From the menu, click on Tools + 25. Click on Flash Size + 26. Select 16MB + 27. From the menu, click on Tools + 28. Click on Partition Scheme + 29. Click on 16M Flash (3MB APP/9MB FATFS) + 30. From the menu click on File + 31. Click on Quit 35. cd ~/SparkFun/RTK/ -36. cp Firmware/app3M_fat9M_16MB.csv ~/.arduino15/packages/esp32/hardware/esp32/2.0.3/tools/partitions/app3M_fat9M_16MB.csv +36. cp Firmware/app3M_fat9M_16MB.csv ~/.arduino15/packages/esp32/hardware/esp32/2.0.2/tools/partitions/app3M_fat9M_16MB.csv From 4bfd89adfffd62e111532eb4b8c74981352273b2 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 18 Aug 2022 10:19:27 -0600 Subject: [PATCH 077/134] Fix debug level on RC workflow --- .github/workflows/compile-rc.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/compile-rc.yml b/.github/workflows/compile-rc.yml index dbf71cff4..058524f10 100644 --- a/.github/workflows/compile-rc.yml +++ b/.github/workflows/compile-rc.yml @@ -49,11 +49,11 @@ jobs: https://github.com/avinabmalla/ESP32_BleSerial.git - name: Compile Sketch - run: arduino-cli compile --fqbn esp32:esp32:esp32:DebugLevel=debug ./Firmware/RTK_Surveyor/RTK_Surveyor.ino + run: arduino-cli compile --fqbn "esp32:esp32:esp32":DebugLevel=debug ./Firmware/RTK_Surveyor/RTK_Surveyor.ino --build-property build.partitions=partitions --build-property upload.maximum_size=3145728 - --export-binaries --build-property "compiler.cpp.extra_flags=\"-DPOINTPERFECT_TOKEN=$POINTPERFECT_TOKEN\"" + --export-binaries - name: Get current date id: date From 75c99d7b7f0a1dbdceca572f525eca35845dbbba Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 18 Aug 2022 10:24:45 -0600 Subject: [PATCH 078/134] Create compile-release.yml --- .github/workflows/compile-release.yml | 72 +++++++++++++++++++++++++++ 1 file changed, 72 insertions(+) create mode 100644 .github/workflows/compile-release.yml diff --git a/.github/workflows/compile-release.yml b/.github/workflows/compile-release.yml new file mode 100644 index 000000000..bc6f5fdf7 --- /dev/null +++ b/.github/workflows/compile-release.yml @@ -0,0 +1,72 @@ +name: Build Release +on: + workflow_dispatch: + branches: + - main + +env: + FILENAME_PREFIX: RTK_Surveyor_Firmware_v2.4 + POINTPERFECT_TOKEN: ${{ secrets.POINTPERFECT_TOKEN }} + +jobs: + build: + + name: Build + runs-on: ubuntu-latest + + steps: + - name: Checkout + uses: actions/checkout@master + + - name: Setup Arduino CLI + uses: arduino/setup-arduino-cli@v1 + + #We limit the ESP32 core to v2.0.2 + - name: Install platform + run: arduino-cli core install esp32:esp32@2.0.2 + --additional-urls 'https://raw.githubusercontent.com/espressif/arduino-esp32/gh-pages/package_esp32_index.json' + + - name: Start config file + run: arduino-cli config init + + - name: Enable external libs + run: arduino-cli config set library.enable_unsafe_install true + + - name: Get Libraries + run: arduino-cli lib install --git-url + https://github.com/fbiego/ESP32Time.git + https://github.com/me-no-dev/ESPAsyncWebServer.git + https://github.com/me-no-dev/AsyncTCP.git + https://github.com/JChristensen/JC_Button.git + https://github.com/greiman/SdFat.git + https://github.com/sparkfun/SparkFun_u-blox_GNSS_Arduino_Library.git + https://github.com/sparkfun/SparkFun_MAX1704x_Fuel_Gauge_Arduino_Library.git + https://github.com/sparkfun/SparkFun_Qwiic_OLED_Arduino_Library.git + https://github.com/sparkfun/SparkFun_LIS2DH12_Arduino_Library.git + https://github.com/bblanchon/ArduinoJson.git + https://github.com/knolleary/pubsubclient.git + https://github.com/avinabmalla/ESP32_BleSerial.git + + - name: Compile Sketch + run: arduino-cli compile --fqbn esp32:esp32:esp32 ./Firmware/RTK_Surveyor/RTK_Surveyor.ino + --build-property build.partitions=partitions + --build-property upload.maximum_size=3145728 + --build-property "compiler.cpp.extra_flags=\"-DPOINTPERFECT_TOKEN=$POINTPERFECT_TOKEN\"" + --export-binaries + + - name: Get current date + id: date + run: echo "::set-output name=date::$(date +'%b_%d_%Y')" + + - name: Rename binary + run: | + cd Firmware/RTK_Surveyor + cd build + cd esp32.esp32.esp32 + mv RTK_Surveyor.ino.bin ${{ env.FILENAME_PREFIX }}.bin + + - name: Upload binary to action + uses: actions/upload-artifact@v3 + with: + name: ${{ env.FILENAME_PREFIX }} + path: ./Firmware/RTK_Surveyor/build/esp32.esp32.esp32/${{ env.FILENAME_PREFIX }}.bin From a880f233ae637662ecf3c87c80ab710e591b1bca Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 18 Aug 2022 11:17:59 -0600 Subject: [PATCH 079/134] Fix #284 - Delay NTRIP Client connect until GGA is available --- Firmware/RTK_Surveyor/NtripClient.ino | 30 +++++++++++++++++++-------- 1 file changed, 21 insertions(+), 9 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripClient.ino b/Firmware/RTK_Surveyor/NtripClient.ino index 0814c6558..48c082d54 100644 --- a/Firmware/RTK_Surveyor/NtripClient.ino +++ b/Firmware/RTK_Surveyor/NtripClient.ino @@ -339,18 +339,30 @@ void ntripClientUpdate() break; case NTRIP_CLIENT_WIFI_CONNECTED: - //Open connection to caster service - if (!ntripClientConnect()) { - log_d("NTRIP Client caster failed to connect. Trying again."); + //If GGA transmission is enabled, wait for GNSS lock before connecting to NTRIP Caster + //If GGA transmission is not enabled, start connecting to NTRIP Caster + if ( (settings.ntripClient_TransmitGGA == true && (fixType == 3 || fixType == 4 || fixType == 5)) + || settings.ntripClient_TransmitGGA == false) + { + //Open connection to caster service + if (!ntripClientConnect()) + { + log_d("NTRIP Client caster failed to connect. Trying again."); - //Assume service not available - if (ntripClientConnectLimitReached()) - Serial.println("NTRIP Client caster failed to connect. Do you have your caster address and port correct?"); + //Assume service not available + if (ntripClientConnectLimitReached()) + Serial.println("NTRIP Client caster failed to connect. Do you have your caster address and port correct?"); + } + else + //Socket opened to NTRIP system + ntripClientSetState(NTRIP_CLIENT_CONNECTING); + } + else + { + log_d("Waiting for Fix"); + } } - else - //Socket opened to NTRIP system - ntripClientSetState(NTRIP_CLIENT_CONNECTING); break; case NTRIP_CLIENT_CONNECTING: From 1a9bcb278166454bbb10ebe86879ba558680909e Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 18 Aug 2022 11:28:24 -0600 Subject: [PATCH 080/134] Camel case WiFi prints --- Firmware/RTK_Surveyor/NtripServer.ino | 2 +- Firmware/RTK_Surveyor/menuSystem.ino | 4 ++-- Firmware/RTK_Surveyor/settings.h | 6 +++--- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 862c2de9f..6dfdb1d46 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -35,7 +35,7 @@ | v Fail | | NTRIP_SERVER_AUTHORIZATION -------->+ | | ^ - | | Discard Data Wifi | + | | Discard Data WiFi | | v Fail | | NTRIP_SERVER_CASTING -----------' | | diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index 145e9682a..2534f9c7c 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -329,13 +329,13 @@ void menuDebug() Serial.print("9) GNSS Serial Timeout: "); Serial.println(settings.serialTimeoutGNSS); - Serial.print("10) Periodically print Wifi IP Address: "); + Serial.print("10) Periodically print WiFi IP Address: "); Serial.printf("%s\r\n", settings.enablePrintWifiIpAddress ? "Enabled" : "Disabled"); Serial.print("11) Periodically print state: "); Serial.printf("%s\r\n", settings.enablePrintState ? "Enabled" : "Disabled"); - Serial.print("12) Periodically print Wifi state: "); + Serial.print("12) Periodically print WiFi state: "); Serial.printf("%s\r\n", settings.enablePrintWifiState ? "Enabled" : "Disabled"); Serial.print("13) Periodically print NTRIP client state: "); diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 46983abc9..5b123e598 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -394,14 +394,14 @@ typedef struct { //NTRIP Server bool enableNtripServer = false; - bool ntripServer_StartAtSurveyIn = false; //true = Start Wifi instead of Bluetooth at Survey-In + bool ntripServer_StartAtSurveyIn = false; //true = Start WiFi instead of Bluetooth at Survey-In char ntripServer_CasterHost[50] = "rtk2go.com"; //It's free... uint16_t ntripServer_CasterPort = 2101; char ntripServer_CasterUser[50] = "test@test.com"; //Some free casters require auth. User must provide their own email address to use RTK2Go char ntripServer_CasterUserPW[50] = ""; char ntripServer_MountPoint[50] = "bldr_dwntwn2"; //NTRIP Server char ntripServer_MountPointPW[50] = "WR5wRo4H"; - char ntripServer_wifiSSID[50] = "TRex"; //NTRIP Server Wifi + char ntripServer_wifiSSID[50] = "TRex"; //NTRIP Server WiFi char ntripServer_wifiPW[50] = "parachutes"; //NTRIP Client @@ -412,7 +412,7 @@ typedef struct { char ntripClient_CasterUserPW[50] = ""; char ntripClient_MountPoint[50] = "bldr_SparkFun1"; char ntripClient_MountPointPW[50] = ""; - char ntripClient_wifiSSID[50] = "TRex"; //NTRIP Server Wifi + char ntripClient_wifiSSID[50] = "TRex"; //NTRIP Server WiFi char ntripClient_wifiPW[50] = "parachutes"; bool ntripClient_TransmitGGA = true; From 2e80170916ef800aecbbb48c765c210591c89c95 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 18 Aug 2022 12:49:26 -0600 Subject: [PATCH 081/134] Display RTCM frames, not bytes Useful for testing --- Firmware/RTK_Surveyor/ESPNOW.ino | 2 +- Firmware/RTK_Surveyor/NtripServer.ino | 11 ++++++++++- 2 files changed, 11 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 3029229fc..892b3b2fa 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -345,7 +345,7 @@ void espnowProcessRTCM(byte incoming) espnowOutgoingSpot = 0; //Wrap esp_now_send(0, (uint8_t *) &espnowOutgoing, sizeof(espnowOutgoing)); //Send packet to all peers delay(10); //We need a small delay between sending multiple packets - log_d("ESPNOW: Sending %d bytes", sizeof(espnowOutgoing)); + log_d("ESPNOW pushed %d RTCM bytes", sizeof(espnowOutgoing)); espnowOutgoingRTCM = true; } diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 6dfdb1d46..eadc3675c 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -74,6 +74,7 @@ static uint32_t ntripServerStateLastDisplayed = 0; //NTRIP server timer usage: // * Measure the connection response time // * Receive RTCM correction data timeout +// * Monitor last RTCM byte received for frame counting static uint32_t ntripServerTimer; //Record last connection attempt @@ -363,7 +364,15 @@ void ntripServerProcessRTCM(uint8_t incoming) if (settings.enableNtripServerMessageParsing == true) passAlongIncomingByte &= ntripServerRtcmMessage(incoming); else - rtcmPacketsSent++; //If not checking RTCM CRC, count every byte + { + //If we have not gotten new RTCM bytes for a period of time, assume end of frame + if (millis() - ntripServerTimer > 100 && ntripServerBytesSent > 0) + { + log_d("NTRIP Server pushed %d RTCM bytes to Caster", ntripServerBytesSent); + ntripServerBytesSent = 0; + rtcmPacketsSent++; //If not checking RTCM CRC, count based on timeout + } + } if (passAlongIncomingByte) { From e2388077559cb7c58e7fc28251e2d0d944677687 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 18 Aug 2022 12:50:03 -0600 Subject: [PATCH 082/134] Allow disable of BT radio Used primarily for debugging. --- Firmware/RTK_Surveyor/Bluetooth.ino | 10 ++++++---- Firmware/RTK_Surveyor/Display.ino | 2 +- Firmware/RTK_Surveyor/NVM.ino | 8 ++++---- Firmware/RTK_Surveyor/menuSystem.ino | 17 ++++++++++------- Firmware/RTK_Surveyor/settings.h | 15 +++++++++++---- 5 files changed, 32 insertions(+), 20 deletions(-) diff --git a/Firmware/RTK_Surveyor/Bluetooth.ino b/Firmware/RTK_Surveyor/Bluetooth.ino index 408d13eb3..6e2773c5c 100644 --- a/Firmware/RTK_Surveyor/Bluetooth.ino +++ b/Firmware/RTK_Surveyor/Bluetooth.ino @@ -116,11 +116,13 @@ void bluetoothStart() sprintf(deviceName, "%s %s%02X%02X", platformPrefix, stateName, unitMACAddress[4], unitMACAddress[5]); - // BLE vs Bluetooth Classic - if (settings.enableBLE) - bluetoothSerial = new BTLESerial(); - else + // Select Bluetooth setup + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) + return; + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP) bluetoothSerial = new BTClassicSerial(); + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) + bluetoothSerial = new BTLESerial(); if (bluetoothSerial->begin(deviceName) == false) { diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 8640d30b2..a036e1be4 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -659,7 +659,7 @@ uint32_t setRadioIcons() //Because of lack of space we will indicate the Base/Rover if only two radios or less are active //Count the number of radios in use - uint8_t numberOfRadios = 1; //Bluetooth always indicated + uint8_t numberOfRadios = 1; //Bluetooth always indicated. TODO don't count if BT radio type is OFF. if (wifiState > WIFI_OFF) numberOfRadios++; if (espnowState > ESPNOW_OFF) numberOfRadios++; diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index cf2c3d6d6..60b12c583 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -267,7 +267,7 @@ void recordSystemSettingsToFile(File * settingsFile) } settingsFile->printf("%s=%d\n\r", "espnowPeerCount", settings.espnowPeerCount); settingsFile->printf("%s=%d\n\r", "enableNtripServerMessageParsing", settings.enableNtripServerMessageParsing); - settingsFile->printf("%s=%d\n\r", "enableBLE", settings.enableBLE); + settingsFile->printf("%s=%d\n\r", "radioType", settings.bluetoothRadioType); //Record constellation settings for (int x = 0 ; x < MAX_CONSTELLATIONS ; x++) @@ -871,13 +871,13 @@ bool parseLine(char* str, Settings *settings) else if (strcmp(settingName, "enablePrintDuplicateStates") == 0) settings->enablePrintDuplicateStates = d; else if (strcmp(settingName, "radioType") == 0) - settings->radioType = (radioType_e)d; + settings->radioType = (RadioType_e)d; else if (strcmp(settingName, "espnowPeerCount") == 0) settings->espnowPeerCount = d; else if (strcmp(settingName, "enableNtripServerMessageParsing") == 0) settings->enableNtripServerMessageParsing = d; - else if (strcmp(settingName, "enableBLE") == 0) - settings->enableBLE = d; + else if (strcmp(settingName, "bluetoothRadioType") == 0) + settings->bluetoothRadioType = (BluetoothRadioType_e)d; //Check for bulk settings (constellations, message rates, ESPNOW Peers) //Must be last on else list diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index 2534f9c7c..ada55ba7d 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -152,10 +152,12 @@ void menuSystem() Serial.printf("z) Set time zone offset: %02d:%02d:%02d\r\n", settings.timeZoneHours, settings.timeZoneMinutes, settings.timeZoneSeconds); Serial.print(F("b) Set Bluetooth Mode: ")); - if (settings.enableBLE == true) + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP) + Serial.println(F("Classic")); + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) Serial.println(F("BLE")); else - Serial.println(F("Classic")); + Serial.println(F("Off")); Serial.println("r) Reset all settings to default"); @@ -206,12 +208,13 @@ void menuSystem() { // Restart Bluetooth bluetoothStop(); - if (settings.enableBLE == false) - settings.enableBLE = true; - else - settings.enableBLE = false; + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_SPP) + settings.bluetoothRadioType = BLUETOOTH_RADIO_BLE; + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) + settings.bluetoothRadioType = BLUETOOTH_RADIO_OFF; + else if (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) + settings.bluetoothRadioType = BLUETOOTH_RADIO_SPP; bluetoothStart(); - } else if (incoming == 'r') { diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 5b123e598..385d90977 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -164,11 +164,18 @@ enum RtcmTransportState RTCM_TRANSPORT_STATE_CHECK_CRC }; -typedef enum radioType_e +typedef enum RadioType_e { RADIO_EXTERNAL = 0, RADIO_ESPNOW, -} radioType_e; +} RadioType_e; + +typedef enum BluetoothRadioType_e +{ + BLUETOOTH_RADIO_SPP = 0, + BLUETOOTH_RADIO_BLE, + BLUETOOTH_RADIO_OFF, +} BluetoothRadioType_e; //Radio status LED goes from off (LED off), no connection (blinking), to connected (solid) enum BTState @@ -462,11 +469,11 @@ typedef struct { bool enablePrintNtripClientRtcm = false; bool enablePrintStates = true; bool enablePrintDuplicateStates = false; - radioType_e radioType = RADIO_EXTERNAL; + RadioType_e radioType = RADIO_EXTERNAL; uint8_t espnowPeers[5][6]; //Max of 5 peers. Contains the MAC addresses (6 bytes) of paired units uint8_t espnowPeerCount; bool enableNtripServerMessageParsing = false; - bool enableBLE = false; + BluetoothRadioType_e bluetoothRadioType = BLUETOOTH_RADIO_SPP; } Settings; Settings settings; From 854cdb2e63294dd0b52047f5344937de46f00825 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 18 Aug 2022 13:10:15 -0600 Subject: [PATCH 083/134] Fix link to PubSubClient lib --- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index ee76c394e..b9ae66e55 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -151,7 +151,7 @@ LoggingType loggingType = LOGGING_UNKNOWN; #include //Built-in. Needed for ThingStream API for ZTP #include //http://librarymanager/All#Arduino_JSON_messagepack v6.19.4 #include //Built-in. -#include //Built-in. Used for MQTT obtaining of keys +#include //http://librarymanager/All#PubSubClient_MQTT_Lightweight v2.8.0 Used for MQTT obtaining of keys #include "esp_wifi.h" //Needed for esp_wifi_set_protocol() From 0ac2b37a30898837119170b753bcd1df0647bd3f Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 18 Aug 2022 15:56:29 -0600 Subject: [PATCH 084/134] Add error check on L-Band keys daysRemaining --- Firmware/RTK_Surveyor/States.ino | 2 +- Firmware/RTK_Surveyor/menuMain.ino | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 75d34f54b..9d1aa8108 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -696,7 +696,7 @@ void updateSystemState() uint8_t daysRemaining = daysFromEpoch(settings.pointPerfectNextKeyStart + settings.pointPerfectNextKeyDuration + 1); log_d("Days until keys expire: %d", daysRemaining); - if (daysRemaining >= 28) + if (daysRemaining >= 28 && daysRemaining <= 56) changeState(STATE_KEYS_LBAND_CONFIGURE); else changeState(STATE_KEYS_NEEDED); diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index 480255596..891918c2f 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -306,7 +306,7 @@ void menuRadio() Serial.print("1) Select Radio Type: "); if (settings.radioType == RADIO_EXTERNAL) Serial.println("External only"); - else if (settings.radioType == RADIO_ESPNOW) Serial.println("Internal ESP NOW"); + else if (settings.radioType == RADIO_ESPNOW) Serial.println("Internal ESP-Now"); if (settings.radioType == RADIO_ESPNOW) { From 23d75fc4a4323d496041a6190029096d55dbb803 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 18 Aug 2022 16:00:34 -0600 Subject: [PATCH 085/134] Enable ESP Now upon pairing completion --- Firmware/RTK_Surveyor/ESPNOW.ino | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 892b3b2fa..7b92017e7 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -223,6 +223,9 @@ bool espnowIsPaired() memcpy(settings.espnowPeers[settings.espnowPeerCount], receivedMAC, 6); settings.espnowPeerCount++; settings.espnowPeerCount %= ESPNOW_MAX_PEERS; + + //Enable radio. User may have arrived here from the setup menu rather than serial menu. + settings.radioType = RADIO_ESPNOW; } //Send message directly to the received MAC (not unicast), then exit From 17cff2f06c6243a41178980ff38d53e079de3c73 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 18 Aug 2022 16:13:04 -0600 Subject: [PATCH 086/134] Malloc cert and key contents --- Firmware/RTK_Surveyor/menuPP.ino | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/Firmware/RTK_Surveyor/menuPP.ino b/Firmware/RTK_Surveyor/menuPP.ino index c13545d7c..c52b02dc2 100644 --- a/Firmware/RTK_Surveyor/menuPP.ino +++ b/Firmware/RTK_Surveyor/menuPP.ino @@ -278,15 +278,22 @@ bool provisionDevice() } //Subscribe to MQTT channel, grab keys, then stop + bool updatePointPerfectKeys() { #ifdef COMPILE_WIFI WiFiClientSecure secureClient; +#define CONTENT_SIZE 2000 + + certificateContents = (char*)malloc(CONTENT_SIZE); + memset(certificateContents, 0, CONTENT_SIZE); loadFile("certificate", certificateContents); secureClient.setCertificate(certificateContents); + keyContents = (char*)malloc(CONTENT_SIZE); + memset(keyContents, 0, CONTENT_SIZE); loadFile("privateKey", keyContents); secureClient.setPrivateKey(keyContents); @@ -336,6 +343,8 @@ bool updatePointPerfectKeys() if (mqttClient.connected() == false) { log_d("Client disconnected"); + free(certificateContents); + free(keyContents); return (false); } @@ -345,12 +354,16 @@ bool updatePointPerfectKeys() { Serial.println(); log_d("Channel failed to respond"); + free(certificateContents); + free(keyContents); return (false); } } Serial.println(); - Serial.println("Keys successfully update"); + Serial.println("Keys successfully updated"); + free(certificateContents); + free(keyContents); return (true); #else return (false); @@ -957,8 +970,6 @@ void menuPointPerfect() else updatePointPerfectKeys(); } - - bluetoothStart(); #endif } else if (incoming == '6') From b95045aa509656ee7164b602574f6b7ce9cec1c3 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 19 Aug 2022 11:18:38 -0600 Subject: [PATCH 087/134] Free malloc'd keys. Stop WiFi after PointPerfect update. --- Firmware/RTK_Surveyor/menuPP.ino | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/menuPP.ino b/Firmware/RTK_Surveyor/menuPP.ino index c52b02dc2..d5ecaf5b5 100644 --- a/Firmware/RTK_Surveyor/menuPP.ino +++ b/Firmware/RTK_Surveyor/menuPP.ino @@ -278,7 +278,6 @@ bool provisionDevice() } //Subscribe to MQTT channel, grab keys, then stop - bool updatePointPerfectKeys() { #ifdef COMPILE_WIFI @@ -323,6 +322,8 @@ bool updatePointPerfectKeys() if (tries++ == maxTries) { log_d("MQTT failed to connect"); + free(certificateContents); + free(keyContents); return (false); } @@ -969,6 +970,8 @@ void menuPointPerfect() } else updatePointPerfectKeys(); + + wifiStop(); } #endif } From e2af03f1507a90fed878e125408b0e3b8fc78c8b Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 19 Aug 2022 11:18:51 -0600 Subject: [PATCH 088/134] Remove unused var. --- Firmware/RTK_Surveyor/Display.ino | 2 -- 1 file changed, 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index a036e1be4..d62a5f4b1 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -1660,8 +1660,6 @@ void displayWiFiConfigNotStarted() void displayWiFiConfig() { - uint32_t icons; - int yPos = WiFi_Symbol_Height + 2; int fontHeight = 8; From 45867896f95bd96ca2549df6d64aa3a0c7c81006 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 19 Aug 2022 16:12:41 -0600 Subject: [PATCH 089/134] Cleanup RTCM log_ds --- Firmware/RTK_Surveyor/ESPNOW.ino | 5 +++-- Firmware/RTK_Surveyor/NtripClient.ino | 2 +- Firmware/RTK_Surveyor/NtripServer.ino | 2 +- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 9 +++++++-- Firmware/RTK_Surveyor/Tasks.ino | 2 +- 5 files changed, 13 insertions(+), 7 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 7b92017e7..26102bd34 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -63,7 +63,7 @@ void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int l //Pass RTCM bytes (presumably) from ESP NOW out ESP32-UART2 to ZED-UART1 serialGNSS.write(incomingData, len); - log_d("ESPNOW: Received %d bytes, RSSI: %d", len, espnowRSSI); + log_d("ESPNOW received %d RTCM bytes, pushed to ZED, RSSI: %d", len, espnowRSSI); espnowIncomingRTCM = true; lastEspnowRssiUpdate = millis(); @@ -348,7 +348,8 @@ void espnowProcessRTCM(byte incoming) espnowOutgoingSpot = 0; //Wrap esp_now_send(0, (uint8_t *) &espnowOutgoing, sizeof(espnowOutgoing)); //Send packet to all peers delay(10); //We need a small delay between sending multiple packets - log_d("ESPNOW pushed %d RTCM bytes", sizeof(espnowOutgoing)); + + espnowBytesSent += sizeof(espnowOutgoing); espnowOutgoingRTCM = true; } diff --git a/Firmware/RTK_Surveyor/NtripClient.ino b/Firmware/RTK_Surveyor/NtripClient.ino index 48c082d54..e3bbf8262 100644 --- a/Firmware/RTK_Surveyor/NtripClient.ino +++ b/Firmware/RTK_Surveyor/NtripClient.ino @@ -460,7 +460,7 @@ void ntripClientUpdate() i2cGNSS.pushRawData(rtcmData, rtcmCount); wifiIncomingRTCM = true; - log_d("NTRIP Client pushed %d RTCM bytes to ZED", rtcmCount); + log_d("NTRIP Client received %d RTCM bytes, pushed to ZED", rtcmCount); } } diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index eadc3675c..160c0e0dc 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -368,7 +368,7 @@ void ntripServerProcessRTCM(uint8_t incoming) //If we have not gotten new RTCM bytes for a period of time, assume end of frame if (millis() - ntripServerTimer > 100 && ntripServerBytesSent > 0) { - log_d("NTRIP Server pushed %d RTCM bytes to Caster", ntripServerBytesSent); + log_d("NTRIP Server transmitted %d RTCM bytes to Caster", ntripServerBytesSent); ntripServerBytesSent = 0; rtcmPacketsSent++; //If not checking RTCM CRC, count based on timeout } diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index b9ae66e55..6ebe1ba6e 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -354,7 +354,8 @@ float lBandEBNO = 0.0; //Used on system status menu uint8_t espnowOutgoing[250]; //ESP NOW has max of 250 characters unsigned long espnowLastAdd; //Tracks how long since last byte was added to the outgoing buffer -uint8_t espnowOutgoingSpot = 0; +uint8_t espnowOutgoingSpot = 0; //ESP Now has max of 250 characters +uint16_t espnowBytesSent = 0; //May be more than 255 uint8_t receivedMAC[6]; //Holds the broadcast MAC during pairing int espnowRSSI = 0; @@ -848,8 +849,12 @@ void updateRadio() //then we've reached the end of the RTCM stream. Send partial buffer. if (espnowOutgoingSpot > 0 && (millis() - espnowLastAdd) > 50) { + rtcmPacketsSent++; //Assume this is the end of the RTCM frame + esp_now_send(0, (uint8_t *) &espnowOutgoing, espnowOutgoingSpot); //Send partial packet to all peers - //log_d("ESPNOW: Sending %d bytes", espnowOutgoingSpot); + + log_d("ESPNOW transmitted %d RTCM bytes", espnowBytesSent + espnowOutgoingSpot); + espnowBytesSent = 0; espnowOutgoingSpot = 0; //Reset } diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index cf338a67f..859598000 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -18,6 +18,7 @@ void F9PSerialWriteTask(void *e) //TODO - control if this RTCM source should be listened to or not serialGNSS.write(wBuffer, s); bluetoothIncomingRTCM = true; + log_d("Bluetooth received %d RTCM bytes, sent to ZED", s); if (settings.enableTaskReports == true) Serial.printf("SerialWriteTask High watermark: %d\n\r", uxTaskGetStackHighWaterMark(NULL)); @@ -671,4 +672,3 @@ void idleTask(void *e) } } #endif //COMPILE_IDLE_TASKS - From cdfb29c493ee8ff44a10bf44c79dc2a13f7c57a1 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 19 Aug 2022 16:13:10 -0600 Subject: [PATCH 090/134] Correct radioType NVM storage --- Firmware/RTK_Surveyor/ESPNOW.ino | 7 ++++--- Firmware/RTK_Surveyor/NVM.ino | 4 +++- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 26102bd34..1a10c8e07 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -223,14 +223,15 @@ bool espnowIsPaired() memcpy(settings.espnowPeers[settings.espnowPeerCount], receivedMAC, 6); settings.espnowPeerCount++; settings.espnowPeerCount %= ESPNOW_MAX_PEERS; - - //Enable radio. User may have arrived here from the setup menu rather than serial menu. - settings.radioType = RADIO_ESPNOW; } //Send message directly to the received MAC (not unicast), then exit espnowSendPairMessage(receivedMAC); + //Enable radio. User may have arrived here from the setup menu rather than serial menu. + settings.radioType = RADIO_ESPNOW; + recordSystemSettings(); + espnowSetState(ESPNOW_PAIRED); return (true); } diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index 60b12c583..9a1a2ce4c 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -267,7 +267,7 @@ void recordSystemSettingsToFile(File * settingsFile) } settingsFile->printf("%s=%d\n\r", "espnowPeerCount", settings.espnowPeerCount); settingsFile->printf("%s=%d\n\r", "enableNtripServerMessageParsing", settings.enableNtripServerMessageParsing); - settingsFile->printf("%s=%d\n\r", "radioType", settings.bluetoothRadioType); + settingsFile->printf("%s=%d\n\r", "bluetoothRadioType", settings.bluetoothRadioType); //Record constellation settings for (int x = 0 ; x < MAX_CONSTELLATIONS ; x++) @@ -876,6 +876,8 @@ bool parseLine(char* str, Settings *settings) settings->espnowPeerCount = d; else if (strcmp(settingName, "enableNtripServerMessageParsing") == 0) settings->enableNtripServerMessageParsing = d; + else if (strcmp(settingName, "radioType") == 0) + settings->radioType = (RadioType_e)d; else if (strcmp(settingName, "bluetoothRadioType") == 0) settings->bluetoothRadioType = (BluetoothRadioType_e)d; From fb7a0b8cabc2a7b5f9573394a1a03cac1df75573 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 19 Aug 2022 18:19:34 -0600 Subject: [PATCH 091/134] Exit to previous state after pairing --- Firmware/RTK_Surveyor/ESPNOW.ino | 3 ++- Firmware/RTK_Surveyor/States.ino | 4 +++- Firmware/RTK_Surveyor/Tasks.ino | 4 ++-- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 1a10c8e07..f54de9dd3 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -230,7 +230,8 @@ bool espnowIsPaired() //Enable radio. User may have arrived here from the setup menu rather than serial menu. settings.radioType = RADIO_ESPNOW; - recordSystemSettings(); + + recordSystemSettings(); //Record radioType and espnowPeerCount to NVM espnowSetState(ESPNOW_PAIRED); return (true); diff --git a/Firmware/RTK_Surveyor/States.ino b/Firmware/RTK_Surveyor/States.ino index 9d1aa8108..60723dcf7 100644 --- a/Firmware/RTK_Surveyor/States.ino +++ b/Firmware/RTK_Surveyor/States.ino @@ -920,7 +920,9 @@ void updateSystemState() if (espnowIsPaired() == true) { paintEspNowPaired(); - changeState(STATE_ROVER_NOT_STARTED); + + // Return to the previous state + changeState(lastSystemState); } else { diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 859598000..73829cf09 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -415,7 +415,7 @@ void ButtonCheckTask(void *e) case STATE_WIFI_CONFIG: case STATE_ESPNOW_PAIRING_NOT_STARTED: case STATE_ESPNOW_PAIRING: - lastSystemState = systemState; //Remember this state to return after we mark an event + lastSystemState = systemState; //Remember this state to return after we mark an event or ESP-Now pair requestChangeState(STATE_DISPLAY_SETUP); setupState = STATE_MARK_EVENT; lastSetupMenuChange = millis(); @@ -535,7 +535,7 @@ void ButtonCheckTask(void *e) case STATE_WIFI_CONFIG: case STATE_ESPNOW_PAIRING_NOT_STARTED: case STATE_ESPNOW_PAIRING: - lastSystemState = systemState; //Remember this state to return after we mark an event + lastSystemState = systemState; //Remember this state to return after we mark an event or ESP-Now pair requestChangeState(STATE_DISPLAY_SETUP); setupState = STATE_MARK_EVENT; lastSetupMenuChange = millis(); From ae6472df560c4ffa18cf526ae924f151e1308b41 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 19 Aug 2022 20:56:57 -0600 Subject: [PATCH 092/134] Center text on displays --- Firmware/RTK_Surveyor/Display.ino | 57 +++++++++---------------------- 1 file changed, 16 insertions(+), 41 deletions(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index d62a5f4b1..73924fcd7 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -1455,45 +1455,23 @@ void printTextwithKerning(const char *newText, uint8_t xPos, uint8_t yPos, uint8 //Show transmission of RTCM correction data packets to NTRIP caster void paintRTCM() { - static uint32_t lastCorrectionDataSeen; - int textY = 17; - int textKerning = 8; - oled.setFont(QW_FONT_8X16); + int yPos = 17; if (bluetoothGetState() != BT_OFF) - { - int textX = 1; - printTextwithKerning("Xmitting", textX, textY, textKerning); //via Bluetooth - } + printTextCenter("Xmitting", yPos, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted else - { - int textX = 4; - printTextwithKerning("Casting", textX, textY, textKerning); //via WiFi - } + printTextCenter("Casting", yPos, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted - //Determine if correction data has been sent recently - if (bluetoothOutgoingRTCM == true || wifiOutgoingRTCM == true || espnowOutgoingRTCM == true) - lastCorrectionDataSeen = millis(); + oled.setCursor(0, 39); //x, y + oled.setFont(QW_FONT_5X7); + oled.print("RTCM:"); - if ((millis() - lastCorrectionDataSeen) >= 5000) - { - //No correction data seen - oled.setCursor(0, 33); //x, y - oled.print("Off"); - } + if (rtcmPacketsSent < 100) + oled.setCursor(30, 36); //x, y - Give space for two digits else - { - oled.setCursor(0, 39); //x, y - oled.setFont(QW_FONT_5X7); - oled.print("RTCM:"); - - if (rtcmPacketsSent < 100) - oled.setCursor(30, 36); //x, y - Give space for two digits - else - oled.setCursor(28, 36); //x, y - Push towards colon to make room for log icon + oled.setCursor(28, 36); //x, y - Push towards colon to make room for log icon - oled.setFont(QW_FONT_8X16); //Set font to type 1: 8x16 - oled.print(rtcmPacketsSent); //rtcmPacketsSent is controlled in processRTCM() - } + oled.setFont(QW_FONT_8X16); //Set font to type 1: 8x16 + oled.print(rtcmPacketsSent); //rtcmPacketsSent is controlled in processRTCM() paintResets(); } @@ -1501,15 +1479,12 @@ void paintRTCM() //Show connecting to NTRIP caster service void paintConnectingToNtripCaster() { - int textX = 11; - int textY = 18; - int textKerning = 8; - - printTextwithKerning("Caster", textX, textY, textKerning); + int yPos = 18; + printTextCenter("Caster", yPos, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted - textX = 3; - textY = 33; - textKerning = 6; + int textX = 3; + int textY = 33; + int textKerning = 6; oled.setFont(QW_FONT_8X16); printTextwithKerning("Connecting", textX, textY, textKerning); From 94e19f16772e7e8c07fd7b07889ab18566daee47 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 20 Aug 2022 20:43:56 -0600 Subject: [PATCH 093/134] Fix typo --- Firmware/RTK_Surveyor/ESPNOW.ino | 4 ++-- Firmware/RTK_Surveyor/Form.ino | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index f54de9dd3..8862a953a 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -34,7 +34,7 @@ void espnowOnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) #endif // Callback when data is received -void espnowOnDataRecieved(const uint8_t *mac, const uint8_t *incomingData, int len) +void espnowOnDataReceived(const uint8_t *mac, const uint8_t *incomingData, int len) { #ifdef COMPILE_ESPNOW if (espnowState == ESPNOW_PAIRING) @@ -123,7 +123,7 @@ void espnowStart() // Register callbacks //esp_now_register_send_cb(espnowOnDataSent); - esp_now_register_recv_cb(espnowOnDataRecieved); + esp_now_register_recv_cb(espnowOnDataReceived); if (settings.espnowPeerCount == 0) { diff --git a/Firmware/RTK_Surveyor/Form.ino b/Firmware/RTK_Surveyor/Form.ino index 72b3a2d09..b34780989 100644 --- a/Firmware/RTK_Surveyor/Form.ino +++ b/Firmware/RTK_Surveyor/Form.ino @@ -591,7 +591,7 @@ void updateSettingWithValue(const char *settingName, const char* settingValueStr factoryReset(); else if (strcmp(settingName, "exitAndReset") == 0) { - if (newAPSettings == true) recordSystemSettings(); //If we've recieved settings, record before restart + if (newAPSettings == true) recordSystemSettings(); //If we've received settings, record before restart //Reboot the machine ESP.restart(); From 5f6b007eb3ddb47460ecb2df0a8425f6699ba28d Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 20 Aug 2022 20:45:13 -0600 Subject: [PATCH 094/134] Suppress debug prints in mainmenu --- Firmware/RTK_Surveyor/ESPNOW.ino | 2 +- Firmware/RTK_Surveyor/NtripClient.ino | 2 +- Firmware/RTK_Surveyor/NtripServer.ino | 2 +- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 2 +- Firmware/RTK_Surveyor/Tasks.ino | 4 ++-- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 8862a953a..b1e02cd7c 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -63,7 +63,7 @@ void espnowOnDataReceived(const uint8_t *mac, const uint8_t *incomingData, int l //Pass RTCM bytes (presumably) from ESP NOW out ESP32-UART2 to ZED-UART1 serialGNSS.write(incomingData, len); - log_d("ESPNOW received %d RTCM bytes, pushed to ZED, RSSI: %d", len, espnowRSSI); + if(!inMainMenu) log_d("ESPNOW received %d RTCM bytes, pushed to ZED, RSSI: %d", len, espnowRSSI); espnowIncomingRTCM = true; lastEspnowRssiUpdate = millis(); diff --git a/Firmware/RTK_Surveyor/NtripClient.ino b/Firmware/RTK_Surveyor/NtripClient.ino index e3bbf8262..07f120d28 100644 --- a/Firmware/RTK_Surveyor/NtripClient.ino +++ b/Firmware/RTK_Surveyor/NtripClient.ino @@ -460,7 +460,7 @@ void ntripClientUpdate() i2cGNSS.pushRawData(rtcmData, rtcmCount); wifiIncomingRTCM = true; - log_d("NTRIP Client received %d RTCM bytes, pushed to ZED", rtcmCount); + if(!inMainMenu) log_d("NTRIP Client received %d RTCM bytes, pushed to ZED", rtcmCount); } } diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 160c0e0dc..c2fc963b9 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -368,7 +368,7 @@ void ntripServerProcessRTCM(uint8_t incoming) //If we have not gotten new RTCM bytes for a period of time, assume end of frame if (millis() - ntripServerTimer > 100 && ntripServerBytesSent > 0) { - log_d("NTRIP Server transmitted %d RTCM bytes to Caster", ntripServerBytesSent); + if(!inMainMenu) log_d("NTRIP Server transmitted %d RTCM bytes to Caster", ntripServerBytesSent); ntripServerBytesSent = 0; rtcmPacketsSent++; //If not checking RTCM CRC, count based on timeout } diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 6ebe1ba6e..3d7965e91 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -853,7 +853,7 @@ void updateRadio() esp_now_send(0, (uint8_t *) &espnowOutgoing, espnowOutgoingSpot); //Send partial packet to all peers - log_d("ESPNOW transmitted %d RTCM bytes", espnowBytesSent + espnowOutgoingSpot); + if(!inMainMenu) log_d("ESPNOW transmitted %d RTCM bytes", espnowBytesSent + espnowOutgoingSpot); espnowBytesSent = 0; espnowOutgoingSpot = 0; //Reset } diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 73829cf09..66710a5f6 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -18,7 +18,7 @@ void F9PSerialWriteTask(void *e) //TODO - control if this RTCM source should be listened to or not serialGNSS.write(wBuffer, s); bluetoothIncomingRTCM = true; - log_d("Bluetooth received %d RTCM bytes, sent to ZED", s); + if(!inMainMenu) log_d("Bluetooth received %d RTCM bytes, sent to ZED", s); if (settings.enableTaskReports == true) Serial.printf("SerialWriteTask High watermark: %d\n\r", uxTaskGetStackHighWaterMark(NULL)); @@ -177,7 +177,7 @@ void F9PSerialReadTask(void *e) if (btBytesToSend > 0) { //If we are in base mode, assume part of the outgoing data is RTCM - if(systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) + if (systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) bluetoothOutgoingRTCM = true; } else From a93bf561f07fe61ff1eb66fe1b897cbeb3549012 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sun, 21 Aug 2022 21:40:22 -0600 Subject: [PATCH 095/134] Fix for ESP-Now one to many fail bug See: https://github.com/espressif/esp-idf/issues/8992 The bug may be fixed in v2.0.4. --- Firmware/RTK_Surveyor/ESPNOW.ino | 8 +++++--- Firmware/RTK_Surveyor/WiFi.ino | 2 ++ 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index b1e02cd7c..4a231079e 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -63,7 +63,7 @@ void espnowOnDataReceived(const uint8_t *mac, const uint8_t *incomingData, int l //Pass RTCM bytes (presumably) from ESP NOW out ESP32-UART2 to ZED-UART1 serialGNSS.write(incomingData, len); - if(!inMainMenu) log_d("ESPNOW received %d RTCM bytes, pushed to ZED, RSSI: %d", len, espnowRSSI); + if (!inMainMenu) log_d("ESPNOW received %d RTCM bytes, pushed to ZED, RSSI: %d", len, espnowRSSI); espnowIncomingRTCM = true; lastEspnowRssiUpdate = millis(); @@ -93,7 +93,9 @@ void espnowStart() if (wifiState == WIFI_OFF && espnowState == ESPNOW_OFF) { //Radio is off, turn it on + WiFi.useStaticBuffers(true); //Fix for one to many ESP-Now bug, prior to ESP32 core v2.0.4: https://github.com/espressif/esp-idf/issues/8992 WiFi.mode(WIFI_STA); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_LR); Serial.println("WiFi off, ESP-Now added to protocols"); } @@ -230,7 +232,7 @@ bool espnowIsPaired() //Enable radio. User may have arrived here from the setup menu rather than serial menu. settings.radioType = RADIO_ESPNOW; - + recordSystemSettings(); //Record radioType and espnowPeerCount to NVM espnowSetState(ESPNOW_PAIRED); @@ -350,7 +352,7 @@ void espnowProcessRTCM(byte incoming) espnowOutgoingSpot = 0; //Wrap esp_now_send(0, (uint8_t *) &espnowOutgoing, sizeof(espnowOutgoing)); //Send packet to all peers delay(10); //We need a small delay between sending multiple packets - + espnowBytesSent += sizeof(espnowOutgoing); espnowOutgoingRTCM = true; diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index e146ae3ab..0867d09d1 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -209,6 +209,7 @@ void wifiStart(char* ssid, char* pw) #ifdef COMPILE_WIFI if ((wifiState == WIFI_OFF) || (wifiState == WIFI_ON)) { + WiFi.useStaticBuffers(true); //Fix for one to many ESP-Now bug, prior to ESP32 core v2.0.4: https://github.com/espressif/esp-idf/issues/8992 WiFi.mode(WIFI_STA); #ifdef COMPILE_ESPNOW @@ -256,6 +257,7 @@ void wifiStop() //If ESP-Now is active, change protocol to only Long Range else if (espnowState > ESPNOW_OFF) { + WiFi.useStaticBuffers(true); //Fix for one to many ESP-Now bug, prior to ESP32 core v2.0.4: https://github.com/espressif/esp-idf/issues/8992 WiFi.mode(WIFI_STA); // Enable long range, PHY rate of ESP32 will be 512Kbps or 256Kbps From de89a18eecf52c150de69779bac79b180739ae52 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Mon, 22 Aug 2022 14:15:24 -0600 Subject: [PATCH 096/134] Change GSV debug to log_d --- Firmware/RTK_Surveyor/menuGNSS.ino | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/menuGNSS.ino b/Firmware/RTK_Surveyor/menuGNSS.ino index 2e9b84008..284584c23 100644 --- a/Firmware/RTK_Surveyor/menuGNSS.ino +++ b/Firmware/RTK_Surveyor/menuGNSS.ino @@ -334,7 +334,7 @@ void setMeasurementRates(float secondsBetweenSolutions) float measurementFrequency = (1000.0 / settings.measurementRate) / settings.navigationRate; if (measurementFrequency < 1.0) measurementFrequency = 1.0; - Serial.printf("Adjusting GSV setting to %f\n\r", measurementFrequency); + log_d("Adjusting GSV setting to %f", measurementFrequency); setMessageRateByName("UBX_NMEA_GSV", measurementFrequency); //Update GSV setting in file configureMessageRate(COM_PORT_UART1, settings.ubxMessages[8]); //Update rate on module From ea9112e65f989d7a2ecab18f27333c8a1d8f2c4e Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Mon, 22 Aug 2022 14:16:13 -0600 Subject: [PATCH 097/134] Add test log generation --- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 12 +- Firmware/RTK_Surveyor/menuMessages.ino | 177 +++++++++++++++++++++++-- Firmware/RTK_Surveyor/menuSystem.ino | 12 ++ Firmware/RTK_Surveyor/settings.h | 17 +++ 4 files changed, 201 insertions(+), 17 deletions(-) diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 3d7965e91..8a4c7e763 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -126,7 +126,7 @@ int startCurrentLogTime_minutes = 0; //Mark when we start this specific log file //System crashes if two tasks access a file at the same time //So we use a semaphore to see if file system is available SemaphoreHandle_t sdCardSemaphore; -const TickType_t fatSemaphore_shortWait_ms = 10 / portTICK_PERIOD_MS; +TickType_t fatSemaphore_shortWait_ms = 50 / portTICK_PERIOD_MS; const TickType_t fatSemaphore_longWait_ms = 200 / portTICK_PERIOD_MS; //Display used/free space in menu and config page @@ -648,8 +648,10 @@ void updateLogs() } else if (online.logging == true && settings.enableLogging == true && (systemTime_minutes - startCurrentLogTime_minutes) >= settings.maxLogLength_minutes) { - //Close down file. A new one will be created at the next calling of updateLogs(). - endSD(false, true); + if (settings.runLogTest == false) + endSD(false, true); //Close down file. A new one will be created at the next calling of updateLogs(). + else if (settings.runLogTest == true) + updateLogTest(); } if (online.logging == true) @@ -852,8 +854,8 @@ void updateRadio() rtcmPacketsSent++; //Assume this is the end of the RTCM frame esp_now_send(0, (uint8_t *) &espnowOutgoing, espnowOutgoingSpot); //Send partial packet to all peers - - if(!inMainMenu) log_d("ESPNOW transmitted %d RTCM bytes", espnowBytesSent + espnowOutgoingSpot); + + if (!inMainMenu) log_d("ESPNOW transmitted %d RTCM bytes", espnowBytesSent + espnowOutgoingSpot); espnowBytesSent = 0; espnowOutgoingSpot = 0; //Reset } diff --git a/Firmware/RTK_Surveyor/menuMessages.ino b/Firmware/RTK_Surveyor/menuMessages.ino index d96ca31a9..6406a7654 100644 --- a/Firmware/RTK_Surveyor/menuMessages.ino +++ b/Firmware/RTK_Surveyor/menuMessages.ino @@ -340,27 +340,43 @@ uint8_t getMessageRate(uint8_t msgClass, uint8_t msgID, uint8_t portID) //Based on GPS data/time, create a log file in the format SFE_Surveyor_YYMMDD_HHMMSS.ubx void beginLogging() { + beginLogging(""); +} + +void beginLogging(const char *customFileName) +{ + if (online.microSD == false) + beginSD(); + if (online.logging == false) { if (online.microSD == true && settings.enableLogging == true && online.rtc == true) //We can't create a file until we have date/time { char fileName[66 + 6 + 40] = ""; - if (reuseLastLog == true) //attempt to use previous log + if (strlen(customFileName) == 0) { - if (findLastLog(fileName) == false) - log_d("Failed to find last log. Making new one."); - else - log_d("Using last log file."); - } + //Generate a standard log file name + if (reuseLastLog == true) //attempt to use previous log + { + if (findLastLog(fileName) == false) + log_d("Failed to find last log. Making new one."); + else + log_d("Using last log file."); + } - if (strlen(fileName) == 0) + if (strlen(fileName) == 0) + { + sprintf(fileName, "%s_%02d%02d%02d_%02d%02d%02d.ubx", //SdFat library + platformFilePrefix, + rtc.getYear() - 2000, rtc.getMonth() + 1, rtc.getDay(), //ESP32Time returns month:0-11 + rtc.getHour(true), rtc.getMinute(), rtc.getSecond() //ESP32Time getHour(true) returns hour:0-23 + ); + } + } + else { - sprintf(fileName, "%s_%02d%02d%02d_%02d%02d%02d.ubx", //SdFat library - platformFilePrefix, - rtc.getYear() - 2000, rtc.getMonth() + 1, rtc.getDay(), //ESP32Time returns month:0-11 - rtc.getHour(true), rtc.getMinute(), rtc.getSecond() //ESP32Time getHour(true) returns hour:0-23 - ); + strcpy(fileName, customFileName); } //Allocate the ubxFile @@ -651,3 +667,140 @@ void setLoggingType() } } } + +//During the logging test, we have to modify the messages and rate of the device +void setLogTestFrequencyMessages(int rate, int messages) +{ + //Set measurement frequency + setMeasurementRates(1.0 / rate); //Convert Hz to seconds. This will set settings.measurementRate and settings.navigationRate + + //Set messages + setGNSSMessageRates(settings.ubxMessages, 0); //Turn off all messages + if (messages == 5) + { + setMessageRateByName("UBX_NMEA_GGA", 1); + setMessageRateByName("UBX_NMEA_GSA", 1); + setMessageRateByName("UBX_NMEA_GST", 1); + setMessageRateByName("UBX_NMEA_GSV", rate); //One report per second + setMessageRateByName("UBX_NMEA_RMC", 1); + + log_d("Messages: Surveying Defaults (NMEAx5)"); + } + else if (messages == 7) + { + setMessageRateByName("UBX_NMEA_GGA", 1); + setMessageRateByName("UBX_NMEA_GSA", 1); + setMessageRateByName("UBX_NMEA_GST", 1); + setMessageRateByName("UBX_NMEA_GSV", rate); //One report per second + setMessageRateByName("UBX_NMEA_RMC", 1); + setMessageRateByName("UBX_RXM_RAWX", 1); + setMessageRateByName("UBX_RXM_SFRBX", 1); + + log_d("Messages: PPP NMEAx5+RXMx2"); + } + else + log_d("Unknown message amount"); + + + //Apply these message rates to both UART1 and USB + configureGNSSMessageRates(COM_PORT_UART1, settings.ubxMessages); + configureGNSSMessageRates(COM_PORT_USB, settings.ubxMessages); +} + +//The log test allows us to record a series of different system configurations into +//one file. At the same time, we log the output of the ZED via the USB connection. +//Once complete, the SD log is compared against the USB log to verify both are identical. +//Be sure to set maxLogLength_minutes before running test. maxLogLength_minutes will +//set the length of each test. +void updateLogTest() +{ + //Log is complete, run next text + int rate = 4; + int messages = 5; + int semaphoreWait = 10; + + logTestState++; //Advance to next state + + switch (logTestState) + { + case (LOGTEST_4HZ_5MSG_10MS): + //During the first test, create the log file + reuseLastLog = false; + char fileName[100]; + sprintf(fileName, "%s_LogTest_%02d%02d%02d_%02d%02d%02d.ubx", //SdFat library + platformFilePrefix, + rtc.getYear() - 2000, rtc.getMonth() + 1, rtc.getDay(), //ESP32Time returns month:0-11 + rtc.getHour(true), rtc.getMinute(), rtc.getSecond() //ESP32Time getHour(true) returns hour:0-23 + ); + endSD(false, true); //End previous log + + beginLogging(fileName); + + i2cGNSS.setPortOutput(COM_PORT_USB, COM_TYPE_NMEA | COM_TYPE_UBX | COM_TYPE_RTCM3); //Duplicate UART1 + + rate = 4; + messages = 5; + semaphoreWait = 10; + break; + case (LOGTEST_4HZ_7MSG_10MS): + rate = 4; + messages = 7; + semaphoreWait = 10; + break; + case (LOGTEST_10HZ_5MSG_10MS): + rate = 10; + messages = 5; + semaphoreWait = 10; + break; + case (LOGTEST_10HZ_7MSG_10MS): + rate = 10; + messages = 7; + semaphoreWait = 10; + break; + case (LOGTEST_4HZ_5MSG_50MS): + rate = 4; + messages = 5; + semaphoreWait = 50; + break; + case (LOGTEST_4HZ_7MSG_50MS): + rate = 4; + messages = 7; + semaphoreWait = 50; + break; + case (LOGTEST_10HZ_5MSG_50MS): + rate = 10; + messages = 5; + semaphoreWait = 50; + break; + case (LOGTEST_10HZ_7MSG_50MS): + rate = 10; + messages = 7; + semaphoreWait = 50; + break; + + case (LOGTEST_END): + //Reduce rate + rate = 4; + messages = 5; + semaphoreWait = 50; + setLogTestFrequencyMessages(rate, messages); //Set messages and rate for both UART1 and USB ports + log_d("Log Test Complete"); + break; + + default: + logTestState = LOGTEST_END; + settings.runLogTest = false; + break; + } + + if (settings.runLogTest == true) + { + setLogTestFrequencyMessages(rate, messages); //Set messages and rate for both UART1 and USB ports + + fatSemaphore_shortWait_ms = semaphoreWait / portTICK_PERIOD_MS; //Update variable + + startCurrentLogTime_minutes = millis() / 1000L / 60; //Mark now as start of logging + + log_d("Running log test: %dHz, %dMsg, %dMS", rate, messages, semaphoreWait); + } +} diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index ada55ba7d..e3c2db2c3 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -388,6 +388,9 @@ void menuDebug() Serial.print("28) NTRIP server message parser: "); Serial.printf("%s\r\n", settings.enableNtripServerMessageParsing ? "Enabled" : "Disabled"); + Serial.print("29) Run Logging Test: "); + Serial.printf("%s\r\n", settings.runLogTest ? "Enabled" : "Disabled"); + Serial.println("t) Enter Test Screen"); Serial.println("e) Erase LittleFS"); @@ -570,6 +573,15 @@ void menuDebug() { settings.enableNtripServerMessageParsing ^= 1; } + else if (incoming == 29) + { + settings.runLogTest ^= 1; + + logTestState = LOGTEST_START; //Start test + + //Mark current log file as complete to force test start + startCurrentLogTime_minutes = systemTime_minutes - settings.maxLogLength_minutes; + } else printUnknown(incoming); } diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 385d90977..7b4e0072e 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -177,6 +177,22 @@ typedef enum BluetoothRadioType_e BLUETOOTH_RADIO_OFF, } BluetoothRadioType_e; +enum LogTestState +{ + LOGTEST_START = 0, + LOGTEST_4HZ_5MSG_10MS, + LOGTEST_4HZ_7MSG_10MS, + LOGTEST_10HZ_5MSG_10MS, + LOGTEST_10HZ_7MSG_10MS, + LOGTEST_4HZ_5MSG_50MS, + LOGTEST_4HZ_7MSG_50MS, + LOGTEST_10HZ_5MSG_50MS, + LOGTEST_10HZ_7MSG_50MS, + + LOGTEST_END, +} ; +uint8_t logTestState = LOGTEST_END; + //Radio status LED goes from off (LED off), no connection (blinking), to connected (solid) enum BTState { @@ -474,6 +490,7 @@ typedef struct { uint8_t espnowPeerCount; bool enableNtripServerMessageParsing = false; BluetoothRadioType_e bluetoothRadioType = BLUETOOTH_RADIO_SPP; + bool runLogTest = false; //When set to true, device will create a series of test logs } Settings; Settings settings; From 757b6ec73d460170732d09ebbe96a3e566cffb9f Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 10:27:59 -0600 Subject: [PATCH 098/134] Avoid WiFi static buffer Static buffers fix the ESP-Now multicast issue, but break WiFi normally. Thus, only use static buffers when only ESP-Now is on. It's not yet clear if we can have both WiFi and ESP-Now Multicast. There may be a fix in v2.0.4. --- Firmware/RTK_Surveyor/WiFi.ino | 14 ++++++++++++-- 1 file changed, 12 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 0867d09d1..ce49dec7f 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -209,16 +209,25 @@ void wifiStart(char* ssid, char* pw) #ifdef COMPILE_WIFI if ((wifiState == WIFI_OFF) || (wifiState == WIFI_ON)) { - WiFi.useStaticBuffers(true); //Fix for one to many ESP-Now bug, prior to ESP32 core v2.0.4: https://github.com/espressif/esp-idf/issues/8992 - WiFi.mode(WIFI_STA); #ifdef COMPILE_ESPNOW if (espnowState > ESPNOW_OFF) + { + WiFi.mode(WIFI_MODE_NULL); //We must go Null before setting static buffers + WiFi.useStaticBuffers(true); //Fix for one to many ESP-Now bug, prior to ESP32 core v2.0.4: https://github.com/espressif/esp-idf/issues/8992 + WiFi.mode(WIFI_STA); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); //Enable WiFi + ESP-Now + } else + { + WiFi.mode(WIFI_STA); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Set basic WiFi protocols + } #else //Be sure the standard protocols are turned on. ESP Now have have previously turned them off. + WiFi.mode(WIFI_STA); esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); #endif @@ -257,6 +266,7 @@ void wifiStop() //If ESP-Now is active, change protocol to only Long Range else if (espnowState > ESPNOW_OFF) { + WiFi.mode(WIFI_MODE_NULL); //We must go Null before setting static buffers WiFi.useStaticBuffers(true); //Fix for one to many ESP-Now bug, prior to ESP32 core v2.0.4: https://github.com/espressif/esp-idf/issues/8992 WiFi.mode(WIFI_STA); From 890ad1c724fd10a55a4d910a121214006379f8b5 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 10:31:13 -0600 Subject: [PATCH 099/134] Separate RTCM counts and checking from NtripServer Fix for #292. There are four ways RTCM can be transmitted: Bluetooth, WiFi NTRIP Server, ESP-Now, and external radio. The RTCM count is now processed based on timeout of RTCM bytes received over I2C. RTCM is also passed to NtripServer and ESPNow when enabled. checkRtcmMessage() (originally part of NTRIP Server) has been separated but is non-fucntional. --- Firmware/RTK_Surveyor/Base.ino | 31 +++- Firmware/RTK_Surveyor/Display.ino | 6 +- Firmware/RTK_Surveyor/NVM.ino | 6 +- Firmware/RTK_Surveyor/NtripServer.ino | 200 ++++--------------------- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 19 ++- Firmware/RTK_Surveyor/menuSystem.ino | 6 +- Firmware/RTK_Surveyor/settings.h | 2 +- Firmware/RTK_Surveyor/support.ino | 115 +++++++++++++- 8 files changed, 196 insertions(+), 189 deletions(-) diff --git a/Firmware/RTK_Surveyor/Base.ino b/Firmware/RTK_Surveyor/Base.ino index 41e68589c..750e930b8 100644 --- a/Firmware/RTK_Surveyor/Base.ino +++ b/Firmware/RTK_Surveyor/Base.ino @@ -227,7 +227,34 @@ bool startFixedBase() //Useful for passing the RTCM correction data to a radio, Ntrip broadcaster, etc. void SFE_UBLOX_GNSS::processRTCM(uint8_t incoming) { - ntripServerProcessRTCM(incoming); + //Check for too many digits + if (settings.enableResetDisplay == true) + { + if (rtcmPacketsSent > 99) rtcmPacketsSent = 1; //Trim to two digits to avoid overlap + } + else if (logIncreasing == true) + { + if (rtcmPacketsSent > 999) rtcmPacketsSent = 1; //Trim to three digits to avoid log icon + } + else + { + if (rtcmPacketsSent > 9999) rtcmPacketsSent = 1; + } - espnowProcessRTCM(incoming); + //Determine if we should check this byte with the RTCM checker or simply pass it along + bool passAlongIncomingByte = true; + + if (settings.enableRtcmMessageChecking == true) + passAlongIncomingByte &= checkRtcmMessage(incoming); + + //Give this byte to the various possible transmission methods + if (passAlongIncomingByte) + { + rtcmLastReceived = millis(); + rtcmBytesSent++; + + ntripServerProcessRTCM(incoming); + + espnowProcessRTCM(incoming); + } } diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 73924fcd7..53ca98933 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -1456,10 +1456,10 @@ void printTextwithKerning(const char *newText, uint8_t xPos, uint8_t yPos, uint8 void paintRTCM() { int yPos = 17; - if (bluetoothGetState() != BT_OFF) - printTextCenter("Xmitting", yPos, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted - else + if (ntripServerState == NTRIP_SERVER_CASTING) printTextCenter("Casting", yPos, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted + else + printTextCenter("Xmitting", yPos, QW_FONT_8X16, 1, false); //text, y, font type, kerning, inverted oled.setCursor(0, 39); //x, y oled.setFont(QW_FONT_5X7); diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index 9a1a2ce4c..2f37d7529 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -266,7 +266,7 @@ void recordSystemSettingsToFile(File * settingsFile) settingsFile->println(tempString); } settingsFile->printf("%s=%d\n\r", "espnowPeerCount", settings.espnowPeerCount); - settingsFile->printf("%s=%d\n\r", "enableNtripServerMessageParsing", settings.enableNtripServerMessageParsing); + settingsFile->printf("%s=%d\n\r", "enableRtcmMessageChecking", settings.enableRtcmMessageChecking); settingsFile->printf("%s=%d\n\r", "bluetoothRadioType", settings.bluetoothRadioType); //Record constellation settings @@ -874,8 +874,8 @@ bool parseLine(char* str, Settings *settings) settings->radioType = (RadioType_e)d; else if (strcmp(settingName, "espnowPeerCount") == 0) settings->espnowPeerCount = d; - else if (strcmp(settingName, "enableNtripServerMessageParsing") == 0) - settings->enableNtripServerMessageParsing = d; + else if (strcmp(settingName, "enableRtcmMessageChecking") == 0) + settings->enableRtcmMessageChecking = d; else if (strcmp(settingName, "radioType") == 0) settings->radioType = (RadioType_e)d; else if (strcmp(settingName, "bluetoothRadioType") == 0) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index c2fc963b9..1fff20ded 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -156,123 +156,6 @@ void ntripServerResponse(char * response, size_t maxLength) *response = '\0'; } -static byte ntripServerCrcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; - -//Parse the RTCM transport data -bool ntripServerRtcmMessage(uint8_t data) -{ - static uint16_t bytesRemaining; - static uint16_t length; - static uint16_t message; - static bool sendMessage = false; - - // - // RTCM Standard 10403.2 - Chapter 4, Transport Layer - // - // |<------------- 3 bytes ------------>|<----- length ----->|<- 3 bytes ->| - // | | | | - // +----------+--------+----------------+---------+----------+-------------+ - // | Preamble | Fill | Message Length | Message | Fill | CRC-24Q | - // | 8 bits | 6 bits | 10 bits | n-bits | 0-7 bits | 24 bits | - // | 0xd3 | 000000 | (in bytes) | | zeros | | - // +----------+--------+----------------+---------+----------+-------------+ - // | | - // |<-------------------------------- CRC -------------------------------->| - // - - switch (ntripServerCrcState) - { - //Read the upper two bits of the length - case RTCM_TRANSPORT_STATE_READ_LENGTH_1: - if (!(data & 3)) - { - length = data << 8; - ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_LENGTH_2; - break; - } - - //Wait for the preamble byte - ntripServerCrcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; - - //Fall through - // | - // | - // V - - //Wait for the preamble byte (0xd3) - case RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3: - sendMessage = false; - if (data == 0xd3) - { - ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_LENGTH_1; - sendMessage = (ntripServerState == NTRIP_SERVER_CASTING); - } - break; - - //Read the lower 8 bits of the length - case RTCM_TRANSPORT_STATE_READ_LENGTH_2: - length |= data; - bytesRemaining = length; - ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_MESSAGE_1; - break; - - //Read the upper 8 bits of the message number - case RTCM_TRANSPORT_STATE_READ_MESSAGE_1: - message = data << 4; - bytesRemaining -= 1; - ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_MESSAGE_2; - break; - - //Read the lower 4 bits of the message number - case RTCM_TRANSPORT_STATE_READ_MESSAGE_2: - message |= data >> 4; - bytesRemaining -= 1; - ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_DATA; - break; - - //Read the rest of the message - case RTCM_TRANSPORT_STATE_READ_DATA: - bytesRemaining -= 1; - if (bytesRemaining <= 0) - ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_CRC_1; - break; - - //Read the upper 8 bits of the CRC - case RTCM_TRANSPORT_STATE_READ_CRC_1: - ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_CRC_2; - break; - - //Read the middle 8 bits of the CRC - case RTCM_TRANSPORT_STATE_READ_CRC_2: - ntripServerCrcState = RTCM_TRANSPORT_STATE_READ_CRC_3; - break; - - //Read the lower 8 bits of the CRC - case RTCM_TRANSPORT_STATE_READ_CRC_3: - ntripServerCrcState = RTCM_TRANSPORT_STATE_CHECK_CRC; - break; - } - - //Check the CRC - if (ntripServerCrcState == RTCM_TRANSPORT_STATE_CHECK_CRC) - { - ntripServerCrcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; - - //Account for this message - rtcmPacketsSent++; - - //Display the RTCM message header - if (settings.enablePrintNtripServerRtcm && (!inMainMenu)) - { - printTimeStamp(); - Serial.printf (" Tx RTCM %d, %2d bytes\r\n", message, 3 + length + 3); - } - } - - //Let the upper layer know if this message should be sent - return sendMessage && (ntripServerState == NTRIP_SERVER_CASTING); -} - //Update the state of the NTRIP server state machine void ntripServerSetState(byte newState) { @@ -319,75 +202,52 @@ void ntripServerSetState(byte newState) //This function gets called as each RTCM byte comes in void ntripServerProcessRTCM(uint8_t incoming) { - //Check for too many digits - if (settings.enableResetDisplay == true) - { - if (rtcmPacketsSent > 99) rtcmPacketsSent = 1; //Trim to two digits to avoid overlap - } - else if (logIncreasing == true) - { - if (rtcmPacketsSent > 999) rtcmPacketsSent = 1; //Trim to three digits to avoid log icon - } - else - { - if (rtcmPacketsSent > 9999) rtcmPacketsSent = 1; - } - #ifdef COMPILE_WIFI - uint32_t currentMilliseconds; - static uint32_t previousMilliseconds = 0; - if (online.rtc && (ntripServerState == NTRIP_SERVER_CASTING)) + if (ntripServerState == NTRIP_SERVER_CASTING) { - //Timestamp the RTCM messages - currentMilliseconds = millis(); - if (settings.enablePrintNtripServerRtcm - && (!settings.enableNtripServerMessageParsing) - && (!inMainMenu) - && ((currentMilliseconds - previousMilliseconds) > 5)) - { - printTimeStamp(); - // 1 2 3 - //123456789012345678901234567890 - //YYYY-mm-dd HH:MM:SS.xxxrn0 - struct tm timeinfo = rtc.getTimeStruct(); - char timestamp[30]; - strftime(timestamp, sizeof(timestamp), "%Y-%m-%d %H:%M:%S", &timeinfo); - Serial.printf(" Tx RTCM: %s.%03ld\r\n", timestamp, rtc.getMillis()); - } - previousMilliseconds = currentMilliseconds; - - //Pass this message to the RTCM checker - bool passAlongIncomingByte = true; - - //Check this byte with RTCM checker if enabled - if (settings.enableNtripServerMessageParsing == true) - passAlongIncomingByte &= ntripServerRtcmMessage(incoming); - else + //Generate and print timestamp if needed + uint32_t currentMilliseconds; + static uint32_t previousMilliseconds = 0; + if (online.rtc) { - //If we have not gotten new RTCM bytes for a period of time, assume end of frame - if (millis() - ntripServerTimer > 100 && ntripServerBytesSent > 0) + //Timestamp the RTCM messages + currentMilliseconds = millis(); + if (settings.enablePrintNtripServerRtcm + && (!settings.enableRtcmMessageChecking) + && (!inMainMenu) + && ((currentMilliseconds - previousMilliseconds) > 5)) { - if(!inMainMenu) log_d("NTRIP Server transmitted %d RTCM bytes to Caster", ntripServerBytesSent); - ntripServerBytesSent = 0; - rtcmPacketsSent++; //If not checking RTCM CRC, count based on timeout + printTimeStamp(); + // 1 2 3 + //123456789012345678901234567890 + //YYYY-mm-dd HH:MM:SS.xxxrn0 + struct tm timeinfo = rtc.getTimeStruct(); + char timestamp[30]; + strftime(timestamp, sizeof(timestamp), "%Y-%m-%d %H:%M:%S", &timeinfo); + Serial.printf(" Tx RTCM: %s.%03ld\r\n", timestamp, rtc.getMillis()); } + previousMilliseconds = currentMilliseconds; } - if (passAlongIncomingByte) + //If we have not gotten new RTCM bytes for a period of time, assume end of frame + if (millis() - ntripServerTimer > 100 && ntripServerBytesSent > 0) { - ntripServer->write(incoming); //Send this byte to socket - ntripServerBytesSent++; - ntripServerTimer = millis(); - wifiOutgoingRTCM = true; + if (!inMainMenu) log_d("NTRIP Server transmitted %d RTCM bytes to Caster", ntripServerBytesSent); + ntripServerBytesSent = 0; } + + ntripServer->write(incoming); //Send this byte to socket + ntripServerBytesSent++; + ntripServerTimer = millis(); + wifiOutgoingRTCM = true; } //Indicate that the GNSS is providing correction data else if (ntripServerState == NTRIP_SERVER_WAIT_GNSS_DATA) { ntripServerSetState(NTRIP_SERVER_CONNECTING); - ntripServerCrcState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; + rtcmParsingState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; } #endif //COMPILE_WIFI } diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 3d7965e91..882367f6a 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -401,7 +401,9 @@ uint64_t lastLogSize = 0; bool logIncreasing = false; //Goes true when log file is greater than lastLogSize bool reuseLastLog = false; //Goes true if we have a reset due to software (rather than POR) -uint32_t rtcmPacketsSent = 0; //Used to count RTCM packets sent via processRTCM() +uint16_t rtcmPacketsSent = 0; //Used to count RTCM packets sent via processRTCM() +uint32_t rtcmBytesSent = 0; +uint32_t rtcmLastReceived = 0; uint32_t maxSurveyInWait_s = 60L * 15L; //Re-start survey-in after X seconds @@ -468,6 +470,8 @@ bool wifiOutgoingRTCM = false; bool espnowIncomingRTCM = false; bool espnowOutgoingRTCM = false; +static byte rtcmParsingState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; + //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- /* +---------------------------------------+ +----------+ @@ -840,6 +844,13 @@ void updateRTC() //Internal ESP NOW radio - Use the ESP32 to directly transmit/receive RTCM over 2.4GHz (no WiFi needed) void updateRadio() { + //If we have not gotten new RTCM bytes for a period of time, assume end of frame + if (millis() - rtcmLastReceived > 50 && rtcmBytesSent > 0) + { + rtcmBytesSent = 0; + rtcmPacketsSent++; //If not checking RTCM CRC, count based on timeout + } + #ifdef COMPILE_ESPNOW if (settings.radioType == RADIO_ESPNOW) { @@ -849,11 +860,9 @@ void updateRadio() //then we've reached the end of the RTCM stream. Send partial buffer. if (espnowOutgoingSpot > 0 && (millis() - espnowLastAdd) > 50) { - rtcmPacketsSent++; //Assume this is the end of the RTCM frame - esp_now_send(0, (uint8_t *) &espnowOutgoing, espnowOutgoingSpot); //Send partial packet to all peers - - if(!inMainMenu) log_d("ESPNOW transmitted %d RTCM bytes", espnowBytesSent + espnowOutgoingSpot); + + if (!inMainMenu) log_d("ESPNOW transmitted %d RTCM bytes", espnowBytesSent + espnowOutgoingSpot); espnowBytesSent = 0; espnowOutgoingSpot = 0; //Reset } diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index ada55ba7d..9de333206 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -385,8 +385,8 @@ void menuDebug() Serial.print("27) Print duplicate states: "); Serial.printf("%s\r\n", settings.enablePrintDuplicateStates ? "Enabled" : "Disabled"); - Serial.print("28) NTRIP server message parser: "); - Serial.printf("%s\r\n", settings.enableNtripServerMessageParsing ? "Enabled" : "Disabled"); + Serial.print("28) RTCM message checking: "); + Serial.printf("%s\r\n", settings.enableRtcmMessageChecking ? "Enabled" : "Disabled"); Serial.println("t) Enter Test Screen"); @@ -568,7 +568,7 @@ void menuDebug() } else if (incoming == 28) { - settings.enableNtripServerMessageParsing ^= 1; + settings.enableRtcmMessageChecking ^= 1; } else printUnknown(incoming); diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 385d90977..eff25c893 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -472,7 +472,7 @@ typedef struct { RadioType_e radioType = RADIO_EXTERNAL; uint8_t espnowPeers[5][6]; //Max of 5 peers. Contains the MAC addresses (6 bytes) of paired units uint8_t espnowPeerCount; - bool enableNtripServerMessageParsing = false; + bool enableRtcmMessageChecking = false; BluetoothRadioType_e bluetoothRadioType = BLUETOOTH_RADIO_SPP; } Settings; Settings settings; diff --git a/Firmware/RTK_Surveyor/support.ino b/Firmware/RTK_Surveyor/support.ino index d57e1b3c6..0ccc155b0 100644 --- a/Firmware/RTK_Surveyor/support.ino +++ b/Firmware/RTK_Surveyor/support.ino @@ -65,8 +65,8 @@ int getMenuChoice(int * value, int numberOfSeconds) //Handle single character input if ((!digits) - && (((incoming >= 'a') && (incoming <= 'z')) - || ((incoming >= 'A') && (incoming <= 'Z')))) + && (((incoming >= 'a') && (incoming <= 'z')) + || ((incoming >= 'A') && (incoming <= 'Z')))) { //Echo the incoming character Serial.printf("%c\r\n", incoming); @@ -435,3 +435,114 @@ void printTimeStamp() previousMilliseconds = currentMilliseconds; } } + +//Parse the RTCM transport data +bool checkRtcmMessage(uint8_t data) +{ + static uint16_t bytesRemaining; + static uint16_t length; + static uint16_t message; + static bool sendMessage = false; + + // RTCM Standard 10403.2 - Chapter 4, Transport Layer + // + // |<------------- 3 bytes ------------>|<----- length ----->|<- 3 bytes ->| + // | | | | + // +----------+--------+----------------+---------+----------+-------------+ + // | Preamble | Fill | Message Length | Message | Fill | CRC-24Q | + // | 8 bits | 6 bits | 10 bits | n-bits | 0-7 bits | 24 bits | + // | 0xd3 | 000000 | (in bytes) | | zeros | | + // +----------+--------+----------------+---------+----------+-------------+ + // | | + // |<-------------------------------- CRC -------------------------------->| + // + + switch (rtcmParsingState) + { + //Read the upper two bits of the length + case RTCM_TRANSPORT_STATE_READ_LENGTH_1: + if (!(data & 3)) + { + length = data << 8; + rtcmParsingState = RTCM_TRANSPORT_STATE_READ_LENGTH_2; + break; + } + + //Wait for the preamble byte + rtcmParsingState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; + + //Fall through + // | + // | + // V + + //Wait for the preamble byte (0xd3) + case RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3: + sendMessage = false; + if (data == 0xd3) + { + rtcmParsingState = RTCM_TRANSPORT_STATE_READ_LENGTH_1; + sendMessage = true; + } + break; + + //Read the lower 8 bits of the length + case RTCM_TRANSPORT_STATE_READ_LENGTH_2: + length |= data; + bytesRemaining = length; + rtcmParsingState = RTCM_TRANSPORT_STATE_READ_MESSAGE_1; + break; + + //Read the upper 8 bits of the message number + case RTCM_TRANSPORT_STATE_READ_MESSAGE_1: + message = data << 4; + bytesRemaining -= 1; + rtcmParsingState = RTCM_TRANSPORT_STATE_READ_MESSAGE_2; + break; + + //Read the lower 4 bits of the message number + case RTCM_TRANSPORT_STATE_READ_MESSAGE_2: + message |= data >> 4; + bytesRemaining -= 1; + rtcmParsingState = RTCM_TRANSPORT_STATE_READ_DATA; + break; + + //Read the rest of the message + case RTCM_TRANSPORT_STATE_READ_DATA: + bytesRemaining -= 1; + if (bytesRemaining <= 0) + rtcmParsingState = RTCM_TRANSPORT_STATE_READ_CRC_1; + break; + + //Read the upper 8 bits of the CRC + case RTCM_TRANSPORT_STATE_READ_CRC_1: + rtcmParsingState = RTCM_TRANSPORT_STATE_READ_CRC_2; + break; + + //Read the middle 8 bits of the CRC + case RTCM_TRANSPORT_STATE_READ_CRC_2: + rtcmParsingState = RTCM_TRANSPORT_STATE_READ_CRC_3; + break; + + //Read the lower 8 bits of the CRC + case RTCM_TRANSPORT_STATE_READ_CRC_3: + rtcmParsingState = RTCM_TRANSPORT_STATE_CHECK_CRC; + break; + } + + //Check the CRC + if (rtcmParsingState == RTCM_TRANSPORT_STATE_CHECK_CRC) + { + rtcmParsingState = RTCM_TRANSPORT_STATE_WAIT_FOR_PREAMBLE_D3; + + //Display the RTCM message header + if (settings.enablePrintNtripServerRtcm && (!inMainMenu)) + { + printTimeStamp(); + Serial.printf (" Tx RTCM %d, %2d bytes\r\n", message, 3 + length + 3); + } + } + + //Let the upper layer know if this message should be sent + return sendMessage; +} From 63da5a4d562229136fb163521b19386212efc754 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 10:44:27 -0600 Subject: [PATCH 100/134] Add test features for ESP-Now menu Only available in developer mode --- Firmware/RTK_Surveyor/menuMain.ino | 32 ++++++++++++++++++++++++++++++ 1 file changed, 32 insertions(+) diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index 891918c2f..a2cc9b83f 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -338,6 +338,10 @@ void menuRadio() Serial.println("2) Pair radios"); Serial.println("3) Forget all radios"); +#ifdef ENABLE_DEVELOPER + Serial.println("4) Add dummy radio"); + Serial.println("5) Send dummy data"); +#endif } Serial.println("x) Exit"); @@ -406,6 +410,34 @@ void menuRadio() Serial.println("Radios forgotten"); } } +#ifdef ENABLE_DEVELOPER + else if (settings.radioType == RADIO_ESPNOW && incoming == 4) + { + //TODO remove + uint8_t peer1[] = {0xB8, 0xD6, 0x1A, 0x0D, 0x8F, 0x9C}; //Facet + if (esp_now_is_peer_exist(peer1) == true) + log_d("Peer already exists"); + else + { + //Add new peer to system + espnowAddPeer(peer1); + + //Record this MAC to peer list + memcpy(settings.espnowPeers[settings.espnowPeerCount], peer1, 6); + settings.espnowPeerCount++; + settings.espnowPeerCount %= ESPNOW_MAX_PEERS; + recordSystemSettings(); + } + + espnowSetState(ESPNOW_PAIRED); + } + else if (settings.radioType == RADIO_ESPNOW && incoming == 5) + { + //TODO remove + uint8_t espnowData[] = "This is the long string to test how quickly we can send one string to the other unit. I am going to need a much longer sentence if I want to get a long amount of data into one transmission. This is nearing 200 characters but needs to be near 250."; + esp_now_send(0, (uint8_t *) &espnowData, sizeof(espnowData)); //Send packet to all peers + } +#endif else if (incoming == STATUS_PRESSED_X) break; From 30c28076bc2d3615f12c58c15df1e965746a4c1a Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 10:46:01 -0600 Subject: [PATCH 101/134] Remove COMPILE_IDLE_TASKS gate Feature is controlled, and turned off by default, via setting enablePrintIdleTime --- Firmware/RTK_Surveyor/Begin.ino | 2 -- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 1 - Firmware/RTK_Surveyor/Tasks.ino | 2 -- 3 files changed, 5 deletions(-) diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index e1aa45311..61b4d8f21 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -705,7 +705,6 @@ bool beginExternalTriggers() void beginIdleTasks() { -#ifdef COMPILE_IDLE_TASKS if (settings.enablePrintIdleTime == true) { char taskName[32]; @@ -724,7 +723,6 @@ void beginIdleTasks() index); //Core where task should run, 0=core, 1=Arduino } } -#endif //COMPILE_IDLE_TASKS } void beginI2C() diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 8a4c7e763..a3bdb3c58 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -30,7 +30,6 @@ const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_ESPNOW //Requires WiFi. Comment out to remove ESP-Now functionality. #define COMPILE_BT //Comment out to remove Bluetooth functionality #define COMPILE_L_BAND //Comment out to remove L-Band functionality -#define COMPILE_IDLE_TASKS //Comment out to remove idle tasks #define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) //Define the RTK board identifier: diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 66710a5f6..5482e659d 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -621,7 +621,6 @@ void ButtonCheckTask(void *e) } } -#ifdef COMPILE_IDLE_TASKS void idleTask(void *e) { int cpu = xPortGetCoreID(); @@ -671,4 +670,3 @@ void idleTask(void *e) taskYIELD(); } } -#endif //COMPILE_IDLE_TASKS From 0b8529de3d6827dbdf4728bf55c14790caefe1ec Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 14:33:42 -0600 Subject: [PATCH 102/134] Revert commit a93bf56 ESP-Now/WiFi static buffers Using static buffers to fix the ESP-Now multicast issue breaks WiFi. We may need to wait until the ESP32 core incorporates the cfg.cache_tx_buf_num = 4; fix. --- Firmware/RTK_Surveyor/ESPNOW.ino | 1 - Firmware/RTK_Surveyor/WiFi.ino | 9 +-------- 2 files changed, 1 insertion(+), 9 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index 4a231079e..d20f57650 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -93,7 +93,6 @@ void espnowStart() if (wifiState == WIFI_OFF && espnowState == ESPNOW_OFF) { //Radio is off, turn it on - WiFi.useStaticBuffers(true); //Fix for one to many ESP-Now bug, prior to ESP32 core v2.0.4: https://github.com/espressif/esp-idf/issues/8992 WiFi.mode(WIFI_STA); esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_LR); diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index ce49dec7f..73d8f51bd 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -209,20 +209,15 @@ void wifiStart(char* ssid, char* pw) #ifdef COMPILE_WIFI if ((wifiState == WIFI_OFF) || (wifiState == WIFI_ON)) { + WiFi.mode(WIFI_STA); #ifdef COMPILE_ESPNOW if (espnowState > ESPNOW_OFF) { - WiFi.mode(WIFI_MODE_NULL); //We must go Null before setting static buffers - WiFi.useStaticBuffers(true); //Fix for one to many ESP-Now bug, prior to ESP32 core v2.0.4: https://github.com/espressif/esp-idf/issues/8992 - WiFi.mode(WIFI_STA); - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); //Enable WiFi + ESP-Now } else { - WiFi.mode(WIFI_STA); - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Set basic WiFi protocols } #else @@ -266,8 +261,6 @@ void wifiStop() //If ESP-Now is active, change protocol to only Long Range else if (espnowState > ESPNOW_OFF) { - WiFi.mode(WIFI_MODE_NULL); //We must go Null before setting static buffers - WiFi.useStaticBuffers(true); //Fix for one to many ESP-Now bug, prior to ESP32 core v2.0.4: https://github.com/espressif/esp-idf/issues/8992 WiFi.mode(WIFI_STA); // Enable long range, PHY rate of ESP32 will be 512Kbps or 256Kbps From ab7946d138bd2bb2929d1f6521761c460eec9204 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 14:34:27 -0600 Subject: [PATCH 103/134] Move reset counter slightly to right --- Firmware/RTK_Surveyor/Display.ino | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 53ca98933..fba584329 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -2275,7 +2275,7 @@ void paintResets() if (settings.enableResetDisplay == true) { oled.setFont(QW_FONT_5X7); //Small font - oled.setCursor(16 + (8 * 3) + 6, 38); //x, y + oled.setCursor(16 + (8 * 3) + 7, 38); //x, y oled.print(settings.resetCount); } } From 908cdeabeee346fbd83666b5c9487526ec6b09f7 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 15:26:59 -0600 Subject: [PATCH 104/134] Remove unused variables --- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 14 -------------- 1 file changed, 14 deletions(-) diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index fc0c0b07d..204737da0 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -372,7 +372,6 @@ char deviceName[70]; //The serial string that is broadcast. Ex: 'Surveyor Base-B const byte menuTimeout = 15; //Menus will exit/timeout after this number of seconds int systemTime_minutes = 0; //Used to test if logging is less than max minutes uint32_t powerPressedStartTime = 0; //Times how long user has been holding power button, used for power down -uint8_t debounceDelay = 20; //ms to delay between button reads bool inMainMenu = false; //Set true when in the serial config menu system. uint32_t lastBattUpdate = 0; @@ -408,8 +407,6 @@ uint32_t maxSurveyInWait_s = 60L * 15L; //Re-start survey-in after X seconds uint32_t totalWriteTime = 0; //Used to calculate overall write speed using SdFat library -bool setupByPowerButton = false; //We can change setup via tapping power button - uint16_t svinObservationTime = 0; //Use globals so we don't have to request these values multiple times (slow response) float svinMeanAccuracy = 0; @@ -423,17 +420,6 @@ uint32_t triggerCount = 0; //Global copy - TM2 event counter uint32_t towMsR = 0; //Global copy - Time Of Week of rising edge (ms) uint32_t towSubMsR = 0; //Global copy - Millisecond fraction of Time Of Week of rising edge in nanoseconds -int timeBetweenGGAUpdate_ms = 10000; //GGA is required for Rev2 NTRIP casters. Don't transmit but once every 10 seconds -long lastTransmittedGGA_ms = 0; - -//Used for GGA sentence parsing from incoming NMEA -bool ggaSentenceStarted = false; -bool ggaSentenceComplete = false; -bool ggaTransmitComplete = false; //Goes true once we transmit GGA to the caster -char ggaSentence[128] = {0}; -byte ggaSentenceSpot = 0; -int ggaSentenceEndSpot = 0; - bool newAPSettings = false; //Goes true when new setting is received via AP config. Allows us to record settings when combined with a reset. unsigned int binBytesSent = 0; //Tracks firmware bytes sent over WiFi OTA update via AP config. From 99392adf30eb2423eee8fa0710e950fb4c15bf9d Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 15:27:11 -0600 Subject: [PATCH 105/134] Add additional log tests --- Firmware/RTK_Surveyor/menuMessages.ino | 22 ++++++++++++++++++++++ Firmware/RTK_Surveyor/settings.h | 4 ++++ 2 files changed, 26 insertions(+) diff --git a/Firmware/RTK_Surveyor/menuMessages.ino b/Firmware/RTK_Surveyor/menuMessages.ino index 6406a7654..3bf78a6c8 100644 --- a/Firmware/RTK_Surveyor/menuMessages.ino +++ b/Firmware/RTK_Surveyor/menuMessages.ino @@ -757,6 +757,28 @@ void updateLogTest() messages = 7; semaphoreWait = 10; break; + + case (LOGTEST_4HZ_5MSG_0MS): + rate = 4; + messages = 5; + semaphoreWait = 0; + break; + case (LOGTEST_4HZ_7MSG_0MS): + rate = 4; + messages = 7; + semaphoreWait = 0; + break; + case (LOGTEST_10HZ_5MSG_0MS): + rate = 10; + messages = 5; + semaphoreWait = 0; + break; + case (LOGTEST_10HZ_7MSG_0MS): + rate = 10; + messages = 7; + semaphoreWait = 0; + break; + case (LOGTEST_4HZ_5MSG_50MS): rate = 4; messages = 5; diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index e409b74c3..2108137c8 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -184,6 +184,10 @@ enum LogTestState LOGTEST_4HZ_7MSG_10MS, LOGTEST_10HZ_5MSG_10MS, LOGTEST_10HZ_7MSG_10MS, + LOGTEST_4HZ_5MSG_0MS, + LOGTEST_4HZ_7MSG_0MS, + LOGTEST_10HZ_5MSG_0MS, + LOGTEST_10HZ_7MSG_0MS, LOGTEST_4HZ_5MSG_50MS, LOGTEST_4HZ_7MSG_50MS, LOGTEST_10HZ_5MSG_50MS, From 25b7b8f77203247ad1ca779ae67c48bd0c4d0c4e Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 16:04:56 -0600 Subject: [PATCH 106/134] Blink base icons during wait --- Firmware/RTK_Surveyor/Display.ino | 26 +++++++++++++++++++++++--- 1 file changed, 23 insertions(+), 3 deletions(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index fba584329..f4618bcf4 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -1080,6 +1080,7 @@ uint32_t setWiFiIcon() uint32_t setModeIcon() { uint32_t icons = 0; + switch (systemState) { case (STATE_ROVER_NOT_STARTED): @@ -1100,17 +1101,17 @@ uint32_t setModeIcon() case (STATE_BASE_NOT_STARTED): //Do nothing. Static display shown during state change. break; - case (STATE_BASE_TEMP_SETTLE): + icons |= blinkBaseIcon(ICON_BASE_TEMPORARY); break; case (STATE_BASE_TEMP_SURVEY_STARTED): - //TODO need blinking - icons |= ICON_BASE_TEMPORARY; + icons |= blinkBaseIcon(ICON_BASE_TEMPORARY); break; case (STATE_BASE_TEMP_TRANSMITTING): icons |= ICON_BASE_TEMPORARY; break; case (STATE_BASE_FIXED_NOT_STARTED): + //Do nothing. Static display shown during state change. break; case (STATE_BASE_FIXED_TRANSMITTING): icons |= ICON_BASE_FIXED; @@ -1122,6 +1123,25 @@ uint32_t setModeIcon() return (icons); } +uint32_t blinkBaseIcon(uint32_t iconType) +{ + uint32_t icons = 0; + + //Limit how often we update this spot + if (millis() - thirdRadioSpotTimer > 1000) + { + thirdRadioSpotTimer = millis(); + thirdRadioSpotBlink ^= 1; //Share the spot + } + + if (thirdRadioSpotBlink == false) + icons |= iconType; + else + icons |= ICON_BLANK_RIGHT; + + return icons; +} + /* 111111111122222222223333333333444444444455555555556666 0123456789012345678901234567890123456789012345678901234567890123 From 57b298efdd8dda849e6658ad49a38ce01ceebbf6 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 16:05:09 -0600 Subject: [PATCH 107/134] Add NMEA message to log between tests --- Firmware/RTK_Surveyor/menuMessages.ino | 20 ++++++++++++++++++-- Firmware/RTK_Surveyor/settings.h | 1 + 2 files changed, 19 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/menuMessages.ino b/Firmware/RTK_Surveyor/menuMessages.ino index 3bf78a6c8..9b75fac7f 100644 --- a/Firmware/RTK_Surveyor/menuMessages.ino +++ b/Firmware/RTK_Surveyor/menuMessages.ino @@ -804,7 +804,7 @@ void updateLogTest() //Reduce rate rate = 4; messages = 5; - semaphoreWait = 50; + semaphoreWait = 10; setLogTestFrequencyMessages(rate, messages); //Set messages and rate for both UART1 and USB ports log_d("Log Test Complete"); break; @@ -823,6 +823,22 @@ void updateLogTest() startCurrentLogTime_minutes = millis() / 1000L / 60; //Mark now as start of logging - log_d("Running log test: %dHz, %dMsg, %dMS", rate, messages, semaphoreWait); + char logMessage[100]; + sprintf(logMessage, "Start log test: %dHz, %dMsg, %dMS", rate, messages, semaphoreWait); + + char nmeaMessage[100]; //Max NMEA sentence length is 82 + createNMEASentence(CUSTOM_NMEA_TYPE_LOGTEST_STATUS, nmeaMessage, logMessage); //textID, buffer, text + + if (xSemaphoreTake(sdCardSemaphore, fatSemaphore_longWait_ms) == pdPASS) + { + ubxFile->println(nmeaMessage); + xSemaphoreGive(sdCardSemaphore); + } + else + { + log_w("sdCardSemaphore failed to yield, menuMessages.ino line %d", __LINE__); + } + + log_d("%s", logMessage); } } diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index 2108137c8..b21a49439 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -95,6 +95,7 @@ typedef enum CUSTOM_NMEA_TYPE_SYSTEM_VERSION, CUSTOM_NMEA_TYPE_ZED_VERSION, CUSTOM_NMEA_TYPE_STATUS, + CUSTOM_NMEA_TYPE_LOGTEST_STATUS, } customNmeaType_e; //Freeze and blink LEDs if we hit a bad error From 1dc5c3496b696f02bcc0c510eaeebe2b9c9e46a9 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 16:07:17 -0600 Subject: [PATCH 108/134] Remove BT Congestion settings Left over from Bluetooth congestion settings (and custom BT implementation) --- Firmware/RTK_Surveyor/Bluetooth.ino | 11 -------- Firmware/RTK_Surveyor/NVM.ino | 3 -- Firmware/RTK_Surveyor/Tasks.ino | 37 +++++++------------------ Firmware/RTK_Surveyor/bluetoothSelect.h | 14 ---------- Firmware/RTK_Surveyor/menuSystem.ino | 8 ------ Firmware/RTK_Surveyor/settings.h | 1 - 6 files changed, 10 insertions(+), 64 deletions(-) diff --git a/Firmware/RTK_Surveyor/Bluetooth.ino b/Firmware/RTK_Surveyor/Bluetooth.ino index 6e2773c5c..d019868d8 100644 --- a/Firmware/RTK_Surveyor/Bluetooth.ino +++ b/Firmware/RTK_Surveyor/Bluetooth.ino @@ -69,17 +69,6 @@ byte bluetoothGetState() #endif //COMPILE_BT } -//Determine if the Bluetooth link is congested -bool bluetoothIsCongested() -{ -#ifdef COMPILE_BT - //return bluetoothSerial->isCongested(); - return false; -#else //COMPILE_BT - return false; -#endif //COMPILE_BT -} - //Read data from the Bluetooth device int bluetoothReadBytes(uint8_t * buffer, int length) { diff --git a/Firmware/RTK_Surveyor/NVM.ino b/Firmware/RTK_Surveyor/NVM.ino index 2f37d7529..779689416 100644 --- a/Firmware/RTK_Surveyor/NVM.ino +++ b/Firmware/RTK_Surveyor/NVM.ino @@ -181,7 +181,6 @@ void recordSystemSettingsToFile(File * settingsFile) settingsFile->printf("%s=%d\n\r", "sppTxQueueSize", settings.sppTxQueueSize); settingsFile->printf("%s=%d\n\r", "dynamicModel", settings.dynamicModel); settingsFile->printf("%s=%d\n\r", "lastState", settings.lastState); - settingsFile->printf("%s=%d\n\r", "throttleDuringSPPCongestion", settings.throttleDuringSPPCongestion); settingsFile->printf("%s=%d\n\r", "enableSensorFusion", settings.enableSensorFusion); settingsFile->printf("%s=%d\n\r", "autoIMUmountAlignment", settings.autoIMUmountAlignment); settingsFile->printf("%s=%d\n\r", "enableResetDisplay", settings.enableResetDisplay); @@ -688,8 +687,6 @@ bool parseLine(char* str, Settings *settings) settings->updateZEDSettings = true; } } - else if (strcmp(settingName, "throttleDuringSPPCongestion") == 0) - settings->throttleDuringSPPCongestion = d; else if (strcmp(settingName, "enableSensorFusion") == 0) { if (settings->enableSensorFusion != d) diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 5482e659d..332a5e08b 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -14,11 +14,11 @@ void F9PSerialWriteTask(void *e) { //Pass bytes to GNSS receiver int s = bluetoothReadBytes(wBuffer, sizeof(wBuffer)); - + //TODO - control if this RTCM source should be listened to or not serialGNSS.write(wBuffer, s); bluetoothIncomingRTCM = true; - if(!inMainMenu) log_d("Bluetooth received %d RTCM bytes, sent to ZED", s); + if (!inMainMenu) log_d("Bluetooth received %d RTCM bytes, sent to ZED", s); if (settings.enableTaskReports == true) Serial.printf("SerialWriteTask High watermark: %d\n\r", uxTaskGetStackHighWaterMark(NULL)); @@ -170,34 +170,17 @@ void F9PSerialReadTask(void *e) if ((btTail + btBytesToSend) >= sizeof(rBuffer)) btBytesToSend = sizeof(rBuffer) - btTail; - if ((bluetoothIsCongested() == false) || (settings.throttleDuringSPPCongestion == false)) + //Push new data to BT SPP if not congested or not throttling + btBytesToSend = bluetoothWriteBytes(&rBuffer[btTail], btBytesToSend); + if (btBytesToSend > 0) { - //Push new data to BT SPP if not congested or not throttling - btBytesToSend = bluetoothWriteBytes(&rBuffer[btTail], btBytesToSend); - if (btBytesToSend > 0) - { - //If we are in base mode, assume part of the outgoing data is RTCM - if (systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) - bluetoothOutgoingRTCM = true; - } - else - log_w("BT failed to send"); + //If we are in base mode, assume part of the outgoing data is RTCM + if (systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) + bluetoothOutgoingRTCM = true; } else - { - //Don't push data to BT SPP if there is congestion to prevent heap hits. - if (btBytesToSend >= (sizeof(rBuffer) - 1)) - { - //Error - no more room in the buffer, drop a buffer's worth of data - btTail = dataHead; - Serial.printf("ERROR - BT congestion dropped %d bytes: GNSS --> Bluetooth\r\n", btBytesToSend); - } - else - { - log_w("BT congestion delayed %d bytes, Tasks.ino line %d", btBytesToSend, __LINE__); - btBytesToSend = 0; - } - } + log_w("BT failed to send"); + //Account for the sent or dropped data btTail += btBytesToSend; diff --git a/Firmware/RTK_Surveyor/bluetoothSelect.h b/Firmware/RTK_Surveyor/bluetoothSelect.h index decd4d855..7ba9e0a10 100644 --- a/Firmware/RTK_Surveyor/bluetoothSelect.h +++ b/Firmware/RTK_Surveyor/bluetoothSelect.h @@ -61,14 +61,6 @@ class BTClassicSerial : public virtual BTSerialInterface, public BluetoothSerial return BluetoothSerial::readBytes(buffer, bufferSize); } - bool isCongested() - { - // Removed congestion testing in v2.4 - // TODO Remove settings and checking - return(false); - //return BluetoothSerial::isCongested(); - } - size_t write(const uint8_t *buffer, size_t size) { return BluetoothSerial::write(buffer, size); @@ -122,12 +114,6 @@ class BTLESerial: public virtual BTSerialInterface, public BleSerial return BleSerial::readBytes(buffer, bufferSize); } - bool isCongested() - { - // not currently supported in this implementation - return false; - } - size_t write(const uint8_t *buffer, size_t size) { return BleSerial::write(buffer, size); diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index f2f2ac1a9..5f3fd5ba5 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -321,10 +321,6 @@ void menuDebug() Serial.print("6) Set SPP TX Buffer Size: "); Serial.println(settings.sppTxQueueSize); - Serial.print("7) Throttle BT Transmissions During SPP Congestion: "); - if (settings.throttleDuringSPPCongestion == true) Serial.println("Enabled"); - else Serial.println("Disabled"); - Serial.printf("8) Display Reset Counter: %d - ", settings.resetCount); if (settings.enableResetDisplay == true) Serial.println("Enabled"); else Serial.println("Disabled"); @@ -465,10 +461,6 @@ void menuDebug() settings.sppTxQueueSize = queSize; //Recorded to NVM and file at main menu exit } } - else if (incoming == 7) - { - settings.throttleDuringSPPCongestion ^= 1; - } else if (incoming == 8) { settings.enableResetDisplay ^= 1; diff --git a/Firmware/RTK_Surveyor/settings.h b/Firmware/RTK_Surveyor/settings.h index b21a49439..f7380e988 100644 --- a/Firmware/RTK_Surveyor/settings.h +++ b/Firmware/RTK_Surveyor/settings.h @@ -294,7 +294,6 @@ typedef struct { uint16_t sppTxQueueSize = 512; uint8_t dynamicModel = DYN_MODEL_PORTABLE; SystemState lastState = STATE_ROVER_NOT_STARTED; //For Express, start unit in last known state - bool throttleDuringSPPCongestion = true; bool enableSensorFusion = false; //If IMU is available, avoid using it unless user specifically selects automotive bool autoIMUmountAlignment = true; //Allows unit to automatically establish device orientation in vehicle bool enableResetDisplay = false; From 255bb761fa224da26da07bf745ed537a247ee191 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 16:08:19 -0600 Subject: [PATCH 109/134] Remove TODOs --- Firmware/RTK_Surveyor/menuMain.ino | 2 -- 1 file changed, 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index a2cc9b83f..5571e27d5 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -413,7 +413,6 @@ void menuRadio() #ifdef ENABLE_DEVELOPER else if (settings.radioType == RADIO_ESPNOW && incoming == 4) { - //TODO remove uint8_t peer1[] = {0xB8, 0xD6, 0x1A, 0x0D, 0x8F, 0x9C}; //Facet if (esp_now_is_peer_exist(peer1) == true) log_d("Peer already exists"); @@ -433,7 +432,6 @@ void menuRadio() } else if (settings.radioType == RADIO_ESPNOW && incoming == 5) { - //TODO remove uint8_t espnowData[] = "This is the long string to test how quickly we can send one string to the other unit. I am going to need a much longer sentence if I want to get a long amount of data into one transmission. This is nearing 200 characters but needs to be near 250."; esp_now_send(0, (uint8_t *) &espnowData, sizeof(espnowData)); //Send packet to all peers } From de93932c81586d4b34d4b8ee32ed6e033d537e48 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Tue, 23 Aug 2022 16:11:32 -0600 Subject: [PATCH 110/134] Move Icon printer to graphics sub folder --- {C => Graphics/C}/Icons.c | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename {C => Graphics/C}/Icons.c (100%) diff --git a/C/Icons.c b/Graphics/C/Icons.c similarity index 100% rename from C/Icons.c rename to Graphics/C/Icons.c From 67c69829f2d9c8160d8cb24fa29cec872d882bf3 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Sun, 21 Aug 2022 19:30:22 -1000 Subject: [PATCH 111/134] Properly display and use the MAC addresses The ESP32 is assigned 4 MAC addresses but only the base address is stored in the fuses and is accessible by calling esp_read_mac. The MAC address are documented at https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/system/misc_system_api.html#mac-address: 1. WiFi Station: Base MAC address 2. WiFi AP: Base MAC address + 1 3. Bluetooth: Base MAC address + 2 4. Ethernet: Base MAC address + 3 L-Band is currently using the Bluetooth address for identification but the code actually use the WiFi Station address when provisioning the RTK. --- Firmware/RTK_Surveyor/Begin.ino | 5 ++-- Firmware/RTK_Surveyor/Bluetooth.ino | 2 +- Firmware/RTK_Surveyor/Display.ino | 41 ++++++++++++++++---------- Firmware/RTK_Surveyor/ESPNOW.ino | 6 ++-- Firmware/RTK_Surveyor/Form.ino | 2 +- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 4 ++- Firmware/RTK_Surveyor/menuMain.ino | 9 ++---- Firmware/RTK_Surveyor/menuPP.ino | 4 +-- Firmware/RTK_Surveyor/menuSystem.ino | 8 +++-- 9 files changed, 46 insertions(+), 35 deletions(-) diff --git a/Firmware/RTK_Surveyor/Begin.ino b/Firmware/RTK_Surveyor/Begin.ino index 61b4d8f21..822c6c9e5 100644 --- a/Firmware/RTK_Surveyor/Begin.ino +++ b/Firmware/RTK_Surveyor/Begin.ino @@ -143,8 +143,9 @@ void beginBoard() Serial.printf("SparkFun RTK %s v%d.%d-%s\r\n", platformPrefix, FIRMWARE_VERSION_MAJOR, FIRMWARE_VERSION_MINOR, __DATE__); //Get unit MAC address - esp_read_mac(unitMACAddress, ESP_MAC_WIFI_STA); - unitMACAddress[5] += 2; //Convert MAC address to Bluetooth MAC (add 2): https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/system/system.html#mac-address + esp_read_mac(wifiMACAddress, ESP_MAC_WIFI_STA); + memcpy(btMACAddress, wifiMACAddress, sizeof(wifiMACAddress)); + btMACAddress[5] += 2; //Convert MAC address to Bluetooth MAC (add 2): https://docs.espressif.com/projects/esp-idf/en/latest/esp32/api-reference/system/system.html#mac-address //For all boards, check reset reason. If reset was due to wdt or panic, append last log loadSettingsPartial(); //Get resetCount diff --git a/Firmware/RTK_Surveyor/Bluetooth.ino b/Firmware/RTK_Surveyor/Bluetooth.ino index d019868d8..451718cf6 100644 --- a/Firmware/RTK_Surveyor/Bluetooth.ino +++ b/Firmware/RTK_Surveyor/Bluetooth.ino @@ -103,7 +103,7 @@ void bluetoothStart() else if(systemState >= STATE_BASE_NOT_STARTED && systemState <= STATE_BASE_FIXED_TRANSMITTING) strcpy(stateName, "Base-"); - sprintf(deviceName, "%s %s%02X%02X", platformPrefix, stateName, unitMACAddress[4], unitMACAddress[5]); + sprintf(deviceName, "%s %s%02X%02X", platformPrefix, stateName, btMACAddress[4], btMACAddress[5]); // Select Bluetooth setup if (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 27c89b0d8..f875f6332 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -359,11 +359,10 @@ void updateDisplay() if (iconsRadio & ICON_MAC_ADDRESS) { char macAddress[5]; -#ifdef COMPILE_BT - sprintf(macAddress, "%02X%02X", unitMACAddress[4], unitMACAddress[5]); -#else - sprintf(macAddress, "%02X%02X", 0, 0); //If BT is not available, print zeroes -#endif + const uint8_t * rtkMacAddress = getMacAddress(); + + //Print only last two digits of MAC + sprintf(macAddress, "%02X%02X", rtkMacAddress[4], rtkMacAddress[5]); oled.setFont(QW_FONT_5X7); //Set font to smallest oled.setCursor(0, 3); oled.print(macAddress); @@ -404,12 +403,10 @@ void updateDisplay() else if (iconsRadio & ICON_MAC_ADDRESS_2DIGIT) { char macAddress[5]; + const uint8_t * rtkMacAddress = getMacAddress(); + //Print only last two digits of MAC -#ifdef COMPILE_BT - sprintf(macAddress, "%02X", unitMACAddress[5]); -#else - sprintf(macAddress, "%02X", 0); //If BT is not available, print zeroes -#endif + sprintf(macAddress, "%02X%02X", rtkMacAddress[4], rtkMacAddress[5]); oled.setFont(QW_FONT_5X7); //Set font to smallest oled.setCursor(14, 3); oled.print(macAddress); @@ -1845,9 +1842,6 @@ void paintSystemTest() int charHeight = 7; - char macAddress[5]; - sprintf(macAddress, "%02X%02X", unitMACAddress[4], unitMACAddress[5]); - drawFrame(); //Outside edge //Test SD, accel, batt, GNSS, mux @@ -1923,6 +1917,11 @@ void paintSystemTest() oled.print("FAIL"); } + //Get the last two digits of MAC + char macAddress[5]; + const uint8_t * rtkMacAddress = getMacAddress(); + sprintf(macAddress, "%02X%02X", rtkMacAddress[4], rtkMacAddress[5]); + //Display MAC address oled.setCursor(xOffset, yOffset + (5 * charHeight) ); //x, y oled.print(macAddress); @@ -2512,7 +2511,8 @@ void paintKeyProvisionFail(uint16_t displayTime) //The MAC address is characters long so we have to split it onto two lines char hardwareID[13]; - sprintf(hardwareID, "%02X%02X%02X", unitMACAddress[0], unitMACAddress[1], unitMACAddress[2]); + const uint8_t * rtkMacAddress = getMacAddress(); + sprintf(hardwareID, "%02X%02X%02X", rtkMacAddress[0], rtkMacAddress[1], rtkMacAddress[2]); String macAddress = String(hardwareID); y += fontHeight; @@ -2520,7 +2520,7 @@ void paintKeyProvisionFail(uint16_t displayTime) oled.setCursor(textX, y); oled.print(hardwareID); - sprintf(hardwareID, "%02X%02X%02X", unitMACAddress[3], unitMACAddress[4], unitMACAddress[5]); + sprintf(hardwareID, "%02X%02X%02X", rtkMacAddress[3], rtkMacAddress[4], rtkMacAddress[5]); macAddress = String(hardwareID); y += fontHeight; @@ -2543,3 +2543,14 @@ void paintEspNowPaired() { displayMessage("ESP-Now Paired", 2000); } + +const uint8_t * getMacAddress () +{ + static const uint8_t zero[6] = {0, 0, 0, 0, 0, 0}; + + if (bluetoothState != BT_OFF) + return btMACAddress; + else if (wifiState != WIFI_OFF) + return wifiMACAddress; + return zero; +} diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index d20f57650..45f2e3a21 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -249,15 +249,13 @@ esp_err_t espnowSendPairMessage(uint8_t *sendToMac) PairMessage pairMessage; //Get unit MAC address - uint8_t unitMACAddress[6]; - esp_read_mac(unitMACAddress, ESP_MAC_WIFI_STA); - memcpy(pairMessage.macAddress, unitMACAddress, 6); + memcpy(pairMessage.macAddress, wifiMACAddress, 6); pairMessage.encrypt = false; pairMessage.channel = 0; pairMessage.crc = 0; //Calculate CRC for (int x = 0 ; x < 6 ; x++) - pairMessage.crc += unitMACAddress[x]; + pairMessage.crc += wifiMACAddress[x]; return (esp_now_send(sendToMac, (uint8_t *) &pairMessage, sizeof(pairMessage))); //Send packet to given MAC #else diff --git a/Firmware/RTK_Surveyor/Form.ino b/Firmware/RTK_Surveyor/Form.ino index b34780989..8af9bd9e5 100644 --- a/Firmware/RTK_Surveyor/Form.ino +++ b/Firmware/RTK_Surveyor/Form.ino @@ -383,7 +383,7 @@ void createSettingsString(char* settingsCSV) //L-Band char hardwareID[13]; - sprintf(hardwareID, "%02X%02X%02X%02X%02X%02X", unitMACAddress[0], unitMACAddress[1], unitMACAddress[2], unitMACAddress[3], unitMACAddress[4], unitMACAddress[5]); //Get ready for JSON + sprintf(hardwareID, "%02X%02X%02X%02X%02X%02X", lbandMACAddress[0], lbandMACAddress[1], lbandMACAddress[2], lbandMACAddress[3], lbandMACAddress[4], lbandMACAddress[5]); //Get ready for JSON stringRecord(settingsCSV, "hardwareID", hardwareID); char apDaysRemaining[20]; diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 204737da0..8731fcd0a 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -367,7 +367,9 @@ const uint8_t ESPNOW_MAX_PEERS = 5; //Maximum of 5 rovers //Global variables //-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=- -uint8_t unitMACAddress[6]; //Use MAC address in BT broadcast and display +#define lbandMACAddress btMACAddress +uint8_t wifiMACAddress[6]; //Display this address in the system menu +uint8_t btMACAddress[6]; //Display this address when Bluetooth is enabled, otherwise display wifiMACAddress char deviceName[70]; //The serial string that is broadcast. Ex: 'Surveyor Base-BC61' const byte menuTimeout = 15; //Menus will exit/timeout after this number of seconds int systemTime_minutes = 0; //Used to test if logging is less than max minutes diff --git a/Firmware/RTK_Surveyor/menuMain.ino b/Firmware/RTK_Surveyor/menuMain.ino index 5571e27d5..b403da6cd 100644 --- a/Firmware/RTK_Surveyor/menuMain.ino +++ b/Firmware/RTK_Surveyor/menuMain.ino @@ -311,15 +311,10 @@ void menuRadio() if (settings.radioType == RADIO_ESPNOW) { //Pretty print the MAC of all radios - - //Get unit MAC address - uint8_t unitMACAddress[6]; - esp_read_mac(unitMACAddress, ESP_MAC_WIFI_STA); - Serial.print(" Radio MAC: "); for (int x = 0 ; x < 5 ; x++) - Serial.printf("%02X:", unitMACAddress[x]); - Serial.printf("%02X\n\r", unitMACAddress[5]); + Serial.printf("%02X:", wifiMACAddress[x]); + Serial.printf("%02X\n\r", wifiMACAddress[5]); if (settings.espnowPeerCount > 0) { diff --git a/Firmware/RTK_Surveyor/menuPP.ino b/Firmware/RTK_Surveyor/menuPP.ino index d5ecaf5b5..53d0c0dab 100644 --- a/Firmware/RTK_Surveyor/menuPP.ino +++ b/Firmware/RTK_Surveyor/menuPP.ino @@ -170,7 +170,7 @@ bool provisionDevice() client.setCACert(AWS_PUBLIC_CERT); char hardwareID[13]; - sprintf(hardwareID, "%02X%02X%02X%02X%02X%02X", unitMACAddress[0], unitMACAddress[1], unitMACAddress[2], unitMACAddress[3], unitMACAddress[4], unitMACAddress[5]); //Get ready for JSON + sprintf(hardwareID, "%02X%02X%02X%02X%02X%02X", lbandMACAddress[0], lbandMACAddress[1], lbandMACAddress[2], lbandMACAddress[3], lbandMACAddress[4], lbandMACAddress[5]); //Get ready for JSON #ifdef WHITELISTED_ID //Override ID with testing ID @@ -882,7 +882,7 @@ void menuPointPerfect() Serial.println("Menu: PointPerfect Corrections"); char hardwareID[13]; - sprintf(hardwareID, "%02X%02X%02X%02X%02X%02X", unitMACAddress[0], unitMACAddress[1], unitMACAddress[2], unitMACAddress[3], unitMACAddress[4], unitMACAddress[5]); //Get ready for JSON + sprintf(hardwareID, "%02X%02X%02X%02X%02X%02X", lbandMACAddress[0], lbandMACAddress[1], lbandMACAddress[2], lbandMACAddress[3], lbandMACAddress[4], lbandMACAddress[5]); //Get ready for JSON Serial.printf("Device ID: %s\n\r", hardwareID); Serial.print("Days until keys expire: "); diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index 5f3fd5ba5..4ecfed58b 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -66,9 +66,9 @@ void menuSystem() printNEOInfo(); } - //Display MAC address + //Display Bluetooth MAC address char macAddress[5]; - sprintf(macAddress, "%02X%02X", unitMACAddress[4], unitMACAddress[5]); + sprintf(macAddress, "%02X%02X", btMACAddress[4], btMACAddress[5]); Serial.print("Bluetooth ("); Serial.print(macAddress); Serial.print("): "); @@ -107,6 +107,10 @@ void menuSystem() Serial.println(); #ifdef COMPILE_WIFI + Serial.print("WiFi MAC Address: "); + Serial.printf("%02X-%02X-%02X-%02X-%02X-%02X\r\n", wifiMACAddress[0], + wifiMACAddress[1], wifiMACAddress[2], wifiMACAddress[3], + wifiMACAddress[4], wifiMACAddress[5]); if (wifiState == WIFI_CONNECTED) wifiDisplayIpAddress(); #endif From 6053f12570b422e9171928a03d5f06218126e712 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Sun, 21 Aug 2022 23:19:46 -1000 Subject: [PATCH 112/134] Move Bluetooth test into Debug menu Move the Bluetooth test code into Bluetooth.ino. Add a parameter to the test code to enable/disable running the test. Use the common code in the System menu to just display the Bluetooth status. Add a menu item to the Debug menu to run the Bluetooth test. Display Bluetooth test results all at once to allow additional messages to be displayed during the test. --- Firmware/RTK_Surveyor/Bluetooth.ino | 46 ++++++++++++++++++++++++++++ Firmware/RTK_Surveyor/menuSystem.ino | 45 ++++----------------------- 2 files changed, 52 insertions(+), 39 deletions(-) diff --git a/Firmware/RTK_Surveyor/Bluetooth.ino b/Firmware/RTK_Surveyor/Bluetooth.ino index 451718cf6..0a1b80f44 100644 --- a/Firmware/RTK_Surveyor/Bluetooth.ino +++ b/Firmware/RTK_Surveyor/Bluetooth.ino @@ -183,6 +183,52 @@ void bluetoothStop() bluetoothIncomingRTCM = false; } +//Test the bidirectional communication through UART2 +void bluetoothTest(bool runTest) +{ + //Verify the ESP UART2 can communicate TX/RX to ZED UART1 + const char * bluetoothStatusText; + if (online.gnss == true) + { + if (runTest && (zedUartPassed == false)) + { + stopUART2Tasks(); //Stop absoring ZED serial via task + + i2cGNSS.setSerialRate(460800, COM_PORT_UART1); //Defaults to 460800 to maximize message output support + serialGNSS.begin(460800); //UART2 on pins 16/17 for SPP. The ZED-F9P will be configured to output NMEA over its UART1 at the same rate. + + SFE_UBLOX_GNSS myGNSS; + if (myGNSS.begin(serialGNSS) == true) //begin() attempts 3 connections + { + zedUartPassed = true; + bluetoothStatusText = (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) ? "Off" : "Online"; + } + else + bluetoothStatusText = "Offline"; + + i2cGNSS.setSerialRate(settings.dataPortBaud, COM_PORT_UART1); //Defaults to 460800 to maximize message output support + serialGNSS.begin(settings.dataPortBaud); //UART2 on pins 16/17 for SPP. The ZED-F9P will be configured to output NMEA over its UART1 at the same rate. + + startUART2Tasks(); //Return to normal operation + } + else + bluetoothStatusText = (settings.bluetoothRadioType == BLUETOOTH_RADIO_OFF) ? "Off" : "Online"; + } + else + bluetoothStatusText = "GNSS Offline"; + + //Display Bluetooth MAC address and test results + char macAddress[5]; + sprintf(macAddress, "%02X%02X", btMACAddress[4], btMACAddress[5]); + Serial.print("Bluetooth "); + if (settings.bluetoothRadioType == BLUETOOTH_RADIO_BLE) + Serial.print("Low Energy "); + Serial.print("("); + Serial.print(macAddress); + Serial.print("): "); + Serial.println(bluetoothStatusText); +} + //Write data to the Bluetooth device int bluetoothWriteBytes(const uint8_t * buffer, int length) { diff --git a/Firmware/RTK_Surveyor/menuSystem.ino b/Firmware/RTK_Surveyor/menuSystem.ino index 4ecfed58b..5091e8dd6 100644 --- a/Firmware/RTK_Surveyor/menuSystem.ino +++ b/Firmware/RTK_Surveyor/menuSystem.ino @@ -66,45 +66,8 @@ void menuSystem() printNEOInfo(); } - //Display Bluetooth MAC address - char macAddress[5]; - sprintf(macAddress, "%02X%02X", btMACAddress[4], btMACAddress[5]); - Serial.print("Bluetooth ("); - Serial.print(macAddress); - Serial.print("): "); - - //Verify the ESP UART2 can communicate TX/RX to ZED UART1 - if (online.gnss == true) - { - if (zedUartPassed == false) - { - stopUART2Tasks(); //Stop absoring ZED serial via task - - i2cGNSS.setSerialRate(460800, COM_PORT_UART1); //Defaults to 460800 to maximize message output support - serialGNSS.begin(460800); //UART2 on pins 16/17 for SPP. The ZED-F9P will be configured to output NMEA over its UART1 at the same rate. - - SFE_UBLOX_GNSS myGNSS; - if (myGNSS.begin(serialGNSS) == true) //begin() attempts 3 connections - { - zedUartPassed = true; - Serial.print("Online"); - } - else - Serial.print("Offline"); - - i2cGNSS.setSerialRate(settings.dataPortBaud, COM_PORT_UART1); //Defaults to 460800 to maximize message output support - serialGNSS.begin(settings.dataPortBaud); //UART2 on pins 16/17 for SPP. The ZED-F9P will be configured to output NMEA over its UART1 at the same rate. - - startUART2Tasks(); //Return to normal operation - } - else - Serial.print("Online"); - } - else - { - Serial.print("GNSS Offline"); - } - Serial.println(); + //Display the Bluetooth status + bluetoothTest(false); #ifdef COMPILE_WIFI Serial.print("WiFi MAC Address: "); @@ -391,6 +354,8 @@ void menuDebug() Serial.print("29) Run Logging Test: "); Serial.printf("%s\r\n", settings.runLogTest ? "Enabled" : "Disabled"); + Serial.println("30) Run Bluetooth Test"); + Serial.println("t) Enter Test Screen"); Serial.println("e) Erase LittleFS"); @@ -578,6 +543,8 @@ void menuDebug() //Mark current log file as complete to force test start startCurrentLogTime_minutes = systemTime_minutes - settings.maxLogLength_minutes; } + else if (incoming == 30) + bluetoothTest(true); else printUnknown(incoming); } From b3e2a50683d65137b8cf5707c74802652cf5013d Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 24 Aug 2022 12:04:13 -0600 Subject: [PATCH 113/134] Move WiFi mode changes after esp_wifi_set_protocol() esp_wifi_set_protocol turns off WiFi Station to set the protocols. --- Firmware/RTK_Surveyor/ESPNOW.ino | 29 ++++++++++++++++------- Firmware/RTK_Surveyor/WiFi.ino | 40 +++++++++++++++----------------- 2 files changed, 39 insertions(+), 30 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index d20f57650..cbe4fb7db 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -93,23 +93,28 @@ void espnowStart() if (wifiState == WIFI_OFF && espnowState == ESPNOW_OFF) { //Radio is off, turn it on + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_LR); //Stops WiFi Station. + WiFi.mode(WIFI_STA); - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_LR); - Serial.println("WiFi off, ESP-Now added to protocols"); + log_d("WiFi off, ESP-Now added to protocols"); } //If WiFi is on but ESP NOW is off, then enable LR protocol else if (wifiState > WIFI_OFF && espnowState == ESPNOW_OFF) { //Enable WiFi + ESP-Now // Enable long range, PHY rate of ESP32 will be 512Kbps or 256Kbps - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); - Serial.println("WiFi on, ESP-Now added to protocols"); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); //Stops WiFi Station. + + WiFi.mode(WIFI_STA); + + log_d("WiFi on, ESP-Now added to protocols"); } - //If ESP-Now is active, WiFi is active, do nothing + + //If ESP-Now is already active, do nothing else { - Serial.println("WiFi already on, ESP-Now already on"); + log_d("ESP-Now already on"); } // Init ESP-NOW @@ -164,14 +169,20 @@ void espnowStop() { //ESP Now is the only thing using the radio, turn it off entirely WiFi.mode(WIFI_OFF); - Serial.println("WiFi Radio off entirely"); + + log_d("WiFi Radio off entirely"); } //If WiFi is on, then disable LR protocol else if (wifiState > WIFI_OFF) { + wifiSetState(WIFI_NOT_CONNECTED); + // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); - Serial.println("WiFi protocols on, LR protocol off"); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Stops WiFi Station. + + WiFi.mode(WIFI_STA); + + log_d("WiFi protocols on, LR protocol off"); } // Turn off promiscuous WiFi mode diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 73d8f51bd..056c0b806 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -145,13 +145,14 @@ void wifiStartAP() //Connect to local router #define WIFI_SSID "TRex" #define WIFI_PASSWORD "parachutes" - WiFi.mode(WIFI_STA); #ifdef COMPILE_ESPNOW // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Stops WiFi Station #endif + WiFi.mode(WIFI_STA); + WiFi.begin(WIFI_SSID, WIFI_PASSWORD); Serial.print("WiFi connecting to"); while (wifiGetStatus() != WL_CONNECTED) @@ -161,15 +162,16 @@ void wifiStartAP() } Serial.print("WiFi connected with IP: "); Serial.println(WiFi.localIP()); -#else //LOCAL_WIFI_TESTING +#else //End LOCAL_WIFI_TESTING //Start in AP mode - WiFi.mode(WIFI_AP); #ifdef COMPILE_ESPNOW // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) - esp_wifi_set_protocol(WIFI_IF_AP, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); + esp_wifi_set_protocol(WIFI_IF_AP, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Stops WiFi AP. #endif + WiFi.mode(WIFI_AP); + IPAddress local_IP(192, 168, 4, 1); IPAddress gateway(192, 168, 1, 1); IPAddress subnet(255, 255, 255, 0); @@ -182,7 +184,7 @@ void wifiStartAP() } Serial.print("WiFi AP Started with IP: "); Serial.println(WiFi.softAPIP()); -#endif //LOCAL_WIFI_TESTING +#endif //End AP Testing } #endif //COMPILE_WIFI @@ -209,27 +211,23 @@ void wifiStart(char* ssid, char* pw) #ifdef COMPILE_WIFI if ((wifiState == WIFI_OFF) || (wifiState == WIFI_ON)) { - WiFi.mode(WIFI_STA); + wifiSetState(WIFI_NOTCONNECTED); #ifdef COMPILE_ESPNOW if (espnowState > ESPNOW_OFF) - { - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); //Enable WiFi + ESP-Now - } + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); //Enable WiFi + ESP-Now. Stops WiFi Station. else - { - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Set basic WiFi protocols - } + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Set basic WiFi protocols. Stops WiFi Station. #else //Be sure the standard protocols are turned on. ESP Now have have previously turned them off. - WiFi.mode(WIFI_STA); - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Set basic WiFi protocols. Stops WiFi Station. #endif + WiFi.mode(WIFI_STA); + Serial.printf("WiFi connecting to %s\r\n", ssid); WiFi.begin(ssid, pw); wifiTimer = millis(); - wifiSetState(WIFI_NOTCONNECTED); //Display the heap state reportHeapNow(); @@ -254,26 +252,26 @@ void wifiStop() //If WiFi is on but ESP NOW is off, then turn off radio entirely else if (espnowState == ESPNOW_OFF) { - WiFi.mode(WIFI_OFF); wifiSetState(WIFI_OFF); + WiFi.mode(WIFI_OFF); Serial.println("WiFi Stopped"); } //If ESP-Now is active, change protocol to only Long Range else if (espnowState > ESPNOW_OFF) { - WiFi.mode(WIFI_STA); + wifiSetState(WIFI_OFF); // Enable long range, PHY rate of ESP32 will be 512Kbps or 256Kbps - esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_LR); + esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_LR); //Stops WiFi Station. - wifiSetState(WIFI_OFF); + WiFi.mode(WIFI_STA); Serial.println("WiFi disabled, ESP-Now left in place"); } #else //Turn off radio - WiFi.mode(WIFI_OFF); wifiSetState(WIFI_OFF); + WiFi.mode(WIFI_OFF); Serial.println("WiFi Stopped"); #endif From 0b9a7f18075fee455d8a064a9ae9f90dee2bf438 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 24 Aug 2022 13:16:14 -0600 Subject: [PATCH 114/134] Logging: unique semaphore wait, reduce loop delay, add taskYIELD --- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 3 ++- Firmware/RTK_Surveyor/Tasks.ino | 5 +++-- Firmware/RTK_Surveyor/menuMessages.ino | 2 +- 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 204737da0..7ab17c88c 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -125,7 +125,8 @@ int startCurrentLogTime_minutes = 0; //Mark when we start this specific log file //System crashes if two tasks access a file at the same time //So we use a semaphore to see if file system is available SemaphoreHandle_t sdCardSemaphore; -TickType_t fatSemaphore_shortWait_ms = 50 / portTICK_PERIOD_MS; +TickType_t loggingSemaphore_shortWait_ms = 10 / portTICK_PERIOD_MS; +const TickType_t fatSemaphore_shortWait_ms = 10 / portTICK_PERIOD_MS; const TickType_t fatSemaphore_longWait_ms = 200 / portTICK_PERIOD_MS; //Display used/free space in menu and config page diff --git a/Firmware/RTK_Surveyor/Tasks.ino b/Firmware/RTK_Surveyor/Tasks.ino index 332a5e08b..e25d4bd5b 100644 --- a/Firmware/RTK_Surveyor/Tasks.ino +++ b/Firmware/RTK_Surveyor/Tasks.ino @@ -203,7 +203,7 @@ void F9PSerialReadTask(void *e) { //Attempt to gain access to the SD card, avoids collisions with file //writing from other functions like recordSystemSettingsToFile() - if (xSemaphoreTake(sdCardSemaphore, fatSemaphore_shortWait_ms) == pdPASS) + if (xSemaphoreTake(sdCardSemaphore, loggingSemaphore_shortWait_ms) == pdPASS) { //Reduce bytes to send if we have more to send then the end of the buffer //We'll wrap next loop @@ -240,7 +240,8 @@ void F9PSerialReadTask(void *e) //Let other tasks run, prevent watch dog timer (WDT) resets //---------------------------------------------------------------------- - delay(10); + delay(1); + taskYIELD(); } } diff --git a/Firmware/RTK_Surveyor/menuMessages.ino b/Firmware/RTK_Surveyor/menuMessages.ino index 9b75fac7f..3f95c07c9 100644 --- a/Firmware/RTK_Surveyor/menuMessages.ino +++ b/Firmware/RTK_Surveyor/menuMessages.ino @@ -819,7 +819,7 @@ void updateLogTest() { setLogTestFrequencyMessages(rate, messages); //Set messages and rate for both UART1 and USB ports - fatSemaphore_shortWait_ms = semaphoreWait / portTICK_PERIOD_MS; //Update variable + loggingSemaphore_shortWait_ms = semaphoreWait / portTICK_PERIOD_MS; //Update variable startCurrentLogTime_minutes = millis() / 1000L / 60; //Mark now as start of logging From 6ad96eea4d38a5e197887b97db75efee9592bcff Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 24 Aug 2022 13:38:10 -0600 Subject: [PATCH 115/134] Stop ESP-Now before turning stopping WiFi --- Firmware/RTK_Surveyor/ESPNOW.ino | 35 +++++++++++++++++--------------- 1 file changed, 19 insertions(+), 16 deletions(-) diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index cbe4fb7db..e0ee88cbd 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -165,6 +165,21 @@ void espnowStop() #ifdef COMPILE_ESPNOW if (espnowState == ESPNOW_OFF) return; + // Turn off promiscuous WiFi mode + esp_wifi_set_promiscuous(false); + esp_wifi_set_promiscuous_rx_cb(NULL); + + // Deregister callbacks + //esp_now_unregister_send_cb(); + esp_now_unregister_recv_cb(); + + // Deinit ESP-NOW + if (esp_now_deinit() != ESP_OK) { + Serial.println("Error deinitializing ESP-NOW"); + return; + } +#endif + if (wifiState == WIFI_OFF) { //ESP Now is the only thing using the radio, turn it off entirely @@ -175,7 +190,9 @@ void espnowStop() //If WiFi is on, then disable LR protocol else if (wifiState > WIFI_OFF) { - wifiSetState(WIFI_NOT_CONNECTED); +#ifdef COMPILE_WIFI + wifiSetState(WIFI_NOTCONNECTED); +#endif // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Stops WiFi Station. @@ -184,21 +201,7 @@ void espnowStop() log_d("WiFi protocols on, LR protocol off"); } - - // Turn off promiscuous WiFi mode - esp_wifi_set_promiscuous(false); - esp_wifi_set_promiscuous_rx_cb(NULL); - - // Deregister callbacks - //esp_now_unregister_send_cb(); - esp_now_unregister_recv_cb(); - - // Deinit ESP-NOW - if (esp_now_deinit() != ESP_OK) { - Serial.println("Error deinitializing ESP-NOW"); - return; - } -#endif + espnowSetState(ESPNOW_OFF); } From 31689e4c3ebca077bcd4cb29f427d4b33c9080b9 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 24 Aug 2022 14:09:47 -0600 Subject: [PATCH 116/134] Set messages during Base start The GSV message needs to be updated to 1Hz. Also added is all other messages get set to the setting values in case user is logging during base mode. --- Firmware/RTK_Surveyor/Base.ino | 42 ++++++++++++-------------- Firmware/RTK_Surveyor/ESPNOW.ino | 9 +++--- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 2 +- 3 files changed, 25 insertions(+), 28 deletions(-) diff --git a/Firmware/RTK_Surveyor/Base.ino b/Firmware/RTK_Surveyor/Base.ino index 750e930b8..73d65eb30 100644 --- a/Firmware/RTK_Surveyor/Base.ino +++ b/Firmware/RTK_Surveyor/Base.ino @@ -18,31 +18,23 @@ bool configureUbloxModuleBase() i2cGNSS.checkUblox(); //Regularly poll to get latest data and any RTCM - //The first thing we do is go to 1Hz to lighten any I2C traffic from a previous configuration - if (i2cGNSS.getNavigationFrequency(maxWait) != 1) - response &= i2cGNSS.setNavigationFrequency(1, maxWait); - // response &= i2cGNSS.setNavigationFrequency(4, maxWait); + const int baseNavigationFrequency = 1; + + //In Base mode we force 1Hz + if (i2cGNSS.getNavigationFrequency(maxWait) != baseNavigationFrequency) + response &= i2cGNSS.setNavigationFrequency(baseNavigationFrequency, maxWait); if (response == false) - Serial.println("Set rate failed"); + Serial.println("setNavigationFrequency failed"); i2cGNSS.checkUblox(); //Regularly poll to get latest data and any RTCM - i2cGNSS.setNMEAGPGGAcallbackPtr(NULL); // Disable GPGGA call back that may have been set during Rover Client mode - i2cGNSS.disableNMEAMessage(UBX_NMEA_GGA, COM_PORT_I2C); // Disable NMEA message + i2cGNSS.setNMEAGPGGAcallbackPtr(NULL); // Disable GPGGA call back that may have been set during Rover NTRIP Client mode + i2cGNSS.disableNMEAMessage(UBX_NMEA_GGA, COM_PORT_I2C); // Disable NMEA message that may have been set during Rover NTRIP Client mode response = i2cGNSS.setSurveyMode(0, 0, 0); //Disable Survey-In or Fixed Mode if (response == false) Serial.println("Disable TMODE3 failed"); - //In base mode we force 1Hz - if (i2cGNSS.getNavigationFrequency(maxWait) != 1) - response &= i2cGNSS.setNavigationFrequency(1, maxWait); - if (response == false) - { - Serial.println("configureUbloxModuleBase: Set rate failed"); - return (false); - } - // Set dynamic model if (i2cGNSS.getDynamicModel(maxWait) != DYN_MODEL_STATIONARY) { @@ -61,17 +53,23 @@ bool configureUbloxModuleBase() getPortSettings(COM_PORT_I2C); //Load the settingPayload with this port's settings if (settingPayload[OUTPUT_SETTING] != (COM_TYPE_UBX | COM_TYPE_NMEA | COM_TYPE_RTCM3)) response &= i2cGNSS.setPortOutput(COM_PORT_I2C, COM_TYPE_UBX | COM_TYPE_NMEA | COM_TYPE_RTCM3); //Set the I2C port to output UBX (config), and RTCM3 (casting) - //response &= i2cGNSS.setPortOutput(COM_PORT_I2C, COM_TYPE_UBX | COM_TYPE_RTCM3); //Not a valid state. Goes to UBX+NMEA+RTCM3 - + //response &= i2cGNSS.setPortOutput(COM_PORT_I2C, COM_TYPE_UBX | COM_TYPE_RTCM3); //Not a valid state. Goes to UBX+NMEA+RTCM3 - //In base mode the Surveyor should output RTCM over UART2 and I2C ports: + //In base mode the Surveyor should output RTCM over all ports: //(Primary) UART2 in case the Surveyor is connected via radio to rover - //(Optional) I2C in case user wants base to connect to WiFi and NTRIP Serve to Caster - //(Seconday) USB in case the Surveyor is used as an NTRIP caster - //(Tertiary) UART1 in case Surveyor is sending RTCM to phone that is then NTRIP caster + //(Optional) I2C in case user wants base to connect to WiFi and NTRIP Caster + //(Seconday) USB in case the Surveyor is used as an NTRIP caster connected to SBC or other + //(Tertiary) UART1 in case Surveyor is sending RTCM to phone that is then NTRIP Caster response &= enableRTCMSentences(COM_PORT_UART2); response &= enableRTCMSentences(COM_PORT_UART1); response &= enableRTCMSentences(COM_PORT_USB); - response &= enableRTCMSentences(COM_PORT_I2C); //Enable for plain radio so we can count RTCM packets for display (State: Base-Temp - Transmitting) + response &= enableRTCMSentences(COM_PORT_I2C); //Enable for plain radio so we can count RTCM packets for display + + //If enabled, adjust GSV NMEA to be reported at 1Hz + if (settings.ubxMessages[8].msgRate > baseNavigationFrequency) + setMessageRateByName("UBX_NMEA_GSV", baseNavigationFrequency); //Update GSV setting in file + + response &= configureGNSSMessageRates(COM_PORT_UART1, settings.ubxMessages); //In the interest of logging, make sure the appropriate messages are enabled if (response == false) { diff --git a/Firmware/RTK_Surveyor/ESPNOW.ino b/Firmware/RTK_Surveyor/ESPNOW.ino index e0ee88cbd..da6689f14 100644 --- a/Firmware/RTK_Surveyor/ESPNOW.ino +++ b/Firmware/RTK_Surveyor/ESPNOW.ino @@ -178,7 +178,6 @@ void espnowStop() Serial.println("Error deinitializing ESP-NOW"); return; } -#endif if (wifiState == WIFI_OFF) { @@ -190,18 +189,18 @@ void espnowStop() //If WiFi is on, then disable LR protocol else if (wifiState > WIFI_OFF) { -#ifdef COMPILE_WIFI wifiSetState(WIFI_NOTCONNECTED); -#endif // Return protocol to default settings (no WIFI_PROTOCOL_LR for ESP NOW) esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Stops WiFi Station. WiFi.mode(WIFI_STA); - + log_d("WiFi protocols on, LR protocol off"); } - + +#endif + espnowSetState(ESPNOW_OFF); } diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 7ab17c88c..12b88402f 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -554,7 +554,7 @@ void setup() loadSettings(); //Attempt to load settings after SD is started so we can read the settings file if available - //beginIdleTasks(); //Enable processor load calculations + beginIdleTasks(); //Enable processor load calculations beginUART2(); //Start UART2 on core 0, used to receive serial from ZED and pass out over SPP From 2ebf3d36f8a993f56d481d048781f84984b3ede6 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 24 Aug 2022 14:33:58 -0600 Subject: [PATCH 117/134] Remove ntripClientSwitchToBluetooth --- Firmware/RTK_Surveyor/NtripClient.ino | 22 ++++++---------------- 1 file changed, 6 insertions(+), 16 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripClient.ino b/Firmware/RTK_Surveyor/NtripClient.ino index 07f120d28..c488b6ae9 100644 --- a/Firmware/RTK_Surveyor/NtripClient.ino +++ b/Firmware/RTK_Surveyor/NtripClient.ino @@ -156,7 +156,9 @@ bool ntripClientConnectLimitReached() { //No more connection attempts, switching to Bluetooth Serial.println("NTRIP Client connection attempts exceeded!"); - ntripClientSwitchToBluetooth(); + + //Stop WiFi operations + ntripClientStop(true); } return limitReached; } @@ -183,18 +185,6 @@ void ntripClientResponse(char * response, size_t maxLength) *response = '\0'; } -//Switch to Bluetooth operation -void ntripClientSwitchToBluetooth() -{ - Serial.println("NTRIP Client failure, switching to Bluetooth!"); - - //Stop WiFi operations - ntripClientStop(true); - - //Turn on Bluetooth with 'Rover' name - bluetoothStart(); -} - //Update the state of the NTRIP client state machine void ntripClientSetState(byte newState) { @@ -391,8 +381,8 @@ void ntripClientUpdate() //Look for '401 Unauthorized' Serial.printf("NTRIP Client caster responded with bad news: %s. Are you sure your caster credentials are correct?\n\r", response); - //Switch to Bluetooth operation - ntripClientSwitchToBluetooth(); + //Stop WiFi operations + ntripClientStop(true); } else { @@ -460,7 +450,7 @@ void ntripClientUpdate() i2cGNSS.pushRawData(rtcmData, rtcmCount); wifiIncomingRTCM = true; - if(!inMainMenu) log_d("NTRIP Client received %d RTCM bytes, pushed to ZED", rtcmCount); + if (!inMainMenu) log_d("NTRIP Client received %d RTCM bytes, pushed to ZED", rtcmCount); } } From f48622314e7f6dbefc65d05335cea7c5ec281104 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Wed, 24 Aug 2022 16:36:46 -0600 Subject: [PATCH 118/134] Add connection throttling to NTRIP Server Emlid and other casters do not allow immediate re-connect that is often seen when the connection is lost, or a user makes a setting modification (where WiFi is closed/reconnected). This adds a 5s delay between the first re-attempt at WiFi or NTRIP Caster connection and increases += 5 minutes every failed delay after that. --- Firmware/RTK_Surveyor/Form.ino | 2 +- Firmware/RTK_Surveyor/NtripServer.ino | 68 ++++++++++++++++++--------- 2 files changed, 47 insertions(+), 23 deletions(-) diff --git a/Firmware/RTK_Surveyor/Form.ino b/Firmware/RTK_Surveyor/Form.ino index b34780989..4f6b77642 100644 --- a/Firmware/RTK_Surveyor/Form.ino +++ b/Firmware/RTK_Surveyor/Form.ino @@ -30,7 +30,7 @@ void startWebServer() Serial.println(sdUsedSpaceMB); } - ntripClientStop(true); + ntripClientStop(true); //Do not allocate new wifiClient wifiStartAP(); incomingSettings = (char*)malloc(AP_CONFIG_SETTING_SIZE); diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 1fff20ded..278959f88 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -53,7 +53,9 @@ #ifdef COMPILE_WIFI //Give up connecting after this number of attempts -static const int MAX_NTRIP_SERVER_CONNECTION_ATTEMPTS = 3; +//Connection attempts are throttled to increase the time between attempts +//30 attempts with 5 minute increases will take over 38 hours +static const int MAX_NTRIP_SERVER_CONNECTION_ATTEMPTS = 30; //---------------------------------------- // Locals - compiled out @@ -68,6 +70,10 @@ uint32_t ntripServerBytesSent = 0; //Count the number of connection attempts static int ntripServerConnectionAttempts; +//Throttle the time between connection attempts +static int ntripServerConnectionAttemptTimeout = 0; +static uint32_t ntripServerLastConnectionAttempt = 0; + //Last time the NTRIP server state was displayed static uint32_t ntripServerStateLastDisplayed = 0; @@ -77,11 +83,6 @@ static uint32_t ntripServerStateLastDisplayed = 0; // * Monitor last RTCM byte received for frame counting static uint32_t ntripServerTimer; -//Record last connection attempt -//After 6 hours, reset the connectionAttempts to enable -//multi week/month base installations -static uint32_t lastConnectionAttempt = 0; - //---------------------------------------- // NTRIP Server Routines - compiled out //---------------------------------------- @@ -128,9 +129,14 @@ bool ntripServerConnectLimitReached() bool limitReached = false; if (ntripServerConnectionAttempts++ >= MAX_NTRIP_SERVER_CONNECTION_ATTEMPTS) limitReached = true; - if (!limitReached) - //Display the heap state + if (limitReached == false) + { + ntripServerConnectionAttemptTimeout = ntripServerConnectionAttempts * 5 * 60 * 1000L; //Wait 5, 10, 15, etc minutes between attempts + + log_d("ntripServerConnectionAttemptTimeout increased to %d minutes", ntripServerConnectionAttemptTimeout / (60 * 1000L)); + reportHeapNow(); + } else { //No more connection attempts @@ -299,10 +305,16 @@ void ntripServerStop(bool wifiClientAllocated) //Stop WiFi if in use if (ntripServerState > NTRIP_SERVER_ON) + { wifiStop(); + ntripServerLastConnectionAttempt = millis(); //Mark the Server stop so that we don't immediately attempt re-connect to Caster + ntripServerConnectionAttemptTimeout = 5 * 1000L; //Wait 5s between stopping and the first re-connection attempt + } + //Determine the next NTRIP server state ntripServerSetState((ntripServer && (wifiClientAllocated == false)) ? NTRIP_SERVER_ON : NTRIP_SERVER_OFF); + online.ntripServer = false; #endif //COMPILE_WIFI } @@ -330,8 +342,24 @@ void ntripServerUpdate() //Start WiFi case NTRIP_SERVER_ON: - wifiStart(settings.ntripServer_wifiSSID, settings.ntripServer_wifiPW); - ntripServerSetState(NTRIP_SERVER_WIFI_CONNECTING); + //Pause until connection timeout has passed + if (millis() - ntripServerLastConnectionAttempt > ntripServerConnectionAttemptTimeout) + { + ntripServerLastConnectionAttempt = millis(); + wifiStart(settings.ntripServer_wifiSSID, settings.ntripServer_wifiPW); + ntripServerSetState(NTRIP_SERVER_WIFI_CONNECTING); + } + else + { + if (millis() - startTime > 1000) + { + startTime = millis(); + log_d("NTRIP Server connection timeout wait: %d of %d \n\r", + (millis() - ntripServerLastConnectionAttempt) / 1000, + ntripServerConnectionAttemptTimeout / 1000 + ); + } + } break; //Wait for connection to an access point @@ -343,6 +371,8 @@ void ntripServerUpdate() //Assume AP weak signal, the AP is unable to respond successfully if (ntripServerConnectLimitReached()) { + Serial.println("NTRIP Server failed to get WiFi. Are your WiFi credentials correct?"); + //Display the WiFi failure paintNtripWiFiFail(4000, false); } @@ -354,7 +384,7 @@ void ntripServerUpdate() ntripServerSetState(NTRIP_SERVER_WIFI_CONNECTED); // Start the SD card server - // sdCardServerBegin(&server, true, true); + // sdCardServerBegin(&server, true, true); } break; @@ -382,11 +412,11 @@ void ntripServerUpdate() { log_d("NTRIP Server caster failed to connect. Trying again."); - lastConnectionAttempt = millis(); - //Assume service not available if (ntripServerConnectLimitReached()) + { Serial.println("NTRIP Server failed to connect! Do you have your caster address and port correct?"); + } } else { @@ -406,7 +436,9 @@ void ntripServerUpdate() { //NTRIP web service did not respone if (ntripServerConnectLimitReached()) + { Serial.println("Caster failed to respond. Do you have your caster address and port correct?"); + } } } else @@ -421,7 +453,7 @@ void ntripServerUpdate() //Look for '401 Unauthorized' Serial.printf("NTRIP Server caster responded with bad news: %s. Are you sure your caster credentials are correct?\n\r", response); - ntripServerStop(true); //Don't allocate new wifiClient + ntripServerStop(true); //Don't allocate new wifiClient } else { @@ -460,14 +492,6 @@ void ntripServerUpdate() { //All is well cyclePositionLEDs(); - - //There may be intermintant disconnects over days or weeks - //Reset the reconnect attempts every 6 hours - if (ntripServerConnectionAttempts > 0 && (millis() - lastConnectionAttempt) > (1000L * 60 * 60 * 6)) - { - ntripServerConnectionAttempts = 0; - log_d("Resetting connection attempts"); - } } break; From 7c659d9dde7137914b1744cc2edfea06b3a7ac41 Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Wed, 24 Aug 2022 09:47:18 -1000 Subject: [PATCH 119/134] Add RTK support programs Compare - Program to locate a common NMEA timestamp message in two log files and create two new files (a.txt and b.txt) containing all of the data following the beginning of the common timestamp message. This makes comparing two log files much easier since they have a common starting point. Example: ./Compare 20220819_0747_usb.txt 20220819_0747_uart.txt NMEA_Client - NMEA client program to connect to the RTK NMEA TCP server. Example: ./NMEA_Client 192.168.86.225 Split_Messages - Program to verify the checksums and CRCs and count the various messages in a log file. Example: ./Split_Messages 20220819_0747_usb.txt --- C/Compare.c | 1480 ++++++++++++++++++++++++++++++++++++++++++++ C/NMEA_Client.c | 81 +++ C/Split_Messages.c | 1273 +++++++++++++++++++++++++++++++++++++ C/crc24q.c | 185 ++++++ C/crc24q.h | 20 + C/makefile | 46 ++ 6 files changed, 3085 insertions(+) create mode 100644 C/Compare.c create mode 100644 C/NMEA_Client.c create mode 100644 C/Split_Messages.c create mode 100644 C/crc24q.c create mode 100644 C/crc24q.h create mode 100644 C/makefile diff --git a/C/Compare.c b/C/Compare.c new file mode 100644 index 000000000..fc597fe9a --- /dev/null +++ b/C/Compare.c @@ -0,0 +1,1480 @@ +// Compare.c + +#include +#include +#include +#include +#include +#include +#include + +#include "crc24q.h" +#include "crc24q.c" +//#include "Crc24q.h" + +#define COMPUTE_CRC24Q(parse, data) (((parse)->crc << 8) ^ crc24q[data ^ (((parse)->crc >> 16) & 0xff)]) + +#define DISPLAY_BAD_CHARACTERS 0 +#define DISPLAY_BAD_CHARACTER_OFFSETS 1 +#define DISPLAY_RTCM_MESSAGE_LIST 1 +#define DISPLAY_UBX_MESSAGE_LIST 1 +#define DISPLAY_BOUNDARY 0 +#define DISPLAY_DATA_BYTES 0 +#define DISPLAY_LIST 0 +#define DISPLAY_MESSAGE_TYPE 0 +#define DISPLAY_MESSAGE_TYPE_LIST 1 +#define DISPLAY_NMEA_MESSAGES 1 +#define DISPLAY_STRINGS 0 + +#define MESSAGE_LENGTH(length) (3 + length + 3) + +#define BINARY_MESSAGE_START 0xd3 + +#define MAX_BAD_CHARACTERS 1000 + +uint32_t bad_characters[256>>5]; +uint32_t bad_character_count[256]; +uint32_t bad_character_offset[MAX_BAD_CHARACTERS]; +uint32_t bad_character_length[MAX_BAD_CHARACTERS]; +int32_t bad_character_offset_count = -1; + +char buffer[65536]; +char string[256]; +uint8_t * file_data; +uint32_t rtcm_messages[4096 >> 5]; +uint32_t rtcm_message_count[4096]; +uint32_t rtcm_max_message_length[4096]; +uint32_t ubx_messages[65536 >> 5]; +uint32_t ubx_message_count[65536]; +uint32_t ubx_max_message_length[65536]; +int bad_checksum_header; +int nmea_checksum_errors; +int rtcm_crc_errors; +int ubx_checksum_errors; + +typedef struct _NMEA_MESSAGE { + struct _NMEA_MESSAGE * next; + uint8_t * message; + uint32_t count; + uint32_t max_length; +} NMEA_MESSAGE; + +NMEA_MESSAGE * nmea_list; + +enum SentenceTypes +{ +SENTENCE_TYPE_NONE = 0, +SENTENCE_TYPE_NMEA, +SENTENCE_TYPE_UBX, +SENTENCE_TYPE_RTCM +} currentSentence = SENTENCE_TYPE_NONE; + +typedef struct _PARSE_STATE * P_PARSE_STATE; + +//Parse routine +typedef uint8_t (* PARSE_ROUTINE)(P_PARSE_STATE parse, //Parser state + uint8_t data); //Incoming data byte + +//End of message callback routine +typedef void (* EOM_CALLBACK)(P_PARSE_STATE parse, //Parser state + uint8_t type); //Message type + +#define PARSE_BUFFER_LENGTH 0x10000 + +typedef struct _PARSE_STATE +{ + PARSE_ROUTINE state; //Parser state routine + EOM_CALLBACK eomCallback; //End of message callback routine + const char * parserName; //Name of parser + uint32_t crc; //RTCM computed CRC + uint32_t rtcmCrc; //Computed CRC value for the RTCM message + uint32_t invalidRtcmCrcs; //Number of bad RTCM CRCs detected + uint16_t bytesRemaining; //Bytes remaining in RTCM CRC calculation + uint16_t length; //Message length including line termination + uint16_t maxLength; //Maximum message length including line termination + uint16_t message; //RTCM message number + uint16_t nmeaLength; //Length of the NMEA message without line termination + uint8_t buffer[PARSE_BUFFER_LENGTH]; //Buffer containing the message + uint8_t nmeaMessageName[16]; //Message name + uint8_t nmeaMessageNameLength; //Length of the message name + uint8_t ck_a; //U-blox checksum byte 1 + uint8_t ck_b; //U-blox checksum byte 2 + bool computeCrc; //Compute the CRC when true +} PARSE_STATE; + +//Forward declaration +uint8_t waitForPreamble(PARSE_STATE * parse, uint8_t data); +uint64_t offset; +uint64_t file_offset; + +void +dump_message ( + unsigned char * data + ) +{ + unsigned int actual; + unsigned int crc; + int index; + int length; + int offset; + + // + // +----------+--------+----------------+---------+----------+---------+ + // | Preamble | Fill | Message Length | Message | Fill | CRC-24Q | + // | 8 bits | 6 bits | 10 bits | n-bits | 0-7 bits | 24 bits | + // | 0xd3 | 000000 | | | zeros | | + // +----------+--------+----------------+---------+----------+---------+ + // + + // Get the number of bytes + length = (data[1] << 8) | data[2]; + if (DISPLAY_DATA_BYTES) { + // Dump the message + offset = data - file_data; + printf ("0x%08x: %02x %02x %02x\n", offset, data[0], data[1], data[2]); + offset += 3; + index = 0; + if (length > 0) { + do + { + // Display the offset at the beginning of the line + if (!(index & 0xf)) + printf ("0x%08x: ", offset); + + // Display the data bytes + printf ("%02x ", data[index+3]); + offset += 1; + + // Terminate the lines + if (!(++index % (DISPLAY_DATA_BYTES ? DISPLAY_DATA_BYTES : 1))) + printf ("\n"); + } while (index < length); + + // Terminate a short line + if (index % (DISPLAY_DATA_BYTES ? DISPLAY_DATA_BYTES : 1)) + printf ("\n"); + } + + // Display the Cyclic Redundancy Check (CRC) + printf ("0x%08x: %02x %02x %02x CRC: %s\n", + offset, data[3 + index], data[3 + index + 1], data[3 + index + 2], + crc24q_check (data, MESSAGE_LENGTH(length)) ? "Matches" : "Does not match!"); + } else { + if (!crc24q_check (data, MESSAGE_LENGTH(length))) { + if (!bad_checksum_header) { + bad_checksum_header = 1; + printf ("Bad checksums:\n"); + } + length = MESSAGE_LENGTH(length); + crc = crc24q_hash(data, length - 3); + actual = (data[length - 3] << 16) | (data[length - 2] << 8) | data[length - 1]; + printf (" 0x%08lx: Binary message, expected CRC: 0x%06x, actual CRC: 0x%06x\n", + data - file_data, crc, actual); + rtcm_crc_errors += 1; + } + } +} + +void +display_string ( + unsigned char * string, + int length + ) +{ + char * temp; + char * temp_end; + + // Copy the strings into the buffer + memcpy (buffer, string, length); + buffer[length] = 0; + + // Terminate the strings + temp = buffer; + temp_end = &temp[length]; + do { + if ((*temp == '\r') || (*temp == '\n')) + *temp = 0; + } while (++temp < temp_end); + + // Display the strings + temp = buffer; + while (temp < temp_end) { + if (*temp) + printf ("%s\n", temp); + temp += strlen(temp) + 1; + } +} + +unsigned char * +process_nmea_message ( + unsigned char * data, + unsigned char * data_end + ) +{ + unsigned char checksum; + char checksum_char[2]; + NMEA_MESSAGE * message; + NMEA_MESSAGE * previous; + unsigned char * start; + + // Check for the beginning of a NMEA message ($) + if (*data != '$') { + if ((*data != '\r') && (*data != '\n')) { + bad_character_count[*data] += 1; + bad_characters[*data >> 5] |= 1 << (*data & 0x1f); + if ((bad_character_offset_count < 0) + || ((bad_character_offset[bad_character_offset_count] + bad_character_length[bad_character_offset_count]) != (data - file_data))) { + bad_character_offset_count += 1; + bad_character_offset[bad_character_offset_count] = data - file_data; + } + bad_character_length[bad_character_offset_count] += 1; + } + return data + 1; + } + + // Skip over the dollar sign ($) + start = data++; + + // Scan for comma or end of message + checksum = 0; + while ((*data != ',') && (*data != '\r') && (*data != '\n') + && (*data != BINARY_MESSAGE_START)) + checksum ^= *data++; + + // Return if this is the start of a binary message + if (*data == BINARY_MESSAGE_START) + return data; + + // Remember the message if a comma was found + if (*data == ',') { + if (DISPLAY_LIST) + printf ("----------------------\r\n"); + + // Build the zero terminated string + memset (string, 0, sizeof(string)); + strncpy (string, (char *)start, data - start); + + /* + list --> NULL + + previous = NULL + string: $GNGST --. + V + +------------+ + list --> | $GNGST (1) | --> NULL + +------------+ + + previous = $GNGST + string: $GNGGA --. + V + +------------+ +------------+ + list --> | $GNGGA (1) | --> | $GNGST (1) | --> NULL + +------------+ +------------+ + + previous = $GNGSA + string: $GNGSA --------------------. + V + +------------+ +------------+ +------------+ + list --> | $GNGGA (1) | --> | $GNGSA (1) | --> | $GNGST (1) | --> NULL + +------------+ +------------+ +------------+ + + previous = $GNGSA + string: $GNGSA --------------------. + V + +------------+ +------------+ +------------+ + list --> | $GNGGA (1) | --> | $GNGSA (2) | --> | $GNGST (1) | --> NULL + +------------+ +------------+ +------------+ + + previous = $GNGST + string: $GNRMC ---------------------------------------------------------. + V + +------------+ +------------+ +------------+ +------------+ + list --> | $GNGGA (1) | --> | $GNGSA (2) | --> | $GNGST (1) | --> | $GNRMC (1) | --> NULL + +------------+ +------------+ +------------+ +------------+ + + */ + + // Display the list + if (DISPLAY_LIST) { + printf ("list: "); + for (previous = nmea_list; previous; previous = previous->next) + printf ("%s(%d)-->", previous->message, previous->count); + printf ("NULL\n"); + } + + // Find the location for insertion + // Check for something in the list + previous = NULL; + if (nmea_list) { + if (strcmp((char *)nmea_list->message, string) <= 0) { + previous = nmea_list; + while (previous->next && (strcmp((char *)previous->next->message, string) <= 0)) + previous = previous->next; + } + } + + // Display the insertion decision + if (DISPLAY_LIST) { + printf ("previous: %s\n", ((previous != NULL) ? (char *)previous->message : (char *)"NULL")); + printf ("string: %s\n", string); + } + + // Check for a duplicate message + if (previous && (strcmp ((char *)previous->message, string) == 0)) { + if (DISPLAY_LIST) + printf ("Duplicate found: %d\n", previous->count); + previous->count += 1; + message = previous; + } else { + // Add the new message + message = malloc (sizeof(NMEA_MESSAGE) + strlen(string) + 1); + message->message = (uint8_t *)(message + 1); + strcpy((char *)message->message, string); + message->count = 1; + + // Message insertion position + // previous == NULL; ==> list head + // previous != NULL; ==> middle or end of list + if (!previous) { + if (DISPLAY_LIST) + printf ("Add to head of the list\n"); + + // Add this message at the start of the list + message->next = nmea_list; + nmea_list = message; + } else { + if (DISPLAY_LIST) + printf ("Add to middle of the list\n"); + + // Insert this message into the middle of the list + message->next = previous->next; + previous->next = message; + } + } + + // Display the new list + if (DISPLAY_LIST) { + printf ("New list: "); + for (previous = nmea_list; previous; previous = previous->next) + printf ("%s(%d)-->", previous->message, previous->count); + printf ("NULL\n"); + } + } + + // Scan for asterisk or end of message + while ((*data != '*') && (*data != '\r') && (*data != '\n') + && (*data != BINARY_MESSAGE_START)) + checksum ^= *data++; + + // Check for end of NMEA message, validate the checksum + if (*data == '*') { + checksum_char[0] = ((checksum >> 4) & 0xf) + '0'; + if (checksum_char[0] > '9') + checksum_char[0] += 'A' - '0' - 10; + checksum_char[1] = (checksum & 0xf) + '0'; + if (checksum_char[1] > '9') + checksum_char[1] += 'A' - '0' - 10; + if ((toupper(data[1]) != checksum_char[0]) || (toupper(data[2]) != checksum_char[1])) { + if (!bad_checksum_header) { + bad_checksum_header = 1; + printf ("Bad checksums:\n"); + } + printf (" 0x%08lx: NMEA %s, expected CRC: 0x%02x, actual CRC: 0x%c%c\n", + data - file_data, &string[1], checksum, data[1], data[2]); + nmea_checksum_errors += 1; + } + data += 3; + } + + // Scan for end of message + while ((*data != '\r') && (*data != '\n') && (*data != BINARY_MESSAGE_START)) + data++; + + return data; +} + +uint8_t * +find_gnss_header ( + uint8_t * data, + uint8_t * data_end + ) +{ + int length; + + do { + // From RTCM 10403.2 Section 4 + // + // +----------+--------+----------------+---------+----------+---------+ + // | Preamble | Fill | Message Length | Message | Fill | CRC-24Q | + // | 8 bits | 6 bits | 10 bits | n-bits | 0-7 bits | 24 bits | + // | 0xd3 | 000000 | | | zeros | | + // +----------+--------+----------------+---------+----------+---------+ + // + + // Locate the beginning of the message + while ((data < data_end) && (*data != BINARY_MESSAGE_START)) + data = process_nmea_message (data, data_end); + + // Check for end of data + if (data >= data_end) + break; + + // Get the number of bytes + length = (data[1] << 8) | data[2]; + if ((data + MESSAGE_LENGTH(length)) <= data_end) { + + // Verify the CRC + if (crc24q_check (data, MESSAGE_LENGTH(length))) + break; + } + + // Skip this preamble byte + data++; + } while (data < data_end); + + // Return the address of the next preamble byte or end of data + return data; +} + +void processNemaMessage(PARSE_STATE * parse) +{ + NMEA_MESSAGE * message; + NMEA_MESSAGE * previous; + + //Display the NMEA message +// dumpBuffer(parse->buffer, parse->length); +// printf(" %s NMEA %s, %d bytes\r\n", parse->parserName, parse->nmeaMessageName, parse->length); + + // Display the list + if (DISPLAY_LIST) { + printf ("list: "); + for (previous = nmea_list; previous; previous = previous->next) + printf ("%s(%d)-->", previous->message, previous->count); + printf ("NULL\n"); + } + + // Find the location for insertion + // Check for something in the list + previous = NULL; + if (nmea_list) { + if (strcmp((char *)nmea_list->message, (char *)parse->nmeaMessageName) <= 0) { + previous = nmea_list; + while (previous->next && (strcmp((char *)previous->next->message, (char *)parse->nmeaMessageName) <= 0)) + previous = previous->next; + } + } + + // Display the insertion decision + if (DISPLAY_LIST) { + printf ("previous: %s\n", ((previous != NULL) ? (char *)previous->message : (char *)"NULL")); + printf ("string: %s\n", parse->nmeaMessageName); + } + + // Check for a duplicate message + if (previous && (strcmp ((char *)previous->message, (char *)parse->nmeaMessageName) == 0)) { + if (DISPLAY_LIST) + printf ("Duplicate found: %d\n", previous->count); + previous->count += 1; + message = previous; + if (message->max_length < parse->length) + message->max_length = parse->length; + } else { + // Add the new message + message = malloc (sizeof(NMEA_MESSAGE) + strlen((char *)parse->nmeaMessageName) + 1); + message->message = (uint8_t *)(message + 1); + strcpy((char *)message->message, (char *)parse->nmeaMessageName); + message->count = 1; + message->max_length = parse->length; + + // Message insertion position + // previous == NULL; ==> list head + // previous != NULL; ==> middle or end of list + if (!previous) { + if (DISPLAY_LIST) + printf ("Add to head of the list\n"); + + // Add this message at the start of the list + message->next = nmea_list; + nmea_list = message; + } else { + if (DISPLAY_LIST) + printf ("Add to middle of the list\n"); + + // Insert this message into the middle of the list + message->next = previous->next; + previous->next = message; + } + } + + // Display the new list + if (DISPLAY_LIST) { + printf ("New list: "); + for (previous = nmea_list; previous; previous = previous->next) + printf ("%s(%d)-->", previous->message, previous->count); + printf ("NULL\n"); + } +} + +void processRtcmMessage(PARSE_STATE * parse) +{ +// dumpBuffer(parse->buffer, parse->length); +// printf(" %s RTCM %d, %d bytes\r\n", parse->parserName, parse->message, parse->length); + rtcm_messages[parse->message >> 5] |= 1 << (parse->message & 0x1f); + rtcm_message_count[parse->message] += 1; + if (rtcm_max_message_length[parse->message] < parse->length) + rtcm_max_message_length[parse->message] = parse->length; +} + +void processUbxMessage(PARSE_STATE * parse) +{ +// dumpBuffer(parse->buffer, parse->length); +// printf(" %s UBX %d.%d, %d bytes\r\n", parse->parserName, parse->message >> 8, parse->message & 0xff, parse->length); + ubx_messages[parse->message >> 5] |= 1 << (parse->message & 0x1f); + ubx_message_count[parse->message] += 1; + if (ubx_max_message_length[parse->message] < parse->length) + ubx_max_message_length[parse->message] = parse->length; +} + +//Process the message +void processMessage(PARSE_STATE * parse, uint8_t type) +{ + switch (type) + { + case SENTENCE_TYPE_NMEA: + processNemaMessage(parse); + break; + + case SENTENCE_TYPE_RTCM: + processRtcmMessage(parse); + break; + + case SENTENCE_TYPE_UBX: + processUbxMessage(parse); + break; + + default: + printf ("Unknown message type: %d\r\n", type); + break; + } +} + +//Convert nibble to ASCII +uint8_t nibbleToAscii(int nibble) +{ + nibble &= 0xf; + return (nibble > 9) ? nibble + 'a' - 10 : nibble + '0'; +} + +//Convert nibble to ASCII +int AsciiToNibble(int data) +{ + //Convert the value to lower case + data |= 0x20; + if ((data >= 'a') && (data <= 'f')) + return data - 'a' + 10; + if ((data >= '0') && (data <= '9')) + return data - '0'; + return -1; +} + +void dumpBuffer(uint8_t * buffer, uint16_t length) +{ + unsigned int bytes; + uint8_t * end; + unsigned int index; + + end = &buffer[length]; + while (buffer < end) + { + //Determine the number of bytes to display on the line + bytes = end - buffer; + if (bytes > (16 - (offset & 0xf))) + bytes = 16 - (offset & 0xf); + + //Display the offset + printf("0x%08lx: ", offset); + + //Skip leading bytes + for (index = 0; index < (offset & 0xf); index++) + printf(" "); + + //Display the data bytes + for (index = 0; index < bytes; index++) + printf("%02x ", buffer[index]); + + //Separate the data bytes from the ASCII + for (; index < (16 - (offset & 0xf)); index++) + printf(" "); + printf(" "); + + //Skip leading bytes + for (index = 0; index < (offset & 0xf); index++) + printf(" "); + + //Display the ASCII values + for (index = 0; index < bytes; index++) + printf("%c", ((buffer[index] < ' ') || (buffer[index] >= 0x7f)) + ? '.' : buffer[index]); + printf("\r\n"); + + //Set the next line of data + buffer += bytes; + offset += bytes; + } +} + +//Read the line termination +uint8_t nmeaLineTermination(PARSE_STATE * parse, uint8_t data) +{ + unsigned int checksum; + + //Process the line termination + if ((data != '\r') && (data != '\n')) + { + //Don't include this character in the buffer + parse->length--; + + //Convert the checksum characters into binary + checksum = AsciiToNibble(parse->buffer[parse->nmeaLength - 2]) << 4; + checksum |= AsciiToNibble(parse->buffer[parse->nmeaLength - 1]); + + //Validate the checksum + if (checksum == parse->crc) + parse->crc = 0; + if (parse->crc) + { + nmea_checksum_errors += 1; + dumpBuffer(parse->buffer, parse->length); + if ((AsciiToNibble(parse->buffer[parse->nmeaLength-2]) >= 0) + && (AsciiToNibble(parse->buffer[parse->nmeaLength-1]) >= 0)) + printf (" %s NMEA %s, %2d bytes, bad checksum, expecting 0x%c%c, computed: 0x%02x\r\n", + parse->parserName, + parse->nmeaMessageName, + parse->length, + parse->buffer[parse->nmeaLength-2], + parse->buffer[parse->nmeaLength-1], + parse->crc); + else + printf (" %s NMEA %s, %2d bytes, invalid checksum bytes 0x%02x 0x%02x, computed: 0x%02x\r\n", + parse->parserName, + parse->nmeaMessageName, + parse->length, + parse->buffer[parse->nmeaLength-2], + parse->buffer[parse->nmeaLength-1], + parse->crc); + } + + //Process this message + parse->eomCallback(parse, SENTENCE_TYPE_NMEA); + + //Add this character to the beginning of the buffer + parse->buffer[0] = data; + parse->length = 1; + return waitForPreamble(parse, data); + } + return SENTENCE_TYPE_NMEA; +} + +//Read the linefeed +uint8_t nmeaLinefeed(PARSE_STATE * parse, uint8_t data) +{ + unsigned int checksum; + uint8_t sentenceType; + + //Convert the checksum characters into binary + checksum = AsciiToNibble(parse->buffer[parse->nmeaLength - 2]) << 4; + checksum |= AsciiToNibble(parse->buffer[parse->nmeaLength - 1]); + + //Update the maximum message length + if (parse->length > parse->maxLength) + { + parse->maxLength = parse->length; + printf("maxLength: %d bytes\r\n", parse->maxLength); + } + + //Validate the checksum + if (checksum == parse->crc) + parse->crc = 0; + if (parse->crc) + { + nmea_checksum_errors += 1; + dumpBuffer(parse->buffer, parse->length); + printf (" %s NMEA %s, %2d bytes, bad checksum, expecting 0x%c%c, computed: 0x%02x\r\n", + parse->parserName, + parse->nmeaMessageName, + parse->length, + parse->buffer[parse->nmeaLength-2], + parse->buffer[parse->nmeaLength-1], + parse->crc); + } + + //Process this message + parse->state = waitForPreamble; + parse->eomCallback(parse, SENTENCE_TYPE_NMEA); + + //Search for another preamble byte + parse->length = 0; + parse->crc = 0; + return SENTENCE_TYPE_NONE; +} + +//Read the carriage return +uint8_t nmeaCarriageReturn(PARSE_STATE * parse, uint8_t data) +{ + parse->state = nmeaLinefeed; + return SENTENCE_TYPE_NMEA; +} + +//Read the second checksum byte +uint8_t nmeaChecksumByte2(PARSE_STATE * parse, uint8_t data) +{ + parse->nmeaLength = parse->length; +// parse->state = nmeaLineTermination; + parse->state = nmeaCarriageReturn; + return SENTENCE_TYPE_NMEA; +} + +//Read the first checksum byte +uint8_t nmeaChecksumByte1(PARSE_STATE * parse, uint8_t data) +{ + parse->state = nmeaChecksumByte2; + return SENTENCE_TYPE_NMEA; +} + +//Read the message data +uint8_t nmeaFindAsterisk(PARSE_STATE * parse, uint8_t data) +{ + if (data != '*') + parse->crc ^= data; + else + parse->state = nmeaChecksumByte1; + return SENTENCE_TYPE_NMEA; +} + +//Read the message name +uint8_t nmeaFindFirstComma(PARSE_STATE * parse, uint8_t data) +{ + parse->crc ^= data; + if ((data != ',') || (parse->nmeaMessageNameLength == 0)) + { + if ((data < 'A') || (data > 'Z')) + { + //Display the invalid data + dumpBuffer(parse->buffer, parse->length - 1); + printf (" %s Invalid NMEA data, %d bytes\r\n", + parse->parserName, parse->length - 1); + + parse->buffer[0] = data; + parse->crc = 0; + parse->length = 1; + return waitForPreamble (parse, data); + } + + //Save the message name + parse->nmeaMessageName[parse->nmeaMessageNameLength++] = data; + } + else + { + //Zero terminate the message name + parse->nmeaMessageName[parse->nmeaMessageNameLength++] = 0; + parse->state = nmeaFindAsterisk; + } + return SENTENCE_TYPE_NMEA; +} + +//Read the CRC +uint8_t rtcmReadCrc(PARSE_STATE * parse, uint8_t data) +{ + uint16_t dataSent; + + //Account for this data byte + parse->bytesRemaining -= 1; + + //Wait until all the data is received + if (parse->bytesRemaining > 0) + return SENTENCE_TYPE_RTCM; + + //Update the maximum message length + if (parse->length > parse->maxLength) + { + parse->maxLength = parse->length; + printf("maxLength: %d bytes\r\n", parse->maxLength); + } + + //Display the RTCM messages with bad CRC + parse->crc &= 0x00ffffff; + if (parse->crc) + { + rtcm_crc_errors += 1; + dumpBuffer(parse->buffer, parse->length); + printf (" %s RTCM %d, %2d bytes, bad CRC, expecting 0x%02x%02x%02x, computed: 0x%06x\r\n", + parse->parserName, + parse->message, + parse->length, + parse->buffer[parse->length-3], + parse->buffer[parse->length-2], + parse->buffer[parse->length-1], + parse->rtcmCrc); + } + + //Process the message + parse->state = waitForPreamble; + parse->eomCallback(parse, SENTENCE_TYPE_RTCM); + + //Search for another preamble byte + parse->length = 0; + parse->computeCrc = false; + parse->crc = 0; + return SENTENCE_TYPE_NONE; +} + +//Read the rest of the message +uint8_t rtcmReadData(PARSE_STATE * parse, uint8_t data) +{ + uint16_t dataSent; + + //Account for this data byte + parse->bytesRemaining -= 1; + + //Wait until all the data is received + if (parse->bytesRemaining <= 0) + { + parse->rtcmCrc = parse->crc & 0x00ffffff; + parse->bytesRemaining = 3; + parse->state = rtcmReadCrc; + } + return SENTENCE_TYPE_RTCM; +} + +//Read the lower 4 bits of the message number +uint8_t rtcmReadMessage2(PARSE_STATE * parse, uint8_t data) +{ + parse->message |= data >> 4; + parse->bytesRemaining -= 1; + parse->state = rtcmReadData; + return SENTENCE_TYPE_RTCM; +} + +//Read the upper 8 bits of the message number +uint8_t rtcmReadMessage1(PARSE_STATE * parse, uint8_t data) +{ + parse->message = data << 4; + parse->bytesRemaining -= 1; + parse->state = rtcmReadMessage2; + return SENTENCE_TYPE_RTCM; +} + +//Read the lower 8 bits of the length +uint8_t rtcmReadLength2(PARSE_STATE * parse, uint8_t data) +{ + parse->bytesRemaining |= data; + parse->state = rtcmReadMessage1; + return SENTENCE_TYPE_RTCM; +} + +//Read the upper two bits of the length +uint8_t rtcmReadLength1(PARSE_STATE * parse, uint8_t data) +{ + //Verify the length byte + if (data & (~3)) + { + //Display the invalid data + dumpBuffer(parse->buffer, parse->length - 1); + printf (" %s Invalid RTCM data, %d bytes\r\n", parse->parserName, parse->length - 1); + + //Invalid length, place this byte at the beginning of the buffer + parse->buffer[0] = data; + parse->length = 1; + parse->computeCrc = false; + parse->crc = 0; + + //Start searching for a preamble byte + return waitForPreamble(parse, data); + } + + //Save the upper 2 bits of the length + parse->bytesRemaining = data << 8; + parse->state = rtcmReadLength2; + return SENTENCE_TYPE_RTCM; +} + +//Read the CK_B byte +uint8_t ubloxCkB(PARSE_STATE * parse, uint8_t data) +{ + bool badChecksum; + + //Update the maximum message length + if (parse->length > parse->maxLength) + { + parse->maxLength = parse->length; + printf("maxLength: %d bytes\r\n", parse->maxLength); + } + + //Validate the checksum + badChecksum = ((parse->buffer[parse->length - 2] != parse->ck_a) + || (parse->buffer[parse->length - 1] != parse->ck_b)); + if (badChecksum) + { + ubx_checksum_errors += 1; + dumpBuffer(parse->buffer, parse->length); + printf (" %s U-Blox %d.%d, %2d bytes, bad checksum, expecting 0x%02x%02x, computed: 0x%02x%02x\r\n", + parse->parserName, + parse->message >> 8, + parse->message & 0xff, + parse->length, + parse->buffer[parse->nmeaLength-2], + parse->buffer[parse->nmeaLength-1], + parse->ck_a, + parse->ck_b); + } + + //Process this message + parse->state = waitForPreamble; + parse->eomCallback(parse, SENTENCE_TYPE_UBX); + + //Search for the next preamble byte + parse->length = 0; + parse->crc = 0; + parse->ck_a = 0; + parse->ck_b = 0; + return SENTENCE_TYPE_NONE; +} + +//Read the CK_A byte +uint8_t ubloxCkA(PARSE_STATE * parse, uint8_t data) +{ + parse->state = ubloxCkB; + return SENTENCE_TYPE_UBX; +} + +//Read the payload +uint8_t ubloxPayload(PARSE_STATE * parse, uint8_t data) +{ + //Compute the checksum over the payload + if (parse->bytesRemaining--) + { + //Calculate the checksum + parse->ck_a += data; + parse->ck_b += parse->ck_a; + return SENTENCE_TYPE_UBX; + } + return ubloxCkA(parse, data); +} + +//Read the second length byte +uint8_t ubloxLength2(PARSE_STATE * parse, uint8_t data) +{ + //Calculate the checksum + parse->ck_a += data; + parse->ck_b += parse->ck_a; + + //Save the second length byte + parse->bytesRemaining |= ((uint16_t)data) << 8; + parse->state = ubloxPayload; + return SENTENCE_TYPE_UBX; +} + +//Read the first length byte +uint8_t ubloxLength1(PARSE_STATE * parse, uint8_t data) +{ + //Calculate the checksum + parse->ck_a += data; + parse->ck_b += parse->ck_a; + + //Save the first length byte + parse->bytesRemaining = data; + parse->state = ubloxLength2; + return SENTENCE_TYPE_UBX; +} + +//Read the ID byte +uint8_t ubloxId(PARSE_STATE * parse, uint8_t data) +{ + //Calculate the checksum + parse->ck_a += data; + parse->ck_b += parse->ck_a; + + //Save the ID as the lower 8-bits of the message + parse->message |= data; + parse->state = ubloxLength1; + return SENTENCE_TYPE_UBX; +} + +//Read the class byte +uint8_t ubloxClass(PARSE_STATE * parse, uint8_t data) +{ + //Start the checksum calculation + parse->ck_a = data; + parse->ck_b = data; + + //Save the class as the upper 8-bits of the message + parse->message = ((uint16_t)data) << 8; + parse->state = ubloxId; + return SENTENCE_TYPE_UBX; +} + +//Read the second sync byte +uint8_t ubloxSync2(PARSE_STATE * parse, uint8_t data) +{ + //Verify the sync 2 byte + if (data != 0x62) + { + //Display the invalid data + dumpBuffer(parse->buffer, parse->length - 1); + printf (" %s Invalid UBX data, %d bytes\r\n", parse->parserName, parse->length - 1); + + //Invalid sync 2 byte, place this byte at the beginning of the buffer + parse->length = 0; + parse->buffer[parse->length++] = data; + + //Start searching for a preamble byte + return waitForPreamble(parse, data); + } + + parse->state = ubloxClass; + return SENTENCE_TYPE_UBX; +} + +//Wait for the preamble byte (0xd3) +uint8_t waitForPreamble(PARSE_STATE * parse, uint8_t data) +{ + //Verify that this is the preamble byte + offset = file_offset; + switch(data) + { + case '$': + + // + // NMEA Message + // + // +----------+---------+--------+---------+----------+----------+ + // | Preamble | Name | Comma | Data | Asterisk | Checksum | + // | 8 bits | n bytes | 8 bits | n bytes | 8 bits | 2 bytes | + // | $ | | , | | | | + // +----------+---------+--------+---------+----------+----------+ + // | | + // |<------------------- Checksum ------------------->| + // + + parse->crc = 0; + parse->computeCrc = false; + parse->nmeaMessageNameLength = 0; + parse->state = nmeaFindFirstComma; + return SENTENCE_TYPE_NMEA; + + case 0xb5: + + // + // U-BLOX Message + // + // |<-- Preamble --->| + // | | + // +--------+--------+---------+--------+---------+---------+--------+--------+ + // | SYNC | SYNC | Class | ID | Length | Payload | CK_A | CK_B | + // | 8 bits | 8 bits | 8 bits | 8 bits | 2 bytes | n bytes | 8 bits | 8 bits | + // | 0xb5 | 0x62 | | | | | | | + // +--------+--------+---------+--------+---------+---------+--------+--------+ + // | | + // |<------------- Checksum ------------->| + // + // 8-Bit Fletcher Algorithm, which is used in the TCP standard (RFC 1145) + // http://www.ietf.org/rfc/rfc1145.txt + // Checksum calculation + // Initialization: CK_A = CK_B = 0 + // CK_A += data + // CK_B += CK_A + // + + parse->state = ubloxSync2; + return SENTENCE_TYPE_UBX; + + case 0xd3: + + // + // RTCM Standard 10403.2 - Chapter 4, Transport Layer + // + // |<------------- 3 bytes ------------>|<----- length ----->|<- 3 bytes ->| + // | | | | + // +----------+--------+----------------+---------+----------+-------------+ + // | Preamble | Fill | Message Length | Message | Fill | CRC-24Q | + // | 8 bits | 6 bits | 10 bits | n-bits | 0-7 bits | 24 bits | + // | 0xd3 | 000000 | (in bytes) | | zeros | | + // +----------+--------+----------------+---------+----------+-------------+ + // | | + // |<-------------------------------- CRC -------------------------------->| + // + + //Start the CRC with this byte + parse->crc = 0; + parse->crc = COMPUTE_CRC24Q(parse, data); + parse->computeCrc = true; + + //Get the message length + parse->state = rtcmReadLength1; + return SENTENCE_TYPE_RTCM; + } + + //preamble byte not found + dumpBuffer(parse->buffer, parse->length); + printf (" %s invalid byte 0x%02x\r\n", parse->parserName, data); + parse->length = 0; + parse->state = waitForPreamble; + return SENTENCE_TYPE_NONE; +} + +uint8_t * +get_file ( + const char * filename, + off_t * length + ) +{ + int file; + uint8_t * file_data; + off_t file_size; + + file_data = NULL; + do { + file = open (filename, O_RDONLY); + if (file < 0) { + perror ("ERROR - Failed to open the file"); + break; + } + + // Determine the file length + file_size = lseek (file, 0, SEEK_END); + + // Get the file buffer + file_data = malloc (file_size); + if (!file_data) { + fprintf (stderr, "ERROR - Failed to allocate file buffer!\n"); + break; + } + + // Read the file into memory + lseek (file, 0, SEEK_SET); + if (read (file, file_data, file_size) != file_size) { + fprintf (stderr, "ERROR - Failed to read the file into memory!\n"); + free (file_data); + file_data = NULL; + break; + } + + // Return the file length + *length = file_size; + } while (0); + + // Close the file + if (file > 0) + close (file); + return file_data; +} + +const char * gnrmc = "$GNRMC,"; +const char * gprmc = "$GPRMC,"; +const char * timestamp; + +uint8_t * +find_time_stamp ( + uint8_t * data, + uint8_t * data_end + ) +{ + int offset; + int timestamp_length; + + timestamp_length = strlen (timestamp); + offset = 0; + while (data < data_end) { + if (*data++ != timestamp[offset++]) + offset = 0; + else + if (offset == timestamp_length) { + data -= timestamp_length; + break; + } + } + + // Found a match or end of the data + if (data >= data_end) + data = NULL; + return data; +} + +uint8_t * +write_temp_file ( + const char * filename, + uint8_t * data, + uint8_t * data_end + ) +{ + int file; + ssize_t file_size; + + do { + file = creat (filename, S_IRWXU | S_IRGRP | S_IROTH); + if (file < 0) { + perror ("ERROR - Failed to create the file"); + break; + } + + // Write the data to the file + file_size = data_end - data; + if (write (file, data, file_size) != file_size) { + fprintf (stderr, "ERROR - Failed to write to %s!\n", filename); + break; + } + + // Done with the data + data = NULL; + } while (0); + + // Close the file + if (file > 0) + close (file); + return data; +} + +int +main ( + int argc, + char ** argv + ) +{ + uint8_t * a; + off_t a_length; + uint8_t * b; + off_t b_length; + int delta; + char * filename_a; + char * filename_b; + int match_length; + uint8_t * ts_a; + uint8_t * ts_b; + int ts_offset; + +/* + int bit; + unsigned char * data; + unsigned char * data_end; + int file; + off_t file_size; + int index; + int length; + int message_number; + int message_type; + static PARSE_STATE parse = {waitForPreamble, processMessage, "Tx"}; + unsigned char * string; + int total; + uint8_t value; +*/ + + // Dispay the help text + if (argc != 3) { + fprintf (stderr, "%s file1 file2\n", argv[0]); + return -1; + } + + // Open the first binary file + filename_a = argv[1]; + a = get_file (filename_a, &a_length); + if (!a) { + return -2; + } + + // Open the second binary file + filename_b = argv[2]; + b = get_file (filename_b, &b_length); + if (!b) { + return -3; + } + + // Find the time stamps + timestamp = gnrmc; + ts_offset = strlen (timestamp); + ts_a = find_time_stamp (a, &a[a_length]); + if (!ts_a) { + timestamp = gprmc; + ts_offset = strlen (timestamp); + ts_a = find_time_stamp (a, &a[a_length]); + if (!ts_a) { + fprintf (stderr, "ERROR - Failed to find timestamp in %s\n", filename_a); + return -4; + } + } + + ts_b = find_time_stamp (b, &b[b_length]); + if (!ts_b) { + fprintf (stderr, "ERROR - Failed to find timestamp in %s\n", filename_b); + return -4; + } + + // Synchronize the time stamps + match_length = ts_offset + 9; + do { + delta = strncmp ((char *)ts_a, (char *)ts_b, match_length); + if (delta == 0) + break; + if (delta < 0) { + ts_a = find_time_stamp (&ts_a[match_length], &a[a_length]); + if (!ts_a) { + fprintf (stderr, "ERROR - Failed to find matching timestamp in %s\n", filename_a); + return -5; + } + continue; + } + ts_b = find_time_stamp (&ts_b[match_length], &b[b_length]); + if (!ts_b) { + fprintf (stderr, "ERROR - Failed to find matching timestamp in %s\n", filename_b); + return -6; + } + } while (1); + + printf ("Timestamp: %c%c%c%c%c%c%c%c%c\n", + ts_a[ts_offset], + ts_a[ts_offset + 1], + ts_a[ts_offset + 2], + ts_a[ts_offset + 3], + ts_a[ts_offset + 4], + ts_a[ts_offset + 5], + ts_a[ts_offset + 6], + ts_a[ts_offset + 7], + ts_a[ts_offset + 8]); + + // Create the temporary files + if (write_temp_file ("a.txt", ts_a, &a[a_length])) + return -7; + if (write_temp_file ("b.txt", ts_b, &b[b_length])) + return -8; + +/* + // Open the log file + file = open (filename, O_RDONLY); + if (file < 0) { + perror ("ERROR - Failed to open the file"); + return -1; + } + + // Determine the file length + file_size = lseek (file, 0, SEEK_END); + + // Get the file buffer + file_data = malloc (file_size); + if (!file_data) { + fprintf (stderr, "ERROR - Failed to allocate file buffer!\n"); + return -2; + } + + // Read the file into memory + lseek (file, 0, SEEK_SET); + if (read (file, file_data, file_size) != file_size) { + fprintf (stderr, "ERROR - Failed to read the file into memory!\n"); + } + + // Close the file + close (file); + + // Skip the first byte to force unaligned start + data = file_data; + data_end = &data[file_size]; + string = data; + while (data < data_end) { + file_offset = data - file_data; + + //Save the data byte + value = *data; + parse.buffer[parse.length++] = value; + + //Compute the CRC value for the message + if (parse.computeCrc) + parse.crc = COMPUTE_CRC24Q(&parse, value); + + //Parse this message + parse.state(&parse, value); + data++; + } + + // Display the checksum and CRC errors + if (nmea_checksum_errors) + printf (" Total NMEA checksum errors: %d\n", nmea_checksum_errors); + if (rtcm_crc_errors) + printf (" Total RTCM message CRC errors: %d\n", rtcm_crc_errors); + if (ubx_checksum_errors) + printf (" Total UBX message checksum errors: %d\n", ubx_checksum_errors); + + // Display the NMEA message list + if (DISPLAY_NMEA_MESSAGES) { + printf ("NMEA Message List:\n"); +fflush(stdout); + NMEA_MESSAGE * message = nmea_list; + while (message) { + printf (" %s: %d %s, max length: %d bytes\n", message->message, message->count, + (message->count == 1) ? "time" : "times", message->max_length); + message = message->next; + } + } + + // Display the RTCM message type list + if (DISPLAY_RTCM_MESSAGE_LIST) { + printf ("RTCM Message List:\n"); +fflush(stdout); + for (index = 0; index < (int)(sizeof(rtcm_messages) / sizeof(rtcm_messages[0])); index++) { + if (rtcm_messages[index]) + for (bit = 0; bit < 32; bit++) { + message_number = (index << 5) | bit; + if (rtcm_messages[index] & (1 << bit)) + printf (" %d (%02x %xx): %d %s, max length: %d bytes\n", message_number, + message_number >> 4, message_number & 0xf, + rtcm_message_count[message_number], + (rtcm_message_count[message_number] == 1) ? "time" : "times", + rtcm_max_message_length[message_number]); + } + } + } + + // Display the UBX message type list + if (DISPLAY_UBX_MESSAGE_LIST) { + printf ("UBX Message List:\n"); +fflush(stdout); + for (index = 0; index < (int)(sizeof(ubx_messages) / sizeof(ubx_messages[0])); index++) { + if (ubx_messages[index]) + for (bit = 0; bit < 32; bit++) { + message_number = (index << 5) | bit; + if (ubx_messages[index] & (1 << bit)) + printf (" %d.%d (0x%02x.%02x): %d %s, max length: %d bytes\n", + message_number >> 8, message_number & 0xff, + message_number >> 8, message_number & 0xff, + ubx_message_count[message_number], + (ubx_message_count[message_number] == 1) ? "time" : "times", + ubx_max_message_length[message_number]); + } + } + } + + // Display the bad characters + if (DISPLAY_BAD_CHARACTERS) { + printf ("Bad characters:\n"); +fflush(stdout); + total = 0; + for (index = 0; index < 256; index++) { + if (bad_characters[index >> 5] & (1 << (index & 0x1f))) { + printf (" 0x%02x: %d\n", index, bad_character_count[index]); + total += bad_character_count[index]; + } + } + printf (" Total: %d\n", total); + } + + // Display the bad character offsets + if (DISPLAY_BAD_CHARACTER_OFFSETS) { + printf ("Bad character offsets:\n"); +fflush(stdout); + total = 0; + for (index = 0; index <= bad_character_offset_count; index++) { + printf (" 0x%08x: %d bytes\n", bad_character_offset[index], bad_character_length[index]); + total += bad_character_length[index]; + } + printf (" Total: %d\n", total); + } +*/ + return 0; +} diff --git a/C/NMEA_Client.c b/C/NMEA_Client.c new file mode 100644 index 000000000..b1a1459e2 --- /dev/null +++ b/C/NMEA_Client.c @@ -0,0 +1,81 @@ +/* + * NMEA_Client.c + * + * Program to display the NMEA messages from the RTK Express + */ + +#include +#include +#include +#include +#include +#include + +uint8_t rxBuffer[2048]; + +int +main ( + int argc, + char ** argv + ) +{ + int bytesRead; + int nmeaSocket; + struct sockaddr_in serverIpAddress; + + + // Display the help text + if (argc != 2) + { + printf ("%s serverIpAddress\n", argv[0]); + return -1; + } + + // Initialize the server address + memset (&serverIpAddress, '0', sizeof(serverIpAddress)); + serverIpAddress.sin_family = AF_INET; + serverIpAddress.sin_addr.s_addr = htonl(INADDR_ANY); + serverIpAddress.sin_port = htons(1958); + if (inet_pton (AF_INET, argv[1], &serverIpAddress.sin_addr) <= 0) + { + perror ("ERROR - Invalid IPv4 address!\n"); + return -2; + } + + //Create the socket + nmeaSocket = socket(AF_INET, SOCK_STREAM, 0); + if (nmeaSocket < 0) + { + perror ("ERROR - Unable to create the client socket!\n"); + return -3; + } + + if (connect (nmeaSocket, (struct sockaddr *)&serverIpAddress, sizeof(serverIpAddress)) < 0) + { + perror("Error : Failed to connect to NMEA server!\n"); + return -4; + } + + // Read the NMEA data from the client + while ((bytesRead = read (nmeaSocket, rxBuffer, sizeof(rxBuffer)-1)) > 0) + { + // Zero terminate the NMEA string + rxBuffer[bytesRead] = 0; + + // Output the NMEA buffer + if (fputs ((char *)rxBuffer, stdout) == EOF) + { + perror ("ERROR - Failed to write to stdout!\n"); + return -5; + } + } + + if (bytesRead < 0) + { + perror ("ERROR - Failed reading from NMEA server!\n"); + return -6; + } + + // Successful execution + return 0; +} diff --git a/C/Split_Messages.c b/C/Split_Messages.c new file mode 100644 index 000000000..767d6c617 --- /dev/null +++ b/C/Split_Messages.c @@ -0,0 +1,1273 @@ +// Split_Messages.c + +#include +#include +#include +#include +#include +#include +#include + +#include "crc24q.h" +#include "crc24q.c" +//#include "Crc24q.h" + +#define COMPUTE_CRC24Q(parse, data) (((parse)->crc << 8) ^ crc24q[data ^ (((parse)->crc >> 16) & 0xff)]) + +#define DISPLAY_BAD_CHARACTERS 0 +#define DISPLAY_BAD_CHARACTER_OFFSETS 1 +#define DISPLAY_RTCM_MESSAGE_LIST 1 +#define DISPLAY_UBX_MESSAGE_LIST 1 +#define DISPLAY_BOUNDARY 0 +#define DISPLAY_DATA_BYTES 0 +#define DISPLAY_LIST 0 +#define DISPLAY_MESSAGE_TYPE 0 +#define DISPLAY_MESSAGE_TYPE_LIST 1 +#define DISPLAY_NMEA_MESSAGES 1 +#define DISPLAY_STRINGS 0 + +#define MESSAGE_LENGTH(length) (3 + length + 3) + +#define BINARY_MESSAGE_START 0xd3 + +#define MAX_BAD_CHARACTERS 1000 + +uint32_t bad_characters[256>>5]; +uint32_t bad_character_count[256]; +uint32_t bad_character_offset[MAX_BAD_CHARACTERS]; +uint32_t bad_character_length[MAX_BAD_CHARACTERS]; +int32_t bad_character_offset_count = -1; + +char buffer[65536]; +char string[256]; +uint8_t * file_data; +uint32_t rtcm_messages[4096 >> 5]; +uint32_t rtcm_message_count[4096]; +uint32_t rtcm_max_message_length[4096]; +uint32_t ubx_messages[65536 >> 5]; +uint32_t ubx_message_count[65536]; +uint32_t ubx_max_message_length[65536]; +int bad_checksum_header; +int nmea_checksum_errors; +int rtcm_crc_errors; +int ubx_checksum_errors; + +typedef struct _NMEA_MESSAGE { + struct _NMEA_MESSAGE * next; + uint8_t * message; + uint32_t count; + uint32_t max_length; +} NMEA_MESSAGE; + +NMEA_MESSAGE * nmea_list; + +enum SentenceTypes +{ +SENTENCE_TYPE_NONE = 0, +SENTENCE_TYPE_NMEA, +SENTENCE_TYPE_UBX, +SENTENCE_TYPE_RTCM +} currentSentence = SENTENCE_TYPE_NONE; + +typedef struct _PARSE_STATE * P_PARSE_STATE; + +//Parse routine +typedef uint8_t (* PARSE_ROUTINE)(P_PARSE_STATE parse, //Parser state + uint8_t data); //Incoming data byte + +//End of message callback routine +typedef void (* EOM_CALLBACK)(P_PARSE_STATE parse, //Parser state + uint8_t type); //Message type + +#define PARSE_BUFFER_LENGTH 0x10000 + +typedef struct _PARSE_STATE +{ + PARSE_ROUTINE state; //Parser state routine + EOM_CALLBACK eomCallback; //End of message callback routine + const char * parserName; //Name of parser + uint32_t crc; //RTCM computed CRC + uint32_t rtcmCrc; //Computed CRC value for the RTCM message + uint32_t invalidRtcmCrcs; //Number of bad RTCM CRCs detected + uint16_t bytesRemaining; //Bytes remaining in RTCM CRC calculation + uint16_t length; //Message length including line termination + uint16_t maxLength; //Maximum message length including line termination + uint16_t message; //RTCM message number + uint16_t nmeaLength; //Length of the NMEA message without line termination + uint8_t buffer[PARSE_BUFFER_LENGTH]; //Buffer containing the message + uint8_t nmeaMessageName[16]; //Message name + uint8_t nmeaMessageNameLength; //Length of the message name + uint8_t ck_a; //U-blox checksum byte 1 + uint8_t ck_b; //U-blox checksum byte 2 + bool computeCrc; //Compute the CRC when true +} PARSE_STATE; + +//Forward declaration +uint8_t waitForPreamble(PARSE_STATE * parse, uint8_t data); +uint64_t offset; +uint64_t file_offset; + +void +dump_message ( + unsigned char * data + ) +{ + unsigned int actual; + unsigned int crc; + int index; + int length; + int offset; + + // + // +----------+--------+----------------+---------+----------+---------+ + // | Preamble | Fill | Message Length | Message | Fill | CRC-24Q | + // | 8 bits | 6 bits | 10 bits | n-bits | 0-7 bits | 24 bits | + // | 0xd3 | 000000 | | | zeros | | + // +----------+--------+----------------+---------+----------+---------+ + // + + // Get the number of bytes + length = (data[1] << 8) | data[2]; + if (DISPLAY_DATA_BYTES) { + // Dump the message + offset = data - file_data; + printf ("0x%08x: %02x %02x %02x\n", offset, data[0], data[1], data[2]); + offset += 3; + index = 0; + if (length > 0) { + do + { + // Display the offset at the beginning of the line + if (!(index & 0xf)) + printf ("0x%08x: ", offset); + + // Display the data bytes + printf ("%02x ", data[index+3]); + offset += 1; + + // Terminate the lines + if (!(++index % (DISPLAY_DATA_BYTES ? DISPLAY_DATA_BYTES : 1))) + printf ("\n"); + } while (index < length); + + // Terminate a short line + if (index % (DISPLAY_DATA_BYTES ? DISPLAY_DATA_BYTES : 1)) + printf ("\n"); + } + + // Display the Cyclic Redundancy Check (CRC) + printf ("0x%08x: %02x %02x %02x CRC: %s\n", + offset, data[3 + index], data[3 + index + 1], data[3 + index + 2], + crc24q_check (data, MESSAGE_LENGTH(length)) ? "Matches" : "Does not match!"); + } else { + if (!crc24q_check (data, MESSAGE_LENGTH(length))) { + if (!bad_checksum_header) { + bad_checksum_header = 1; + printf ("Bad checksums:\n"); + } + length = MESSAGE_LENGTH(length); + crc = crc24q_hash(data, length - 3); + actual = (data[length - 3] << 16) | (data[length - 2] << 8) | data[length - 1]; + printf (" 0x%08lx: Binary message, expected CRC: 0x%06x, actual CRC: 0x%06x\n", + data - file_data, crc, actual); + rtcm_crc_errors += 1; + } + } +} + +void +display_string ( + unsigned char * string, + int length + ) +{ + char * temp; + char * temp_end; + + // Copy the strings into the buffer + memcpy (buffer, string, length); + buffer[length] = 0; + + // Terminate the strings + temp = buffer; + temp_end = &temp[length]; + do { + if ((*temp == '\r') || (*temp == '\n')) + *temp = 0; + } while (++temp < temp_end); + + // Display the strings + temp = buffer; + while (temp < temp_end) { + if (*temp) + printf ("%s\n", temp); + temp += strlen(temp) + 1; + } +} + +unsigned char * +process_nmea_message ( + unsigned char * data, + unsigned char * data_end + ) +{ + unsigned char checksum; + char checksum_char[2]; + NMEA_MESSAGE * message; + NMEA_MESSAGE * previous; + unsigned char * start; + + // Check for the beginning of a NMEA message ($) + if (*data != '$') { + if ((*data != '\r') && (*data != '\n')) { + bad_character_count[*data] += 1; + bad_characters[*data >> 5] |= 1 << (*data & 0x1f); + if ((bad_character_offset_count < 0) + || ((bad_character_offset[bad_character_offset_count] + bad_character_length[bad_character_offset_count]) != (data - file_data))) { + bad_character_offset_count += 1; + bad_character_offset[bad_character_offset_count] = data - file_data; + } + bad_character_length[bad_character_offset_count] += 1; + } + return data + 1; + } + + // Skip over the dollar sign ($) + start = data++; + + // Scan for comma or end of message + checksum = 0; + while ((*data != ',') && (*data != '\r') && (*data != '\n') + && (*data != BINARY_MESSAGE_START)) + checksum ^= *data++; + + // Return if this is the start of a binary message + if (*data == BINARY_MESSAGE_START) + return data; + + // Remember the message if a comma was found + if (*data == ',') { + if (DISPLAY_LIST) + printf ("----------------------\r\n"); + + // Build the zero terminated string + memset (string, 0, sizeof(string)); + strncpy (string, (char *)start, data - start); + + /* + list --> NULL + + previous = NULL + string: $GNGST --. + V + +------------+ + list --> | $GNGST (1) | --> NULL + +------------+ + + previous = $GNGST + string: $GNGGA --. + V + +------------+ +------------+ + list --> | $GNGGA (1) | --> | $GNGST (1) | --> NULL + +------------+ +------------+ + + previous = $GNGSA + string: $GNGSA --------------------. + V + +------------+ +------------+ +------------+ + list --> | $GNGGA (1) | --> | $GNGSA (1) | --> | $GNGST (1) | --> NULL + +------------+ +------------+ +------------+ + + previous = $GNGSA + string: $GNGSA --------------------. + V + +------------+ +------------+ +------------+ + list --> | $GNGGA (1) | --> | $GNGSA (2) | --> | $GNGST (1) | --> NULL + +------------+ +------------+ +------------+ + + previous = $GNGST + string: $GNRMC ---------------------------------------------------------. + V + +------------+ +------------+ +------------+ +------------+ + list --> | $GNGGA (1) | --> | $GNGSA (2) | --> | $GNGST (1) | --> | $GNRMC (1) | --> NULL + +------------+ +------------+ +------------+ +------------+ + + */ + + // Display the list + if (DISPLAY_LIST) { + printf ("list: "); + for (previous = nmea_list; previous; previous = previous->next) + printf ("%s(%d)-->", previous->message, previous->count); + printf ("NULL\n"); + } + + // Find the location for insertion + // Check for something in the list + previous = NULL; + if (nmea_list) { + if (strcmp((char *)nmea_list->message, string) <= 0) { + previous = nmea_list; + while (previous->next && (strcmp((char *)previous->next->message, string) <= 0)) + previous = previous->next; + } + } + + // Display the insertion decision + if (DISPLAY_LIST) { + printf ("previous: %s\n", ((previous != NULL) ? (char *)previous->message : (char *)"NULL")); + printf ("string: %s\n", string); + } + + // Check for a duplicate message + if (previous && (strcmp ((char *)previous->message, string) == 0)) { + if (DISPLAY_LIST) + printf ("Duplicate found: %d\n", previous->count); + previous->count += 1; + message = previous; + } else { + // Add the new message + message = malloc (sizeof(NMEA_MESSAGE) + strlen(string) + 1); + message->message = (uint8_t *)(message + 1); + strcpy((char *)message->message, string); + message->count = 1; + + // Message insertion position + // previous == NULL; ==> list head + // previous != NULL; ==> middle or end of list + if (!previous) { + if (DISPLAY_LIST) + printf ("Add to head of the list\n"); + + // Add this message at the start of the list + message->next = nmea_list; + nmea_list = message; + } else { + if (DISPLAY_LIST) + printf ("Add to middle of the list\n"); + + // Insert this message into the middle of the list + message->next = previous->next; + previous->next = message; + } + } + + // Display the new list + if (DISPLAY_LIST) { + printf ("New list: "); + for (previous = nmea_list; previous; previous = previous->next) + printf ("%s(%d)-->", previous->message, previous->count); + printf ("NULL\n"); + } + } + + // Scan for asterisk or end of message + while ((*data != '*') && (*data != '\r') && (*data != '\n') + && (*data != BINARY_MESSAGE_START)) + checksum ^= *data++; + + // Check for end of NMEA message, validate the checksum + if (*data == '*') { + checksum_char[0] = ((checksum >> 4) & 0xf) + '0'; + if (checksum_char[0] > '9') + checksum_char[0] += 'A' - '0' - 10; + checksum_char[1] = (checksum & 0xf) + '0'; + if (checksum_char[1] > '9') + checksum_char[1] += 'A' - '0' - 10; + if ((toupper(data[1]) != checksum_char[0]) || (toupper(data[2]) != checksum_char[1])) { + if (!bad_checksum_header) { + bad_checksum_header = 1; + printf ("Bad checksums:\n"); + } + printf (" 0x%08lx: NMEA %s, expected CRC: 0x%02x, actual CRC: 0x%c%c\n", + data - file_data, &string[1], checksum, data[1], data[2]); + nmea_checksum_errors += 1; + } + data += 3; + } + + // Scan for end of message + while ((*data != '\r') && (*data != '\n') && (*data != BINARY_MESSAGE_START)) + data++; + + return data; +} + +uint8_t * +find_gnss_header ( + uint8_t * data, + uint8_t * data_end + ) +{ + int length; + + do { + // From RTCM 10403.2 Section 4 + // + // +----------+--------+----------------+---------+----------+---------+ + // | Preamble | Fill | Message Length | Message | Fill | CRC-24Q | + // | 8 bits | 6 bits | 10 bits | n-bits | 0-7 bits | 24 bits | + // | 0xd3 | 000000 | | | zeros | | + // +----------+--------+----------------+---------+----------+---------+ + // + + // Locate the beginning of the message + while ((data < data_end) && (*data != BINARY_MESSAGE_START)) + data = process_nmea_message (data, data_end); + + // Check for end of data + if (data >= data_end) + break; + + // Get the number of bytes + length = (data[1] << 8) | data[2]; + if ((data + MESSAGE_LENGTH(length)) <= data_end) { + + // Verify the CRC + if (crc24q_check (data, MESSAGE_LENGTH(length))) + break; + } + + // Skip this preamble byte + data++; + } while (data < data_end); + + // Return the address of the next preamble byte or end of data + return data; +} + +void processNemaMessage(PARSE_STATE * parse) +{ + NMEA_MESSAGE * message; + NMEA_MESSAGE * previous; + + //Display the NMEA message +// dumpBuffer(parse->buffer, parse->length); +// printf(" %s NMEA %s, %d bytes\r\n", parse->parserName, parse->nmeaMessageName, parse->length); + + // Display the list + if (DISPLAY_LIST) { + printf ("list: "); + for (previous = nmea_list; previous; previous = previous->next) + printf ("%s(%d)-->", previous->message, previous->count); + printf ("NULL\n"); + } + + // Find the location for insertion + // Check for something in the list + previous = NULL; + if (nmea_list) { + if (strcmp((char *)nmea_list->message, (char *)parse->nmeaMessageName) <= 0) { + previous = nmea_list; + while (previous->next && (strcmp((char *)previous->next->message, (char *)parse->nmeaMessageName) <= 0)) + previous = previous->next; + } + } + + // Display the insertion decision + if (DISPLAY_LIST) { + printf ("previous: %s\n", ((previous != NULL) ? (char *)previous->message : (char *)"NULL")); + printf ("string: %s\n", parse->nmeaMessageName); + } + + // Check for a duplicate message + if (previous && (strcmp ((char *)previous->message, (char *)parse->nmeaMessageName) == 0)) { + if (DISPLAY_LIST) + printf ("Duplicate found: %d\n", previous->count); + previous->count += 1; + message = previous; + if (message->max_length < parse->length) + message->max_length = parse->length; + } else { + // Add the new message + message = malloc (sizeof(NMEA_MESSAGE) + strlen((char *)parse->nmeaMessageName) + 1); + message->message = (uint8_t *)(message + 1); + strcpy((char *)message->message, (char *)parse->nmeaMessageName); + message->count = 1; + message->max_length = parse->length; + + // Message insertion position + // previous == NULL; ==> list head + // previous != NULL; ==> middle or end of list + if (!previous) { + if (DISPLAY_LIST) + printf ("Add to head of the list\n"); + + // Add this message at the start of the list + message->next = nmea_list; + nmea_list = message; + } else { + if (DISPLAY_LIST) + printf ("Add to middle of the list\n"); + + // Insert this message into the middle of the list + message->next = previous->next; + previous->next = message; + } + } + + // Display the new list + if (DISPLAY_LIST) { + printf ("New list: "); + for (previous = nmea_list; previous; previous = previous->next) + printf ("%s(%d)-->", previous->message, previous->count); + printf ("NULL\n"); + } +} + +void processRtcmMessage(PARSE_STATE * parse) +{ +// dumpBuffer(parse->buffer, parse->length); +// printf(" %s RTCM %d, %d bytes\r\n", parse->parserName, parse->message, parse->length); + rtcm_messages[parse->message >> 5] |= 1 << (parse->message & 0x1f); + rtcm_message_count[parse->message] += 1; + if (rtcm_max_message_length[parse->message] < parse->length) + rtcm_max_message_length[parse->message] = parse->length; +} + +void processUbxMessage(PARSE_STATE * parse) +{ +// dumpBuffer(parse->buffer, parse->length); +// printf(" %s UBX %d.%d, %d bytes\r\n", parse->parserName, parse->message >> 8, parse->message & 0xff, parse->length); + ubx_messages[parse->message >> 5] |= 1 << (parse->message & 0x1f); + ubx_message_count[parse->message] += 1; + if (ubx_max_message_length[parse->message] < parse->length) + ubx_max_message_length[parse->message] = parse->length; +} + +//Process the message +void processMessage(PARSE_STATE * parse, uint8_t type) +{ + switch (type) + { + case SENTENCE_TYPE_NMEA: + processNemaMessage(parse); + break; + + case SENTENCE_TYPE_RTCM: + processRtcmMessage(parse); + break; + + case SENTENCE_TYPE_UBX: + processUbxMessage(parse); + break; + + default: + printf ("Unknown message type: %d\r\n", type); + break; + } +} + +//Convert nibble to ASCII +uint8_t nibbleToAscii(int nibble) +{ + nibble &= 0xf; + return (nibble > 9) ? nibble + 'a' - 10 : nibble + '0'; +} + +//Convert nibble to ASCII +int AsciiToNibble(int data) +{ + //Convert the value to lower case + data |= 0x20; + if ((data >= 'a') && (data <= 'f')) + return data - 'a' + 10; + if ((data >= '0') && (data <= '9')) + return data - '0'; + return -1; +} + +void dumpBuffer(uint8_t * buffer, uint16_t length) +{ + unsigned int bytes; + uint8_t * end; + unsigned int index; + + end = &buffer[length]; + while (buffer < end) + { + //Determine the number of bytes to display on the line + bytes = end - buffer; + if (bytes > (16 - (offset & 0xf))) + bytes = 16 - (offset & 0xf); + + //Display the offset + printf("0x%08lx: ", offset); + + //Skip leading bytes + for (index = 0; index < (offset & 0xf); index++) + printf(" "); + + //Display the data bytes + for (index = 0; index < bytes; index++) + printf("%02x ", buffer[index]); + + //Separate the data bytes from the ASCII + for (; index < (16 - (offset & 0xf)); index++) + printf(" "); + printf(" "); + + //Skip leading bytes + for (index = 0; index < (offset & 0xf); index++) + printf(" "); + + //Display the ASCII values + for (index = 0; index < bytes; index++) + printf("%c", ((buffer[index] < ' ') || (buffer[index] >= 0x7f)) + ? '.' : buffer[index]); + printf("\r\n"); + + //Set the next line of data + buffer += bytes; + offset += bytes; + } +} + +//Read the line termination +uint8_t nmeaLineTermination(PARSE_STATE * parse, uint8_t data) +{ + unsigned int checksum; + + //Process the line termination + if ((data != '\r') && (data != '\n')) + { + //Don't include this character in the buffer + parse->length--; + + //Convert the checksum characters into binary + checksum = AsciiToNibble(parse->buffer[parse->nmeaLength - 2]) << 4; + checksum |= AsciiToNibble(parse->buffer[parse->nmeaLength - 1]); + + //Validate the checksum + if (checksum == parse->crc) + parse->crc = 0; + if (parse->crc) + { + nmea_checksum_errors += 1; + dumpBuffer(parse->buffer, parse->length); + if ((AsciiToNibble(parse->buffer[parse->nmeaLength-2]) >= 0) + && (AsciiToNibble(parse->buffer[parse->nmeaLength-1]) >= 0)) + printf (" %s NMEA %s, %2d bytes, bad checksum, expecting 0x%c%c, computed: 0x%02x\r\n", + parse->parserName, + parse->nmeaMessageName, + parse->length, + parse->buffer[parse->nmeaLength-2], + parse->buffer[parse->nmeaLength-1], + parse->crc); + else + printf (" %s NMEA %s, %2d bytes, invalid checksum bytes 0x%02x 0x%02x, computed: 0x%02x\r\n", + parse->parserName, + parse->nmeaMessageName, + parse->length, + parse->buffer[parse->nmeaLength-2], + parse->buffer[parse->nmeaLength-1], + parse->crc); + } + + //Process this message + parse->eomCallback(parse, SENTENCE_TYPE_NMEA); + + //Add this character to the beginning of the buffer + parse->buffer[0] = data; + parse->length = 1; + return waitForPreamble(parse, data); + } + return SENTENCE_TYPE_NMEA; +} + +//Read the linefeed +uint8_t nmeaLinefeed(PARSE_STATE * parse, uint8_t data) +{ + unsigned int checksum; + uint8_t sentenceType; + + //Convert the checksum characters into binary + checksum = AsciiToNibble(parse->buffer[parse->nmeaLength - 2]) << 4; + checksum |= AsciiToNibble(parse->buffer[parse->nmeaLength - 1]); + + //Update the maximum message length + if (parse->length > parse->maxLength) + { + parse->maxLength = parse->length; + printf("maxLength: %d bytes\r\n", parse->maxLength); + } + + //Validate the checksum + if (checksum == parse->crc) + parse->crc = 0; + if (parse->crc) + { + nmea_checksum_errors += 1; + dumpBuffer(parse->buffer, parse->length); + printf (" %s NMEA %s, %2d bytes, bad checksum, expecting 0x%c%c, computed: 0x%02x\r\n", + parse->parserName, + parse->nmeaMessageName, + parse->length, + parse->buffer[parse->nmeaLength-2], + parse->buffer[parse->nmeaLength-1], + parse->crc); + } + + //Process this message + parse->state = waitForPreamble; + parse->eomCallback(parse, SENTENCE_TYPE_NMEA); + + //Search for another preamble byte + parse->length = 0; + parse->crc = 0; + return SENTENCE_TYPE_NONE; +} + +//Read the carriage return +uint8_t nmeaCarriageReturn(PARSE_STATE * parse, uint8_t data) +{ + parse->state = nmeaLinefeed; + return SENTENCE_TYPE_NMEA; +} + +//Read the second checksum byte +uint8_t nmeaChecksumByte2(PARSE_STATE * parse, uint8_t data) +{ + parse->nmeaLength = parse->length; +// parse->state = nmeaLineTermination; + parse->state = nmeaCarriageReturn; + return SENTENCE_TYPE_NMEA; +} + +//Read the first checksum byte +uint8_t nmeaChecksumByte1(PARSE_STATE * parse, uint8_t data) +{ + parse->state = nmeaChecksumByte2; + return SENTENCE_TYPE_NMEA; +} + +//Read the message data +uint8_t nmeaFindAsterisk(PARSE_STATE * parse, uint8_t data) +{ + if (data != '*') + parse->crc ^= data; + else + parse->state = nmeaChecksumByte1; + return SENTENCE_TYPE_NMEA; +} + +//Read the message name +uint8_t nmeaFindFirstComma(PARSE_STATE * parse, uint8_t data) +{ + parse->crc ^= data; + if ((data != ',') || (parse->nmeaMessageNameLength == 0)) + { + if ((data < 'A') || (data > 'Z')) + { + //Display the invalid data + dumpBuffer(parse->buffer, parse->length - 1); + printf (" %s Invalid NMEA data, %d bytes\r\n", + parse->parserName, parse->length - 1); + + parse->buffer[0] = data; + parse->crc = 0; + parse->length = 1; + return waitForPreamble (parse, data); + } + + //Save the message name + parse->nmeaMessageName[parse->nmeaMessageNameLength++] = data; + } + else + { + //Zero terminate the message name + parse->nmeaMessageName[parse->nmeaMessageNameLength++] = 0; + parse->state = nmeaFindAsterisk; + } + return SENTENCE_TYPE_NMEA; +} + +//Read the CRC +uint8_t rtcmReadCrc(PARSE_STATE * parse, uint8_t data) +{ + uint16_t dataSent; + + //Account for this data byte + parse->bytesRemaining -= 1; + + //Wait until all the data is received + if (parse->bytesRemaining > 0) + return SENTENCE_TYPE_RTCM; + + //Update the maximum message length + if (parse->length > parse->maxLength) + { + parse->maxLength = parse->length; + printf("maxLength: %d bytes\r\n", parse->maxLength); + } + + //Display the RTCM messages with bad CRC + parse->crc &= 0x00ffffff; + if (parse->crc) + { + rtcm_crc_errors += 1; + dumpBuffer(parse->buffer, parse->length); + printf (" %s RTCM %d, %2d bytes, bad CRC, expecting 0x%02x%02x%02x, computed: 0x%06x\r\n", + parse->parserName, + parse->message, + parse->length, + parse->buffer[parse->length-3], + parse->buffer[parse->length-2], + parse->buffer[parse->length-1], + parse->rtcmCrc); + } + + //Process the message + parse->state = waitForPreamble; + parse->eomCallback(parse, SENTENCE_TYPE_RTCM); + + //Search for another preamble byte + parse->length = 0; + parse->computeCrc = false; + parse->crc = 0; + return SENTENCE_TYPE_NONE; +} + +//Read the rest of the message +uint8_t rtcmReadData(PARSE_STATE * parse, uint8_t data) +{ + uint16_t dataSent; + + //Account for this data byte + parse->bytesRemaining -= 1; + + //Wait until all the data is received + if (parse->bytesRemaining <= 0) + { + parse->rtcmCrc = parse->crc & 0x00ffffff; + parse->bytesRemaining = 3; + parse->state = rtcmReadCrc; + } + return SENTENCE_TYPE_RTCM; +} + +//Read the lower 4 bits of the message number +uint8_t rtcmReadMessage2(PARSE_STATE * parse, uint8_t data) +{ + parse->message |= data >> 4; + parse->bytesRemaining -= 1; + parse->state = rtcmReadData; + return SENTENCE_TYPE_RTCM; +} + +//Read the upper 8 bits of the message number +uint8_t rtcmReadMessage1(PARSE_STATE * parse, uint8_t data) +{ + parse->message = data << 4; + parse->bytesRemaining -= 1; + parse->state = rtcmReadMessage2; + return SENTENCE_TYPE_RTCM; +} + +//Read the lower 8 bits of the length +uint8_t rtcmReadLength2(PARSE_STATE * parse, uint8_t data) +{ + parse->bytesRemaining |= data; + parse->state = rtcmReadMessage1; + return SENTENCE_TYPE_RTCM; +} + +//Read the upper two bits of the length +uint8_t rtcmReadLength1(PARSE_STATE * parse, uint8_t data) +{ + //Verify the length byte + if (data & (~3)) + { + //Display the invalid data + dumpBuffer(parse->buffer, parse->length - 1); + printf (" %s Invalid RTCM data, %d bytes\r\n", parse->parserName, parse->length - 1); + + //Invalid length, place this byte at the beginning of the buffer + parse->buffer[0] = data; + parse->length = 1; + parse->computeCrc = false; + parse->crc = 0; + + //Start searching for a preamble byte + return waitForPreamble(parse, data); + } + + //Save the upper 2 bits of the length + parse->bytesRemaining = data << 8; + parse->state = rtcmReadLength2; + return SENTENCE_TYPE_RTCM; +} + +//Read the CK_B byte +uint8_t ubloxCkB(PARSE_STATE * parse, uint8_t data) +{ + bool badChecksum; + + //Update the maximum message length + if (parse->length > parse->maxLength) + { + parse->maxLength = parse->length; + printf("maxLength: %d bytes\r\n", parse->maxLength); + } + + //Validate the checksum + badChecksum = ((parse->buffer[parse->length - 2] != parse->ck_a) + || (parse->buffer[parse->length - 1] != parse->ck_b)); + if (badChecksum) + { + ubx_checksum_errors += 1; + dumpBuffer(parse->buffer, parse->length); + printf (" %s U-Blox %d.%d, %2d bytes, bad checksum, expecting 0x%02x%02x, computed: 0x%02x%02x\r\n", + parse->parserName, + parse->message >> 8, + parse->message & 0xff, + parse->length, + parse->buffer[parse->nmeaLength-2], + parse->buffer[parse->nmeaLength-1], + parse->ck_a, + parse->ck_b); + } + + //Process this message + parse->state = waitForPreamble; + parse->eomCallback(parse, SENTENCE_TYPE_UBX); + + //Search for the next preamble byte + parse->length = 0; + parse->crc = 0; + parse->ck_a = 0; + parse->ck_b = 0; + return SENTENCE_TYPE_NONE; +} + +//Read the CK_A byte +uint8_t ubloxCkA(PARSE_STATE * parse, uint8_t data) +{ + parse->state = ubloxCkB; + return SENTENCE_TYPE_UBX; +} + +//Read the payload +uint8_t ubloxPayload(PARSE_STATE * parse, uint8_t data) +{ + //Compute the checksum over the payload + if (parse->bytesRemaining--) + { + //Calculate the checksum + parse->ck_a += data; + parse->ck_b += parse->ck_a; + return SENTENCE_TYPE_UBX; + } + return ubloxCkA(parse, data); +} + +//Read the second length byte +uint8_t ubloxLength2(PARSE_STATE * parse, uint8_t data) +{ + //Calculate the checksum + parse->ck_a += data; + parse->ck_b += parse->ck_a; + + //Save the second length byte + parse->bytesRemaining |= ((uint16_t)data) << 8; + parse->state = ubloxPayload; + return SENTENCE_TYPE_UBX; +} + +//Read the first length byte +uint8_t ubloxLength1(PARSE_STATE * parse, uint8_t data) +{ + //Calculate the checksum + parse->ck_a += data; + parse->ck_b += parse->ck_a; + + //Save the first length byte + parse->bytesRemaining = data; + parse->state = ubloxLength2; + return SENTENCE_TYPE_UBX; +} + +//Read the ID byte +uint8_t ubloxId(PARSE_STATE * parse, uint8_t data) +{ + //Calculate the checksum + parse->ck_a += data; + parse->ck_b += parse->ck_a; + + //Save the ID as the lower 8-bits of the message + parse->message |= data; + parse->state = ubloxLength1; + return SENTENCE_TYPE_UBX; +} + +//Read the class byte +uint8_t ubloxClass(PARSE_STATE * parse, uint8_t data) +{ + //Start the checksum calculation + parse->ck_a = data; + parse->ck_b = data; + + //Save the class as the upper 8-bits of the message + parse->message = ((uint16_t)data) << 8; + parse->state = ubloxId; + return SENTENCE_TYPE_UBX; +} + +//Read the second sync byte +uint8_t ubloxSync2(PARSE_STATE * parse, uint8_t data) +{ + //Verify the sync 2 byte + if (data != 0x62) + { + //Display the invalid data + dumpBuffer(parse->buffer, parse->length - 1); + printf (" %s Invalid UBX data, %d bytes\r\n", parse->parserName, parse->length - 1); + + //Invalid sync 2 byte, place this byte at the beginning of the buffer + parse->length = 0; + parse->buffer[parse->length++] = data; + + //Start searching for a preamble byte + return waitForPreamble(parse, data); + } + + parse->state = ubloxClass; + return SENTENCE_TYPE_UBX; +} + +//Wait for the preamble byte (0xd3) +uint8_t waitForPreamble(PARSE_STATE * parse, uint8_t data) +{ + //Verify that this is the preamble byte + offset = file_offset; + switch(data) + { + case '$': + + // + // NMEA Message + // + // +----------+---------+--------+---------+----------+----------+ + // | Preamble | Name | Comma | Data | Asterisk | Checksum | + // | 8 bits | n bytes | 8 bits | n bytes | 8 bits | 2 bytes | + // | $ | | , | | | | + // +----------+---------+--------+---------+----------+----------+ + // | | + // |<------------------- Checksum ------------------->| + // + + parse->crc = 0; + parse->computeCrc = false; + parse->nmeaMessageNameLength = 0; + parse->state = nmeaFindFirstComma; + return SENTENCE_TYPE_NMEA; + + case 0xb5: + + // + // U-BLOX Message + // + // |<-- Preamble --->| + // | | + // +--------+--------+---------+--------+---------+---------+--------+--------+ + // | SYNC | SYNC | Class | ID | Length | Payload | CK_A | CK_B | + // | 8 bits | 8 bits | 8 bits | 8 bits | 2 bytes | n bytes | 8 bits | 8 bits | + // | 0xb5 | 0x62 | | | | | | | + // +--------+--------+---------+--------+---------+---------+--------+--------+ + // | | + // |<------------- Checksum ------------->| + // + // 8-Bit Fletcher Algorithm, which is used in the TCP standard (RFC 1145) + // http://www.ietf.org/rfc/rfc1145.txt + // Checksum calculation + // Initialization: CK_A = CK_B = 0 + // CK_A += data + // CK_B += CK_A + // + + parse->state = ubloxSync2; + return SENTENCE_TYPE_UBX; + + case 0xd3: + + // + // RTCM Standard 10403.2 - Chapter 4, Transport Layer + // + // |<------------- 3 bytes ------------>|<----- length ----->|<- 3 bytes ->| + // | | | | + // +----------+--------+----------------+---------+----------+-------------+ + // | Preamble | Fill | Message Length | Message | Fill | CRC-24Q | + // | 8 bits | 6 bits | 10 bits | n-bits | 0-7 bits | 24 bits | + // | 0xd3 | 000000 | (in bytes) | | zeros | | + // +----------+--------+----------------+---------+----------+-------------+ + // | | + // |<-------------------------------- CRC -------------------------------->| + // + + //Start the CRC with this byte + parse->crc = 0; + parse->crc = COMPUTE_CRC24Q(parse, data); + parse->computeCrc = true; + + //Get the message length + parse->state = rtcmReadLength1; + return SENTENCE_TYPE_RTCM; + } + + //preamble byte not found + dumpBuffer(parse->buffer, parse->length); + printf (" %s invalid byte 0x%02x\r\n", parse->parserName, data); + parse->length = 0; + parse->state = waitForPreamble; + return SENTENCE_TYPE_NONE; +} + +int +main ( + int argc, + char ** argv + ) +{ + int bit; + unsigned char * data; + unsigned char * data_end; + int file; + char * filename; + off_t file_size; + int index; + int length; + int message_number; + int message_type; + static PARSE_STATE parse; + int total; + uint8_t value; + + // Initialize the parser + parse.state = waitForPreamble; + parse.eomCallback = processMessage; + parse.parserName = "Tx"; + + // Open the log file + filename = argv[1]; + file = open (filename, O_RDONLY); + if (file < 0) { + perror ("ERROR - Failed to open the file"); + return -1; + } + + // Determine the file length + file_size = lseek (file, 0, SEEK_END); + + // Get the file buffer + file_data = malloc (file_size); + if (!file_data) { + fprintf (stderr, "ERROR - Failed to allocate file buffer!\n"); + return -2; + } + + // Read the file into memory + lseek (file, 0, SEEK_SET); + if (read (file, file_data, file_size) != file_size) { + fprintf (stderr, "ERROR - Failed to read the file into memory!\n"); + } + + // Close the file + close (file); + + // Skip the first byte to force unaligned start + data = file_data; + data_end = &data[file_size]; + while (data < data_end) { + file_offset = data - file_data; + + //Save the data byte + value = *data; + parse.buffer[parse.length++] = value; + + //Compute the CRC value for the message + if (parse.computeCrc) + parse.crc = COMPUTE_CRC24Q(&parse, value); + + //Parse this message + parse.state(&parse, value); + data++; + } + + // Display the checksum and CRC errors + if (nmea_checksum_errors) + printf (" Total NMEA checksum errors: %d\n", nmea_checksum_errors); + if (rtcm_crc_errors) + printf (" Total RTCM message CRC errors: %d\n", rtcm_crc_errors); + if (ubx_checksum_errors) + printf (" Total UBX message checksum errors: %d\n", ubx_checksum_errors); + + // Display the NMEA message list + if (DISPLAY_NMEA_MESSAGES) { + printf ("NMEA Message List:\n"); + NMEA_MESSAGE * message = nmea_list; + while (message) { + printf (" %s: %d %s, max length: %d bytes\n", message->message, message->count, + (message->count == 1) ? "time" : "times", message->max_length); + message = message->next; + } + } + + // Display the RTCM message type list + if (DISPLAY_RTCM_MESSAGE_LIST) { + printf ("RTCM Message List:\n"); + for (index = 0; index < (int)(sizeof(rtcm_messages) / sizeof(rtcm_messages[0])); index++) { + if (rtcm_messages[index]) + for (bit = 0; bit < 32; bit++) { + message_number = (index << 5) | bit; + if (rtcm_messages[index] & (1 << bit)) + printf (" %d (%02x %xx): %d %s, max length: %d bytes\n", message_number, + message_number >> 4, message_number & 0xf, + rtcm_message_count[message_number], + (rtcm_message_count[message_number] == 1) ? "time" : "times", + rtcm_max_message_length[message_number]); + } + } + } + + // Display the UBX message type list + if (DISPLAY_UBX_MESSAGE_LIST) { + printf ("UBX Message List:\n"); + for (index = 0; index < (int)(sizeof(ubx_messages) / sizeof(ubx_messages[0])); index++) { + if (ubx_messages[index]) + for (bit = 0; bit < 32; bit++) { + message_number = (index << 5) | bit; + if (ubx_messages[index] & (1 << bit)) + printf (" %d.%d (0x%02x.%02x): %d %s, max length: %d bytes\n", + message_number >> 8, message_number & 0xff, + message_number >> 8, message_number & 0xff, + ubx_message_count[message_number], + (ubx_message_count[message_number] == 1) ? "time" : "times", + ubx_max_message_length[message_number]); + } + } + } + + // Display the bad characters + if (DISPLAY_BAD_CHARACTERS) { + printf ("Bad characters:\n"); + total = 0; + for (index = 0; index < 256; index++) { + if (bad_characters[index >> 5] & (1 << (index & 0x1f))) { + printf (" 0x%02x: %d\n", index, bad_character_count[index]); + total += bad_character_count[index]; + } + } + printf (" Total: %d\n", total); + } + + // Display the bad character offsets + if (DISPLAY_BAD_CHARACTER_OFFSETS) { + printf ("Bad character offsets:\n"); + total = 0; + for (index = 0; index <= bad_character_offset_count; index++) { + printf (" 0x%08x: %d bytes\n", bad_character_offset[index], bad_character_length[index]); + total += bad_character_length[index]; + } + printf (" Total: %d\n", total); + } +} diff --git a/C/crc24q.c b/C/crc24q.c new file mode 100644 index 000000000..c50cb87ba --- /dev/null +++ b/C/crc24q.c @@ -0,0 +1,185 @@ +/* + * This is an implementation of the CRC-24Q cyclic redundancy checksum + * used by Qualcomm, RTCM104V3, and PGP 6.5.1. According to the RTCM104V3 + * standard, it uses the error polynomial + * + * x^24+ x^23+ x^18+ x^17+ x^14+ x^11+ x^10+ x^7+ x^6+ x^5+ x^4+ x^3+ x+1 + * + * This corresponds to a mask of 0x1864CFB. For a primer on CRC theory, + * including detailed discussion of how and why the error polynomial is + * expressed by this mask, see . + * + * 1) It detects all single bit errors per 24-bit code word. + * 2) It detects all double bit error combinations in a code word. + * 3) It detects any odd number of errors. + * 4) It detects any burst error for which the length of the burst is less than + * or equal to 24 bits. + * 5) It detects most large error bursts with length greater than 24 bits; + * the odds of a false positive are at most 2^-23. + * + * This hash should not be considered cryptographically secure, but it + * is extremely good at detecting noise errors. + * + * Note that this version has a seed of 0 wired in. The RTCM104V3 standard + * requires this. + * + * This file is Copyright 2008 by the GPSD project + * SPDX-License-Identifier: BSD-2-clause + */ + +//This file is originally from: https://gitlab.com/gpsd/gpsd/-/blob/master/gpsd/crc24q.c + +//#include "../include/gpsd_config.h" /* must be before all includes */ + +#include +#include +#include + +//#include "../include/crc24q.h" + +#ifdef REBUILD_CRC_TABLE +/* + * The crc24q code table below can be regenerated with the following code: + */ +#include +#include + +#define CRCSEED 0 /* could be NZ to detect leading zeros */ +#define CRCPOLY 0x1864CFBu /* encodes all info about the polynomial */ + +static void crc_init(unsigned int table[256]) +{ + unsigned i, j; + unsigned h; + + table[0] = CRCSEED; + table[1] = h = CRCPOLY; + + for (i = 2; i < 256; i *= 2) { + if ((h <<= 1) & 0x1000000) + h ^= CRCPOLY; + for (j = 0; j < i; j++) + table[i + j] = table[j] ^ h; + } +} + +int main(int argc, char *argv[]) +{ + int i; + + crc_init(table); + + for (i = 0; i < 256; i++) { + printf("0x%08X, ", table[i]); + if ((i % 4) == 3) + putchar('\n'); + } + + exit(EXIT_SUCCESS); +} +#endif + +static const int unsigned crc24q[256] = { + 0x00000000u, 0x01864CFBu, 0x028AD50Du, 0x030C99F6u, + 0x0493E6E1u, 0x0515AA1Au, 0x061933ECu, 0x079F7F17u, + 0x08A18139u, 0x0927CDC2u, 0x0A2B5434u, 0x0BAD18CFu, + 0x0C3267D8u, 0x0DB42B23u, 0x0EB8B2D5u, 0x0F3EFE2Eu, + 0x10C54E89u, 0x11430272u, 0x124F9B84u, 0x13C9D77Fu, + 0x1456A868u, 0x15D0E493u, 0x16DC7D65u, 0x175A319Eu, + 0x1864CFB0u, 0x19E2834Bu, 0x1AEE1ABDu, 0x1B685646u, + 0x1CF72951u, 0x1D7165AAu, 0x1E7DFC5Cu, 0x1FFBB0A7u, + 0x200CD1E9u, 0x218A9D12u, 0x228604E4u, 0x2300481Fu, + 0x249F3708u, 0x25197BF3u, 0x2615E205u, 0x2793AEFEu, + 0x28AD50D0u, 0x292B1C2Bu, 0x2A2785DDu, 0x2BA1C926u, + 0x2C3EB631u, 0x2DB8FACAu, 0x2EB4633Cu, 0x2F322FC7u, + 0x30C99F60u, 0x314FD39Bu, 0x32434A6Du, 0x33C50696u, + 0x345A7981u, 0x35DC357Au, 0x36D0AC8Cu, 0x3756E077u, + 0x38681E59u, 0x39EE52A2u, 0x3AE2CB54u, 0x3B6487AFu, + 0x3CFBF8B8u, 0x3D7DB443u, 0x3E712DB5u, 0x3FF7614Eu, + 0x4019A3D2u, 0x419FEF29u, 0x429376DFu, 0x43153A24u, + 0x448A4533u, 0x450C09C8u, 0x4600903Eu, 0x4786DCC5u, + 0x48B822EBu, 0x493E6E10u, 0x4A32F7E6u, 0x4BB4BB1Du, + 0x4C2BC40Au, 0x4DAD88F1u, 0x4EA11107u, 0x4F275DFCu, + 0x50DCED5Bu, 0x515AA1A0u, 0x52563856u, 0x53D074ADu, + 0x544F0BBAu, 0x55C94741u, 0x56C5DEB7u, 0x5743924Cu, + 0x587D6C62u, 0x59FB2099u, 0x5AF7B96Fu, 0x5B71F594u, + 0x5CEE8A83u, 0x5D68C678u, 0x5E645F8Eu, 0x5FE21375u, + 0x6015723Bu, 0x61933EC0u, 0x629FA736u, 0x6319EBCDu, + 0x648694DAu, 0x6500D821u, 0x660C41D7u, 0x678A0D2Cu, + 0x68B4F302u, 0x6932BFF9u, 0x6A3E260Fu, 0x6BB86AF4u, + 0x6C2715E3u, 0x6DA15918u, 0x6EADC0EEu, 0x6F2B8C15u, + 0x70D03CB2u, 0x71567049u, 0x725AE9BFu, 0x73DCA544u, + 0x7443DA53u, 0x75C596A8u, 0x76C90F5Eu, 0x774F43A5u, + 0x7871BD8Bu, 0x79F7F170u, 0x7AFB6886u, 0x7B7D247Du, + 0x7CE25B6Au, 0x7D641791u, 0x7E688E67u, 0x7FEEC29Cu, + 0x803347A4u, 0x81B50B5Fu, 0x82B992A9u, 0x833FDE52u, + 0x84A0A145u, 0x8526EDBEu, 0x862A7448u, 0x87AC38B3u, + 0x8892C69Du, 0x89148A66u, 0x8A181390u, 0x8B9E5F6Bu, + 0x8C01207Cu, 0x8D876C87u, 0x8E8BF571u, 0x8F0DB98Au, + 0x90F6092Du, 0x917045D6u, 0x927CDC20u, 0x93FA90DBu, + 0x9465EFCCu, 0x95E3A337u, 0x96EF3AC1u, 0x9769763Au, + 0x98578814u, 0x99D1C4EFu, 0x9ADD5D19u, 0x9B5B11E2u, + 0x9CC46EF5u, 0x9D42220Eu, 0x9E4EBBF8u, 0x9FC8F703u, + 0xA03F964Du, 0xA1B9DAB6u, 0xA2B54340u, 0xA3330FBBu, + 0xA4AC70ACu, 0xA52A3C57u, 0xA626A5A1u, 0xA7A0E95Au, + 0xA89E1774u, 0xA9185B8Fu, 0xAA14C279u, 0xAB928E82u, + 0xAC0DF195u, 0xAD8BBD6Eu, 0xAE872498u, 0xAF016863u, + 0xB0FAD8C4u, 0xB17C943Fu, 0xB2700DC9u, 0xB3F64132u, + 0xB4693E25u, 0xB5EF72DEu, 0xB6E3EB28u, 0xB765A7D3u, + 0xB85B59FDu, 0xB9DD1506u, 0xBAD18CF0u, 0xBB57C00Bu, + 0xBCC8BF1Cu, 0xBD4EF3E7u, 0xBE426A11u, 0xBFC426EAu, + 0xC02AE476u, 0xC1ACA88Du, 0xC2A0317Bu, 0xC3267D80u, + 0xC4B90297u, 0xC53F4E6Cu, 0xC633D79Au, 0xC7B59B61u, + 0xC88B654Fu, 0xC90D29B4u, 0xCA01B042u, 0xCB87FCB9u, + 0xCC1883AEu, 0xCD9ECF55u, 0xCE9256A3u, 0xCF141A58u, + 0xD0EFAAFFu, 0xD169E604u, 0xD2657FF2u, 0xD3E33309u, + 0xD47C4C1Eu, 0xD5FA00E5u, 0xD6F69913u, 0xD770D5E8u, + 0xD84E2BC6u, 0xD9C8673Du, 0xDAC4FECBu, 0xDB42B230u, + 0xDCDDCD27u, 0xDD5B81DCu, 0xDE57182Au, 0xDFD154D1u, + 0xE026359Fu, 0xE1A07964u, 0xE2ACE092u, 0xE32AAC69u, + 0xE4B5D37Eu, 0xE5339F85u, 0xE63F0673u, 0xE7B94A88u, + 0xE887B4A6u, 0xE901F85Du, 0xEA0D61ABu, 0xEB8B2D50u, + 0xEC145247u, 0xED921EBCu, 0xEE9E874Au, 0xEF18CBB1u, + 0xF0E37B16u, 0xF16537EDu, 0xF269AE1Bu, 0xF3EFE2E0u, + 0xF4709DF7u, 0xF5F6D10Cu, 0xF6FA48FAu, 0xF77C0401u, + 0xF842FA2Fu, 0xF9C4B6D4u, 0xFAC82F22u, 0xFB4E63D9u, + 0xFCD11CCEu, 0xFD575035u, 0xFE5BC9C3u, 0xFFDD8538u, +}; + +unsigned crc24q_hash(unsigned char *data, int len) +{ + int i; + unsigned crc = 0; + + for (i = 0; i < len; i++) { + crc = (crc << 8) ^ crc24q[data[i] ^ (unsigned char)(crc >> 16)]; + } + + crc = (crc & 0x00ffffff); + + return crc; +} + +#define LO(x) (unsigned char)((x) & 0xff) +#define MID(x) (unsigned char)(((x) >> 8) & 0xff) +#define HI(x) (unsigned char)(((x) >> 16) & 0xff) + +#ifdef __UNUSED__ +void crc24q_sign(unsigned char *data, int len) +{ + unsigned crc = crc24q_hash(data, len); + + data[len] = HI(crc); + data[len + 1] = MID(crc); + data[len + 2] = LO(crc); +} +#endif /* __UNUSED__ */ + +bool crc24q_check(unsigned char *data, int len) +{ + unsigned crc = crc24q_hash(data, len - 3); + + return (((data[len - 3] == HI(crc)) && + (data[len - 2] == MID(crc)) && (data[len - 1] == LO(crc)))); +} +// vim: set expandtab shiftwidth=4 diff --git a/C/crc24q.h b/C/crc24q.h new file mode 100644 index 000000000..66972e602 --- /dev/null +++ b/C/crc24q.h @@ -0,0 +1,20 @@ +/* Interface for CRC-24Q cyclic redundancy chercksum code + * + * This file is Copyright 2010 by the GPSD project + * SPDX-License-Identifier: BSD-2-clause + */ + +//This file is originally from: https://gitlab.com/gpsd/gpsd/-/blob/master/include/crc24q.h + +#include + +#ifndef _CRC24Q_H_ +#define _CRC24Q_H_ + +extern void crc24q_sign(unsigned char *data, int len); + +extern bool crc24q_check(unsigned char *data, int len); + +extern unsigned crc24q_hash(unsigned char *data, int len); +#endif /* _CRC24Q_H_ */ +// vim: set expandtab shiftwidth=4 diff --git a/C/makefile b/C/makefile new file mode 100644 index 000000000..0f457571e --- /dev/null +++ b/C/makefile @@ -0,0 +1,46 @@ +###################################################################### +# makefile +# +# Builds the RTK support programs +###################################################################### + +########## +# Source files +########## + +EXECUTABLES = Compare +EXECUTABLES += NMEA_Client +EXECUTABLES += Split_Messages + +INCLUDES = crc24q.h + +########## +# Buid tools and rules +########## + +GCC = gcc +CFLAGS = -flto -O3 -Wpedantic -pedantic-errors -Wall -Wextra -Werror -Wno-unused-variable -Wno-unused-parameter +CC = $(GCC) $(CFLAGS) + +%.o: %.c $(INCLUDES) + $(CC) -c -o $@ $< + +%: %.c $(INCLUDES) + $(CC) $(CFLAGS) -o $@ $< + +########## +# Buid all the sources - must be first +########## + +.PHONY: all + +all: $(EXECUTABLES) + +######## +# Clean the build directory +########## + +.PHONY: clean + +clean: + rm -f *.o *.a $(EXECUTABLES) From 1176224bde0e2c14bc6bcab046cf82259922021c Mon Sep 17 00:00:00 2001 From: Lee Leahy Date: Wed, 24 Aug 2022 15:56:34 -1000 Subject: [PATCH 120/134] Add makefile and the Fonts support program Fonts: Program to draw text diagrams of each character in the font file. Example: ./Fonts Arduino/libraries/SparkFun_Qwiic_OLED_Graphics_Library/src/res/_fnt_5x7.h Icons: Program to draw text diagrams of each icon in the icon file. Example: ./Icons Firmware/RTK_Surveyor/icons.h makefile: Build script to build the Fonts and Icons programs. --- Graphics/C/Fonts.c | 349 ++++++++++++++++++++++++++++++++++++++++++++ Graphics/C/Icons.c | 8 +- Graphics/C/makefile | 43 ++++++ 3 files changed, 396 insertions(+), 4 deletions(-) create mode 100644 Graphics/C/Fonts.c create mode 100644 Graphics/C/makefile diff --git a/Graphics/C/Fonts.c b/Graphics/C/Fonts.c new file mode 100644 index 000000000..eb85dc961 --- /dev/null +++ b/Graphics/C/Fonts.c @@ -0,0 +1,349 @@ +#include +#include +#include +#include +#include +#include + +#define DRAW_OUTLINE 1 + +typedef struct _CHARACTER_ENTRY { + struct _CHARACTER_ENTRY * next; + int character; + uint8_t data[]; +} CHARACTER_ENTRY; + +int bytes_high; +CHARACTER_ENTRY * character_list; +int data_bytes; +char * font_text; +uint8_t * font_data; +int height; +int map_width; +int nchar; +int start; +int width; + +int +read_value ( + const char * string, + const char * text_end + ) +{ + const char * text; + int length; + int value; + + // Find the map width + text = font_text; + length = strlen(string); + while (text < text_end) { + if (strncmp (text, string, length) == 0) { + text += length; + break; + } + text++; + } + + // Skip over the white space + while (text < text_end) { + if ((*text != ' ') && (*text != '\t')) + break; + text++; + } + + // Get the map width + if (sscanf (text, "%d", &value) != 1) { + fprintf (stderr, "ERROR - Invalid map width!\n"); + return -1; + } + return value; +} + +const char * +find_next_character ( + const char * text, + const char * text_end + ) +{ + // Walk through the font file + while (text < (text_end - 2)) { + // Determine if this is an icon name + if ((text[0] == '0') && ((text[1] == 'x') || (text[1] == 'X'))) + return text; + text++; + } + + // No more data + return NULL; +} + +int +read_data ( + const char * text_end + ) +{ + int character_count; + const char * text; + int data_offset; + int index; + unsigned int value; + + // Read the data array + character_count = 0; + text = font_text; + while (text < text_end) { + for (index = 0; index < data_bytes; index++) { + + // Find the next data value + text = find_next_character (text, text_end); + if ((text == NULL) && (index == 0)) + return character_count; + else if (text == NULL) { + fprintf (stderr, "ERROR - Missing data!\n"); + return 0; + } + + // Get the value + if (sscanf (text, "0x%02x", &value) != 1) { + fprintf (stderr, "ERROR - Invalid data value!\n"); + return 0; + } + text += 4; + + // Save the data value + data_offset = (data_bytes * character_count) + index; + font_data[data_offset] = value; + } + character_count++; + } + return 0; +} + +void +add_entry ( + CHARACTER_ENTRY * new_entry + ) +{ + CHARACTER_ENTRY * previous_entry; + + // Walk to the end of the list + previous_entry = character_list; + while (previous_entry && previous_entry->next) + previous_entry = previous_entry->next; + + // Add this entry to the list + new_entry->next = NULL; + if (previous_entry) + previous_entry->next = new_entry; + else + character_list = new_entry; +} + +int +process_data ( + int character_count + ) +{ + int font_index; + int index; + int map_characters; + int map_offset; + int next_character; + CHARACTER_ENTRY * new_entry; + ssize_t offset; + unsigned int value; + int x; + int y; + + next_character = start; + map_characters = map_width / width; + while ((next_character - start) < character_count) { + // Allocate the data structure + new_entry = malloc (sizeof(*new_entry) + data_bytes); + + if (!new_entry) { + fprintf (stderr, "ERROR - Failed to allocate next_entry!\n"); + return -1; + } + new_entry->character = next_character++; + map_offset = new_entry->character - start; + map_offset = ((map_offset / map_characters) * map_characters * data_bytes) + + ((map_offset % map_characters) * width); + for (y = 0; y < bytes_high; y++) { + for (x = 0; x < width; x++) { + + // Save the data value + font_index = map_offset + (y * map_width) + x; + value = font_data[font_index]; + index = (y * width) + x; + new_entry->data[index] = value; + } + } + + // Add the entry to the list + add_entry (new_entry); + } + return 0; +} + +void +display_character ( + CHARACTER_ENTRY * character + ) +{ + int bit; + const char * indent = " "; + int x; + int y; + + printf ("/*\n"); + printf (" 0x%02x, %d [%d, %d]\n", character->character, character->character, width, height); + printf ("\n"); +#ifdef DRAW_OUTLINE + printf ("%s.", indent); + for (x = 0; x < width; x++) + printf ("-"); + printf (".\n"); +#endif // DRAW_OUTLINE + for (y = 0; y < height; y++) { + printf ("%s", indent); +#ifdef DRAW_OUTLINE + printf ("|"); +#endif // DRAW_OUTLINE + for (x = 0; x < width; x++) { + bit = character->data[((y >> 3) * width) + x]; + bit >>= y & 7; + printf ("%c", (bit & 1) ? '*' : ' '); + } +#ifdef DRAW_OUTLINE + printf ("|"); +#endif // DRAW_OUTLINE + printf ("\n"); + } +#ifdef DRAW_OUTLINE + printf ("%s'", indent); + for (x = 0; x < width; x++) + printf ("-"); + printf ("'\n"); +#endif // DRAW_OUTLINE + printf ("*/\n"); + printf ("\n"); +} + +int +main ( + int argc, + char ** argv + ) +{ + CHARACTER_ENTRY * character; + int character_count; + const char * text_end; + char * filename; + int font_file; + off_t file_length; + int status; + ssize_t valid_data; + + do { + // Assume failure + font_file = -1; + status = -1; + + // Verify the argument count + if (argc != 2) { + fprintf (stderr, "%s font_fliename\n", argv[0]); + break; + } + + // Get the font file name + filename = argv[1]; + + // Open the font file + font_file = open (filename, O_RDONLY); + if (font_file < 0) { + perror("ERROR - File open failed!"); + break; + } + + // Determine the length of the file + file_length = lseek (font_file, 0, SEEK_END); + + // Go the the beginning of the file + lseek (font_file, 0, SEEK_SET); + + // Allocate the text buffer + font_text = malloc (file_length); + if (!font_text) { + fprintf (stderr, "ERROR - Failed to allocate font text buffer!\n"); + break; + } + + // Fill the text buffer + valid_data = read (font_file, font_text, file_length); + if (valid_data < 0) { + fprintf (stderr, "ERROR - File read failed!\n"); + break; + } + text_end = &font_text[valid_data]; + + // Find the font values + width = read_value ("WIDTH", text_end); + if (width < 0) { + fprintf (stderr, "ERROR - Failed to read font width!\n"); + } + height = read_value ("HEIGHT", text_end); + if (height < 0) { + fprintf (stderr, "ERROR - Failed to read font height!\n"); + break; + } + start = read_value ("START", text_end); + if (start < 0) { + fprintf (stderr, "ERROR - Failed to read font start!\n"); + break; + } + nchar = read_value ("NCHAR", text_end); + if (nchar < 0) { + fprintf (stderr, "ERROR - Failed to read font nchar!\n"); + break; + } + map_width = read_value ("MAP_WIDTH", text_end); + if (map_width < 0) { + fprintf (stderr, "ERROR - Failed to read map width!\n"); + break; + } + bytes_high = (height + 7) / 8; + data_bytes = width * bytes_high; + + // Allocate the data buffer + font_data = malloc (sizeof(*font_data) * 256 * data_bytes); + if (!font_data) { + fprintf (stderr, "ERROR - Failed to allocate font data buffer!\n"); + break; + } + + // Fill the data buffer + character_count = read_data (text_end); + + // Process the data + if (process_data(character_count)) + break; + + // Display the characters in the font file + character = character_list; + while (character) { + display_character (character); + character = character->next; + } + + // Indicate success + status = 0; + } while (0); + + // Close the file + if (font_file >= 0) + close(font_file); + + return status; +} diff --git a/Graphics/C/Icons.c b/Graphics/C/Icons.c index d053adee8..b34ca7dcc 100644 --- a/Graphics/C/Icons.c +++ b/Graphics/C/Icons.c @@ -47,7 +47,7 @@ terminate_end_of_line ( text++; // Skip over the end of line - while ((text < text_end) && (*text == '\r') || (*text == '\n')) + while ((text < text_end) && ((*text == '\r') || (*text == '\n'))) *text++ = 0; // Return the start of the next line @@ -151,7 +151,7 @@ read_icon_data ( ICON_ENTRY * icon_entry; int index; char * number; - int value; + unsigned int value; int x; int y; @@ -410,8 +410,8 @@ display_icon ( } for (y = 0; y < icon->height; y++) { printf ("%s", indent); - if (DRAW_OUTLINE) - printf ("0x%02x|", 1 << (y & 7)); + if (DRAW_OUTLINE) + printf ("0x%02x|", 1 << (y & 7)); for (x = 0; x < icon->width; x++) { bit = icon->data[((y >> 3) * icon->bytes_wide) + x]; bit >>= y & 7; diff --git a/Graphics/C/makefile b/Graphics/C/makefile new file mode 100644 index 000000000..8ce498b47 --- /dev/null +++ b/Graphics/C/makefile @@ -0,0 +1,43 @@ +###################################################################### +# makefile +# +# Builds the RTK support programs +###################################################################### + +########## +# Source files +########## + +EXECUTABLES = Fonts +EXECUTABLES += Icons + +########## +# Buid tools and rules +########## + +GCC = gcc +CFLAGS = -flto -O3 -Wpedantic -pedantic-errors -Wall -Wextra -Werror -Wno-unused-variable -Wno-unused-parameter +CC = $(GCC) $(CFLAGS) + +%.o: %.c $(INCLUDES) + $(CC) -c -o $@ $< + +%: %.c $(INCLUDES) + $(CC) $(CFLAGS) -o $@ $< + +########## +# Buid all the sources - must be first +########## + +.PHONY: all + +all: $(EXECUTABLES) + +######## +# Clean the build directory +########## + +.PHONY: clean + +clean: + rm -f *.o *.a $(EXECUTABLES) From 668fbccaf2fc10b327ae16c631119ecca90f2174 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 25 Aug 2022 10:27:33 -0600 Subject: [PATCH 121/134] Fix PR #295 BT MAC overrun Reduce MAC printing from four characters to two characters --- Firmware/RTK_Surveyor/Display.ino | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index f875f6332..7ab2b15d4 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -362,7 +362,7 @@ void updateDisplay() const uint8_t * rtkMacAddress = getMacAddress(); //Print only last two digits of MAC - sprintf(macAddress, "%02X%02X", rtkMacAddress[4], rtkMacAddress[5]); + sprintf(macAddress, "%02X", rtkMacAddress[5]); oled.setFont(QW_FONT_5X7); //Set font to smallest oled.setCursor(0, 3); oled.print(macAddress); @@ -406,7 +406,7 @@ void updateDisplay() const uint8_t * rtkMacAddress = getMacAddress(); //Print only last two digits of MAC - sprintf(macAddress, "%02X%02X", rtkMacAddress[4], rtkMacAddress[5]); + sprintf(macAddress, "%02X", rtkMacAddress[5]); oled.setFont(QW_FONT_5X7); //Set font to smallest oled.setCursor(14, 3); oled.print(macAddress); From fe60d9416c306c1439f825d39fc9f14062511660 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 25 Aug 2022 10:27:43 -0600 Subject: [PATCH 122/134] Change WiFi prints to log_d --- Firmware/RTK_Surveyor/WiFi.ino | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 056c0b806..b2e8ec439 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -254,7 +254,7 @@ void wifiStop() { wifiSetState(WIFI_OFF); WiFi.mode(WIFI_OFF); - Serial.println("WiFi Stopped"); + log_d("WiFi Stopped"); } //If ESP-Now is active, change protocol to only Long Range else if (espnowState > ESPNOW_OFF) @@ -266,13 +266,13 @@ void wifiStop() WiFi.mode(WIFI_STA); - Serial.println("WiFi disabled, ESP-Now left in place"); + log_d("WiFi disabled, ESP-Now left in place"); } #else //Turn off radio wifiSetState(WIFI_OFF); WiFi.mode(WIFI_OFF); - Serial.println("WiFi Stopped"); + log_d("WiFi Stopped"); #endif //Display the heap state From c2c8a8736ff12f185095082f7b02ed7b37a0440f Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 25 Aug 2022 11:27:15 -0600 Subject: [PATCH 123/134] Add compile guards to getMacAddress --- Firmware/RTK_Surveyor/Display.ino | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 7ab2b15d4..fcd4e6241 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -2544,13 +2544,17 @@ void paintEspNowPaired() displayMessage("ESP-Now Paired", 2000); } -const uint8_t * getMacAddress () +const uint8_t * getMacAddress() { static const uint8_t zero[6] = {0, 0, 0, 0, 0, 0}; +#ifdef COMPILE_BT if (bluetoothState != BT_OFF) return btMACAddress; +#ifdef COMPILE_WIFI else if (wifiState != WIFI_OFF) return wifiMACAddress; +#endif +#endif return zero; } From f769d56a7393d7e2ab5340699d7aa3d986fe4512 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 25 Aug 2022 11:27:48 -0600 Subject: [PATCH 124/134] Increase first reconnect timeout to 15s Emlid needs more time between port closures otherwise it complains mountpoint is already taken. --- Firmware/RTK_Surveyor/NtripServer.ino | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 278959f88..192c56817 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -309,7 +309,7 @@ void ntripServerStop(bool wifiClientAllocated) wifiStop(); ntripServerLastConnectionAttempt = millis(); //Mark the Server stop so that we don't immediately attempt re-connect to Caster - ntripServerConnectionAttemptTimeout = 5 * 1000L; //Wait 5s between stopping and the first re-connection attempt + ntripServerConnectionAttemptTimeout = 15 * 1000L; //Wait 15s between stopping and the first re-connection attempt. 5 is too short for Emlid. } //Determine the next NTRIP server state From 6b5eb47c31b4e98cbed25e99ef9b2c2c992724ea Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 25 Aug 2022 11:54:12 -0600 Subject: [PATCH 125/134] Fix four character BT printing --- Firmware/RTK_Surveyor/Display.ino | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index fcd4e6241..0b9716c53 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -361,8 +361,8 @@ void updateDisplay() char macAddress[5]; const uint8_t * rtkMacAddress = getMacAddress(); - //Print only last two digits of MAC - sprintf(macAddress, "%02X", rtkMacAddress[5]); + //Print four characters of MAC + sprintf(macAddress, "%02%02X", rtkMacAddress[4], rtkMacAddress[5]); oled.setFont(QW_FONT_5X7); //Set font to smallest oled.setCursor(0, 3); oled.print(macAddress); From 9e5b37da347a4dad3981dd102ef2d8577215f3e8 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Thu, 25 Aug 2022 11:54:43 -0600 Subject: [PATCH 126/134] Return PointPerfect cert arrays to global Until we can figure out why malloc is not working. --- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 6 ++++-- Firmware/RTK_Surveyor/menuPP.ino | 8 ++++---- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 3149f6585..97494787e 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -159,8 +159,10 @@ LoggingType loggingType = LOGGING_UNKNOWN; #endif -char *certificateContents; //Holds the contents of the keys prior to MQTT connection -char *keyContents; +//char *certificateContents; //Holds the contents of the keys prior to MQTT connection +//char *keyContents; +char certificateContents[2000]; //Holds the contents of the keys prior to MQTT connection +char keyContents[2000]; //=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-=-= //GNSS configuration diff --git a/Firmware/RTK_Surveyor/menuPP.ino b/Firmware/RTK_Surveyor/menuPP.ino index 53d0c0dab..276f8c4da 100644 --- a/Firmware/RTK_Surveyor/menuPP.ino +++ b/Firmware/RTK_Surveyor/menuPP.ino @@ -286,13 +286,13 @@ bool updatePointPerfectKeys() #define CONTENT_SIZE 2000 - certificateContents = (char*)malloc(CONTENT_SIZE); - memset(certificateContents, 0, CONTENT_SIZE); + //certificateContents = (char*)malloc(CONTENT_SIZE); + //memset(certificateContents, 0, CONTENT_SIZE); loadFile("certificate", certificateContents); secureClient.setCertificate(certificateContents); - keyContents = (char*)malloc(CONTENT_SIZE); - memset(keyContents, 0, CONTENT_SIZE); + //keyContents = (char*)malloc(CONTENT_SIZE); + //memset(keyContents, 0, CONTENT_SIZE); loadFile("privateKey", keyContents); secureClient.setPrivateKey(keyContents); From 7f8903c199e32c1311f9830e08e43ddaa9f73da2 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 26 Aug 2022 09:06:05 -0600 Subject: [PATCH 127/134] Fix MAC print typo --- Firmware/RTK_Surveyor/Display.ino | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/Display.ino b/Firmware/RTK_Surveyor/Display.ino index 0b9716c53..d47e13a22 100644 --- a/Firmware/RTK_Surveyor/Display.ino +++ b/Firmware/RTK_Surveyor/Display.ino @@ -362,7 +362,7 @@ void updateDisplay() const uint8_t * rtkMacAddress = getMacAddress(); //Print four characters of MAC - sprintf(macAddress, "%02%02X", rtkMacAddress[4], rtkMacAddress[5]); + sprintf(macAddress, "%02X%02X", rtkMacAddress[4], rtkMacAddress[5]); oled.setFont(QW_FONT_5X7); //Set font to smallest oled.setCursor(0, 3); oled.print(macAddress); From 082ec69965791da50cf3a205d4015630994274ad Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 26 Aug 2022 09:06:43 -0600 Subject: [PATCH 128/134] Remove free() when using static certificate arrays --- Firmware/RTK_Surveyor/menuPP.ino | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/Firmware/RTK_Surveyor/menuPP.ino b/Firmware/RTK_Surveyor/menuPP.ino index 276f8c4da..b19e1836d 100644 --- a/Firmware/RTK_Surveyor/menuPP.ino +++ b/Firmware/RTK_Surveyor/menuPP.ino @@ -322,8 +322,8 @@ bool updatePointPerfectKeys() if (tries++ == maxTries) { log_d("MQTT failed to connect"); - free(certificateContents); - free(keyContents); + //free(certificateContents); + //free(keyContents); return (false); } @@ -344,8 +344,8 @@ bool updatePointPerfectKeys() if (mqttClient.connected() == false) { log_d("Client disconnected"); - free(certificateContents); - free(keyContents); + //free(certificateContents); + //free(keyContents); return (false); } @@ -355,16 +355,16 @@ bool updatePointPerfectKeys() { Serial.println(); log_d("Channel failed to respond"); - free(certificateContents); - free(keyContents); + //free(certificateContents); + //free(keyContents); return (false); } } Serial.println(); Serial.println("Keys successfully updated"); - free(certificateContents); - free(keyContents); + //free(certificateContents); + //free(keyContents); return (true); #else return (false); From c6f9eb15af5e2f10a9a018285510f2e8a337f351 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 26 Aug 2022 09:07:11 -0600 Subject: [PATCH 129/134] Prevent PP key update if SSID is empty --- Firmware/RTK_Surveyor/menuPP.ino | 60 +++++++++++++++++++------------- 1 file changed, 36 insertions(+), 24 deletions(-) diff --git a/Firmware/RTK_Surveyor/menuPP.ino b/Firmware/RTK_Surveyor/menuPP.ino index b19e1836d..0f04dcfca 100644 --- a/Firmware/RTK_Surveyor/menuPP.ino +++ b/Firmware/RTK_Surveyor/menuPP.ino @@ -940,39 +940,51 @@ void menuPointPerfect() else if (incoming == '5') { #ifdef COMPILE_WIFI - wifiStart(settings.home_wifiSSID, settings.home_wifiPW); - - unsigned long startTime = millis(); - while (wifiGetStatus() != WL_CONNECTED) + if (strlen(settings.home_wifiSSID) == 0) { - delay(500); - Serial.print("."); - if (millis() - startTime > 8000) break; //Give up after 8 seconds + Serial.println("Error: Please enter SSID before getting keys"); } - - if (wifiGetStatus() == WL_CONNECTED) + else { + wifiStart(settings.home_wifiSSID, settings.home_wifiPW); - Serial.println(); - Serial.print("WiFi connected: "); - Serial.println(wifiGetIpAddress()); - - //Check if we have certificates - char fileName[80]; - sprintf(fileName, "/%s_%s_%d.txt", platformFilePrefix, "certificate", profileNumber); - if (LittleFS.exists(fileName) == false) + unsigned long startTime = millis(); + while (wifiGetStatus() != WL_CONNECTED) { - provisionDevice(); //Connect to ThingStream API and get keys + delay(500); + Serial.print("."); + if (millis() - startTime > 15000) + { + Serial.println("Error: No WiFi available"); + break; + } } - else if (strlen(settings.pointPerfectCurrentKey) == 0 || strlen(settings.pointPerfectLBandTopic) == 0) + + if (wifiGetStatus() == WL_CONNECTED) { - provisionDevice(); //Connect to ThingStream API and get keys - } - else - updatePointPerfectKeys(); + Serial.println(); + Serial.print("WiFi connected: "); + Serial.println(wifiGetIpAddress()); + + //Check if we have certificates + char fileName[80]; + sprintf(fileName, "/%s_%s_%d.txt", platformFilePrefix, "certificate", profileNumber); + if (LittleFS.exists(fileName) == false) + { + provisionDevice(); //Connect to ThingStream API and get keys + } + else if (strlen(settings.pointPerfectCurrentKey) == 0 || strlen(settings.pointPerfectLBandTopic) == 0) + { + provisionDevice(); //Connect to ThingStream API and get keys + } + else + updatePointPerfectKeys(); + + } + wifiStop(); - } + } //End strlen SSID check #endif } else if (incoming == '6') From f191b76c5cb20e31e16f594de7e648c4afa17071 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 26 Aug 2022 09:07:42 -0600 Subject: [PATCH 130/134] Move connection timeout countdowns to printfs --- Firmware/RTK_Surveyor/NtripServer.ino | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripServer.ino b/Firmware/RTK_Surveyor/NtripServer.ino index 192c56817..42ab6825b 100644 --- a/Firmware/RTK_Surveyor/NtripServer.ino +++ b/Firmware/RTK_Surveyor/NtripServer.ino @@ -73,6 +73,7 @@ static int ntripServerConnectionAttempts; //Throttle the time between connection attempts static int ntripServerConnectionAttemptTimeout = 0; static uint32_t ntripServerLastConnectionAttempt = 0; +static uint32_t ntripServerTimeoutPrint = 0; //Last time the NTRIP server state was displayed static uint32_t ntripServerStateLastDisplayed = 0; @@ -351,10 +352,10 @@ void ntripServerUpdate() } else { - if (millis() - startTime > 1000) + if (millis() - ntripServerTimeoutPrint > 1000) { - startTime = millis(); - log_d("NTRIP Server connection timeout wait: %d of %d \n\r", + ntripServerTimeoutPrint = millis(); + Serial.printf("NTRIP Server connection timeout wait: %d of %d seconds \n\r", (millis() - ntripServerLastConnectionAttempt) / 1000, ntripServerConnectionAttemptTimeout / 1000 ); @@ -479,7 +480,7 @@ void ntripServerUpdate() if (!ntripServer->connected()) { //Broken connection, retry the NTRIP server connection - Serial.println("NTRIP Server connection dropped"); + Serial.println("Connection to NTRIP Server was closed"); ntripServerStop(false); //Allocate new wifiClient } else if ((millis() - ntripServerTimer) > (3 * 1000)) From 72a55a00f611fbbbea1ecb26c4189eb6a91f075d Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Fri, 26 Aug 2022 09:10:54 -0600 Subject: [PATCH 131/134] Stop/start ESP-Now when starting WiFi Prevents AUTH_EXP errors --- Firmware/RTK_Surveyor/WiFi.ino | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index b2e8ec439..4383e0121 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -209,15 +209,23 @@ bool wifiConnectionTimeout() void wifiStart(char* ssid, char* pw) { #ifdef COMPILE_WIFI + bool restartESPNow = false; + if ((wifiState == WIFI_OFF) || (wifiState == WIFI_ON)) { wifiSetState(WIFI_NOTCONNECTED); #ifdef COMPILE_ESPNOW if (espnowState > ESPNOW_OFF) + { + restartESPNow = true; + espnowStop(); esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N | WIFI_PROTOCOL_LR); //Enable WiFi + ESP-Now. Stops WiFi Station. + } else + { esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Set basic WiFi protocols. Stops WiFi Station. + } #else //Be sure the standard protocols are turned on. ESP Now have have previously turned them off. esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Set basic WiFi protocols. Stops WiFi Station. @@ -229,6 +237,11 @@ void wifiStart(char* ssid, char* pw) WiFi.begin(ssid, pw); wifiTimer = millis(); +#ifdef COMPILE_ESPNOW + if (restartESPNow == true) + espnowStart(); +#endif + //Display the heap state reportHeapNow(); } From 31f1e8e898ac8c41e2580d1baf3dd1355e1772dc Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 27 Aug 2022 10:51:23 -0600 Subject: [PATCH 132/134] Increase NTRIP Client and WiFi connection timeouts Related to issue #285 --- Firmware/RTK_Surveyor/NtripClient.ino | 4 +--- Firmware/RTK_Surveyor/WiFi.ino | 6 +++--- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/Firmware/RTK_Surveyor/NtripClient.ino b/Firmware/RTK_Surveyor/NtripClient.ino index c488b6ae9..963a17356 100644 --- a/Firmware/RTK_Surveyor/NtripClient.ino +++ b/Firmware/RTK_Surveyor/NtripClient.ino @@ -47,7 +47,7 @@ static const int MAX_NTRIP_CLIENT_CONNECTION_ATTEMPTS = 3; static const uint32_t NTRIP_CLIENT_RESPONSE_TIMEOUT = 10 * 1000; //Milliseconds //NTRIP client receive data timeout -static const uint32_t NTRIP_CLIENT_RECEIVE_DATA_TIMEOUT = 10 * 1000; //Milliseconds +static const uint32_t NTRIP_CLIENT_RECEIVE_DATA_TIMEOUT = 30 * 1000; //Milliseconds //Most incoming data is around 500 bytes but may be larger static const int RTCM_DATA_SIZE = 512 * 4; @@ -317,8 +317,6 @@ void ntripClientUpdate() if (ntripClientConnectLimitReached()) //Display the WiFi failure paintNtripWiFiFail(4000, true); - - //TODO WiFi not available, give up, disable future attempts } } else diff --git a/Firmware/RTK_Surveyor/WiFi.ino b/Firmware/RTK_Surveyor/WiFi.ino index 4383e0121..961cdaaa9 100644 --- a/Firmware/RTK_Surveyor/WiFi.ino +++ b/Firmware/RTK_Surveyor/WiFi.ino @@ -45,7 +45,7 @@ //---------------------------------------- //If we cannot connect to local wifi, give up/go to Rover -static const int WIFI_CONNECTION_TIMEOUT = 8 * 1000; //Milliseconds +static const int WIFI_CONNECTION_TIMEOUT = 10 * 1000; //Milliseconds //Interval to use when displaying the IP address static const int WIFI_IP_ADDRESS_DISPLAY_INTERVAL = 12 * 1000; //Milliseconds @@ -215,6 +215,8 @@ void wifiStart(char* ssid, char* pw) { wifiSetState(WIFI_NOTCONNECTED); + WiFi.mode(WIFI_STA); + #ifdef COMPILE_ESPNOW if (espnowState > ESPNOW_OFF) { @@ -231,8 +233,6 @@ void wifiStart(char* ssid, char* pw) esp_wifi_set_protocol(WIFI_IF_STA, WIFI_PROTOCOL_11B | WIFI_PROTOCOL_11G | WIFI_PROTOCOL_11N); //Set basic WiFi protocols. Stops WiFi Station. #endif - WiFi.mode(WIFI_STA); - Serial.printf("WiFi connecting to %s\r\n", ssid); WiFi.begin(ssid, pw); wifiTimer = millis(); From 030e4c4eb82da5461a943db55839ee94c1dd34c8 Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 27 Aug 2022 11:04:49 -0600 Subject: [PATCH 133/134] Remove developer settings for release --- Firmware/RTK_Surveyor/RTK_Surveyor.ino | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/RTK_Surveyor/RTK_Surveyor.ino b/Firmware/RTK_Surveyor/RTK_Surveyor.ino index 97494787e..10f777de8 100644 --- a/Firmware/RTK_Surveyor/RTK_Surveyor.ino +++ b/Firmware/RTK_Surveyor/RTK_Surveyor.ino @@ -30,7 +30,7 @@ const int FIRMWARE_VERSION_MINOR = 4; #define COMPILE_ESPNOW //Requires WiFi. Comment out to remove ESP-Now functionality. #define COMPILE_BT //Comment out to remove Bluetooth functionality #define COMPILE_L_BAND //Comment out to remove L-Band functionality -#define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) +//#define ENABLE_DEVELOPER //Uncomment this line to enable special developer modes (don't check power button at startup) //Define the RTK board identifier: // This is an int which is unique to this variant of the RTK Surveyor hardware which allows us From 7f4533e36fa02ed61648673e0f7d73fa9c65eaae Mon Sep 17 00:00:00 2001 From: Nathan Seidle Date: Sat, 27 Aug 2022 11:24:35 -0600 Subject: [PATCH 134/134] Add v2.4 binary --- .../RTK_Surveyor_Firmware_v1_10.bin | Bin .../RTK_Surveyor_Firmware_v1_11.bin | Bin .../RTK_Surveyor_Firmware_v1_12.bin | Bin Binaries/RTK_Surveyor_Firmware_v2.4.bin | Bin 0 -> 2052352 bytes 4 files changed, 0 insertions(+), 0 deletions(-) rename Binaries/{ => PreviousVersions}/RTK_Surveyor_Firmware_v1_10.bin (100%) rename Binaries/{ => PreviousVersions}/RTK_Surveyor_Firmware_v1_11.bin (100%) rename Binaries/{ => PreviousVersions}/RTK_Surveyor_Firmware_v1_12.bin (100%) create mode 100644 Binaries/RTK_Surveyor_Firmware_v2.4.bin diff --git a/Binaries/RTK_Surveyor_Firmware_v1_10.bin b/Binaries/PreviousVersions/RTK_Surveyor_Firmware_v1_10.bin similarity index 100% rename from Binaries/RTK_Surveyor_Firmware_v1_10.bin rename to Binaries/PreviousVersions/RTK_Surveyor_Firmware_v1_10.bin diff --git a/Binaries/RTK_Surveyor_Firmware_v1_11.bin b/Binaries/PreviousVersions/RTK_Surveyor_Firmware_v1_11.bin similarity index 100% rename from Binaries/RTK_Surveyor_Firmware_v1_11.bin rename to Binaries/PreviousVersions/RTK_Surveyor_Firmware_v1_11.bin diff --git a/Binaries/RTK_Surveyor_Firmware_v1_12.bin b/Binaries/PreviousVersions/RTK_Surveyor_Firmware_v1_12.bin similarity index 100% rename from Binaries/RTK_Surveyor_Firmware_v1_12.bin rename to Binaries/PreviousVersions/RTK_Surveyor_Firmware_v1_12.bin diff --git a/Binaries/RTK_Surveyor_Firmware_v2.4.bin b/Binaries/RTK_Surveyor_Firmware_v2.4.bin new file mode 100644 index 0000000000000000000000000000000000000000..d4e50150f89a1076a119c92d5e91ff61c33a0227 GIT binary patch literal 2052352 zcmeFaO^hqcmM-LTZ};u)4M+6jy+%R|h*RCwyLR8QU3S&}t5dsfyMA|Z>#uF^pL1?s z3YVSb%De4McV>E5)#<+PwHWaxNG%4uCoupdU;qOcJO&^k^duM{o{$g{V#1&Y2qvf} z%z($YRzze*rZerdUAt=6;ncln+s<6EV#SITD^{$vBI5t}$&bqaef78h`2Q@#{=N`} zKmOUufBRd7YV)7`$L5<$tJU$#cITq#Sv{-eTjh^yrM2QpvDTkH6>xG0tuJLSdBlP@0?@Uq$R zKlu1cK=hpoytccS;;I!`Uccpipi+;%ENnGJyJrKf*mfPqY6n)wc-FD~cKA315P>Te z{dF$iIC)dw-o;N*UPOfrcj&dPVyz2|>*BasKR6YQ0jk>@I%oCf&(9Y9^2fzaX|eO= zBanx`|ETa+;?ds}-fX=;J3iX2o$WM_Mj8C$Lg9Y}-0v80`&*4vxc?Gxg}?bC#J9g+ zONIOI0QZH7@9;1c?mq|ImnPhCdcFSx;C^Dl)zjhrYry@;q_2@q-~R----^LCQ|bF} z0Qcj+`HiT(jkl?A{|VrJ!@yTR+D?W0-vRf}8SQv`_%0RhKLgxvnsCkiRJi{IaKCN9 zeY=z1UP1W2kaAFadsb_vG`H}hLg4~%3lZG*;mP*TM=FNAyae2DL~uJNrz22>0^t6& zFaAojBDmd?-E_ErANXEIaQnL_d%MTm31HwW1MY7}aIa5KPa3=1yL&OLfLjCH-$}q7 z9=?u&5q*CTaK975o$Q>%LHHNo{ubcY47mDMI@}`QzKGz`sAInT5#W9lgBzia;eHEn zzh%I^P3t$%_iqAjBZ8~%9-`{w-JKYffcqB!_cVfQ)H3kx{rIoMwgGpLB7Vfbe+l@0 zY``^Z%{L<>6L5bYa9xt$f@|#6w?-=l+$rSm*&}Yp(aG`I_Q}!F2%D+i{{s5u zpNZgJzpIY4mfQOV_@0|^tLbq62>5=-gi8UVdjCVf{V0MvNQx8}1Kht2xSvFDM~(f{ zQB4WBZ$aOS2(BJiXo?8H{d>UoTL#?wtv92ffcrN9_mv4(PiY9?{vE*mb_CbV!gm9> zAAiaHfiZd3Jj&qn-v!(k2Ha?4K?mynw;<0yiQwMW_r4h=5ODt$VL0QVOrT&0?d?|%k;e=iP~itjgo?|(Dls;et$eEFxq_x~DjYb(#IXGuu( z$G;AI|4$N5E&(F6fV&31AN?-(?`~s{^;Ps@1*12+mD<@44jljcRs6V}`yK4yp zFaQn6g-07-?VM~kzd79%^n3Hs27QQL%jv#au$+a>M|c9)!R8}@ zzl}Z?_@aH;@_Z|JwJ;1WiZ2#K*?f5!1cRdWXG8nrtA+Q)H?`un+aI(7`@Cl@2rP;N ztZ-i~9PGZburgn6UwUredR2*#1a{D~HZ|)6*1n=)1;fEcS-vsoa9Sw3@X@xe2Cf$@ z@Ef8stmVq?1edQm)<+v_YyPn;Y{w4lRsrt{m+(sA_b*m{`9z`F?zMb>>9LI-FSc8r6%;$}l_QMb z!@=VxUx$c){X~)*vPn@-eJ6QFRhRq#0^2TjJ$E=rkacOn8w3~4N`#b(xF0R=qUT<% zi%YxHv7Go@2!P{5>|6)$8G%?St@(o7aB;|U*MsA&c-6SGCSWxABIqnf%`~51Ci+FbTNjS& zBv=ZkUDtMsJ?nzHEu+r!AsFtgUqER61ZH;_V6ehln8AG8q1U^f=X!~f@B$8ct($e| z90G|NOWbI?J=a@@?&!pyUqD3`efv99==WQ_p5;aF%|4en8^d;+`1I!?mk4*Bio2eb z6w`546Iy}k2zNlt(Mk&IuHWtHL0s|2V6(~pZMp@2V zk2cQT&JE@!f^|&@oIsli5B|BTM%62)q>_53lSy;7M#ExtTU;YDC8uv{%nOR zUVtkZbL6!hoVL1_QtVvG`Q{G9aHD*_xpD6Ce>9EBc}Unkg!Bp>Pudvcp(F__gR)OX z~_40>*>Lo;&E3MP=er^<-opabVO1Xh+R@tk~1jmgL3KDsH%ChCRXz8?oM&<B~c479pUw|soJmXUQb{xgmQ$~>O}CWWwa1z2u+7T0#~4J+3fmbB1EpTPR>yW1 zgj^jfVW`VzA6va4bd9NBO^)jC8@<-K)iX!=$}!g33!AFrD;s5oh>uuZnhBcBN)udv z&lqT*FDEOLI%b5E70Jm;b#?9Ov*#~fuH^mp1J9N8j?=j;dm}ur{=joR!u03HbQ&XR z%W5?Gb5vuj{=jq19Q`>Z&)25bEo(pUT=QCgPRaA9Q}g`k4?Ner)}K@I{MpnzfA#~< zHLvyOlstbvHP4^lC(m!u?3Ts>%=A|a$~NYP=>=@$dW7>5D@t zf)K1vHqVSzf9gO}N@-V${+;=5LUFmCChHUcVkhD8)nrUw;=4Qc_x``a5vODj1FY^>>qXqlUdDkC;ZMJY&sE zOE|;+x#bD>f?}#e@?-h}eyEy)GVP9MRU;pJl6axVI7W8Tdt}*8(xTK8) zt#ib9#oFud;GDUE(2!?r3*M9fQJhP#o*ZH99);Vj%$U0fJ9a4+*Y+&oz=KnsJjnWn6jOqpypapD9u* zXVIs#2&p*@%I*wB)0_wmkMO80r>nOZ&2qXLDLU)yXs~MRaKSXGJi#0ck_@6)2(3SPweDL%*9+{y`l&$e;)I-B+FKpr;j1^yC_sbF_e}>^AgTy zDP{Nq*ExP5uLA=eYJ+|n4HF24SnOg4D0IQauqU0`LF)snix{v4G&kbHx>9-tF7vkM zB5vP;27;2nl=9KK5lhvzpNdOt1@fO5x}id9;YH=;GhG@^NylYcGh^kz2Odc>W#u1r$`8- z^u3L;d^J^hIG7uh0p>ag>CS`!?$T4M1A_n&S!X5;aQ@YX$N@u&$j8}Q0asSTYRyzR zJTf)gLrRrniAr}S6j;=TD5|recwwMen+?Uwh0S*!lH+D-LItz#mi-|I_hBw^j5J%y zVwT$6q25~OS3^J0QxsBNoK_E+C0*CEgUdcm7yVYyzT`OzYd{&jZ4CxU!j#so<$Sa~ z*P#%zn)Xz1SlE4dMLr^?OY@y)wJnIB_n4+dRD-~*92Ybp8tM=87{{8CJ4dB$NIqt^ zzKgJMtBoX1nkomb%zzZgr^A}5M2R*Oj*eACq$A;F==ejM$FD#rJRp4lY*1aatlpO zwp=W)#_-OZb7G}YXxqe=!={Y&!Q8`*){mjYK(^Yg0nIHWNFY=tDMQ#K49PU*TOj*J zTp+t$^dWvW67G;9K^(D>$*;}7@KwCQ7#zroH^tk>I+nxK z=q4FlrWw;F(HEvydGZh#DPNQhXVQMyba8&Y9UBf{;ld{VDbuE)$!=)5z!|NBpX(Gg zCL2^Q2xU`Ab1l8@RD=05V-krN3?lq{#~hLsKLi%3p$1u!o7C=@QDOBDfmc#R!9L`@ zdUwnzUHL;`lv3&tD!Ci+j#(8}KQ*tU8*oJ7O|qua>oMGMWNsGatU&Rgd1nL5AyecS z3(dhcpGUK>xyz5#Au{ser{#JI4XJDxv5x1q%-+BtfqULpja4V|z+@r+25ohKMT9M6 za*r8h*Ge-5TNqn#){~)Td9*pOB));yP4Cd?V{rv%rntgt3Pu%g3&0L893+IKS!~JS z(}PSSX2@0Oa=u*KSQDPTzexfjE8lnTrD&KeI5LzWY9j!ZsAQ<-K)G+ z#+YcgT$h^@fb3jm!yLjv<-dQz0ecag=HZ{gPAagXi)j@r)cD| zF=o~r#5XawsqyLO6{2%igCml#@0ZzevI)VF6NHt7_?FaOw+DO=LjKV6lXIpZ0a8ZzbHy4RqsSkpV5J%73YZoWf6p^J+r}5XN6HkX@9X$ z-RvGfLalecQ?Rtn3qv14PnW)u;Bx@OA-TAGSf;EI?Auofa~?FZHku z$rO@>v_m)aTl&1EajM2Bol(yLeL9es4~(GE6I>xx3BDE#nttDPIEP|@l_#Y);HVVN z)loxJfL$E)#d9;{_QId@2euckKuQ z*%{Cu$lGV1zF1m$!h~a+334rPd?8bzsY2`l+5M8_rHXhZaPU)9m3~7z3Mv8{43@=H z1tUudnHl_)-dU9O8}1KahCwwUFQUQ!H0j%0nH7OU=v9KSkKF^L{i`dVV~RxTSTQ38 zI?9l>fro}+_Hc<|itXhI4@WYN40=jub|p>>G6kN6o?O@Q(}vVpe5!P^K=QZNYw@jJ z9BM(roa$X1AgO&2@$-YmAM~Q@LP8ZCr-;L0=+Ks?du(7{dV=$x=rIXJgVV|p=SuAd zjZS}R;=~fk-u2TblXV0Yoe(TwkWa_e9*$2!12yfp%h@)&Q`yO}sEekyQ=`*n3X z4#&^B(!HiX&9RUOx^M<~-|vQZUEr>eF{3KPD9uwKd$kZNs)aWeiyL)|=xa&xt!P6z zQ6nQ6Zi{Vjp6C#b(VMG}sQxH_JXaAFeKYHtXJN}6$Tq>~HT~rsZ>Du0#bifh0r$bo zDhpI}8d(7Ry~+a7o2z4q&2!2E>Uw~(KFAiSDeoxEvjT*VUghXCM$~Cu{_guB7M#gu8>vTours#C%@;7 zVuEJA!G1Pj7BMJ;to1 z@y;bVGS>#F`ni*0a7^4-R<4I85K%YJ{SMv zQY5#Fq)SnVcrGytcYJ(WF$#&DSB^qN4^xm14`0tCM^yY%h!OBU7%3ti%(>KIAp)KU zCqpMYCo_rJ-24aEdi$88n$je?V!*+MA4vm za)v}++08u3rrDySTbGq!pu_`_3vS!oVgW1T)IrRxqn@iN^Uyh)vhbIOHGo^7r6E#qB8ZkJyza$Pt?Oln% z!2?U-AoetC%{Mb`42TM+3PZZhDXY5$weZQ;B8o9{Iw~ZVho>Cg9vshTXEdm2szjt) zodkai@_=iLa<5HeUMr^et`r2?`ru@td2qD5wKJ=V(4`X+G0tJ3ip(VxcjT}LTQ}c& zM4@?*qOo6_X}c+A4{9})o>DYW8i%t6K3FtRdRoyqoG$=!hgt*o zTgG}{xQjqZSlQjl3`KUb{&H?u zBC6@++ZpA7i>8Xhs5ewsbqmrklQ&e?e^}2>euh8GnkmVWI`CSvOE>|T%s^XR+grA>@YKVIJ;e;s(OH8usX9Ctmd^U zBy(2pR}5C~N*}y_xB39ZU}h@S!Yri0Ml1rNC@hC4^IN#Z@rmW2)Jyj9E>JMu+&h2TM&h5awB4^#yV4cSJFV0 zJwSn|&uA#t-`A&73h(Q;APO^uC8R9Y?@TScuRl03X!1yzKA(J zK~j82dVwpuJAoM6s$26wBAe{2c{Gc|NtaBOm(h@>0>1@mnMrkMYR7W*b{tNss=JdE zlkDX8oPI~9d6p%HDmaZ0+}pv6iq^XlfroYMA~EM}eeatYjEJ!46jDG{-KQ?#rrwbx zP+fPY4aPR=*5-{m!n0?Ul@%OdIJQF4N6Fm%sBBJw2@Bkp#DoOgh3Oeqc6Tz9oHfkf zIcE?>_47OzqhtsK%1$Q`&)4o*AVBd%>DRoRJ%Sao_CX2+%(aO;$`Xj@(+b4%`xc1j zcPS9hAEH3Km_tLL>~tF9#eHiCP&`rkZ%sqISbLBHF^7hDF|CGpao-vO6yKphJV*`k zat;lFveRjZm-nq9K=IuP#LEY%Azsd*Ay9Tofw*rC0gCTXAReNIs8nay5L9+5fk1)# zH7beXI}-?0_5f{&N_BP(L1m{Dh+)hz43Wr|(iS>Fz{h>^R8wXN$Jm>$L{HwZO?oeZNb$DD5`(cpvx- zZp^S~PR*g=?^rg%R4ZNoT}&pruDg>8?Pg2+oJAa!u_0govsKgx$Ms7LK7DhzrJhMoI<>87)?QoV;wyEV* zatd_;@H>`@*aSk<<`$Fr)CH<~xbkptJjE62;6SBXBF{WTFK`iLej7xf}4T$YC$4d5S>=g zDoXHI3!!P9$~Fnw^14>=YT@@aEVWOgZh3aAXk8ClPRGLarWdUqnd$tr?K*+y_WY<4 zqhOpD+EOt%H}qP8jW%!Cti`xFEzb&~5k|j?Hfj;)fWc?6&5t_nm4lt;*7>R)5qV)iYF>InL$c<_(<*3E%aZ*^>Uj2#<0 zO5J1NkWo$acSGS>5KgO4y^l_#=OO?2_FPr4eQC8nSe-aqbf?g#xyII*!WuT^x8i}b zQSPS1JQ5Yh;vK0=RwPMtd2Op5r6%c|3LEIcDjH4 zm;aD4Ym6n)L_LfVm@e#V6tNxQI;flo7Z86Dv_4qAXblFQdyRn^SiKwZY(@AMM6=_I zE7uDy1xWKO^p?~0F=Q11M6KlqKpaGkpxQd9f(hwcEfB{H@`)Hw(YJz2wG_QlD$Z+RajubOtB z8&q~ZQMdkVXnUaJ$O4KT>!U4UuIye99AI1k=1SXODe7_^v>Q!pfdtzLN@B|j0?Uhl zK)WKkBd%=lq~|)_B0&21*6k8$#7;CIK-ao$%O`S6sQscf>;>y!Dlh=zX=$Zj5{Gu* z4t#n_wZ2?g@s~xV#6K8d%ot+HHYJj^i0xds#kTFWdzJ{S>mbszK56HTGL;x3;$zI!*gihjRXsq#1TLT)8lsme~1N}oneB7o#A`A_m$MKK*K$&l{7r=ss; zLY%-RO+!qNI>Y|C<%Lb<_F(kVG$ysbL9OOXwj_jA3|KRdmYv5aN}05Dee^j_()hhG z!QFq~3VNP+;ie{p`up(OB5sd&UfTq?^DNQW8)SpMRSg1(eAz$akTxWpT z&HxHgT3^$M)(A6ak+CF_PcLky{ORxG>XLbCVy<0vxeVq^?D1NOWT*O3!8&ZI~J}tQ5^Rzw_^o%`-z%S?#Fo2CJtF9WK3xz zCp4AFc7Uk_)66160A`PcNgEToYNyccz!czmuxwy`z(zSB!-dQgG?Ed+NVDvZC?{=) ze&6cAm>?tR+`?oc++l#x643NdaVuc+P=rkwG7?LorVK9_2GX(tb~c+rD~_#+)6-M2 zH0Z&|f%#{_#v6Jf7zQpDD!nJ@7in_3j5=jJ8kR?6(DFX) z4V}k+WT%1jEqB=KSl%)geLWYV<(4K*wWj!d7DfjT!CSC6Xe~Oa@upf-3lLiQFbP}e zw(U@kXu-mVhpR=5?s~b937u3Ehni^)agD;9mL}0_*hS-L+~fff5%22(y>af1(KOO4 zk=cY$Nn-e1%-BJpGM;tPPg)Gh?2}gCr2Yr~c8R2BUjGL@AZKl~hmEp)V7y@{E zGW1P88JcEa<78fCH0MraD9>h4rY|8wpUrMZLkvC>8TvM#41N2((L>+nRdWd$`u6Vh zkXAX#&q->^R8hBYkHFm3tBh20q%z)hNsal`<_M9vsm=1+wL-dT(K3f6Vs_8;qd#dx z9JZp6KxEV@69TR&d5)G;%cezva&|E6SW^sWLu;wYOQOXwDVgS*DZ4XR4Ai=u$c=G| zQg=5>$2R?z`x=hoY&|`$vr+IN^ft9`hVDkO?`412dUA|T)~JS7%~k@Vhu^%e?UqqV zZpR>1V~TW44dgj;ff1PN--&KPUI2uQm|i$^(Yq56YGc};nzqNhN>wE$zgdBEu#$t` zW5$Yd;F&Wmmn-u8u^^)ymeV@#S;v8A4;l!6!Slbl%a6oyvwm7yrcy_(QF?u} zF79X@e&^~ToMFC|j3}hgkX@1KHkvzn`UVa%cG1bkQUDO%ImFP0gPz+$JX3iC;p|HI z;$(QQ-SXL6M+NP+RT3xc7VIEMh?pJ69Pz-Rz#l?*j4p|1$bm>W7$phqo((sn;cwfq zed?jk!}F&hW~7B`MpJ1-?q`YP8DyMY*%x-BaS&aZ7HP^Tl9y#Jy|ef1Ou5uUny}}y zr_9DFB^sVeI3b6gG=64bIGrme`g0S7ZD@1LdyTM2IGVD>Vbqe6#U~D3!at{m$g|p- zRYMp|m`N<6^4}*dAzO8d{H0GR8ifC@MPs7%ZB76N8|DxWYUcM(IABXgX)~WdZxH^w z7LF+_3n?1RggHcm%6~saBbSXa^Q1z26LXsypMG8;I%hRFA_@C`nH@*&&Gj65$Ok9TlZvo*%4 zIVI>W)Qk2Pn4cNzp_Iq!QLM`nJ8&A7<0I2cdS32t501}dX#bDQ1HH9fII@iz`BeLG zVnx&CCC0(TUL4h|&uKT#gcim83(5UBrWES$W`R%Qbe06~!2#-Gvy$Sr{COAt=6Ln7 zp`=+rpRqL8TXHxfBhxu|sS^&4-jFA`kIYNjh7)aBxgxjm{&Axrkm5OXS|3|B-1a?k zG1KM}Y_aLtZF<0tXykVG-2kbj$W2AcCXR}rq*0`xzN1Yl9jl9szi2;9t7q&)aj+}M zDYhaE3bjHI?l{qY=n2lE7`yH$t<&r-{rwY4FYyZf)~Bhp*0Z|~?b%w`tl=^DCr?Ep zeDi5#IfIxx5@%{Nws}Dkdk{*y14h^vH{#O0;#dc^E_H_OfJB(NC3B~v>|!vCA}k-R zOB*|lu;UCH%RFq=lUu}84zdvok&&s+0}#R4=4>|7#i`|8AnW_yr|!W(&#bpRZJ(ZM z#8XY#VX^e-nwb~pU1HK6&>BlYY=2Hu_n4NMdMy7o+H?+)ZltY3$m>UtN~i$OCFY?k zaD$>^esDvZN;|fXJ)Jk}w$sDb(61LZkIS`<@?djp7WYo;hGwe3?uic;zG6o-woQiB zbnv=v(L{&s4P$C@#m`ZiYD?8&X_oID=zJNXHbrbZ+?(NtA#?LRhOged5oW=swuq>| zh48sqw^8*NT^XCIZ^g1XEN;=JRFf1VZjSxG91D+3nb5fSd=-0Ym+_#a{Tc%#P4Ipl zUum>-q2(?%Qs>y5o+WU3>GrMpg4nNt0aoF|jAX}~pUvw~A;=JRtk@@X4{w0#S^;&C`e^##rtxY3*Dsq=+n z1=x)LL2g9D*0#3mIIuZjpaCZjQ~X5A3Z1PH)#6xJtlKB$qKq)&HWmVmbj-$b`5vPz z<9G>vf2)IVf=@0hk0k#PoZF$F>*!%K7jHtqCmc!B`0$NFpK$PvGYnF@K35JMmz4R| zX41)M9v!X2V7SyRjFA?0!t!bm4{&@0Kf!KvMl)V%&1DB9Nl2Z#s6q61OOrpLQhMqg zP429EI-Wbgw$vV0flBp|4q=1Xg4x+D*X^cGPd1@KH5;|Rk zRM;}T!^TvthNAN@@)-~#4gX&0rGc@$k!Jp>=U&)7tLc8Qa3qov;Ox-!=net3T2Ocd zBbqaablWOvLaWD*Hx>wKB#g)N2^H6fP|j|O6Dlyw3(Z&HeI7G+kHUgZ6gHv;ohC6ar$-{*)M|;@uf0zZHMOXzL>A=|ALmz_~4n|&7 z!repShCvE>Gu<{A;5VWu5d39-kKRHql_O9cs{Q9v-7)`oJ}rHR9c&YCkKt&e-P6=Goz6ba?+hv10qO1-res zg9(?9eA7C9!off0(H&9Cw?to9iP)8oDy;#Aa`SkBbS-we^7(H?~;>BM+qvG`MOvNiN zt5lvpWYUta zblA-;ska2Gh0UYkwNPqvYQ2_3mPTx7XV0PApcsyicHwfLL9yYwh||+XdG{k?aiWQX zB)gV36QZizoYfy*D|X@Fzk}-bOt^49N^NJmyi?0j{62=~POVvsk3~Ls5XVh+Xq%kq z*cTj)#NkLX@UEic)Jq(or*kR^5aShREQ#j(a{WDx*YId5I#JQ1Wv>g%m^w&xO|0}_ zh@)f00I8hv#7uP{lsxItp)(`Z$(GnzMg59sKTL5tX{x#%A|e|fJI*>CJ|POkGqz z68s4r{KTlwNk>hkhR9@@$HdZVgH4~!9VoYX4XhZ(m=^lMyy^`R!TiCzYB3-Fe_&qW zls#6%bjlt%E9m^bq_H)s-!pA3L%|z%mgM7SW@zP7V%QsMc}}Z$N^^@|l`B^uww>~& zLX!@PHJ7S1jTLX#cP@kLyC$JwNL@b_O#j4nD7#@~Kx5QjpMNj9u9YjDX5N~8u|Slo z1;ai(+`Lx6Ji!(La#pYrA2B){hK=bNa0ue^DV6;p)(IE9Z*f_k>WKcPL$bpRzY-!4 ze1Nqt(+TMeN?u4C(yhGb5KQ!v|ju@81S%ZySSO%Ri+7fip(d0NzoEXo-aW;&oo5r<9~#srzd-Rh(P)?^}^I!*cpKtdz`ovG1fn6d>Fq7W|E0&>F}R~Z623D zw{6rLtSQi+;}m!Z^GT%WkO%dwvLm&UQVddPa%pB}i_xCDmYJy4vr9^d<8zV^&P5_^ zz1!(p(=Js)Ny}0>r*034n!!z|1*g$7QdTsIX_QOMr5qcr8k;&k##GzUD|7zO>0%B! z5%(3t9aFdYm=iByzr6n4zB_q zVU5h8OI%f=68mscHFh8@d6HKac*TcJQyu`P6txrpZpdK{Foa=-7)+jEbEUTRHvF0) z;t7dH1gEsOE|UD5q}I6$dzL9=mq<)lthCV#JYa zuJ6Lf7V{-ew(fK8++mS6b;oUur-`wGY(ptyh^0JE8*Pa|d*cSjyY$l|?J+SkN9HYG zOLohlcG)Dos-J2%MXYGLITT}9BHHdVGe4_v`-B#my_$a~MJ!UyZjUij(-bG}g*uot z4zk)BI|9t?OjNqJpm4*gV?u9EU$-0oL@H8C^zF9iqLIvbBopD<56(A6J|K1|_9@l4 zixcy-Rnfx~g){G_P4J5mejEC0obF0fIhuLzJj?p5zflYeYAg213w&n0%HkQyfU9D1*m(T$U zVR~%<^yn%!GVkd|H{6}(^^w4eEPRJ<^jntqskDW>Wsej1k&kD2y!ThFr^yh2abU=P zWesOJD+a5}-quBhv_|#Ci|9>`&Z8#BICvXlgpktTxUnK3LYsMP@5dB%%B^ORXys_J z(wB1Ho#&XuO#2vs~f6DU4riWy57;H!3?M z+CQtFYpd^0_RS_~!4_t2?%1n<&1LfJMu;*#lC73TFd~2mzO|eiP6C9RK<+c;IGktU zC)+F7(9R(%?21uW%fTu@PChbvbP3!V2P9I5IJC~7G#!252=H9IQOJ zabwI2eI0pxJx>$vMMAdq0y1%9`S|nvU1uA|yL`Y!(A3jSHzA};PjG9rIv0GiE``CR z4Wcxv#@beT$fe%`u9X9Qswi2aIY)kU`-D6lpfTjL&FNC$Ik)VqXplTB4A<%6-WrvI z=y&)`72Iu^t!ecF`c{YLTewtQM8fGBM4U|m2OKRD^fHzPl8>`akkN-VF7ncGe|?w; zhd~gnajDdBpibeD_c@14-F^#4^F-(SjAS2b)J*nS^ljv+|1RCH=t{+d+^?n&f_me$HL-IK?r>cR9M?mZJSk zN_Ms=hs%9=3&F8(gfl!>@4wk>A|X~(y`pv+SX z#rAR=dYXw zwOmLd-nHz2rocQcl8PW+ewIm0le)p3n9a(`x*}D-#Yd`~`5-OW3SpfOyWhHwwXnHE zUj=<1KOoZ;HYuG-!WWlH3JZdC@{OzkQm&3+^8+C!Ixq+{$}h+{BMWt#HjvWx14cK7 zX;PR+tK;WdjI|vailljaOpJ`Xx8ZAoZ@?DP!xYZ#$ikN!dPv8?Vk0IYeAmH&Y3wAV z$Epb2esmDuz`e4(BEERc!S)RfMni%>&0}nTusqH@@ zL^g>s-^SbX+8mP9&f;*0W6(CgUfbkZ38eHqYZ|hWCUl$Zs;N82y0(L~&cQ9~bgWrw zCsCQGlXmfo7TlQ~#ad@{Tp5jyszo4Nd+k>X_@_)Rgwn6zynzVvD>-g+boB&DN1Tykvs z;+5#Q?IE3>S^Bdf4k~K!woKQn^?FN>OF{7XNyvCzri4jx7oOFnK)l)%e;&Rk?BrxU zciq4byw;%9l(j4c5t3iauMxc%HE!ny=LKz)FN1y$UkcP`WvFS}DL@Va&{o`a+HMCL zSHAldmTIzH@^{k1bDJQIm*@ch-3WE*L9VTDbDp%Vlg6E>)hrC{;?8m8az^ zf8oj3qFm;Km}u9+qg;j8N|mr^?Nl65!ADnq$;J7j96d$l7jRy2%E(gR?>oTzuYR6QKtaFt6a%M= z8o95DQ$#&#qK05Xg(>)W`7z#;2!Ir^)PvdsBUrJ>94Hov{D^OE0UMI=N(vt`VuAhp9WpW9~2l%2}Kv>J=#=vURMnQB+ z9}30~1=+q3OLnIOM)YtqtG~1m`97YQBug|+>L%AIV-{1My;g{cAP5_ikB&jsoo_89 zaS+rce15TtqW074U&l~dv?svC8+gNXwB#Deg*K`nL{7Z{n&aX%LVWx+Itgu!(;g}q z_O$|HfsRt6K1!5De<3$3KnPq(8nvAMsHq89qAV2iY=)9BrR`!iB|+8^c7b_Vx)Ny( zL7%dt!gE;@5D^;*He_WA@w?aTpIs1t@fS%xP}|^0w1N?4M+EqHOQtyOVUI%^pP{oB z%>BtvFmAAQ=5_Pvkh(hB;>s!<7Ga`qqbAX28aeMnH^<~Xf-(7?0Ro-$X6yagaqaC{ zHHM3iA0{Zpi0(Az$Ri`GRrg zYSPQxNMGh9v{KEBvr^5A6Q^1bn{qU1ZRL6OjDbm7%s)9|&3*d!-xTT|nmMqV6y<~$3QEdHn;QK=h-b?KFr4!=i zS|+XlqE3sxjWi;Ct&y`8T=*`V5i+)1hU)>D542rF9j>Cfk9I$^%qMy--YH`n$i>sf z*{AO#*;9$dDpot>gGTBaZaPP3U7I>&RI9;G2mf@fBk5kics8x;$B&h1R4(ti9-TEU zJp_nzW8q^-KCyw0Tv;5XL*4^AOz!n}Kt!%^l1tujv_vkGZ9Yj-{)Wb&dLKVg1B?%gK7eaoE*o!n7%sP=cw z(m;vf7{<{6DJbZ(Ip|<44GaDt%tA9TJF$SC2}gX78E;0N1CM#LfqBWoG_8Z@EOffD zd5gJTDR-sN`4$f57ln(kkVRm~!rIj=$tLgQlIJ*p>Vqtb`G~Vl#dhN@9Zg01E)Wgj zI23U@q6+K#&JLa|X}ZWira-AMC<02>n&t8VnFvx#@)Lq>_k86q9Pi{^Aa^cK6Op&o zFAMoI+^nmHf0|Rzs6qMm;Me=7IJ|XWaNr^-KhqfP-WUOrIF)1|d#z%k2k|}VU z-@|W$*;eQWn+%*i+v;`vP(?yL=);txVr33UD=5jHkf~}3 zCizO-)^-=MO)G-T(ovUC(XQjG(~s3?%u$ZIQWeG5?Oe4=;|KXgT$KH$xynIx;6Bo* zsn8VkJ6GB8ek@{rPQ`YVqNus)6=iu|7#WaqvQS;CLir47 z4npaD3Jq;`2rP@rvRHeGdh~$gJzi@s>Ci?GDPnL7nL{!zJ(`|!nQx7hj2@|14*rGy zh)oV{P{OHCl`5!6)d}(~Ylg}SjChc#CCm^+%~6`%Kms;g>$@mvInLxzKm`MQAMTQzBC_N}gDuy2&=yw&0I6IPzF%2sGU-Yr)qZ#;iZDT24( zIwcAwFJ*lcvy%0_q`#y*^271npNEm0(arYsEwoK8aM=wJt;nS*AXlYJ3uZg7>; zb;kI+aNg^9XARK(VQ=Vg^noa*zici=7|`lmbxKO%@%D(b)0UCEHA|72F#E0PwHzNw zsr&miEaH^1fE^V1y)aXAqe%b6Y@r2?%ORk0w$nV)bufkuu>Gwtt}zyjNRbPLv0#UX zxxi#FWnvrl>-mUlbc+mrm410L^ zItK|SJ12Rd>RUOW3<4*$2B7)qJAIp{^Xj{Yz<9j7lY`1eEf2=V0gK?IcEp3LS;C4g zQKwK359tvC7L>N&7AHMVhGfRT3AJetH> zhMLq&0(x8D`-VsxS7kk!2b7^%6kL=AGyyJ5gBcGOWdKcpV|+Op5@r94M;PV)jD<5Y zeG(uFrRM)cAUj z_6=~t6ZEu%e?nJ~uDDX-nxB@&)XdToRvlZRXgrTY2&9*|VpmwHIrX3mvw|0kH;;)XSCX%eCh(a}>dG zOWdRt@a@IZ670!sV@i%{ zlH7tL1-)2#0g>T7CD&9(^=+B&Ib;N`Hc@n|wzWaPLZB~^t`0r=0Fy{Nk zj2;UbjE_*{tJL)4E561&#;7x&A3tApX-thg#SpVk(Z=zWa(~`NwUPKILJ2I)F*TSW z#v|c`$t9)RJ3XW@zI05qGQtXZFsOh}BD9dFWSXl#Z@E!-|M-$IA(H`(&Xp5fIpJ!Y z%F|y;NJ9;b2#2iwUH$1*-CYZvqf}Z7LAXFUEN)Tqrx8ybU801WroycZJS|02X-tJ? zCy~vdPA}cQHM<@S1M5jc)v&(w*b8f7)?pTnX)>NcGsB-|J+T=Z*%U}PeuZ5ah=m)G z{gnIbpUBj#uVdx0QVVyFGOk2J$Ykc{dI#vHSc&H|v%sV@cLFtN{xkVsXh*C*%ZN0a zt*7efZwgftGG2!)wKGd%O3Hf(o@anfY-KEpM-@^}(FKt|w{Gg#I&;B?hcEfCA_Fk~mQ zy7<|Rw^O0yQew)9E3wqJ!U^$5qH3 z63K^|*FoZu!eyibMt5-0`OjO4yRO*4c=lAU{=(76ef;bx-A_jUnVn26(+NOEALpS! zF%P>zZm-@chJGGyFej4DirFeLEM|*vpBw%XWqCZBy%1ihqcpHgJS6VXpC00nBToHI z-&~Z)RHXENIirRNbkNeVygDOW$V{<%B`T&AQP!Z$_I#|)V!<|}g;O*iZbcpqyotrY zKpVaJr>R95Qm18xm<+~z(!Ef|_^0{GAa?WCTI+w7&5iUs8vt@g+SpwuhuExw3}oD) zEc^HhXMvSUB_zm(c0uZnw5*J5s8sgXu~cl5r3a%~KQF~+P!s8;a=D2VR#EdhL)&r1mGu~h zzG5Fu=Y~9M#O+Y;d@`*ddpXw4teeo!u>@P?ebZrr;rVqOg0nfIv^g9XL`TAe^#9=> z^5`EehMBp?8`6|UBzIrFqFa`|;|?POFn`JY!;|A$1DOu#^qMxntSZZ}9Y)%0S`nA7 z3u6LXu;lqwI-}W~P@^gPr$3cbLL^Kfe~lSpVWdLB1`{g2n`6rkj#>k`+@T#aIKT=2 zw62%MIlnRX&|t5H+JA7cqnX3gmRww8FN~hWNSgXB|ATxX5yf7T{K!Q!PESIWPv}$w z^!W`MqLnP84${MYjGzE?8 z1j8|HbOX4eduxREvDj0b`CJigT$+yQp)W$RmAEQns>E*LnnIB+EJ#!pyHu2Z%DO)8898)u{mSZ0ZpZ${mj7QKv!}8Ppl?!`$hN z_j-kp`r62sPJJKClum_+a-`E=>wIRiq%$DGyy(>T@r>vZkVGzY`ui{oI`wrd|9J#r zB=b27BFcHrgb0&=vml~8=S+ww!#N8i%5Bbsm_&$?&zyn7IKeOj!pvb#2Z?7dkAaEu zmPde+>Bp%6M$&QW`*^BxDu|I_ocdm+75_R~JS!9R7~7n+p&7;*2t{PyNplw#VPw_G z&4qgHTuFlVrJkVXOP{{9t?dLe#{S_t4BZqJLcGTz)o1O6qek*9Ub6BS20q=34*j4bH+aQile+zYM7HvioBm-l_Q3NQl&tq!Rw2wRmmvVAzCkb^I{mBu4lk9N1 z{edIm=5U#>u|PZk!a*sTyY-!4jr) z&)lXoWEoA7q#7x-SzSS$mdJ~W`Y}iOnBFi5439Rvjn;<9Cbw3C&fePb=w?ib_pr6#7y&7*RogQqpyat=6!!gENuo;Ij0&BbKT)QBHK%X#7#*LW(L+ z{+wrZNsiX=y1+PsBF23unGAjpLErL%QRdP(g7i z{4$$lZzxY^*OBRDpOdhfgqfvwDc%X;Gf&c8AmjgC%X9c-#T`is-|y4Im2kLmiSBxK zMGZ-}eK)W_S|uS-3P}mww|s8l2)`j+632%()4g&Lyoli}VL73tK@Jr9m7-;*ZpR4X zSYM^GaP~p?Lyyr#Jn;edNqX$mNXw6(c{_9GNm0l~oH3h_dtN?Dq)K_;x#FDTFSr znOd9+1-BJ^516=jSejYv=SuTbOGVfi6qhY!rA*z%1OcX^GyMbt^@UP z3wg^Ci`cKedOQt>NRHX9rfH zjGNPfo^|0Dcurauhx~i5!E=u5&=rY=@EM~(lQGi{dzNa7&VVZw4mv%niJYRvj>dLS z-4r1->vD zTi7Io8vt=DLE+H761#98b#H`1My<-mwOg;B)X^(sb`8KnaQ6HL$J4J1uAx}m#QFDK zTs+;gzI;>wp$_tNasLBuFE8viPLEICot^CMgPbLdg_C9tsbIrihx_r|!d_Y4i_Shj9#Tva4c7ormo{D3~*skz?U%V_(4J0G&|}GF5<P&y#U3bdnEc6_rJ*JyiZ@1TMf(6({CbxZ{=5PkXMi| zLrB`qF5l|?<_ctuK+IJ{ft{qZ!lE@rLA#JxgfZ~-(I%>Rg^DK}parM((eCmIEObwV zVkz_pUwN#4zP4I}x-~#G>H&>>`M?k9QOlr$Kd^C66AoZ^+Bf(ys9*od&>C6|NDlpM z8b3{Yz0hm<0SUFH!8G6twD;}c=uMxlwyx22!*sEQB8F!TEd(i3eIYiNr|fQu1B6?3 z;*a%y995|{CSJF^&J~VRmR@#w1q5W)rGZW73oGzrIy+Z-dkTgJ<&1l(7D$D1;KbfV z8;w&QQ=g|irmevlk5AvlUPPO6Gae`4_35oKXnF`Z$#ia`^p!{;`TZ=}j@aX<9kItz zJ4POBy3~tgJ4PNS;N$I3(5fBWGwP9X>S+N?#r#QV7SC8Mk}SZRRd0Fj2i&}fql#mX4{7ss(;e9D*yC-vOALERGam1#%dc5q z^m;?63$wPUJd17Y-7yAP60v#~Vl{E8cM=f|eH5-K`%T_u^X=|VIL~l{NUJE$D*Ln$ zpi90*j`(YL==tHVBio@vTLAcDlRhg{gr;$dQMJsHeY^ zLw)3(o?KLoN3g#9J!lG(f-N#*y_>{r$F$UOzqJ=Cb)z|3txg&|*hJXJydnx=MHr~+ zm^ZeD7Z;WXJJ7d+*h_A=Y+F5O_swz!OOmgc4KX}BL*$?0jx0;P;%SVcOUf2JwQ%Y> z%&u39E7kYQng1Bjd^v-nhw4{t-ljd~WCEXSW44Z+Y%W)YsXyAtQDRdDvm;;Xj9(>K zRx~5Rz$t7EgTQqd7u&o;Wn6+i!$D+QVz^{N-k_>}4D`5JKR6X~SkoQ{2iG^iREE!K z(O+k)YJayW%8R~u-E5wg5mNl}5vj#u4VNbd>q3^-r%RuaT?&KkBMddRav>(x0APPq z{-ZA+ZAGqJG(W-!&_7h+Vv@}%{GXnPi0bMO_zAcsrq()H}`*hp9xh&tJA z&E@kc0a?AG7z)(uMa15K&= zZ4whvn({KFRKKeoG|y-zI@_ti(wD7J??zgop4Z+qU!T+uzO6M6P7-u%*BX*jII5dG zpS&fL#Pm*sT{nVsuvl8`EG~kMw{9PSExC1H??rd0fEsfY}}uU zM%drc_zhR?1=g?YLUOXmegQn9`;bRpi9P!|`84Gb-PXE?+w0(Gk#et*^NR=t(G3>> zxgru(a*LX9)!;RC2j)M8D)xqh{^QDO6OE)bh5=NACE0cB_o)bm=Wu|*;q%ezX{0ny z3%2m}6SdqR@`nTc@SVM9tFs)^nr*z+CDhRzP12Y#RK^RVacWnwE)A2(7mBy=%gEl~ zhsPEac-Y1Kh-*)DMD#*U5NTzU*&D-;lR<4rUF_LT3)Ivt%H=Xh<|<;R`QTQwbbgaTN6y}o#~zSt-%V?dV{S5|xEllp`G}w4bO$BP&&*Cs2m+jp>Ld7;>e_FURup_@o(4Y0@3mv0@s88+!7t zKw}!*#JxiW#$7u#y^y3y!skl1)IFxBppZ+nL(@Z$wT=bUSMe9%G}}B$d%`HF9J{`- zuG=ixU&$FyTTf^)2#L+f<4a?0QQUipwkZD{*hn5J`M92Zthw8lZdi`>B}yLeo)mXp zHj*VV6)8hhO*`QPx{WoDUtGDS&c&^->KkYPATs2lsR){eJo2J>bh5L%swXJ@lx8&j z%tvJye9cx5Yr=4@#^N<~I;47zTOWlv?P0xu7N9b=5j$}Es^8GlJ9Mp>bZ-tIfiOXl z9mgJd>OL;OWebQ5du{{w*lItr-@(59P6L`@06S98u~h1YZu3G~pydn|n|#D*G0DRV zE`7Che+aBpYMQjniQKIl@~lvwvA6XCP9d5vsiC1WD|A6=?u0jy>^I&*tid+G)6C%; z&5-LLtOA@N89eJ^FKi*8L1=iXDn|t(-x+tAPZr5!IwMNiy+KMc|InGa z;SWy2EyRxt;t>nRXgBJ*kSl^BxTvIFi#b$_0fzTR^N7u_zblMvn8s%I(T9z#TFTRX zSR>fLJ_;_kr;k2Yo6ig9t$3zk_<*PF!bSFFuvzbr;Z^WEWQSq7)V7Yc@C!?+PV|et zNSM%QIHvtqh^}!jzzU_g369SjKbr3b=EdIH1Gv~>AK+q#gtdUIAmkBX8lo}ALe26= zmwWastjyTz(^842N-LEIgEBgzyi#3#Rz5s02&$g7EdY8w5`BK8{Vc}Q57rHO?44z4 zn^Fk*sOi2_^{F@%+oGqIcY#$XR->>ffmNFw85=$&~P*gsP-N zP&p7qIL>c$dFT$WPmWaau~Nc`b`*4Lox|S|?ok~Mx^NR%;>I0%R4Od7E-r&$;IEg< zwC~m_`E=nD5_jpYr*Z(tFV#Wp5VIj0we! zL4s-1rF<16Wb^&8s->M$)^iv&#BUi6Wvwhd1c-$WJ%@$hXN4nZ%XOHqbhDsNj-h7- zl_*1bLLltGSfLcQp&ZU>nu85F^asF-Z)#HO6z(uBr+|a4nsD1=(u=hK1n+VjyHlu! z5S-itH%MC`7E$D21iD&9BTxcoH0)x>0!mVF80xhzCoMUlFY#%O9XX%V`c@6S7!d3u zx+WM`ZgnliSv8{&K4L3|`y$TPkDdaP>;m;jf)#44Z8Qn67+Jlbxec26X`!#-sfF~A zXT{`0>^F)4R~6vi<4ncu48HB5XGmbNK1LsEHl5te#ASFLOCyuom#oEeMmpwU0PO8 zH0}0>@(z3yY{gLbU`4xH6+5+U#$4OkCe+&aiBlPqJSj-*%+hkB<_q~uPHt?PmSL39 zv9@InqYaC`fo(-4SS))1lQL zg*wqhwsN4tFm8M;`e7mEM-T&bzX}FcOQ%VlTj+6vC#W1lLUF}hzvG3PFW8AdzGpnb zbV2hJKRSg0OY;IfkP&8~!g+WO?Qc9+3XC*AJ!M;;W08QYs6i7w6pXpTZ0nIVEVC+# zkP+CQwu?fMeDh*Na9UB-Y{9!;mp8*y zUQ|mjt1Dz5JYukKM!@7%FfU3^U#vWj;J!`5$;)3}mY%J?TxD~Etr8lQlIpS2GqDLM zO%-;mE|yikY=FEwW_9)HTJti8~Z%ZeoGCzf%RQxDY4&s=G(l}<_x{x_g6vn>gz#KG9!ic6Z#gIvs7-)C^g9+WVQexeUdu~i}cr{4| zRX9>pDy2YBPYymc9wjl9CV2%7#ht)o)4}P%E?njaG3vpBGpk33sVr~2QX^F{Neydy zn8pMu$HNv17m@q0su(>6fJqLV)gk;5w!_jKE~)tjYe=#54gN?}07tok z(i7Supq_Dw_#-)K#FoOec+|!gl24s34%M<+eO9SBaY=avpbI~cE18u|8(=U9Wm?O#=yo>-`pPfEaH(YBV3wn*U6 z@5n+n9+WTO)5P>#!as$w@3qV4$jS8suQe#0!|~a(N|@S9zw(nW>1i9uEr~KF@UIYn z_il=-rDvs;7#0fRgeZ~1Sp@5bgA(OvGde%GLA@dN3ydJY3BGynilk~7H|vGX%1VKZ@AU$lfqYLl)_^}RsH^XO3d_9>li_fy z@R1WM;JENP-1r_BV)GYTG_T88EtcGE1P%FLoOdBp#L;z#o~Xnsm~t}F7G4k9(p=bc zk%Em#>JF5n2lpc)&d4F52xNhRj)mPKMWYH7V4~VM$b@s*;97x^+ieXIYa&ggTMY$O zdtZ6Jvi5?k?zDPUb`k7viltwL-nBLbvuTf$u8DTbQB8D5^)}1pW-|!y>Pq46>*f4Y_{V zmJulQ1#PR8E(66n<_gCwlA+mT5gGxrd|M{yg`Q2s zy9SVEdS4PXnH@(`pq5dnL(+QzVM8GdNvITbe3X@eL?-wMk~vLA-V|k7Ma_^1(J8?5 zX3)U|g4(24ft+>mXH|9-BsM2#>tBi=1T_qxXo0lk9st?TCGvhyB}$=B0+;fqQOOA| z98+@E-8S2=d|~7;i#?aNfGj|fp3om7Qi7Jkt~wFrV$pcZF3H4NwUz=eT~Ad1OD4rMjKA?HixrO|fjOVa#PcHPMP6k{_J z(F8_IGH8(#p)c=U_HqdjO;bP{%gg(^meRn^9sJaYs>gql(n z;UbcC%W3w$fYS6Yt`bo5svd~i-Ml=;}&b1`MEiT**x1^gu-6d{bAHbO3<*y7KG@5o^#- zQ&8CU17EgBZRT`!M2o!Y`1W#cIImPK9 zkAaIUxDdVfxMXBP$bEfCijcKGCI z(p@2C0oq6Hv{bn&^09gbKExgaT1zKQ9^}7=w1rtNp;6Gfrag@umLl$fqX3c{5!CdG z4QjmY(To~M#YBqMKO@d#QT3787_UT5YlJ}I)E*vPr60Hmfnyq$zAY2d95HH|j=jDJ z=~iANa;yL^X=!AFgD9jg6p&l41J?8z`%yxAg3;}=kd!9mw+OVW#cfhnJ?4qCdZT&v z=J@B>>B*Zr`SZldrgz!OQ=isD(GqF|rJ8egaW*TAz<}#fbr5VBt7cd2HD19@=kJt}p4m;SG zsia6q3BLXgo`4Q^ck)N0P=^oRk#Zn2=@)yQ0u~tibcmZYzQ{5KA~^Ie zK5UhJdMkwq;dJV;>^I0(mL<>@YzFVp@oSPcib7#Mkd%J}QE7yIHCfk?C8DRHgwnyd zBIlq?(~IZtwZU*$JW}_P;KRVD?GVuKM*aaOekf3t2FYn61M&~5Dg0*>5MyCRo1$ky zj63X7kt>v7BhLiqPjTL;RX{;JR?UJ*u$@ACKDvu zv4=F((gPWX<8URcITA~R*Y(3KUP_=Ufw_gj!K#9MIzVBvE#XOqTTkF<0}PEJnTuF` zsF%Dd0|dkYXF51HlrTp;rK3noALqCXt?|7i6PK7qRr4#`3T zuN>;K3&f3NwI0P1$;$omk!%F7qo^T72(U8%REVVH@y%nU7|CXa!;y-U9qx5qIEKR0 z29Uu)nR5^ky;6$}K6VM}#3J5RFRgWSq)dV1a5}$WOXg%442Be10qbewijcd$(G)y` zSrZ-s!KX>Y-l~WKtoJgEV-^Cq$E?Vdr#>c=T?HB%$m>DCU+z5=v|StkDhN#PkP{Gp zhvl~R{MI>%i1z?mxY!1RtH?oMHfS+yD7B?2^&XJYdK{4g+wEWvBIU*mXy>O?W=OG* z!pIaHP61?ZAK@W+%)k@EuvcNEE;*pvxP${0hp=E-3O)%7!6QW;!h&llusSG6)PZ*? z5ZkA3gpH_y4*pl*#5l6aYE-G1*N=VW@(XQli2s|$R-pop^FCAv8GD178XPyG6QihB zcs(SH+!hoD6b%>zeHDy;7)_mgIE_E-!$kMQc72;PL6y3JyNIk(Ua#tc^p<)d{+5_D z`hqln?$`rgOv`)oXlsAS!1a2{3mqy0}p3HCOtDt$i#t6Ri3S?$i7^(NKp2PXW)Yl$c2x2kTUp*1T&`! z@o*-D?qiLbrZfeue`0j(g}!W^%GcNmWxs$C68?yV4#Lzs>ID)*-4ATNVlI(OTQ$3? zonJh?BDE>pMgff$d536a*1~~!EYm*pmkXCz-u!Vhvn zs9lcOmpHP`QF{770DCV;qp~BAf*%FIZyQPCSiDfmG(X=xFCVY`qOci;Ss>}wGW3E_T!};4(z{h8GZ3LI}H|XL^#iuXh*q(Bx zk5URnB--$OUUdEfzCBwR!6(-lQ{mG~6UO)DBjz$&OW>o9xG5%Q+e>UAU`GK5gSA+& ztCL)?()aTfT&SUUQ!J4`MkWxkP9lf=lXa|*CVJdx6)eYbVhyaaJg~&p`5uoK{l{2) zw~+r1%w>#Zn%|_I&L=KKUUVHTqV!`5ZIig8jLMeg%@|tjlrCXwRn=rf!WuAAk=M59 z7syGgel6{iL;guYY!rn`%HY?#9hk?8ERIQ_T8i0H(H$THi}YJ+3*N{Xh@43J1#u1| z<;zDY1+olW1*&_DH&&9qQ#jGlX#rUyv{Xm$HLP}lZVPR?HF=e&Iw4|D#%Xn;xqhm) zpr|m3c21K_P;jlFWKES~F~k``(G3L!u>Vwc;OOoqa9fADiBF_pN~=9Okx8{E>how< zn-&xK4zrg`IYI!MSOM{;do@ah#@_$O+M9q=`MeL~#}bEZ*;3h)UG{xD=Qwr;$4<(= z@B8i`l_g2pRU#r%N|GW=qNoUwrKoJ#x9pt%JcsJ@`F+2?>wT~5{|>X=bI(2ZbI&~U z%-pja^*?u#5h4fM7ycQxG4uo%eHZ4pd z{9HZUH049YP)KZm1|<@Wl*V8KLe#L9XfrHUQ$0k-%rsox5Q7xcM2efLtGQw{vF75g zPG0gs7$c7mjSvDJT0InnvNzX|p|qEfaxwLi4|Y^Tp|QruPz*}S0&Su$jzOD->ANFC zFlb;kd;kn1g#p?0!~eiS3{2GZC^1M6LP;oBjGCDlCKMeGv8iu{Li(7XJTw9=EqsIR z-PNryCIFOZYmO>6!%@X-GMH%Lk(DWgPYW9K6C!rS(MpLMXL0 zkec>d{#X}1T`wU!(Ey`RFGEwbirttD-&A1*59qY7AVjN_zFV;E8i3U}y7GjE|L`s47 zk5#jjb9c1ETB*5e2AD~h8oRjYyI~CcgDic5Wc;N(b)~g^(I`<((GU-J(;%@hT}=yl zfBR4;Z?rb0sk9+RP0iiiOU=SiTgF6M(oM_6S=&^{-&6)%)#$ILCgG>!q-CXU6zb|} zuPu&pcMlZx3J4Ypv~$FYhnNOX>I=D`jb$W#E$xtM_Q4imav1Y4S+gKXNkczV3oR!n zbr~~JQ$GnaxnMUF19=%e3yol1b59+6OI06hh7C6oxA%0k3USeK(D6e0hKFISG<;;Vu`(8>l+u_0ZJ{uX z5mv|*t!ts<=40pSXyM{+>Y*zmC4rGL4GBb<$@$nzgzD&{9VM(>L-f3Tu#Qd^PMS!x zy@ziYrN5trk+Z!I*4xJ_KvT+3+T6rYN=D8Y8yu`Dz26h5>!bg(ANpUqI56aedTqim z+aU<7uy}zkm#{sP@C77<{~io=g#A8-Xy@y8ny`uswi19Xo~PY>M8gApMF~3;efN)8 zivB}s3j3`CBy{NqpH~2bexpT%a8r>T^mCp2doD!XK~D>VZUlm6Z9ta|=5K~4 z$sZN;{@O0|V?EF}3{r>@N+o3f7xf@$0}_~1?2n0omJ=HM?rXEaR;s_*wS4@;Il)8+ za13UwO8XNHFcpJNClEffgu5FJ>>&-x{?Z9F!2>DK=!q~6-`~j%INaZy$F)Bj2lt0^ z0)g2%LJDHQ>uDI258T;p=L@udK-l|x_(Zg!jW9kQU|bIL`1^Onf+dyxr9Wtt0v(k+ z_*?^dIr;Bv7(v;DLnA@6lV+95|f;hC{{vh~gPd$bp31R5coc&X)zX1n(`Z)E#ij$}C?+GBd848pJ zP002gus-##sSt>ZOF`#U|N63E4GKiTxmM0oa;L?huq4>Y2s|n1;>`cQ1PR3dUlIfd zYyaPJ2#)Xm4}ykZT^dw6XeE%I{osP(e{BedT0OME4=8&N+T!o=;en2i&^{qOfWrO; zcc9E8oX-Bo#QXPK37w81^hy6H>|gYu)qTQi22^QaR`9f?3HxW8g#~~%u)ht&n4n^XR4u=kd%>0{!U28QKa7+-H9`wmel=|C2?SqEst^75+^S_){`8hz(##6S)wK4m5=Fy6kBX zpKsD4KHsKAtb*{3yL1T0FfK$L@Rek#5gWjM2KGL%rP9=hUOXQEe`BFy(?K3mIcmfh z@Ed`B2J#PsGPD4F9#B3E*eSqciy2Cl_0V5NtpShmkOh3E1A7D5+xKY+;rk%$C_{}v zl+hx1fPVw{rRB5;7Elfv*i|6IF5uq)X+^+~2eu2qVnEqDfOn{rP(Zr~Sa>L)o5Y2f z0yvPraggo_(z1aa1$0e78dNWVfZkG%&&jD(&CSWl z!PpzB?%Z4IUhWT9(Rx^y`;eqtiP>!OR-b%~e2if82dTsV?zz*2y((dC8K}PrJ0m z63Qj3X!!Fpr*39l?&K$X1MY0R?+AnOARvBVFiQl%OL#@_R zy2erOL)9b(a+qJ6sz0?t;;bat#5TVeFa;?!1mH$*giBrxL~JB$mIsiG_!3CLV50_g}7=WNS#WLvz6sM;kCE3UQPj_@2986HnY1qVSQs0dEm zMm)aJmh*QU7K1RnTG`mxcspB9F9skHL$wH{9t1||;06W;@ZYr#;Oy+|2RM6F8*u)F z(gc1uOXVn305Ifma>xS|pj7z(AvNKD$!j~R#H+-~$$9%W=cp~9MM6fpZ^%H43XMmj z;|V6g(D177A6EYcI3+SRGbEslkRc@l0wW?P-H*Xwajo8a-mP(e(_rL)c~Arlwg}rG zl>(6Yawb1WNK8)VNbJF29H1fqZv+>n(!|Bp1U)vgnTMxE2}&W< z<9>jU8f9v#{$EpJ?Dp|+MsC9d1SbqeN5{cIPftpEhzv%6({UOmK$QLgkBM1K7)wvb zrKgW2EJFPgIh=u!5y!~L00#{QN(GG&2kh@uIyyQWuuv+ɔTf6Q-20f6&r*Hz9x z39vsYba0;Z-gF)~-S4!66gcQhPi1_{I7LBE3cbp}9Hg*_jp8SiSU?L`Jw{6gYut!b zQQ6sOB%s8MhVB9RL1r;hNkwIEXA}wp43)hD6ezxNfV8&<5>!+m5O})99T47uf&?hY zLLk++v8NKfPX{)-6a5cDjiZeaHf#|ODiXGd#}mE^Pbgzqc}9hk-)9N~LHK-$OL!$XjRvS2V(+R z*ytYZpDG7(p~ZvGC2Rvf2|h`9Ja7(ZkmCs=2b94>5*=jU7cYd-xT8u!!hzpugd(&Y zDk|Vj`prWO1Op8gPvCdwH`jjz0yx;m`0Y00aUe)SFrYjVf}jCp9}c4hf`A?pLW1oJ z9SQ+@F~9{64@Dpo^QWvo0wLj0jf_;~*rym78HvLI2cQ!C{UA&=Ix;evF-=~4mK!L88SHV9F z#%hmmj)B3b=&$KjCV;_6r2S*oMhJn1fCd|7AtfdTQDS0JmQmpIutc-)fTsnW0I&dX zU_d11cbMSE*s_2QW`nd@f(oi+QqukMiQ`b*tRPOz&CNXwq4Dita z-Uy`=H%m|g0+)@rjV{ArN+=YH7or0LJM9Q&-;aqwAUHYcUd^95FFK1wJ7J;D|~%DHK0wReMyvF}_rLVCW;(2*IHI5ZygcZ%}>zjzfS#sQy{G zQK%S*7(|zNpA5)HCf5kD3R7uZq*-iK0f21VY)GPHETd3+`rRx5WsnUpK*nMV$Ut<6 zL3S8IjEYJO0RjhxAWsk`BYfil0Z9Hpo&-3k4=75I>+gCw5IZ3qgb7i|`CWeiAIc9v z00qDg@Y;+LQu$p7yjip13sc- zVhC`^0rr0w=shIJ^gzx8fdic1@ZWJ5p*mnNNgf_y33(uT(0i-;w>)Ci1A4#%)pAhZgf8bVA0P^4gIWQhC4hztH5X1!aT*8?BQyXg z05t%Dzt8YN^@FyvKVl>#9XKjy49=*ico=x7u&P9=u(BvcE3vSeN13y-p2MAEg|R5H z!0?l=Ch;&99w;<4i5JsSAfw?G2ovB%;0_%k2hJ%~E2T*#E1U`|D;&2T6$QaBxFG$$P#E(qligu~gPCP&2%{>0=|5kktH4k=1k4}ID>S%}+89X|MtU3_pSrrbypoQ#wm6dO2n9J< z)YX>J(AE}Uhrt*@;Rq?fTkNF09>B#aY*R3*Yeq;LpeaKx;{I2@1#4$7+nVbs-iwu@@BB(JO$w;ea7iODFeDdX7s+J` zc;+-Q4MR||8~M}Ao0^(h%7fA@-;R<8Pb9Alq@=9GgXiJV ziq=+h782bN6~a>ptZ_CbL{pFeQel8|bQDrdOG`&W4uRkfhlNv8`bSY86OZB*5D?`D zjsUNi76!p7x8JM6;c}vMZ|*-ArQ?^{g25u7h9k(x%?%uQ8O#(`R%QzRfGF@#Z;6M2 z1_g!iFg)mj=@vnB2f)@rGWf?cGOm*DFftyc1Mf2j9S2C|fU<$E@1Tz-bo7hRyAJXn z7(5{g8ZICJp&f<6c1TwtDn}uDt5Cu^AO)FqLg*;tZ}O`k1lWMGaX@82&3^|t00x+( z0}L_Z0m}a8WRVVxX2C22GQY>QKyd{b&|c)wk%EFMjG!kbBO{Ime-5VFNC%LhM2d*! zWaor{#5u*2#W}2k+JdZl{zU$IVmcU%n3z_mmROy=m4>nks6kjX=(C~)A%jNSpwS4d z4jO?#>tGS!IfzI`W56@Q;T|4v8G0EW88TW5FyDi*umHY67bu1R`T-aR5fMA=7~4^L zm=Z7`1w2?X9L|N)wkOlk1=1lUvCC8E_!9XM19r5@Vj-V8BXL~+D2DDx%bnY{$_d@coV5w$_m=Vo zQt(OoTVJ=o$}ZIB$X2~jeiY#t&tm7wBvEu0jbnMS{(zm^USX7rYhp(}wYB`UwlC8L z1L|CUbX2+Z4fzc7~EGae2H(WEY0}^RfhszaJ@_VtqFmFMRG1&h!w^Gm*tC zijQO&d>QUPc%JEG>7FZYMtfPeoQ=Yu=-%i8r75M`7)o?Y zr0k4VMf_uUKsQR#?WC082e_)bv%*~M-0oc4+|io@`kF=2PPcR~27S%uc>lt=i8Wn1 z`nWAi;kyNAIc#)=FaErcVQlB(F)M@KEE7zot@m@BbPr0g@$su#;xp`nDZ-NJR_)6L zXPbr799}KwWIxq4IIdyjBO~3BaK=|W7gG@8W;R?YCC5$dElj4Fth`fG$)Vf9z}#*g zX{A%{rnq*CZQkZ>c)U(|vZX}z6-)0JiF&o#``31(-T9AV3e_+{JyV`xxL_8x@qiqz zK>LzsNBdVU_I3ZL3@bSH)338DGB)bH?aMqBaRmh#8HMm>Ov#ti`Y%FSSLJ3H?8v3= zF!i?uzUq>XrC!vdW4?=fRd`dYhL1B#;t5ktZ{A#WxTNx{WnOF6r$c%3BaOqis2-4{ z6f;-ZD9lh4K33-Dt}D*E|7+mK6R#`b#%EaqW;;cOmXz9@djuwn3kvx7KW000UYnDX z$@iI@{Bpx3qNnG^s=8L*%DKe_m#jmXoj!?Qt=>pEpDO13sG(S@#>2^l4A{|uuU$RR3`CgI;yV6})ZX$8J zqdspr;UZydcT2|HA|qBi#|ow3Uyoi_{v3H_M9%dA9-)EWdKlbh6XLbbI~J0HiyG0Y z+x}h{w`ueBt;N`hOg9}4CNvY*@OApja$6RtlAj_&t<$r)_Zjc7@v{}}DbNRsTF_cC zC?t@oFxnrIJNg~IxJ0M9^tuLhKW>DEb=HpPES*iJ7L^{cB+*3UIGs@A2^1@l3WII0 zUK)cv)6Ol}oe8loDl+HF``lI7?)a5qGu$^ew{?EqbC4dfloZq2E=33BqF}s+F4WXr zqdry9y7K}VsRoQQ7Ej_+*xMS4xIf`e$Q!Mk(61fKntrYEGa+Cj{YOfFFt=xn#@HbB z{c{?}Y-Zt3$161(+3p&5-MU{bS*lL5d>OCs66V~=408n|r~m9EpevU$Oms_o5RCPb zZr7iDY~{m{M6Vpr=l))`mb`J#yJbT}@U%&nl?T({lU36l&hI)c7bv|0ixW^t-!r5~ z;}SUMnR+kq`<&F0Exg?s&a1t9Qekd5;=}IyVLjfK1g$%gJXrUkD^6}v6HhKx4!;_< zaZ5k*Q2*s~WXnWMzsGnY^D5P1K$m+(^!Ki_)e%HH^l9k|)*>7?UWBe26?R2!tX#4) zH0pL(OdUN;BdgH%BkP_P8xb~8K769CPj#y1SK+N?_Z0aylipriHpI#z<2t*b6om^HEX3<8Q$hKK`YU+ zd8{;MoU}ZZZ?}?jSCM%x{-QF`KzaeST=B=@Qt{klZ^QZQe%KA&d3&KeNBLTl-|a^& z)@x^6PDYz}qtT=#t2chVl)E9LfBj)c)yd4wVi&6`4mq>x&EXFOrYKNS&N;@8R+(>I zaxWa~cgg;ceDp@IyjI?t{^t>l$f9)q07Lz+tM@QrycCJN{*=65g_b61Lf*iVI+F0` zL{LYYTB+yXd?UJ0A~YRXFdqLwTXw?&F)nuA_!G4n?bk1prLr1+bPY&G!41)(MCMwD zDH|;V(y;cx0w*$El({|oQeQIlLeq1}ok5kTPZ8ZHc3iE%^YZ-03{nua zmDadTB1|+%!b+@id{pdZpGJ(+XIY}{h-~%A*IB0+V^5K#rpo(@G}13l!!E@bY_do* zI3BXN81*6*E2%4+YLc7c+*5qgq<~ktG%^20`QRrb$95IyJ^kf>5ww=3KBlylJ4QSNJ$uNdAXiK2T-5=h*==3&{@30Bx|glO+%mOCj4pc8JezZ= zh39F2+6ygKl$J23Ut-(UqC71(BWbP+yT2~a`8}mbKi#G#^=S9~WNps_cHEGRr|^2z zmue5qXTx^8SF6?g0=;U32S0>G`nd$H59F0Bs5V4>*jh@e-(4L0)KT(|sB?Qv^;ezC zLjI!=4jZv=l${ZKgLeATR4*>w3Xx+SKEDvWEwu1jWymz>YXp3it~6bVhoM>IVzXW7 zr9usd!RXz?QE%nVL&;-@{NE&bzBzp^-K)0q;$vHzmsMF|Ap=2k?Nx0F!tIz;`<`l& z^5kmc$uG>}H095uqNpv!n`HxYI~uuIJRjFN+6;wH*_qE540p?SY}I*Qs=ltlQdn5T zgbp1OxHJ9o;gHZX_m>N0`5P2Pv}tT}{9@167ox83d~D7&)Ecuv+@qDg zHFbBcbr8MGkv+l8)?;zygxJepjBc-F!iFszrZyuA!@geL8@rkEH2h?ZK66ZU!dO_@ zOi%F%=j85+Aq;s~eP^D(Ohl`R?YFz~HS(wq`dxd{3PCuD(>s3S zd%YiisB>pDn-H^xTqb_Us8PvmQFQ2CqL4%*y-@Pr!Xb&v{vGO?@4_{|Z_!UuB!8bu zMe&7}C4IwN>cmf0U`kVnjdiqyN!+rH=198U8m+Be5Q*`8!XOc_~rM`YywvaS`%0oq=})}4X8Xl5q<8AOhz;^nRY^U@xRMtSgK9HnFeG!v`N``e=$v58^RHjS^_dvI)K)1qy!X~iTe4)IX`w?P7QizApwB!EFe zG+~gCB7`A%?*7z|=}7GkmLWd13u25qDA;3GGKC!$93*1x{X%Xz0Kh*m4TEVpYFKXIJF|IDqe z@E!kTo6lNNPBB+{NKNmdOn0mes*;mT3a^{oCH_>9*mF*h_-0H+iC4?I!ZE$B&kD;9591PbC)YIAA^?K~xtM0K_^}^KMWYk}%i5KP;#J~@C zX_2B6mG)$-M${sNgpY$eLylAwRb)qmN51u!;m?h)i+TOsBinA9Us@?sTlc5Ui&lwm zED|P;im~r9Piv>1yyM9$eNpe7Tu7n2nX#2SqlA!^hI{WvMsr*9kJ%o4`r|9x>ys-b zv*_me@9|MS4ac2MHqXWsRu@i3oA#LKcWs5X%N`z%uqa}fo*;EJPLgrRy4dro)z{s3 zc!=UevKK91=6#1XTgsu>mhXoxY@E-(Gz~YjAbqi#RQ*!%#?yD#d^%RZP@~?7Fw_Vd z4lfpXLy@BOPNL-P6XENf(p3T8o#Hq9AIjfT^UeE(ol?~oT|1ROL|%=c~jw?mKsr+_JxIQ-jfCFYr{oH+7tN;{oBf;6S-3_1ZIA%61o4uJ2Z{^ z33b7X2fIf%NpMPFNExL&sz#I6kcc& zc3$izawhcAQ}Wc2(wbJBh$>7i^O0iXzlIcluZ2yyKIA=!pu4ybmLyQ`i}2GjF-<{~ znu>10>gSMFeGYZ@^)vIAy@tycZY{;O(96XN?R3gs!nN*Q3vcr)lWJ}_*0`8{V(31X z#Ng!D7p^CdP=-?*l0`67(^Xs?WeeZi*)Zh5MXEa^|G6XbZ%6uhp$(! zN=Hk|Ye{Kw6N^)dUo9Wf<_+KnW-mQWnpzJ&onozo4?0}`c=&_e)#nTqnTGVuir0^- zRQglR7QihEcBIj#=zA|pem-QwK-PHj&dDEaL@r54m-e|M3U?~4G3TOs3txD|PIGD$ zVV}*;SD2azvIxlZSzb(*=hvJw8cKL&R?}*CgW8E*rt0guxg)dMND)hWZM74G=QBEh;V zy@I#vnqCH9kM#eL^;&B8bGHHJr^2fwp!A0(k0WwyK*RL!TY!lwnGJp>8tQ9OQy!-T znkZ^*Ewm9(%yWaVB^)fSz?k%3ngj1xpt?n%v5#{g^xIA_q@xeGa8KI{{G6&0xEn0Y z@2wNiWHB3Qqmd?|gR^JJEg1U;odph`7B(&7zs)b$O^OXr$6P*s#@>YfEp@O%%Q?iI zs~*WM%xE+nn(@9ly*RzJ`z$|(&Lq9e!VsO5em1<8<3_$;cFxVSSI1q(>pE4GUJX>a zIKSNdx{_gh(b&dD^ipgr7v_z_5nEfW6G;}NHyKPH`88KomOXnBq^{0-+WhUX^=6ep z*p;5K>L-=HgRHExQo%C4hcCR&lgYBFYq?FW#EyGw|0zduOpaBUUr+LKpa1>BLffx9 z)0f_+`#-3!-h-!g?BBv%Zpg<$9ube4;NaOEUc^v;8;QT)QV&&JUB4nTJ!^O2jH;_)3=b88cb# z9@FUHczW^TwJ;o+M`o6d7!G+B*|dGFun?7{UK|lw*(LT~%!=xhd;m*_hlJ$HU45a$ zs>U{!6nHbKyW5AFF2(a1*cVjCa>O!h-4s?S7YekrKE@_u#1*P^C5iHzntysm5MH6& z);8wUrHW%0$7rq31+>W=I(ZU1(w~))_Crd{JB|ct;hF8sA`&@fWuWH2s6&c)Mr{>s9 zp~IBPk&E$KgExr#7y$Tq89jY&&Yi--IQbR91@tF#b6L4qgM4P6uiQ%EdPbQ)r)<-r z;ftv3RJx$e%~i%ojG0+M2e-VsdhMW9E%OI$Ln-OkMz2AoUEC@YOdI*s`=k*0ph6^5 zF!;E5(LHV}E9-5f1q~3A5vk8sO=u@EDAaA5JpbYJ?B($ow~Jiri{=&S{oO78jZ&|! zGMi}NK5Vxh=^*N%QnNCA{J3}cIg`)l1b`=f#qx~D!un+CJ$o!@6Iw*9Gz*G+H?OKK zA3tsZ6d+1UDNF3_uP&_|t>w2oV+Y|xR=%F@zVL>l-NRkr_z8i5!LmpNqk@PKVOCH* zv=`#i(pn8XGA=2;5#YCVgW8$$v-5M+>s!9Py_Ni+^%T7lS5)-EscwDOzZ?wvAQgP& zYwtU~q0XZLRDeDArR;)&;Kt}#As~CLIU)}?cMiDW)ZJwDSO@Sf+T=Lp<5ixn@nZa5>WC#hGZpTuX`xyC`2lG4z2 z4&(5HZ2ZW{mZ!|Yyv?$lEV@iRR6msKc8NQ8e${+l-zfcX^HrXVsi()l!+@Rhs7e#@ z_hPwRg1qO1+s1-|KAAtbT2w8GJ6l>&QJe)H#>CXr!ObDpE+Kww!NZ^qf7M9hHg4qR znY}v&1y^2wzSu~ytDjOAIc?Tr%$w3icyV=2`VEy|Jvh5W_Uf~nXK1;{+3r`G6p8Cq zw;J9><(Ui8_4a=%FXi`ecV}6j@^+9Pz0S2Z9Vsr!URGY7U;jpC+OD+lK2^boFA>_Z z+;_SqZl$NEw+p?QarO8mJ}2#2x=R6j(ZaFzCN961t zHMN&PV5OWhZtO+P^g3X+(3EGSo)i4g{P8AvQ)@;K*u$wJSQ+?yT&qTxIX{($~ zspQ?uq^$*1~?|I(SX zsW@WhkMc6!tNbA~zJ6wb_~R;qK@5yyzs_f2LOUpwkHqRn|{j8c~G+t>N2vDuC7JM#C(a|C5D%}>mO%`K= z5y;>A)MBa|J?1MHO-`d4e&g;)#ZUyr*f_S3%u59Gfc_|(?obT6?Ua@U15d4E6Dw2B z**7OoNa=z%+dd1CL9#w?gf-(0`TXt3QP5|+{dD?V?FW=(^L9v%>QG(&v8|)ur3^Lw zt>cY&$x&DKmRAf&V}AzRoRCv|pZ`m_)^V`^I`hLV0cqvy*4aD!8RPcd61k@+(ixeg zPiQ2S^Q3jZY*fSDYS0o0yfr^1fn!!UR~t$c`C08AX5Pb)|C9IB-65tiGG)e=ZuQrv z`n|u>P%4w{GM=JKFo+b}u~8FyUzFe?TDqXp*FU2%VPRaO{O$8S)i-^d+n;7a)L&cW za<8MR9zEWe>&M)Fk4_wq*^9ufSWisQd}OShs2KX_v$BljJ6;AJMbe&M=H@!`F;+>~H`Cri!S9ke{nlzg~pbaTq zKXtreJvsI5+f)D6xKm>*D7fEB@M?{5L!3j`c?t(rK73KhqqIWqSG+RQ@2hT7vjqfI zTU-hA4lF5U+~s}?S3VM~G%HmM_M}P8j2Z-A?2&!`B<=ZLFubsBeMH!7;#1iT3ToN=vnlNZ}G@b zv}IUW%Y_b+`hk1b`Kn8YR08IGrUD()9JH>jqNYxZyx$(FW56VKioY*Pwo@YysI?AH zpl3Tu%Q2>AmAzgyHR5x-+R3Nq*7CKv9d93xSIZ*VI+XAEV;N3Tj?{NVXRPcv1&6mX z7&2~gpMJElE^BOMlK(**5kj(i1#b~{_IcxZhaDaBEcfs3?(U$B!$B_xA75ChizGpt z!cvJ<%ze%Gqu$xiCj!e?HifCuw-Y!eU-cNjym7nW!OJ#P ztyx2+jn$IQTZ$|F7ZzUTJocT}3;XDkJGL@F-xrxnZ(@eBHLd7noc)q;S%J=f)oE=; zrVgV}bLP_b@AOj{3B9i5)y`$ywMC15bA5uk#+Nix0_B+K7kkQz&(D#?(F(|T_;U+K zb_9z))e*^eF&j!}Bx=UH%+N4jA*$zU%$D-jOCIbu@u?bE>N;%Q5L9wA|A?~X>)hF& z!jk(+8{AY@Z ziHgzM*dr<2)-Qt@sCboqYo3bLR6m+_v-cdnqnMk;dWWmFfsz zyK$-{>(|bqV)P3);+ZAm-r3rM*uAGI^K_O`S_@y>HA_oJK~sNMn#L;sVQ;i6*q5zC zUC-{izGeP;0<@e-%wWX^or5WSsstSebwRpchQfM#vCd-+WOi~)*ngl3QwF4QpgyO zxtP1D7eG@XlHE3A)Gb*g!utO1>kr`A17J+#T>TZJZzN|mP1#e8u3Zh~C~7ZA$$jGL zE&J4&jYc^o&*^KEWSyU4(j(_+qM%R85z&z|Gz*3H(_PHy@G~Lv1&a(8%I@*!OM_Wf z@_of!FBg2Vb+V(075Y>t^ZZJM_jQ%i%iPXwGFlegSu3= zK4;&J_~XdA)wSdT`Jj(}OOvPf)C5=^9o~0KJWF2zeeKH5>$)A{ggczipM{QZ#T7pY z#JjAPyh_t-e|A}QaS^M-lDRG8v&-ALWy-48WuP5X1Fjt$kXhixBfZ5<&Y z-FrAA_pSS9!U`D3orn=)VP;3_^HFxR_wCfZ zz8@lb#zRQOrs9bSY<>icmU7jK#kVBI&%_Zo)ve91UmNN)D$zZf!7=#(-8LO5z4FqT z(Pwe_(}~eI8aBuBiVD+n*rgrywJ-7L)`ICltDn5;QoWnH(b;O2B|BUX?!4kV-*nAb z;mC%p(s$y>L7QV&_SRER9iAY&zz$Rsk7}yr{g*@9-d?Yi_8^&Z^{B9Xlzr~j5|7ZV z9(pm2VKM82co>b#muaU)I_&#y2C_of+|`mpQ9W{1X_+i<4wZ*aO})L|ke`@TFXXPE zrLKO+DMK^QVdrzFmurCHnK=bwNxmy5M6@v^QOeqP!=pKql9FCbyB=j`jy@FT*MYkp)icimo0J}%r4Q|WQR8)YQg@J5jclMf zC5A0;ErVTm?)+b-XWiY)3@1M$8#*VLzAAV$d z2cystlz}(%H!;q%KVUR*PXapNu%y=o0s8-a6amcxlDdd(~qUkAr0rXu03X}x%gb+P8#{c>X^)s;@-}vjwjl& zQ;D9Nhc1ZwQCN1`FlMBuXJn|EcsdVyv{V+vYhoHK3!9dgDcg+@V0WM|p2dKN4u0r; zNX5zci?Ayp7!38I4X>0LuUnr&Wfv6*iDC*13z)S+4u=r;X=|%$@AEt!&&Q8vMXNb& zP-LFjCTR%0ckDaE!uiuil+@JV(Y)uRE;V7Rc6|-(<#FX&?zRl9>}bpH zT96iEzAnptnhDOUpm4__YqRP`34R3jidNVBG_R&!+)tn6h*>$%=^ zlUa&W;(E0%VNbG-iavGbkVniR@X;32TUM)%xZpfBU#bN3NB@_(gAvs)Lh?u1?e4s3 zP0DV*)Jr3Ms(|tuuGxMjAp(7$lG@OZ>7)Gg_#QEt+23U)}$3Jp+_L}vi!@-%;?p@F)5&`~arC!M69jF&o`&96@64P1MyJn~BbXp^;^{n3;FUCb>R{)1l5c)Z zodvubw(o0mNy`jAD=eNpvFA1Khow3i)pNRe=Hv^nG2K%Z@g}U<0ZPKG^EXlSt*v|~ zrmB*QixJJ_Z{^-wYR!98_I&m_`|o7o`aWDUV0HJ!WoFR9*s{{3(ql7 z#=|eNs0&7-oQXTaZFbT6b<4B$`bMdXrh&HAr= z*0b4r$DUXHVUsIiNrBJYb2MI%qzO@#rakM@S7O2$Uv;wY2(P}USl^U~)3u7?f@fYQ zZk8CFym2O7fQaNUpMQ>Q^70v-%(xo`X&NSa!5H!Pj%2p)cS3w@8s17SAtfR(y?5?> z)aOKeq>S+6tMvQ$hrPFnwMi7yfV{ldh!i=542E zPW~3~z(W`FDXBfxeSgIwn)x1!`tDwQT-hXacOas)Y`N~K*V^#U_vccs6_A+*IEUxl zwx}TwdV5=TEm)>-O`dGxc5Wko9M4#LOGHUg`XE`bbkPS*g+^)X)H(*gZxYWvpRsoZ z`ESLFH+09bmzXq$zB?V6b!E4iT2IoMUqH~?dZDkdh68cCyPJmT-O=oO9GMTijc#_G z-wsY*J)tRg^@VRQZm5Tfar@$!ur^Jw=i)HMxtyx&4q!3zq;De2`#YrSmj&n^#YB@1 zX!m}(oi6NWTsSM)9?<;y$@k0I&TPc2G;J}TzG(hbw9jS9j6@?{Z9LYguL(? zWqcV|wMNo~HySiF#dhzze2*>bp7>DuQ1fnP!Alk0Q9ip_auehu4tSH>8mdL%yYQ-` z@~IHPnZ_T^_9ES$jH~AdUHn2CR)%s-G~^sp|Wu43%rkLggfDzgyOxx z>Be*REwoE1H@@Ab%TqBDwwt}w`U0zpVqdf6=-QTxafwYJ5@%1*;{Ha8N}^|YODokX z((S_|AmwM|&&hLYlHqe|9=?<<+8c-43N=2f%Jkn` zxi9;wv9S;IUOm9xsouy32RfJIBy(TqP9uN{8m0{{{ds`0jjOZ^;ICxfS89)nPywa( zKYv?qE|1*x6N07fq1g<=ca&L{W;h}_;s@#wQ%&3%Qd$1f!*Se#^NA7P8V?n6(hMgh zotbI$`Xp#JSGBjWqk6*roaEN>wItle$Br){>rroCys$ofj}FUi<=A-|&&+hb=P=e7 zj(sw<@IyjA-XgiKJ;U;xPJ(3Z1%8qfCddy9k(bJdrYStysdZ+SbK{;quj_7K^HGm2 z=FH-Ks6554WII6bGh{4z6*dtkFHy04zr3m}Z`i=O zTxo`~FJE-X*RbJ&N_2+HS@lNy%5%+u;&x}%kk_tYn-67tW9{J&TDhFFb>6O7F@>ln zJ|vftIdM^U?Pqnf^rl1jWSGKjeAe#D{R6w z6K&)rf1UN=(ru%JW#v)NgvUCMAGp7&Eewr*#F>xW#QOGds&dS*8haJ#UqG;SN?w03 z%NSbL(SaV4GnG}EeqHNdH6MBUeCqR=>YS(b>Y>$_=JdPAz8s3R)f3h=diu@Wdy(=! z@oS{a;*Gs!ai8KR*r)TQCt1+>3}Zg;R_XTGiadu+MYfI;MT;q0?3p^vms3Wikcc*h zh#@BKNvt!i;^U&X+x_T}_)|?xCym5A6|iAq28G>e<|MvG-+kHU(Ld$-`eJ`6^u3jE z`f=;xOy7gfCP}YbkNphtq@z!`FVCDW!Ob6;cRL& zUZAeO1^v0<`JSU${KJO+U7sfxmSi=amAI-f%#uX}&SpB%^lb)99TAqXEAusw9g~*% zmgZ}4ZW}*oLS{l1_2mnnc#l!mBy~*?l{LMaxl1D^Yx1;g5XmsMGydy6wy9a$-D4!) zvD=&vEBStwCokU&$NZ>&l2KXWS+|zjyH}}PUD)}P`&T>Z>A1tU(<>iXkFxiRj>iXS zb4(T+j4LXYbwriFlG#GpEnf8~aBt3C?$*4&d`!g&b{$E)u3kkMkO50=5=!n&vm6MH zTP=>fXkIJN!Rwon|FPvI@%D!kUBfLhCx`T|s#p(~l)atVY;9JtHC?+YS8a3SarmS6 z=IxgvlD@ylKrenBQ$8EDcx`+5i*cn#^HX}KA-m5*+}J7gf1)&u+)*+AR6fU z3nhl&Z)8k|(y(4CJ!En=jAE5;BwrsH&`O4{zkg2jK{g0I##k|MVwdRYvEh8h_LrT@ z;$-XnUV~9)seM|CW4|1z0s`0b=4ZE6KSgHWfA<7)Ey(o5*LytA+AY4uJ zK=|AW|5|y?y9W1_TkJryb>m29RI5&1f2LFZM!Ve6ID6r8t)WoM{-)<*!|m{3|I70Z zbw``D7E{`U8j0_&e+(|U5Mf(n!t$iI1$SeCi$1LGh~B4`k?yA4Ua#@)7Ti^bHNMo4 z_7#fOh0&p0E&fZV_bBT2RBPAecv%`A|H^-|q)L2tlYJL9*{$ZrA076kbLplU$2>B6 zC2VKlSwDkIvvX?xq?&+o>4zXSzAoz3t72agojzq$G-PD$j>!zT{HX1rZKu_b=^ra< zU#aQ#J10u16R`JF^SQgq*^cq^(&s;}?8c2or&5FzRUGb|)X%swQ&ptO(^-(OU5MO7 z)H|*S@M;Ub)7#RzNxPK^N9-Sn~PsaE!f{W3yi}f#B|=hNo(aIebG?A{=xWUisyCb zi15LlQ+;)lA8sm!%zO0VpY6OTE>=CQ+$nKxQR$dS)YgMv_p56ezxt{O4$jPwv_A}V zF3sdPZPDxR!{51#POZY?e3q{BGONkCuA+prCaH2zTeP!(zNg(DX3?5 z3${1RI8%RlNvZyLKq+rTSjHN^kSosZ-IkP1cs=g9R)G1dS@&HT0lD}6HggNJY&T{T zC;D(Tk;=}>x15E?;x%ZI!M|>;h0?X{M5C)_PHlyykJnjPQdGX0N&gsKd0*0}YA;ml zg_KFL*8c}uK&8Jv=HJnoOQ{6Rb(V*pl6;B98y&VqTSLkQ{HDWJSEC0^Ph)z{E;?z8vhgj= zldB<(%O8`;@+L`Ju%OrJU@Y^OH%Ra)8IEa?LO&}jVcNROQ?BwNawyiKCBbl%XE1ht zA985s1HC6{G@Y7J7C1`6qKBOFan66ulHN_J zK{<5*E=fBy&PW>P=Pc$I1l9}y-Sw{$mVXe7+fIq?r44JYaKL=ynycT_sEue8r_*Sv zrjbnt@nB_T(7H*A(nP`lI!wkx9z@+iOZ{#G9>?RAmGO+iV^etC5fh68*eR??akiB8 zOQ>%rABzpc;^obb8rDGUp{NCQ!pqj_@%F*V{^|bV!R6k;uH9MD1Jr?8k%IEm^p<90 z9+opFlgk!txWRztr)Cg)tRK>73d=*Vk13AeGJbITXa`q?Qzam<(r5d-ZM$+3u>pPK zfBh@mq<{J2>xAF5pi)1(4PmwWSr0K+;K<&P;?L*z`+ca`iS#`A6x%(aLs;W1f01Xm zs-)@10!cKq%_YUA0Q7_>YaI3m1;BUG>u?#!K=6Cm1~HX&Sgp=YPOqUbjbXP!(d9U1 zU4}4%5x0Y2%JX}T;AZ%OCh8#q=(@Cx`*aHXr*~7@5h78{$3kuw@DTrPni-CoN2-Ah zg)sxjY4wUCETPU?U$qnfrD-TZhY6kuX*^2ug1#7Lu)%>aW#w;XK%Y(~Sy#}4Vl+&7 z2vk2h-?)I*StVtYKKoR`8mj1?kQo@#go!$7Q3tpx2)|%nlL_>~vOYZpstKclzdJXy_hCm65K~K% zeoMtuq)RMHuNCpMr$B`)w0g;K7&16XBsOL-J5Mi29#j0Mi1U?|%a$1>P}^=muj-Eo%H5#Q`E{X>DGm2eJ+gsd5r zb{9^|9Cwya5}O=*IDo~}-i8%Ra_9z2cQ0G+Aj5KQBsRL*l}<0A z*+$ggk0uh+&Y*S8TJ&~2OgMG$H)dqeqMvZW1;8;)hUZmMe-S@i!SE14+m!SHJqFN< z`n&;3JET>p4qyh7C`N!>@)$8NX~{Z(xawElN=BpMz2w*os}aGlCB_B`l;Hs&EgT3f z^^wFuD_G4*FUGl@XBXrqe%N_+c(T_Hdc&-s!D>Rp_pVCl%ar|{pDuT|Pq#0(kM=Pq z?R|iZ)u1Ivc``}^z!}qLKMt;wJ`Koi927U%T|h>0Y0Fy{5@(JRXkDuP6Z5I$w^F+~ zI|c?~L~;Fmahm9GV3c&4T6n!vIUH^>L(!-mY;o@s=23+Du4Dm@a=RWD$z!O%;oj+6y4;u=p2$c52VLE|6Lpe2EJ(-PQX_Ed%b6Qs@+*xAr!6S_5maF>!epgICHU)!=Mg_u0f?( zQUaSo>{q;d0K)~F1P_x`U^)e)O{XEQvqpMc zZUCc8vdGhOL8$t2$eK`HJSC&bY(fOd2q2&cWIU=tUuU&|-GJpCDfy=hasso0-aY}@y@HAy zs_X+D2C#s9U^i9};Mrg>r2o{NAPDZ+yvGJ>J~o)| z*iiGT?F+bKQv8Di(P_>S$2%m9NSc_IX4ryt3cD@Xw^W?wL7w!}40ll4!r?@i)9N9c zO8YA-ZZkb3Zm-e;et}>s0lp+W0frALJJJ}6qBxb-;R6WUq#}ef<(J1 z4`DJ#H4w^+78JBIjizcymgqE%OAf-a;HBOK34nH8bl4~B|CBhHvZ(uHU0&0;-0RRW zQFJ-3k5py32gs31UE~0PR!_-M!vXRt4thzRjX~lYkoV#UvEMJnA@ZIaJBP?;d5FBa zATQ#F6q^G9UHi}U83Ba2%96Z~;<#c6cgZ$LYexw*)(&m}=ktKvfjAknc{c9dz>g_8 zD>V{?AmY2C`Q%Do@T0)C8K|^CHVtJ}!lV#aXDF+>3T1+6MD}VMke%D_DR~Lw%_cj92mpR0H@_l}wo!&(YyNb}Yv<$^?|fxNP3pk;xg4Fn#xU`-e-_cRx=Crt4RS z+q*Q%~fK0!SDCEh3{?b0Dn zOwy&4_uHHL4t@&)USaOkw}q`5?o4JZ@vl%#D`b?{WG%zIgMnsuts|W$no^0cPfE#Vgh{_IzL6`TjOM`TD26uo zF|>e<&hl55M~f^3o`rAWh?iB~0vUOe7U`AC3|ncQdk6>804e7i<~{xvP~_!-9g)x+Q2!RjzWV9 zb^&1@bK1p9RU~SgM9?g!3Wf~>iNrGUtU-F$DHEebb~opeab%W!>;t*m2VMN<(9@U{ ztcU!2OB%HrcWo0eZVMI}N>orWs$jR2CH>q&E`ijUGYS(7QDP)-ZFp@2X4`0quqlbj zaF6+vrTwK6mdWX)G27zZx9yLe@*YTu9W`o`qiMrcq(0p1>+oenW?WI;N2GdMI4fvU zY@InribZXkW_O z(@^i{mSS4V*BgtVmx_}WXi5|h4@g?>LE>mr^Opbh_8==`^Qye%ioN9p`pfbT-brvu zm8$5qE&beY2k zRVxBh4gdVoc00lIVRk)v9Vp;Vs+&NW>^B@Yst`)J+&JTbp?_PIu6DlG)ef0i_w2}5GnF-)WMHs)!XLp7pkY|{=KAPSnX7GG(9%H#UF65? zm6gpc>dn#zcGtzvjkfzu=k6F6bsHz3@8Hc)6=dAd)VQi9Ul+3T38$Z-BbuzILP(@# zO!&{>Ah`u`QE`_FiWbp8j3!< zYn$!ODEdRa19c%=+k|38x6GpX26NFamnbgEx>n?kq^`9BgJu>N6kopdIXpAi6lvY9 zVq^CRtUYQs`=97wteeQ+#MMvC>S%f50wJ3I#;?jL9 zM^ch0+$6=k`wU5Z3knyiVGP>ZLb5`YeWN>sQaxX7xEJ1NxkU9EiMu0{`>P8Vm0tj% zo{-m38-9O*-#?I_plh7+P{`x;l%onmua#6wNby8o9jn73$^7OOD=RRuVNC{rYB|aL z*&7pnG+~zLL$2?*g5XvB9+vPsllYw=e)pyVB30bBQ-2rX1#4JZ{}gW-(s~Zk;S?!K znG6$#@yf5C-_FGzF7L zO+^E#lPQ(!rfu31v=BFv)k)@}2ehDdLxY`pB`jOw-nq=`b!L0u0Gm4GO&4k8g;Nvs1}o!BxkgRGIu7- zK<6B^CEle1xG7=1s_Cf2EKMpog18)s>AB8=6gX;M! zJdoc^B)k-Q+#5h{{kaR;GNq`%B)?h{b6hjlTW*Y2ok@SPUr3C|z4;bKCVTLCm-acR z>2~1f4V7BYQ-lmQ2in7O?Gx@=UD>u!^>^jh?j>lDXn7@j9?2u6BBiCX)oi?C3cH=> z$^F9U-8lGjbkvB0-#=XiTG|H+dqEnDmi$1R8c*SnF@9wW59tJVTnal5ET#00OSiI4 zTJq8o_WRBB7$`!raDPQK%gYM+Y6>i+bPS6NxP@*dYFI`IQ>fgCvsL!znwNKp8V=!E`7#wInavO<_2N zz?7=c*X7?wyu`bI;#JXU!S9C@ZFo04yTgDQdZ=Z(-P~h0u)xY%5j=8$DZ!J(sIlS7 z;=mm>(H%+10`S&^eH*NX8E}ggN1#liX}AgWuvp|~=1i~#okebJtO1sv6fEn2y%pm8 zI#h!Il4~Z^4Mv{>P|A> z8VXv=-MDiQ8XH?_q>uj$+{&}9w3FFGyk7S_n{%pTtNI`Yo&FF_VN)nI!Z%N;?$yV0&J)e(M`Poi;0>^3Z;^3R3tzL8kd`nKWrXLiqN0hv##i2}=qsR}@_ zvck+|W*u)96XXGuS$~Rm0-Y}eW!8UA(jSZ-Vn!fb=<4#(MyVyZl`k%}Or_Kk>%cWg zI&dVvouIAHg`_RX7a?9|bEd)xw*XxS|4Jjp3Z7rw0H z#>E}`2sG+yH1$4|ngn(GK;rrk z#z1%lkXZyNLc1Q0`p3TbZ;Kw#k!bcMHzB)@N~ z+p1(d0*p68;a88g^$sJ*;tdlh*}n%u2Y{TCA54?hiAaft_1=gA(U%n>+b-*3WZP{$ zvorvi1O5N#m%;Yr(d+k6kioYEXSkq`11_b_eGOll!dWx#1Az#t6u687QIkpGeE)&o zVlp^90-Y%tRGKL)JHl(N?#S|%%@-AdGABFpQd6&_i8eGNEC2x#!rgP(usIbqzSHiM zSXtBuDG(q`-K-asKxqhAfHxl3WA9lVn0R(iizU4`izOB3ZRtqIWwT-FMmh-$)&}cQ zphQ-ca2A1NQENuJ2A#W5qh00N>&1|T$r_rN&%B$WihrNcm|)?FyXTiHgV*~MIn?sS z@&%9Ft%NWhhgoU25VKn(Nac<~71_d$Jwl@EM!|Ruzb(_O%fmSP_mMFS3I*FEefy;I zquA*KIJdJ=Ma*Ozmgo8@yOKX=d#IhNcZkTXCR+5a?0^H<0(kTGiOPi)yMMz^CNuZD z&8}}?O$_GjRa)Dt$g?j6ZitbFur1*{NU}#j66dA`gWrg7uBK&Mx%ib#A$X438wIG-Rpr5Cq856{F%&G*|^{38VT!E>un95%6@*U>7-@ zv3jjzr{4lBlQC52nP@+Z9_1C{vs(V3?qqYE?vW$_|Azt3l0hPyCe$kMqPc=C|@g)$lnKT)ZEN2@tudf`S_lwa$ac+dvnNRu<0) zR#-^HG@pc4S_n&7b{><-gOIdlYGWmOK@*|`Cq6>?+&TzUAf*I~XHU#rlYQr#R zjg$~oPv}4~5WnmKkfO?dVE$CB%gTz9(ZqTNFsY&?(xe*$)X!zl5D!z59eEwgTux_Y zMcN|N+gsFmW-^h`EY~eT6ZtG_5Rnm8-!QAg8WSb#lrzi30CEkRc%w&LIcDA}uCJS~ z6$tj(_XdczI0Q`xZi2*W?JS3usl3?Ogw- zzuE@0aX@9b;hDJUN-+_P2T zILMztaM`eL8Y_KVppq-27hV>S>dM|lEA||$RJB9=n#;+LO{y2Uj{S7vK0N`%Y-~0-Kb>O(b{fBTWlsD>&QlYuwKy9g1)%*&o zniN>EtEBe<6v7H!#2j2-T3gea|OghZ0n z2$|0V`7QEgP{@5q65XXT@p$iK|5s=j!uX|MWYcOz_fKB$pPVQ?QA-8&6a^G&>mo*1 zR4ydrbe$cULh|GtkLra?TeeuWHNWx-b6m6Xf~tjG>qETgY_KNfqe$@~F0;;5si^n4 zrAaZ)A#-Rl_1XobXVNl^2SskE4!Jz0TElgX7*p;Nv>Y}Gc@U&IRdtofMP1dU$x^c| z<=tXC*Xd{4hk7Hjq<%}45qze_nn;141qX24V=*wOhiXp3C+gL)WKzenm8-r>(O&b|>Eg@##gC{?~;u5&6Sy;X@Om|rv+KeEVO z9q{08;=?PeXd;ZEi0MQ_zU)I=%j%7@2IXLtNGL1TS(`(K0-mu$9*<%r=I{C%=ctZN z$eU%)KBj)zc@06U_@_(N5fC_X#qj_3wyI9_B1ECrcnXEhf!Q-BFuSc0O`8-C=h6w# zIZ)i=40Ht6AG<%_Ds5m%{9us&=j!UF0aIV>;`pIT9y_gQ^v9S z*^0Be`lL>C7uPwY)UQSO6}1SN(iJ#VsDbPdHfIkvN$*!ynsUs$G;lW+-w^xiHH6E$ zJUHCln@k)T5K2@j*m$BK$Qg#;=|qcV;aV`vfX8&pD9ox#i4+&UfF4?1G?q7Nbil%- z03k{_tHNaULGmCG;S}(2!&O+8bMVcz$NLwID_ca01k746*rPrA0@HLjy(<54;9)>W zRz^%(ZJgFs`qazk$&)giC+lGP)#VIGyU-5Wx$+rYO~u9416%Tg!5 zh)-~IGDtwX!oYgZ;d+NSP0Io-KFzN7XV(*vcWCcn>X2q}oVImsF)UkMjK&_M4SrEG z2^Isa4d#;|Nvs47T8Owwk`>Lpdo?hu6_LElHi5;Ie7gq6Db6V@ScEFIa)*G0t#5t+ zq4kX^y@aF3Qih~^h67?ji%yb#62^DlWApArzw*fI-caz-N0K#b1L?kn{Jk<91JfSJ z;<C&bfe_K;1u#ZMvAOQ+gz!%4&& zPNGzuL>}2grQL@n%-55YlWej+t0xgH~^qqe&1u+J?O89rr<%K3V4R8|0b z;-rU$S7;n>W<)FvBZ?j#7u)6*{hJmyP8dn&8*ZF$>OO4Lvlt{rE>Q)PR~gFpLPqx! z;`M44Vcr^~^zLa2F7gdHCf=J{V4Sx==2KQ5rcAGoQs-0#X;bTCTx%Mm60N#O*aSbP zPy;M0rT!DR&e*=SUZ5S#Y3a@F$KtO+&pG(kh(1o-$X#Cn;=|P#c>5rLrFop$P7tiB z%|RC%Yz4o3X8UlU*6`6Tp`BPI)8f@a=upF&*)Vg8Hp7o_4~45C!fXz+!%IwMLdgt? zi(anASO_f<(P>SeonkmzP2;qyCNJBSwv^edXB)|5oLl7rpnQ-T`IpM7ySG{_fcLSr zd#g31%Swdol+B<#%^p*OYWv(jcs0357D@-9crvIZLod3S4*Bu8hmW?Sig*_C1b8_ zM1!6!#~SulTZsWvep||+=CKrD<#os@Pzt6d;s=;5ihsvf@*hzY z))HWezsBMZ7M+qE8n6E|?6%?m!fUQOxlJIbRyMijBe3@yP9Ve<1QVE?|8u3i-u?Z> zAEDqm{+K+8qV+*aPO$;pH`qjan+)hb*5TLH?PxMcuP5(EbO3(_lM#4>^7Q(8a!0R5 z(FC7O&qT>vEO9&fZUUPVGjF3wGVZ53^BJTkA`e`N3)q`i5QFJ2-w}M{ePiwKtLqo5 zF|K3B7&n|yjMq%0DY7tu(H1NK4xVI@6$jQ6M7J& zLGAmtmIIk3bndFy?7`udfyhq1>6<9 zskbdkt(j5>)Cpb?{&Vt=e-u%$x()VN|MM8|lH6C{gu-}17vx)KZ9Dt!vlaqHeLnK&qj8?@Ay z4teK$2-7&4n9OpI^Bw4wX*|vABe$Jg!(PGz@u=QeA|l((_Po~sEltV7SPX7BERV@7 zMqBf>5XS-5Vf*a#upK00h+Yg2WWqz2!iem6|A&{SZT+U_^TX5A!`E#Uz5pUV?7e_Y z5V&9?ubjnP-mt6qbPLYNC2=}i6kNhH*?xXsE(7z%EuM!&)vH9=dNr0x$9Ve%KZIASkm8Oe&QuSDMq!gx1CCi z1~0y*7#I};%{lg*FbT)3gnEKnq&}lb;gRM*w>~>%|1-DXCKi;}F_kv6cqPGBu6n9e z3c{Idm2)-kS8){u#jw!WRTNC>E(od+hA)PRBd^*(wGOeNB4J4eu$Crt0%`1kFvw+< z#cuVa3e2Al#bJtXQ+~5u&J3e2WQc7j2tKsjh6J(sbb@j1kT+hTkV!}SZe0$>_<|bt z(7dGRG=>Qh!BwX=xzPdLd3(&+2tLa#ZMfCAa7I_>X!~o$_uc@Va?96UYo(@JwjhXY z%eV&Ejf0Xu^}DVvw)m<6VW%gO>Ra8q(pMI`!KZ#vmwJ~j*p!OlnO%-Xa)lu?>_Sk)0tvK#b#KaJ zIRo7?{JDP zNS2)DlSg>SU(p+Qq&v$U*w^^rDG}^i`$6^BeoGhkpszX5lZ@>M-9x*4!rPZJO}9uR z4I)UBIB9n!`7={)2T}(p)xoBvO;+1;qn}?LF8CVh%}GhVm78*N@FV$3h+~pb+m2%P z;1^_#AVN)9Y5Cmg(Ap^^j4SKWu^Wgm7+RxI&PxhCI!po8<{%ow%b_r|CCJUfmLS+b z$28Vt{n2Z%{zoAUcfEHoAtUm z>!Zx_qxYi>otTIZ_4VdV9nZCK>JOy!bwQHK+?7w!qs6Lr+wdV&6?N<9t+VYK?jDw+ zq9}0FScy?o4N+vH^PqQie!qe42bOu7=k7| zRp21zxO?C;6`tNNgoQ@E?TQ9KOY4@6z5*CW>k$DqU^;xD!&jlStLwl-3!;P?6%;1a z;qQ!C%1O1tE1a2VG^8Rz66!qQXS>!XN*xrf3x)EM3yC`{2)_?C+XH2E8(3cal89tL zS6`nJ1@gY+qWOe1sY^3baiOT6$DN8g-CBy}N-aBDD+HkVR$-a`nWU7Z` za#`g1He3eHi&NJKO}h@&uEx=p13ucwkM*OP7BQP|uzq|n!wt)dfh)Gn7ImoS~@47Op4QQ&Dd^ zT}T4Nssf<08HO1>gtr$QrFn+FI-D{AQG3%SkO!@)Fp_JlgbI{ji(ux}*#Wi9XPq8u zy76eT7|y7n%1kC&od)vtU)WQtMl6gstvt+7`^_hG6Jt%4uQP?tKog99<^~65637e5EDH zYqh97IfS}wWySp#g2JwCAojofTOSiNWFD9EG#Ry3wpe1dZ~woR7(i58WBJ;JU!o7g zU3A%A&RsSnR*zpcamUw$j(D2Xjx}=Gyz_{C54|qIWzTcR5-OW|G8nzo?Ijxhnf00H z5PQ8!h8HXw=TQH#EeuT#tw9Nrzdkg_L3j;An%19J4(Ek!rFC0UyjyoU+LA_k?Lsbp z#SbDNkoqDBX#HV3FSR6@P^hnd#p+*R5R{EllVP+u#hYkN!QVlBM z@G63v`q2FMUhyW1d@o2DFGk8r=zyBnO#y87%^~jGAmPTBr7Tn@<1F!|SNPS^7EB#; zkp|0gQCqBOT^!XUQuj&VOQKmZyoz{ov3oZF$g6!2zyT6f z`zV4&Y|Njg3V3f%XBnbD+6;YPn4x>^%@MQF)O>ke=~l~6C@~Qb(Hf$sena&AMnm*( zZ;7s7PfC9~lk->9ltcwsQ?V;sO!Ep&MfYt{adl}bcWlcU1#?r`UHX`agde0CeTruE z+6*s#?lIL?nXak!bCbS^sWvu!N6GUhQ|&i^ia-sdRP~)S7&PBsq`}}jN`6rWgKxlK z@QE}SG^KuMFc^H|8Vvp@eJ^k*3PvS;m9ak4w`am~iQRL#b|_|3+?RL#b|_{_$>_|3+?G@FfmX)+tbETAFG7ZtZtGVii< zR)*1*)DO6GAulQ-`7ZYqE)N850BK|`oTQPq_H_!G&559>{VKBxK=)ghmm=%(GFCc! zpV?G4SCC$j5$pHE2UhuxD$D;^rvAjr)U)4Ark<5#>I?HfO=5K}Wqgd)}YrhlPuj5M%03DYmW7b7@7hfFX!rIa2Mtj>^;8zxzugn<(k zGf(JkZV-tj+J0WTl%X(}T-##$>a7ba6xGG+#{E#e57oDKPWRtzpTf~7#3BiYgR#fR z$8~OFLrn z-9(5xJA_;M8anV{m|2y)hCX=#xmTa6LM31!n_xw0nCzIMmgAbl8;XWnKv*qJpS2{a`E)F-g`7~2 z;^AnNA>c;|;RbHh#aWlICg#jzVy-JSs!V) zlM1$$8I<2=-AY`LQ;dDn-smg}dk4n0tx_t$Xwi5EE@DM^s*l3Qz83)};QY5Dw8E1% zxbDmFtI~geG67YXn2M6op5rb6AGZ)+E*q`pgk9*@orJY$3K%cWKn&WSkvU)+xxR?_2v{JO~!IgsmQfQdCZV3Ov*8oLu09bh2lAgEtud~|lz_e2_$lwYN5m|6vaB4PFIA+JW2LyT?3T$4m+^PM|i=7p7uPJKV(Yc9~RO-FGN2n7+>)@QlPGiQScx|l{J^1EOnSOQwgZ#eKh)(q0 zvMR+^H!tAkyH!t(YH+IdDuYd%0`6;Q9yn0q&fnmiCAY?ihXnP5RYQ1HKj$EuRgaZj zkf*Ddh2bMi+S93gEokAxUEH}v_wc_Cvr7H}gC`4_u~pe&%Kqtul_Wfu47zhZqc&7> z^0no05ssiLTIYv?2^HLCG`H+MD_Pxss#It^8I{ZynMi$&A=Q`9#9^#fr%W0ahMmh8 z&15ia&`WJJCdO|$iaE6udw_Lt*zB9W%r|6}fI_V4WxkaaxM@`C{+D0n1FxvxPUC1?7$t4x@f=323V^UnEDIW#OX9I%?0CjemKd=r?Ul|n$<1#H6h&>f_ zrX$9Hf;xQ>F$Ok$!^m!v7~@XLEqHPjkZmckxMSo%N-Qv$99A>~+pMA)5J^@uU_KAz zx5#gLl4rXjW%y8*GT;k^0XZs38D7C}{U%#L-Wz?#OQY{Nc4Y*g{nCdQn5-K;gOBf* zhUwDxOD63tt3JYm5V{~sZsI5%4(qAd6N)}QdW8|MMRzS{mbT-cSd%k)^iYvOG<#nA zJu{hoX(s%}LG)KvX1uG7Ayt~QUorDWIZ0txHNIv0nF-ZF)_75^R1_h5w0}i#_6qOv zauzZSS8!NK>YlOo3(%OyA^Py#CLicF2GT$ib9H#;Fx2zZa%^G+3ghr|$mDC4GoJ{@ z7(cdx_XVDGs$VJr(^q>K7PSD%HZK83n#Ai!0~Y>8gNIFqg7Ky+eFiknWvD6_TjjV} zk3C+Vo}?7j39>RcXcZg>K6p5gkZ+uOz<|zVyjvYMDdRC2Ms0j}vFxl7t(C<(poBU%th{GZu-R0C)YB6<9;}0oV61Naw0# z&6>HfqS?tn8AkKugvU4CX%; zaFPPUNJ&;zeZ7&)>T^ckDfQaVpkDg|%+s=4Rj2x!E@^H~YrnW<~y#{9;(o zC-6%&MSd_$=#T1`P}BX&{L#u#zkn4@l8QBD6n;PvQ#Ur2sRO@N;XiL|fQ@xpc^6W^ zOfsP?ofX~4J;V(A~^%yf8C3{T(3$Ce^Ez+8(+wjuHVvs zMB>@h+7D9p>>Z@>bT>oP3kD<97V%nyIAZ`$ppO|df&n%`LUHE|{V@KsR7r!EA=Zi=F>h(hGq5{pf7HWEM? z{~Lh_0EfiQe8TRzMWvZ)q=g@P<7sVFN}e%8&*Sp}_?gZ30hsGv*+e*?Kov|tB}x4d zQrmKQLn`+adic8`^C<}K&L^`dggk5(q5?nsZ}0MNʬb87xb>V|)N{@>%@a5VoB z5BCUTC$^~2lc$z9)O=9P>Z?O^W|>=qf+~F>X(BfLjuB7mQ@ghs;XarjGx5jdQvw>g zbi{Sk#9~SI)KdR0-NHjNOIPTc(;JTA{s6y0giDwF&9qFUFr0u2bzohu@rt9rps3iD zkhJxul@-+ZZ~c8T5pL>2i}rW;g{heLr;Dx4$>h5&kyV=4f^$mv5(YWrdQzV@TYqnD zE?tc=y(nPYBoOrMyVgc)1K4o!z}Xp3hw&x+*dBsqbv%M!&&QmDE%y=p+(~j_038oG ze&I9bBcNkf__eDUYI6X* zU1@vU#u5JBUm>Ed3YaTebegn<1oLrZCvlt8a@(X7od+U82{8pQ0H~t^``i1@?1_W2 z(<_I#*!!5Booi>GJRa=*^xY;Y?)I)f8htW4+^hHed9e4*I?4WYy7yVW$rf>y=Gk7H zE%x&2GAZ`vc~%wa`KHQ?64`(HnTn6{;^N6FohMnD>^*++tHE-U&8eWDh$^`EHi#}! zY+iXsUVi>lf-Yi(NIWooT_3F+?lgKDGsC2z4 zFGY$#iqYJn%`Cd#iag3jRep+oW*6cbAD40Y%}s{Bt&^g<6LEBH(^pX}8<&F!#2r;} z6?OaJ=_tFvwCLI9>O3jzEGDBYUnFnvfka)zO-`%iYAbGgTG-1rtJNSv!6b?RA95wO z;$?JV071;7d#WlN9E!4-(@%!kNo3$F0x=42k975W=LEwd3+`#f3Xx)d{4C1q`eiVh z7fDX@V^AS6?=WTG}my30qA0(PT$h}EF+H*i6>4Y7YFF3c?X`3mKi`UtvJP*>NWLI zZj8Zz)_;{`7uBVQsiQ?5$xlEj2BWv-;0odW{lP8&_+DHT@g2HND|CpTs;(7`*|Ajn z`-jK)Qyq+HS+E_bOVR0Qt@mGaFA-a~6xcl2vzs{(UU({G7s5kP<s+j~eeRlyS4IpbdLk#q)QjN;6~V{Z&$2BtDmPI_(D{ zu{aDvOs?f#jTl8$Tam=`%f3FIjwppIWR!6guWh!>Wa9=+&-~L7^2tK|5Wpj*D5^9- zy^Q5-&ATctB?6OG$HfKj=aMQ|rbSupsv!BjA<|z*?Uo8If3im2iTk>GT`Glt2~XD|v6gQNcD4v(X3e?L2}CQ}BiY&Hw0 zGpat@*;xxUb=?Ip37FwVlsK8gYD7PxT+_1RO9r+A;B;G|jfggz4x9Gma2VAJ#G%t@FKWS7SFv_naZYiQI#jkm!*$4fGx@V_^CuJt~edWfG7FV{~22NqBGS7@k=ZR8*=^$j^>XmJv zAeJCS&AF)=xNDFdrN{YEis}cIj~0+80653M9gNvI&TQ7Ac~*A_SX3XQ9Rn7;u688( zadDKRDTUk8h?>lSa8L61=@bk3tESBHZ>T=8&*Sa=Ak>_jK0iolHw#T6C8{I^LfrO zm+5nEAzQe2Bt%*7pOXs=BF@sCyF4abjx9J#Y%9c7lC zc^4frAYMfqv?p%m&vW_nwfy<1pA=7M`||M!-dOz)2lli-3QJ2XIQ;a}d-evPT zhU8(1(U%;;A#+!=NFraAHCXbbs26D&pRZ8hGF>c^tWHa8hI)n5q`um$s&u_d>U@oa z0_Rblt?p_m1faI&NLYB{tH_(4o!ve?JUgq-&Wf|M?Cfkg^Teyj^C#gM{z390K3G0K z_-uAR7N2ar;a5X%QghN>i2UA-{45ZEZPv&0 z_XznukM3W+2peg?RVkU>6qO>e0%!x zFE74nCwzwHzIgRzt23d`;LYq&y^8TCt1jvP1NsOK{5gpU>U?=X$W}pwnl0jmYOpU@ zlIai-9Qc6v$3a$GpyUMoP02&7xcXG9@1+1qZXZ6RQeDw5?*wq4~@~4FOZpTZ;ef8Ue3DyHYk7$$Il!LR)XZVL^1nffE9)a%V z#5+6mNVbQ-X1QE0yikwmP=JLWV!~*UbJe})m9I}8q#CKEKmG(+_q-&sj99>z z-(*SgLen;D5>cArgntCRDkZPendSqGV3;6yfd9v!ir4%5f0RFC{*VBsj-;9{>Yb@L~ zgym&L{Xz^cgcUFkcJC^=a`UJn_z~ksF5q8uWp(`z6{MU#@+9h;CKr(F$jy;C31|b; zR4^G>7Z6Q7cUqj|I%{gkJf?+F}LgeE#uzZ|i+`jk(rym*d1Jf}&w zIN)o)A|2TlN-ON}yL*yro$l{zg+XhG*tv#RtISXz3GdO^3)D8Ydz-k7d(FM-BgLd9 zzRPzjewEihcy1%fATu=viCSru0-Y$~{4%IAWjj1f6 ztO*qbpyGTKV>!NnFl`0w3PA$UtF3L_sI9^pQZ4)Y1pgLY%J0hgM!Wf@m?y7D*>_O6 zUxW*aK(7$v*+6zDL;vWYI!(`4z_%>&beOh-v5|31#^J%(_7b##J-BX9+$&a4O_BzH48{#QVdAag z^JFD++OSimQGqQ;eG5CEY577$$dR})K$ruPFVhz2D{WgxH*H#Lp05)>HsfA7lu&MB z^Jth0mDH6w#-wRB^gWJq4%(zM}%ND;xz!KQy0e>}``)L7 z?>+HooLdq|;K&7JMrATmQm2ST;w4Sr_g{S(b>WGpC_@$H8W`{|uV0Cb#gi>sg-#DG zl+n#=k?s%j&_NzjyBPQc_z}lJ%*Pws_YPdE+zd>}ezfUAe;cWV% z-7BUy{FA8Y^cQ;aLF%7?%H*1`&re2}-xxBJzoy9zHVD}TATi1)brdfaFRxMV%e1T# z^lH+LB0Gsy9^)v?VWBY&!i+E*Fh1u(h3=>C<(bWn(@P!1(Y%ii--}%(IN}?h9h|>N zuRT=R3o@Ov6T7z?>8sOuPahw9T&Du*Ep<26hiJK@&)`fnQ51pi6oWQ-VUoRoYU~B( zU3K?Pz)5~3CxAvj*g+3^kKJ+XA_b#AOF%x^kuFOz{raIx2Dvt7N92EVN~FTKXJVu! z4c7>Cl<(*uVJ6ct&6j|3K7t~m3q+{Z;a;Icm5l4Z*My>ydBya6K&}_{@7zhBRAc8< zb&GeS)qp}~tdQP8T8Y-{_VV+>Q8)EhF4urC1P}aPQ-wKexq>l)f;n!CHY#&eQJPpV z@WOJ@Xg9<8i-D5pVe4RY&DA@iizW?eOI7oBA|^XO2IyyJKe z$nCe@@O0??_Sx~1_}Q@(CEDl%lHC1v@2UiQk>AYYHF}*yzeVnR&Ge4ed~nXS;_VV&GWC?(K_gc-5w_}}Ocn_`Xq7T&VYFfn_YIzDews$3yj0f4N z$tIy6p`HuW)IkGg#s-JGn?a^u*iK(Hk41RvfPff14r%QJ!fIC}%1BC`Ut_p=6zinA zjz>4i`Mb3Gs+pG(uJV8M#O8fD%T^?z%og-5XjY)8%@~hx{%Ec(0a+7gzozAYwkVIR zR3jTiP+k&LUq{zw!W>P>wUUt4MCU?0*O#Ys^Hh31Vi@yW5#z17s&Df$rEbHPnOJKl zTUNpPs0=23lJP$_q%V`C&0U2grKy^Nqa#NXkC}wo68??{E(b@knQ3}rgMI;-}(H%4aWgycfr<*FA`!yNu9H^8&aB*O)$C>wAgHn zCC_*M8pcOtQB-lBYDXUQYaDJS-})P5KcF9U<}m!-enw@-Seg%?Qe%Z=7mR5+`$?ug z$&3h|YQ_qX6r;{{T{IfqWArMeaNgHFDw?7fs-zJ^9)T4(GO|J!ZsO4(?Zf)OnK9@*gBn zkq*XeFN4$@bucSv&X!K2#1xlC_t4dH1SEIn^|MH@VnQ20-h(RZ+Ts(X)v^%=SLl`L zk@~BY!(&#%oybuGEcD?+!`G;#f6Dqc9m|P$PVP7>)xtuMRt*o9Rj8pM^KO|@&7^?) zg`6rkr)cF2Ceqq%@KW!b)BQ4KBC%Snsz2f)K1uFDY1)hr;uPv+?|g;=+c zTwzEP%EM1eklwET+D_mQWNJ%o#6{Q~wo#&UTj}%;OLM!&ImO;4E0TGBk){7g7JD$p z#r>rcB||8URF#`71+j3N7rnAXussTI@U{j%0n8;8;O)hRjJ0D-3+${FZiLnNIo;1P zns$&PoZ$Zyh?QmuA!m^+AutIAX&+$KwCP{qs5eLf!Zl^Ina2h?HxYv+>Eol4C;v@y z+dlx$QvDtOH2EY+~V`vs_qVnKHU}bYW1El$; zRKstS{pYSs5EvoqGZtxu_iWwNCxL^mJ)%D?@fOs8A3;+}e}O%wzvI6j} zqYTZChPBT}JO_L{$vP&q6GI-*gmOmBDGz~-zn9rFI^L=XG9Nl<DSdXVe-JWxT+eqUjAESoQSMGhsi>XCiM!ZTHn=9UV}coHn##X=cBIQ zFAPS3KBa^g@LtMJ*>MuvTk(a4}M41 z-k!4EWN_BAO9$SCoS*ASj|JPng}0(3=e7>gJeo>nZPzn#Rpx8E|Pk;iR%81-+W6{ad%@x{Ejp1y~_9t7aXnHl7J12fPAFW~)o{6jd{WSy{5v+s!f^IuNiGVK71DK)EwK4qA z&9Pt_D>CfW3yRO3ZlA7p!8)0lFHY6okli^{T$Ma<5*jF z0vk;eAQoU#+`@6&YF+Q}lQ#SGfH_CFBv+$lB2#HpDH zakZ@qS6x+$)KbwO@TPv!wnsCQQDQRMBWPHhMx|!^3o+#-PMV{MF&aP);9@38l$eJ@ zKPj1`?7B@>FfAh>l~Ym$9EpM>`E!s;m?kYDR=^$O1J*^BVNW!lP8BFNeOE1z-n9wh zZpC!OHTaymCI-fyZWZ@+6=xTXX6%Uns>na43U)y(l_z+GEEQs(2Prer)vqn`dzL*C zd(Jhr36tBaRY(ccfp(gVS4RLUX$uM*4*_P-8K2Ty2@1sZxq_;;fn8w4pfpps9f0mS92^u!y0W5C*~JG|mK_a;#c|bJ3mqc{%E8)14$S{7?u&Sl<`5i79CDuDQg{jU zOTTNdoi};0pm2H>Ur^*Wa0#hs!3HYYwDZ2)oL{9CC45oZncKUXkJY)_mR~ z)ef+NfU$Ao#q*9ZZ%5T|2(<)zb&$eeqoA-g;p$K+4E?lWL*PQJ6!HM8v;v(gmb{@X zjv@e_gEexL9t!GFo9iJ~N$%mC=ed#}W#Bjhv0XSx z{DrtA;RWuh+oR_i6<%XCQTKI(Jl6sALx{VRad#9)`GdCYc;|8$4P}Er7=ZD*FsEBv zyKs`!2~^f4L&`20N}emst}BAt`cSJu5Gbtu8e3mx%o!}B0mu+?LUlQrhnVa+vCG^; zY|x9z9f9m*5n>--v(FWrc?3C-yIlB7v6eZn!E8q;ycQdL_$jKE2{1eCUIy}GfN9Q) zvYu`bBHm-ELNU%VA~vL$1nj2_;4dZ!^{spBTg&=VxsFSGp`xQZK2gP**($op^Pb|w zEu_)ipoOV`SlhpEtwiP+W2rQs&RQ7Ns19pFpReGi=sEyBVsQLoL-% z19SjAy#aUzIBaGH<8c8gD0i}}Y32qfRx7dt67VSJFeH_6y)-o1%~VCMP=xWo_!y!b z*$ocjB(-Au5_fNv4?_Q5s!P2+sl+G`p2{jG*omR%0snVyo57XTF_6?tTV+WTCeTS4 z8|iox%Lh3wbE&&#M#D%wG#^)q_4j6GtF#14LvTWpdXx~CQAy{`yM&alQJ<)!DLTDX zVt>}N2Id~~VYo8d)FVhC6s|+#Mn|S462ZOkutKOBXW5T@KNTqiSQstIM^$ZfzNzhj z#MszR5t5+EA@5J9;UA_3zUN_X+X;y%^eSb7T_sYb?yBsud7*7oD|OI-p2mRs`8n`} z(^bM_asU+a3yOPxh)^&h2lIk4TT<|PcO>CM;Z2B@`!5Hthi5e`>X|6*@$nzXc zf1lNWH4n-UP#!HH*+uMd z$cGgg%^}uD*GSydFbR>Bz`iDDAbqLL165vhOib!6(G{%YJ%*?H8yb* zt#RbQw-d=Yacq(qpD_=JlC5>sc3}+%qFof0#Zmp9SrdQ`U6uz-M=R3|neMpv@W;fm zs1fiiJw3+k&w(-ckJ)I}%GG=I0_~7qAtz0<;_?63xU9++RnEziPsi%yp*GlYn{RHP z_{N?U^|eKxRiG6S&fR=awrwLvVNa1A`K&=<|{5r$k9u0wD9eBNL~7(h$j2 zmotzuiW?^=GC|!Wha%~5LXQuQNMB;lHNhh_M#;Qb6Ue0PBDtTq^eqwyy#xk-r7qn;pGiPi(FkQFO{3;tOfoh)9{`@>Q!- z(KSVaGg$b>!U55+)!cQ-Z2W-X>jPK8=}7CZu-|b0*V0NJ`s!Z;oEu`omXM0_(}{^0 zR3fXIg{+rJdU09RH|YWzU(u!`<)PMpFRc<>O^>__X!~iVMBd5CmDW#U0zDQ{M8?g1u_4i)dl(yj0W_^zbZ_VMCIhx|V(V1BGoYvasXn zg|eSRguL90&45S_BFfl$E=&-y(szb;e+n`mCPPLhUd&RADwM_PNrlNLxr;D|fr8&svAX_c!w;=yfMw}x+ad6`2udZhDhmk5b;y_%_-U1Pg2a1H4g zdB@Lc@;_yJ^^>ps>S)G>yuB)?!btn^XQGywjP`B-r6J8nx+}GY!ZM zQGuSVz`<9NgSVUAPswjERpdxBL9R;1ztsRq!Q7hUykI`K5-Ug>9~ToBE%_NBNn7bP z#@;`WpOk}fCMO4DnnJASFD`gU1=F%m%{EXu)!a6y+;@hGqX`X7FRZ?uk>3mPv-INz z_ip|%Jhz?wZ8m%sOy546J+6Q4xN1akJ&92Mjnd!l|B68%%cjmCGfFY5v6;z+Fs*5J1F)PE_# z^h*h(k_InpGSS25U$QD))qIutiGVLSwkbmn*1JjbkCMW4a?&pqYrcW;jXXTsNBg*W zv|FuT0|&y^pzpZ?H6T}9;;zXK+(v~HV5J0#xTJ&MV%f?bTP4{QF!}mv>}1dC>ksxCGXE<@j(Q~QR~VR?RIN3FdmZxkBm-ZX^27yw0*C> z_uS$mllZ(`tAZ8R){ig8$C^!T;_DnDC`=N!-D^`Z>2bQP&T*O$p&&g7Wu!vO8mA!)5{tq6TDlxn1#@U`+@y>eb72@!=(0A8jt7SBYr>|w|^`z zlAvLXqJw@a)>;_GfmVz3P7V@BhA;S?r50r>zEs2nJ9NRKCIyQZL=%l5r>6YAg=gNk z4PI>c`^RBnCObr6&(vE zFP>t{bVjX8)DL_~s)BBJYNb%%_%+NrxiHkz(FrO#$H<+_pQ@J$J*yFQ)}WY>ERkOf z)A&wZp!L6HnQPlyK0PQx$1!!)J|(inWE?5&Zb#{VFoq1eNdS?tRW*9jQMWyN^3)jRuz>bE&+e=aQ031SqwcYyT;eWzzPlM zrXse%RbG(xpCiKDZYFo2; zg{+f8!Zx|gA%jl#cv|X;_<<1BfZal*jz%JYAAdm_`Su+pp*l9#+hHrDU(23x$X?mP zqGz+Kxd&atdsRKhfz8U=+n_X;K*gA}wh@{292{(Q+Za$kF@g$BZLG`-56$8#GtM0| zPoSl%SF*sKoN>g^hxLTPS2K6dk`9mxquzJBDOFy#!CD6E8Qm(si(94l-wEeu6E!W@Qe7iNS$J{r9UeH?% zMUPc5$m^*G4nJMqd33Pm7j%8u6AljYJ-N%gU`H(O$4osG%U9PVk0vzPs(|prp3eVJ z(xK25Ej(E(5p<}OaPGfb=~$?Gs8W)TdgLI62?x9?1xC5*TLdycS>42UWgq;?v%sv2 zIuknU?YfH$P1YI|jn_Lyy4R zo5{v9em=-Hxy8R&FDb0It!**AE}`a};!w3)a$w~v#cKCbhn^d5wy^UolAcGD`S7p5Qj@FUhx5*&h0 zopMrXvSa0MFxuA`tqOjHU=TvTJ`@jUGO@W@JX({0%F?rFubIA66iN{hjUxOKHUoNT zIk%jOEtV!KCk;quvdVXe9t*?3PxFND7JQNCFazC{LeM-ai57fQ#Bt5o9^0CI;lugWLqINlu1n4yze#=?Z`&h`-D_+Z_=wI-$3R?b?@GuG-A>Y zU`$GjEU{5Cca3Cu} zdGQNA4b18BAVR6=N@Rhbk7q}*L?jWrn-#E7;DC!)QYaSC^^Xpc8OmvYTsr0>H|CIY z&~Yq3K9V1Skd;=5;G+?WJHj4lwg)$N@d}ZcO1u~LAE=E&7>qf9$;!!0EV7ewN$#bR zHV%s35Gv|=1T{@ql9j|;itHk+rXCx0`jSTu{E&Io`>v%C6)*WW3XPB3jZQjk!12|= zLDt&5%qniTEciZ-Xj>6)l&eFI09@xb`$`PJzL|5BF(4nLWShk24Ma=ymr<29YsmTA zumTlKGhRtO2sLABH^NJcR}BmJHz-!ztOX}A&a|urVTKZ?H*|r@{ zq65ak&<5;6FD>r)gr)2`d08>R(M??7XhhWC%v~P3$J5TDpRzVB?U|PNs_5tnhh%(# z`=Aolu%Dh&DQJGFb2gl;G;obcu>5SW0Xy~#{1jPVDxdf*Z_qEk`AXe4{1R@S z$-~{JKyCebSI9x>y05-`rB{CRz5e_etu#eU6%jORU_^JwD$Xz)mTWbzRE`B_|67dv zBr4q4bG|eTm>e9SVw3Z9q$(iWM)LtCm9(8~{ME=`*Pk_Z#Y-_gC4Srtnuiq0kqM8? zTIhiUg8r8>!zpcny5`wp2Cta{mhNTS6CJ)!=Xft|HEArgY7wW^OG14gwsJaSciH6D zd1M!=@wBVNS-sa3$c7+YTIz&2)=bLTOH%R>%MT9n5h`R}a$1u1k1IXWx7Zs`nNk5d z{p6djY~IZhci)gGg?_UEgU3|^eC&_~t{ka%#(ox+`pI0Zz&1sPFwhuhZNb?&20hhD zfn)3qx@BePsQ_Nrr2iF?k-%Z@k3c*JSLMMIylD31K$;5#uJq|I4bG4Z4gRuT8$$z= z?R#gJ*xS=T3J-NV?sNVj{vxdt{u;ek)eZMbt?$9memSb6&w&kCxTYSBjZSrF`1uGg zKn{mn{)J}jbF0}>zK;4t=To<~raKjqMg3L21MX1i{Z@qR0l3cj9A`v(G~Md!dWSUDWXUF4*TOvveg4E$sXB#Kd4hjJP7&d@z{_S(Z6}Pko7Kyg^E?1VI3VRYP7GbZxfPb2K1& z=#lKL@6N>OsPW1#7VJG>r>H?yXDc<>vcwDTd&VCQ^LFe&^X>j%Zsjrk17BVETzsc~ z|D+5V?xhvOJ*nWX1~&=fL%&^Jn25 zJlgl#SO41}1Gnv(!rM!Q%h)^Qd8-|Dn)RZ!t>r_ zn1<>Gbs9|mbo$NL(jEa{Vd}7o+wUy6Du-^G)3erMmR?Yc)_(1uO}H_O*7c~Fsz67WA~7NJv@Q)Tp^K83fCwMS zaA(i+!v_vxO@j8O_bWYLsEPP>H|6iG*rWG$MkMUpOPLLI89PqF$PGO10{a~;$wJ&1 zHN|jcw-K}$IBR!W<63Je434(^EqUYOLgWbY2Xo*Epd$97+<6usx!fJ#TGn8qLi2C| z+_unZfGwJIJ4N88+CS17P0mG$?qgmgLR3m9$z=b?*@*QkIqwl{o{j7~lDNw)LwAA& zMN(Ulv|2Tua^13lP$x>xx+`IHg3j!pj^to8qR25yy4t}zlr<(KePA(;)6f3b+J~Oa z;c1Mh7l81wGtHT}m-?99qVlHbrh$8=m099!MiA4*MXePwK$ApIRo9H-tD!q)8lPrX zBs9-$SU*lCdR-MdBU+|K|5lSAceKfX$XRSm0bti5xoW znqNta0FkKEI6z4C&UN0DDQrM4oJ8V6t9->p!aE^;2&vT<17Yd-k)q3pMh;XNL6Cf= z_h2?5`f2eP&tC_4^cWx0)YE$H$9&)FH?4#;4cES8z8`_1gJ^AvJ4 z_1@%be7>d&BKZ9@hkunT1inm`l{ce@bvs-=KbqTJO2;^^{k&>Im;js>Nflrpw_uaM zf(ftJd9GaO`2R+=b=|1M&)IW&E1#Ouxc{kNCk zu~%20Gkm?dI!{P|I`PPT;w`;-(72t@%!YE5X%LZSe7M1|szjRcn&#x)*Ew|dXofNd z_nRltQ#6h1S`>!{h8wt=bvDQ;&zT(he7J&QWqgnakMY;fsozhKe*{A4I6CB;#dOR4 zNt7SWAEV+loyt$$4Ejb{tA-Kun9vI;l4Ww zCvm4`ju23LL{G-1Th^}uM4eTm*6q!Y?uF|q4H`aVtY^3R@$zU+J}-!$oX->}$&1fT z020;2H?TuvSs}l|CxrtRl%bd8p%x`-3;7Xov zl0wC+GRf{dq|MDQE>?YKpGS|?C$X#loG9~8YS>qn9OvE~oe7SanRI_U&erSGyq~>Lz)?FdwxuoKc>bF<#URDEdoO@qw>1sYiZzC|-bJw$k;}NJ589 zrtZ@}72(U~D?v+od0@mvPga1x2mFNvZCRST3PW^$n5y-Df6QmemFe@62yNq z2YFw+PZt|;O7!6mxlVSyXwI&Dg7CxM_ndU2Obs|cS^`gb>2G2zU=tS4XYRYS9WQT= zn;PRxg>fT4ax1)xRem0?NT=xWHEMarRP8h<*)Nh2&v8V7B}gg?=ym0A%x%GEz5naU+0F3iiCx{> zUYAtOXa1|5$Va*(T43%j?c6Pn@xQ$0!7i&7bod?eGc;`-5tv%NL~D^dKArMem|NA* zmA*a?*%8~4E}IXJ?ZA5Qh`dnbS5D$$3EDyTaez&9K?h}BV~+J+5V3;fF9La~;&+{DQ8oKBp1v|jlHNqC4)0VEexa-*!^oVlI#3BweLfj2j z2M;@!5|O?EDsP(0@obozFL6OkCSkv|#+b>IN#P2xKGH_>mL z=&_AHVQ_9-du`en>6DjEZ>x?hc}o|7eUE*$GNa#eZe>-X5+`D(G<2UAx38G-XRS$;d^Iqu%P5>Cbgm;C-pvE%M9 zqkDA^f_b>{K0QJHrbsU?l0sdPO6BFsLL098szvErAYLJZyjDU2z>B!jcidSHNLtMp zk<_%^l|_#U5JqMCA~oT;?wL^iAbBLom9u8Y$-&3OEiRw<2D`@DjrR)KqgQx{dXb`= zjjjnY>EvO(khl_2nR#qiBCf*f2;A1RhE`8YC1=mqQe}3Ag=Kn4saCa&u^4B|`bwpE zsEb6XTj`$>HmATuZ5X(LOhv^-_wpPM?^~DGAR*C5Wczp|zk$l5qMm7nj=$oUZf+=` zV%F8qF~K?pjCO7uNU+>^*F|^gx5)H9$y)n_Sj=nL{}QX~d_}BQ)Mp2ykATmeYt;wJ zZohi=aUW@Ry1(CAy<{=aj(;aAiMc`=hu-{l=j&x5ub?C<^5qfX>UBM@t=V0XW;eQ^ z_Z!aDk)Gf>2xaC2U0fmwhcQ>Bz157gyBf&bG5^b`y%`t08F6m<>15g1lHqc6jZb+y?hML5~*~%F+ixm-6z>n37-C zYQ0@_b~eJxMH+(e1sZJh7{7Hu$~vDyj}Qb&*z0a|&fZ1^T|v4SkW(=Y`*n>2K`t!C ztCh!v9{t4Pe54_mdI_*9IG^4VM8Q0M><#1_t2UmX+5kyTw~*X2EvSJTxuuen?eFW5 zR<+GRLC5Hi9u)&_1r5sr(mb^*Y=ka#DIDB+>KZ{JabXgTf{%CN)))&d$XI9-s0CHU zspOELf&mp^eAKoJ*$_ENl>Fz&u%Wx8SfFQIMT23ebWzh%K9ds*0kZW$j{9kn&PE-A@Y*`%mRkGxP*P}jV6jX39y`-XT(-9L?pN;iX8u@e>T6e%TR1mbJx2_h_vLuZ_V{#cXR z3^IJuG>~{!bu1mBqgNuc_2h`t%}q0>LPNpy*1Q=NW~V5y%tvmFn?dd^C!Glb)hw1R z%5lkz4kgqERTEjTqj&it2tyifHoC?v^rBii zf9F1NFg`|5KBJ%vN+BPYPJy7zX9;drNffr zlFvHOrO?~{cQa3ots)GZ>7Y9vU~pUs*_`X z^8~eeQCa)JtVUb`$!sg3loG_ICHPd^gLpJSPnRo(uO46HMe~nSff&WgH&;oJ)21RX5w^-G*v`esaHHgE9np;1PxvfDUFh(QFLT*7lWi;e`&~iSRvFUGgv#ktTG;#C&3n|!YWKTv?pDpl%rn%vN@hh_>- z9*7IwZgHZ*?~qyk=om@8*^unmDn%#0w?S?W(rlb?-p}fr#w40Ms8={KJ^}KZjUrh;ZSd4+gIBE({a1iDl*NKXz zq3O9++0~aUpgvR)_0^e=w0}Mt-Ae^YQe;q3r+o}|8$FXE+45Yjz&h2gsd_$SS4_3KfDDnpY0ZO7Oaz}@jBZ&YAv*;G7953}Thvx_kmST4f{JZ2_c z42u{$HJSow%on+PYq9xKmsD7`c4B8}2yxlaNeZ3GD-16r%q%iG>(|(+cWY7*D+p6I zZkN0q;n|#C_mj+zV^G!ygEd;NYh|=7Ne-o5lVI>hx!~KS;cA-RW4|gDUkw(CW~q4&faDvHpl>1U@VzK8Tg+NfIXw0ZRA<6xqil0W8(NvKKR zPOEN9Unafch9kxJS55cXO_4JM#9HcXM9l^me=y+Ck^PC1vq|$6()+b7SQ;u*bcyni znBeHUX8U<$?=XSWchnlJRZ!PXNYL**q4q`M8(nx2U64#bIYY5>cG5N2I~MC`c`$~? zh4p-wa5}SKDLbTgXoVNU;6~yY=$OIBSB$(=GXxe)>%rmhd za~_=pnib?mvGHft9w7G)75)rxkanP@>P$>kX)BM7YvnO87fCj*O%x?L2i{6-q)f0Z z=2&uR{zx(~x3bn73Al@qpr*eRD;9ZX`Bz*D^_m1(A$0n5StUds`o$AQEo{Njq$`8K z>l|gQ5skg`_;o^7;RL@{B*vAi0i$sHLk~9yL=U+d^C#7{B4UBSnF%Te1 zKgvqmzElB--|TvKfVd3#_uT6knME@>LVrwwgq^Xj;oBnK{3Ez(>|41m*`$cA4gGJw~4 zNZHXJwG}!H+E#f064*dD**;*1%E@>({lUl-Q` zrj@(wC-{ngt2<1Mb($LY#Qm`qW#|gquOoVhzJy@@QxfCS=5k41qS&>B_ZRn*k{U-q zE27;nCG*6@OCa_COLOkKEoi#q$?-R<>Z89mJ+LIMN=%K$1RFj#ll8nb(9q2-5AsxE|e&fwY##93OT^#(Rvt z?iyN=H@e<_)cJ-tc{!>#dFaWIM`%k&At>YAtrdC_U+CE9w3|_!emp$^e>M0SY;D`3L{@Ts1|X(AuwFe)W$V0&?zH-sedPW^%oeB9S1hin_; z=dxlR))Jk&U39mu*_x}hlfn8nkoRkc`g-l_B-`RY1=J>RYS`3LA_n{IOY!NSh6jZMTyxr)>6p ztXGYx$P#6ZReJ%C-ilxTmh@8Lx-+Uu`6|t8rjN!N^k@ZRh6Hd%d|-|}RYKI;5dA)6TCS1Mc~%%;lxG#>jcyh^jb@kdS{@vZ!@ z@lLER7sUcSRdwjN!Yz{ur&Jy|&WYklJj5kk=dJV48se(^hA$?mo3yXgnfE5ZsPAxW zt4z9dMo^Id>h0Q_+cu8)|NRsantA~9BvDSlpP5($?v1;>y}fShUqFpbn|XY(d><%!s4 zrfd(2s<#Ji`6IQXTRA|=2{FyjSFq1)*}Bs_o(y*%@~SLC8+-{wdjRO;M|2Q^MW@F?7W9ez+=dM7vk1LMfUM7d!9^t*_a~Ra zqjdGm>|~LdeV|y=)#^|Sbr`OWK1Vy@J$jvpr#p}N)p_T?j=Nj0ae}djqGu52Q+~1? z*gI$AMw)81BjaRcji1e@kW-Ee?(NB{yv`yC`asJGun2GCJF1WoBRiDfyE!jK*bb&; zygTOs=7YLJ$=3`~uZmTLB6TC#-I|j*#0H zTEI{aVdpu^N!trvHdR{vsBxYfS~IcIE3)rkxObW7Fm>SOR(G}Yt_6rChA=4Zm7v?R zcR+?^v56~}44GaP9>12&qb%;!Y8AT`z}8`XN8dT?YetvkEE7howLwg!kI)^@pKj-? zheRH4?h^n0r7{-nqRGf-!X&+-tzb78A6mS&UX(wl?>f7gau@CO9+wbJgvm#3Pi;`s z7zF+Xv7l{Sa=+TB@``CY}6q zi!+u2i__D7F8`BI$s+pFrSYu(K9nATB(ZS5hNq<%MS2OKaeIopO+lCob0|xNt$KWT zw~a(MINKk`=`i|e7YTj0agS`dR5xd?WyNo%#m4j; zB40bqc$CXXS1TpiN~7GS$EBp#)~2;)Gidy^!NlwiMU9E(UjA}}u<_#wc~<}AzsC5t zFKyRK>+6SJ50bQH*JY{9)~&k<^4rxb%!jo2{JE&4p8By*VX{Q~)JcTGag9SM44MR2)&fO4v=}xMN(=1bR6-Po63Nc8zSL_b9m}{M zGAL9SO3irxs3)Wq`R;z~lFy-YRxUWXwql#6Q`khG#7C|=7_m_#7;&~s365i(`tVUN8&O?na`!svJ_bX5grLB!vO8s^Vg9CdkJ6I0rBC?eh-YP#T* zpjvBb-3pxR>ZPhz^E|^c5b)QZbf~Fo)zocKYcN)!cbfX?qPFP|#J73+`K}9W#k1qP zA6yqwrt2TLFwM!gFW+5Tw!k1eFx%T)tDg5wQcgi*oZ}tOlJ3Z)W&-I0DR<8*JB$OYClS5NB=|Df2LeEUPh@Mc#*@M5O zwoJ-dV6QvZNO8PQGD_1jIl8GLwMJ5b5ee`=GOf#}j{cB=`wHia?5fB%BF(^TYqZS9 zsxlS-1k#iva`D|SagJrheUrx^Ev=foUQHEJT5>OnH1|Y~Yfz+EA6n~)S9avqP>h^6 zCM(0)!Qt1wOacJBQ(wgSwN-y}jlR&EAXR7fX(+2|x&=AjoFVXhXjs(}Os#n05;oOA z(LJGttEqZj9^zz-w8XDWg2Y}{H~NZUM0C?kTTMGl#o6%s?ei?E*cXT3K@v6ABy-_&L{-*Dm!imZ*pF-w-^CzsD+Tat2gs$t+jm4J%kh~z|yO<$*^^* zJGABea|r{U>92U`JgfAF=lUO9ozqo;|MBoBRulfR1<+uM8wJ88DfgGo%a(OJ^>stj}xjWNGzfMBtobCR2e#y#uB}v`TPRG)Oj|x$AVoQt5y2jf))|qm2@{!?Qzl*18hhNgAmZ z97nP7w$yEZ@81p(zds9a+qcDOtYVa~a}0*9>qiySN8b<+7Gztp*J&NUZ!Ef3*7j{I z4$uWS!{G+w=&R0g&tE}9TR)AO|A}sDOa-4K?mk3kW@}4rIH$BcOZjt5Y+~)Q;w=wP2-4>8EJhVkMFM>YtSL}4|K@`sA=%}754|L>8nnq-dmFRo{u#fA z`mA>LK3*xR{0}yX#RF7mh*n=eggg>jGF1QDJeBl0Rlouti*pPHR`Lnw?F%8CPl?JMeKLDAG+ASBwlm84b1I{;j`s)g;Vl@54u7bo zl)E(Y#a2EE!3GzXy$`t5-*WHShg{s}@j2%&St;A;mV=D6WDbtjNA1$ z&-<`F$bBTOcCKKWh21^cIM>9t^9vOs5KYaMkKcZzJR9AkvC(``P;lC+o$e;ihN#JA zrvCY<*%wtJIgXWkcmQ2}_PGr@ZoGF~9m=^yfIdFn5fN6SgqlQY z&EgJ9>rh@t=C8FVMuD`Pe6`$ z6BQXsaAh;9aR4H2h3>T1RP@(`z;PlOh&s*_^pl(G;+ypDc?rLp)J)Us61p1d9%pGy z?Av+Lbwk}OfPeQmPt=$9r-VbG)FaD1BtiKpN_w#r+S>dTBTI3=^~^=Z=~yX1u4R7e zFb^=BP|`h)FzEYMOxQa5JKqpa%y3+wkMt#s%h86#y!s%h#Gx|R$UK)9m1r^s@Yoa^ zAGYr2@QpxHXovZp zq`OI*8kjl4Cc7@>_vGK7BikUrAW+-*mFbmH*5lc1q;uT3NEbe!sQ281R?bt-W(dUm zd6h{=9F*II5jDw2-syfn1`@MizT8D3>gqgdFt49!+INf2NsNn6Ww?B_-UFVi^m<37 zvx74LnjHV%$+_4Mx{^#Q21O3pU1ySu(_EN)S+?|D5gFp0JCU@1d_hBB3A~_We5;D} z&Pg|IhM~#X%pewZpjFuULX^`#Nxw(Yn<63XvCGOUUH$sUP2ZmYL(S44~~L-;AtSy2Trj}ZQ0^F=1H`ZOzWBq=UEQqV3pD% znHd7MhXlsjxmdj9*FP8es9#=tUOv-9lT`KZ*J6M`!a*Gr4*yh5jtp{OLs|?xn{ikz zdX(fSJBLj9*}!CXSXFl}rXn4A+Z{jeo+YB+X7WCa^;y3IvEJB1l`ctn^cacpvNd;^cmNy>X8D z&FX(@Re$(O8998nqnM~~!s zzZck6KE&B#;MuS~E<|;@HM5TwGY9N1icP#=tna>N-YmFC$yAFxGSgEQU$EVT1~&;x zOUe9=o5zU4Qjz1Y({}*EY(7?#n-}y7rNr?X*Rpd zGW08k+ESdckTa>L$QfE#^3n&YP$F^e{$PZJzmL>4Pt(})z$R0RGUI&r*eG*rN{^EE z?xop}Snpwrlz#D^C~cS>sY{I5Fy;@j;l`s#E|b_yC10+d9J8Z|yDd)UV&*np3CHB;4w*-c##z0$UrU531)oWGBmZ;6~8E%?7 z4vd7}nZ_#QTO*;}m>_XIsguZ73i$ML>MO+)VN@jB^;40B>-dD>DIti>jwSbn&re_$ArNiQRk$N zh>n^p8!*smIf<*CQaU?Y;d%Y0r;LnVAukfrN7OX0dMsfAuiY z3lIbZZY}VWL7Yn32&K|wE>PX4(zx3m&WO!zQ+4Jpe3dJ?{3{v46LQC!mG0=hp3N~W zOR`Qfi7q>#8Req@MQKzKGU!fQNW&{WCr(xk0r=dY#^k6haipcr;GTJ zA-`3Ws7o?NgGv*}R0Y~qcxvUL(1KAl4Bx4PVfD5mvM;(#Y?1X(Y|AA|&P7I0ObFio zAr5|${qB%gUamhiQ^(x4G4M$$N}TD8MDFS; zBgOBM+i z{dGGh=FtG-Z`M36*G0=m*VX>5EE*D45e5zq^bkZcL8n&u5X@c4C>Ag$Y0kiL4mRXp zi0UUpspp!VygfUvP>D6Mgy&iqKb*6u#FgD-q3^8{DU(n=9^&t%Xj<(Mf^=1=1m3$~ zcPl8R_6p>wcF$WR)6T|qMzo44URRj=x-VZUaN@OO*v$pnk@&B5)-b-$tm+{-fT!@u zyX3yE<3i4{&8gP-I}{+lcG2Tgm%Y~UUxfR1NpRNFsa5&Rd7k)F@{{i;HwmWKT1Jmq zS~=qV7}7Vf!;-*cW=1XqBKM1otRlgkm3+kdJa7{;@*@Xi(F`-z7;xE}^WaoMn%pBy zd@udsqE)Wze82T#J9<70K2s#bper$YE8@i>%fPCaWxyh*=EwLke5%a0z0_09*QW|N zutDU}JZUL>+F6c123yNTZJ>fu7Xoo9QW8EG1xo- zSN9r<0Ksy??L~nwiEmVPB!=7PlVMV4*0UN?^!!I@R7c9n&>n&liB?t28-!p@oWt`! z?v@nyF(3~6bvcf6JnuQYGc8xVFh`YI^r#=FPaIf=j%KDROeK;&kODIpy*g37DeJC< zKeom=5jMlIEaGq}L2qGB6cds5^t@S3YmTOxy%c6e-ihR-J$IAgSy&F}y~)%U-L{(M zJWjOTFWL~GSOzHQ=YLqeIO-XYNC=bS36!ZG7)_)K8|B4HbN5el*ng_KO*7OQ&WKef zzvu~;dvG}#r>+1nXt-6Sq88L)5%$W6+k;vx_z^P{_iGw^fHaS9H8{P)!KC5OMJe=@ z9OuA?rnL+kCe*xW(|ZQrHwRAX!y~WY5ok)*QC4h1>P*}So;d0xuk*5zd4`gaUS*!? zRpaVi2p0k{|CucPaedg$7-)=E+Vr8nYKMU;d-b zquWS)zsHxh#Ys>qyUcz57PP)W0F=KxK?*5E<`LvF678iv?OeIT z;p>@F(}B~K5O4w6XNc2`z6o>9!d30b9po=rxBB4}eD_VBT$c5n^0s+vY}5xl3hnl( z_~f7I_!T7qW~`jYqG_z-(r)sMUk$w5_Hn6zB~;X^!uoG~%{WVX7kN_=9{^*ubSD(Ygbzx|yYz ztry&wEQoQD#5-jz0jjQpfe=|EOZHjE)8qu9ZLGPM6OLA%yBh}uemprf$|em=XB%fs zBkyco5;pP%orsfU_*$v4{lE;vSw*upU-+ccGgkc}5fmI60@kjaP7HdgP~qF#6#zN({m1nXJvWL!h$f_ck`Q zVOYWnH*4fGu+p-QA45@$?SE(+9akjq!P^~*x32cM4+f{{EF-yRiAJ|>6LUVUgouI5 z7QyPx6?F}#BrKLf=y4A0`GwPX7UO&i4{fHdb(vnxjd>oD{rwi_dSStt(4Y>6Z)6-J zDsHlYza60`^lXM~;xs*^7CLsb&RjE9O|o^$LOY)xs=;0940gNoL)MH$ApWj8skF&c3HJhU8n@QIl9w}H82sDU*ifI0FQK%n0FnBI+2Jne;|?0^>V}81$B-~14m^^$a{3eQeXDG z(?D=aA}Y;rwI!40#JH+?|3S<(l=q@Unru2*OCsmQh6%^p2G9!tqfGz!-e$|v$$WQ? zL>>J=E)Rbz_*Z*cBCH7d=0 ziCJx8Wi3P7(iujBWtKyCIuOind29d;D2Q6BB)g(9jul;TY@OD;I3j_AgEWw%*@FT} zc7{}}EW-i4%ayVdPOkrHFirpqC>|LA2qsN;{A51-ly$FCK7co7;Z_Y`l^Y+L)HA}a ztncWgFWaF8LmeM8a8w!(WziSr6fqdUE$Nh$btT`|=)-eS&Pr z_dypf&iMXSJ?*zyzK7FyA(Chq+xT%!8qlL4EpBY9c6G7Ff6bQV&wCM5wtfh9$Tv9c zy`^DNHi%Ko0sb*w%_wL+YE1O32vJ5GtiG&S!-tq^)CEJ>phQXy@M@~M)ew!u1kYGt z_+x#@AwcstBTtB^b`3(y4MxtXBhbX!F8r2DBBa2vf>y|mAbG!kDVH#ns|5P!3gS0I zQk$Wo39&KTlfOS4*tD4Few^G5W7D)-Fc;_h-^gS7Uz6ms(!7DN6IOL|B#?f87w?uR zq&e(rOKIpr0C1usTmQ#>mcINfB^*a>*##EYp?x6~Lk2Kux#%K$Dg?{5v)2@tc$jXp z_XiD6M9k5f#6aVHTcfy3C~#*%ARAlnmyi?dZ!^G$Yf4_WCidlpP%qjiy)Hj@RX3us zb%Cyf!Zm<_y;r`m#NnWvzFlfSA(hJLLMb21x%8vUZij)Yt^!SVu=2KJ0s8!b0t#^^ zyB*TJE6Ns*$dfZJ5--{xYbe|c+?%be4zAh@zAMfP>%LV)|O^tr#3{@RLogX?Dc$wXOAwTj3JD!G+8iD zAgT%rr5TD-|Hw)*_Tz{eGs~>)gH!0Ua8zi{eI8TMQ_Dic&;vkFn87kwmg6M%&la0= z6{G*|b*h|iWkRCxMI_}mlKlgi-)qMg&d}O!qaEKJ(4sY5lmK4Ab;B=e+d-dD#JKCvt-WQQ$4H@I{uwqVsu zk(9pVf72#N&g0Dl0{#jp%fsUX(R-)OJ$SnsAo9$b`T1vXe<$%3>^QqWgh^-bZQnUE z-kaeg56CFroIE-%ln&;Rw%CZVdYypdJJE-ro{DsIM1|8`65aEpg0IvRu8 zDj4a-SD2RkK^NTz$ZAtSo&B<(C}chMUi0@~WL@68aSG^zDe=RZHH8TBzp>zCqp;yg z4jVySmb!zDwZVqFEoOeHMZMhPWt$vwGnBtZ=&<~>vh!S*^ZQe?zF(8s#Vh(0oc@YlqhIN#VTYXw+=0U!*=}TCb+zh)bbG zB#G%4!(8?l{Uw9kXI(Vz27q^~(=2dQZSve{7-x6R_4SD_V!H9lltI~i!vO@3JvC|8 zKU=5h&sOoRz1r;5Dl9`H-yk*#fCPWSv1AfetPQ)X95oKjM1J7<%Ph}K__J{w@@V-| z;5_&)+3N)l_p0-7En^<#a3lm)GAVFjDSx-PU{UbGcM4a#zZ7y7f+ck1JxN^9sae0= zT)Z8eot*u= z#v}q^puL5HHkwc}-wSH0>H$h5BJm$yIzW=vGaHKBtsc*2xIeo+-9zY}slV_Xy`RMT z#!1)BqKhy|j5Mp$lsK6p^ACx>q0(KV*m-Hv|8=d>_bw9$#LAQZOX3-(ST-pm<9d0` zVqAETsu7`FUNNa8*;OJGN3l-@wuEIet5Cp**M?TPyu^KJ$8>|W&vvLI5lJBAl>wzJ z(RSI-2oTnHfh5mm^9-%CmN!2pq)~|#fwYqJn zxmJ&4909L~I&Lx?D68F~&ivWq1bZVGMuHoE6;8tXcWk@oA<#2)iR^$k(S{S}88y-3 z9$FQ^N=U}hIw86VdE&iFhW)YjV9hhIBh+)XFhL+qoMIk6J2s~<(jrAm^X6*K z!yUhoGM;F86{pL53r*(~)?dppNQ;TmGa?Ghxg#1kdYNvLu8IN*rqar_T-jLV(q5pO zvC0@ED<4PuC&x+rq9f6t^8Car&s%RY7o=6&wmjCJn6Ra7P=1^6dNWTtebJNV8(k;p8OuR|a_Bb?+2OMPA;!t}Y=e{oJ#d+<|^VT}$Qx`b?xb_TQ(I4Nk?h-P!6DCSovR<|L zQ_jNBjl@uS9NBrnD7?H^#&QhFv+yz*!K$BOAx=0LH44z_R zYe%T<{N&z0Uq{nHx4W8z-0QM>I84@=EFkHK83 zw}A-s$k6~Gea^)Bgs-sE)^IT&JDgt%Wi}15#cng%8pRgk1h=e3i6l1tjP$T^hDrxd z^NED(j2U|R&kEq+UYW)!(E!vv{3h>tJcYpG7E3s2fj1AaroF^TgCbOGnUSMs=_bIQ zVPFoFlgpEb%?}kDxUI zx((5a%kgT+K6&Nw;{rPiS4a-4(YM}vyH480zZ7_(Tc|n2%;NvcycA`^h}`DAK~s$(&3$8*JLm;upZwPKG+~|laIs~GeFHi;V+Mv2 zYe-3}=YY8_c8(1 zjZXPSwMX8{TgG%TEu<(7y$8sOK3nmD!^{+qG1n~cpqn<9Gk+bD_quIBI>u`IhJ+5` zh4Lfd4t*{l>jkMTBypNQ&S>+VQacJ$_nKxuMQe>{nqZrTP2Fyp&N{yypK7rY#%-8^@6bnMy(#3Qr zVeBL~wp&q8lbK7!3>2>>M>+4*yb@)zOUcHl#h^U-f$|64G^In$G}QNqLy+W5XCW5M z*%jME=_CK7MXO>-G--!R-74EJ>d7ZitY_2PXXwRKtaZObWAH5Y9O%Sj6DnY$!Dh0OWPUeu_jAH$X6AB+)xluP(23l zxb!{&ybU| z&Sbiuilwbd1&q8T_6m{Io2;hQisGDzmJ-vszW_@S#jVX*dT0I2=r1Qguf3T#!}(H8 zMoknqufFSiQ}n;ysb1aq8J}|F%g*=~acq579<-|l(?z`SE0G@*=`UfMDx9=i&lT5& zTVrG6UG(E^mN!-no-SUn=vJ^mt_P1Lw9MYrY!brVyEB0u;hNy1`d4utS)DaG?ddk2 z3sHtNA_{Igh+?0jhq;0{Q8jwR_-GrF< z9J08^01495bjBF6w7slw0Y?UYc#AWxsZUA3Z@hAJRY- zaptkCjriz(^P&iyf(fnO2g>2oautBnw z-L@S*&lXNSUX7~wE*lNW1LEKTQcGw4z3>n5(*E8w-~$xLHV!fAiKQ6SD&un)fss{U z#H{X7>p(^7flKHTnY&11$F}n5gIRMAs|WnNu0Npj^mtbrB(y(NVn&iSyG(u0l(e@U z*r@X8p56RcYUdz&xRF`!N+=j%^E z4SE6%NZYV-xbQ>+m7dn@oNU%Ffq)8KUJz#);GLk%oReja;nY(3NXpN!JuL6@d_vyg z@W{MtmVps0QQJAcKbq=*@yEv+=8+JUC`LJ)Zz9Al({)ckT9P1St+;BGc!A=OeS3?< zFiI@ivLP*w!RUs;X=a&oBEl_Q9ZA&8T_I*B3%){nr_`MW02mc-Bhx z1i{Yk3sW@Lr=uyv&6(f1Dxs{%`IeR}aW?jl6#&VdQPt`}V#K4Z^t%Ii3fG)X3bX#a zc{m$a`MI6CWxv)Y=V;)zRE!;;xB$vu_|-(wyF4;MCi)JTFbDPLg2?hO@?s@#JbyQH z4@Vc4Y#*<{?4NdZ@tX2Zc+ksUSS6;8`sc$Z+W?WT;jG{|x+bV9v z`?Au0=0- z;0r-~#)@qj;Lzp#Eq#^$O|F+G){Z<=$JR=Q2^$-&!mND2;KeEiUxMOlNl%*gg5;?3 zqNK`GRG5qT)>xQ!*J5F|OloGA=i!$FD&FNSh)oGeLt9n@^p|79uag^RXOWRDd)W*C zc1dpYCJ1?fh_V<}iLKkMbYNpL)J$7PelUpP7o2i6lQn9q#Bvn66dDq2+Lv@X<4GKT z^|Gr~0rk7P|9ZO_biaaMp%NDTMsS^A|78P=;N8v8)d&i2;nO& zWA5*C|3MN_tTrk@q-q3E+U$U>lZ*p3C| zI5Mq*rjFUJ)iHt&wfST1s<34Byl9kC+s2E1nU&u9#^_&f*o}TdV~TjRUmHO>m2>^E ze)*Pm@ikBx#_jNYh^0h?VfSDIy8?rY%RkOXToUc4F86dyk8G+>vlq*b{X9|)Y{pgx zuj6OO(W@M6%TJCsz4qfCl62<&w=*5UYip4h}b|#kgjrAa*EQ}Cox6uU1vezr7mc! zBT%3_O}mpKe`%wE_-d6rwb5DsdS@0lXBb*kn}{#;lQ1=+eMW^tT-9~yce2@XorUMhUKPq_KVUsHXSx_3jre3( zxo~H&-!4(3a@c7)sAxo`i8@_@`JjB%#{^as1vhX;-ghNDu*B1g#esOE+ggB059mAJ zKvQfp`l`o0A481_Z`I=H?nb0X?k3W#qOZ-$%cBqOeZ@kugR0>Cid8|;s-E#~t==Ti zHJnbg^3xnBd!ZiMN&!W154XlVg?Jii=8(1oq>)`P9dkh0f-HZnO&s#ktV&~`MMg{< zS;u}@aShQ6n*pt3qk5lW%d2TEdeP{wKTeUW^K8|xyT9H2cp!tgbo^UeRz|s7#g$ru ze;yErQdnR(R^>G&t$yO(sCgeUf>EL>zV%EIvsjKwHFz*H(14$(>CiB049saF7*}Oo z=H3j-eAW`m-R|eCU^_QJUPi3kCLJu%G7+FlV5M1T3OZyCu)6%AGN)z3MP#OLfh)nR zn%s4j{SI^Q9In}tBVyRe!BK9$I5Zp;n#`~Q8gwFKyu=z#cO!O|O=~b?W6b~?p$8I7MPA>MPu|wuKqf|Zn zl$B&VRU#^DomXB>fZ5$<`<1y|KJR}g|EA838qa(DM|;QmOS``qtR|^#lngdh)xh*l!5zjzp%J;Sc{HSGNBm~49;E#<+6WGuAa*G2HX(y24eNqxV=##|_@ z_}py2J6JEG^8dZ?WcuQ55FOqBzVE$gExtYe*9oA1c2qFqY$};y*LK{x;6^Yeo zn`Zuv+{x~42*0BEJt~)<860y4&V=Q3t+l8&S0SaGUx0wuciHg?Whw1wZIz$!<5?}X zQ~YI0QMnFTwCH1k9}sSoNjFCq5CA_K0%Df~*AN82$ll(?*~Q7w;lGtwjh&qVu5{OH zA6XE3Pbr}w1PLi+7r!8e=@J5<(I7+GC6L=-No*yxEGpm*2t5FDL&f(cG3X;-hR^5V zew^g267`qHir8imRRnDhJ|;`%&J_K(r?{H*Q{_F{+jRdOa@IbPkku;K>? zpu3jNHEQ(yJfr0kaBf8{^3MP`)xoP@RTcIAgNN<#N+L{+= zU87-Vlr#bg6XbwRXEAkN%loAIHK(4mX{xMUhD815eEfWcpxs{rxy^`Q_!j_{*ZUIl zvS8@Tf!l4qBl^~MmO^^JC+s3N=TVogne9F21CbFNA9%>T!+dLQtuk76Rc}t&O?I2H z%INPf@u>i}LkFjCI(Mh_6cS%I@}9si{3cxjA{sUHt$=$7Qp4wW3jBKIAJTftL)Qa8 z&&ThPfI<#_J2TYFb>v7o5k3+4krnQoQGlfKeuG(OxZ3QPS@30=AEGSE3lNdYsu4@lP%ZiC#yqsUR6^q6q&i*;jU*DTyg6*ZyL+eZg~ z@e=maDeGGO5ZtIkR>$Pc_1RXZ*We+Vuwc-rKvkhI$nOgd5j`tr41SH|JI)VYY$+Us zUE$E`lH<)w8xKIiCrMBkar|%kc;}y#9H*xeai;UrtfNoLCkT{qwc@3bSq6zfS}A-k z$o>NAyGz{3czCp0zh_ssCr9>9{;LIH>l@?jQqm`3c3o~Tpfc;YfM%Kl9hXh6BRu#H z_gQ=KJz$KJQw!%pxTF)ji3^qkLVN(iPaa^-H=ofw)X35J^K-JW1s@p6^BELdme_Hi zV}t4>pRbuW2O(G}xKUuG=Z)a~X~Vu$4B;_gHh&z|e8-!_ydd+KlSfJwMuYKI0)IR_ z@&0#f_@8oFz&#)rFd7*)XcS&G^YTxhZd`a(F|AG!&gQwcGr@9bby7^<&pTQwNBZm! zMu8*0mN@DVNQORa<{)@I*h#}11DDsRz7cjMe(bDfjt%4P4cz>+Fuq*6Bn%};shj-G zHzx^x^7$$?eK=lkw9{cmt(uHZLnn#EmuIf$eEncYVaIMu+|-?0=`R!wsu`&igxt3Z zAC6n*>1BO$%ho}D9~zmAk~2iAjuK7RX+s0?t;2#LNqmO|SUiK#(yn z!??wAYU&?c7s2mNk^5DeQankS- zRZa^ud`bhsV6kIMH>1g! zt;k7MN3;jZjgRYVM<^5pVsw?vH7x;Jo;UZaE){hs<}Dq(E6x^ZX8r%MQ*8^7*-9^l51 z-2#ii9e@~*41ZI+*Ek$(SmwL8{|eVfVVGNKFcohK0L-8L0EyL}p-R0R$GSR>3AgeC zA~ZS4!qoR0o>SMu{Y!gNgTDwGqkpL8^6jwFg8YQur^J}1O|DavEG?Au;Yw+-%s?r- zY)Bj|+Re8YDSL-Dut^+XH}f9Flh09rff^7AIT_EEU}iCb6CL%!s}r9xS*EI}Y!SFT zxa*PE!bRCGN(!$$a#T4j&5;(_XowS!&`v2MIEam}8+D~%MOd#N?u}|SIKmDv@gY)t z5|B#V?@?2L8;vW-ov6?X^Or&JeHCZc^SVzvn%84l>`3lsfIDdeeF&ugc6*M5V`|>z^uhwmrqMOryEEumor=!XCQI1_V;gbmA45V zBu&zGI;+=f_zakj@p1UrR4^e-Jx8%n0oG*U`K#=`uy0a2p$BB4Z@6M>Yjg1sS+FQH z6o`Pt$QbS1R|qq4^C|JGxmBT0eK@lPEQaOizK!xIXeXv~x(Yqxg(dzl$ixpS8k?Psw zMl%ytx8aH97y(!_rf^A!QlEkKOC%ygst*9DndK4-8M9RT;8@D|G+G4rG2h>d2Qtl% zw`&1uS`cPQsU(I{1vO|siqkMOpg@!nE&mlGRpo24WWt`g;D0>Tx+e$sXV*qy^1^7L z(z(_`jVrB*`d+Dl5(icfEsCugT%N8W$N`@Ga}9&Zd!qe&}&W&#A&y8MDloS1T zVOI1V#O=ga9d6C8mD%K}-nrMc%-aB45v85U<*ZqUZMJZg0r*sztB>KU}Y zD=pDOXzOIqy$V4`2^-X6mqCa^H7syQk|c&G=Q1NY50@U0C?|^8kjgP7OOyt^I&+SZ z{0I?cWE|;BkvP-wvqah8Cj$kV2$$ftey?HM(tm4Y0Q_D*t4eY$(FCMKEiXA^5|wpO zg{UPGl;8-#0%!cGJkk&Sj7W+98<~~ht?E=KdlQn9bC%3U_&+_Al>Dlb;zBp76Fo^= zvjyGI<*K37wW^`a&43lK+gMQM0aZ}uF~CaL)2t}766&b42H?eP-PROagmqL~igi@k z0r2BTYk1I_aP=CfbmI^zTpSNF=swj@=n)`PxTKz?&FNYPkT)V zPzF@r@5}Y0?|}aN{pNiMaIyZ>t8KYaEt|6eWqhu_*)-ym`s-o*ph0uRI`Xom-T0W<_hxd9&Xbyx$8 z@FsMmr*IoNU}JC-HWufw8#5Lca1%LllW-e05m&GiH&xeg>o%7w;3^mo5ekw z-tPd;;}mEkW(hxYi#Z|K4qL=2-E_zVcI8%bF1H)Af?Kh*nAzWmS|xrEqnIJW|9V#A zK|c^2k4y$p(t_B_xxI?`o385$G#!+E#P|>FYS)4XchYrVz139Ct2a`S;GXbSa>}OJ zrijBiA^b4qyuv%O;{Bb22jiWfCu{u=;^ts zw7Vv(8jVbI`xK8pAucaIc4^4{E`o=T&{F1`ZXcc}SRV6Smb)612e8KU{JBUJPyDaMk)rn7h^d4@OTU~%mf$%x$CJ8l&`PvYhYm49 z+o8dhst7F$o&aNq0$g1YX7stNc-3Kp5ca{ca>pP&H69zEpY2_!Fw||+pN)9$h~ZEV zD0f2b>7qlXQc@wuV-xyI0+DItX@~fvE)~?KRIB2~=Tg8Rq83)lTsdXY zEWOg_COHDh+XXII#fDrR@|IeZ%AI_#(yEv?T=L4++;dB=Ugq57=NuWk1x`rCO-DO! zWT{N46Afma`u1d5!#ArIfow15*kzDWH}md2fNk1474#J;=i2xiWK}Xd^wCJx$o4`k z@`YV0VofeRdOHP7QVR8AFBLMsi)kW0XNg5W-@>SZ?6E%fcQxx-eWx9|;lN zyTGF*&X#{d>grp>kSXSc5`FwCF1g#esHN}0`2%4NegG)u`yTI4Sj9i12q??N>kSWo zC>QSBcz7xOIWzR;(o7=XR(^HgUhfYZMs?EE(Go@UrCX^%2W*Y{_Rqb72qI0|8aMs( zrGohXu=S78m3+@1C_Hg8nV1vXn%J4xwr$(CZQIGjw(S$!wsp_%`@eUs=f(5ltis;i zpW0Q`yHD@ar?y4qevO34%b{g1&WfQ&aVi~?eTK)%jIJE2jz3gel44{O$++d}W$EpX zc^ehD4Wo993?(?|C#geqOa;Rtl8XwF!l-S`{x1`okF$=KGY-1Ln*t8XNL|5T)}$E_ zrfhXZO>ZHePb5*ph;nxqE&D*NU-U(SO0v=ktFy!nHZrv2kNAqj&WVv7hOc$_~Ze14YTrMBy1b$3(MPN{z}7-!RIn&&9_!#@RMa z%wP=jqN58Bx$zwd0HSiQ&h<0%mIHsZ{D^Z^6vE#g;Bw}E7fD$i(el2bn|z{07ro24 zRQ5Q?2a*0clw$isXALq&+AR0c24Zb98pBXJL5=Hgxm(5dJ8u9}*a2?1A@A#%anCqf zz_+~Rli0g!sNAV={^>)Ts87ze$E|l0{HbYT%p0{RXJ^@Skl1Q`F%X;c9}?5Up>^hg z0wZtuV7LrsQp$y%_N!N^Xfz%knw|zLRA@Yi1ry#d!VEnA;-S}vB7RRsjLK4l)g`<; z9HUh5ui`2Kg&Bq zZJA5Hsz_&!e@W#vynN_5y%pc4^UTM$m(S`yDJG$hf9^h^#U3dTPAPqemmnm8;f6_) zt3?dB;DT5cFi+dz)9>~1-0&FrSN;kNV`LFhnN_ReAD%?{;CJf$Abb{qF8{|5x!j#K z@eyo#lmAYA_i4;7@>VPv?>Qq3-Hq*y5eO`2{IU!cr zUwd9PhrB?1OxItv>~wIimK&d!PfXYSE6|Q%$`tJ7d?v>?T_u_{P;!q!<>TK5beWsqUres! zUy*xRx%I@|KLn&omLqR6MReTB+>R#l8KLv7%iOu;1uBa8$<9$V$&N(@Qr&bV@Wb?f zq&yn)Q{Kui-<3%(K62%Zk0_?-$4&BVx94op-Ku!H|CVs2c-7$N%U6V9_F*ZavTXGq zb|Ub48Y4X0TV38OH0RYWojd*gi)|C-m4e<>AmD3MhE0JJBou;r<<*N*;a_O%4!!+5 zdBl0i4H9>Pv-M-}-xE+z9t4jB8~*kkQDg$Wo+R0U(xV2nerBj*aGxvrQr)^zsXX0Y z(}WuFsw;ii@8H9iwtSKA5s)Y~sMo3yzMkzs)ftpaFD1dRxon%TZw{yS9f0i0zDVOp zu#8WZXdnffa~rM8Zui{?)==)Roo$1EdLrWWjQ;QQ65K`v!{t-E1fBC~|8$awZnXS( z)FiHs|Mk7{;w4G_ zxOr%@q>&4lXkJJG(XWCfQwId6fB?eJ=*`+Rm>Xa?ztp9O_#*RyZWsZoSQut918R!xHO zF#9}{3*J#SXX{&FdW|S=9YGHFWI7w-Qfz|f?g?4&YaU%${-KNFAaE zWc>J{6?*+7Xx@gt)x$yuCFsx+VdQq;40|U!E;qusMLd`oM1Cw4cs};p+Bk$TPSs~M z9%!Vzi_M^mNn0X_CHw>93E(#yEC6sBD(48f6dmdVm z2-6tDsxD;t?U-SxzRX?HM4wtN6*h9?=%2(M->h55jA|}?MBigP(F+UKW=21)af-{O zSC&Jp<%U|Jfx1d4JsgS4y()W?D$YyCkMLKH%~~4jF%0BZAv2wlQCkv9Dc3O*aVWX= za(yYRLFS_Z--8PJ$*hnw9&S7D!R;fKY8ixL{d3GcHsaU(XWd>Q-xd8dxa13`dlDKe z!W+yvYt|B9$zxJ zlH+*5St1}C=D0n4nFp2;M8o+qdJB>F$IKW5w^3SuvfhYB;`qSbEJN29&Jq2d`k12$ zAbG)^-euFuge{%@5&PQ&WI>feSgmjS+PC(&@(kl94L1;?sp!(5T0%!rG-@Ty!rX^* z#oi87!ptccQ2NU)X;#>>xa25Zs!ODHnn}{<{Mau#pYWjC#Ksc*6{ITVWmkxH*U&@+ zF_Ukd#VY3@U?xWq=4(Z@MbEnFk$%cjMZ-h@&+;vh&HFoMM$MzA!RH&X)zZ^wv9QN1 zZ%GzpJ(u|L4GhOwp4_XjsE4VO(sN1sZyzP@Z2w@&WpGD5n^ks)s<7381`^B3wISCh zKbk1zLqH3wwf*FI)nZ>Nv)?dJOlOGRZ&Pt*8}0Dq^YLUIr&|+YV!Qa%=G?%=q*?wH zjVGUCAvh^&rk-~i5^3O1UlHoxhDU_ED}kn%91N^`|9HS*b>z zq3JM$dv=s8Tig0J$U(q+DF`<0POOu0tXFfiRN2ejy$}pT77w3T%?pN4J9PWwvF_3S zj|sP6c&L&>2&dbIO|!eNU&9a!CC7ktdJ#f>zKo?kdw(@tr9Iz0E%J5OXT6O&_VU%P zHBJ`1Xr3dkrV+Nb_7C4g4%z1GoX5uC694=Gt-wwWypigzk}x4vtovujwZ?&v&Sml6^>cj#-7iw$sM@Y>H6xCTO`%E$7-uz zV&dV1%0;iuDxF&3E+DDqJ-P;@GfPC9F5tREXSlc?RTvgvaT~D7Dn-a$9_ipErNN*{tg^6U;f;7cX`B;Tox$H&YF+o! z=eAN9QE0MWmLDD@^%eysiM#8zG^vRkh7`*MP%&D8l^!+f6owx2@RT-aH7zf_qVu6+=2{qF5|(d>grs{i&aZ#o38p9)HP! zHJj&$U7ZtOL*x{3Xlc3qfaBXEpAwVurWtEAs|#A|A1<`=awq3s913OZWk<*q8VzGt?ld$RxG4y78h$4hS8yAdIvhM^5tGMn-1eM~6bmI!DFHY?rk3HM-DxwW;fVpryA)WdhC_q5)^g-1`hMM;>0#ojkh@6J_Pa zIW@+PZYgAUDUOy-cIi&J_2C;qkg^Iyfu;}G^zzxL!u#f}VPu!{>-z%a^DJ{rMR_NH zaZ0kJ=AB75u^XWgdxcV_#Pxu+f{He-u=|~GP=wMi&T@&^LP&=hF>2iXYNVRJ^+TOVNfk*x%*$1$KNm}!n!fniCM^qo}@9ij0!>ciUI zxcbt<+4Oc&PhYH`;r)Ey3^6KUzqXg-XrG> zd(b&5Nvf0UDR{+Z>aRU}&noqPY4H;SOjApxK9&WK2IXB03!h@~6<>^3~ znZsLhT(HG<3>sy_O}O3Y(bW0kgf2Edv&B;_u7Vg_0?Y(1;#!zaJI>&yScnxa2m6Mr zXgJl^jF$z+O`^E@_F=tagRa2on7-oKmUCJ2H?{mGaOK`|CRn@5{a5eNClRL*06Wul zvR&p=1aq_GUc15M_~RNz-Tg%vWA|Jhc{^sCJHjw!E3_^YlqFI`XmZXmvQpAKWf4xb z#q6TJOWEFcxlw-B~z7A_w}O0d|J1Ykf4-3 zgL#4g85puul+rqcqqS2Z6aBRPli%=lL{_37bm+`wNA>Oni5g2qt1;tiVV*)E^HEsT zj#?+4v>Q4+0R>ye_S%jnhaOjzD{d}9klW?6DB3iUq1JtjcUdKpQMRQ}O)x`X!ZVIx zXd3)~ItV7HWXuesN+k ztzX9GFP^Ef#>f48x?RCl7mq~k0y38en$X$&AQ@stQAeyKr*)q{NG%jnFj-5@iO(=t zZN|m02RFq^mY$vJ*I*ZawM!5k-YMUOyl%aGT@ zD2Ybq>?6_yO;@MdHx%*nm45yPtJYS{xUQ&6ZkJ7?psiqP7!2>u9=HS$OO1-iY%AL> zS7*wEG!x{n6KO<5@)wRq9&M4>g(FNhEZ9#LFoe!A;TV7=ayS#mJTU=X=wJB%hb}@sT2?*N+nhBSpC@*#j z>IUxsM{bUpiXHCV2^8Gcws1wKh1iP{TS5K%!Q%T!xwO2Phi= zNxnE(wNufBw*J^Pky;;uYLNzwA#6ADiI2BDV39WVrCQP|#oNeeM4U>~9Hi+Qa8b}} zMBB1b`ke)*^~>!kxcv*RnoSj?ancgV2+#m zv{*Z~H;al6V`Gm_xNtz~pGuUj;oQY}?=IptnXp^}AM>8dKWP~=Ir6`5A$SpbbyaUP zxHg#OecUZ&=JH(X0@70;U8eUNVEgq`$H5hX{QEUBGu$gEmpAVBkkZYQ@qwenjuh0bRKpxJJ3q6; zIO}Kh3)(>yFBh3qE&{)-dIXJK81X9hoLs|pp_A$gAT(v-Q4XC$e(29tu_aRcIxnW? zP}YrOv@q^kl`RjVcOE_U>Jn^6l5S(Kdhf+7rY1-6ZR>)Fz>VmukKj6)ppe++W~K2H zi)0Q#SE-uSG9EZ*dCj@di?HwtPtlDkWdr50lhL7CED${AiaSiMw5RCJTJZnp+19#h zY5c7nZ1QzM6f{vl?QELr;cIv;=9*RNU#k#@h{{STx=>Gm2zna}^@A{Op6n7m;i}>k zD)?tk_HBF=k0H5ChZgeM^}01r>B#;%o@)&b(dy}w4P|F^XM<8Ph76U4vVK@itJjMk zeql}cGfzY?PoCS@7_Rx5D->T7Z}^W_?~6@pa^jh{=K+SAy9<4(OLv`@5n?;i0az91 z;U7>&#>`N7Lp*QoOU#W-#5#fnQGA`0GRyf;b3R@RIS3uP#5{xX>=reqxBvP}PM3wn z34KHGUmf|B^h5e`Pwg8_VwpI+nQmZ8Gq+iPPBe-(-6uZcp#_jaJ*2mJM1C{_cW753 zzVQR|RK}=bPDa@H)!vnY(0>6e z2$Jqp(8a+_*RTaO?i4N*-q@GA)Xbe#VU3}4E$!Htb2bnmecl-(f;oRf{9_@iB}AJ> zAQOTF(*{2eZ}f;z4BeKTeU26`WR50CW%P$NVTb?O7t$i*55Fd@k-g*muU?ndw3zr-J}c2~3=#~PdfQ}xRTwnz0_ zc8pBG6R+V}HB>?v$G|T&QVPqMKhx;zp98zRo4h6DQj2rYX{UiIg3wL52IjIErk}bz z$DDozX3M)^2sRLNzXg;eL06T`1kC(P@Arb9NCY)AYje}k=`Qf zm{0xrrN&`8@XpqpvFnNk$HU|fJFmVBdS~PIu}G{Ss4H9qqWgRg=D-c7LHoh3sCX;h zxs*utLw@xCSwp?#SCjPtf$)80-<{N!C?E_2$B0;p7oc?gyf?j@khHI=3YNtd#a^=s zDVAXH=-H1qN@imeP4|OIXw=0=@*^c!eUIZ<*DFRkiFI zgJFC6!Q%R0z!(z^qZm2rYEr}_*xZa;p~0AbWGL^7I#$+OZ=&v;hG8jM3*`l@USOHc zB{>NHi90{k`o2EbyIPC1yEaXPzlR9E`KQAxrr_*8NalI)?@G>oNRqnK3a=+VSTWCiC{+}AM@w_FDCvVdBrWo2x*Qw)XcjY1*>sY z+M$xpVxZ6@QAbIhTEP1%gt_$YDN(m2OEcu*t4axY2X^uBl>{=&R6`zoZKxgh+CdA& z-KCiHkAnuCi>_$<#Xd_wrUezqR0ElXNc&T|VXg^#5B@F9gj($+wvCzUfeCJLQ?sd@>|O%=MDvAa^{Wa%I@Q zhw@f<%ltjy*O?O%Rd9u zZyCUabe{@>7MbjOgOuE~f^d81_dcN|UMQG!8eaX0&C7o{R4e`{Se&A^#wCF}Z;h43 z8Wvr4LSf1)U`kwTn#<+U8R3vHp#Hk9IuTeDj3!qoC#W|8rMyDL%`m&OT=MANa&S!xe zRADTD0^Y{AMr51BeUI+0_zFdi@-|}If2UFht0s!qO6L&!W{~Q+4c=^g6@roNe@Uf= z)Vmmmuavzf{W-`RJ8B^(KA(&A-aY%^y!MStbQDn9v>L)ovNiaWaKqK6|yR zp|1Du8b#XbUKK;Nd|x>ItI=A;Si+I5RzHNR@gP!#a8u|UB5n#A?E(k9iqBHimG`1h zH~uEqlW=*h=x#8HA~R3)80K>}AXjlF&9-hy{6b9>wVsm&FSl9czsg*f7H!~wd<{y0Afy+H0LHnbAOU~e6n$(Oza!XzstcPb6HplqLY-$t`E$q1}~0Ne%_ z_>}NUlq>GiFvR&~hVJ`0M-z^5YN&DyN{HOEj4J(6Tevh?6pPA3B8tAQ2I^yoqI#IU z*XMbXJU!IrK`+4@F=26CU)Nl&5#h@j4q{(*o>`&ocGZt(w_k0rKYy{U&0G=j9U4J) z;}>Bu@sgj{ZDbnx&`iva2L){odQmA#IU;9?$ph)Vc3ik*(gn+oS5!z|`K-3U?Wwjh z6?jE{ng##op-IA2kgr>Y|Mg`0+8ra?*SoytIXe;0fX5K>Gje#R8M!{ai6ve0-d#iv zBkT-UDPP*^mkl$yZ;$*x(HF_mU;dot#yacp4!47N=XOQfpC#T{3L^B__E;LqS+@*D z5l%v=y;BWo=mMvjKVb77m+_Res%%r%7cxyy99Tq{C7yz$Q^5IfBdvk01 z&uY8-b{g0#^Qkvej#BrXb)!a5;w@e4UiF`zLTzW#K|M+XM1;I33EmyVCt1^zi__M@ zPpF!-hC|;0bB}T70{*mZ-2%5WG1Gyb291d4o=75Go3d4!qTM?vSJY&Xnrn)o^<7QZ z=mE*9_opNlL$;8TX{R}4tiV~SK}d5@M(7JuwKopYE|B^oAXeX7OKl1;tnV1ipDCx9 z|F18!Auu2G%plG8FTznT!#b>e*i5o%@}UvG>6Hz9%Q^}6AMv9&mkxi%SnrR$wP8IR zOxP5L)&b7bv;jMFS2c2H&CrN-)Wa>50hmfDy2*xd>-(zR4m5r<+>wI{NPw(Q@q~SG z$QHxOUle-GJ8LN=ZDAXt(puKzeJOujZ9*LfI*YiGKQB4yhGLALCBPR3N)=wDqPFmt z{wkLYmf`-oTfxzAFNw}dNsO7UGojkz|J+b1%p~x34Q*R~B;r4MP@jD%G=6)DFBIOo zsz_oP&s1*PP!3v}9Ce#+X=s%- z-otxVO_zbKq=Om`p`ht#fs0!*0bGKU{j=%p4sMK`hz$9c5#x}w@ZpjYMz#u= zq6#;n`jSgu3=**q!C<5NMVR$BCBA$CBsDg?I=-UhJ(Hjn!#8l zahcWg@W7#bOKDAa5aSZb{SvrRI0`Kq(()XMF2MkmWgQeJSbwGORoa%1GVA_N@VIXi zRgiGs+7`cFPaMe65y=OgTo`1=IqQ$qHy%#rL+~E+@t$?tj62(>%#zLt+YElW=A{3VMDb4h8VBr+S`_w%wWg#|wu3sj4znxk6I z%c&sJB+4b^#=#Haf=!E7?q^hG0e4(`_ z@hSxRZ5Q;m<8(|Mdsz4dyZfo8O@MVpk2%P!igOc><=^`cY}sO%w1&k=b&^;Yt-kEP zcvhGJ(bLzY_p4t@A8R&|?H;mLf-|Pr9QeE{*6%u0$OHl(Oj30ZD$Xg96jVeie{8h5 zbe4!$k%O`BxHm*!KVn)Ik6rY4UF>%f&lz*?5ZiubfeReJSo>T~Vp&cOE#x-_o?8B0 z6b)V$Isd7YCf&l*z8OzCo*0d4U}>PwtfRUavxr+IykT^ zzUTFYAw2a5&H#t1n2@8MrK{Q^bFtl^n15PMtcO11c;3sx*0oisn78hy*A!T#_%CA5 zh0UnS^Y;6M+*_4bVf@#EKLfWF!72F3p#?r$Trvhb#MS`E8alScPINAYt;wVFZsUy8 z4%)maa_@S9AE#(ZE+iV6?l-@S5nmM)t1GHjekoHM9Elf}VL)_(x1(tfo^CW(!mm(j zcztr#IPtFTOcSjNy;3%|*6_^Q@41_w*W(=$YbUaU6Dpu}Q;BAR*XdkLAT5?}5^9Vw6>^2EQBj)RYRbDa8Urs z+lM|ukt_sJA&>89W-LgGAuEmCq0DdR@w?YWL3vJ)Y1y#aT}JsleKno4%Ljum>mA#dQ8jp_|D_gwg`M9&coZNbw(l` zQ;>T^_fcGqvn)$iZE)uIn)6lP2elqbbIkLO;y+CHcW=|{K#97(if3o_KtGOY7Ft$6 zjuds@2)PZYkJ3xH`I)kir85?gv2G-3(H@Szq-2=loaWM{;VHeIRBOCe;w8PndT3o@ zJ+3LWp2U{%bo=Kvqj{?*#r*u!63A?uta4Xu{T5I}8%he}^o)REq-Q2a< zvht*`ZLw}O+FWb4q1t>kb<{Q2?GLFFhOsacis6&Fl&0#1x{g8W(NPZ3ragyqru#=D zRLV-f9;<2T^j{_{O;n}5MZ{YBL1)zJO=?I7Q_n;xYZi4il|21~egMy0i2A~B8baHg zK1>zrB7oF^LwI`sznl3CnS=~#0d-Wb@Oj*HtYfuy@RNhHI;hEZ1bKT-ke}3)3heXC z{Ow4OR&_!2ydj@c#M7981@5{TOFy(b9WK7#L9_BOKtx_;E|i7nXXxqupfhX^vy1V0 zgMSY^BaktY>}*J!a7U8=A?6_NOecN3IH&ua{TN158$V`@xWsrmc}9bcLX}k+N=~t`!9jxfYu5tBOY;`GzDeLQU6UX8DP|7f#B+?U7#NGhma0846+`zjcj5R1&d<4A z*~%G)aPOoPNE{Jy?CNX^@+0{0lxKh7RxLZq*k7q8u2rD(*VcneEw_iua4(I4)j$W) zcEWK6oV1*7-Ol|t^dSIge7pW&GxeqFoxwaVF|COff2R~Ih?n8!1aTDEbH+~$76(_? z%cSy2Zyq$u&)Kpv1*I^!Zp1Bib{bD-_lk^b8t)w*WaeBeJ zeOqC4#kv!jn$W#$X;7C5A%#Ub=)(3mel>~HfC!pwragQ1ol!J40aiONW z<;nHr!3!NLXoKy%xrvBK!EO)jSu$~A-!O;3>vQtq0+rxC2Xk^6Q#NqEa0t_h1G#N= zh)fCcz-NRNNd+YqL=HGk4uH#!F6Wahk(xKxH-4sscjQ!@a({#z?LBIgH}%HqF*^kl zyDd-Pc;8Oq$(8bK>>Rv)Qo?HsA(!skAHyLOa!Bljs0Nd*QqE4kl|*8f(IL5!P)H!e z@f4rwIP_yf4sRu77Ut}`*At2o`uy{A3}6(qfsHcXF9QqHgr+kTUD)ZSZO|v&`|KGs9bP7|7d@r6>GS6?^}ggQf6l z$p2vzRjT&QBBBxDMU8!Xu~_-LF6%kJP;5=9D~b8ttYoF6;D^8#Z+(dAp}uBTt}LxB zgEzgtft*?8;RAEx3j5kXJqfuj!<{=}-s~|=R>jO>qp%hI4`=7EEmv>pvRC^JT#n0W zvhD|ebEcOQd5pg)HaFTV%6TE9Ru3;P(BkWCrRW-rJnh}ypQ~E!fvkE28LiDZQ0A?+ z>3D&xqiW!OI_Hiwr*is}8hNYMiTsU}}r zKK>w5&oSqQwIzL;D?pr(<{{>IaGftCNPO8|=|Vdh`7N!Tkout>9(mMQB;Neg9G{$< z`XQ!>zuNTrNFGYN&p3{`66A@#5xyESpT?c+7e38x7$|9pgh9aHFj_IwYJ84}bMu3G z{gZ-v!9ZJg9hS^rf&Zref4^ok*Gv%fETMx*xh? zib|N_&7Kzz<)*@Hm?jp{=M%9 z&y-h5d6i)*013~lN^r9th{G*0j}cQgiH(RDJf>`6$eyG{yc-~i+$58Ul%n>(wP2v= zhMAj;Ld{I=-M034EzP}%dxiY#*bi>-MN~f6L0^x7voSKuzA2M=Id?P&Dyxrn3HuNn zUzDktLzl?w>3e{gcC67(7MmdHVC+B>bx698X^~5r>CLV=y_I`e_67t0$UN+70^ zL?j(TIS)>G@Rx}5e!aW%wsH8kdX>2|ljx{uDiJEwNlXjhr$yxTu=vj>@!Xmou$m#V z=+9+3t}koHT4>#WmPvC-zWz}oBa2D$*WaMO&lJdhwk`Sw$B`o4{Zv3_u<}-1e5{Sf zYUG^_5@Tj!M2-f2z3Q2cp2^z)J_cvqQ+)&S-Q9V!BY90=9!AnisJpYnVCB;Q+cV7! zr&pCA@dFlr)RuXCxJC2!ABn)9&gIfbDwfMRZFBPyB2rXb-wS0&-7Bk>G|rfcY-85< zw6w)z7SE(|)t2I_pJq87fO}9yFLbbh*5QK$l&w>y z8bM!uh%<}JolXbIwow?xb>tBn*>sGN$CZRjg&0E`B#<)u{DDBg9x}3l1?8;CYdiA>2d(N5%X;T*2#pW&R*^SMSIf)z+oVPq!al{=GM>Zz zoNnU{eGnga>*FdR-_uTO@8^V{i+keqP?v7LJrDcvoINE3j2+src;2!yB5tZGd%FfR zzm^u)ZtG_|biw`|wCM5#W|(!Ax1Cj2iT`M8&NySXEBs{9Kz};8 zsDyRVVtCT3SUQTiIWcXvSX*?`x>%2pxzAF>!SxEF86u0c6v26niL`lw8cJP=LNq&C z92^_AaCjzK(wk}jo2ex`sYx!Dpx1*QPk3j=E6&sfijhhnK?``}RXHF?LSnF(5S!w@ zGM{@u);omfflu*@kFSn~?@|3Jf2_4Uv&y!eHP_^+fvfxa^1-jN9XBSA?T=4ojupIR3?<`73OGBv8c zvC0YV-P8K9Zp6(?JO+b|tWhHt#?pUEeOh@^0mx8B1?4Ed)miXW=Ytd#G10BQB4eG zz)TKM<4y*aT@E!H@IbZD8O7U$@Z)u!>dl<6hzV^>is63uI{cv?vIRfWQ7M=~oNO{W zYc(XqYELe}b*6%atu`-tyMz&LP|U{h8HtI>x9Bho7&!^^Ll^amKNZCn1>z``Ll)yCnad6HOTuY5$kp(3KrIR9 zf>?GFk@0H>k#X_V6&kJeHbOb50s4?3HJ%8dw6{Q*ekR0}=X*UkpEmTCMgY|3)8a^3 ze;*|-SPgb7?UV34{dn31|O3gg@zl#Fy!bK6VE$^2DMco&6qjx6YLyD2&& zc_Ae+3Hde-@h5DT1N0AVAk+DuUj}%P&+0$qsQ_^+dcJ}F>{Ze`6jfV}zjWGu!&mnF zGHgr$orkRFRyt&jI|i;ohATuI^o~Kx^ve;f7dGjEz2et0-hzM%2;!8>YV7l&EM)p&ze+9*BeUi?N^Jcb+W!YeE77Ra`6cC`{z!jGyMW zY9p`p(dkl58X_54{`ONR5WxZa-5A8RN~yL%&Eq36`jzGbjmygf?ZaeK#yR_%%Q|EM;B1z*nA41cy+AT9lZh_D+UcUKJ3zg@@I^}c;+)l%eswuTQGvNe-KecptPIP8?=kJoA; z!G!Pm?3FXB%j4w=$irL3-ks~@P%ZZM4{0dhozGbrJpviJYty72EJ48GG?!7 z$*oxEvtVF--=ch}7P!Lqi`nXfaijD9+W{kbj0biyuFFp6irc#sGcebN0Mh6>Op*|hwye{t5goY48IYuM&gNOCyw+{ zPTrqO1d&Omf*UA1}HaX9dL zW_NlFORi0sK~$O7Og>UX)_-X)Qh?w&fE8Gm=meN$-g+Wh57Y|CMcu9=TBG<70@WMg zX4pQo0R~bXzvoy7Qi;JK2!e4+EHh{CovfKI#kAKqJSu9euej8fSqV+g*T_!Xv{AhJ zYhZYcmRb3aFV@Ij%7A?w)@rP8dU1nSOt0A4mGux7eedA?Bq1JVLvng7uQ&siS=n;? zEi=~<_L`ftZw)Wku9hbv9k4gmHt(ji6wsNaCrN`0#AcF67l_GAye8C3nz&R1S z{b(vis*sNoD0Fj0K@;VwT}XcDKxsc37)yh`Pcm$Hw9sjoa>=nqf3WH(T(+t#S+=Sz zU#?OCSgM?zuc`o_BNQxWSR*{A&^tV*RL(u8nz6i^mG&%Co?bG7sdTe=UwFFQtSKIX z%};=zvd3U^v!|ic?+NeA@6YZO;M%48L~Syjb#N;cdN9_?Cy>k~D*vgo>Ryv31HA?ZHam}~@9Blm zN3Nt)@XTVKJ`*A3f9h-KQmMtITc6iBoXCUjOa`yG_86XBsghu|U>o8djGs9&b8V{IA zZU0-<;@~zpt{%vB^#-S#nrRQ^yMDyf?fh!=Upam!9W*g-3qK)z%2lW#Vy$dO$}B#l zEQnjFS`)Ww)|Iq!i8e84@ZhLZZ^~V{z(N}`SxVXa;QoR;h~!l`E%<^zj2?2*_9?yF zGH7UQ7qhyFCvLt8JM3^OO3P+Z1G!1F{cSEpj^y>UFP~1tQ^>LgGieo_$0Z6H-GpQ%CBx z5L=Q(Ri*!{H|ZbGfFZRcYphDY7|j?Xw6sSyvc}^3VELMPh--4kG@^|WS7)Le%NT10 z_L#^J*9J&c)SD>8vn0|2Png1z=&a7P3Op|lkN_p1@_$lBRl1VVl#wJrN(D#+0aED3 zQ%1@FDHot54vi{asz>SxpaIGM19?3E9}C2LsP-hYBVRq2aHQ$=)^ zWGq0_C)OS?zq3mb&Rr>hZAt(sXmuuWV_NN$9FON7#}hHcE;go-IdP54vO)6d8aNg*ubI(Ns|4e_j+*X9}-pg}_v2A~c#JN&Qdf@Lva`lqN$L zI!nImH)ySl+_AM8Po80nTE65a-fbZ6!w?stHh8DasW2&n)83GEGHFJ{Eq79>EZwbqEr?Nddpcf_48ApWFQU53##J(tsYok52>BV za#B;pZ&?p%Yy>wxij|biLP2dQCjrQ7tm1bys@8QL)kp(Z&m2bZjs9lhF|x*kRF5Va2dSWcRNJk5H@%|sS6ASN2{ z2%t_FkcSP#P5RG3S0lJ~63ba7fCmW>=l>?C|I3;ZV3IsMSU$Y@s-F*t17hTXC5pao zW_YeA?@Q3w~(#CKSqgc$zO-||_XPe*C`NaHLY{V(}l*Gw+*u+9vaKtG# z-$({eZZln{ZAyT=tSWv=^+3jY$ix40S5gz+um6%K5V;<5%J_dSWCnVh*pi23Z0!$M zYSaHaAsJmBcj4_vF6WMGmj>B{zq8(Vtv703u2Yp%X$Rcs*2C=xRQY<1w!vAz~zz70|!e)HgH}L-aUBCjxZyA#X z%$+D;?&PzKP*rm{Xq=~q19PX81xnU322JDq6et-)18~5rIWRRG|1}<|6|#)bRdZN0 z9_g7)_047k7PCM}TEa&FaG0w(T+D#EGYiZejsGuq%z(M05owqJz#-Lev|7k8%mv^$ zYd9*IPssxj(W^O9%%|#PEMs^y953cF3^M^ZnvF**g)E{#Of=vTKwU5Z2OEf6^q+w) zW>a-SmN7}d+yUbJU+&}qXPid#5`SQB%xYwP8HEy-F<8~WiKp?XY%YV?`!Z)%;~S|1DE)tJ9B2PE6-rqy7=F0s z@K$Z-X8~|1t2v-G9E%!L=p<#k-nTiNNW$(-2JeWCi{=dtgTfm02j?&O1SavW+t_$g z=Q9EeS)hb1;X?p8IRAMtt`QLE4=DK|XbB$xz~T5$ckn-7R+o}#aG4x8KHb;E_7($6 zIevC78+zToDQcYGdjkP&w_r5R`HH11V}N0r$9Mw*i<%DMy(e%WM*jTg>b|FdZ9m4+~08c=$zssG&+?mX!G?&?2f^(_PB|Jy?Tmk6vH|B)UrSH>oqVuZJmAE?q~FniM+zQKc)8(`h{q`&#dxIS zQIJPU-YMnfmX~5)rg=H%rJh#;J>rEwBYL?95TuuCL2h~kB`~O$N<*%CCDu!ciE}-_ z2JBry_EN&)XzvQPm*ZZ#^dpup?MS6-H$uefj97a2zl4k-K4Qy{AhW4Qj@Y*&M(xcJ zBzE5~BBP*>mp+>MSnK1lkJUbc`&jQI!H*L^mi$=r>`r_C z_1)8l(;fD}!@mRb_|Y-$EA-^T4|x1f;%8v~-F@uL@%h_bx%2ZEj12w^uG-+wi*ggx!a1}ig+DJjwZiW=?%lq1vwisT>Fv80uRnh5JK)vJ z=g;1J`0%-X?p}1a|B1W%wza$V`s2;p_kI8(eiTbEVFCajiwFoIe@;pe-*+1dGg=c_!g%Bo1_JGX!C z9rgaO<4>zYubI$2cH zyeOTT(rUW6FTZ>*#+4Vx)%{%LS3Bb4JTIzp zZ_lIVuF_0Qyj}hACZ8;3VjzEdDr+qKAo6szwkBD6Z%_XAlAFmuKKdev{3`Bh;2OP7 zW*5`69N5RGTCGYky9#<{c+}?FukbPS&44hPMJaZWA;pOLfMi+iRPhpROd=X?Jjut4 z8-AJ}Z(ih8PF?H$yb#6xYcUgJOw7q_)*C0YnJ>aB z2tum=JQEK#@j$J%%5XeQXOlu?TxGL!RZo8odROVJ5(R+yW!1Y$s_|5mzCf4e2|ib) zoMQ=yG#-xnGg0kian+OGU*r?fzsd{0pY82sy$r7x=vExZ^rd(9?Ckm3i;H(J&Yzs^ z?fr2#j%}WPkU0(R?WMi>qMZ6!5N62bR9}c{QDi&mI-D2cR(6Pbk)jurlIDw20p@jj zIZLx^*`u@{EYmALb%!PE8m6Ou8mAjduT`eeI?Tk!s@@=_{JO?$$#z3)Ogm;^ImwsR ze*8SCroF3Kj(U&9Uq0v8BFQHCjUNQ-J4~JM4U$|7UF%o(PbWUGNdv4}hbh&{eMkM2 z^`w%dLHOPzsgi@s@}NozeDH!ky1y${EAO`+rcV#KRcu;_E0sB2t#;F1nvG|R2}X>9 zm`0?OsIn^Gg0T2r&(m<&$riI&e|vtF=BF_p_VHytODj$s9*+V5Dc#${8}KL{q&@Tr z5Q(VXwQ56P&S=aEV^P4b3_w6hG}!9v29q@qvYxQqTzs&xv?`l(SuEVNoD&+H-6FG} ziMt*7+gaS1bEnQ zW>p1Y5{vjtIV4qLAdou}kw8C*tNPm`$v0M$X$~YZnBfvo52ffJm_6k1_2A+`U>2aNL?9XCK_4a4ca^0)) z*W4*dx@Lh~KmOrQr9Vs#ei`ithbc`yGCs@iL~)vwAl&`iq}Z7;5)yP@iR-hEbH5CF zl_)De34&@`D{I!R==P% zM!E8v`2zL6uI^_76;R2SMUEa;_ivKfLin;kigj@B1>uw$BV@5NzS}`-u`qW*GXkpjH=!=Decm?WoaB&$*dIKt{QD;t{|N7f}m;I z#MF98RRND)Pm@W0SECdt)gcmaYp?R0SwmpfX)W2eOLiy4_aqxrQP~D%(u-Xa$_=@y z$YpbbiSN9cHNS{`S|020DrO#w2=V zRZ{?7=*{wEA_uI$zpOeXiX)K|;$RN;oPtKpC)r!(k9q=*a z;ocb1MbkwLH3)B5^dOcU5mg8;8A@&Jqp7MW!>uBW@$M1T$;?nAFE6S~;u{i<8S<(; zmCkcSV${-dgC~n3q2EY^PNJA4_fe|RrPn4Gwuu*un@dp;dY0mAfUm+}!m=YdHESb- zNIdXGEHsx5y#RaygGw7I$KsEl`&}*UchwId9<2lV`e%%i_`>e7>Sq!AODS$(SPVFl zG{Df1=O`4ITZ&c{!u6&)66f!{NOkUAb8%zhr@sLMxXnG_@`d)^Wdl6s`vR} zcorYx6%QxzVHEu|+5hY?yoi@;2K0HX;d~k|Z*nLyf>u@J@iPEhcp*Q|L~<*1@}lzA z;fMI}AHFTJvf03X!)Gxu($}K$hu#>g_yZ7QayiqFoOv6Ln9jKFir!WK)4=8dP=gG542$|p$lWho!IM|nY9nAg^L znq=2hRh2KsQ?5zBP#gLgmFmYaSORx=o~HyBYR0}%A^V2b%rgVdzM5*TMG34B+_Zg_ z{j%?}16LqyG?2^Lf}mnDp|~&*;D^QKOWs%Co zyIN6_Dfz^&EL;ERh~KtEEW(SS7{&BwwOX$E&DQW*(PrY1x~eR881d@_xC$k79a753^x88WADLd%&jaG)rdRKpC5fLK3gMH^E$7Gma^hfW8=hkgpx7 z#`f~5?4|8sTRH~;&jx8Eu)3)$&mCYqBN@TZNr*!qgK(IIARZ17UMRwbbXH7t?YpM- z)ynWA8eNL20JAWYa0@?3Sy}|ThZQkJT|d&9qY=%X0XHTWOx9PcM#3&Yq~RktiKLxo zl9f*z#REfjSwE2G8Ufm$4WQ=1RuH8z@tiexahQiin2h45z9i|;UkIBZq0ffN2;-w4 zP)ib{U;ATZ&H-K?E=A}=@58j0%;&Rv40c#zdAo=V+Zh8na!1@AZ|Y|zF>5xD z8d}X~s(EPpvT>wAp$ue$L4VP;-1Iz#i`E(~kfvs`#G|1hlW;tojN(PuAv-4FBFqE3 znBLpPWGC;nFCfEmT0bYHyi{mBeUQtm#8?Vvc_nc{>)S3f z(J=kcva(8ME=k4=70-snNZ0KwItKKN)@4}gmAM}8?YXpjW^E5CWHw`rHls1-2*8-x zL*Ff4+TyvC%5!Ux$^uJ{%V9q1n~86t6;j%02pkR8Gy;?WC}t^U?HH1(CL7Zj<8F6p zS{sq+Kx$_GB=nTUEdhb;>aK{Vq@QW1L<2flC zc}$jw5(X{Fo3JXFDupwW?Z@S(IN_>2@A%ji?YgZboZB+i%Xb4%4il!!7ssEw0pF+<~p)s zZZM}+*3u?D8`>D;Pr@o(52dhV#2jWATgRMwDDh z9pxznD9xk+c>NAy(L$VJ!Y`BY2Wx6s-YUdfm!#8;cToFNHOmgye8s?*-7_O_%bXXd zywG)7sugmfselXC>ZbV@cl-gF+b&OKQFI&Gd2{ya_0#hgzOL3|m$2t%A^RG>TWhtn zRR8{me6cf4Zh`3ePI@z!;703WM-{#i@Cr|MJgUG8cL2*B0buToVIU&gN45L=T3<92 zY-cXZp102fr8?ZaW)f{?omE$}UQ3L93&S|6;e@-5VcEjT3{&r+1W?aa?y7;rCTY3V zW=iCU>R6V>@?9~6Q>sT%+n_If3Nf^ov_;-lD_KyYx~?DUL#s(M^OBfVJ??A?CeV|; zN11l>w%E&_WuqRK?Om3(sO^9%=Gx}vM{wO~eg`(Mq0?=?zk*hdOgyf}Dj~ig(A_)z&bGMcKXt^9)#^7Ozap8E;X#R4hXnuK?~Zt)9qZp?R6|WNeKGf8aqUw8w!vC znZ6E8t5cR@o}}eXT9!_mt~N@(tTqEvGpTA^uR+B!<2wzdHOmaM$CmbFo_gW$huZ2s zk*&rGjYq!^-}dVLp>_KfqQpD@ZJ;Rm&yQIbulRsM>NzcSlV(+!Uu-)bScJ^FS~`zAVuT!a ztmcm}f>~G-`P`+-5?i%p4?zfsP?n2{yP@Po}fO1Em}Hj;*f6C+y4yp z5gS$VOslk|3>%9}xv5r?mS)Y*v0NJ%;89JEEBVSLhhEm=P-) z2wP$mi2_Gpr7TV=|0t->^nRulvM|%$*pNKc@h`R)(4h#rqCGS%A5!M)EkFeskPbkX z(Qy%$NrBkbFKpbDOXw+)=;7~v-47@Ys~7n^oQbOnS?H%T&og|0tUk}B^CJQneXdqJ zBy}YwflFW#zmAt|rM^vO(VxX1L(I!%o)nV^3L79cf$nmQV4y__kHJ*h=0 z3%`#&T8duyL+oM5Ncns0QIH*;{u+}ikl)ehqrZpz{E9wBKWHiZM@74v@;EQ4axoWp z3={=UD{)h@)T$CR6x=i-#)kXXGM6uDuoI}oCgnBYf^nN99;S3)sj@ctH7%3x<0B^t zKEo<8N$=4AtMocHa@Hxo`>E+aP;#75prG!a4Fd6CaxK^obYQbJSdXqpc4slCXg-X` z%QMHxl4d)beA1ArliT!~swQ991r>TpUX$`mJp|=Mkw!ahNmCxtm*$)8O4FEE`ZYmV zQ)j~~zFu!+(0csdnh?t{XhvQC+kjKw!eR7AhIAl<_2W;|$wa`kF|Mghq*(I1tZ+?u z+Nk$?q!L!JOaq&B6IG6auyc+G6%VM|aHo+d7elife(rZo<@kP#k&tyG#6wa%RS50Z z@jK|k_ca%0xw50<$IUY6!zVWp)DU}b&wcCJig)Xc8~u4PpMa^F23t*lE}D-v#Lh(E zsQ3de)R_FpBqGKXvm<4su(N;QomEcrTc;201t`DNr?WYe+T>st`BUV2N-k`_qkb9V z@ufq)j3XPi#V?K=k5Gdo)#4jSY-$=0JRmUZ3})SgMknF%a@*|k*LCqXiSEig<{+W9 zA&D>3!MD-(eRrK?E(snAFm6lWY8Lb*0$#rk@#niKlYPV7Pt}|4GBy%7}-}y!{TU4kgEhfk4#W-y@hd zx~Sf=hI^U?v!f-ekK6dr>yuY$eNufTOH`<208FA=y_`cVv#!c*TtR33vMg7=u{3+s zyGv`D6Vw-*1l-~cz{YiH<6c^2m{4pqQDABLy6^#a8v0$- z*)c0aenP)YKu@boy1fiU{_dd!YfS-_etVc^h{9V@cvAu`{Vi)dIUZMK- z4>Hw!tM&MM->HJVq&37Rb!Bfp6KhSg+AG^EpNpL739s%? z)^WnT3ss+Ni)TCQkh|ft^u>$b~+K|vvImdBEG!6j+MgByC$j=y=DAcRN_hXkpEljO#HwrfEZuU!?EF(@TXnD|_a=Rs> zKnk7EYW66E+TE75wh+l8=(LX&Y7MEa6NY#{tZX)Dcj3_Pg{0j%(e4Da8w0A>*9CBH zg5bR@8q{cl9h=nuvXMRoMz)glE>bz3qD{u9;l!3}6TEUW;SVPvnrx$h8}vR85$@IH zFr-jFjs+8N#_ViqWpn2`+opXaj0;wgU$^Lh)zF834}Tb$m?oqT$oE5%#t(zf{50kmuUK8!`LXSXQCWENh9ZIx1>&^d zG8&MCm$B&~3-L#o7_d^u`8I+FdW>wm=}DT;o$o;^?I(SnDP(C?A!B^mfWkp0h}P`h z0{0@CdsCv5a$o5~%xr8lhgY!vPcn_V4w=vN1@Sy$4wcDa>cLnH1!GR52- zA15JDY$sy$`hkMr`X@OB$e#6wA+G)Ug)}W z*Y`_gy4E8Z;ji{<{N`a!+3h1d-q5WY^_enP%gVUh=!Iwm)}dU9F7i z@B~`NNj5oEfS8;T#x$gqcCQ*%N(oNME!E2d{;I!i@mHy?I3XpE5OO%|NP=KWQoK?O zC>>qlALcHdNWNMhSez8nLuGVrtL8M&wZ6|5+nMCZ$=*Z;QspMWF6F8ogs9LG(ZgwL zA{2PnD7r~x=7}H*ZpN@#;3uK?EzTFhzXENSB`M4kAkV{MwLY=5f3Vq4!P)MS@^0w)N7t>Qb& z+_GPkuQrS1cr}|z^}f1&pUm;~lMD7sv%g?-G~n`)07b)(1gY>O7Hx*B=WQ4ni9cI0 zGpnQKy50hywz17xGPZ5(d-IRpnox2p<=XvJ(zR`EQEQJ}TWZ-qW(~+8R`nrn3@1WH z9(veNZXY+d5(^%QG8Pexb$jD_k{;)ypl(MLEa@#bm&RyFnBZO5bWF^a2_oX#9+h2? z;(-N8n{+m=$FOrs7}GZ{yiH5s(eVA0CAno?aTLnK3v1o%D(P9>LT%OQX7{C={cj=u zRBIioXsv820hTuxgCHLfZmw%r#op#OmID8gZ-A`mxbvU^V|QhL=I zYbv+f$XUP6+0(%T{48pq-X}3T1eqFnwk0{ZM{6~O9V13b%-X1vv$o!4e<8EVa?Peb zKC;2c+Fi#W9TI3(M8pr(zGosTx(w^?a)UJ4Q{+Y`2!QRHnsylRcsqd`mIV|=)1x9zIVchhBZ8(t5tjRx5{bL>ps(tD1N&>HyUMVr@Va9 zPWG~U6}GXAqlx=CR7UM25mqT_O>f$>`btAxi1oM7RDh~nIz;E%>5zFy@^Kn&5T-L) zGQ6KaRPv;&w4#!8h|zes%n>RM7fD%}sMfsFk*-A*57P?y@EOTChYJ>UTGf*U>h?SL zYFGMXz@gapl$#^OBl|X(91TaH+^Bh^a~9Z>?Ik#265k(PdAP0mF{)RmQ@j%LYzq04 zTmdpNNqv8w@F^EJ_|e}f$$WoXz}bSgJNnf*Wa7x4P%*9C#We8cfm#x4J+Bcx9@Woo zm{c+nK;ewp8!Js^Y{VT(inQ~VlSVS~#cpm0+>YAr?)=t@?wbap^`QB{J zehAhC!W&2)L_#Bv4-4RfkxJlK#%GYR5paqrj5Ib}WzK;Gb{6=6liIFq(NmI#LrMH* zQLXyaZCVL$!1}?A~6zvgUVPmwXFChqrz*c4YNg56e#6$ZJQ_=&sYgVrSzlIkX&9 zi?9LwLCQN6Qb_@Y#okuJxlH0**2cL^jXSU7+@{fGZ45IwM05D_0v@_D!f{dZz%sQg zM{7%euWJNHpE!2FCyrS<@~%?Ae9Sf))&hWy{2NML0I%{PG@ER~LVe)hQ1Vl}$_IC= zP54ni+{>cQ-nL7pXWUCH4ZXMKEq5S`>!$%~Y&Oxss;38O@I`#gr=F^mAT)V&_YX3a zDT{RyruC!U&cnT|ZTFGjNHribr}MYGgWu3F_wdBMz1pih6woRW_FUWDBl-f#dQKw^va^{Q_VG6%6NHbTHImPPd`(h7BZ3@MgI&@y+`R)1lum;9WM=}bQ|-;M7XYMSN_B%)~Pv?1S| zb4_Hgk@!7P_)RUaHRcXePPI!dg@$pD6kB~i;LP^0L6q_Bkm(DgEZV=u?+?^Qhx0=F zYBQySV+_phAX=0#9bIEMb>Yp-Hh=;4l7Ezkscb52vtPh-i3GAQ)xjAz!C5;TMZ+zP zPZ(ZTa(F{I{*Z_5;vg@dFOK?Z3CY3BNC0fI@c7VdKGzTx->g`3Ckvx=ZqDRX+!>&9U9?2s#rL z`6a{V5xy|uEz2Vvf-UPoopLRz)?yp;BC3ai@3gcA$s=t@KVg9+oXwwJrN9!>w3SSC z&cvcbMBO#8vqu|mxg5pPVe%4+oEzq(b=vt#c)qkvE>cE1LTvKo%05oxPTA#krNdy1 z%0S2c>%6tiIeu$~2+U)2cB#8b{M^5hhBl&DWpYZDSHNa&u#;O#jb=jJha znhnw_!q~3NJ1Q*caNkrm)H6csa6H;?C(cF(1^rQ96iAU5$M?z)?ILul?>TqlU3@*z z4PVQ>5lW!INji~Aks=2Y2qWY9;U5le4*w9|;#jD~2&bIBJD8xkgX!>Ugrh~@;WND- z{$c+TM~Y%u+=h1{T+=7N?DZ2>iiZ~oEg?Bj&OZn#Y`%sokY?L^`eM|dSl9=o*e=Cc~x7; zrpM-ygkM_E7PZ6Nh@2$_SQ!2kCL}%27boK}hAPh*#>ypgZZaoMK&O~Xa;aDPG-d^H zJm{LykKChsbVf@*;uhY>m*9@GS5*6Ib*!cGj}f-I;-C0D3l1|n{wcgyNvTP~>3(_V z6(Hlmn7-s#l~Xjkun053ex(T(!lU7(W z)`~NeBfh7VmXZql;m|EpHZ?A7zml~w1d~wrW0gs0oLt( zSklrUBgtiq`JErc_rtrh9CiT&Fy6bZig!$8U= zvxIyH`wQ}4hCAN=oE`#HW4``zQu{6+jsi3TdfwSTVf)9~xl=-RabXjjUeaqI0rXNc z-i8X>X29C&_^^G+C4pEvX=_E67L7sKGGfqng%Fu-dp zK$mSRBTkzlTG|pZAGKc^y^YGXBF$o($gsC(Y#QoA+?uUMhVXd@Qy+&*McJaQ?SOY4ww@fPTBDxehV=QPW4x52FAkXaqx16!lq zp#<=<-v>uA&N{No0oAhC%#)iN*IwOEXJZ$etZRdkira0J4WcCG$Zs#^^PSY znc@mPZ>#QOoT!Es*S3;{R;b|c+Ik_KVqaBsI;NuIKch?Jb3!k8s}BA|9w)fX{<5K2 z&bUIE4Nd*5o3h7HaZT22VvLjaoE}j*}z4l*M@;ax= zKjHjq8hXk5x|F}pPn&+XU?4jirCb#@oYCZE6s24ahPj~(Ih_TvNM_`dqq787E9|8G znsN@Z2m_2r(iS?mB@E>ti4vXs20f#XF4}y%)#Olxa#@k!Ef00N=cUCd`;`>&)cT^2 zNRsm5+G*nZnk~Y+RYUOD3xxJv^sbxz7~cqC8lwkPQ&;^Yd8MYH0(?gR$dLwvyaWRx zsmg7{SlmA04|d0hlz{scks}3WBj^R6m&q04N%RKm4r3i1fDdZ#8o?9uiZumtrrZLh zwu9%e>KFUp@tE$h8*ELBNg_{&uJg`W!#nH)i23inI;Mav?b1mQ%OCwk_C~uEbg4Rg zqz}TDtU*&b1L9_?97o)$>Z7cN9`9vyFeTAlUR{&xOzUTrTp?<4h>eRw@Z!L{eIOf< zqpO5*Bhf3AH*DBIUw9E4#b10yi+L=wo6sZ|hcO(%# zgrEQuv)-4+hfwcRm+C`lcl;nXD3xoJDu7Z6kcm#kC#cqz_758!UB`~2>+f}KU&$Ow z=27BGTieGSml%l*PheX0gL!5B;NyNOkq8!_Oh1J)e7VOL*?anA9{c58TG83)h|ElA zvl+Nmyp*FuA(L}0w^#Q$Q|4q+HMcXBDwESGf>2GA*!wa$$4TRq1(j|5-q&JGaxG5f_ z(6p<3>oS?*(% zxF*l;EjU|r%g!=;H>-53wiQIEj<5idJn$}nsSfmdX=7FHLX|(d47IVrRpITjE!Sjb z|F*+608>1$=%SAAC#d>d+L7<6=LZ+`cmIa|YJu-U5BOd^;IkXcaL=PhN&3Mz`cdNJ zg@WNd|Kg+kU5BS}Rku$lk%|bb+rhoPQ;8%W;!|wJs6|knZw*))mK3Jg@b0mNl2%gM z^${dIf)%%aP8%KK55VBh1u0)zY_??f$4@7-4lT`_q_VJ7jOpkVXu}%{bY@Eg^HaW@ zKuk`cGQHHbmf_fvyx9PpYX(C411lC2Ol~qrswk;8uXH6m5TI#M7ZvF1WLx%e9bzcd zr?wY%lNu_JFt~~rkMKqkzjFO(X{ezDf!c);IE;c&RKV(bO+;*@U71}+|6W0B1;5!4 zymW;rKDZhRqsRZvn3@RqpXLYcvcDRSsN6r^a(ZF6-iLH!t)dqD-;r1MIsnIpkW$6(|4qR zwgV$C;#*>?=g@r5zqr-gpm5EdM95QoJ|Bf2Xe_4zu2)n-C!KV`DIZ$|@B=O9@Jal! zwbvzl9sjifjMFW^a4;!aSkPdwPf_`^K}oLe=-Gf^TJ`UTPexzf;SVUsQ<~zZfutTU z@3-tWI${ z<4vWf;roC#xSj-hRX&f~i~Uw^0I+qNIJYx-my6tAYvNSYM#>`uZamN}{F6I(RoVsE zh{qj7;OfhGKKNsF+<*Bc1Ur?Ah4kEi8T4Ns90YyGsE+gtKy(w;Arx|Q#}|0xdmr%u zT1A)tS#oD@q-?QV4g3Xb$HrNSM)Zqyy;JNV=~U#IrHhKx$>I2WVB!x`YjaXUgR)QT zLld*MC;4EC?Nc#jyTXqtbbvyRg;O{?TL|?@HsJjW;1M@2ZK#L0N*1@~*%gXE@J`H) z{NYi)`-hnbhtgynl%Z@=hP>rYYBU!XYW>zVuE^1JFe8b|lOk;pr3=iW#GqmF|Gv5>+SaOsN*2IFr@F>Kk z`y?C8st0%+relK^daX=z!yE-1c95|=jJt=A(P&51L^?>@3Pz1ba2QmI-sQxp68s#G zjD|&$3mI@#QTySA!kx;9qX>4IJPK=Q6%ehWV=?m z(P5kGVbzJ;rv?%}yaGN+GzR;lL+-+vEBB6@a__Vu_fD+D%rbF>{gVL9m2GgbT0x{S zpOk;?#%7ogjv(}1D_UxVq*+}^8f&qrAudhV6erXSq_~WKXr$c6yO-fTg+;#On4yns zan{-^WX0|A3nv|H<)X<}&bwCq&EV$O1Vi40rAebse5T)3 zAmm5=-ZHL2Vm%w)kHXjdvwscQFnr3-2iL=AqwobRfd?1Ek1&^_{r8R_d^tElazx+4 z=We>pA05zV2wlzCJzQ5vm&pz;D+peZGSnYwLp{YTG{HZVp|!uA;~f$KyBr6P$kWqU z@=!qVSMe(v_gnm6$UjrOQUMmU~{myY!$>7m9P4Fn@Ht0^SQFTl! zYWP;p^)Cl+4!#b*moJ|kykRXt;?oZVf~x^+fv>}FgXnemB)l4YfIbo8RP(1npNhmk zgs1#-@PtHug^7RX)nqa8ul#N?@kcawHwyn2{|H?B`-o2c`VpA+S6Ct{)9Bx*(Z7X1 z%0{b-TCJeFQqdR$<5d10{J36saEsIJ0=Oe^7e?T2NZPx{$`c+Ey*y*%Y@s$0CGi!% z&tf-X;K)V^5JrvddR07|IQ4Eq$7E1It8Wd$^6tv7$umM`@pW~XW+I) z9$Gh|z-hYdndf!%8I=q|={WWMar};+0%FC&^?;6h_cjG35zI+9f50sJ9rud2F%{A{ zIdj@Q7_*0m4YuY3$|L<=?QJURTfMXiSbBsK;l{t2ZPR8#VI1$`s?G#rQ;{_QRWWuj zvOiRxZx#yH`uVUD=_tpJs4rk5g`Q8wGg|;JYMyq5(rDT$=B`g$&f8Rd!?w4e7IwmW z*)5*&u39#CD*lbmnGMCyH3aJ6*TWIy!O~_smwdi1)g~e;`;FW8Heh)!8!zcj_Rg8$ z!#u_0xjP|BxM&A-CcHPXwi+WOYg!jMGF4@Q8&S+C8I)Vb=gHeVVzf5KQiPnbWZ@=C zAO-4CTNwxgqZ@=1E%&rlncRK^81Pby5sRIk$=zgcq`#-(ccA1(8ar_GVBYY}l?J5a zw&kOpVysdrKfMNV%P?+pWJ$MuUa+x633oCiY(vhJVyR_LqB2fgPl=CwR!Av7hQ{@T z6iq%kdPcokYRbu7u7gY-d%}(4MUJtQyBG1^hn7GMuc^ZsTb}3*{p19C&;uV=kF+{= zdf{v?7Muy;(So!WqCLOnXS29rSxM08aC3KLg0C{%%v6~KEYubPrli_!Tsf&hPNAOy z))2a~QabX{4+azoqrthR`yzn6KktM|A>-k!w=U^5mw7zi4pgO>(4@5sZ}TWAjI}yS zgTO7Gj30wwh253aDu|)+J%r=CDY0u&jAG7W!^5}+k9R&x+ZLCQpQor)qEp3#A z)|}Oj6Vg#7Xr-j{p7|fh7YKs7OxVR_bshhaI&^8q@~=6rerg4)2{O;N;!MR?$ugH- z>+(Izp8eEz)|TBJ)5(~5_H|m6l>|^LL9v6Wlo6*Q9up8J{JU%lNYU_B1)(5(2`d88 zwQ%u>d@w|Yf2&}6315Jx2r70ZG_qe6Li~an-o2X_d6mC=$Kgt9DgKqBtSP=R8Vhu( zLIG{BiT(;fnolB^=GL#sVlx%Bv}jR(f0kB2N5K)JsX6B$)4u<*A`O+*DDthDt!b#) z`ohTPtiq@HhXbfpD0L%3CTfMuggU4wvf)K)s5W@V5-!g?qNMiHIbBI0*x9#P724y1 zqT10x1^#L~ojE=za!(Sn2MI;BLxpZQh5o9NoW(t3$Zqy&?)& zbbwX83Y~LnqMJ$`jsn!F?K_HqTJ=2^(W{F6nGtY}Tpm#>)YY>Q5U^%aih!C8`(KpX zBkAW-PJAV<&pyt5kMBhNZocB*Cx`@HN!z{$@ms`ns=h~#A&!0HCxsZ->Z47HOvdn? z`Y4f57FI91{ADeRuEH%5-l{BwwsqtwnF$t-uU zyQG?z(cz)mLjJyl{CFLp9eJ{SZIFFW9&FLNb# z^qtY@j=f3W>t&2P2l%0LTCC=cQ$gz&rH^sE&;;PA9Sq6GVd`5(T1hbo`@-oCQ2es2SsXux3k z;DO;z6KyI9Ch`gE;#VO5)l~=fKWert7Bx=~ei*xJ**+2>OPxeB8{I@fc%Mcrf8NUZ6W)2MRNK<-_gt`6O?W*#hg}fX-poyGOi$Q2NF<;M&}g#oU9mF}M~HnJ@>J zB6=s*HR5R@D+6(A;AwMOPp%JEEe%k$f>SllSCEjJ7#9X!@Zxu zKjIl<2JhnvcQbocAk64e!m}!)?!kte0Z+uns{x5B{QsQ_j}Gf0ZM$%fuR^DZE7c9g zq+|Sn&qN1DtMUwo3}QAHb9L6cyxILCx%77F9iN()>}|e3O!udG9UN&U_By!Cy(A=4 zfHwf=LvUFaMbB7A$qZ5&%SJ%-FwGW1W_*l3Zi?vZiki}|t!3T1%83L(G&^~T0|its=lu+^=ZQg_t4SvyXBPCrG2Y?#ql&FE^SZabID zdL=2Dx%+%Y=O*d>`J#0Jy6uLPsoiGa2<9}F$YW?NSwn*;Ey8!&EG*WSc&?wA+PFjV zTX}!GzC}`OxyHRcih=ifjs@d@#FG|LgZ3DVr7%vawxuFT7ge=ezS@#pf@pUxWLLV^ z6fN8>*sCwRke#&Mc5X3hU9ljK%+BW|bR^eoct@Jl9UJXue2*=C0N=*OX;D6~x|x$i zQg@O>XM6tPk@k8wM=TGORY#S{r$@q$DxF zswB7htH4!10jZ7f8+oF-d*eg|$^d>LT(fucQpLEYXs@r;>EDjvxj|vC9qZ9L8(f{M zm}W3jaE^m2V6#qBk1-8uvz!u+NNW8WQmb{naMdp!;@ zIH2vwJL*|_Z19?v2b_Y(vcf#xQ#S8cwNfiD?-Fo|6KvY!UaA@sx_lgZQ!+DEHpeZG zKH7AzT~B|GmC3+cZ-8dlx&psFKP;&~PqK8rm@%cb7jm^N5E-keJj;XQ6ipJvl5>Y2|oab;}rRAHn zOfTgv&}n&+r8gwL%M%oH4b4a$HpWaw_fQ^%AD-G;YF9?v%4}l2PG1c|J5rnVdxkTu zs444c{ZQjG#J0A2Pz}jMm!N=?eUyTW>dc8+U@u~`x}F)_z*ktrmH3SditTt2EAE>< z7^@tzx6zFB`mSnGpRy^7JR z0k(s?%g`HL#+#(Kkj0gnNqR)=!D^Gt4hRWI^6)kTx^>~+RWfPadW)+VJ1$DxdOzd2 zs9%<6&2bbH9rPSLCjX@S&Q~`&UB?2U?R^GomQ7q_|F<2VTUSpOIwhY($7CuYu>Cnl~kDd7k{K6HV< z4CwzVk-?M~Vryv0vn_EWJUA0HVhtFz-gbwBAh#jpwd||ahWm{l4A79h37f9nb*CS) z0Z@H^w#7)FtVtUHc@#7usm2%9w5KN7lej>x7taRzykC^n6GjhLwUMR*wk5gAujs^D zlf2Q_OI!f4u%&^Dt6i#Zihh%BSt$dEVpOJLi_#9AXw|Lg6_pX4)MYVml~E38Wju;o z>Vdxzy_w8e`bTrGzcUxK$=0qG7#_^p2;E(C0vY$@)!B(RvUW>!r+Im2hoZgv7;OEN zE4CRRTkh9xE`8&AYh!F*JO*bUk6l++j_ra8XquTWKi(nEH9ZnhRqn@QU$F7oYMD-8 zeoi@?5ig-|`Q=b5kTpU+>WnUMnr>2XEqyhkKOP0m^^^@&-`OycHi1}oaEE%3{RiPY zg1)}7y2f>NZv$8QZzI#X9ywrIk+Rn_@%T7_O%fW(V456+A6Wpatz1XFY5?!BGm za3FNbS(}ukIUU9IdZu>uB6Zf1Zj#?>AhE_BSNGI2nf=ZA_`Iz zlqR6G@AqbR@AfX2fZzZBeSvqoJM-qv%$qlFX5KXH1zR+B^rV*=<%6%3d9ZcMn69R3 z!@e4un{_d&)UCHZ%eZ}?*LB!4ae2FyG2MR&xf$=(uuj8yXFq#;^s3EG4y7$` zc}ktKc}--gj(@fJ{^J%mekfDv+}L*vqbH`<`@PPGW80sJ+@037Z@HYW{5SVCENv8= z@l-XK_o?vq7?@Ch{H(&m;1?Hme>dm-&!W6~nYQPz>zDQ3;d37p>>GJ~e(>;qk7u^M z7#;boE~dgCb8f}lxtp>~*X{4gO@1FR*HC9?H=}X4_s6$y9lbtm&(by1`kde5-7sad z&%-NMMz7sB;pDCUAgUd=M#F> zHIL|&ZvFkIat*DIf6Hw#bI&iib?+oTi#fbN|JU^1>+hTl`RVry#$5-hz3RAAePWa8 z#`wuK`}JP%LH+eLvsCKE*pfBh7;@pl*bDat^k3Tl-O<(hkL+4~g~=2$bK};*4`(z| zHv0R=pA$d4pH=VBPuEHXb||vx}P7m9oyxj^z3`nW_-NR8j&+QaMhoM>(^j1r*jw6+FuL(T6VkH_TIq@ z{rBW-Hf&dH>kxf(?fSp_uI^U$g}-0_;TJb7?%sXOl;Hl;vhpsBvJT%GGk5IdFYbJ@ zWOdK{%KNIN@TK4BrhK@!YtWwW&iC`3XYP@-Nd5H8@r>i2=Nw(p@=V*DJx{04H`KVB zz4`ID#BF^IKOQ^R)~8!&{T4swBoFSle(J`9BQRaOsNjc3cYbaYbnf;(Ki%&>>Ek@l z+;81%ZNj(jFZ7Nq_+dgo&W;bag>Fk*^KjjeewRk4UwPH-pF1ZTZohwM+}}IbpWe1% z`zL#{`>D!wef+pl+v`8hRQ#aYoSW5sTj8J%{c1J5@#;|DD~huB$JM^`>WeO46bxH+ z?yI_^KB%y8NwwZP^3q3TH-4U2?_a&8Uwrn)SK%u{Dm+|!&!@+O#E{0hE$eRO#w_i- zsj&IzzD+eFO~#d&o_qgBxIsN2n zpZHUc*Pd>t-ZORjnUTFbx}5S?xBREs#bZ#}hT%C=_RPHT!SjpeH6u^P-n$te^V`K* zb4ES+W zutC=%{$k5L165lL5!=h8eR2NkkRSaQj(oD@tvLPl$<-dt-S*MdIcKX5%A01m@ZIpE zhON(1FW%o-X?tm};4iMf*cWrN`pqqiroqd{rog_#>XaR)dph;Ix67_7?{Pl+{%Owz{>B?? z|9CX;@8SL%?%y07GOoq$_cm_mnfI%?(YmaK>ECxSdLKIeJh2rwzsr@fYc)Z!e;?}F zr1LMv3*i->-#)#w{fK{3+CSHQIpXsM&qr0s>hh}Ui>FZs)-`Ic%B}rXctx+Er6(SA z{CddLrhjEW`{c|wpZ-;@v2IrSM+0A-wrnjEdhXy5?*8A}=rxgX!+JN2Z}acs=I!<- zxA^MJ_8$ji+->{rHy8C;D=XI7q2KrT&s7^6eKLP(kaG3Yh}!j+uc_ST!)x!>Q6z5O z^2Gn?jJt}XO(Z^6G#-!^o2#;EA;BYs*x=y0!(PVKz)=W6Sy4V%~G zeE9vcvyU>D?B5vnWc;1^#|m$CeKJbX#?*KDM^V2U6#MEHj>+}PnSJ*1sUMHM%{6cS za^=Q$g{!jWFS)Y+Oows{zaPG}@j;KT8{DrnKK=9iWpan?$}ae)+VQY%rg(LG<@sm5_be;eZMz*ddrH=$ zDt?3aM153GvB37={5yUR7cQROLh;>^9^Zro-dNW6LYeF}Tjp#{*s;1{&!x*!`e~Xx zJ^Zfn3ZGeHzvm;<*8YE%$&Qt`apwEPE`5AN*J%l(JFZq}`P^Tgdg8&7<{XXZbtV?Tbl^v@FmD}Fgd6Ljr~k{@Fp z7qaz2%8pxir`%90_ue^dDQuDT%W2O&wv4N_7X`1{yLbDA5U+mssy`eydPe>8pENVv zZS?N4eVZejl&d{t_n99KFRJ+4oo*j3_FY;klW$&X%WwH>%8$M9V})A%;}-R?H6KxF z*Qls>n(5QLKmIUr)i-16%m{AR;N|GQfA}RauR_yw>yDyx$#W$(ZGr>^2^7_@l?PII$Ur>5# zjp}=k^|^R`-L(^+?m2$sj)&KX)u&!ONZiw@%g{mQ{3+MU_1HP)__A4Fzj}V;<>pIk zuFkvvH0#x)r^hx(s8JNZTX+vnPuuGP9=Joi&B^3mvtu)3j#oquMPT z8WU7*_0zeXdhA=WBj?JwzutLt*{}bRD;thp`KxeN{W)KGWo{IUl2tQIi#?2^y= ztnXH*YXAPr?=GsO?A&H^Zc_TSF#VW}xu?sn%uX|WGJeB?F3+{YE6q82bY_Ep&zuRm z{FUX^(KSsDuCBLOUu#(X3AH_D?}?pzW=!O#qpP*yLPrf9cE3fhk>ak>diy?{;}_Xch6~>;H0|ehHAU7jR?JJtrnzxr~1#8<_0Xecq%UWmRE~u{%z;{ z{_@I~f3~aA;M(p`^Q1LnUagF7@#*mV+^5OM^Y1^NROVr=4{NusVXWk5ID9$kZpBNZ z;-@w`_n0>5tvEW;AF%<-kwVBV)9Yzh62NUVBKhuh)d+ z`n=Wa@kx(^TaJc&7??2Lw`TskkKg+HVeWv`KR&$LRdHkfpHEJ`ckF}UY1Sv(;_APD zv(ACb?Z*e7s(*Um^6`%iZw1xg6tSw!qSCF$^+;=NxjQ~{%Lcvgkux9op6L^%Tkh5K zkJhtBXlMS^WYeMd?#8bFH08aXiJd|&*Bdqam1^R|_L~Rz7nV&g*!ahsn}hatT(hE1 zzw*PTEc@c{y>FLqt6J^*zIyZiR-GDWE^o1^N5#|$>wjys{^_^%m*vM)_FSr4`%dp$ zKVFR3xM^;D>uzH+tX{*$7z&m@D1S{^Ds1zK2t|u6z3c8cQ{KD)ybny^?R{jKBNbPQVZ`8gXKYqV|?2=RKn$E7S z^Q$!Wtu5bbo^|_G|5W*p_Il3OH$M-0yf5bd%Z4>3d{OD_%}?6DT7M~M!jOlhD&5H1 zxM0P5F9+Uyaq;?|wLR+G>6Nhe=CfV{=1tz;x577G!{^=H`t`Tb&+;NI-K(6fI_lr= zKdM{DtHti{27gpIIB!_#56`d7xpt)H7ablnYMA();n1}E2~~IcZhbjsNVP6^ernWZ zQRPZMEa78(a7jh?1!woHy!5bn;O&9|HJ9$V_vgN!s}}xy;N^qgt3E0J!rI`=($D@F z*G({f^GiDd24E$5Utf{bi|oz|U*TKYgZuJ-4aaoM{=b zsZoopCSP@#cUNbtUn4d5%#FKM?}ts>TJPwDdbMti9)0WJlkC}5I^H?nc+{btl^%cI zy~fTV3WfgBqtZXe^nEw$>GoeH8ZL*fE!}NS!ONZ#4pdC7xVe3)#P1F?9Mh#*C4G6t zL;vS@f3I-YFXMETN(X9m|8hy$$?HOf_Go(VO2WIdJ8!68IzYFgnRe-{kLI>fEsD-M z(WP~TPL*eky}oeOGS!BaS32|`IP2XDYd#$QsLY({e`aL<+PU_cq%IF8ojUbJ%*qK> zj%=9h)uCgO0`zKeq~78qSQ{VEatj+&F(Q zpPhQWZ@UX$SE{P(d~0IO<FAC`W9LL<*or}oSoS+MRa zuk1$tsUvGAe4c+}=}?9F!GK{&BkQj0(RyFg7i)J!RzLCg+XpMOt`Yxbm+{S3Z5&bi z-vI9_^#{-JTHC+nk&3nN{g*MiuZ?N1JCn(mwCduzg==*9~-FNuD)Qn|FH`}WuQc*gL|s$WbvTGnIj+8XRoe3~rtDRp-Odm6B!rTD~i6K*7 zgy&ke|DoHzb3#_HI```?`?cZP0WY=R`OY0*?cdSXMOUT|tNJ9b^^IG38$xc3nRh;W z`d;+B&YEodPqj~OIDD}6UU2CSv-@>_+xCa&li+7z6-NZF znEUJ5XCD@P)@9{80}ijq*`3?8e2!N}A%8J{{mnW1?ry1Fb;*O>r#dHD*I&IdDxvV# zd4Nt@`_q zE61&VzD~XM+WEFC1}*SdT`C}Xb;p78THL7Gr14J!J{a(>*M`ZvPkZ~%KiuiFmTN}! zGX-Xxe5JlNR6qT05Kw?M2q6lXXoywew$F_Ey`>t(hw`f9tTN^s}RXRG88GLdE-K4}E{BU($~W zTYH~tI%oO4iYw1vtoib$@j>UxcMEd@V!rL>zr4NruTI&QhI~Kf*O<*4PHcJ0BRKH= zP4~9^@@&hDUp9BVY|O1%{gKa}Yz{pR@n3X^_& z{J4GhVcqWiUGv$)le+!Q`hMN=*pN-*+7)&kpR)Pmw!f?mJ^E{0lA-3pRv*2ZJ!z`x z{6}S{bG2uT4H&idTjxDM7(Z7#8ttuJ5-S!$am&sl3GJ{q@9@F{MWnnpB^gp>+)G)`{S;dKeyH!Snv0?>oa$>8Zz+d zPUWR%XA%zA+5K$nt=l8M_M9-R?2gpxL(5)@`la6DxW&En_x4@=q1up#sSWd&_8Pge zZKIz36+;$3UK?|I;$q9$YYXOAHs-8fBqK!FxxkN$FbyNKLqn9ng!S< z_t@~;n45Do>$p?>tWmnmYD3rmu>ofj-QLpuV)Huv`c2Hux9z@quj9?3JNM@$9jtz1 z@bC|6C=dGmT<&Jrv_;dFd-osF>8Njoo!9**EvYrL%$oEFRfi9&jjVIWhwH>QC>Q(o z%pLctcYNHoW^$ET{8*1KwoNP@aHMc=!&^Cvy;q;N{Sj|nn4X<{zST0tmM=e_v?fN8 z`>#j8%CQR;d|bcBwYa(izO4E3XV1ZYjponFdigl8*`^KGCs*q5*Q|y{k7lDQFMFBz zMR-WknD1(h318o~UUs9VTMrMoJ@MUHev^;>`R!Zd?>99}(;kZH*2?dEdPdEi3FW^z z+G@a#n~9rx&DcMBY2`)@ca87)vQm@Jz8pC%Hoj7sS?_F{ymjrDE312I@(zz!lv*aP zYvaoWUu-yf?%==5erw*oGIiua1MzEZtv?v+nM*9gS_G9~E-4?GoQ%dp)*Qe}3+xu2UP=e|Ts2rNT}Z zb9!zy)jQv}5LRIKMo8`#&EnK3cQevo*`o=T>;Hu+qhg;p(R!oQ_a#pVPTb)n%)5 z?jC=1qDsNg0x#vy$5NC2IBZOxv+7QoLDG@Up6|Qc6V~59J!*%a_-Ph{-t>4vb z?v0tbmllo7fBZqhsE+$jpFem>*JI-CpSyRupL#X6_tup&tQ(?kJg*v1|Hj=>eLe{o zF#ccdq}smTZEv<%bH!(uw#?BzRU3pHxTJkDwbWQkgRzZ#E~bAn<;3>f9;Lb;x-mR> ze6Oipf_+wQ9}$PEP0oz^W$7~EBf13+Ly~~DSd`Uz1&*sck3@t|2^@1b*&bsC+_w? zSgCqqmvN0NkDl3e=7oj#J2oDA?+W*=slaFN=Tlp)J6-q0#46WnXWjg@{1+2D8b_uK z-*EE!^LDLlJ3?o*F2yCMc2}m@%(>bEqgffHGw0-~%vxoX(X7_`r|S%y)}T@F)+{Zb zq0?*mbX!J-*34(AEPT2a2XJY$daYHf@#p&(ZG4_iujdU~t%kQ6d9?~37Aok0rIn(}bG-=H$tIlZP;=!EF#FfJM_jpm{g*l$vD zd^q0OZ&Kd~_$IL5B*L_y{8LOiF}n)nm(LN>i}En4Sq^v zXR)Gk2&JfSs&Guqav^vsBnS+aF~Lqip|I0_0rQ)`V^ z<;!X#Z`N9EW&^5H-^k=dPftEvud-N}bU0#G@Knu!D%1xBpR65Z(^^paGIW_EM2^Hu zPC#c+8*`|*o2YD7V-6%)-2}32v8Xbk5gd`mig=JYrYks*m15-twn3dhV)A%a%SE>^ zb#@Uq!c$Xj!VH?&2t=vQl3~00glB2h*%n(4pMi4MYEUKAqDvS=#s1NaKFmhF9(j?1 zFa#Gj!jtDeT~OslC=0WVG`Ur)2LC*rkkm$-!Ac5WXXSHL`MMnJv=a5C(n9*Y72npA zg9fxhEhRA-5@ebZq^d0{ zJ%}0UJdqP&kRMMzf|^3Hw%en9Qz5elAeramA`_xhV?dtjq)f;iLTSgB*8D9`9?eQB8b?cx4ocQ&a8&vd!kC3R9%VM>pfX2A6dx$D zyDwAhd^(AkLmj#jk5id5wGyAvTytUoNw2u#CquuJ%HZ-;I%|~C4DKguEheME0+k`O z@l4%O&p>SQWm<|?Wl&v0#jt4AZb_hZbrW6;<}OZ#ovx)cCH9O=?v)&yni`oPMdU67 z^;l7jXOi;EStKCvM-L2z&q)Dm(e;oJEj zIlL)>)Y$mQ#I#hQGRVtB#(aPGB`5`zmy^F#PzlE3N}E+Xba4WZZ>H2;*y9rNjmpd= zj1%>A^ex3Aq|$U|rb|G#S>h9@x9g-_{JF~LW|DA2P0$;wtWqymh>i8@>^;F=r~)K+ zqzHww5h_CQScugLFJXQJQGnwcw5%ywvreT?X5Q2rmC_`26A%b} zh{%*EQo~_-U8W(2Izsj&7weU+EnuAjgzl-*EBIoFBMC$q9ad=wl4OMfOAd=itAH-B z7!&n+8DdOQQesM6T+EwcC-;s|icb=|9d8^YJTdt-xNLl-Ku;{(XfOy$+YdQZ8&R?< zj0|#2R?aPsHA`nMg5u;TW*A*V3wkFc0v2I(MEzWm2@t!~_+TlG#c+!np=cUqNO;9C z76p``%GG7E!A2Bo1q^DG9d+H&Myo6&9G;x?H|C$}p^E@9BRxa)fWvv7p;Pc&1lSEY z1DLnMBeV^D<0*xU_|P+S(~Ih%T*Vrp9SE@$n0X(+=q`18-UKTFEV$x+~SR@+s zY*V^MXbj+ez!X3s;3}XZ(ln+*jnJo{m5-BJK?=5-X&V?@qP=q zp?LCDYJ{G_yX5B;=F59^;b}8leLKcM#@dz#{m! z2V~(r3C}n>3Sk2U;D3tL^XdZmo)K=braU~mIv&NYdiqEQdlK6lshf)V8EJB@9P&8b+?d#I z$*Ey#YibtSoDz|tdEXpaq8y`3e{;%jgp3N9uPE+^^X0=d8Z!pj5N}@|b%Q<47z5x% z{CiX-qAP*){ie^*+0Z3`F*Bh%K8B9Qvk=e2fRlg=^n_cNE_{S7$HZIIDjIiKYJ+^APuQ#L;_BjZjwYIE%@o zwB~a`!L8fK@Cz59&H>7f_Y57gM3C*mMR1!B!1E5=jjYh3jbgxo(bRc09E0)Xo6>GS-jKpspzl4_Y}ZY zz$D;My>ABklR)DPAOh~hn`MYg-gaNzSR?ciKuoj6sxn){G%#&gIc>gHZL?~_Q3tJB zu9Ilk?ZOETk-1jVvl;YEVI4smt9R&iQWf;}p`kQsER)sD1q5UnbF=|4m%ykR;4d~Y zK_LOunTFZO62O#MK$d946+eUh1O0;o^tyDj%8bKs1G>dU23X8$dO{VLVLU+>*8=;K zzuIJ?N^g(cuZ#GlH9Mz7hpsw|uUanG2)l9-LJ9>`g)XDOJKbp1`-n`TNB%+74S?h{ z6ui}Z?Oe80#spNh65gs4=(_+&k)g8;9z`=fW+uML{u=y>z6Kx#bt}>!nPSEKaAp|& zVWTsLA)CpLccPJK(i-T=tSDMm8dQeDi_t{SP6=soaa}k+ssnyO^wXYx0t4FzhGcX| zZ`~#%og>8~2S4efgck`#dU9U=!TE?SAgs&(c8R0&s!dK!Oko90Wy4D@3Pp-GM`c16 zM619a=Nzqu##i1Js|Ky7Qk|b46r@lH&8aVsj*Yc-u+r+olFD;lYOY^oa&lsF|9(C4 zqRoN@E`qfo{b8*%Xkc|<)|`smn!O;Zre-CCzYgVd=tTL8=bpV6#kw zxdRP7a5auc=$L8HJAmncd4OerJZ-wgNCRh%@ms;C8ZiV>844uJv4w{n+NK33?SIW0 zd4$FR?jXG6=z;I{fJboSn|g$*CTWuzBd650Iq}XVc<<^;Sm}f(mpaQDlEh= zvO`cCzc%e6!u&dfgopWshlF(tj0kTZ(k&i%totGZPdFs zch?rUxb)PT$^OSBnsu0a;nGZ*W|c-u-PSNmfk92tKog_Wn-rT6&8f%@I+knV%MUV| zI+N)>3-1OaoI5umXQN4l62QC7qBR>-Ia+8Pl|F|P+&P|d8ENv9rYv-3t)_|4DVIFO7VL&jpUNjQn{qC z)bJQCF)1}RF(HK$2PlDDx=~ZW4dKEP`bcg;JaT|KA>^Q1WehD;CX=2L0#*m)`{m{3 z`N3?H<7YD?z37FZ9!uzAyQmRIFz`t*8dzR1I>KZq>MI{>pwPld3A%xTlA3@i6y|E_ zi`7n*-u@lW_zY8jc$N_@tA&fl)Psgk(t?r!!Sy5>T0Rj>Gc$z|kC9V`4hg`(i-$nv z7jUVtTNu%b7Jzvg@J>ww8V%zl6;hgkogdKG3tVrh-Ye# zX^t=$bMjbrt-K)9G}p$lhIXbFhD?ofnHeS`2rW#QZCJwgLo z`g0#}&7>@F$38-u#(ISA9*sCY^au^abKNMkgR?wCS!1HKs!eumjynK%ZlOo$r3D_L z_W)x6`G8G;DS(pz`Pj_M<}dxXQ+W;=_ZA@xz@UOO8ZtOzZid}odTCaf53TySV4tLS zImqLX@UvDTEr8yD>i`-XO~P{?-~eC}XvxF*MTN!2(LmLsZYj>AI$ml4Zj~W=Wy+K; z#nC_fZ&IG;n|Oz-3>Y);Xf^qi$W&!gWOA%BIWig+mz3_z#vhTCn4F46O6bB{7$$R5 z7Qy#v!Z&ZudwY80&umpIbw;H|Yf<+T-uwH5h>s87r88#nT4!WXe?HKMg(v~LlZYME zIw~sM$LD|6GgqUVEe+NL`%{)m@0V%P8U59qQi(+yXneGs4ZQ*-+B90O%RHkIYL0hKteuqMZi^g_kz4wwn}1>enpv=1-_RgS7%#R{m4sE2$5jtgzi ziXw_iA~iqJfZh+~s2eSdy31Id4;bGTK{Vt%qNi{8-HV zSfrV|E+{;q+BsvHY-%0_(muj zR4={=dOj9NQ6#kfh)Prz$i_U1=XWsp&64vU!v)#H6-hZUqi7nDS5^wGT(X+a5^c(l zwWMGKVkK*uw>L9dwe*4ND2AyrS@P>5iK9CfgB$;if0F1*q27dnkQ51>vHSIfWI_d^ zMQqf@6=5Lb6G^LtRHVR>V?jP7j5i}wG%7~r4S5`QCeGO%bfQB%21fKwui ziOpSPoGfoJS<5wPt|R$^)tQsI2=$i=oR*u#rX;)fl#>^ig{GNOjZzqsIahRL>#%id z$wQVZ5kc}P62wguawl4=BZZYwC1DOh2%VfG z&>|-onW`pdv6_>Q%oQ{lt|PdETQZvAMpFUdF~f?Tq*DsWj4Q}0#U=$1UB%=R37Lx{ zD#=lnYjKi?I`Uj3@9kyt!AO}#%idlZA9_~C()ZXzOz7mK!zRwwB69!l#y%7m8yUo> z^`^m8KT4Pqk@qiV_)}s4RCYFAvX6jVdQlj{h!aj&b*i^%w3vs|2e2rykUPscpW$(l zVafk#l;9jX&7_1p_x=HUPg~C zq&0fMt$1&#Z1|RZ8`4GY()`AOUz>g!Ge^Zn#znkA9_+aCd|*hbBvW%SDV2GK z!&ZsWA8*gJo2o$Uqo}*ZroLe!fhkX7i6!igy(I>4%|;QC2#-sC!?cQ+|Nqj;SdN|m zxNI|7c`G%<0>_z;iB`nW=u>o*sV+fZbcT(PRx21WPNXR=HgvBnS8)>SFd1dZ7Rc~L z5S(bh(t~w=7J(Lvy)uW`V4GoWKT?Y+Z*;q8m|tYXCRhoWa=}Q=sVItAgI*&%Metu+ zEdNP+60)o4h&mB=sT^BAYzLgPLx#Wt{dNv{`dH%@U2cyfAV91$i-Xo8I;kl9`!Y)TR~hm#%?TVife z>}J;lz(t^|G#X&x!EQ4~jG?+l$Q((&?HnQD)?h0gQ577Ex*$b%N6gPK@ortGUeegk!9=DVEP55D6-g+a z;-Som>2_wOEZKx3+Kgyts>p2@1dFt`q8R@-W{yRp;z>GR&vT1f|Av@s#UEt@Z8onl zYK7g0;w&EuOq`{o`rv0XIWb5oV2X@3Teu_-J72Jqls4~L&{J?5lHzr=JjJ45Q7iVd zsoBge)dARBX-BIskCh~_@4*Lq)%Xn9{a89O%rq~GMcTy^lvll?g(hW;l83cbvKF&g zifmg2CfGH!*9q%o-4wN)s#xSS=ONY!TC^dP8wr_gvrIW)au}%8z@kKo3Tv8$s*EV( ztmRuA~ai*5At=DfO=3%5+-lA`6*Et8d)9%F(dP&cwbc zCQ@)pOsvwNP(})>0Mms`+d^{+t)ac~BRtVo&%)>|X6hWU1zgO5JZYs8O?wlvd4U(d7z7hfbzb^il;7vP|6|_ZgOD zObWv443<-1J2D*ypvHn{0~VP{IxRUhT+H?B*e)i#vzN^^;c#+Ft*DWBmRi24i?5V0 zCLB_7UKhC(h*c0YvTvOI{~AG-$p|(7#^i-e{Fm~u_sZTl4x!MC%`{6wCTceo5UZn1 zSCDWye<^8moKnc3;A1mEQ)`tDRFPZa++lI*h{fm-MO~&qO>n_1nDB`cD>O=pAoG)> zK^<{8c0p&#f*F)%xRYX(nBhx{6YQX_(^7&a3J^jl)mF2fW~EqoQW`eBmMW5+rsO7# z5S%f^jxt0)Hc_q%Bq3uSF5Qa%cjGFTS$WYa_2v`v&H-G#TR9xC_08MPT0a&hYdKLki{{OE3P}b!eGcAnp$YbAkpru z!Iom3)e$*0rPS7lEgyLZIb&#US^zdZPwJ!izMZfS7IT8dqfjS?PcIS0oR4lNS{iE> z>S9TqzN|bYAyPGdU5}R%FAY43PaN%`ETI0mS&ZC>HOR%Iqt_$Uni6o(S9(2;)$)2I z^_w8E4jWVsZE| zMUvPCGh~sM43$P&*#f>ugQd~oN)gK!4+*%8E!dDw-E+Z(@MufA!-a5=KkVjoV93A8 zpH!C;s!QY;5pi)MtURNcNjB~8v~xr57#0!kEHrG8LmhlN1;C69n^jY}SFnqhlM+y1I8d4E6&rz*NU+&K!Lxm6_C9m>|7?5IgLuKbg?R{*@klI3e?xwRDv|D>}YCw@HupDi(awrtIav zX1ufcxFY=Bz*d!W9w=+IOZ+7yC#T20$m<_%%}xJc__vSZy4_yU?rwIKSMP6oRDS#2 zKig+N>pOno@(l}{y*0FZ;~TNw89nY?@7H-BH+08h_17}LXXEsQG*pvS#`KtwIeJYq{&dkZI8j|qd?$68Kx9Tf?SI={3@RSdt{M&xt z@!Ens-+I-@mYLgP^pZOjmVCPPVE=o@xa1>OS{;2nqj%kU9cIK1{e8y3-)f&~UhngN z%X!o`f6{ltx;0r+zOi2e)(!}qXs^N92WE8DTa_<)jAKPT#T>iyaF<&-mz=^lbBJ`8v#_}) zvnYlvqb#jOF=R9(R=7uU;dfCaSzPi;cZUVsjTp^bl(V>5d}dT)0#O#|@{7;K*_dbe5+gII>Jj1zQA1M(4FeN?N z0Ns6DvcyPbTN0hu65+T?g&fx^DxzyS^uDnzgaK`~!qA_iCjtFcF66i*;9)mNiFi$c zXA|j_7jY#z(i6^HE8xus9_{cd39lLO4vO(gaZ7ZhCrEI^y1coZ*zRRBm#4lF|qiZXVz_;7RqjIJ{24EBBtGJc`5X3_LI3N##)-UI6eSMS8?%2@kJM zZ3(z_W?*QrQ)U z7Yw{Pz?0;vIJ~mJ+bgDz%8iaBp|rW?w;b@UiSd?%=LNh9agO{-^j!1n2Rwh^N%<`f zuQ~A2fJb>HC=Smbcte3F<+nJzRiLp{7B7{HJZ~^X!gJ-{ zM&Ol+cjTiuyh*@o3Ow>BK1+CbwWpKbCj&x7dL`j4FXXuXz?15mL{FY)qPH4&xv#;a z`mqdnp8-#*Z^hAD1-vz{!6SNW00)65$$`5z6DZtTz-{13gojtB^7stjxgx!i@KzRb+$`WpvjH1H5~$!6SO@fL9~Y!M}=dqqMp5uRZWWfG6>x5O|Wj6o#fH-^?{lJyaCyqFt(un zEcKx_;<*$s4lofg3}6A|0S<5+_c5S9-c^7UKrA305D91n2mnxDaUDGYO#v+cnVc}z zc^mK4r`v$%62Mr%1i(;$8ITLu!+{>)eY_6>X0p$RT0Yd=z&y4|0#!CTUJirD}0@Q#WfbM`qKxY8;=cw;O{j~r< z5Z-+N)d7A0FF;wqBEVq4E{@~E0F&^Z5BL~h1$+QV2P6UB10(=C0XBeN>p70w4wwO$ z2DjM&BR~gO$8j9VKFRA;e18rw0I~pU5q34lam(?(5zonhPw_qjuo{pJ&;nL*LVK_Q z&q;t!;5Hqw3NR3$0aOIk1k~YhUNN4Z;#nC`4ew7Ib5}Sv>nroKU4XdRppF^24h2rtYXW7?N8kJzQt%xI;pFeQsy zkc3+~uyuj%DUpZt=W)DE3tXjPGhow34vuSM%So_qt#xpbLZW=o)ljs~S2${moz^LH z#yWRP7D^47!@@7jcngHsCoR`zt6AXIhVewCMG__F430)df>B&D!c6L{c{m=;Nf>cH zIMyy9P9;MS&K0J!>%Aa~vfu)ac;G233Tz5sPiz39;%Db)$rHhL<2vq`AwKEVHa%Op zPUOKvET|VElGPnX2j|E$A9l}{wEPwabm4eLVgm1t8paO$V#z{Yaj=`VtB+I8oC#U9 zne50mLG)4J+I%(E4_h#Yo6ipDl_epTjsoMwbv{6)jT2PF8K_EFrEeEb2Z~d~MYzT? zDxTOZWGs*>x-3R1i&84ZxQj3+Ma%^fMMcj`n`3|olD_to3iX1mf)l))Vv{A13LQI7 zy%3guecY`T7Z^zz2}khJ^=x@&)Do914GyNTWm`lHyb^bE=&>9ciwLY(NCBM_-wg+n zIb;D8v*f%GxKFNPVt79sD@rB8>Lc6ci0nvJodtJY6)MZ2yq@Va83A&yEEQ@RrtXDP z2b_Ii#Kl$uS_L7m29_)pc@SqgdzR&?$C-t6x~QQ2orJ|oYb%|~AxYAXJo94#C8g$s zNM-HNiKMv1YpjUPm5XQ@d!5GN!J__U?Eq9f4t29{`LcW3U8o-0U712)Romgj8VTV< zI2Rvb9T%;NaVEmndlhwN=x$J5oUrr+M-96;q6u+vp(cm3ummIhnY4B~Lv673)AeU1 z%Z?PnX+Y)zB{tiUQ%YjEGCn>{nG_ZsiSwI;Cf1vRTKdti!PuW2UnB&Aw7+qnq9+hJ zO2eUNQ5^1*OGj!1vPM}_38*s~y%vX$($$FcYQHebWS} z4IC4jN`$4&Rnq!aIyfDt0Sba8(@>)NLYo5i3oR&B^vYNRZveY^df?!;uquJTx?1=~{4hoL5c?$N^iEG}9}%$N%aQM*bM zgi~60br8`2zaxq$jolTG{5>b;b$l<~E;VBDrTD=CsEARyC5OZ(?+b*K$=9siba%^LM(&RS(Fx>)T$Ja#HE%RZy$L?YLksJ;uplB?MDX+-#DKf zEO7&WIO^QK4Yki=C)UoahE#OD9dyts2P3O0PHnlBuE?04hq;AEV5Pd^(Ot;5^v5u^= z+>sOU+9l`zDXEP1o21nZ)uK#h=i7zbg(DKOkxCuQPN^g&zI+0$3&(@WSQnh@uf<9K zjG4YXL-FDJu}kIH2j7{7i29Da&0t}zCmI~9Km%SuuI`K|JkSO1C>9aEwV|cGvt7a(c=b>swCZs0!QHCd` zC8WNlejh;o!YQ?-Zn!vJuGT zB%n_nh2y;#aiS|;mZ)TeIG0$8B9N^3WAs!KcTQiB8dzrB#lZ8T(8qwqc{z!aryrD})yD3#pXBI@Un_S3V zDV=S>`pvYV+~VnE2yufc(qlcj;*haDgY+|X#(~0aUSnfy2RXK#NJyE5*MoDOO^Wbc zj442TViY4AtkPM4WcC-$O}OmZeMHihB{pnAB<>PpGqB`HC}MoVNJ}YrN^BGzar%$d zY%H+5;@Ac?j$Ojdcchrzo(bfV8yXI%^p4KFos^TiQecsIrUvZ4C@>N+Tww_PrOu{N ztc4k7VQ8UCzuCwX=5tSWRR|mL{LXx$Z7D>g} zHv{*N8}r!w15j~+9Y%e`X|_L}jgIZ1X|#+(G!#xU1M{Jm1@T#&&BJtHqbwQWNon>Q z+GNh`Dj&q{d>&I0P6fhkBrFJqH{xBhbbOT$ZkSbPTXFH0i>Xf@LWV->n(ZBAlJ6av znxagN4pjDvNL9u~_Kb{!aVj-gnUa{693II|MweKKAu~=+r;^1W*9xA(7EkA+`*mUD z1XGa@=Q75i=qv>|_ai4jA|wvRrQ=uV)CFAh07HNdwkBnk(U`5ojVv_U_I9|a(=kF4 z)Q3a|+XV${iQR$PB^ox<7$0ZB$hev;OaRfHgtQG6rWfKJw%y@6UN9DR7!?K?I+L&y zk<4!}{ifS=daH2tat_`1f_rojMyzkn<-?{P$lQ!VN=%4~jaEh_M@G`^SW5KDaKmjR z5fld6!ofS}JPZ7*%=VwF_1VgN98%BDprCDg!WC&aNI}^<7014VTn}YfT54huB_ZQ5 z9giP?E1krXGeHx)hSZ|-S*up93WQ1VFgAIk(pc%7@8LL)9p`z5r6eY>`w?)&9P5v{ zHUh=R!|DZ0aw^<-VlQ0UBPuwtExr^R^?_-gle_nKSDN$WxW`?omUfc_Siva*^Ep@o z1Kan;8$CFFXeU4LFF7pdNY>~Sm!8lr|s59dmQtg_DXq(x_uCF0m1SBj{xD`H}q=m!ejX|ew0c)Z+ z2kRM^qP4QAO}0~9JSv5zo;Y?Ij$mh}>hJH5OHry-j*N?9Gq$|2jZVSiavYjAu%qN= zSZGj9Wk&Xt#O^Nbj8x5dAhLdrQLio9(#Q&z)g2pI;{tGVCr-9E;CLNv05jSY7YT8O z7xg=B?uJc@S{gRXC(d>ViQ_azs0}JLs;ch*}p?iQtm+%r9fdzn=lGSz9tPdZ*R$et)JjLwBru~ec9 z6``Y(CA$^$#ck$XQaH22;MOs?B38t1Cl)5%Z7;-{6hWgFmk5($qi7H$xU$5-#XX+G zmGDyIy2a}(7Dk%hsqv11z9B!BGkc1J*hM#EmJZ`Nc`7AB_GC-cvOvx5=%7YUm>-eo zFt*9Q!%cw^I5Q{Q6eK)?g-2`Q(MEWL2#>bHqa8i)XZtXs>lnZSz(&A#fUAI)fCi%? zy2b+r0I~qX0h0mq0m}e80EK{~fG$G?xPte;0OdwUbgc{U19Sky0tn}Q@hRaC!uKe^ zEYW=po;$^N!a0KXlYsMpD}dhscK{Co{{rl%`8XZz>f)*qkE2C?Jpd=}3+pfsnS?b~ z;eo;$%F?{JW(r89fQP@4>=!?fU<1s*-nfz$)-r3BFSUEPb_1`Niq&T5u3 z)9C?f00504de{b>?1}X-L`!HJ>5vO9Ake9y6cchQt7a&@cG3w?dOrX+9^VyZZsh(Z zfA5Q7M&h|h7XA{w53Cv50MH2_r`6l#oBRrap8;E3XEx`Hw@!TPBAq2M*GkGCvX1#6 zYkt2BO@HuFtIej9Cs=h_9_ilsR?Tv`<+e1s*j zcj|K)w7A(=DKsr+rwMb6AhG5KzhE3K)a#8?ca1oB5cex%6%JF}3SN_?HmSwASium7 z3ux&~9ZcNmq_bAh(Qrg1gruRHKuSJHk`@3^8DQO$4#%^W5YU42W-Q{Qp1ZLE%Nko5 zC}h%@J`jngs)P=!J?m_B6egi1ldTi3JaI0T6HxGDxXgAU4AN-jor5x#2;fdmwrY^2 zROZDJE}AuBF$c-Y33X#t*-|)hgFP{CO66t5DWjtKC?!rPHj7?o;*yet50eSY;84_r zi`zG8rJ}I*UXqKf@s7LSkB*Dz8c{l`E3GSiM?#Q2Ntf*b&RT@g;N6iIeIDYJ4QHv` z(VI_Kh-FWfEZp0Q%Pz&-C?R8zx!9zz6uKb{v%lV0YsJ_@b9}gSQbr9!H54{Fq#4E{ z1j#%CKXzHHNJAD93lW(KiiX>~J-G_Ut8hm%;b6@`kyEpZ3r>wUb&+9V#B?cj_93q@ zHQ2D62ptwhWqVY9UBnZkn0n69S#d802JuDxg({|S@g%;YqTuoXWrm?hP|+7N*YNam zstrPVXbAz%O@dOxfx+JPNZlGigz7*fWp#o+Q6V5r^725XcQWkR4<;7u2bd|Q!Gk_8 zHVJ$Y?;UgIkh~tST)qRvOKjJI9oRdyaK~0Q%*5C zBQx`7@yKLrbtoW77$MOtHkKX1v9p&6<~b&;w0;V@9kcvo`XRfSaAK{n+E+`{|IYS7 zM+D3?NA_d10K!ru?+mRLOHQ$jTbMo5AZSWltdrQpBA=L*ah3!!ZP^7=(iSYiF6)$& zz;-{JC57<>D<(1-QedHed3%|pm74B!EfX9p^wx3qxX`raL5H73 zimV)H`T_fg0MyTz^hwRoe88s9u+HJrnxXgbJP8P#S~JuGa20MJO@N(&FUlWlC@g9$$i!Mf>PS;faH3CXp<~-|_cJ$YH|F7lYu03OQWatdn6-4LI#Xl1 z3~E1xqIDY_?Jb%bGTf$DK74|#W4?1(hX0;+B21i8-H4=K{q(CP9kr zy$;&Qg$}7>Ux3S;A?qZwA6Rh$(5s+1EmV3MJ5pGfYwVNEPJ`?G;#SCUw=j5eHTj8O>dtOHll;<&6>QmC{X1;l-6RXLx>0$@uW1P0T=u1K6s zG!QctYd05*F&hPYuW+@3Qk@RV2^MzJBn_JycXgMh%*A|S8-c%wLN{TPmSIzJ&Y7hl zGr8D#fre0}DPV>e=Hb`Hg$RW}m&YE!Vbq2oKv82d8%qzt8EjX;?PCcMskkw^XKZ*R z%%p5%jo9I3>&3(~K|kQlP}LwKThI z7Kjk0(yBHIUxKxYZYEb!@~}08Ca}eKDRS19NdAOoPaX$C7<39o1qFC5Fcz(Z1&dx> zr_U)(0qjSr3M@D(f>a_o>BfAVnTkypSv22B14mN*(nTF&-E*iFdGtIBY}KVYB}z0$ zDRV5DPVV9dYrX_3sG4j+hUmjuON3Ig>)VkgDLA&l*m*C6bos;(JRA3}h`fM>0+(r9 zUc(HUMhwsxNGaeK%`rPRmd%{d-5zFD0c0J&U4y6^`e|A^^5$rp4%jC zB54vcv;~T{nc4)>BxGues43thDk>@>Dq_{D=z~6}sHljkqT(YeDkutSRa8V&R8VBF zzwcW6oO92;H)-qpdH?&pCwFD-z4km$Yp-oKPu&YA&RB8!x}w>`phETx%F@W~VpKzK zva5Pm98S@l^`$~t!8GNNa$=~$gf2?1TWDS0EP)Ql(_y>>p>GH&_wL!nLH0P*FKH?2 zQ@TeS40~3Xi}&}+QL!%qhGvbvziQhsFbE6)eLyd81<(x~06KwoU_bCGU>|TPuou`3 zv;a?M6tV`*vg|+(XAN0Ej%8aV&~mIg>mjSrsKIs~l`IWTT)D)PsvClRlch`i0f-MfW0h&a*Iz9gG8Z@!l&9uMrI)+`Zg`I?{ybkV0F{dWX1v+~rkt^~=+_i7`W$38!aZqxSN&>?vY0xeXZ^HadxsIj?6+FTqZprqkKO zy$&`eR_QjKpuAv+u5dUZ(mg#LoK8`clNdN8sm+ekm(8wye|2zZv_c85XTTRlls-S4 z8g>?qLduXf;g*GH^?HbU**y1ui|i!$aQ_^zU)sG&@ABb=&VP=#h)$I%DkkLu6P|BX0R%!`@7AbdM zdiqv47nRtc5Y~F;5B+N0C97-%H4v3C(nt<7l}Xe{Az3avqs(@N|5X`TEgi)o>SpLl zb`}_f^*L=RBeiK}5++NS1NAw%BLT!Yv-3i8Y~Z=0at%qlp-4d+m2*a8?iU&obt`W4 zX6C5=I$7=5kkX*j;)O)+Mmj!e5m{XOjST48uwyi_i>X}ybVlM83;rX$oYHe#q6+|B zX3E@vHNDKU2UuM)r9174M2A*_qAGKOA(9wihLy>eiFf31SL6z+Eo3=?>Re(~%K3l@ zCeX@gF7;E8rYn1f}!LZjh4cQwd-n3JFQ;l55^ z-RfwkQ#c&=8Jf3h5AZRVOGb&;5lN3sshu$7Fs`d_HGvFi7)T`03YYL1iq~hDDYu!Y zX%xjLuc)WC#@y5dFZ|0@Ec` ze5iY5Sl-r6SQ0-0*7v-{IRvw6%Z_-{-paa$W>`VRp{~44^fpJ9IL$*0hFGx=9~#`O zC*{1xs=k<-PR%zyWSi=CTARkpv$5GyyQ_Njo>*;*&vK8%fcf$eN#{tbLyE}kYxVT4 zJ^%+)H{6b_of8q6+J$+bNvaeR#{=|z2}csjp`K2;sZZLaX-gK!Nk8Y`q}*v&ZbF@I zht7dUe_ESfn*8~PBaeQjI1C>?oACX%PFsC6xb&8#WVb1*hD1Bf%4lWMBPpeME0)Hi z3h6x@is^NX#$=UeLngYoPVfDc>}w9HH}%n+07!4s+ka4RQoDgWO-t=2*L)HGp=4jZ zp2V7xJfF2=cVeg`t9A0em$p3$JPbSpgfeFqmhB%41ViDB%xUJ6^w1};Helf_93v{M zCeiddq|-g~C@9|a2-CMHn0gL%v3-;9g>q06bHvWOsBK5+3^dWnmQ4GkyVTP$nFqm6 zq(grPno=oTw$RKVM45F_vp375Ic!Rr^E7OUFb9c-XYNf8omhAVW>_;*Xvu(sYZ6mC z^vDI^k+i*Zem+8QM&5(KWbwtLaC)8Jl{;ELS$RRs4^)l8`#65s+I^i58`K zo!+LEtR0F@4cw+~1_h^1svU| z(uj_LK80HEEK&55O=9Xy5%xv8<+Vb?yd06->1OLzu-QZqZZ|Hgan~%hm(#ho&!S_2 zr{so?BvJ>}@0%_)oHa_q62;}WbfAYlLgEd(l7Dt6X_N4jF_O6f`XS-;Hl0|-R=Ln1 z&vyy?cb7x$>+f5wqrcxJ)hXR^JHk4QBkmf>gN~NWK6M9Ecu=$(lkGg_zhsHbN@P|n z>rv$@869Hlh6Pa9Y0RY@%;YofxpO5*MM|~KI&)L!#B~LW0=h*cpvXEFmFBsehDdRE zwcVE~Q*`S?oMa;APba?OG&$?dLQL&=?TiIpzihh6`{^8&h^q{|Q7d;nM1&D@(o$N@L5`4lNINpx(=QCd zLy=fxt?7MIJWU;tQjE((M5%`Xq*aqE=pawZs-@!n!P*;Kp_qQW{UK z^Kx*Xu$9~_lj$joAJbW+t$4T|r}^y3uM)|BOW+LEwyj3e*qs@eFIV8rQ-(yh6x^sJ ztRzQAGWE(Xau99=1K*VN>*h|sznAkGS1WmhAw39c?p=Pu-?C`<@C;W}XcC&Ze$C-h_>dDcE zY*0#xjsD)p z41V&7xoU3RmuJgitC_o)mYuR?E^Xw@NyHOUcLuL?C7H0~Yb`PedyW%y<3NisXYKT?eKuQyJp-c~)=CKEoG+lsgE-#_*p&yH7M{-seOou(n=R>) z^gEK8nC|HO$c9Oir!J`*3_1t&#z5(c&9awnWUI=i{h&#dFaf06V^dyO$YqPnSaKRK zC)Jw`H;B2oeVRF?hA-#gk`bGkZVnCi!8Ybjsw6Q>5}S(VBwEf(IMg=>38w0Fc8RP* zZY+;!M7+t5);#ZIO$45{xwBabnF&qea9jw^rmaa0j(KBOZ{^5Vn<45_oZK3KyG0|< zM1Rz%QnScViCR*|87hnKw!V=8qcO)$a%s@$P2Hp}v+t;3I0QF$l8C~_>?iourm`DK zqHL@{XhG&m)s+AXd9Gz&VO^dFAOz_lb9s3xBbmEj#!i4nrNwx)Bm2nW{=!`mA0!B4&w)PNRQdPiUFBI z)N@_s8%p<|m1(kfzC=qpscY~O=@vf=siZV=KV*AdwWTaSGM85_Cs|j>I&s)tN62t? zSPn6qWHLj9&%x0+11?>hh9!&^$wsbD<*{n9xVvcL!0=2seu*SJhoY-hH$1C{`+R21 zV4JglRQ6D%RygN4O!38nd-h^Zsj|;v5Yeh4PN^vVAk1Nogwl^#5X4~i%F&z~oa_G? z#sZC!%hRL2>zo3=4QERtK&$5<$rIDF?TplcbVg^{9K^n)QNrQO_sWrh_`$*ckpZq( zDARyy%+VCb=ae@S0OWNHP38hq=i+j@V}~gr)dNXdx>vHjLi0jQRSI3L#yFNw;rBVvNx_3M;j#&@aRUjJCM?C9Cy*&rusX5eT89qmLPH42s zs4i#A-EEv|wXsdXArgmnhJDS#Lw)jHHbs%7;u`N7zDj`cVGCPTn z+mW&*i8Su1YI6I_%$mHs&^MP(#cyxg6~n|n?g>|)S+CjN!XBpgiBN@qA@w= zX~}6-YgAncWEu&n1hRf|=JMtcXR@BnS1C-*JKW1{P2oQ>3Qedo>~r0n-s_-jhYrSJ zCFiC;;^&q_cI92^Qn|UI^5W_iN4D;&2utSpj;iLg%bv=u>kC|b7n)Rf?hm+HhdDSA zvd(`+xG@Y|vb>>EvZ*Zv-rqjV)~TFFcy{_3z1s#fUEZ+(jnr)crD|H*YSERkgWsVO6iLhq!R?xN09a0yhQqyU`E>D}0O5+mG zxRMvXeqkW)?P(_<^+Q%ZOh9F=qMXS>bk9Y!p&0f@;UwuAqqu}cRQFWeD+W||qnCM# z-kg*^OuRAn;-idS{R~XPCCAdpHIxv|6ALayI9Vh~vehQjTjr)7&$8NPF>mHfPESmF z;W|DzA{(ufc2b(zE*G~XoGBa$pUgAFwYWaH#(J<*mnC$ zv25x5h7Bc&9J_N2N}AoM)H8$ROQ59wmIWqH>zj`{{X;pIBS3+-d*iWST z!(9reDJ?>Jwhz2;@e#|rv@wlO>VghQFTE(6V6CsP-cR` z9L4oY*(Vz-w|gbuX*NbVA0cx_hKCRn#7Hc)hNB_bj8jhSbE*D1PxjN6$frqLl-1VD-Y?g0qyv&D(ip@ul$^rh(v+SY zIZ?!AmfM1oGR(6$)VW63p|o#z8g+9`D{}g(%q0}p6(y!IPNTv_EK~3_y4iwGEp_4gc*GqZJ8{k8EXus23o>q zm+k}A5bjsKouW!Ya68Flzj)$7ERd(Zx&KVmJ-`fL6p%aW^5&c92Y@l)b-*|vGtsNS z-Hu+~dOOoHL>>^BY&MeA`;%j=0_psXB5rc7M@qX)I%YYur6U&6UYC{jAWpP=MPzMc z-Q`Ht?UN^UXf4R?@!Mj5D`A#)?Hk|L0t6_`!=&&B21 zoR=(Sil(>{6m12PL#805c50?+158+RF4ZVO{beJ+rdkBGAOl@aVA9G>tR^y4C#>YE zdceM(?38oALO2n44A7%ei4s&~L?GQ$cQZ?uyK`JdBz3bw9mz6Du1UEAk9s5pXeP+6 zBXvSc(^+Dt-cZzXBNBe1Z1$v1GsVZXIwLmAi8xFv6qWZhOTvBR{7AWOS5hIiCi$zC zL@p7rmG8LsFMODrBg3@0x@k8#S-qw>jJ$p&2 zVaiM~Wz{1KVL92B%?;VrXKkR~4O!+r#_??yw}$4>FX(sjg>76Q@_jFEOGqYzJf5Pr zUP`tfNzvOW`u!>T@f7{B6#Ybs{$z^YdO0Qh6uq6I-=Cr%PthMs(NCo4Pp0Ute{UoE zj10Gl8MbBn^yBEq(T}?_-q2g868iCM%+b5%Q+@r|8F1^v6>46Dj(WDSB&qO86;yJ4L@gML(XRKbE4ONYS56)>o~qZHn!( z8f&Z8xr+6!VuP!=z*TH?6&JdSbybe@^{!%rtGK{bY;+YDs)E-=#SLPO1@XP-;i_%n z97MomxrJa^d!dPLW})+@GiS<|LJRrqh*+I7&Z z>Bb+|zZ->?olJWdGzm8hIY`{)yB(T@>!*DTnuP18-33j;_0zrxO~Uolz9uxn_0zs1 zG!>YWkTLc{Xp(mjbICz0llm0kjB^4-^7nAPblYG)_3D3? z%<+sgNmcMK0yu?7&Uq@Rl7Ei7a4u@;V-g>gaop3{5l?CI+;JC_d`xsKsHJ?|3@30K zt@}wiIqm|}Q2XOzqmKa2mox6Fz*4s3CVdepCx67yNU;)G{l;B|=#~PGyBv9^*dH+y zxMnf7@Fcme zyCt5xpf=|SdP^fXt~tVg_aj>Z>Q3Sq0dCgtvMeokA()b*NU%DtdigglS_y9?Q+~ivAGjpsf zW=^vPXJ%Pf&n$s1{xBisdZw%x)5Z>X9&_JoT0_s~JYr3t{DZJBVTB&To%XWyIoXEO$g$PaXC|j6e@7TdEl!+S_j49W< zxVe;Sv%E~$b4|d^u!RAdLk5@7W?sf5(R^;cx@C~M)<{VjsbuEg*)L)c#7G$y4TX0U zOGi7MyJgFFS65b5BYA2^T^vdKP1RK^mM@>&xE`J>VF9D`;}Nbp0WDxXHT z&roZ0)PgJZSR5-s*OTmC$W|RJ{>Y*lQSsiEp5ZBhtyT^YMg}|dFox556~5;a%(Go2 z;O&Z4o>l;sXUW}hYhx!5aZ#Kv;xyYbPYCH7N6R9crVx>wl4b-zxrgSbi;iAc-d=Zc znVd3J??51Yq_U~fY@#B+Q*J#VWT}IvuVhuWZY(O-GI{6GM@l-t61h{d-WHB4R%~sE zeKbNB(`*?LH$$9@IahUzuuK!A#9sDDTrpR2k5Hb>=r{r^)Q|{EUU%Wf3(wS`e5XGM zKvQNuUk|6*Rw*ysVSQq!VQWfR1q)lGUy~;3n4$Gx|mJ0gd`s&sWACvY_xKH zoJUNT$=g8eayK-IAhP(5SZ$pu^zqFGSulHA_sz9f)6O&+3_~r*?Z*dk=-QOs3y&!8 zjqczvyQ(Bgb8BN`gSaIuA2=Odl zGcTehh&(vDJ?0BVULX~l{`d3Tbh>6K$-+g;C5`Mh)Hd&mwN%z5dCuz)Rq=-Ux=WI% z5<+!-L+j3(cynV6sY?DJ+=SN0c1>lwDzH6~Y3A?P-t6zcZcM45_#Tc&jl z)H;1q!>uG@TGiTES6fNTjn~DtS0@_2n9)$Hxz18uHHq2wrdWMtO&soXj=bY&b|xxc z1LDk+8juhq={!HlGeYtN5@9AXLX4ZM>o}7nvO5~w7<=gzbE;Bpl|(b8{M7BPSRDg% zb){6BBv(xhb#>bj`sk*V6 z=vK+ALy7XJY^bXBH@QTUZ>?vLtI|rcU8ZJ*wCD)9_qD>7b0ifH!Lc>xuwD3Bu@95h&Lq0Cll?xbPvr`aYTeBg(!R2%`Hu_ zM4dM&YBYmSvgJKcn-e2B9wBlxx%xP?wDNc8{z2cfnlwFdsL9R21SFm&clC~CZkSXz z)yEP&k3+BCOWM37xRw)DstOtV(igNgB`THBTHw2xgzPr*SW8PHyLMI6P?8#eQZyI6 z`tHR+&C)W*qe{2t>v}yp6~Nc&C&*^jlkU3~w685WE}VmlWcw6Jt4b*%e{|ZVmU%m= znhs-EOKY<2)cUWMsaj5TP7U*wt<{X)l9|cgICOc9Jt*nk5&sn}8+;3;au( z|EZa|suI_=Pm+(0L2LcR)YU|{ppN!3k`Uq^W8uGs}56IOYZd()+iYN zvLRuhSA|T|n#yfeQ>{E_PeY9{!I(0_+PO|?TE)#L3C1)^`iMlyBqFn`u4?0H0)W$3 zZ(*baVushGUc->+)Wxb-1w3kMyE6uEPa-dJi^Ljmr3jlMnNv&6Ow?&LNgd;qxTmR>Cd@o6<^`zq9dMy=YlRBv zn}Df_TX`9#>RG(`dP09F{x+uc>e$X$ZKA~|*_A1z5%S|ET5wBU%BsyJR>tZjt64iX z)Uh0r%uHHErP!;a36Ms^&grGnwd5}r$>fGggvsrQ?W*-H=3Kj`-nf$mmO;q{=~^=( zF@0rLFlhsolsTm#)92LMBc>RwSnp}5+o5H2hH~=TJB!SBt!qxwYuE0$M5;l0uDKQ^ zFV4o^X*0(4tdhCjX+v{r<__8Dv1%9UG<&G_Lbsx zfhps+nxzbs;ycRqf7d-{K(=G-0@&G%~i!u%l-*btgGH=ljNMtF{F=aA`#!1b2c%;4yF* z{8n%V_`~2#@aMqOz~2F9fgb};2R{qW250@MYTFEO1UwVG0W1eYwcr5wQg9GF3J!s9 z1k0iFN5L83d%>CDpMs}>{|3$i&-yjtfX@SGgCFfB9I%akCiqhDEbs_;Hu!DeIp9x# zbHLvK=YoF&o(nz&&I8Z?4R7v%H-gUrw}9t?hrk8ko56+PPlJoV-vwK9E$b<80Q@32 z2+n_k^nlla!{B;w2KWlF#i8<>zya|4z(Merz#;I@z+vz|z!~72-;#dtDzGqOHh=@* z%fUf#A2T3brE18~_Kvq2J*SyZ~&K5kGJMTqShyrQi^F2pk6A z2+jcC2F?V33Oo&b0-Oc@5qLWI32-*}Iq(edwBJ(>;Dz8>;C0~H;9Bq;a65P|_|@P% z@LRz7;E#aM0e=NN5BxBAJ@`-H4dC#TRogBA7lS*&YrtLL?cf98OTh=hhrr$7>%cwW zcZ070-vz!B`~bKY{B!WT!G8hY3J(3DYTJ9j#b7xSUk?s|tHD8V8#n|$3=V_e2F?I~ z6r2hEDi|&*>rpV=Ox9n(a1~h@Pmw?1g<#>-S_hs9t^>~kcYWEA6VedWFb-bRLh9IGF?4_9NSLy*dI1-Cc-8*>w&=HCOs{oe`cxun$+Vv1`3~-01lZ#z) zVP;K&Pi0ERm4UHFg!$Auud)nvHH+_(nZB+`@fi@AAOFm?mx#lhK%YicBuA?Cct@B_1tAY?pHMYjn&*Ym!jy zZ4gtT7|s^GOD8hK2F9x85yG7!zQTktb*%MWCL`%W?xKt}(|Jm2hH~IQnSQNxv?XDAvQlm7#jYi#kW@YbA_jK zq_=C3Y#EkIE4UML;k;?#g#m4sW%##3x;$|wU7-nA?}>?#m55IzyirrdCSj|YYcZ3@ zm~taxLy{~mrjas9=IX6ub=;<{?(1ALFjg-wl8}&67|Z%#1QL^4VK5qwtdv-mM$X^| z@f}U%Z57;HNdEEVE|HT!{Ul9QDpBI7w1Kf#j&zN5;jXg3Pi{gpzD`+J>AFX{w1TEN zTD^5-Y#01NJhS9x01Q2o_%0Ufj67k-l#*8O43(=XrIFU;BBW|c5%+YcJ%_o_F>K}rGI2<;%_8YvOfQv z>Vfa&>X~OW&{4zP(9{wqqdglVYsQ-0N4(aI?Gh;mHC#YLs%T28&f1aN1yzn9kh*VJ z+IQ~8JXrgc)X>yxyd0mc6D9pD80JTf;5z5H;!&6qD_*W@081;Jsr(l$#V?`21o1r zk?C?oBbL;ont1r!IQ~|0-*LE0TOcEb7mw4Mny%2XBT?4sMj}U$G(74iK%zXkfr+^Z z+D)IImgK(^=O(V`@eGYjOr{KOu7(9w`H9Q zWpE8EDoUAiT)4x05mtg}-8ga3P8=3b_`kPA)>%v-+=-QG>zAq7<*7Z7v_JDVFh=zh z8RF7E$XFj)A#JN(-|cERAU&qe5z_`dTIn|RBWWCzes6O++01ZAf`sDEiL@m;b5Cbt zClR0sTl-Y_1d*aF$zqnk4I^5%iP;e;Aevo=8(EUl!jF*tQXU!8emC)oHAPuwLY-_f zrY$#pGWMT2(8?jRCP|wUbBVDmwsbnDZO2qh>3aso+#b1d`(;|Ih?=Por7JEs_M`~3 zWpoYIboF*Rj*0FW9LtD_3_fT6xCPN_9>uhKa;e-TuchBmya0Pu&(pEg-I1=#$X&-T z$K~Y``PY`U){*n2&OESkJ99^!?77oK$$!MojCxZw2-2Ps-9OjkVPhR@(igI{Vn$X| zZLCqrKc_95ApKq1NN<|4c7^K7tpio8%}s|N6Y2g^3fwa`=}os|=-Q;22)mU`J#1oC zV!G2-L_jeLcXfKHG|mz>5(XwNY&mo_^iATdba>sBDqP&o^<3?1{+q|pM z`p6`owxilU_LM~2jI0?RC(qVpCkPK2FEcZyp3eEVY&HI`QsmU=_Sur?+$p_1C$E!8x&UYeaarFz4h z$;J3Ea~tY;7Z(!VG$jJ6YeF^r#do=a#(=8cGmhJR-+iQ|VrY;ZA~% z<%Z~7i1CQVosk2Qx-jY(8(Ry+5011Ac9MAm0~WGK+*iP4&x?mkkb8pUBxnC3(iTz6 zk;C0R9o><`Z9^h&$qAD@U4nb&1V}nba;;BCrMTq^hT2^EABKs$J`p!)F8&baXg>p7 zJl-+ZW)gxdYPKUvg)-LG-ZNUhd2`&DtfV7Jwd^G9bk+~E*yKsqLC5?4_A5#?6J%c& zQ7yyCftz?u;h#KVg%HXv#6esoi_x^&+&;XPrL{ar!M?y+>H}iy+T~S@)WJZiqO;4h zy`^ebyt1XKF3zE{@N09*3fp;y5x3N)eu5 zc2tl6j*@91lI^tT5uupaV$)!Ggh>=KKSo6>2}gp;2vRet}Z$^Le=OJVYWlrISa;#~z0jY=&PiYxKOY7^0Cb{m0jhuvKnai!Sim!c zl`}Kn9w)4OuseZYpSDpS5xL?lmh%aVf0k)y8h z`1>}zSk*Nu`({>*yI!iO<0rg4{C+1zxotKo)=XQxgLVk5)d zyAaLo*)T3)dWh92cMnW&_>|Dsrs%6`)OWvyi-}{~01e2xvg=5ER1YznL2I%uL8NA{ zZD;1yIY|FShtNSU!3)WDsJM4IiMR#nZ zHL7GSPftWVHG-(*T@*J)iC}mEWn`!upWSe2CNdjBFp!bcm1g3%>sX45c=So>Oq3_1 z)9@!Fw%k=zfM+$Ze2;8W6+`}sl5nJ$? zz=+&q7K6y>T%FaH%iSdd!Cp03bvhC0snMAd53pCvXqI-=S;cZAz=cW5C zMl>l*u5d-eSjuIg=GsbF6}e1Q32%N&nl~b(OA3S&9=cpUBT0o2k|HkC684iV=R!I{Q00J=w=3IvqyT($ znM`vr*odnmM#*lt5zpIwyxz>2cf6fN8>up_Sj4Qh$-}qWnel88-4I<40-fCCBy8&B zMpkj1B;cx%9_CX+JTjKBFi5hEa8TEr>>zAkWIXSEHjKnod`$r%CjyRW+d~QxNCVNnI>|@R2vpvNIKQiY<5+WtPTwJjKUM3CDGQ=Yg(CX z-6s`lvWZ)ALUkfCsSCfE>qa6!G;)xG7iOvMus|PBQezfCUXD-^(78%60R?r1biG&*dqK8>&N zt<1aLl5b~$pTC898gMHx0Biy*;L&$6rvq*P_5+)M9N@{D^X&=XR$w0x0iJj#b3fpE zU@x!=c=jF8fSZARKnd{l+wl{q_^L>wICaYO-kGoKIK(=D`5wzzsl`oG+7}PCYBGsjQ{T+_eh^Zo!Rp)m$8?-raH*9eYZ0 z=*W>EM{2Z3m!>JtgUAewZNkz7QH2)A4@;$M6ES_rbUvTQefxS2A?eQ;>dTcp2tVM) z(tVkX_YH(3!xpPguUuF9h9&9g86ccak6fimnr0*sL*{}8>$D(k-c)|marw+;qrBH0 z6sY$H7^^3-)^477p47~E;dDy$2~G`?{%Wf5ygt?KvQzDvwo108H1sL$ohF^0Ux_H1 zL263RQd5*3OU+xisen~Fu&mYDV3c<99J z+o10Qq&Idd5;G3dcFeJtAU7Wk4i z(%9Jy7|<82YCcL^2MRwz9|R1e4qG;V2LoDya2rH^u0K>G66@doOle=X3FH6n7v?U?U7Q=qU7CAtZb|O4+~v9F<*v?M zle;#zEVn$@nj6Xs=dH_KpBu;z=HLEi>-IOV4+TkHfG41B$%TMrFD7+Bwzc2dhQ4VB z{Qa$aMO>1kP_n?u2Z^wJ+gnXgwWQvIrOvP*xv0LwWq%^F!$D zb29rMiTAEU0;#HaCk6I9S;~ztO+>7=OaunuUG$S>=9*4->>z?;)eqrvV~2q) zbK@f6aVk;cknGsZky9bY%*qN2uOW+6Bj8lgI+dy;l65A7v>FNrR!6&6QfD5_ zO=)WmuH}FHK!=WfJjr;#^94T-Bo<$eEs?h`X@?t>QpN)P?Nyd*2qQz+K@PB4E%2@) zb8^?9t@8?A5gF7ej`L<-k{QfnJxnL?Oy(?F@^Uhi=Dh1F=K;PU&#a@{ysZ{L#MsIj z&yfgQ%RZ&-akyT{3{an4(N|H2I;pKZ8|<1&s^no(=3l;Gm8ujs)jf`{CZ0OCa!5n+ z*uhYnB*E#0k0kp(&^h7}bRV@jC59|x<%utbT4!$*Y2T)3M22`DD<v_^jA> ztvM&YfAo9yY%BZ3{~rC0JtOe#iRt56u?GT=P85z8#eQndKk?YnpV`IMq7%P3`b&Fp z;O7$y#}~vNxAIRseDo3foWM^e3dZNfejNDW#N6?`*pIB-6F)fmkew5FW} z{fWOH{hPhc+IZq0NB?PG77?B9VGCN_^pV=r14 zo%q+$=j}~a>4_(g{=r@m_~XR+<11rN1^zs-W_)ezFV^Z4e>(cKy(;j;M9KKF*l(@# zPW=Ap@9gE)(i6Wv`WyS)z^^8jj7MT81IH%zkGI7>XmytbKEUUT9rNAI<-3EVv~JU$ZpoOSrb7mj}39<>HfeCFt9?V-S@ zC$1VFh}~s1p1A4g+wE5d-Z{}c-V}RB;FgKq<9lN7wpvfT>*&pPOW?MNedCwM-fzWE zeBkKq_N%N*PrUc&`|QgC@0qw{d~fX5zzq{M%gO4HG-Zcf|fHaP7qQ@yghBR_w&lqvN(ce250lu?<6n+(E8e zSBa?WO0K!pSJyQ&sWk+-Di)75HrB-}*>nBRJC>2*o?bl@T-Px|FDa8S=^Nr<~@@Rn13^WXG*&)n<&y8oQ(|8a2B#~*vewog62YvacrsVYDA z!^)D+eQWo*pP6{&$}fL=@9KNM7a#c5JA;RRcXP&T|MLEsN1lA|jNX^uw&=fPB`q288Z+u~S^VjZLa_M)zSbF(`_pLp7Rp=eR z9}U0j&##+x+aJcV-}lm?#czG_io!Skts{5*xz2fSc(gY9iC@-l`Q(pxUU2*e_PP(> z-+JEXzupx2^#5MA;-2sBTl3YM0zw`Q~SrHlFy>`IkKKl~u3$elr5A*$Rtr zDBdBQ%tvIH;7jbK=dP~a_O4ac+h%~@0nP%y5gY`I&3~aD2QqU*({e*uxuNN^0@hHSiu2WlLTfS?ry;iZ~$_qF=JD8grvT}p7 zaszU^O+VKWnxvr59JWSI!uEOLg{=|d0@6$iA+Bs_?MUEXC#tUA!FKC4>#Db{UR%Ab3tR%;2@ZiJ#V@a^-WEmw zXYeNQli&-$zXq=YKMp<@{3CEK_yl+c_{-oR_%q;B<<;Bn1iu9SDEJ@XW8go5Zw5aG zz83rl_!{s<6*-$LtjvlzxfOF}Rm_=FF=uwgoScd|g%z{2DrPULm|avcr>tVu>WbNG z*3Md6F>BTOnQJO$%shWac}4cZionVh*%vOHeqKdZX~lH37gS_jxG-yFMb?IjY0E06 zEw9MRugJ`(m_2h|W?n_cj8H~iMR-O<1~&65LQBO?XnI8`QV}|5OK9#whyhI3R0P&l z%)qOa6@d#E1~yg%f)yd0OkWsSTEV>DU#OC8XE;k9;Nxe}fu7cNvl4*~v0~$W>MIg)EusTP6ashVlC+&C#>zy0B;o z{%;a1UT~fp<7=XI({lY^!k((q!c5B_<6u&<=h#&wLUn_2ONnK{izQEz44l=O)lTL0(z?a@rbGEIuMWm*;Otk~D8Xk@giRjX$v+Ed2l?Wx3V zPqZYO6b@%(WQHm-Xg#!yf{HMWi3Swd5<*?PW%iN^%d{cWfX=O$hBa$pAX;I~udrxF z+4HUNd~0!q7hk_3H77AkCke%+9;Ju&KI^F8FHyVJJbGF^NGq#E%WxcpyfXKEaTIB8 zm2SdxnopuVIc}2LQvk0`j1bM6{NZ<695^lCs3uOv^{{#0%V2c%h1^ey)kD_wv>sa;hc2nL2d+P0cjVS5J}Fo|3jp#9C?t zOG>QcPt7+9Z5gYpzEf!550>%zVc>>G%(%S)^J_4Zu{-OVg?0uL0jsLQZh_{(|rt>8O=3E-X|6x#XNv6*u$ zz>mE@B0Yf2DQ+blY{Yhq^eWr3te7LRz1TCXkI=z+)&(CeyJm1g&g1eV4)H{ct-N^YWC*4_Q=d5&<7(8)Q%LC$BsV(7;> z-*0R*cEz6mdv>V6ewgwT+QXM~KC~Y{USr&KeyG4MIbLAj`bnd|`7VPuUCSQu>(l+a z=8M?>T!C$Nl$1Tu+hmz!MI}|Fzi%zqTh^+JHC&LD9Wu`iCeDTvTLv7%2*-YcCL0}a zgm4c_PRw{F+62pCna`4J7x=U=JosWkcB2R@3hv^ZMs zrpA4q>UoW8CIxW%4CcLGj$xGbiV9)k*a?QwldaQ4ZYQj{TXpbQcusk$)q60iQ|?j2 z|L8Y9t)Zk)PG^%`2s@*bW6DsN?&oCTba8O6Ve5gU7yC10fm$Z@<`~mqbA^wR*D={s zV0VF|O=A{slLJ&&qq%g3{H1idUW|3#Gt^c_I+n4%o*jdWZI1Ew%=x;DL7i_G&1 zz0hk(B-+_W^vqn#!o1qWgK?f~_Vlh zDv~+q)~EaAzQ}2g0DL`-lq*SJqNne4EBc6Wspzho9b>T;Koyvx;r|IeAlos|Exjx|dOl}($)sM!eemP7F zs+L-th#PHDuBftoOwxpN$h_8k`if^>U)GA(*WqP?bh*yE%=&n;Rk)(So(W8p7T8t5 zwOgyVbpktpQXnrcG&?WIe||Z6ET%)5c~+Kcp=9R;XU-1J$P3QOv*yf7{PM&Jzd%6$ zhw=j9yg)`?0Jqcg0?_B?1+2Wl>^v(dURnI6>3)r`H$Q$IA-r8!jlY??it;FutqEJ_&vjcnMfQ z{H*#SI|nEQY@iY72F8FJ0IQ+Mz6<<-=uw{pa)3?1KA;om1+D??#v;1~xEpvD$bV&# zy#aUw2~&m3^h#8+?SxmNBy$t{jjk7nlYGO1J)z#a=z~fcb+wKOe zP*ErY{*CF*-#K6o5TF)?GDGv=<;V|ZThrOKDT1M+C^$1XD>ye;5X`pb1apIVP>OMMZ7mw#3_gT74aUFt17av zr)FZhWgq=55C#h4j5V*Kf4z*pxD#~;eK+{}E9kHHqsP4QV3GZNH)F~n`g!Pg(l0;J zL%$AmLqCpwxV^}}5qyKV$G)kJ>C7G{;|2CTmokoDO~3zY`f(ugnj-rSApf;RX}s52 z-Ddsw>|3yl|6AV5cm_Q5HpZ=+2>t34v^MXCT=7n>QQ%i*9#zPjPrQVTK#a+Z*eFIe?6M6@LsA=d1y z-nIb92A4*1zC3+$T#DI<8>rM9#DnrsfAmPNjc8J*HVhj4&PaGLw!tG z&yY^qip0)li`$R>nZ7R5WJMt?=aj{x;|2EkYYXh#t}C$beqDk64C))eH{ZL&z74ns z^W)%1ASWESAXql%nVF#%f)PO%2-{fOx=!Q<>C0GhEfPK(<*i&J+0{l>rL4Fvcc`ng z$EkRd^|}f>yUcL%KyNijSTq$pP6SGQXlrX3V@J$Ah|1wjP1$A+Ymxb^YJ5yv7_(x# zB?qmxQF-udnAhTYzg?a#rzQ!L)LB-{$zwMvk($I~c^Q2Q`s%Il!FKi!61-8ESj0L< zMU+NoBsS97({BRFI|h{oLM^jiZPpIN}(?u)nX*R9(WQ9ENzkT4j=W zRno~$Q&6T(x%mcDb|0)b$wcZmOJc{DL0^oNe@JcssE?yG4`J+0v)i!*%lp`e zyS>2P^qvB{^A^(|V3hQoT0CaGZoZJVTIFjtS~Wy@NO!nk^5Z*m&2gE5yQz=e8z>H! z_m|~97Zilk$ywMBc{w2$!=3e?M-%t`tX318*IGHGi(-?cW0XcT>aj{&x1K1lum2ip z0>)4u2P_tC$aBqs)se%&=@zHzjHE z>TM4J_W;L$Y#23jLbLQgip<&8992)x3C_$3!fF{1Z7^fDH7zHYl@rX#3Czd|%*uiH zG8BS|Q|t$_7`ugT&0@gLv7lprj;a^@sKDO)NP(UI;{tmab^gNzb{%jVaO@|f4YMqu z6WEV=DflH|A920`^H4YtXsqYVdsp?gJAf9Tct)srR;Z*T^;f(oG=FgtFl_4vuB$!NR1z#G3Fa3D^8%rTn3e=fN`gyDta(Mj86|;PC4rK(-=dNL zex}o>qTqAkQuVWhHzotKEc_(SNxwyD#Bhm~Sz=|CSlP)oacD`Dtfd-H6f=KCz5|

$ryJ_j$&t3L5Gz%A%EH;`2Z+i3GyrTRY3*J&#{O0-AzOOB@kN=fE13czn zQK!N~Ddxj}XTI?_>Mr;;2iK(F97q2!{=P(d9{4kP1HRS4qE3Z7F!P&_VP`)y!5bWW zGiuShxQaB3egX(`Xk(q5yX?H>rQ_q|L+Dgs+9}Bpx`q&^dHb7b=S|hyY~Zd}R&R>{ zH#Jso+YrsTAes@?-&&u-QyU}y|HaXaa`$KGXf2n5dV%YY=W0zTV@<#b#SrtN8RtYZ z*643u)Pk6;u9j@bSa@Oh+-SHs8eXfvCD9BNE27~=8#79x;i&stx(N@%E2H7Xn}|<1 z91ZgyO8&-BFdDWtigs2sJU<#-R@NAcu7Y(1|s)#xyM?-VPPvR4@qM;el z(5z@^el)Z|on+{L4cGW!&5VX-yT0W`L+7ZvC>kn=hRUL$>}bf1Pw?Dmus9lAt3Tp{ zVnsBl@d-ww&Tr`&@+Y`58eF`F{0WAmLH--lU^Hl{c2+bvKN?)1^bFV3*wOL|&UT4; z(cn26L}4@}`4bIhM}x#?(T2bU(ZIRUKyfs%HX2wK4J=Z{3RRRu15y1g7k@;(G8$Ms z&srA^grk8>*R(tuu%ZF}&x!`-M*|C#o)HaXxvp>+m`5cE%vPgmQ7bPRILCDkonLk| zK*TmjtqY_&$?tquu{LV)GsM-=z$#a5D2t=koTycf2gxQ=2gP#v^CLHEG7&r!GWpMrs z49tX%oqecp0`3GJ0GLW~XqRQen+8}w&Mf=`KbeIe(>cEeYJg$j9^gUX86ccp zXqN)}ft!Hmfdw-P?JdAKe%=j!9IyyKi@2778-Ztl1?X+Uxd{m87TT+bM;WxIUnE^T zz#I%tpTU5{44Gs9KrX!xoey1;Ot}i6i+q0XgI?g!MP9%8&O8G%4C(E|vbVu$3#*v+ zgEEz5E+*$G2azbsm6pUjmBsF)WbVFQEqfmv{!D7YS;km7uc8dT!5DZMd3-tf5(oan z*mD1wqgoZg>qtkC=XK&cVB)ScJlt^+k%U~GPNEYs$MU&(AG!WLZ<+O#Pq#FNKK`1b z_TRm?`u+AB&iUiFXFPrI<)^;-&s#40+JaAAacL~rus6&6ob$Qq z8{b#4yyv?gn1B25n$@5A^Nau3)%LwtZ@uc>&vjd?_Ah?mPxtNk>BYZz_{mpXx$?L3 zzVVaRo4=ovdGwj8Fa754|DJf$C-1EZ|MJ90M_KXgLv{HVto_x89=vGJ->%(x=kL#d z*RflF@VW!9{qO7kcg2sk9QpOa(dh2_MUQ3oK5=>9Up{)r@eAL)uJV#E+}QcUlXt%` zZQ1|4^$&%Q+|WN*^4D*@^4x1~Tk`YA|LgTPZNL8$k7fksemMTGhu*&Tyf1Fb`|SEJ z54`bXpI`cpNbRYytKatgc)`!gzj@Es?>e0OotJ*R`J2!G`5&i#{EN5m4}Nd=??1Qe z>9;L@;|qWJ%v)cKeKuZwZu1lG8~Ig5UGHn3yRQ3{Klsz>D(|CTv`*N+Ir903-*Ry9=3DQ2{g=Pd@TdQJ z?}6Mm{UQACV`IxM{?O&)8QYc&{I%oo|7?%^_T{f0EnNQf`!2X)%{yCPy83}Ht^3_X z(d{3uYKhLc@mp7xe(c_PpM0!yIR70pYwr2LS1RwnsQgENd*sc1KMQ>Nw%SMU{QLL+ z_t~8}{m;B&-=;l7@BYpQpWJ#&+pIY!ues{Mn==2o;A>ZWs;A&Ro6q~{AJ1RAvi}=pfrID&`zQZB`oGtH z`!z3Ivh$fwKK!Box$XGi#1~$E=kkr){`ugBkNozpS3O#OPWW5re!cLPjQ38PJO1lG zp7)uN>DR3)p5J%rv8L#cKfB^LYp-wqf%T`zOP{{%itpTa(JSiqe*dAreB#B*UF%<8 z{jcEb8n=Alj#qxze%m|Vzv;PqKmW5OIj8>q!|%?_dpiE^s)GAJ_S%Zh%ZrBgA8mMi z>B^gK*zxCk@_+HF8IPS@w>i5uvt-}bespL1+u!xXk>5XX;i0!YQvdPZ-OoPNb@ivR zzJx@D1s}cpn@|3Hc=5$wdGnhFwtntFP3Rx9+b-Di#s507@b+Ile`{{fPv3g;`xd?7 z58rDo{pF1xeB-RI{%(7B>^-aJ+|}~sdAjV6G&F3Fn1{Z();wq_4@?TJ6P_O7=e-wP z2!4axKpi}h&3Vf&;mHvh2*GFQhJw1PKZg4GOW2>Xo(b)Rq^tW&4UcY$7ys9^dyBYJ zOgxfT;E`sQ#OxhJnh?=3+!b-Ug-DCM9zC2riHTza$wS#zZwC910rokkv9EcGbFWj< zM-|(*q23fMwr>m-+cht-PdcsG9?RtH?z>Cu>#-y7DbjnJrdjTlg#*(9)8PQh3J9N8 zw*F=CpZz=jKmTw1&M3AE|50Su0As+jK;1)2>^s1{&vTylqS-GEUXH)}s<&+f9=fc0 z+Z8|95OSmT(6h}*pKP(gX9usobm9?C2atvoMOR30kV zU$8vH&!|_p3be)Lq50(@g3c=sWtWF$l!q1;g%+uW^Gd}&Mytz1YaAy*LMbl~nqNkF zFw<2V%B=EWu*{lM9?UJzn5+M@*rWG336%%3%Y!p~u2z)?^UH(hNGQQIN?%(ZIG+@h z2h1;{Jdo+Cr)32=IS!Tw_~j^Zh5nx|(R1vd&*(0p1ZKDtzY*#+O1H{`0V$>_f5CDB zn$i@9d8aj1p96Q!TT}@Ufaf6E_4(7 zKGLJz6nKExifW^^$Wh%wxP~^D)EHF>rjp{IC2l27A*+luER<+#z6ehJ&UMUPd#<_d zD8@Z=*M@rST00GP?Ylm?RwKk|SH9?6pHgkOHeKx6PqimLC8sXchUb3Dm- z5{+x$#jX{}r$?k|cs|*#(G=LV@7f!8;#lVS;Ku1c#jZ~@fQ(bt+*5(#K(P2!X#S~i z-l>fIQ<(*)rY$~|6*)ECx`Xy~AHd1e?0_{pXwCk2aJCgHI2FK^WpT@zMNWj9iyVG* z^meo(e~}}bPQ&YV=B0}q${lPQMmiWr0-}(cq{2*<(932tix(q=L$`#(i!&ByE}ph{ z2BAN>2Y!)3&IMn=dU7ZGZE{8l%?4JD(B}a;qo#jzvw0YrsJDP$u{)ygdKxpc=WT_j z(J#o_EgZ~UvLw8UZObKe4>RA(7=KHVeR)Uqww1s?+pD+T4-^%Jf<>X(9RK=$`JBh9 zc2-enmaB#`-LZq;I0=S}LfPzuawJ?7R42i6ih}HoqBXy)qTuwRV4-M5PQYybiw^;Q zbEXAz#Ai|S%Pk7bEehoMDD=)88E1$o*5sEt4SyW9#>!E9#QU>~?b7MR_Fmwj+cclM|4yi_KNf&zO42G{5Q+VO{-q< zZ8Mtjw$!Ru{LWRk9BcfktG@GgS&>4KV2kvB! z{mDe#oA;|fEV}LE+h*PV%{7@XJoa+%xu1>&R{Zr#)_uj7TeC*jSQ{@Wuu9)E!@BUn z3@iM*p!L#Vztv?9Pr&gnfqUevD7L$* zg~zsc#f52od)-;2%WRLdjdl*Nm4EDFkOoH;r^6X;7l8$=tWt?Ef((m1MrZfNTJ=MC z7=VJgMRVuREuOo0?!vhX=AO&nBK}I|TGo=ek-1CfE}whe+za_z0cGCYLTrlN1!uHd z^(1q%hl}icftgR!zJ9|x;tAFe!0?~obrAiJi|m0%;E(t|d>OxhckVC5>DSmLUibe9 zp1R*cdxky{JNBc@?J#Tk9e(_rHj4e4llTw46A1qbo{R4x3BtSa z_wXiyZ~HU;;@4jM2}8T{G3pdt7^KvxwgqDDw_>%YThA=CV8P#VqRBSx!EFtk~%+- zfYcmFBwbu?udOF-UYciRJ4tS6B&22C-94+y@SuF7W}#zNTfG}I!g2G5H|94ZE>mwz zTcucEx5;FADOOfqwtCg&%SKkLFs@0dCSmtZN+;HG{&td5v20|Ps$-QE<*U{u)J9d= z>{_TKq-{zRRfVJE`L&Am#ItNwxiL!+$_#;Wt60|Igi>jA#)P7+a9oMfu}?*CsiJhK zyQ-^Qswf>QIpxFymBhpGxUy0eQpAocRT^U{ZznorgrlrlHWU>%Ra=*hsN($Xbyf93 zi5Wj@S{sd@)NvE0)OOFK7X0im7M#GP4Je_W2h5!aONqNqw%5igq$H*F6c!ZQkIrK( zEo6KJo}JG)4Rp>ewj0rx0MBFR#)ZZ9gW&z(W8h(6Ah+0lG6#KeF>-yeTf}|^`r~to z?Hlm32FL;)I0rrOJoe?x9&UL=CJyx+q?5M>``Zq&EzAt9`=GMwcZ=|TtKc!_h6pFR z^-AH3%eK0EM4x4SNc0)gtd9%E{8OsWvOX_3INiFYl(;M}w!4=Z__ygI0xv5L1Yb(Q zGIU@k;DWqjGl)?6;mEqOvURKZcVVOf?tw_H2y_xjb&-0+Xm>|qNYv@+Xj_Fr$C^m2 zw>P5BM0&Th32r?khEmHNO9zBK#p6sk^Sr|yVg@@HVqn8D@_u8xn-EQjM3bhW0mc^S z18Br+Hm@9`%0px#dr84iIGmA@Iqg3W3z0C4XX@duYMy+q+{GKrtvgg87Oat_#)KE2 z#Q^cZh^Nrxxoj{ZVrzwop2H3!5iD)%>=1FE!a@|Qs*JbR*S5sV%_|<08Ldm_z!VY8 zVwI{SlE7Vc9QFEjL>VDBg9(<9c0}zR?&+k&wrGHRYO7jm;z-xf=iwZG;)896MMCLl zKhiJ{b|o2!cdQ*K?W?;itBs9{HvyjkehmB*n8(HC^*}w)16&Kd54an65cm!7B9PA- zbQMquTnbzT+{Y%ybHMp*g2aJ$0^b2-Q}6=d0B{TNHQ-5L4*pyK>;;Yhw*p@P9s&Li zT#21`0ABSSa*!HMQPmO?~$#xU7vRb**0Vd<*KhO&z`^31J1#jtWk zInPlJT`BLr;D2pHQ*Fy7MpC>}?2Sk$_Q(AU(W|PirKe4cVN$hq`28HY^oc8L$(A&E z?zAu2$hoB2HHOGxkr%A&gB|UbFPC;#*S91^yGk0vp%I!!dsk%3vd%S0na<#fz+x&C zjEGLf8tCldEyFcPdOw7aP3S{93iS32BV6ymka@_LVZkNPIDJKo;|MoGM>@2o_jYQ_ zAml?@nNw<$SVml9cSJAG(lREqPnfH>9*}czy%QU0MdE+?Ml-^QQ3p2+k>pFWV+8UU z`XbfZCz7h=JrS=-3Da;yohIeSBsO%)Su5{T>{UwRu|BYAZt(np;eB-n#eWjNzc4#=Mr*Nz62lu-#=i5^qR zhVG5+o@5_QruMU|h+SCDsja+1m|`j6;Yi;hsU^vNc!@KqPO4_7>xT3~D)rOJnkmv? zVjYqC#B~IoCY!?EVApDmTawKsjWX0pMNUp0qM@-* zsu@eX$m%0Ew2R~}Hc^&sy;4z+MC3`LqzKp5wzSk$@8B6~5zXFQdug@QDXD9R7)pB( z4=ZEW0c5LpM>@KD1_+X8L$&plF6&&8Kkvx$Uk^jJ3w>WiHk>rU}dTOwWTl$gGWj&;q8hL;_6x>~Al`!1x zFUUl_^i}ja?MHVsC;6S|b`EfbDN&54Ydl^9Gd>;|k~SpmI@|JRrCh?MStZjXKFJif zV~ii@v__>;I^Dh8jNx%DKgD!Y$uy_io0J$IOePO^_4djbljP|T?@Fc-_4%kYD&qB! zaVcp`^1;oIq;&a<Vy zhe?ITLe%Qj(d~fqw3Qj**hu9Chtm(vZqcp90|w`WH?%vXNXS5`-XsisL+I2d%OVK} zl7Yr2mYHR~AbdXg?I%J`v9E6`8lU|3ecq^p4J!#d-ZyY~9Z%FBa6X>;Elorz;nV7M zD>tm*x=)2K!UhtA#87Kl0uKzN(^o7oJnH6GDI>9Vt6tAe4k8 z^w3T!L0TlC2^f-dPKunnPp=TbvxoaomBYGREM^$e}hLdB4f>Ng6VI$cVwih77kMU~{M13YwIdoNV*r zl^veFS>C}s*(gGuN2;=f(1NUZM3J_b&EKB@M?R07XyT>c%IYf2U~8x&J`oyAQeu56 zh@i4M1(H7UVJ?hAXtU_V@TZ{GJOdhj(Z=}qEb2C~_Lh$vsgl*q3ux@cN1LIUlQTY{ zd_mthW(i`FKn8W=)zhTShpj9s!nTQ;8#ciX4Ks0cGD-a!7P7(U3}xfku)=mM%B4u* z^B2|?r{FDhpQ*A23b5$Jh+|D+E?ZVmT!XjJCt;MGnm=>e)G3o@%SDIXp>gDC86n8Z zL4e+v2+IjFIhCibrL_qxy}eb1w891%&aAJ(4I)mlpj_Tx9mqS>U^FP-;)3dm6f-x7 z!@`+R#ewAolJ%Q)73?KBO*x7vS*7(%fDbqEAwNtd@YorZqteyRCZt$NedJLQOltx? zer$u_M}@N|d~`ZZp({o|u9$HLswln@e6z`%=_X^XCiG)A<|3RlB=ATjz)%`-dPP9# zzg#WJ291LNv`U-;G>abSKaLMQ(3>=ZuDLr4oQ7EnZsW1$R3E`Q!(bW!6d;D}wOlJ5 z;j%>aDbfWCalK3oAocIZoZ`*vfD3N%9ZxWDe?Rtl(Ebl4>_|s`$YNvP5sT3ZD&P$| z9__-}N6=pm^TAIJcEPWjB^7c^&6n}32QJa4*?-K6^bO_(y2GK;MR%PtGUk;_Y;1kX zZ#+!VFluByG$RFz19<_udJ~O_;e&14ibrYEu?V6%1IsTEft&)WT>GN8ci(GPjJiAV z?LKQ#_b>YClm!cB72H30^un+l^PC;uW?a$c&=fY(5BSPMbQ}oRK*#cf!;um|YF2j}&Pc`KcKh)38yLm^>?`sXxGD zaJ(&8LOnsd zjsv6YtzA7UV6KH3j)SDF58zx2rWWPFo7pA`ev8H8z9|B7&)t?l9M-L5NOzZ$?Nhic1^ml8Z;%Yz&mc)t`^T?6M&nC$Us8%(L? zWp2C}#QU?rE%WA=l~+MIKI~As4B0Cjfs~5{(7z1s#ul!6Ak3_(D8&$t4w(v@;$rLj znb3&`{;35!fu*yu27*g*TOAuZc&4jFIz|4o7$QY3Iy93H4w~wL^*OOVFxO<{)U2$< zV?Sm9p=O|oC4E8p9M#oBVI2x0^Qg+COV?xxj?O*X1TIf!0G7%bK}!asQ1S?%~MVf z&pvAZ<@9ue`3=nOFjt=8^z?wa_em$koy1PB(__M1=5u;tU`Cwj^z?!`7bf{VCr6cM zCrp;-$}d!T_U>2Z$v9P&X9rA{r*@9hgC-){KjHM?I7nRZE!qIg(T}Ne?*F~3EGHgt zmF1kY-HGQ4K&JfdJD4l;Rk_=Lfiq>gf8JG= zV_l&t$8RuMjy#l$<+uQ5Z8&6j1s430L;Wvr)MC{=+m8^c$j%G6JXvAa}d85I6a9lpNE+Qb7h$m&m;)(#8#(g zFwD2MI6XsP?uGkMm{H|U&oG#iU=D|QCCm{p&#Z8IM#B6AW(v#^RZh<+m>Xe^hFSJQ zSI-!j=0c}uEX=$A=;|2Va_eN zpXwYEYHB3NWt}{3Z5jtV|5#Sx=0A^>agYsN_>3ZctX!$d?O&`zQm1E3n3|6PEfsrl zI8sFyEdp^$OdJ5KRV1C!+2o@y3G_ArRQUji<%@V_UlbQ77pmAtukD9->>w>=jvj3e zhN1-XY@1hNeWLsgAAtom!X}D_0kz72rh_JBWd(zBu3t8zpsevkhG%635@{ZDunp6e zS(F%$a^e|5oCEr+Se~RN3Y3XL1=4C51D-Ww3=BP@acU%GH5C}|Kw?9_)(W54c=*J` zq+mg9iTl9@|7HFe#eZG^hW_u009gR8IYGOo%HBlPdCL|cU{Z4-?d)NrT6O(mw5ESG z7cwizE@;6;oR*-$HPD3^*GKwr{7xt;Evi)V65MA*LoJshdR$<=!Z@IA2(Oiw;U)Hl z0TcM>XutTefuQ{ww3tQp9PyfAuEfEOGnco9Gl`}N3+e=!>gd)pI2r96jTu<{S-c$jmg^vBg&L z#1^Yv%rY?%#~w1(3&Ef2Kh@KbWwi~ceQe$UI|hi6KGn=Bt*)sZs8hpSe=6p`b(jpv z{xQ}UNFUR1th|{MFERvoY_s7L8}ExSnUlGa*LdZrOf@^sh90{Ahj1TGWw8yy9s`>u zOUx2TMkSayQYi72rEt+wKM*0+(Wk!}TWtd&N>R0-INw`Qi!Vt9P{7_PGcI%^|7jQa zpLZYsUDp96G3wo7Ybc}D8qo%T=0TINPt*z zBn`9m;8rAH8OCEpLTQV@@~*~T28CAgXqYE!)g}g$I>?_WK?tI%aUNZk56exp*A6~b zD*>!pxeQaU9D)gW++AK;BSqkG*aS9{2W$-Xd-q6*P0f@f6tLM zZzuc!I{~@qiqocLW=u2lX5nTLgwFZGEm|BTSFpK(u69}$L{Up?&8ZXBVw>9>++#A+ z(oBe?Ofyx(@Wn)mpML%0FQ^9Ox{bf;#XPi!0`tX%9Iwi%^pO)LsO(A-d5j`=UpU0E zopX;T7Gn&oYC}hUL?VJxUXH;442x3ukc&-N^Aze8H`Q@-q*$byE%$VICZiwLLuaJU z@v$8W+VZ#g!K}x=d4I>>6B19VzU#|PZ9ZSN?$a(|F+TdeHT0=dKffa7&gr|p-m>$& zwTtdEy8C~*FZcPeqhA~~asDfPxi;kwr(GPQsTUg78oYsNv6*zk2uFAHfOS>1mPWJy z1|!(&5TX)LidAtT%pAm=4dCi`1RxO*2QUHae;(HvFanSVm<6Z>)B~;r6qYTJr&3f> zNc(6rGiy4Ya!Z>uQHl$N%INxw&`Ag6ndFyjtr&?>BnZ)>CmVn| zgsPc?MCK*10^)hCzexEW7=ze45;sfusi)nx?PPuVp}Z9Shq}5S^-2heePvDTf>sX8!ukW{i4>om~z~ z`#)B~W6~E>RIA4Nn>_z*j0*oemZK;Iv4aMjqPPNtmvRRUy|5`S-%RyZ)j?tmqg;Is zrWfP=*iNnXPsqTG_b8S`^rcna08_#aR>a>}AOFfxKqkZwxrJX>pNFkF#F@*-Y_ld6Jw3*xxc=eaFzjvP-)IBuzyvVJmh>}SZ7>8g^Vgo5@$siDdrGB0wAFdqdB z=1QYC>c|!^s!Em+RHQbM9vn!TQ)cAK(?m)f75cHk!9r@O+5|HlVk&0EB0d_*rwix@ zEJ(OO1c{A|$5As&vq}f0rYzwJAC->Lx&C>IB=kI=gw2I(?*XN!doP`Mk0|F&VTtAqp1ARw15tl-SU@6+TF6# zwEP=0tvH+-&;Cs}%iW5{^5?hp3w6WDFT;g~x8qxOn%p1f&x$8BJSl0#WzUZcq{CTu zn#8gHj`hv-th5=9-}awde-MX1`#0U}HO+4;ycH+$t+234e|vc>e+%D=&-#|r)O5A^ zAjU(BSe4Y$jE)R)JLu`egzj1EH1@dgKC|F0dSsyeDJ)5kTZFrIR)ZM zB922mc9x*py|RXrpqh&OQoj_vQdZtkI%?!uTm_xSIN>V8^{$FqIn)uGPJ`%I%DHlA z)XGCft*kO?TJcPIzIK8kLYxq@$i$rkEjnLSzM!VSdTLugwl3*Q8j`PC0$KrhR>X4> zo(=K5hi5#o0G??K0Pw7W=MOwn;5kA%U_4*~U@9ONFdI++@B@kg3jpPSg@C1ia{w0t zRspU8Tm!fPa0_4);NO5PfNg+B0gnNm1UwCR74QMzW5B0?F98Pu-vj;xIKT|yfL4Gu zfDV8zfD-|+fWd&_fRO;avM443P65mT%mWkviUFLO*8$D|ECrkkxEOF5;99^ffLj6g z0yYD-10DuE26zVW0^lXUtAGyxp98)I{0R6J@E4#3n7bvQJD@ip9xxa%5J{8(Z za0*~1U^XBh;0Kff7629lmIKZKoDaAda0TEhz|DYL0e1nm0CoYM1iS=z6Yw73W5DNt zgMgm_zXKdDv{gVmKzBetzyQEdz;FPxVTv(;@qp=o*?>8Kd_Xy1A)p4Z7_bU(Dc~Bw z&44=q{|0OUJP4p3h35b-1KtEs9l@u7Ytb-~6;XeuI?tX3lkI;5%rKapVX{sBb_dS0 zVZH^EZFL9C7BJVsFCyh*wPfwpLXipwGEPlMU z(>-8M9ucq;XBJem%dl{_>~v4ho2J|ur)39@Whc(mth4}5zz!VCF5}5cSs2Zl3)Brb)hGUPgqZW$HSn|877=BmU$C`Y!|IG~(Y} zUM3+QgdqSEK>i}Hav+|IxR^KoXs$+HvS3PoNSXXR`+ zEO%{4Tx-#m*aqmo8?dYqf3_9+F9WP@#Gh@-4Pg9h8}ZN3{<~prY{Z{!l;M{F?rX%K zZ5iEyjDKe%{-hKAcLSbl#Gm{_|7C!88u4czBI$|zf7ysX>zw|(0Y5k5PukFb8NdOa zw$~-;%d#PA`KOhwk02iXnK%0H26Sn}pK;TF86dU^|0>jT9$*NdGvGJWJmAd1ejx#>~bIrhj&&=pK7ZSL@63x> z{_5uL6h+NI#U)GmGQn3Otq?DVRL!Bx+$^S;sgm1nkWxj6B;@WamxzUQ;o#;tnd z%XfF&@ZO!5N4%BNrpF8QM&6;@2Mu`k<$Jt+FM4a@vvW?%&Odp=`}^;2yS(QGbDk9I zyPk3DN#fTQKm66J{-rw}{c86&$=(_BM!bJkuiqZr*`n9bRVAmL?irs`erEnz4_x3^W@^zFGs1(T^`(aPI>tFKvo- z-(6PGvFDZxS>OEKujTf_X|KO@)g@nVp1X0+?`B>1M=t7d?`z{fy8rxxcV@jYY{-E= zUwje0E9&oOm%jV))bG#!{Fd<-EExCL_T?$JZ8(zoQpq7-x9)8x<@|B=dD~O2eCFM& zoFliM`Fi2kV{dJJLBegX><|C&tnGu&%sA9BZ`;UKed1p1_1@FByDjtU*HUs$UViIE zZGOM(p@aU*+MVC`{;8L2cx2D|d&6FgjHn(R)nWCRr&c_EM(#J^N$te=^A~pQzNX)% zSMToKcKgyU?`%F{YZK+&G$Z?(6|H-$`SrGfZMXbutddqMlIS-)NL*AwqNKJ>S<^9qw+ylz)+M#`SvyFUJ~ z@B0tlyM6iLLD>@rJ~#91=N`Q0l~oUfuRhXw|MLr8{P5Sg{W`9^>d`abeE98ci9cpc zJo(GAx%>Or?T<}g_UGqE{*{_o_se%P69*oyYjNsXi*qY_cF%5y)3rXY_x@#6MRiF2 zQd5WRTYcIqkB(ZOeeY-c?|JBNwYUrX-SJxVpO@|%zphK(xwmC+?ey2}5p7!^{&V9z z{}Z?LS^Q2)_S#Orb)2*OhuLq(y%_)Q;p?5@Ezf`Ps>1ct?|yjy?`Ic1vV?sHe}fJm zIT9LoAQ4!8-F(xcg?Ai!c4fgguY9qeJw@=xuUiYsr@uS#*^g%Lx^MTdT|WNxjX$4V zkv8O^rQhBZarWGe+aGA{KfBExbyc5yS-i3I=D5R&A6$EA^58j{H?x1^ul&=d)4%wy z_iInjDs9v0@DF|LdAwoJX>VU}=L*k|^B(E2&zrh(Q{0So<%0%Ye^%LnuQtDYYxf~P zZC~a*>%Knsd^vM>>+h$&%f6An;omi$Rtw*V%X)0DeE6R6>n_~!%(hYcZf)^vw&VGw z3$7mY=sD+~cgi1jf;46aA##ddzG=~wk6hr{Q@!E5s?kFW!v8(a@nFuAo<2XFc5U@{ z*9QC=CvNPf++V$z4q_fZd{ra@i z&wXr5_Tcw#KeD0kW8MFboBjF0#ivcY`JpkB7tFsm?zfn2Xn z!k2FMcH@$BpJE}$*9nZMp>~BsP*=5FuExy0x zvJ1EF__4#5Yv)wIv*A0>xeu(5x$g3w*LAz3;K8w1oq{MDE8;(LLs@G2J^B3UUB3C| zUz_gBzQ0x1Ss%m?|7rPT@6%1ili&KQHD`8D|JM!6&+h)>=J}DkcO2T*F6o^w&uo8P z+^+6F{nl^)<(EIY_QrXY1N&Tk^81~JZI4`3J>s;yl(K%)AD#DubNYz>c`FX2{yKZ@ z^_x}|j_O`f`)~8d9#3z+WO&%BM|wSb{+$Q=fAi|Md(Z8E!^;U5T|9EeQ>UKaF6YvS z_O26Bm;YU{u6yS$@xOh%AncO0pL{;{qfLX7wlJS0Cx5it`H$bBzf)qphxa`D;EyYB z?6m3Me|)yn^0&hOe9EK4OFR!e_u^?u3uX>}aX`l#+njmw*PmZ<{nD;~f0Xv|)T{Tb zeJgY1%|ERl{B`{Dvs{aR@ND#c`q|Fk#-|PZ@Q0T>E#P?_&+T}A$8$WM=kZ*R=X*To zv(lp}Gp+xyjnZvQ|G9HB`@Pq0?4cb8Hgu#*@HgaaaqhLtU(fK34?lH%UHS{3eb8&t zpS^$Gc7b>Ju9)s~+rF_Zc}TCeduF`)nCs*R*R)Gs`smgLyP{fe-+E+v@AQ!^`#$v6 zqi=4%FC%A0a_Y}_ZE;7P8yUtE!N4z=lCsewDejf6o1ay}^AXFMiJ;U#x2!NUdc)Q(}%kWHO=9SYUle7KN>?tTZA21O~%~|MU~)+#UN7Q64Vsh zmO6lx)k1nRz2@p$jA@pAxmPzOw<}NUW?T`%vkPyi4sNpdn>Abj!DMzC^>H=ID@<$^HlTe`(>> zaP(J*v8WQS9MHg>NTG1}7q=Ukj^-{_c72uVnH5gcSyukja#PI-Gpz6+Z;8J?UbTFk ziv3EcJg%t-bo2#f#S|zlDYr7DnTTk-bg&p|p-^=deWg|)^&GrPmRh@5zl!M^;0L5Y z$nuM2!_xf^PFJj?19=OKgVq2Ex!Q!{1W>r91cafYT5DLs!Ej+|g=8)r{Ft?#GZ9tM zWDAtOdA!tM$xkA243X+071>9pu6Py_oSEqvpf_8V410X(vo9UgXh$j|39TP}cCJ#e znl~wo+x285Ii@JziEs_nA$g$AcKtW5vZ8E>N&aAeo0)EMybN?-{ZtG&jn!aijgyG~ zeT6d?_9N(?LQBJ}TN9Pz$~NN(7Tiu4TU4rqnPp|AnAUjBKsSCgk)}YEtn$a;)CiTJ zcg0ew6T+q>uTR~}#1s#;Lx%u=Fq{8r$18aQf12%TCZ^{mC4;WV!H60&OHV^7I1?z8 zZgY0R*xDWLXkz#QHFXp@X_@xfhK$MHZ&`T%11yuCJM?%e zKw^Zm6%JMAD=p^LNbr+XU=*NAAmD#p5HiJaRFXpbPiFBdWG)md)UwyqQv}mjCkGcj z*V1#00?D5$1UnElonUXrE?-WG<3Y~be z;M&cP`mcz`lS`E~ws56fmy~0jqoy^1;SD#DFrL?wjXST9CF49>PjoRktF=f?Qa0BOgV7vtiDTJ>=~*ho}T&o9@66h76sHFZ$I#6blKm6szCdGVQ*h1-9qOPvO0 zY15{RmwCioRcad}KM;>ul?xVs5LbmYy}Wf0;880_SgK;`9!vsDS#TsOc1fY#S0$KN>Ro^>!DCdTMmDh)QrL3N&auf# zLhV_ydzW|OtVOXI=Pw?JeW(Q>h;503oeHg&gX>Ec9^)ENu+l^n{dA<$^$-q4p4i&K zv?nlJ%2;!9Cz_U*6=VW00^v;pbsM#=^onVL|X9IDNO0xQcpz7}#d?gSV-V&Way<_NqJ>$mMAQ5(&;MC2#0kyx3p} zESF4hKA6^DUA9CHhL~^HP*J*$D?K=1>UjW<6;#Q%JE+m*>?N?4;1yf!L)Tf6&{t2w z)P)Z@Ya~yp*n@L0wYeBfewx&AZtcfWGh>b30p%=BPiL$dh%GM-rxpR`wdSlW0~ZZy z9%AodAXr`I8kC+pja7*|*QyM1)uU7NK^YTtUgK7_Y$*Yr(#eEI18$Im29B|~$h5_0PZ(2l z+-_>H1=s}UvA4x+8KE}Od@)jXaSFk|VCN)W_wNJ$N(tHE26>WR@4}6QG9>-Q--anUaEpe6?jY z`Sswvd@mLrD0My~w_>w3>&CV-G@pQv26CN*{yj)G`<*f?x-7+LoF%ZME3Uw83apiD z%nY0|BQ$p8EmXC4q*vjVV`?*}eVSfPZ&7Q64D68Uz4yk(t3XnEK_)vwv(hVv30zOc zt~&ZEDnLN(Y6oRebrCk3FbeQtdTSXreagfsQ)f<5PjNxxUk2|0CJvd^ zPvA8P3R$D!TYUp3ElSH!h=&}%)Io5g{>n>E?Np47ZjgqYQHSs#12O~hCaa2tf1BH~ z!D($0vOg7L4+dA6$;H?g;BlDj!I6SQkv>WTCgwas2a^U{7?-*TFY{w{H2Q!*qh?a6 z1k|V^ZcIhw;DJG%vIUrGQbn9!(~VVOZQodwQkhKk*4Cl#QI6OxW%tH|dF*xs(rg$a zgSUZY=Po-&G#)Z9PW917biSIL*lYi^I<>tPINFs(;B8NsIpf0ZC zc!MO7GN!Va$KsS51;Rw0ui=m)Wo2+Lz!=fxIikhYawPfApuoC6=x+ffa>Mt zQyi!tb`o-Aliey+KiWgfT?fsm$ffKLP`Q#-@e0hesX4Pzf^@Pmdf>*2!Ja3GiA8}F z4^ZXAeO>S@W}3(kDz^ceg;7!f&XTvZB@$V)3c>~<$em-p zy`uXGdypo}Z%1mHF(+s6OpJe1aM8Idz7H7{%GG}c%4QCm6SS=}COXe>~Wq9Laofzxfuu&~`%VI9GF zy2#B=<#-DtKB?IPH$YU4PUf8>EkukM8S)J*+_lgV($*Xek3w!PT3i6p(b9H|Xd5Co z8ErsHQV0{5JouB!FJaCh$~=&#O!1*I&A*iCd0UzDpH$|u%apnP zVrA~WLzxG7DHT87pP@WB?}|_^n|DlH0RHIr(N~${JTR954&B|&^E_Y&U_GD;Fc&Zh zFap4MwgEp;Tqc!2HbtK1oIV zXdC`c_=n=NEQ!Exukq&tCkHSZPs&Tbx-JK{@q=g9;60l4i0>;&YE z>F(JGa}8h_pbWsx#(0XUq?khnW==_;Hamw8-)3Y^jGs_ZRG9){%iQ>oPh42!mBWFd z&b$hFv@aCRs_ZXo{BM9y9Q%*>a{<{JpZAI0)cCIf--Gzy zf}a&86yE`lcYwbPY3%@h6mY+QeJ5ZIpbU@$7!44B{^w<%_iHOhSd@V6#WA=JtzDvm z*05G0ozG<1`CroL^pP{ie+Fal!y&1N-fQ|df6fJgX zHhh4oj>dAj!opj&YTK?;_nxu+1`HZHYE1h02~%@t7x;@8lrLO*&V{S4y5@#kHvN0c zwnra(^66JU`1sQ=4}SlrSUc#Vw97JvFMR3G-P>+`ciWe9_RJXhecSJ6Z(K3%^4Cx6 zcGucF!{2huIp>5&&P_V$@w1|)*Uo#S`tQx}FWY47zrObS>mPfp^!iWE8~@0`r*3$x z&GR=$om4sS%lJE2)}Floj{D}mbHVS6rkyf&ZTVA4x9{!iy6@?wvmgDj<$ zQ@qa_&~4QI+{o>HN5q_%aJYQnF+HkkLtFn;wf^+zj*o5Z5>Yn1$E3yCeYfqrZ^)LYZX-{= z^Q|dUpItZS$I66~?^axjz5841+t=@18R2|-^&dwbS@U&S&cK8uM>z=qb zNrM;s2YZtagGNpMhP2rE?uE-qj}hCle zM=Gl_NvGBKe=>!%`e^Hs*GaF+3(xq0G~0Z2$5Eu)&=a1HCGD>4Q~DC=_sYrN-$)vM z96NOc>A3Cn)vHKL|GK*ulb&_X0kcWdb3VDPf^>cD&(vL{?Y7*u=a9a4eNglrX&jxr zHJ)@H7xU*@()yFu2OlB5_gs4W7}7j;Q{)w-d*uq(0n)yzqID$ce|XRGV5>ezE^gz4s-8HJ%#mn z?bnxlz`DFW`}z-ApWaiSd6ISd+(oG$vtDaH_AX}K-m>HVH(0-i?>{(?bv%Dir*zhH z^<9Tt`+aI-a9OL>VDS!fZXbjS^w(_`h4}`*uKw(@7W#m z^p5jh?(y}37v4DQov-R&uJ~^0)U$qmsIpV_oyCWY+t%*g@Z?$E$a`A-{)l_+xV9&b z@78W;%Y`SdJj>nt=f&^FU2)RWo-^)xHhJeG&vb}<U$eQ{zoJ-k4f?{J*h49XDj?u;C*{ri>ar245b4;0wrj|2U#W zWXq^lt=mMmJpsB~J9g^aMaA6p#BSYt^fY67^*$-KPv5wH{Ra$;PZ*S#lss7ar%l3( z<9KdezWb0lD=*kfyF^u?efUC zb1)Es@wgktlYBh!NF;ka&TvrzbxBM}PSxXKi%-&tI3q028$lcz;_(kITS81b%3QmKFkLhCu{=XoN6P>WeS;4HW}gyPRG50r`U@G5@@5hu`IP zy0r^4Ww|*lH{`=|b80sxZMnI$8&hNK;R3fmsP;f5?ULW|kUJS1?=AFVVv-x5nUOhI z))7!%9OF_$E-m3=z)3EbGr|E|;Bqvmg8R#sN6Vmxx*BbHv+eQ@^MU|&N0P+=tko&-*f&&kat*DR=tSK?LN zj}SZ`p6M^tXUXhG)Swk_sd#rZCxe*$v za?Ru!66M(7Vp@o8HDXO&A+NZlmeoofRJrQY#J5sP#cu1o-_p=4AY&E&S||#x@*{`P z>x`wAn4(=w`(X|jVPd*lQoNuxULCs2=+l*yp|nqT8;nyTKn9_DiN=t21P|A~QgJV( zJSXwN16roLCCw2MY6|fb)pU2H#;vR_F2K2u6gH62O|>}yuVo{61!dEr_|U?Ja5NtC zoI2g&)D~!7toT&u1jVtj#Rk}+lb_R}XigPE9X(D_=W7sx;5no|ZJX|n)<}GdyC4u( zj{M@5ppHvc3W}xB$elvtkZX~D$($^AUA4?`F64HoIxKezJp1cJih1codMk-+i7}oS z12l#b3Mi`))NO{0*1&I|6*_R!>J%JjP@=C|_4Sgd=E8vEbhqs9ksAoCU_U=k{+;el z&=L76f)U{TB_2rBDPbn&twBVoI!INGzYa(7OK{O9U~6%Cp9`<}VW7{^g-E#eh4uh8 zQjcki4EaszRqZg{9j_y+t0=`|J`DlnYJO{vadMseQcE1be zbK1SPwU}JQ+;bVP-Ev^g0dU`@M7u47 zd8W3*`KaH8+V66j*el_l$+fUEt(#yT(RtYfJ9XJ?hFJtW`ai7Qo`iWV+?bb_wA_3h{*4rUbzIbqLf{^T_+F(+Jt_q5gCuG^>R%y{CWgkNt`-98IZC@xuM2^BKS8@u z=L&&3SUPJr>SrNPUrP_|M!hZs>UkN7bV+0CcS(nx^qi*Ms264~?4;)c?M59kb+9)@ z&y^bQ5}4epVR_fV&Nw#0+yY>E_rPS{_rlxCp-$=E5oSDq zw4wVb?Vbs99)M}ky+XU!!(0PkIq810cE1be;{fK9?yqV0_hJ45V0q~tj=ey}8Jcb@ zxHD`An6UunhcFa&h8+tt2f(m&FVyY}V4ekFe&~Lwc3%tgP5|Si`%dltB+NIpo$g=4 zPCEPulK`vSho#xrFZ>%t>y|Kk0a&OZ+HC~PA^_tZuiYlXoCn}WZk2Ycg?S;s1m1Np znf^wY4+0dG;1KeQtx@k&S|Wqh&>RezvN#AvLWo?Q9qDZjJZOm~S>?j`|BXF!&(s+I)3P$lnikRS3TZ%=7BGFGCW8t;aN=ie=5~eacahAO)5=aD!XQiXdryzyZDdc*4U6 zIT9HX`LK>#|5*sD$oAQeJn|@&5@o{fF6Gy(8#+YN(z0SI3L~%1%4*Z+f;{zSZe^&T zkjK&FlA;2v0?Z_;aW0M1G7_h#j&eNq(gp5WXfHYQ3neatTGK}mSPL78CUGSS=91Rr z@_52j)Q~Kk6xy)!LO6@OD-XNW0!NB!1W&igZzTzh)p~P*a4nFx)gaa>H=Lm~SuRNW z{o{y0AsI^{1k>gH$bm9KDKb%ljUgSQW~=716fDPaAUB`?M29Uz_x^I)7OJ)5P};Fg-BugSiamUYP9nzNLx5=)_-OB7zAt5rK~;l+mrBY2w{E znjRs3pos|j{t6QjR7uk*_DIt$4oWjZB>qN!^_vfa<1xot{tf}4TcizvX<19l2+V3_ zBSCNAugAm_6YPR2$~ar+&?Yt^2BP7>4f4}`;1plJB3jgYn~eqnhswv^nvB(wv6IK_ zG3E>{u^3y=zQ*dj)WsqQsK6~2FJ3emTX{h-7JNFc$?~K5m`3^v1`iuKR1EhI8}1!G z(ux_6np9H-FcZpOjE+2?V%&H>6{>z~14sqccyj<)lpTZkAN8VRvlD&lVo0UpE-bFz z)IlMMJZZ+0921U4D<}h=PpJiO9z!V)22LZ1u@mR&q@nL*3dMNUH6xyNhh~7;l$X7{ zg(kKQK-voEVL1jCAKeO~+VYZvn^SU8)~IjEVzsp;6R?HiQpzmwqoxB}XBM?=SkwH) zU@pY3vWs$=0a?DIsK#Q=(Od=Q^d%(Dlf;P>kj%$&%*)qLZIQ?F`K-oD9U6(Mfd&-- z!S6*<-a_R^GkXJ+TwbT6NJi5rR?D-*rW#hGB&_B>Nn2DlE=ggb3{e-3L?wLkTq986 z9_g{V8;M1)nHdWkWrKXmWE%6(JC2HvfIwwE4MI{m3iyoOreZT2aRXd|T>#2|Rgp^? zOT|k5sMs@= zWlXYPtVu9)+*5mGM@#E>(`L>nn3hAnnIM|FDqAasSPrwHbojG zmeol%N=PV154d;!8+(trIr)6>+5#~(_vpS|hiKHVsUF(Lbeig+8%w0I&bir0tcEc) zR}oou#FaJqdT2^0X?9GqLh~^WSx2fLm)8a4!(280Q3Tw<`;S5%BQXec-U1cLGt+vxSL#1Q&Z^` z1yy*E4KGzdUwyr(tgI2$ejNB=bE~Q*zs{QkV6=`-Ut}Q^63D5M_b-K5>?jw0CrbXUdd|QPoz$SE*xIk z)>wgWkzP>6rvxB^rot;b-{sVg7EA_>tSjOwc_^}Vx9rII6!#3cufcUWea$aS^ABPZwN@jCmM<14O8cu;T@zcPfc-Cc*c&{^&a2!!qU05vtRN$|zHG)cr89!^C zK)d~SW(TmebCvT0`Dz4o_4miO>uT5QqE4cHAve%gh!jVPY!3UdapZQabT}OwWZtUy zh(*gN_h>O%ejiA{cVuTHQ6$Rm-ShC>A~9m17%0D&J&f;&`GN04ui!hXEbtxI8{chC z2*j6@h40oU1>#%38sDw5B|g_?js0|)93f?L98Z}Vi|_xWTc@fXo^Alk{HwBu=QjY& zAkVPXqF&{uMxnm|{erS%-^5<~Y^Yv50gnE|i=hOs^9gTFfv73-`zgBl%#A%fgqJm( zwV{Wn)lEG-PMo5?bVbIvso`1UW;wFP%>(4o4wws=57@acbDS+dfhSjxo;5ymYNy^| zX?8dtj#155;6r}i*n@Hc+CARGlM0vwxEydR;Ca9Rz?*=d0o>P&Y-!5@rpNi36hT)t zPFZg+1>Jc%iKl|q{ZCtSk-eepW#qar)CYp}2v&*Cgnd>pIubSbB?sYr&ev^@M`z8t z(rrWXmXzoF7UR;d%}w^W!N}F{9sEWW=i{_6A1}|~I0uS$8hTmI*0VGr-tww(erTL} z6)qN+p`aA)p``--u$)RP@?$hcZw@nUW^$sKnVCa~A0n;sNr^+mRBW}%gJ&@_hlkn| zX(mG!GEZ3oF6rqLC(~(gJR~5*Oia2JHZ9zK#ak~evc?@6kT&i)n6Co%>+ess{h)UL z4W=Vf;RH#bras8{u(|3V-ajqit9Rn^-aS3*0rvpj0_+7m44{8rJ=H`=)V%sEylkuN zIPB(K*}VEpUWbt00jFuTHAlIodKd8E8~wW-H@&u|5!Xq$#xRZdzO%5xv!my7N3Btx zym}t|@#?J|KOJ`@@VG5H1ePST!YA`@>CVWd7LE$cF6oJ5NH65)n??wfF1HRhYjE6) z-_#bpJa(9j?^%HHfLK5Wz)vA?8NS~K90vFRWq`8)zuRB~>~{gS0(JrR0V1NKARg_; z*u#`D@;Smp!b5zU$Pk?{uDmX#!|BhFz$rEe<-b(>*TH`}#Yc!`%$C(&* z&hETZV8m)EemOz8FNEMW{XZU|{GVQ^{4cygnNLhn?&l0qW?^52pNdBe7;bYrWiD^4 z%-wj%hVFYI+s<@8!8pcr(*`NC8si-OZ^rmZ^TCjC@puGKzJ@3zK2tK&iR?8+Pu0E}&X9b`JFc)xl z$oCWTdV0PCbb@;VU?c2r0bH54Yp+ioIP5ge0od#6_J z=GnZ1VX;BmgeUrB%hR?=o6EBz?y?m@BZIZWmXLr~J#9!bS&Xi=P$cwt_?xD;rDhZ31 z;1431;jS<~Jn3|~-0m-c^S$-;DJl7!c`0QeUO(Qt^e)H;IWVL)iBnf$ z!^*843GFMm>B&*9TZgQ1Jx|CQH)UiXaPp9*637(7Y?n1|2=E7ngc;T_j6FewQsGK; zII9PKO_-j;fF}T!+ZV7$J50~>Fp*K5k>$&6RQfaRy*iG!U8d(czyko<4+DC-8^R{I zJ!$i|()cD4>9sUHBR-3fu(6Zr`QpBlZGGdD(UnkXvI3R%KTe9(-YO+^c;eTU`b__I1tioL%N#n6+Zlu6>n-!P5068 zPXy2(GqU_jY+6ts72{|4x!RviKxu(AYpS?$OsQR7;Dgo4RUYB>8)bO3(99_ zrJj4}!a?~lU4t@Uv!u4RswQR7pkl8#0gRsjS-e5emQypRUrMBjpP-n!l6c2Hi7zFk z0jH=^@9k)M_5*eUlnb7Cg*_Ve9a{G*;Wi1-4LlLR#rNpWrpIG*Yme`o5Vtsd`?Om~ zmF8M}bF{k@zO3`s%F`v;b;xr@B!23NrY8n496F~RgN@98q-rA=9;F6dPgGYG39s5q33FA&%d&anT+B`FETej)B z6YwhFT>!r^jT0~adE^M+MU>M^d=G8JjcM$>@U3g^e`Ve1!JBT!n>Z6jj@k56#$Ro2 zO}^op)h|UnG$%H_@@`+8QPOr=CRRAS@X2En=wbItg^2?7URvg>8H7XCL0+f{#rwdO zW${zS4@!_8gQT26LA<<95$`W6lCPFl_!mQU>L6{vig&xE)^8fMl|1Vbk*9(WW}2Qc zfVF_PXPcfk0m}dz0R?kR&kJz(!0ZR$w*_=>3W#g>o1wq$?pvA(Z-uqee*(C~x6-!U z8;gT!(cMauaanddKJ5nqeP)@SeEop`z8`cs2SD>)4YUuKXL>$4OTkE+oo+wR z4f>6RpXW67JqqSTZ9hBT^sGD%u+nJET<%lxcAjr~{s!>df>8V?ke21PvNC9=+gmm2 z`{&xA`ziH7yA>|fw5Q*qAec7YpFw(bi$uN{?o*xqD+^4|rAYr!bh$TJ81iGEXa7x@k|n03PO)`^scGpMnOVXgTgJVh(^i|Fs#T_E%{>iaTO)47Ndx}z zKxlmS?*|YEzrTRF6u@r_?0B>r8khEqY<7O{3i+nntv0u(ZFc%uV5R>p{6D@lm^R(N zK)GLso0aZfe0PU?GD{LAw<$)U>C+JS6>8q(`@vI^B8Nocg5cX@m5u zo)7vl{b8WfGF$rZ==A9x(zPVo`xV-8!JSewOT?6dDgT3`ua5(=ueOqV>S_P`26>rG zG1H01Y7sAUaHtp0f0sG#V#q0*J+sCg5ji+HpC#V~hgXxo^d^0j$N%mABT`y;5)Z4n zZ=Uz}aTX0ohvuN+wh8BVsk!MBCNx8hWBKDf!vC>JoUC8!eN~%e$W<7i3*aoB!{eK8 z?u``74h&!Ncxrm5im+|lc3hG5^Y7!nbWI&GIk|h{@7ar2oI3i^nx*ee?Vt|w#38+w zI?1DwnXOFErOLeEab=$Vn>3fLOh^^@?K{CM&6RInBTfGcFVHme*E`c-ez7QfIL!@L zb}fhL`E*_42AFGlJhAf)m_z#fydWyw%BNWW*10o>EJ_!9rxcezc2~L>bJ_e)W__6M zS-q{k`@J19at?m<#wT4TW?cUIWaFhn%QAjB`NOB3@!K-C-thL4^!l$dvRcP@YFoy5 zmH=J@bij8zz|K}No&$gz+QfKTM8$Z{gy{$H+XA{b1;n-cU9P|F?gx>c9j7t7mA*h) z#JAG6+#8F7Y0=$Elkr-1J3j3L;8zHULRr%QD*zkt-5GH_3OdmI8YY4EnJ2_}1`bqE zVzbjN#`awfdu=;~R|)eRZQs^D#`ExTfR#pbW?F|BPn(Xx{4|G4zjL}b#EtHyzTLfp z?sxVH+K&|<)9)IR{x2vS-G;!A;ZM-!8(m^NmmvKiF+o43|5;mqnPP7`76;jDD71TOKdv@Q3>;$T{Ix6)*M zmfem|`=fwg0PAyOJZ}IxqRhi!-i`d{0%$JPK>NG1VmxcA6?|i})9qH<_xG^>He2ES z2-7%K*+=5Xof@`d1*sPC1fLH9o8LHn`dWBNCSr2jAN zwgV=^U#-pA^J6@%k^a`=7?0(*2I-#;I$df@f1Rcw-H+98QMS@7t@5VG69nx3OFev$ z%atCrQ1C8zv|#gqV)csJF|j_L*}xDI5qn-$CQeF<{ex4e8j=b~p)jPfdPz(uLUPjx zjr%D1ZQBh7nIboGnW|7TbxXEOUVE^PLncp154_?gH+m^{ohHSOrF>u!&;H|Z#DjA5 z6U64#+B*HH4|j&sCghkrviJJ}XmpbM;7g>+RQX`4B@#1v@`OwoPe4sRBl$m)sy-vr zhRQQ5Qw!*uP+XY<{j3yrkk*hQKw((Y7>F9zr!@7)OiexpLe7*iv1Mg-ye^b3Z4hc- zI3~7EB}l1Nl>z*Pn%Jh&kr|MBVX^6~US0yd_1P5eZHUak&A333jwePR9=0UYNF|cc z5`YI15gW27j|!7;aw5+G|KBvw@NhUIMSN4#hCTGEH(R9Y`htAi9zi3OEgvsH_}H5H zBtod0CP}a#kVm4tG*VcAa1gZ;%8uh!e|?J9k&d=hQ86aAN9B z9TjREcii#hueUIT9g8}ql@%y=-uZqg4xagD5hGVevbYn7>Q%1*Hx>^vf)vnfr9%5A zFqrM;P^3hzJXOY9HOIlp$X&Cn-dHwJ;A7>KD9vTHH1NhV+I-`jkjl4PaVqSGk`-KW z$jHsjrLJjo5xlcgfu1WnkDD#>bPUI015F>4+2RpqD>~KnLRbzufpOM$RQIhJr<4-Z z`8chnkWmU4L0wqGwHaaAF#?(1qGAD=>ST0TJfq{A6uh^lkY&E&VypUv4kzl;81Bz- z@Bs(oOdEP^t;b$?*^PWl9;vo&BU!#Nt)NLGaC?rrmVM{~L^WPo!6OvlSKLU#IH%68 zc?qdlY2(MWV;llPNv~FUK_r~6>tRnFJJuo+Ajp&VKpeg$&`we6HMOTwn9*2hGW_x2 zSrIbJ&1OeOcuYLdUq8&C2U6>vh}2^a@>&83u;Td_r39Qu$_>2&WK~y3tb*3-H-F_F zi3w9C0g5>4u#7Dj0z!o)+pcW0WVqX zrKT)E<83S16Vmti^ZvgB6C+<;6<(LFZL;AuOjY*Wy!1eQ^!|L>O8ug7S9+>C)7a{8 zQwpJA00=30F2-PTDCAhsPRSS|mDgC*J36SPB6(rF7LN@>yuZ4%3=dvorskKI2{`~s zisOkZD_)E21zzwaI~7a=(M|dBA`qGtI|L3DUfiE7ufjfZ!*c2`tJ_c&E{C~+vOP0O z%agim)DRf-BP#hrDyNs1nCdFx$y`UH@R=DaDvAzK3MPo9Gh!8nLdm$v3iiR>ju6Mj zi=ZQbY;QhBEqOmh&ki`yYF`jOpTbZnW^P`p9AM>rxfoGWo18c#5rpPVST;n>`^>Nv zm?FI?W|eG0X0>-wTw;A};)wcwXggkC@B@I;$}g(+gXgRwu#Y57{WV4T z^pylZhIhX1`Hn{8d~Q)Gt~XoJ%htyDSzi2yklO!$Z4j8Ntd21ub&Q9I^dM_W9;I+v zxhby>D9$acgz7cvMfHejWp#eYHNc5a1E|s27bAa)o*=8fI~`a#S{J<{XSq%8(`{rDc~Emq5gka-|b|n7aqafbok%0~?OU z9sdt-ryLJ%FgHHRtI8=1dk>Hle+SCH%5HD6f#n~D3Q0^5Ld|RN1W8~{f`J}6&jOu6 zHVYGIk}y*8i@FKqb0TVXa_k;L%c~+($V3-1vW}>p*uEX=nkBq2`Q09-X=I2g>YHxS zC&J#xSR#fQ^F>Y2J*pGz3C1k3K)H3}_Yh;FL(GK5Ydixbm9AY5vC5Gw9lESCPo$CysLX`B--{%{)0!o@AF9uPTm8SBEuXD;LXaIw#g1HX5|jQhjI4`Iel;o=J8bQycc z$xk{Vf#EVPcZ-i*#_evg0onn{A(2^wE^~AnGuDG;W=n@CV}KBYjZ;KgPdmcpK$xfzPQncYV}eLg2yOZx z*4!H$+nwT0CocIR(l+G7-p1W-vD&p+r4!M^RU)e44DZsuTi|$+(^wNOZgk>a#aB+_ z=5TR|%h(t$?splR!o?dd<4(}WW&9f`ZsWdivBzy}0fF4c1L5MLFyp~+aZi}BGhDn9 zW;_}$ehD-7gp2D8OGqG9X}7oQs`GO-goB|-VsrD0cwi@(E+gNC@q=mGm@hRSNo z!8bYIbc!FGDr?bE|Aysp<3v=$-$pMPL+AFfP*G+aa)`OGta9{+?M2<9qI+JA8hOZR z{OT0XJ4Z|WE`3gf%70_0OZei2c)+pS0qfPSvC=cT_i4CeB!vY5>GjeZ7%V#b1>}BYX3I5#wv$6n}4p>H5_#UDq%#gd7@ZF(WVE?K2JN4wLdJB zu5jvg(gcyKP}+VT4&sRW+Zb;~ix;E8bEt~e5~<=!hqzG(Yn>b?#M}{U9b$v!G6E5J zJS!dI67ACF#0v1V!vGIG>cHtS>y%wo-b{}(c8hL|EV`S#9fw4Z@7$~c#lKu&@NF?a7h5SWxzyC zBSwSas*M#cvCLr{af;Or<6eijP1>Jlm^Y>MV~26RQyg~m2g(yp<432=1!52#98s-} z6i1$Mswf1ymFK41k2oSaxO$;Q%GA4dL|0$$S{EkHcie#@e(7!lJDQ609o=y-OZ|aM z6hrFa0Y{(9(2+Pg9Co1tV-InivprnE&X>5!iL2b=U1vG$Uunv=Kd}!=KjtgRE-yR8 zCz=LxdKhsSoY<4h6M06VINdm(9Q&#pyl(v4A#QOPPdEgMzsV`CU|YMj*&$2iw%5imvGjzm!^AbH z`7rS436F<~cO32E@}t9eBTQW2G+@8dY3vUZ>z!TR4ij%Vr^987%UI?Xdt3%CE`Q*f z4419$=nulg*KQZ=J2Zi=akK~fk4xGdA!>Tx6Cu_)j6Dtz>SWl@aT=e8i|d_(VSm*b zb8Ce7)p^2(2yv;)_$pj%a&?9MX_xV>OMK!oVE+^LaB;r7!?h9Yr}w(W=Wb(Ngjg2V z0lw?evqy-h!V+NLU>Jz=9>cgjLYx;)`{m)rT@hkecqe4!iU?JCZ94nd>b#FR#dEs5 zYMloBf&iO(D_ zfxSTCLEVg7oFd&=??iWTgA;Ry>zrWXYn)=KjKE=B<^&mx$1s`Dkx70<&?q*t-mOm) zB`T39c15ExQPGoC>H&6*Gd8-!IOArQm@)81m)Pp) zz=q*ixXC5fY92)6K$|o?RvfK5WeHJa-0l!dN6NCC*b!Yj+a4!A2D-LQzNs$*0t zt~(mHIm8^?&8sjTaEN-iT;7&GH~1o*{aJOk!-LKuC&(>M?&4m(%F`4YGBPMFx}hV%PwA{>9RKa6V)#gImUW1+EFEL{@xL*Ew-RA0t} z4yG-$-ewq^tjD;+As*3Aa{kt<=V@r(5~cGXn4=8LFeiZkmpY6WIBH=2K(^=i138ycLG{%H0m*f0%KdAzlhovx=kyL^a>o;Sy(%Ju!jV?-c7D#{DjK zz2{+IL^tXpCBe4KG%KX{LGiuDo-owH?P20V$HOS>yUwv6g^3$o#*<;Pxl^2G?8D?g;TH$HfI$5-<@QE* zN4zl@^=6N!m5I**M!m|V#V^EfEL}Ag9nE7$9I+D-WQK8xo;1F*( z*t4J)mDx-<34QuF*QIW;=xiZ=br`p~#ih>Eg!tL%+TsSoqbcok8IQZgde#8w)O!HT zVa89Ghjo|Sw#+GRcfg9iY>kuiNr~2m{Y|fpj!zuopr&|xc1dwYxflTn=1Im`VzEN) zonYMR6eHL;bBqm6Oxk{TU_x+{6GPW(CkGT6V`nbW`g2(|9{h%C+~yGXYQIiBaBnx) zSmzKvTo^vXxLXeODkH4Vy>gcHiUYH36hTdlZ*m-Ph_7`7gL6Av>;kcFc9L%{a)~P( z#$Knm2h#%=7ZPX&uQ`mB7_=}#L-n67{i8v{Gw6(;H>I}EuMxGd^=EPCm@ZHzQ#!NxtMke=I?qI&;7t0aR3#$Z<_bk&u zEF3P9L&J>@OfTR>$QX$`$;BK&&II214sruVQ^DT&Zl~BuEBNAGr`S*H=VRA}&-M9J32n&BAu>taboe1OMK-pcDXnK*zICDA9rzL^^^-; zXlGzJ%kagO6M$4a+Y z=QQ5L`pRkGs?gI;11_&RjXzyn+x_Me=eX#CxdC)Gqci&3C4SHuSmWqw^u}_YBTx=f zyE_a+%0=TnPGfHv>J%gWYM1dun7EfQKI}4H z3=_||T+bndi+zC0co|bGwwjyV#%q}U(fW|=_+F#+fZIUt_b06vhPghKQ!M)&vRhy9 z0!K$~L3j;Fws3!=4d;!pZU=L;70-bvZP^U& zZp)^5M_Y2rZEZQ9+|ZW%auYC}UDvf0Z#rW)M2l4}}`s7cD*t`_qY!OIjFPqQ&|aYaIA^ zDbjc+QoPa9_`aq1tfjFkO00-7)<=nJqKsRj#63~%ZjBZnL>bq%6$hiZ-ugSL_XE*l zPb=f{&jR$gL2QnWyfb!gNAomLxIFP&ZK;|019Z12dJ|&&Z9Ro%z}sSpANv)R^l-ix;6xsEq;Y?CPhobNxk0<_2C~CQGoZ0Nv}J?B_&~{p|GF>p7bW|DxDO2h0`#5#+{a;ZYae!i`1xJ?_WyKW z<_=zLVX}fl;KN^xiy4-yBDwSu3^oI~FCczN?$7pdHHXjWm46DYlHA-rZY}MWuy5is z#zN70YBhY)So~BLS5#cqU&=Mt4MX^Jcgg)fmc^7ecWXBDr~7jF{FQyV4`egnmCrxi zm-`Un?7J9pY;sL!Gb5}Umi0l`a8&r_{>dwQ z8;m|6eWD7R3`I4`HEZu7mvSfN+T17h@nVCmw6B(MF^kC`{Erz0KHnB*k`B0l*YSsQ zF?iXNuw8~R^WWtvwG^(<5akk1=O3Lrx<7N}{v+5c!ME42Wxb_j|6lA^`(ocJ`Fshk z`(FuLlk7B|pL-d!T5-t~Z%eDf?vqUZdzGx=AvdCFpiwOB%lxDy_tP`b8E!4Xm)rN} zZpmf-a{s0H{MGDROU81Uo5EUq$OGPt-%-HjxRRITZaO3Lefhk(58DB_qD@1v|0}SH zjF(m9Ig_i`bF*_FFbwdKlH5Pbj1~6-WU_^r*SBJB@uD1>BS#%f-!QM4EIIT~`+4E` zitH7G{i>t^PqCI+&6nxIzmusAI?|8!XLjWC`}T9n^F8f`YTUSB`cFXQ>(QZ*(gW!4 zH|KsXuEzcWn)APwVAly!=J-OiuWl?8!@&RXU{iom9-W&nk?n$KaY_4fNM4)6#>cI^HZX?|zlb{sShHc*06v;5$*q)R?hJFt z7-zoVTI~2?DkkwI-@GWFhYD}LB9dW`yIT(*rHA&vG}Eu*Y>Q1@{24A&xdj$W_8q*TfILYq==Y1B(1Wp2Y3;`X|E&C_da5AZrtF;8 z;IbHU#^2w7fo<>mqxT1y*5Ba!!}m8~TVPNBg8lWleC>UI$o@v`|J*0vS;qUlI`>P= zR!hE=RVL}E`rP#xwYaRs`nbHLG~(wVV6JP=&mAhc>VlWa8WEjG>y+(3SXOdQ?))<@MmpGQihh-4q^IJZRg!(+ z{);dgmf$u{W)07(K$OzT+{Kw9E{loJW%T6rxtC_TBUU481B`PL_TSLnmciYnT;|9b z#UNA0ERhxQ+J4=k022uH+mI|$%v5lE#B-(a+mAt<`L?i5$m+lt4<5yTdwK)-TK#(b z-oV1fA*+8(d2p$P%|bQ|hQTLga~ZO6Fk5RFpVa# z+Q*h#%g_PV2!^3AWwRfw6%3s##juRY^f+u{h{+5%7zUfn2$-!58(>q8^e~~y%!8d{ z$xAg_?lG`ekbU#=YYwaWYiHRT!J02C51vK#PZ1N}w}VZ9*=+WK&4OV&GgbCcuthLi z{mp=_ft_j5TLjw#v-ui(8krr3-VRu{$*xz0rdkbVORoW}7VLhOytIKeIBfQUwSd{$ z{0LZwLvI?a7tGdPaKA4z0%ptS8rZnQCT`4TX25LirGU=50A}m&^J73IM@EqX&>OJK=* zz@q>&lVIy$94nD!{D(@*R4no{eKQZ^;C*`)DNsS{@WF^)~?41%?fV zR9hMc8w2}*h2b7qrtWFw!Oa%73^oV$#}>8;)^S~VFwHR^JnTzSc0S^A`|0JuW8-?# zmTJK2ueZ0)Ca_*GTNygQCc!XeH`9|g*blY__ALt=1DkzDd2oB21?-zgz&bn1gB#;a z`t1_fI#^SjNqQS#RnN3vSFzibsRzS0Un-x~xTv&({l0}Yg3USf+QC-9Y~vFCyhr9Z zn5|Ebf|Wh1Jh(WK9_`G4HG-Gb!WzLg!Mh4q0=b=lb{*wFLJgQr>aX24d! zu=$;)SH`-O##fc3wqJoui4VY53k_~P;)h%-rV0c;-Z>Nsm>n^*(e1+&dH zx4{ZM_PJQ09BUr1m&R>M8S24C!3N_@^3n>Hc}aQj={OU;9_&geV_9IcdKd}#td;z@o73IMMu4_g;VV^?v3!Gxg9J}FAa09*@T=KL7 zw*2by;4!ofuKNY;R&f&d+VX(&{OqrpE*n|dfjNv9^lc+}Gw^r+BcU6FSoD^79`_fSI1dEy&AApur>?hE$-rQIi53`POk%O3(Th1 z57zXS^5B?7Zw##T#`0jv!j6EgfOW;0uIGDhrz4gHaQ zZd#3jV+t(MXQf{@f-Qi3jCncl3O$#aMiSCLI>5Vcwy$^kX%}oC`__XaT`9*H*z{<5 z@ceigr5s1VGPl^*S4&_8uol`xw6N~`S%({79dEN=b9cc8!TyLUdwP;yH7C$x<-rRR zjBURWtOqO~_i5DjJHU^>J=L$I?e~M#y`wz9@RLe&jA@2J<%eG?RQbW0pmzx*$-FLs z^@6>~!ZyHGz}{eCyI`&Fbksj?$n}ENTJ##h#=!1~vu^sk9js|QJ&z&l1M3F6DXu5w z8wJ}0d#Z)afHl6WJeVVEkJ^mrEm9BcGK=0iSj}x=9lkKGw*xi|_EGBnVVqTA;aK}_ z`<$WytOpE-F*4a3<9cmii(n75wTJR!rp!tz-qy4^Vc=70IVJA zMtccZ58GhlV3)?3__KhGt0l0+UWJSo_1x5YPkDf&My5^CYXzHqZ)$EJtOu<2edWP3 zEa?q{4T4GCf`@%q@;L=oH(4HZ$MpjC!FjMzu;(%_w?*}UJ56c~S_7Z{KzZ=wxUS@9 z8*B^gF_v-^u&Az`!a6_By6Lxiu(l7St`%al6>Ji0faQ*|n_ObF{Bwoh3hu}N&yAIwpQy$dExr{?QU^j_Fq6+}$Yj z4s$&HIDLx+B<4SCOSIbvzWa&t;NS4s$d{C-9qh!BaIFGv)@L7B-|hB2q*1V0u!)3C z=4S>hxC4HO*U2KXC;3?d*TF0c^Sa?-yI?J|_C8q+L0B7bL9cfh?(h$%_#^9GHn8KL$C@L~#AYwp?ib2~ z?^?<*0=D+&_HlC>YzOS3xSo_@0j%ar<-r%@{X^IqZGN>pc(Fxq8?1Q=V+T5tQMUoh zP{1bMu*`C54JWJ>YzOQS@${tZJz#ZzT^{s7-AGT^FxUjx4P^7tI3{_S z0xNvIJm6k-b}3@*%*#C3@w-xExUf~Q&TpW6mh?`5>5%LzW#?lL5PFZc=+%K82m3^v zH83wNVB^QigKOhV%GV9H4wldpHUzf#&GO(+<9cFq5^UgG<-vR7O!SU|m3`YjPd)~A z4D9T9J#;glTVR{3<-vO_HcQ#j!;th#E!fa^?B(MCu?%)Sbdz=41y=L7b~Xss4|a`3 zZvt%Ip*IIs_IGxhD`4FYb{y;|SYSyniwVm%*rjowiLZ-bb$@TqXERton62!cU`q}* z09O6ou+1Ys;Wa|)XdG+;>|61CN}HGk>-}DNfFpG&UoV3N-!BiA<9Y$>eG{zoAMJDQ z3>G-mV79qQ4OkyoL)@nLr3q{b?A;dD0oJf#U#s+k;bED@EvC0@k)$9{dY3W8_EL#S&O!NriPywE@-whOG`$PwH?N zti!>oizuIiHG&N|SUcE=gY|(;IM^uIjDyX99R;(k85hBp9BdtI)xmbaHZAF~?yC-A zJOIOq?@ablPl(p{ST1K+zm4GIXH*39_-xdL>9^ zx-!oi0~)PU1R3hSCgT0f(=u5_MQ|(GJ0sT3@@#_5t+Z4PIn<=fRGG;gV)D=?|-5$H0!ondqGW zn?AoHSW7VGr|cr+r=}v{Z*7hA77JkH_27jIDuT=6e2#IMr#A4`Llr?MJ{$UyZZFt0 znB0e0jOrku-U!&_MPdD{My#7`8mzRw!n&qj0ILJzQYM++8dw09828#~a~rJdQFgsT zE&4XtxjoXyE+6Jp{s|a2RhvFap+mHV$RQWGPpKVX+Nj=ts zWuIP=+-E$7=9FRmw1Kxi19q`o&R!nnXM^i;@;>nS->XQj*Q5ItW8lqQ6~PSRX0MC% zr94N#Ho&lTVdlBWcCZAt19pED!zhoi4X~G%A@7dbO50aMw$m-r&VZE<44yJ?h55K8B z?O6@*o@C1&wh6ZNCVLs!7RTR*`iyK!-I{a|BY_~o8iM`Dxb84Dk*NZprVyWx4phAE6|xTk2en`!ndzLvo!K8`+OvAYSG z4oSad(2jI4SU{UKcBabjVI6iRKJ5pa{X|9Z64*D&Aq>A}$c%ilBDwaL^zbvqO#KnG z?P5$%*b-RBGOh>l@l4nT*xJ`Cf~Q;3+ojEwir{Uzw9RVRn*Ua6jwd!7!Rl8l-umMtPLzV=CB@Sz=OTLf$VyNck)mh{%a>eeup z#F^;rfNg;_SXdPbRrB{1!4oa40j$Tt+Qb=9iuCwN_1#{uS?GNuV#q+qMm&1c9)=&O zL_t2ve=5B-55v#Lqma}qU@RN@ZbkBpo%pOCY#z)uCus#M{hnQ~2TX@#dc$BX&}%^i z#rFI%<X1y2=NWZK zvH+|fHn$N$F{wYv3(qs^VCV_sdB&da+v}a@8Feu9qz&>sqYg>N^Nczq8P7B7kYsYZ zCWJ}G^Nczq8P7B7kYqg1sDr_z>^#q?gTbVHJkO{@lJPvF4oSxIj5;J4&ok7M+<9WtrZf2ZQy~W)&AaL%+cwWLcKl04a0u}XJ;}>9m<~o>gz-G14oSxIj5;Kl zoM#MSlJPvF4oSxIjDyJMAR;KX*LQiI@dTJ{PB;%%_QQ(c4=sADV8dXySl9{b{iq^& z?oxbR#!c@qB=gBf6zPy;EgshGVM87^>0w7b?3jmbd01&)mrmCMzpJ@qt%n63*5zS? z9yZ}&a~`(hVaGiz%T16lB0tvNHtu1w9=7aZn;w?oO$tZZYdoyU!+4%i zhonDwo>7M+<9S9Ml1$DshA_!^o>7M+<9S9Ml8omWbx1Nf<ia<9S9MlC0gs`aEpZ z!)82e(Zklk7BJS;A+su

X4N3ZH^+yjE%5sO{}m=4LZw|Q8vhv6Y8nX%&)>i3~E zuJ)JZdNd8T3HBl)tSMOnbZh;O-y&ex6_OK}roA*p`Qtas%5@c0LkLhooO*Q{JK1<PcAbUIdTcIx*e2M9BfSjH^kuf}>D7>hA?X*MXVf9dc%D&*B;$ET9g>Xa z8Fff9o@dk{$#|Yoha}^9Mjeuj=NWZKvg)EHx{ml=?T0jaSi6VydDy6j&3M?NhpmIP zqi%VbSLNGlXFFiMU@x>Vo@ZPE3*t=n$Qr=P{ynvSCTq1eum!M^l5~2#U^*myJp#7) z6Z@I1X|Q!L+cjwkj!VjhqZ#8fX!z@H|gshkKV9{ z@jRmr$-MA9qYg>N^Nczq8P7B7kYqg1s6&#~d02~wb$i&5hfRXDp0L;LQI8%Em-RvK zb`(UFVLv{pe!Jz-E3L)7hX1hlm0Bjp=NWa#@`L=R>VfAO zbx1OvXVf9dc%D&*B;$ET9g?j2A)2JyM5Bkbdsv@`je6LOhb?;8x`*v}82{Fa4oSZ> zcvzc<^?KNdhfRCff`_en*tUli9;!>8uJ?KmYxS@m4;%KdDG!_XuvHH`;bCPDbC|7>m3Ej`ZE5d%H005n1RI84V9`73(K`mV2)z!A-j+wN^x;qlL$b}+dYC-8 z#i7^b(Hr!z2@jj|uoVwG?qS(_U21LCti!|lJ#5Uwj(FIThi!P+u7_1$f^#7MiL>2sPqN=Of{lPZ&BEHjRvoMltoCOW z!Kg)V6l@mkCJUPZYuK)^KIdf-OowE@UH7mZ5372lwy4X_@2WpEcvzc<^?KNdhfRCf zf`_en*f!WW{Mm|9CF{1(fb-H0Ru5MExm~XntQV}!VzUSAsDllIWqx7Tn<5KCvTo-+ zY}La~cv#t^bZXi!{I2S~&cj+ftlPteJZ#d#j(XTJ58Lvv(o5ZCuk|oF92u%6>!{14 zH|Sv#9yaG;D;{>-!?KTdm%Zp=%^ue2VFMmE?qRbYw(Mb>9+qizm%YZrnmnw-!}>jJ z%)^d&*pi2Bc-XFoRX@h8}+am4_oxGbr0JCYs0wPg<>YJ0acI1xk?9X z0L%We!us5;Hn0vb-fB;>xsd!B`jfa#DNL#Dx2px1BFTkzm)u4~*N&$u{3fqhUz4>j4e$o@C>8CigLB!KQaAf;UHcd+X_C$cq1Ezo)SY zHUh?5-`TqO?=dqa5Qf3Xi`?(vnQR>lCigq|8_1)u`4mJ@Y%eeT4P@q5_Pp>nkUe0N zaXm?ozk$>tnI3-wsY8EP9Kc^!PU&bTG?M77F)g@JCF_N-|aW&esCc_$1!LBZwm7 z^0{ZXLOq{bRk6rhAfJJp-O7y5Yl;q%W<^orv(2v~eg)pm_+vUU<@_ARpTWm1#1~%~ z=`KLNYmu))UiRyX;Bk0Y_8TPKEqrf<{Jco6@{>)ri!fcb`EJDLEoC#GjgI(j4mqFg zpo3YiA%}dzA)j@~Q*A!X|2pCiTk^l{uv3<7BNhGPx7w7vn5hm6|*fBIFm7f?M4Ts$8YNS3y!f;^kxxj3^qsbo~@6@JYgIw3-^S- zhi{FTJbwTvlk6AK_;0jB_KStLgnzTgkheg-1>3y6V75bFzo^RO)w5F#JM0%tkTV^# z9nRo;59Hj+HSM!sj9cumUmS(J5XD#Re+%E2AeU=`kuLki2IR#=eD;e>NnZUP&WP{p z7mbLYwDa5O7pth3a})VzztBP2QP^MDFSac4)BQsE&DJlfV7S@RUno!g9zIN$*8&~P z{ERr{Qx5sjlw6H_E0A}<|6Kl=?PN0*UzLl$haZjAZ^J3|_Z{f4Z%Y}%hN}B}CS5B@sAm_Fx5Iw+g`RxwO5c_%)cfbI%DXS*Wb zM0^l@;f#FnC*-e8^GWdjTt4_R`EZ=m7xUl^2lCcEzE!Y6urli6W%}s^*a%qB!q^{< zf?Z2?Ta>0e8>WtJsx%+G2l|H1s64IUlLzy`Tgg8f=?Z5)7?NXd+x_xtUM*vdYSZzo z@1}eqB|o;0c2-kzWoHZW4y0SeyV)l>=IWsAtMamq4In;`>zesbkGU#7=OW{XFY`nx zm+}wC+!>2}2=aNz_vSh({siPYsQf57=OSwsJ4=rE=`mN?kuld|N525D#M_Mzl6Ix^l(JL&eJ@{?{KO3wD7gR-Oi zPMwVKL(Jq?VEPeepL3;epGV$ zu>*FvMPu4I9X}q0otL3qDmyBl^kcD*54t1!fz&JenGVYDdwv{7{BK9`m7M*o3*jCz<#EK%1^i0XFod*JG_-``X}AblpXdn z9h4m z?PK)3d~gQxuk7@Td80C|lDFu>;9Zqd$3sY+~Z))p?omJ^o;sR=g(cfIq1uL&F~NPdoIkYXIdF@ zmapuhbbDa=+91Cokq?${400aZ(tfU@46mb*%O0GO?-|H5wR!dT3=BEjRU70_$Gd5V z?P?nG7e;dB*DZd3a6UMZkh5KFL%ug}C_3vMsuEN^cAsKAm44d)N>2ajpzJC+{by@u z>GrYLFKu?je<4uz1L+6!pAJesmt{TBe>#}?q5pI+(q|_QAdm zW_i48zXTB0EaXy$2msew3VlTUZArSN^F_ z$yNQfIOJUp`9Mmpu8(6Wxw1b4`7z}GXULTDLxUO@Qt_3174oG=Vm^d=)_yAs3zS^% zvY#jChaCR~A7##)!g4}B3HfKEd~{1b*w0%p%?JOOkh7oHJvtw}FOn-eWB9%Z`P<-s zl|N-?2J)KA@&Ws`lDn^)h$2DNk199wt%E6Vf$#+E7V&QSkNGY%<<;L3rY|d$9p<|i z^4%!@sa`(<@kcrzs(j3c4k~}{@z-`eN!wNaOxsm*mQM$jo|31>UnOU~=%C}5g@RAiBL0)2bOVvk z;CmnBKaJ$7zp@>5HJkeqDnF}`>!8Z%uHRAUzYdX;<;+}>SAU~8QO*I#UmnF*?I~Rk zD&H*U2IBMfxY;gQ&gv)RgIgoH$~Vh7139lJIzO)ZK~xEbTIAAXd&KBIqOjeQ_gx^h5a79oA$SKWXkzD+?VrR z=e3HC&$SwZ@19e1e})mm3{bC`-@_pGLZf7z8sI(2=r0`%Ci}iz3+iAn+1H*0;NRhv zc{(E*dEp+k4oSUD4e)L-NiTyo)_!F^`16RV3S=2LFVex#>n3ZmGs$O%gO!EGl4DFP zjj#^uwGi);Hsmh-j;r#<{jj~ZJp}pQnr5$U&p^(fs+(=e*R~fC|MwH|$MC)G>hzpz z2J&Xe<^F=v7udG@AipMIhi&^P%EIZz4YDut96u zetHh8{LeY;0OA)TJF31ohn;}@8IfGY=N$GpKyyW?adg#qVUU3TgJBfH~U(_$X)@+Ze+%1sTLVl)Um+{#z8!Ykx$eSUrOvE3< z_jbsWewu;27xH9z*e?emKijb5@<-28%(X@6XXqV;y!90H5k-P(uY3AcZRzog{%D4r z{xaJo{m~0~vOm)wI+*t94;@VTj27Zu$yGhjA0x28H@69-pRcCktNd@J$*`={>5;6C$X6*6)< z<9$5;s{YdBy^_zS>QDKB<##AoZU1pNgOM-*j|_V;Xk$_9`31&P=M@%6{5^N}g_?N}l##@jhyw z%Fd}@2Z9XOc?_q!Hg3E5kUAGjBjF^5Haqd!gb!s7y2oTaO23!3hi6jun5-+gHtvB< z+K{%TY>M72WJ6$bE^<##7}v%Uq{p-Ct6)nOHb%Yc!+B!D=6!s2UHrR?^mI_Z<~Q{W z7suIk(QCvyMTevw&#rHx3^jZ?79wyP4U@`or&I}hpl_q z4plaOpqIkX1bod-HKNOfOKk z3vwNjJ{SaRdVVMVd?4JZ{&M_LfE2$DxEm*K+)?5n+4;e`IJo>swlE8@}A@h*q!s;?!5kL{A>TVIw;0WLfh4G+sdQ%`ss4TQ9-x{xFNAUV zrsAvle|o;F>};jtD>?U%7GXa*&*r>K2Qxp7DY;5FJ>OOH^`2CGB_B%3Rem@w>Y&mM zWL`e&kf--ORQ&Z+e02|VJ0(~COz(TB`00HQRbGyZTkzXqWLDL?if`NZs6rf>cZCHr z%QeD|ACoKpOr_-RbzDntUOj8oXqRlSI+*p>qJ?-j<*7bWp~}hjs)HGSObhXD%4bsY zb{W?ww)JiH-6CNa#FjEBeYaTyyeC?M&*yu_hEf$C^;|n15eea+S}~|HP)F{|RINTgSL0 z_kU^JnESFV?P3psW0dlz8o1bA*p_yn_i77cTk3mRcn=AmO`Dti9)@HcvHuN2?_7+j z*(XGEu5PBs{x|uG@T|+5BGyiJ8f{7R?&G#3{&ch@VUD&W>|||ev@aiw(J$|f%HGei zJKB=8vy=TcKCFh+ICvWS3sMH|FI2q>=a-q!pGW!Zu0cZFU&y{1zcoRnXJ2rYo`+Af z3$Yx#;LWeitG`#yjHz}g<)}upYkpmLkAIIznvGyxV9$V|?A?*wfHwK}f#(ME!C%r` z#nn1Zsrx>#!PnzVHT8-S6FvTY;3GHWgYQspFFnc24A}4+^1&CWcSWSv&GZ(*bV#;s z{(a!)H`;#_xdYY##z)5*=}Gzc_kndt+T`B{)*;DG_V#lusD{KCli3lRDzx2i76U9Dg5J^r+(- zdwtjOrnkEHc6;BP+6R#IIQF(fk8MZglMP5c|Au34Z<>i7$KGME#JW`&$KGi$*}uhS zvmb5Z>nQT_NQ(EE)C0%fc`*5n!8_u0#Ibh^>;{V-$KKxI@VrjKW(U|5*tr%xj=e|0 z>MV@c@pZ6QlHC^1i{m;jWjNW`+xC`x^4X~3dyc(RV6S0%AC1y$XT9(`UbxY&$Fa8? zOwP(6u6do~*gFm;=LS9(*_8CS#@GduHOZcy)Ze`sdufWnX!GJ1j=ef08TWQ|NHXs2 z>X2lV+xiN}`XXK(H>LLU$KmD-eH!334xZePqHY&n3t(rX534k#PmHrmQ+EijW25$a z36o$gw}g8=_-xk4QG6W)lXGPWb`0NV!3tC{81u8m?_n@}5S68jg-Y{o=CuxN0d}8+ z&xT#8=N5+^)9kjhVTx&&!RC9iB3?DO+OL((V9j7m!^lsOdYyQ=_JKK0jY97!7Cnwr zt6;Q|w8?R53#=I#H<-lbI8`^6@{QzW6HEuC$8Ty}%)nO9=pl7(kYZ!L%5kb6HZMn; zPNv6kYW5xBZ*unZq%Js4>0qQM%rQq4=2&kCyEo&MB`@L^j#D}q`4o1#>y4Am5s$%V zZ$hGmKP5emQ|<3e_ZhZ>8PAx)Ibt{TzJ{_GHUsK8#wqb9$En_Th2!v7qw!So;uxny zkN2Q-FnlKLKE4Mfd6~ASCye)?=1~UOi@qyfhBdG)u*AJG@yj+?%WdIVJr>4j^SlS8 zgHb-wbKHXx=C}vd&U)za*c`Sq(VMa}NpIfH+RMVsC--(oQQmieg+-OU#d>_Nes}tJ zbuExLL;i$B{4RXgL6Q&mf;pb)V9Lj|5bvgZ#vxyTdwYMX4 zVwuZMwKAmNM1h_K3|RrDBlQUUb7z#%b#G(>mr!= z^r|SYQctsBTVUU0ITCuDcP~!c=j)q{8-`>Za^AfLy+hzho4ii#g8g2cNnSYb?)>BM zH>I?#$|rTmd3VQ0?dxaGyGOv}cSd`9;up@lx4;A%4)V6HZ^3s(48 z_*;i-;=bm*yBqAah-3Ig%E$eIwV8ZSYRTux=G|M+vz>|i-?Bg8n0HH?_@A10*L^&7 zA4A$p>N+JArOrli-mQbt=B55P@75v7T=Q;@znpguAum_qJ^QSvz0A?vsf>A>x2Mmf zP>*9?_73|xfa6FNm~AhL<46nG{iu(ZIUaHxIRe&XVH`&`zzP<|apVM8VxLj!cN45^ z)}Bv}BQ;>Jve@J}G6q&()h76DZ|~W~DEH;lq8H`U!o)Akrw+-yoNhkZc6BgqmW9IPdb0(7dK*}H zdCHtho!IPCk9DGhnKs#Pv#d;y{Zt1dFVf~V0d`RCI=m~!5o&Lrt@ye0oQ>lf`>76w z&1s6I{P@rWUEBS$PO!qCrp~EKI~cIrmAuL%EKJl$QyAB!u6@>JyUl*)a}%r?c{vZC zQ{~6CyASLsh?8B4`dkC`YQW}?rq2FJ8JfU!F!Cvk>(Wi=9mjiiBeK~|oBfcjd_J7d z);=*d@8*5qs`-5IYsAYo$Jr6E_Ai9b*kQuP+4@0sZcnxy3PquAW`{Xr92g9cLlh+_u8{{=8 zvk*Qvga(W{;x(ui?5`<)dAyEz4LSiPXDr?rF=@M;%j#g{Mb57B8l;24hAC$M&7fWA zU~uVT^j*=;rJSif7co$w>ff%{%`^w>OwuHuu=6?QnRz;D=iRRH94Zo2_SF7cy%yqK z$<=zlB_;2cG%5D=krAxvY;z;_ktql31RMBL_)It^pxT0rE9@i7U|*$pkF~S>oTrU_ zIUoFh?CnuokUDW(>qO7dM?`NEwno0g+rX5HBl{6gJIMHMO)xogYPMiI9CV6qJ zv&1H^aWg32U%`g5DQ!aX!fRarNf2I}r!i0KXFgeu0i>7s-BOW^eR~z`(|9+^Fa2T@G947-w~BW9 zhHZFcHGCe}=OUj*zA4g4VK8*XZnK9`#plz)cf#iqF`_Y7qfa}*62GaHGCJCZF#2>D zdI8Pd8I?nrV_XQdPZyyl_lv(B*K=IgyQxQ?ZbPq+>EUILrSz!|hR-A~j&VWi*D)@% zGd;(+AobuF7lb*+1<4D?h3>x%%l?CS**PvufR*CiD4*nI1G1^Vv+s57g6WVfJNI#q zK+m>+)(E!v_xWHD%0_xp2JYiFeK&jtERC!7BK5~}UOE`*i5~ZH=e6E;ynHjX`MvNy zD-9TPM4q3}!LTVlTL&A4o{Xi1C+Rta_=P&YHt({@Hm`$`o|LZ>z_sRaj3ZKZN1K;2 zFsa@{9#)PvNKqaK7g>Op+XdT{j>M?Dl-M~-@svY$ph zh)qX5G%!6!JxCcGtM7cVI1eD*6|!tyelSiLzx?JoY%q7Tcnuf zaID|Dg#r881=Sf0yW$&1yO6r*MEu2n4F6V#C`(?8Oz&jvg3%d_^rZZbb|K8sE`)6= zb4i>1Qg*xFqzsOBA!Ts13-JpR^7(TcevxP3Goo=Vqd!|W?E9$nrw)c+y0t$SpqFF2 zxG=iT$v%@~yo=h!oHmO0q}>%e6W<)SGx1HPJv+U}YM{3PSB5Duq7o|d#7Cvd1}lH?T@A6pW5HOTlrV_7@|$8I_EdFPsui2{4suiLO85`RpQUkOtDY-M-8sgPBJ~_?x}D51CX3!Cc*9mcxDoH!$3*D`)XN}$N5KkY{BEo{ zPc|kmL9f)J=V;SXKF76M+7PeRE3jE%vB@^Q4)!qm^QrMNuuZT0Bp=)n*OT(G@eckp z_4@%yZx?I{?3c6&-LUMEPp-+LHPRj{(q~+gE&PXLi~#qIkJD(qmid+QHv)VtU_<=fyGaQ~5+0e06lY2ZouS_*@ap)LeJ(NwHVl^Bf980-f>-0+;dQh0$$A_a z)^@kR7r||N-rT?F-c6m|XkdP7X&?+nIg3)qko$b+(xdMNke+QW=I~v>GSYVq|Bc_{ zAy3)+M`aY>k<)k6_k`E8$3{Hz0q}2{U-1F+t3%QUj{J&$9Caxrkwy6V_hNdC4=^1|eO zej#Tt>zHM5_(j_Hy=lXX$Y85QEKl(s6FtW@Mas_k$prKsW6|R^MTew69oG~|&#{*vjPny6k~TLy zY}dm$KhYs+lk*cDl8k%CIvA{-?SFwv_$u9P$d@3$G9f>m-~W~73+jA8=m%GO zT1UL|6X~%%?LaQqAj9u1kT(VczwKw1pW2>C=Bz@{#ysK`R+Q9PGrqd+ZE()f z2E7MT1utE}tZVj*J}~(m?alEyz{#!!v(Rg#IlN4p_h#O_0h@QmZOU~b)h{Gbb$xNn zIpiABfp({Z$|t`mJ&y4+m8m(7=#6>wWX^GRIHu8D*kR~T_KPa83n<=WQU=aB8o|C1 zXOiA7ShlJVtdrdq)q~V6=NubgZ;$JVP2Ze@$@}IN)8`a|r^ancdTdK4z@+cch*3Va zrLuDi>UR(ykMil&b#jy)4H2C)zJL4I{Y-h%IQkjvQzqi=RWz6tqWUshul+ivDO zb4*lY%^2ljP|ZZepMk6f@$aCo#lDg+K)zfZ_75Z7Rc!?C%8s(Xh405L@w2e2gBhP~ zxAgvL`yA7CFyp7kbd^tz={lJ4ha7T_={lJ4Ii}YkKUIL{SkJbrgNm=xU5C6G@!7u3 z_#D%9FynJf??C)~B7SXh4jf+Fc)qyDV!s3OA;?=2c2Z|7!u{$IhyAIPT$Sr+O0Md6 zB_&t!Hy!d_hdlk8Ze^#QZ7d9?-&!2<^l!SAo%C{9g`emY4lj z2QxnV?J(juCE};&Vk%uF*!T6@HN=;_BB@_xhyC`1MV{`rDxbeQ z{Wfg>ss5(q>3*x^ze&I4*q!=~YuGPVQ|T)IY&qorbI)Q>>GD|&I+*Q{&tlNQl&7D? zpzQEj3_6(c`78zTl zDYxA9KiO9P)*fT$Oh-Q-k6fBblV*A9*2A=C0F^JaL8vJ@+F6S-67w0$jf+BISgjK*E;0Q4ta+|-sg~y zIOJ0f`B8^_#UbBx$afv`s)O1Kd+on06eahpN*|cs1K~WW1M+9%UC*C5cV_Ud$5f0k zO;rKy)N9rN?;=)A=Hs0nmYQcNy&`Qo*7m|?!CiX^%l7m{Z_~q0W1m-SI@b09%g~XW z-xz*z+)t1-^O#5PcjSJ8l&>+lu2AKZHsQFRAU;dYvy6IoJWE9UGGk9q*vZbI>#CQe zjP!QwHYJ~_^^u|1kesU+tj)uEJ#56z#MjdvmYQc7d2u{TM9Q~qw<*l=ED>S!rEi?* zeh}vRXv5i0Mf)#O296WU7ZlVpd;cTOI8O8z3)bKLbDWrTFpd+hv4G>mBJ>`Q_iV|v z`W%Fmf#XEsP{I0q>rJpGFxksKBd*7Bq66#@ZQ`W|Q1*AO#|FVZ&a&?@DLcoB;ziio zp~@bUyl|XY0sDl7ahw>a4ex;_^c>@a*t|F6#Poyh_fB__mpKQ!SN9#?b13-?Tp2?+ zPAnq5yO3`7U{nv{PmUAg4++=AS4B+9ej4M1j3Mi=xdfXXtcU9(o5DCwRM!=P8_8b2 z$7=AM(vnLqXk#OXyXJ zAqurkep0``cRUYX>X*;P8-q>Tv$%V~X24{RP7EUhVfjYv=}FyBd)R`9@p2abq9Cdadp?^7TLXKfg{^{> zKFZ!+PJk7`Y;{zI^-2?%t&ZxFYZ)V-T#vOv?;=ZHy6t+>UWV+fo9%ki&ctU&J?xl= zZFyK}a*bk?uhzo?59{)dQBeI;bHw?Gf1z_lHQm{?}&#jfvvzM=gg8t zb$tlfk2b)@8VlC5*1KR+U{A5+r5X<&I}T=h{#YY~+hDYBq$ho|9jxpz1@(6oMxtw+ zus*N}uq!QkqhM=b{c$GO>KU-s$J)!V2-XQEb35po*T!|Q0kHQ{JR0Ri^1TCAc3F7d zBB57xKa7!JvY(t_4PZK`vh$mI&R?6IN!c08H^+9(c^zwU@k=L-hQY{-{C3T;7C)iq zFcVr4@1`#6l);u)&W(zA^}{z~csJ^PSlbOC-vyWR=I@RBybElssi6Me;V0v45Ul=j zh2UFwH|$C|eR-Wj{LJMA^*3U_uxFEbUBPPs?28y1vi}&dIdqeZubgB>yne$vk#^My zJsk|c3UkznFvtFgTqn8i(ZR4O^}MVB-VHX+`k)Vv+xeoduTp*pgP||!*4mlmmnyb4 zqJ5WXv5#@h(5nM`7T&WzXw&oK$alkFhsf|U`!ap!st@{Z26`-SQcu>5U;)|BqV%L) ziSM3hpF?dTeghbWiImL@{Bi_qoXaeXYsO~iRazL=jO}2y`4!iU-45p1TN0mf&Dak; zTiLm090RkBW2t-Z;yCqOj}7SQp!~^iYVOQ6<1B2x3lhWE4NRYF#^4(G40Fuv{-^4? z9i}<9ize_5_$_h05nbNHYkNu|I0A=fOP`j~9RS~croAlVU^*E275~hFRXxjo7HQd| zw`pfZmLtPyco>ZIq|emYndmjyndGwrtP%OV6?U_CMdcUP54H%_NcMw>iOtkKJjsx% zt0U0chMw)(xCB;sc0oN8?q`urDZ>Vs4$1QEf~`YOelLCIb-JEJuUaB2O+!!e+2~>I z9@b}P;+Ihmo3S&=%OY6Ea|!{k9ogqaWsos}_wcgMEd<;%6p4_he zE#(-s>q=eB*qQik5v&6?UyGEo&x~veTL)VKdllKsA|^I>>^8gUo76o#DU6yIHQ3i( zl3p8F^9u{Xi0q=q$;+ypiB0Nwul1o(!>0J9Sto{fgEcUpopvUAj(L*k z@mk;U3j4gB*ZN+tD!eD_h}Zfduz9j8Bfm)5HzCu($fx9m*Loe2jMsV{lFV@*No+dq zBMEa{>xJ=JKhbBOS2^~F#b>lpg%C1jlKl^y8D|MU&_hokWv-_1EL_lKJY3+kC#?~Ck8nxkMk7;P<}%^45l z{_qjld;{WT?}%)Q9`}cJNZRE7untM)*dLZTsC|F9?7%SmA>|ii%Ccd%$ZMhfTEFMJ zF(@>@-qHTShQQikN7-co)I5mibymRsJkF$DZGes5V4qj+f*k>qXMjLAtSdFw#kFwm z4Taz=B$NG02 zi?I1C+WcIUp5)~;)=pxR5|`8p&QAu_A3U_{O@{x7+&z$GZMBllIvOHVO7HysI+M z!D{b>v61W1G^aS$@DfM8%Q(pSqA-m3e2|tc8qnB zPmXo-(35@y`{o>hW8D^5qU=%zj&;@VwCi!KYXh_CajYA3FphOIV74-BfGvXA#w?C? zYhc$~e8#cPbq(NHS3h0|ULV(!_Q|nM2UQRJrq-Ao>yAM05F|z&Nj-3^TLEjcFphQA z?+WLfG-vc_j&(X1>4~p7*6EOB9P8R)vkMW7yoeshx>>OO@K5%&@xH>bZtb>$`g_ha zuJR&!9P3)%o$AxlUO3i`gRy-Z=?UXlSDdilL*`hgL$VAU>vTvm$5xhlz><4|978zPtvU2K)|~)L{QgbyG7MIDPik%>ZHZ&u6qx*OnFTfKonzfP z*x3}1#OsJ--3c&hpQ8~IU!MT$d#}ChWtb0+fF<%NdUaqkV1LN;5_xF>tA1Z0cmdgD zl%ABY8%zhK$8YNTJ_I%hJ=pcm*2g8z)7fJ6J*dmy%ZnwbJz^;qyN%>0c z`zm6y7OZa4eti$X0x;WNI?sA{fW5+!-k>MF39v=z$?vtH8`itzbB;FOZ%=OptQXAY z&*NaDU^c&Gv9B@>#%9avNS7Rm=VckJd8!Z$ksXb*O|W^*7UL{a3WYEj?NiEE1J?MV(B?`)4?4Cv z1Lvy6&>r6mn{ynF>9+tc9Skmh<9NJ{G;!P8tP5c*w+@D$md1i zfavdmswNrz-gyw|Qzx84h`a^gM=Wyoi*d;Jem_@~_?%16S>$7oAA|f%yqorC@O>R} z8JCRwEI@t&@L-Hm;5&- z+gWI*%^~k`$cG&A35Pt@FT!+}Eb(3SIyW8OvzBtI-|5t&e2srx2(B{9>C(6PkNP?& zzYdqU^v98ov~9!B)SrbsS-)&oI+*pvcBO+UXS-U2on(6$gZu>Km*QR3W4p86mrbUh zX~X<&7W1ig%=|Tfv=DqWvO8T;h0o022IOZ&^1XK70Q(P3$eF)wOZ*wgyAYo?&Hli4 z-w%1xUu^d}D8KYed)Z*Y1Z9zbDF1 zyX2qkegpD{M{?y)w)?V~bbYTwUITfuooz#|gYu8EQ-<-e3Gojl?AJox1$ol{&5-w7 z?DKjs26?jmaSb_Ti9Z6l4rYF)Qu1MGS4UHFmH!ooeA6LMT@S)>glouohDX+nS3m68_7Xb5roa;G9Jvk; zfGvPsf%oiMH0KjG4w(+(Pp10`ZB9X6 zN83g_<9NCRc`+epy>CL!@l(flX2_a$#-2y#%F(I@QoV-pDzTrBTjZFYIoA-IBpc@Q~RhzS6wn41~aeq zN|chfSmZ9dvwt7{?!{=kw7UlRUYkC}=VOKGN*=?E>M_!_$H_5Lhom0mKHs|Z=-cky zv&7HYGoPvNO~^RG^ajDI@UGHR1!q3lrpLfuO;!=8D$)*2&mi0F+9FvP+PoUlt;(CrTS@Oa$ zxf^=&9J;5)^*AQaY4-d$bBxJilVft`p3vqi<9fSfVKDqDdfYE>hu$^d**C@YxL>YA zQqQqpE;c#WnS{;DY4aU%o7^wgA!&04Y!!M}QSZZXy+yFI zA(wQ12$Nh30l6oT^cC!8Qx{^w3A3NE8xhpT+FW14y zr}Sy=m+O#Zj(dZm$Nh303_WQR!*(Wmj(dZm$Nh30k~X29HPoQR?ISIL@`;HMqZ0?MJgtEB3DK%aC&o5XP4|JIBGA zTxGy(s*xf?{R0eOwyY?rqLkzy_-jTB^)qTdFM15J> z5U+cyU~=825oJ^uuY0>-wsi{YyRNb_C{hJ4Q;*lZR36*DHG_al(Y{Tjm#>wVcGAA|fj?gRe#MhA4k4kPju~%%2WYZ|FC!eDs}Lsh-i9 z$j2_^SHXz(hf9C$yh?TUF`?g9U8&A;7;=_l81gE^E%dab0!#~#E#iul(i;>&n?er52yNUr?A@w6NAz32ZH#cv!>7a;#` z6kqw1;cvtyX*E8;+4PQ_hTolPw{<()X zQ>+Y_j*8ze`QaW~?}e4>@1RP$<8r;^^-~AsPi2Sm%KnQggUZN`iqAc?k=jb*8AU2S z_t4fMzXY~bx+*^R(8}s6gTcs7d*)QG6R|vn6-~Wnyrv#nnLGm$T_=u%eHC#;C9H7j zu^rDotTK2p^Y@?8wWt47@=~~@QtgqJJS$p{x%%P&;?^^L@o`an&+pTa@2yFdyan=Q z$faF}@m+Q|tEy7ZNT=PhbE=HF%bwl#bF0)nU?U&wmEOcX7XkMQ zJ{IFoIO ze5Cp{{MTPvRKM5ij+o>HYF@vbfZnA{Z!pr6ywESf!J_r-0n63pU_jpVdZBj_;w1gT z^v1yC-pYI8d0~1-z+_M4{c*;6C_A&L_EJ8y$6Re^6meg~^iMJlHQ%pj9p8E(AB*$@ z8TVT7eH-$NBY82ycEI3klQm^U^&E$py?mdFUN&D$w&keK+Q9CQbd&z24|~DHzsy+Z z0H#MD>Y()aO`T6=Th_r~k{;XgaoChO2O}B%ify@}P*i`zXpaR}n$(eFPfZx-J~||Aj(XUPhb?*-_tbPq zrsvpGlYDYdO^2kOV^2-=PIlhjWpf1S70)ULzeWU=o(vY!&Q7+c=CbM7Qxlup_VNki zo?5Zee!bwHS~HlO2VlZRpXQ!gJD7|~3C2COL9i;SB-pSBDAbIf)b-u5rzXBW*`C^% zqYT_r(?R8h-&A@$gQ|nU#4kL9s)NBKFFb>)Lz12B45~}daRycL!ZWBkB-7&=R2`Cx zXHa!WvXh-bJpzAT31y`x?NiFmGpJi&1qV}*HVj7DC7+FUCjM-xAD_yW%{#N!z2?81p;%Jq$@7Ip%oc2hQ=@Ve_$g&(6o^qMYODkhHn10p62r6S7fl zb181qHOH%g4(E7_(35999HSmPOWA>T{7=6%d*(=;9yZ`%;|`XrPo~dnX45%E^>=|d zewQ5(b;=v?+63F%3k#fkp~wH_ka2EM?Sa)pf9AYmP{ey!t@paEz?6h!{oI?j;<9;f z+KS7jtF5pu7*4kjDeZK-{r`er9P1?M>s%)-RTq=LwG{R{vQ7$Ew;PT=N%sG*lT_m<`JY-RS$rmW;W|l&WIy6MNe6>TK7WhrB*`b&NjeyL5hhck5GL7gah)W7 zajcVs-N)-BDf?-xlSJ=i>m--2xlYm{>Fay5PO{h(pPg)-)OG*xeh>{9YXGj3Cc!SG zIKdq2B=O5>tdk_4r?E~Fy+y|wir4pb58Lsusxw(&6_Rz-;9+eZ)@x@{h7mgxe@=VY zf}M%YH9HfV+jiEFT&Hj?!j}%>i|{-X*BCmO@)j+`yOOIlNtZ)Dkdmu=vSSYUj6=R) zk+Tgj{4UMy7tp8V866wZT2|`o-mH1HV3YME{xHUt}1ChKq?tuu~@!TJ|kLUK1-f5gGR%4s}euXf{b2ucu)3^sBHcw-2FX=hX6$^8m zE0**eb9-TqxxLst**y>$)S~{*Z)#8PKE4McdHF5Q?Ipe6;@n=+<8wH4P~#`Rse9I^ zF}Ihxb#O7~kau2C3^;F5@w;V?#Q9CJSTxS>s^3vDUMu83VSLto*?~E3NpWt%{qm+m zMfGA@;e;vuWTd%^g7ghw#I~76q-4(&~uPcJFdn$s3l6=s3zkE<#o(~%Esya6x zj92G_75rX5dng}F;#GBVKB&j51+VT$<%6}$@Z6L|GE=Y!H99~ALwx-uV> zU6l`N@oL6v@X4@;*D_ukc#U0~4`%RMz-tw+ExdN0k`GR_!NyZz1Ft5$+VSeeYZ$Ld zyjHG*-m~+;+=~$(ulio3jn^z*OL(=v8R^}GJl~oRI&MRH@5u*?pThfR^FiA>bo2O~ zYXQ&uIR}4_<^F|W7Jrv>2e06=LePoV;MI6e7hZLE7IEKO@N8W?k8Tdnr0K@79Ez^iEszw^7aGHAKHGFbU!WzhSL z^8=m*JdQJ6_aGF9D}qt@{s{cOiZWzxhaZu*G32Qg>Gr~2250nm&P&x;X|QtV!Jzwl zcOO3S<6Yd=9L8($aAxCIhc|xstHZ^^|9!aq>i>r9zYhmlybm9MUMXI9$7jYV-1Do$ zbHoe;o=AIp1J$*=!@?@OuLJZ!*ABFC=J-JNAX}SzK@{&z4NO-Z^p;N5BufS zhoA9(Uj5pay#7_M#`oVSa2ZE?e1FC@Pkh0t*eS)24B79g$JagK`yB^c4zHB89Inf^ z9Bw+hHJ+^hd^_u-nR z-NTEI**!ds_u9wp9v;1n?VIIbP`*gMli!<=wio($c>A!_#|hP5&; zEa&3O@w=Q?R0f$0>-i*cr0)H3j=mNB@s^guOYdkoynxqFZ)@3W|48q36D^0?&a3|f zY2JP?Xu#E?h*uR}S;#g%QyFyPa|>SepQ{Y!=kQyteFuZ=VT@&nKa2MU$clJP;`4M{ zY4F)EfBO4uW7{PMg8|s6{^X&c2k#wtwcxc2xi3AP&L-k+!|o9Y?8wa+;iOmrR$TJf5Oyc@h3udTs@!SUB03<@Yi)&Dsd z6p^=$PaTx9j559JE)43PSQ@Ot?h0Pjh*!j`^PA@f?cX^+=si{%^y4-6?L)!Jng0)a zZvz%pwKsfkW(F8=P(Vaf)R|Ef4GRbn4V^tBC>9zjDVil9qgbS?=x_f2wf6e@ zuf4wZ+I#kd$Q6XSwho%#rp$00B8e*y^&-9-Exzk3z6UM7*DJo)EWW2JzK1Qo(<#1N zEWRf!z7s3Hf4yW~uzZL#3XqAL{AArkqs&9dO5HCZ-zZT&*f>HfSHKZ)3Z1%gLKSg$ z!bVst(jjcIkdT9(iA+OAQU_`1vH*89QV)S3fs-~M&Z$%-Rn;@VL@#74;QTHE(L^_& z)XSpniuT&p#{XARGlurVpO7N1kfI$5sf=MrF)j(WGDacAcqQCo>=IJ6F(JivtdL?Z z6S9Lxin&U-mG8zQJ9^xmJTlNDm1n#-9_(>5)hh9n^&9@m_v((c;UazI zS!blO{zUfh_=kI>@_jn|mG8+Rdwcx#9%=AMqeu4f$i5yK;gS73vcE@0dgK6)9O#kC zyM)Lm%Htm7k;>j7{8$&cQiC-^6o0g!%u`0h{W@zvv+b2drJ2P%SS+uJ1$)-r$UYgJ8}n9!6B#xCy4ms zudRH~E=V@D>23Q=&FnX&tW8$-;Zi*^4VmuIGdyw{G81wj7xEwBVGvchA8O`B0V(HyW0Q1c7=G#M?Aesm8PU8 zQ5%V9V%J6GH3&`YgQ&dP>cz_|M{#@VPJ<5^+SWisNlk9Wn@CQJ>xLy~gD)Vnj;rn)+|1 zuavp%e5wEJ`cwL9|8C^gekS|}QEuf-{K@~%p{{i)XM*x7XTpD!Vj0zUl_soJ&P02? zdHE}6;!54Nh1Ogh&r{1PPv~ClXTsQiCc>_q32{`^u(zkCg;a$kVo@Y*%Uj9o+T&^^ z&Gwr5vn%M&XF{YeYD%2RHmM4u_0tkaUnx`D8E%vRW%?na=ERw%e0sI+PiI2cekT6p z|L0KGy8d(~Lc}|cl%CLDM=D)=4YvDv>6A0ker8lbo-?Rv*QEA%Do^P4(Z@@2k5@lP zqm+92k^xKy-pcZv^6&?`+i)5OsU z!f&ETd7?;QqR29RGC}T|NVHa$Ru$qM?rYRWb%+Z{=$P2a5||R47UHE+YrK7YwSN8` zbOCI5ANf|)iTfT=l@uycl-5+iFT=CO$@3+nONW2;zyAKJfxl|t z|7$g%OeSrGp6DL?@^3OKW219IZ)FauMT*hr5K_!RRY)-w?Ldn0$Bqp__g_W3?(k`{>#>p~ z@>1;bQ+5U65KOe~yj}|a5(_Fp0yrRdAlcr00FX@u_$I}Oz=(q$qDUD{*rl+K(XG}}P zDfT+z{H}fu!{z$0U#m&5_f4?|bpPG%kv9_m)v?IlqfAL1I(QXxqgK}GR7;R4{{B)P zG81wj7t$dEra@e%PTmO}J8Gf>1AP($0@SJar9nOvz#>=-g|Hl0rn>t21iK=AJG-KS zf_#PhYQp_ATD{iWFGSgB)k+cAi=ARofvNR(FI4^im5;YM*= z@z>w%KGysn!pH%X$Zxo0e}05i)!$Fjm-tG>lr{VrKRFSm!E#s+8$siv)r#@4aFw5& z_Z<6P@9=Ea3P1S}M6IN4;BG}Ofv8D5PqdTgpq}@W)6f^AM-eY$xu2YmTtrw=?o9Mt z$XV?tr)Mp=e}R6+!uj*9a|-ev*3Vx!XU^<7vxZ3{)9%to-x8xp_osNQL<$ohH~4GY zZ@R&u|52||Sp`{ndh7i8bLZ=4&(Y6YXkBQXzF_vOIaztb^b4jxU@gd+u6XKaF3ijG z{~yi!KP6_KI5Bxb`t-@>3F9Ioa`X{71ENIPA{OYg3iNri=UDNQJb}{86U<}(V<>-V za@PDg`kBLsn>UQK^2J9)4*hY)^a4)R%`>FDoay-sW@OEAs|&8E`B}59ZqM0s=DC#_ z3$mxrU*y)aX5^uGijh2FLS)2(8!YQ}tB%gdyMOM?nKAmrM1Ayt|8>mdvC}Q-(zoH~7L62Za;ytxOrJd`$GS*AP(LAg^z=VPnmA@^vQm!hg6Y7It|j+I|9|9X#E)`FRl10+$6)2$B{=nG~)V4b_Lz+dV!D%qUgM{iC~Pma|uD99>U zxPX)4FC}yKqJ%Y^;)M&WBsuee>GQ4gAV2S6jt|q1o2$3x73d$zwQ?@!XFXumTjvmS zRB{IAQaPPUQ);```cLiZTL0wKMKOHW7?GfS#zwncaqY6r+v7n1cZisTc1@ftcN%VG zaBN&`f=DkW{?>#zMe;E?CYH~Hn4v;MkC`|@^rUP1_}vi;@6nH$Gh;4;$BY8~jJeiD zvlkRt=ghF`E$MAlrkML*g-lJpK4{Wh{hYZ4`UMN~^XJY-TK}B-Dj97;HA;RDQR`kBlW z5exqB%mmk+$E(lM)%r+UJQ-zk&culuMx)g~V0~cj{D<4B`l>>^!#%L@nig<<2+qKD zp**?%Z&cS`LHMO8QuS)^31-F z;=4jhc+dBTgx>z0qW^AT{)+ck4g6IDf7QTWHSm9219~YyPRQ*d#m%yq;<7BJ@Ov$$ zy&0{hye#$|>ZxQ~_taVHRG zH{Wh!H(A~>KX>Jq#kW>JS@n50^X2i?qu%>h<=#Penp1t&efnI7B>DKxpDrG~V`^1q z-67-MnQLW9%P#cKl#cKDUXYmWwUWyIVSr?R3SA|eay#%{QOFIDO-H!dCwG)hgSl{< zkK72~!eQ=hX*w_53okY32(SllmF6X<1m3DFnHdz0tywk*2=rJJAo^G1Bx8zL1miipBKoLcT2g zt;IBmWB)#HHhsfZ;>yP@rgs-xOb;)zn6e8jru2M^>6Sc;=>X}6&_2T;9F9}3N07&a z4u_!%_QT1!J!QU0Khi~-fq$4yePI+#g}5k*V^g5kv?f|FFB&MxC;LhAUSu)tLPz`D zPq;&a1LP3S-(EKL598iHIY18N*mvkDchPqiwVK}YNizM6d*||2QxnqXg4q;>egH**7kC8hFzs%OX$0tDH@2vdQP?&B!tb$|E)(YD zREudJY=&i!2jd`;Fumaz_Wwe>^WabTaM*#q2adoaupC~4Jj$D!VKG&R^yl@IDIB^&5)$EdI6zn{GA}MbF3t&%b9o?PG45%rd&=n#z#5(-fsJ#}=l7Hk z(Jz;Cd^M~GpTuO-X#XVBD86&Q0e8--R?{xzLHGyMQ@;Lwk3QB+J?({O@zXxoYAQkQfC|_L>A@D$VPqW`X11D6Ap?-oC9|nB^n+VqIHZ9U z7Qq^L9kxI<9Dt*60#3ni;C0z->HyuKFT{WeGGGQQfFf84rLYtBLJicy8E6F`7iqvP zV1Y^S5IhGPA)K-IQ{>lB2VRoJ6b4K1zXkaoaujkpJP4_b)6XLxM{Y#E4-WLtkhSm& z`tQiFr|DB(7Srv>{>a715y-cYlaaN^JmeGb5`-4FnzkVKg9-f?m|8a4$Rr#qcWZf^VP!{(uk- zV=^ScbXWv0zz+BVet`4BO`a-m(gqo(Lh_PU(>KgB51`v1i8l1jLySdZ=`ZxJp3b(;fVoq$wbyzca#3`0C^F0FG-Ii1+soC;QWjiVW9|K zfVbf9@Duz2JvvxSx53@87*;?jybs?(1E_S=IrN7_xD#^WNmvg%;0ve+?*NNwAdH6x zVIAy%YLIA0-y@qLf%0n?@q8BifxB}@?1CuJGKb}}_WbE)-a~|YJWPdb2;kflAZ6AE zt&FXUyC<1e;$9CsA&@UHe~J7RQfMZ50=^*}vvyQXGhE8Gh4@iJi$cBetIoM$*?1$svgs^VR zF)#xbgAJa7W$+xVf*0XmgzbTR8Fs+m;UdIzCoU|2^-uzzflTenmja}V=-qmV_9N*G zb6>5Ns^-eKHYKK@A*(TKEHchqIPqO*R5K1Jpe!FT}w}xEqS_e*^vw z67DV#12SYlK1>sRINrkA#$sBHdjsr(uiyu`jW%-;sp&=g1Z#i#De_K8hX>&a*akb{ zU!dzv`5+on;2xL{%fNgq>C)~tq1Qu4y~Pv{_rRO*75ol84fGp$4o-m4$eax?!P{^I z&cJJ2fBE*|yn+d4z+89?2J~j$=)&_Re`^}Q5_bu_3sELL&j3)D;NO?LAQs{w7aoD- z@F5(7W(bU+-k7_hk<;KASPzTvD+Gx)ewx0SnZbC%*j34~aAX{;#opGTTnoTuxB%a9 zyc6T#N&5J+r{1;yzE3u_;HT$VCQOh9u?(d1Qc`fxZ)&gX~P0B}oBtKDr(~ zJvl&Lj6NK_?MK(0XFfPM^pFM2up z=Gz10L+GEOFS;W@K8{|Co{}0M*Q5WAzLR?i&q&<5%=@8(!OY1oOEjehWe z`0FDdV9h@Z_Xc&cX)WzE4_!#K5`ZE6)1(R@D7Be zb6&WP*c3@W!2L1&9dum#WI`i)3!H~;!AYj+%sUccz2ODsFp~|y$WL`zyh0KK~#W~^FL+E0BI+V_P@OY1K66@7toa^QI z+hHdpET)~p&Y=NvA=hPx@$BA^ZebDr*Q|*t<%$AZNf_cnqF_bzq0L;UhQ*-@;Ge#rf|J zLm&fY!UD*H$Ke@x5$x3A1|8)@cL;X?X(4F~(m~|L-(9Znku4B)3*#}g;+KJ329dgC z)3eADSj@WT2(k%6qZywF7mXYNxv-e4{z7;HU2_k6X2=~7$olgOAr%#8}#VSjG+t4 ze@*@c_ix}cm_7)-;TDh~74C((uo%|CDe7?t@;f+38iAyB5j}{tgpA&Sd66d_0yC%9PZCa#!R^hx4=_qugn(pud6N$UWd|4NbT>&I0vnrET#*{TH4kFgwx%| zIfa{HBus%4*bm3x91Kik4RRZEfIPiQs!FSp3MUC@>!<$QU2>%LRIk+c0x#*oz}`sdMX^ge zLH3d+%411)31iu@+t^=1e;8hdx8MLc;olH6oa=rV3p3$)cnc20Wf(Yu_6iH&HP{2c zK&Xj61!<5EufRU|4t|4RnKci{a2L#i$6zDugIZd^@5oRy;|n|iufcBk5mMMUxrFRw zAq{u|M#Ff>f;rHM{`D;Kb=U%LFdtPTPr$#yb$37SCr-ypg+ZT*rMqi-BlAlaMRj!< z$(#kFU^>i)^{^AB?&ke;$RFSw=#r=h7y|dhlducE2ESyBsSiwrT(H3#P()dzjo)1; zr;Qz=J=Wsa2+}C75g~&)L5 z8ubXpgt-qUz%Ym-t!HVUW02X94^P7L@Fx5neuUi9E?0-q%onhY@H=2yv&+@YSeuD7 zPWRP|26FFJ4 z75>}h(!ycF%|I?1OPfQ6ao-|?dR*Nh$#m?T%e5N6H5}UxV_7e}gUrXT0zN|j4U&Fy zx%|gjOkE)o%#aF`ArtP0kcX2^4Yo_mLcEjNIu9{;0s7(zS#Y=LC&W=c+Y7y z4dxoPcw>MZ#yAxT?-(WNDB&g+Cz%?N;^k}?k$Z`A0Jasg4+d$poe*VB3X$U(AE1EnpChX#a~(0>OFDvn z8G;$dW55hkAsd#!dMJml;Gb|7d?vEKhS5*}&%$d^3Dr;o&ET8PdEF%!%zz?;Ky9l z%DGqpQd0U@@syw>na4|#MKDp4Mw=xmH5G7=6X2JI91j!FCvtpZI!ux#q>hy)j2$VZ zXQWG$QYTB3(nm{ElQ`~T=jIIQe*BgseFVEclBAvQNYW+zcH-Uv+wt4}rX-bbbGa_M zq_@gblY4;+C@Fz&)g(@M}38sztpKS9rn zBTbSQUsh4G@Yb+>|-iQ9yJ_ys|5UnVW?{DvUA7D$o-KO^+xhSP14l9WljEO9#s zKk=i!Y7rK{E`-n2O1(*cn#e;+VKO6aRbQ!L!G{^%hq^1nZx`$bAB{%x@e2T*>c^?zyDX*X-w3yNk|_dG;9)3* zgV2|D;`)jC^^BNfIlZ*YR{T%mzk@SomIr!58=MNubJcZ!}W4zf?k#fb1x9tdYfK8zt$jc=2)VvmnA39AH2=` z=HuP*b)+ASdppOqq~ZG5j~3$5Z~`WR^dlw zsL!KIgwa9UtXPT&O2*J~9k)U@d*J{a0Vio4N7f4+ z&V$7LT`dGc81#iBPZ{JTt9r^|5QSU3i+531Nq%CcMtPrYH0LT))IDY0OIRPeyEp8{ z?-=-^M{mML;--Oy^C{k!+sv_l!8H61ac^`n^5WZ~Wl0_EWz6xAfuHjpKe_6si>8fW zhaI5**F}@|_U`hX98ZU7Q##2i-ub6YH9yqCCwG{)k8jQgqc3@`r<@29@Aqyc{6_qCz&6+kNh^EGE1&|s3ig9| z)})oXY=+~|72AS9yw|)x#H-jxL{2`EtlS?HbApUp>`#qB4&xer0x}Eo;Zd-G*rRzD zX@kp!0%8T!}ol+hjIiYt}`{Tn0`?FE8`1#H#kK3B9T=`yrg63g-`R{s%OIG z<)gx74L0VWpGygs(;PwaHjrN8IN^^k3zzdphs)<*=HC9eo^s~*203g}PdN=e`W1s5 z_(ixJg4Ba}Z*n>^Eu|;#UJjQxlXe2>%J|txOZSi_n`PfijBUcR$DR zcR`%nMEvXV59eL>@gT!ED5%3`!lvu!Q;>&W?Ml|qa0Cv)aX1DCK)hpGynkA}qk27I zi&xNpIS1z{>wb>!gePGyi1$@TS^eY-97~zuC(k2n0W1Phrb6OB1sNs$rb8LO$-o0c z`5X(ZR!JxG{N!cmOCcSSU^!_%OZfH3ZBR?SH$y%8G>&J$yS8yXcJM4%J~r*-x?GDc zgQ&wQWFCH*u$Jrg3iyWfEJm6w2cwq+ykmptL>k*7iIvH#3CX79~A zwHR~ucJz~nvhEL~o?1ArM@B+4B!GAiSJDvr7WI)1GS`LEU@@$RX70`*ra34Gd&x0M_hEL!K)Paiqb|Z*qXhfY>aQ(J~=OUHoAMq2<p7km%5Q-{Uv$Qn;UF_TbKOvw$V?(6$QC3kFG)y{M}~2I8x2v!OC(+K++`fP z9ep`O(M}_wFX$m0!XWBJY~}YZst6pVlMp*{SX`hF~@$7JONGMglBGH4~X`97X3E}>_Y$ISnUI*wZ`UA~BNqujk6?( z5H>Ht9ZP;46y3XSj^s6%NV&#g0>rVo);*equno}yeHA?(F@U!=hOFClO_>H z)L9|23ZCcr)mK5RdBl3B6n!Ur2FF1>XC$84EoT0x!!6O?FCo{Erl^WL?wMc#p6eF%c#ge(@$8g%-cvmH+4c;& zc!pa%&n=$e70+dh=Xu35>UrcZ&O-rGtWU)?++uWRch-FTj>b01A+8?QAjP^*tO3P! znr@h%EY@g|T=$8!thg>)L%g_~`EEPz<*XS+y2qGr*3*yIa!jl#G(9*s=<$qEgCPz! z0@o0b29c)jawcfa-DMqVi8XEFQBfy>RpKoP z(fB2Xvla!3xY7z3NDcAJBjRR>SW9@}3=`L&g;-WawGvzRx+EWeO;Ube3L?ZJ07t@qE%=a6eCeSwv(fN(x*) znzrbqZS=+^wLZZmb0Jr@gcDa)Uchhe)T%Ni@jEl`?A1K^V~>%isF#iOvo*+WJsE>0 z`pNsrV=($o{2xHR2qz#4_Y!PNI2)T_wtXkYM&@*|!$#N)($2jao&DdY^PAn@Nr*Q2$vYtf&Y4+%$kgRn-ofw>rR{eV z24~;Qc+j8mFOq#AsHM!xJ_6@c{I<#jj-P_UZz(s&kD>by;Cc)hf_xiU45>kvIvv72 z4}HbJB-1U(QMZsTd8|hdzlnK{wxEe-4~9I3;6BUo+$U+{OZ?;$=>Np;E96J871qL& zkPpvC@k{|S4k92Jw&3R??T?UT)A9?_cTkdP2#msi7Si>+%QXkt3%85?e<`1k{FalR zw%wVsbcI|HWsVx`wrv$|U-S=<8d^jZQuN>Eky^P7|8H^cpuR667njiX7{A0m!)lJ% zAQLXro+D$DOn0JBM81!F9Qh&q1X3((L=b(XDpaeifv1i0liT`;=nG;$AdmF>ZeW~b zdNtbtH3>ES*?BpCqma^7@L!={<&Jnvo?m^gPgc0ZW z_c+3`9ePMeZ2blKA-v0R*QeAM`yp@QK92iEq^PqF$OMoQ=xCx&CEqGnZw7icl9fI~ z{cfXvatTvN-xYm*@!hn;Fs&@=Yek4w*@F=EmO|OY+FRJSn>eka9n(+6`S@_C`+SJ8 zC4n^C+Dg1xGMqiz(^f|!0IBEwDR;>skqNlzn)H>-7rg==R2CtO8(!=_6xQ% zXKS^R`PZ{sG@D~>r-Y;Wm$Nm$p0zazeXM_}s@pvsq^*5yzbMCkI$QJeS=&jWAN2pB zgS=6n_O9Ocvv8Y_p4}BfGDh1!l%U_7t@-Ax?K`21WWwCZ98r#adA8=Ov$n%Rzbcup zgxm1>*)6JF!J??5tVLdihjRNlK090T`Pqn{<5vX*+4i4Zr{!a93F6bUYaNQvbz7Ap zdF<1d>TREhw61c0e3iRW{Yg_69`3=L_ zwza31B^lm4>)3KupqOUuZubpWt6+T7w{G~y*jb|5MUg}leC#1UM>~@u| zQ|*s>>)LpO{j9FD&cBNHcUq*nsJ)&tAJmB4%jWeT8?L#^vEL!M5YpTl#yBbH2)M z77pSmX&v#TH3(1q-0h<-@w)a=cH4FB;}}sz`-m8JrF~GA32k{@UDmSk?(`$Gsi4a( z)O)4>c9qq9lc!vw-8eUEv8wEntId|f-o?4P4&fgVdUJNfh_ET3eZjU;TPZO?8WHgV1d?%IEHuRVv>tS{pJ&TBY)_eW)nG zD%%Gwt1|G>+A7?K{A};L6@S}%LfNdcz1vc_thDe&^NyuKD~hXXi}@@(R2)>ewTjpx zzb9L2wzt@xR&sh@`Fv0L+(NEhOEVy9jxtBWBF#Pi{onT*puu~-c1ozPZ|(db{X>PdM}xk9s91xT zcW;YhMawDGC2ipkdk*?+_tmK)3gY{R29yo_#IdZ!{<(g;Z^VLl+r7lk-u94nTf)4e zmgucjo8AvEdoy9Ue}0oX|1piuKjO$IKlnSIXeqh9<)Cjwe!O*U^;7>~dX)zG`tXQS ze3mqSk2ZgkzV6eg=;#9bRQ&_~q5i&>!>TKuNTZMS*7PVIR$N$EP?V%!6|BV_y{_u%Exodn^hFxO1aI%D855EWqtud4 z9h;<&_4kfGP`D?_5UVj5gZ*@&{rhNiDr1sikdM+QOI2RBaFKL%XiLqc7TZ+iJf$d~ z<6E|9i-Qg0TlB?&eD+`4$&lu*^Ro2`hC5rfsNC(W$ZmXkmEMusQqr*{Vt%~gj+P?3 ziV=*HV;Iv?Zug2*ZDTwRuXuXZdB^CM5=~3l+<1e9q&$J-mI~FRFD@BOEu|_cqIZH1 zH=yV%F~eI*`$#GNmcD_t8fj+t{x+Ah=vXI<_Ve{S%hn{A<6DX~qRkC%*;LWNx;lZ0 zT-~GGniH?|s}jlZhf^7FQ$%6LI4pgnn44PY;9@ZSDZWze9HPVmv*x6;`lNF}kj_|MDh=?WqHO;ZMjL9K=#i?jGanVJ4*C}- zFj7{Bb3hc^@HC$ZYF+S$C4O?{SveS6F8Cu#`xaS-s3v&Z1dH%PhV5BWL#L#g~ik0AKSXgI;yhdeW&H9&X^Oob<qb^aEj;K=E8N>TVoGJnHm9z^vCVnVuQa`9>E6V3psz9lLJE(w8jz^uk)|)m)#8pNm3d@7a##BZ%4?QCE zgu0Z<^Ya|}l&*B|%!t^^`Yf#PSi1LqD%f#9rmj7x!n|lq-5?6Mbz@m_WpPZ&EN4;D z=SAr=w{FV5T@nX+Y>h~&EScfd1sjuoQ+yM{g|G2wV40vV*cMDY4mIEZJQx*+OsXHbziUL z!=5RLNbfCD5b^K!#6N7OS8L0L_ndUQr1O93ch@r|)`dMo2fFs1b1^0-oLIlQh`B{I zBzI)wf`p0D#;R{usSN?neSBY&yJlwxskf~)YGa0E_p3;W)UM6Y-&9o`rt9ASHm~jK z!l706)m6``4s`oALo!Itn1|2wbn3K&w4*MHw2SOg(MYWA$QXT4vwUjZQl)goXG3#c z+qKq)o=@>e6X9(CIq1CAls(;Y*@1cn}u7p$8SDQ~PUl#G2r(P&dXo9P7v))?V z^QjBO%~Dd|Q6N{HOFLAMSzD0rEGY7dUgZ@R`hm16%WJ8Z^&=(jqO+m1TzVCY^EYJHt3w zta4ujI1-fWj0fXus?X@OC)#Ep_0pAMemO4YAlvRUjG)RKWSuJJAmxICIVh}`n5P=X zi7@Z9hl$7#bI@?%rsa^QdFUC(Hj!tf`@&;@J5TG}_?k^;bgHw};U~&2@2S=?^F?pa z8?*dG&ii7-wMe+_)%JADCd50|pUI%y6C%7t#`niN)}0}Y2!3Dup6YNcW&vC4-FAU= zr+ZS2xHG;|MaqP$i;59*fHH?_`ga~AlKDX?|C8Q+aV$X11#XF>{?MaGvTsrM(ZzFGHPo&45$Sd}EUvJNQiao!I^1CmnBZNKk zuCk}^HTKLt?WjF{egC;F{^t{?YyNp!=|b1Gw^bf{4z}l0)+^p|;Ph4fXGpx`vo?F; zZ)8sok3BuE*mFMmy8g38vFDxkd?LbxJ;SfEr|X~XF$_NK*e2}x^B82kIlgAc>FdTI z>l$SYdgV&`!PkvJ5hY3)R<(zz>mPZ?Z$8!D zXX{jdu0!+5Q;vIYU{Ck>ni+0mPLv$KrcGGqdF)AP&&PUcuw(Sq_JqbelG^O)awB^# z3|1O#-5-P7#?-Q-*V|L9*mHAxK6Sqh#-56+?D_ZLKaZ(9PC5GAz@C8knrM$b8xya! zC&yz?NP9k3=U_+YtL^cNcLcWCqrH(mr#$vFU$N)&>+N||vFCy)zuWu8f?D^@6J(btnGe@y!Uwb}v$Avv9S>b?&xyf~f;M}8zL7oqJofzkiai^ywh=hG>YJ~O2h~^GW0uyhj#RCmP!Y?vTbIh^jRc-0A`kN4_lJvBva-igWb|8Q zmkNstSEXn+tL`W->l(j&AlK!qB3CKLi&usJQMBKS-Jqw3b}C-gW9_3^9y5Wi(3qtyM;Q?56Ti!yTvC5M6$ZL{+vir;K4z52KMK z_B+kS!$C%4x0%7y4auU`i8RwP(J=B9cUVH#sv-)9*vzMjwd|rKMsBL;wnrs7Mw}|O zOEy_pu`=IaTzwYOU(&0h*$>y_SltAZ5>{ ztl9iz^NEeAKWKC;EDvp0mz@b?MY*9q;?W`1QKt@XI#j-)o-IpfnB5qNciF>3l+b(Z z62Vz5>h%TIW^r(vD&oN*WBtqRIrx?>?!Nw!QhQF_gG1^HhK#RhmMO)%Cv^O71eHP< zk}T{#>4Qt2a*ThnS$KL!JluVdNCNHg?lCi)Ck0E}20A*N;(U!BTzAejX{wh)i>qwZ z;D~ds1CKa-PKn%-2WRCpn_q9<)6ct{8+%9e+r8^fV#k4H4p%dwM-J}k+&sy4Su~7G z9rllMTxdS!PZ44U*WEW{xX3WAOmCe>-ji;>M6s>+53$Z3B6bURo_I=pQBkbV4RvFidEI|%{5KUwns#Y)wed+G&FA+zsqbJBHXrLmCs+q=Wu^pw2*7f#pA_& zsO{QHKikj3r#hm!=KE&beTr^ut~u6hixj%;sN&PBx#sKUEw)`NH-;<=ua3@- z^|m*aXwIgZvSwSHqMvH2+0bk|D}vfeh0m6fT@Fz|r4n8fKGGw7Dpqc`*QKF}spiqO670`n{%_`ER0XLi zXZ4`}j(_Mq_b+plNSm8#?rom1>5#2iiKm=Z>GnQT4BLGs*uAj1O!$jBpY0b8ulsMys4|hwc6`%U7AAApLDr`^fa&ax&GOqdXEz+a_FUQ#ClCjN)v!qi2 zdo~@iZm%}H-o#+S7{Zq3fknFR*5N}&aeb}yJ>rd2;tlem4yw(~4s&yfxp}FVu2K3{ASf}GXZC=fe5zQsMy$Ns9jM!XFWUlQEam}ShDfAJ^I%^O60ZUa^JZ8E*L~n{8 zBC=A#-_l&9@;+Yi^UclGH#e8u+^pNK>ruC}yY2p_10Oh|nzw7~wDeU1I|ks0&<++i z4ZOu}fIEIkQ>1E=MK`Zcv+kx+U&*>UKFc6fAE|6r{P^BN^_J>Z#+!QyRU<{LjE{Mt z2~{nXt%#?k=#r5DjY3S(4f8|8G<;>M*0 z<_vRDAN`&U^-E)l`WPy`mX0q{FD_i6DGKUnFAiK$tj`--G`{1C;=u4RIEu{SMSYB= zZ+~1^sIjjNY7ZptV2$r+{Uoehy_}3fZ;~8GoA8YIup4{98&m7%isADS$Jb3Inx?Wd zaY|dMmSO@$OX4P~_{{2L@M#h=mTF39u($cMCMJbS4XZBO=c1_^_B9<-9S-N0z2MpD*2|d?w@gNsEd85 z%}tf6&Dw+NV*jE@A2Jrhh-ky5O`BDb{zjuW_l$L6I+Z(l^2E|3p-~ zVoo$>t!q5IF;&NQ>vkXE85g$7o^M#vxGrer-x?QRu70xd2X?5}d0nEfaJ+0qTxoTf z2>42H+BbR{8dc@?vCiujb7xa%cduBxSL|qMeqUouYE!@ds+c>P#?KR(lt+ZnP%_^T z`%z_s!m{o8vxBno$Yi!x_3TEDDvvi%Ga~tAapLnGm$9U(^sS8UMs6PCVZ9t|xUFeI zN!4MMH#cD&Lz~3GyX<9!Hlxx)$2K|!i^?Tz-G_0OzQ&m${*IU?rR;Sd#5r#99E|uN z&Qemy%GZw{!HTnGHk`SYQa8V2; z_pN0jw{yX)Jx4T(v0OPvURSkE-z#miWKd(-eQ}`|dd5UG8r9jMDlb-hbz0G?{F_R8 zHAa-h8SZYJr&W3-t=ES$xT>o(-lu7}&rGAipcV&GRQ+;7ML$yYo8K|EioD^djXK6Hb^q=i4Hp`X!IFMJ)wf2;csQ)&_eTBaRsH*@qCc++jgs~pa5>I3 zzPxSIhu+mKjVlgRg*K}k&c+h&#uXnHmYs-uqkC^Mb~H7vc)4)JigP=5oO|iE0jnlU z%YC-qx=N#7?zh$0>=WBnioHvU)u<OY%ACl1jg?e~MdbQp~4~=1&_F)G3~u+i~uV`+a$zej)HhtF)S zTX%U7d;6O;+&>AZ8(me}nddYNZ;HJ2`g5CNy-O!b`<{1^^}beD%(lkP*j+^DC-+{SpYH@6BDJ(Wf&0oMCF4ekr$HqNHC&81F^@G`)KX}it7xQTur(?ZFJp*#PlKUI zRDD~4a^1So?k?XH>wEF$M@5NZ`%0on4^t###JlmO{EAR&TbX9wuuO*g8Y$FBrBIPd zp$sz{MWHB@VMb$5XH14trX;0IKQ`HE~5oNL%B|}DIza$l3cCFhU&y8cs z!3BqT3Wexdw=KSOhA8)e88LS?QU|;L87s#5!ds(x9EwFzYpzivZQElw-H@O%zJ09! z2BYQey~Yx0^oDTD+dGW*!qFQ#Ti#X;(vI%aAyp*`Mm%FF%O?_DzFOR#7uCoe1;g-0 z3m0l3mkD5qY25c41+CjC3Pfovn+|Q-8CbVLDGdb(k(B}%iJ-b@h;10vB-(+nE59M8 zkFblf8H|mr+4?1@Mnyr*)`|1|x=1O;C`>xAAjTkM=&h=&Y$NIQ6AaxN z@e1WJ0<|bMr`ubUza+E~Ta|H7&uX&&KyO`8sxe>oqgjR9EQ|r&A;G1RJL_biY^G*DkwJ@1x?S zUBR_=<=j{+`%U-=lf>FFLH$PO=CV&*`~I!e@h$???GXX$esGNvexe^d(xB_e4eyRT z$=EyblI@`e=0#nA7;uG8)MeWO;S+WFpeKZ`gKduRNxUSE>U1KU?LOhdS}9911U48| z+R#1S4WsL`tPS(54KYde1AGSf8gd$jh7Ro-YY${*w?1;yq-A0_zCT{vzcl}?e(^Uc znzSW>{lZlHrioSGi#Mfpzp!1^*{rI2>83P)RJGYFV%<$@FR!$L7c!*_oxN0N<>HvNhDo0|tJU>2{Tq}k^3h5p*RM5w8pO7MNN~HR(tByl zI)hCX$3ztK@4t?Jt6n5B$bY!9opDg}gSV}_D6csF?e|{QXMU~eOp+^h>1|zv{~O)? zY>mIJZ1{Dl&$>_%e7j0q+y;na-+t~@{m)-(d>h0wp*BBHaKn$k#{BT>0Ny?cC9#r6lfn^#M_fj&b? z3p9aUN`bUV3WWknN-d?J(jw*IixhW3)bj)6C?cNIq@Gd=o`V$;DteMYpcE=hQJ&)I zu2LR?(kFetcj-}4L`8(s-0$oZ@ZS5o_kKS2k7Uo9S+i!%+B0ir)~uPWxHEsuo%z9c zl0Twrfz#vUN*;NNsX-^)3mRgC%r(`?@Pv)>(g`)f?z<*4$p3kJq7k zYj1D(<~*N{YrUHe1Qpl~9X$y6&O6W{;wkIs?ya)3<@TUbJ2RnC`~$n5w9S@ZE0wLz zdRmrjVs5=;$r>-K;Fw#}6zcE2N8HGoCQBZ}WX=6m+tAz5*bB7~8Te$DPSk#NO{W`U zllf;%@e$3FwKctYGOFeszwSSAUYt4ETG@L*rt@JkoJ#meq%a-d^s*nZeeC#TmWkZ5 zmbD!>21LH}LdT`vtT%VEmyzOEp=8*Cv0=}2Tgj9tx;L z`k&i1&{s)sr;G{vvAsRG6Jx_9R8Fqe`DhQ(TB-}YwFi5nWLbf+%_BPwc=#ApY9BLw z1K$I=WsOvJxO#K{aA)bgJNEV_Qzg`~r&rPgS-NobCw*BXRUQBCRsHN{vh>Q1k9%`} zba#BztGW)@_=WnDJ2btpSM^^{`YwsZos>nKF8VP*{mCEN9lhqPUZX5<`sMbnvi68| z*WrzDW-yF1H|<_l3w`_3&#Yr)x7y5OtUP5HX_AM*6!}D7 zxN7lT^S}h!V5!{;l)1a^Klu|Q!n%ZJ8d&q1ORgD)&|2gv#_sec3t-|Ezc-QeURYBR zt9yYFzcWSZ^tX&5hjir0-pD{TN$b5V16qqI7YZ!W7)s{#W+l>$*G(gCkjLm88~>`i z^dB!1I^4oo-@A5ML5uOpih7jYxoJE6_}+AIKcPZSxz9&F>~fvpy{$Bx3TBri7(Y|S zp8idRLmZQ-BxU>$r`QA-eyMz|wLOmi_7p@h)|_k5AG>^byUEag&1Uz)_{R^KYfVftFxhyttRuMBs-Y>4pkC{68qiksBvu8aD{?RWhIRdSZZf3Tak58jhCDz@ z!T;Bdv_*TaS-g9frDvBYtt`!TDWOE^65U~@mvmB7r*c9Ki3$}y=-^vUv3>^~T$>v< zBGKbZVP*{GYp4mhog&Yg^@QP(YZ&~)QW9q|=0~pOzpYDQ`2I=S1c>4eG=-emRDcZ& ztW;o)u~R1<>lE6?*kbV>K9YDXF^Eak=@u~Bf@^FLrgBo-)q17v>LEQ;B6&&}Tjf&Y zvsuEdi)h|0@O>BGI*nADHVprZm5bmV_&IHI%w*)v?;%(Jm%J(W^Ku*hFM0VBp1c;X zHE;Hi3p6iQSIa7B^K)88A9Pr!(!4Fo%Zh_=_7ApBq97@|RwV>qhA(K8)j%Ukg(%oH z)_I7Jri^)mF;}UlFLl{~2D{2ub}|D~QoXl5!S*GvDGdWr`;c{^n9$Y&^4&s?|W(H_v< z>5abv%YuyRVWsxBTjZM4(1yC_kcFu%CSm>TD_zwKWv88x2z z+-QH>dGVgcWIvki`1>_vajiU^af$^B*?2Ad8BH;w_@_V5NL3l$xVG`$J>ToTmwhoC zqApC_?&yp{e=@X3g7}i?bjN)1&z{6j$}|g8scC|binBT98$Y?C$s?<-B^1#-W8;9O zS(s3pdbZTD4ay{TIklO%di5&Yy+AUrmD}HT+z~aG5Gj6WGJ@pmJsJ~;&fG(J=0;Nj zl;%RR=vsng0nyT8GDpnUY-W1coav%8#SstrO!V;S z3ct_i%(K}bifM+#C)cW%%34J$<6`1U6gm{GD|RMp81=ECj@WD1TabLEPDSrmze?Fp z?eRBdCw_8efd63<|A*tiKR3XC$o~WXSM?z7ughNM%myJ^;2$Q9$wNoHZNh6eY8T)? z%6sg4vfM0&Vr-gc2)dRQbnU$SV#Njd6s2WwPwe!v_+!h+P&Cwt3rg#2J!lIChe+6K zew?sp5#Jfk6m-)$+Wkoa-uYxUXz7euW zB0uyb?4@Lt_vOCqzT9U?03srq#f)L4)jzB;b)X|$X;oxEb0-8dd^^i%&#z6vc#3DtYo&*)g!p1 zNG{7%rSK8+52P?> zF%>;!JwZi;J+t?E$a_857L~c42dz-yT@U_q0EP?y@??0Kx;Lb4-9>^T1002i_bLB>cUH zWcR?9z1UPWCRq5JR2IJoK!~tW0$dp;=NNT*&0y<01Khse0~JHL6`wLy1?z>sdKjcY zjIh=NECB1vgw-B$=>ROkUp(Z}0Ava;OMo~Zzzf2Q9^gq3h!a*w07rqz0xtpl69D3c zQAg?SRdKW4Io_f)3#2&p}1RA?_rrYfaMNRbjp&> zwnvEd5S(JF)b|K69)bWS_6QR_K)k7PLXR-PLtwJ0a(s_4UIJW`OqJt$glGv6<52F< zD&<9Ctf#&vQ`P%f!Wa)=G*yo75k`9m8X=Zjg4V;H!Bjb_M~Ltcj5Sq`>=8zKfEW<; zuTnlOgn8K2n<_Oug2q$YL{sJP9$~nLAb?>#LZ}4r6HJxr9zpE^#+%ltdpfyCZgP(b zK|N=@OJwOa0bI1HS9v=`@RuUEai+?lJ;G2=hA30-+1s_kU@6Hp*3>KB{!Q@pK#`_S z&i^JCAb5LV4)sV8l%5)nF;#Ivf?NVP0E$%t;{iqkZNAVio{=*xqp5==Hy>Gk(J z(gM2YCuOJGKd6%LASL4bFS9A)>jQ{*g~l(VM71e?d#kymOPWfA;a@j~85<{$fR)!W0tqaRzWiYy8=%?f98zShGBAG4#^Iyvk*z`2} zL4hJWV%`549k_6DOIMiw6{J@Em2DMNE8*Fq2oRb`hQu_fH+0X6S~X7b}~UY5iU4O0TW|$V_3vl}i-K zK@1y`p2D!AidGP@D#=+P{qVi{FZhFM#T*9AsiPV3!{`C_xeuewBf2MqfZ|HUA~jni zYhGF;@53)c;|=$W(UUm;FDmG^7*o3ciq$OfdGTJFNyGt|$C$JjsVaJLLI~YnWJ(>s zTBmq$?ow}zRd;EONs1}Hlg5dOb}yPuD`kri)9wCC6nxkua|C1q(~dPtLQTC5e)1IT zZ<{`oS|f#3c&z5D~RbV$6d@wie(}kv+Ra!Ko)9 zLG>MYGW&_FGWWRKJV>l?QrKI}Jw~5CqEi7Q2u{yAlNhXW&5W2)e1kokd&n&r`V_K? zFWiumM$C&gS9jeP(hiyGB%+%y7Ri1nERv}=T({n#y+Zxn4{5i$)0Ird!XJ{qbyIQu zM&mPlujk@eqKD;-vwdmTDUy0p9~I4YDd&c}$tN%)vN}(95%nlVkrIz_^5#NTX8Cs~!YOk6O;N>fm*xJQ zK?mdiGdHcEQy0yo*A6j1)~(YGE)RL)jG`U(yW&1=PA7(M^6&1MUqwI*QS>v$%)Q&# zq>c-nmF8}tu-jSk$A+v#3v<&hD|O24`?9U)JMkhCl^1FUmD4q17yB5mV)?c35PE?rfus4*(jx_@aIma zfb-2MahH85O1pweMeL2!zS4a_hW#(%?of1B%DM$hcd4Cso*Ql5Mk`338(`qLvGm+% zPw}4{o%TFH5@FtCf}~3AdCr5`8?rW>F5dU7SK`6jAkKToA!S2Wsw9+QCg(YS>u#zz zGcWotd%;|m6|l@w=C5Wl1^@DkUR8Ex*|7-VBp%GBnGcvCL}6z4h9pS0MTHZd#e1zU zQI=3pFu6Ni2r~TM0V5|hEzanI zpXELyqOnaHshfPuIP8#(gm*^>jP9-U@LcbAIpHIl9_ zdgPoTon5LQY2B=H!>1kW50G7yob{t3w5)i^!Rk12a$MRti?*@LCWPzKWZI)0?BMdf zopY&4d9#7<3}H`f(u9-hF30;FtjzTuW!I)%fq&y@CO&kWD|@cZYgB>VNAeIGg_dQr zdr1UJWUw#utsz;3WoYt0-=9Cg?O?8s^(nBcUfUdk2}XS3pes=Ub9E5Vh#PQ*)|LBc zH*}EWU6?j*GGcq~&>6YwV+2*Oo6b0+|618d@Ei1&mC({mfv7^(|Wa$oj z=_fB}7CNjQQ`4qe*uh329PFI>Y^uRki^`ywO`0&`>~dIWeR3bxXNn>|RO5PeF0AHg zNc?YZonVLakIpwcB0`b-n}>gtpV<++OtPOUBzdBE){hbm7 zV*(?mjwTA>l0-|q=NJmoWb9GyatN467wp8^6|a%yj=_;=Tlrl!nOOP<5TV?4nZ>R>|Qf1v!#EiQKId^fUBM{p6k)Qu$y@jG{c6ny~EXXFtJBhqO! z?8U%-$%7pp6sx1y?9(vKh}YbSg1vaJG1YcoR1$lqJ}dEdeHp?AMivex&vZG4Lptd9 zu64$DBRe4FMCqMR83ZL?F`23}&O#*ximp!g++r|Me8A|tF;-$AD{wg66ct>D+bD6d zho(q8s5;$Qx=>F>4B5_$Dv28~KOrdhmOINhkjA&rGzh8Kg|zUX+@IW$nX=p}w$7MpBC; zajucnP?Whw!@+h8rgH3di_1`D#Hd=Ny)f%Hova^qpmk%9V>0IQ7dzqW3b@|`JI-}t zlU2Nq&0#4$V&=NnGwBwo)BZZ=#xDP{Xj$$kX6DQnxIWBm-0-G^7bOA`IMa@XdDk6V z^j9AL_P>gE5MBp_So=DTqP-tkgY)$#jCP!@-ee#B9^S@ncX(I2-3|YJ?l$PZzDj`| zq+j~yRmTSpd--P}HV)Ii+X??+857>cUoz=H;D*}|V<=Rjc*C7B+O4zuV-4uE&jc8$ z@zs^Pp(!$){UdHn^i|Ot?j~CqlG9mk55-As{?U`{N}JgSKB{R-$7Ai*zjXo|o!Ne8 z3(=)8u3V@)HgJ>1m#pt}aP6#2j5pHp6*SgT8aUrQ?WB2ar(<&a9Ig2;H1|fI`}vc+ zY)K4T%G*M~-B`_F@?xhW7&KfaN+Tgjr;x$eiMmI`u9J9X_&aVkaBHJubUR!wFJqJu zKM$FRD*)JN@wR)n#xY_bems9V1cy9O8qyND-)Wk9AZ?oKO(XtH)4T@K!uU@grY+@e(6l>k9v+`|l@6q#jX^FGJaQ4ooitDA zblhlzT%shoES8ic48)t3x_#A_2Bq|OsT!c z4gL7&&=gN z{&V_su4__y!Tt2_`Q3j`--yjlN zDEGA;bKf}!kaHaKl?JGM-5fPk2+el+OAaKyC6mj-dz;E2iM zLxUN0~Zx%?Qer>MvhNR);>>=FEL5y48%hw>6`(NCp~8%9;A81 zF>#SWGSx^%`%@e4vw*%YHd%k9K_A9-K*}lS@T9khxQe8lat=@X9bOv;bZDvl5)=`q zZEu5K28Df6#HctFi)0stTqEN^g7tIlm7o!EU;)q`XzUq^+;S{mHF3Jp(&@DQ-|jc| zVx7r{#bNG^Gf!#3ZHCBp%p{_e=4a@PVjR(a(UvLm)-LW)_pp|Q9VII9UIe_97<=IX zIEA}zM;wqX+ZW;T(jHJ)`&(`G0hvBa)ydvPGV8}}7kUB) z#@yK&WR}Bc$Df&tfmo$uNK%JW2;xgl78%$b)_>8Q_x#9AWGWYep!RDGDRS~i$LxK+ z)74}Ko-#6>=HQA?l4%_h4qt81hO|Y=nls@iygh!*G~CrgOZ?r0*MvI$PWR$GcN{3k z2F>EXO=b7JD7TF6cu{8gqV+{Z?zhn04AFH|G`pGU!SQ4KOYPYhAb!CfT6P7UpyN#f zz6sb}L5&`;n4wLH$~bLUhfT-8hsS!Sb^i%(mm=}5FKYW|{?%3Mx-smyhjQEW53w1ua17KP3dq{D}hEp$82)p#QO zb5usK(8b9M{`i z>v8VW+Sv}I8NO^PKWoKxU((XWsQ}oA{p)2w&rWoeXU3W6TP>D>T z!iZ8}V^}pwny&9lWy9Gi7YXZYGkZ}^BUeoiwVB!JQSdFAKILnH`WMZep2BM2NrZG) z;Hn}S+0<@}W^7S%@Lz;U%pH2Tg&J~*)l)uKVxX%NO0U!~#k+4g8ZaA8!3vZ1jdpYr zN~$r+yuQ8i^>#V>=j-j)<(Mt|Gtq2#iHte&9Yv^)VgtdiE?KI2t6TMrn}P4ty%v;< z=Axp_1@1rt*Eb9@Qp2dHjWY&4tu8!O@Y*8-rKPPD&eBcNe$mSM70IwdpCa*(K;A&W z7Ud;{XnkbT0-q9r-mi0OkG9@7MbJLxc)XqeDTc50tP47rw9XcwPEq2|XbBRl-RAlh z!{@DuH32ro@=H4rohKi=Qd8hXd>w^MO!(U*pndjE2dHi~7-qB@ z<*Gxk8iuuRabR=`3Kc@yw^W9I?-canh*NM13lAlM?JdyOdT8qnRDMP+6n8*wj$*gDbI-X+ zOIt41Bc#2p0&a|OCupl^pwHH}imUY5(kA&a(r5KRdgVa+w={F|H}t>a(g5zo0i5## zIMnb?)4!t6=C+D*v?8=A>)aNbk42s0<=Stu?rXC}Q3Y??)4TtKO#Ea(w`<>Mp({h9 z0zg>Y&RPicWS z4&yU}Z*DPSj44Yq^o%di_$VY+NIuhmu;k;%nt*|TD-xrS7u}VTY+{B*EwJ<$zjWW4 zr8Sqf;SeIwc*bNn(k7jS6y3(2MDNJJ@E)CFcP0vo)Qw@ovW&k{4s<3qtOBmvwD2=B zPHV!{0z5~UVC!c6u;8aT1gidmYT`500<1LWmZUN;?;>_^7)Bd(1OksR66Jw_4l?5K$NkXhoBsRis6R$g{8 zVB6`k8>a)pdlHIpiU(z$T2Q?A&O)c}#--^_kTdyZWkmK%`&qX0BMatT$ddU65pZ3uZ7o zN6@B5^`^C;88bGU&jRYhziI@%<1it}wccbM+a_H*fG3(eKXAtrY@}zKp}{G0u=#Fi z92w+UKdwH&CZe^g{cJG>#*oZ38CIsdP3#LfU{h#{dg232yV)d4t+KcHY1? z$<7O&v@+Vr(5=)3n76?lhsuNXwH~KWt1qpjbrAiZ=)1L;DBB#1n_Wqiy!GQ|WW;0| z)wpz#yAzHBne*>q;*YvgmVFrTtIq3p;)w1q?ozuqzoa_jQOv(S~=6dMuu#*LbeG?v}n`c`iw`zTNz+!hP9;;;jB`w_ zG(@$G6UKE!y;~(rDHmd?^P_y+&*H5xmL(TkFL<#}UT5io60^##Fs-^7XR0e&p?^)% z+>0S!wxWvsL<3!83RC#s!%BrIh~Z2I6}8iv8E&abd#Dw2SDjs&zMjDJ)sLKLb;z4_ z*nW!f%;E6fXH(JQrBex>kfbSvvqI;?ZMD^n^Ala+=IszQil+Ity84Tii)2k zUR_qVmZK%;WON##HhNiKr(l#%Gp6NS9q#QF8^gJU9s*LrzQCVYUssKr-2!T3Ja1a% z(Px;K52kIoNd9@@{X0xCNtP!@Gl^q{wkxn;yY*6(~ z@nU7DLC+L#@i9-O$-Gv__9j=50msgNcGHf9d|3OS3>d4-A2cP_4ACi89=eGLSE8Gk zTOFI5XxQH{A>VqJ3dl3}RfTKMHX&nTCY|eXmVWJ|RtNzn2EmwhfU$h~^ym@8`KJFL zvTS=;pgRn*-1%o&4ySyzyXk+7$sF2h9o~xbj>B4QFJQUCDj-8e?4M*PF7MX{H_uQe zCc+X4CKnGdY4I>A$q%NgcL%jb4GObu9u(d%c3gl~)f$m!)5=;m%UlMWh=5 zeoOnc-?u!FpJ9NtgopAYJuQw$nyU65DMy*1AvS98Wd3w69m2)s*sxHM<`zd>Q|I1! zRZw5$5u7%}GgmP;3-32W!#P5lNKH#*s1K=biHwrrU+jpbV+Yl3O>oOk@e|%@Cf~F; ze4Ds-nnK5Rj9)F1t3_a`$o0L7~^AJu4%#S3AFW18h`Rd zi{p>R%d!@^t0|VsE_INI=tDycLz7)KHdW5XPX8EmfNFd9?dTC62CiMqJs4@ zBHG`Y)Rg#DRQlPdP1|dvycjdyZ-Tjh_u919Mq_P2raZ;4v*psUL^-qdh0IyZ%rOzT z$WoCA_j$1q=fvoWjrR(M^FWD$zZ?>&ktL@wGh~(ntHqrijnw-(1|jUt5MEB?FRD#!G3NMvXLjF=Oq zvwkHCE1@jk_MRmU1plhOW8<$A8!U8;No zS;4@&!KKpkY)EN{{6*AnZDil$hfh>@EVIZwZ08(F!iDCG%Pwe{1Bv ziS-b8JlJC#&Pe}`BsV!;Z{#nfjlrTr7WHgncp7yB*_X;(7Xb|}qcN|WTrgDz`7YQ$wMMY79&+$*0a z|0LPK?dyOc{_ZyWHqn=$V6=yu)lo8xeg$^iyZrBhmAea8e)NGx#(kzCK`oBNMjXRQ zV#F_KA^EJrI;#;1Z;oth5Xax4eG0aX-y5+mQV01ODx0w~i$X*+*Qqb^k8pv}Q%ycv2^yRy_?IDLZVG#Up@ z-+sqwFZ7(F5Fb5hvlr5H6nXX&*^ZBzk<$!>O(G?Y7MNFa134liNVC6VF(_``;3=7Esp&d%Td17kmFK)vqk$C3uJ zmQHvwIeIIBQ@~B}fLa#rx(GSH{V( z%pX?0D3?wk&D*h}AdHoblaEuFcT!d#-25t?M|o>bm~NaxyQN`X?ppf?*l~}nZ{HJ; zPz-7tisuqsyqtDYo!S>>nyRRvlVpr7?`Ai!vUxjS%Ny(*v}0?kuG|Y9E&C~Ph=!`wZ9#Znv%Ar;Yw0KD!#b0gE|lXH1>q+aWdd9e6MzxD4;<@V7S z63&GV1!-CkR~O{buUL_Ai~149v9gSQhz{D-X_t!&`w>X2@xo^d7WOA9>Hr-ZF2yEb9jfKw|eFp-jlH-21o}>** zkTq0t4c6H-Y!;j3UPEE)!_G2>fg{r*9Boan`D@JWO^((kPyB2Cesrlck>X>iY`tAi z0~aHpVX-fYlfA#v2rDP0FZ;DbW&Mdp(0i@u$z$oH?++46I7QJa8tkwZK%jC=+5Zx< zyOD;ePy1^jyEWSD^_l50nN?nysybu3{!$$#WnVNo+UohNSh@;>w5?a~lXqOHCpYV@ zH4?1Al{3~VsT?=`H^enyqe9wB$ELY#zWfdhnGRRe5$sskxl0{aCTu-b>hFl)_~VfK zI(G%`4ng}e7dEl-dGDj0(qSy%M25zzJtrVxiuqjq6;nV$oKC(2S3!K~g*nKg_v*>c zCdY|-v{HWV{Z>lb==Tlml+7~!8@J7VFT2=3Yw0Ymywk+} z;Xah_ur^_X@sO`0zlp;pY(D1Xm;l-`8Em_5Eq3HKVS5ob5=PNm{6HIO;e!YD-&Rll z-elb_Rl1!1^Br#UvrTlmVckIImstxQb*!Q7<(%8Gx(Q=5hrnNGz*XUPWH!<5`?GGx zOEiW*>!ueq0cVB#jDk&YWl775tXF#-%Rqwv((QO2Pn_I$JV#+X(S!?@9DUUnP%*Q2(ei$ENZHJp&sWf@qs5)Vj*SkahW!~2^WY&M3+WKM?@Ix zhYfaJ8S1H(o7dEn$D5#?U{x!jn$Bo>+E847SI0} zu>NO&ufhg+v%nT=U(Z%>@9V>m;27=)W1jG zYhWJ%QNHi|p8BKYT@Um^-}x`=tI5A4hy&DB{|njLzRYRBFH27P6K%dLD#ZAVXG%7f*68ZDTU`z z%FuGvMY5TqFM;6KljkY=Vg%nH&mt%;LU5JmB`oSYkETUY=k%3xabz+@P3cQ3Y9vLC z=W*W4HMcKqeFxnf1ikSgu5?7t^g`A*0@9TV?2j(-vM#4hfoyA(Hc8i3`@7Qn(!Fcc z{|GIp4k-F>-i5_~zPg<(ZYm#|@*61-TyrKh>C+=-6W_Of-FBD zkWO8e+Rp|oz102;{?eXpxN#}q;#r=O#hSK}TE7f^Ycd)w8I3cPtP)F6Z>JDv9Z9PY zw$N$M#a5;Aj0!zpL!-*=xtdF*LL9Y`&FnLNY0Ub^*M>PzHI1ML&L{Mt@DEQIrd=gT zjqs(Cb3eq8#725fp8r0^{Mc2hrL<4uADenX3EY2EB1g+|yZa$6oSqy3>E*WfqZEb~ zFsToVebp$8&Yt9PjSw+D&2i><#ePZePPUBI#xz1BN0_sFGtW-4BFWI6yrkd5$kkx;)ON5S#k9(Y7$RTU{m8{=`~#WGKBZr3O1w7H3A?NJm`)y&E)S;E7Dg-?mM$NrldH2AQb;Ec zEtdx|x`6rV2oHb7D_iFU6WrZr=09aFTNp4utqji7dES^1l%CfdIhsxBbsaOPt~x%d z$0UcczUR2(-veQn^EfL{*ik-+As0}y;nvMp(SRHU^`+;i<%-Kc9{YYaO%`L-TeUsCI)DwGJ=Kf#Svl5xqG4vTjaAP)Y)GB+L7W$>D$dK# z+BxjS5DRITqg?i)?cI`wW&bi1CbGlF#>udDO^sxOR~WrmMd8X-NjiQ=B2V{*`EK`0 zWmJfLUl|*`AK$XJGc$E%<3bKlBPHBHqr{Zo?9MV)4X?>eJF_gQEKj*IM7O6myTG?o#IG&djvg6Y&Kp=NvIQa^tOSJ7PD7jQcHhPIgu-tD(&KMn^_R8>{_w%O4$A zo4EXuIcIfa<#;Vxi~;nr0qx)G&b&wogPdn)4 zVz#2~*vFbV^VjU8Y@@{+_Zqu?jZ`K1PXj3G6F4c%{oF#UAVQP}*o?HCwlY-FZbbcPt&BX*K4lvosnb5+ zfQqT6strkX=auy#ulMWp zXsFcJosr>dVVL`llIFNiG(@jr10i>vo$))pG~-k$%wLmWu|1^|W;Rsn>PnPnWY%D5 zzVTRtz3f*gll?Km)P~A1Pm);Djze`F{6RZX!uUoZVNbaqSP_1A^Ts3 zBmdE6pDwc>wAoyrO)Gq*^$Yum@#D-C5hAr>*Q ztbI#ByDs3=iSfnJ#qHw*qEEM<4!HRB0Y&4b3-bGGLrmFmg}yKY8?`l`-$C(<%IRr^CTI**aM3Xx84Qi}39Hzk{dntg>2)4ugXrs&ukT!0e#*3J zMcz#omwFHO(20(U9?u_g3x)NSMYU&SZ%K4^Q99c5^`3Ttmf&}K!)sErhzDT#qV|-I zRMumi$-c#gqhS8aAo7g|#z0Y`;>&}ea@lDmDsFa=aJatm-CDFEx%D`uD;%t^e5dvu zcyg8~H?Oh&O^VxBUzt~%w)QGkTku@+UZS-glH%?4mA2Xg0a)SS!sAzIR35BHzlIO( z$h>;MtHlRbtu|JhXV1Z z8LB-}YlE?8v6t&pgY}bI&ko{ewfj#fU`QLdcLe#Pkzb}x_tCDZCA;b|^ykD_x75M` znQnK8J7dWEh!m|c){NRBA1h0>16@ke$*JpT4EZO`k{x56U(0@c-lrZHcyOgLBpedD`=4Vl-Ot{A^txd=O;#%zc*ew3m=W1bj-~6-nY3bQv zeVi87N(-}&uRS1~tlSxz=d+7!c34N(O2KzGTdhw>$QEljMXr{RXVsoeJ79K(GS;M8 zvZx+kalEX^{@~$v91CgZ%g!&uM)YQ_b#m=JZT{T#GbDEeQjZDSC z$4Cs1v1hOQA-&*m+qRwl1sDE9=nbNVo6w{;1|S9#Wxe5^~L?|1?R5- zfdxV=vYqiMQQ(kFSjL<6_c)Q^I zFRX_3+jc7F$hLJEn{oEvSKB%P~Ce%ND!dHl)2+YgEeA@6kG!q0X-LfrfoG zusr#q%34>p!TMDVj-q-}N`EYs1bzHcdTte~h#;X&={M{HJf8lm0E4+sysH~tol=L@vnw8yZ#h; zN|rpDA)iuy=f+fcfmtRz{`KvJTO6s;lE+rLmk&G0cBz^jHgQn)*qnD{hUaUv&(*L8 zXXEy<7$$a_E#f6x#CYcxNA&3Y1gzd$yp3O8S+zX&upxf3SIeO2;^G+-RhX{+;wHPU zf_E_~M!Ws0VLP25XKKCipU5$@cgS)_Gn^qMJK zmY)0N$j+RtyU>uQ$K=-07iK@Q&iVBfcK80zhdR$yUmj#XpR@a!nVa8(lNji5zv~MG zpP8Gp*QPLGNjCfXO~Yi#=iJ)Yt{NuR(8IYCYG#Ma;6NI&Y#AHO%9bVO#I9a8Q8hEZ zEcYrMyr}-1fWE>_iXkswg#wxqLtdg!V~qKc8upNJ%ou2_Qn^2$5<{|(z#C!^M_#yU zl>6_NljT<0E14b;$jS=YHafL>Uzc|Umcm^O`bstXNn&|8Gol#s6e3)P7?MGsX&F(BsK%#v8%;H$IHRr7L ze0+cM6?axNChTwEM%AR)#942sF1c-oW%>DR819z*FlQTXO!Ilye6_G}+m@V+l??y6 zJNHXBQ!1xhQ0N?DFUAVKS-*7y9&LIREP4a_$2{q(L99+M_nvMSY4uUg~yQLSFwOo@Izx*`PTyVq?xLnY7q1K z)4r~**RC{N$tqj1XLiCn(!uvDEdkb^n#T8`Yzqc`7PfrTpeURDgZvgU=;~!vV{M57 zT{ut69?H*YpAwL7q6WiBrScspXhO^k74Cc`f7DSGF`UY`!foiO+oy?Nj8csD{`pyD z`y-?M5|%D#pA@jvWI0%k>}eNk5^`~r+2-@vA|Duqw-xUx-p5^c<2^9(8YREaU2)kB zirhK9Iv=W%yQru4SPsZk`))PFJS2v6*5Ty_#_<2>C+&5ZQp$KHhO{A4^p7!=){vGu ztm`5}m03~VqzTcG25F?p$lE|+JnJbuIEGxMFrIZ3W@AWg9hxkUKn)Fueles&=C%cW-}vz96yU)I4BBx{woqr5JcE>9yj(EAk~+B#eW`Y4?xI40MzVcZ-2j!AgB z*7rN&D7?Pku(%oqJZoyTH2k;tITEW0Uu~UD;m3WQK{5D}#H{;?^w^elCWWkjq5lSF z_5Wf;4z7b0nP1!Q7=a?hHT~pc)RgPf=k7sW@~MNU<8CeZ8ZPnWPx<+ue#cPC51vCP z{Fi=%QQ~XN{h}S=)#TA?tCqs|`5JLQQQ}KOA!`c#H*Eah`1-MyTDMpBJASW)Jr>Vf zc#13f9lud{ML+p#ovIeHW8aG}40Kdc7H`nm0$E+BqWD3s%x8^yDt6<;t7HI*E8QhJScQfL+s{{5X82iGP=Gp* zShGCQGyHJNCmeA1(&EqQwGFj~##+m2TKB~Se<`Zj@5^#$FyhhK8Ogt*)~+}IKgM+N z3%!c^0sm=CAAWyKSI=XXZGP`kp6y%}JG^KR_srPWH#(}4nl=7p|l#LTG0z~S4$!K1t7Fm>qH6( zTvg?hRnj%ORL6{^addx-Dzn7~%p5{wDr~WYRS`{LTglYgj7WyWQEdKzp2X8~if9LY+&x{rqHwTI zz7hKyI^12q5zg3|cH@e|3|fnfp(K-La@qCa--+M2h4k9W1+`RkSbBje^{O9*Zz?OF z#PEx)CF>F?F8aD~p|TR+XQ#4eX+5m>XbqgpBXUdJ(7WKcN3wa{8wx5(K&@@`aCM3g8Cr{@3l$?7c#TzrG1ihQ!qOEgJusSZ*W678nhh4}c+@Qm9s@)_`5>nZ+txAl`6 z^WhpOe4GUN23dj)zg1F&zx3T(vgV8E!kATwD z>FwLr*)H6MoeHa~?9X$KV3x45>Voyk)|^AP)wWxHaCKc5oy!g?NMYD5aM-cdpwkdj zb%~N+u4lJ^h;<{4k|rTogCU~8A}_bdHV25K^g9jbwQy6v@Jn`cPV}*N248x`dEu6Q zYtHT{;FVhB{4#y17LK*XxlF}5cbKkVE`#z^pL^!{vuo03*J!`F0x65n>IqMq0B_Ng z7o@<`dPC(El39}}4~6cu(AWGtv{k5j@-XroAbts;;pEvGHFVcAhyV?2rCOe;$ru(u zmLP&#q^J9*bj#DVS-)l>qA=_()YENLX&*FCPw#^hpVHH>VwH|YshxH5hs zD7l_~Na@`NSqi@qm@Ac552Y;+qN6X9Gn9?4UB9@-(aeh;X0|=Rx_D9e`P<61p3EB` zL@&KS4kNQ|xqrd(02fC^uwWp2sYPa8`vCD`h0yVBWu_Lc?+|`HoYJWyk}H-sFwyTzVW>K1-b|f@s!Kf1OH&4}4%IldRG%uU6q| zuvH_B=+9k4$X}!y1?wHlE6eR8r;m5-aaU-NX~QUrP|XU@R+21=!>jZ_D770MPghE3 zz_Ri+6lISud0wjW(EI6K-&S15%4AS{VLU~6&xb6QYBQL&p|bup8P$FX@yCP6LeyLg z&}$#9mbT`SPxUj-j1kFnFv%*EXm=^dJc&Qw`?SCP7Q-2PG`=ug;$Iy#8Lmnp0J)H)OA# zoRhJD;S2k7clM*U-06wbej($&nE1ecVPVo%e@mjPG5cSs#NUes%d_8>z#^;<|A9R? z-XZ?WJ>J24e@b-K&^{$9S3h{73H(2iASyp4BdVRVkigv=ND#Lofm3{n-40uk=3RAl ze!lZ52KID(!fMk=S?>Qq)|CfDU2Xs2I}6)aS)CMIn88721a;8dvYvxVYT6T2Qp*x` zFfCtV_B6})80;Y`m0P)FH8VB>Cgm3t*#?;bM`RI(HuY)GrLi(Cb63Fmea@W$wckH8 z-+S*l=bn4-x%)lm49D@Ah%X5oiCJ|-370)YWamV^F9n{#Q`#R8juj~az7hG2jT*A~ z-Ro#y7#)(^0~Yle@$M-cO!MNRj? zke1X)DGUcW`iWFOC-EE~HkGqCUW5mR>Tzqaql)SuTv@dFdh4cL=1n7X^ztkRM@gd} z9{uAO%Qz(b%$u7&(w$o$vdfct4i^Las!^=e4fjkxwHhw5~kKgTCXz7@W0NyVY>2}HPn-b8y8mn(j`h^1bG4VDD1`E6U4O@8F+Uhr4oL+f}Etfj zN5l(n5bOG;c+)E_y|2V=RLylevN1m|BzR}M1B+)NjVhoe9#+WGHQ`7hg!*_k>L`Gg z1fwLQxgtqtzbL zy~wAh*(ZF+H&GVpgRJQ8%cFyqt2Gdsi(gk9TDhVhXrNBLO&PH%`jp1CoT z@3Vaj*J>0A6IwIRW||j3FZB4uQ#anO(I1Lu57EXF`v>D?GqA><+(USpwa<}Go=3DK z9Yw;NXTjS)y#vbI@w8kPh7!N_NBAu#e$}1)#_6~kkOgT@f;JL z&(^UGn%J%nhBv$A567?bBE{GfDSLiKmrr0XcSslg!eDK9 zt8sEvjukh>w+gmo8u(i}b6K<<+@#<7tCYE58{cQNz0Kvc26m)p|?(Bzjcu zRja1EJJp^f+5`?iFVe-FFidQrp+$m)FF~b+(XSu9sEB!!bHs_XjVDM|VXM@28XTNh z8jt|rqvCnVH=Od3k_7R()NjPvKd_AvrH+F|`XQsMOBTerZn(9(z#h)qhK1X9c5(Mi z3GS+%ChlBL)7>WG?vwb%Qq^~ZlP@^u8y5l}KH<(e^GbYQ73aqAGT7Pp+X;B%l)W18 zYRowqwC^Kx){9lGgB5?AFzZDLI2=o47gJ1UTuJtAd+R?+>MBC|xbtSC)FN%;#fkIBYpGoAm#*eul`VY~C)0=kpfvgq*qNX-ij)&Y zif@}>Btpr}+YeKEPCODglcjRG6(vrg%-M>kD~Fw?nkIXw=(V$|58{<#I!sSr%sB>% zZsQko`P*EQ2L5)^*Y5=}*)Q&>P2r8lH}7?3DnpdBMZ6MSz_ZiwhnK=F#&5QVa@o+4 zBws#wD8+QxH-F+Z_YxUlZf&+`^DZZ$B{+U_Z{FdoW<)lBHpw~Bxp(hn#&A#xe` zAtQjyT*;eB4JN~BO2RXuboysTbCv zfHqC)CuT{Ns@?J}0ZL91rO+9bS!wYt`I6*8Em0bsS{9|LR!bG}O+pL})0Fj_@uf0; zzb9aMKVFD(dbVH7<4dKq^#P13H=d86|C#NS$LMy&{3e#*`q8RWwKTzQ8SD!Xz=sDF zAx=}cQ=Op*b{5%st4)d^r+PDC{p@xG;OW(;@7|Z2Z+Y|1?vV{c2`Q>i<*HjL-*G9@ zC;3oOkFg@93D-(ycq{l16XS$N|F%g}OYpsu4uIMF=Gq-$@10|R~ zml@1YEy5*&x%fDYs)fPKWH3Lr2_O~=R zCuQJ|j|1kHI4@vrtgmM{BEmt3d(en~k63&>keYW5RJ}=FT^()cbrb2d9tNfcgg-}d zBa=uz{`BA&*3iG>K55nBO%`-|ph1KyKiGE7zU9W1ABJ{Z?BmMM@h20+iv-_b!ov*q zzI47hbIE+GnD*m^GRyWSvRb+M^FPn>`+yI~+rjgF;P|E+ovgT`nMFc2=4s!di4p61 z{NibZVpYqTyBN#nF5JDr@K0##tPjolqAe>$Vp!3#K7oEX*BcAH^NZHqm>~9%7fW>0 zn+heahG=bO6MOR{HoQigL1=VX0}3UUbYN>6C?PsSHY^tYq= zJs2Gq4yL>3PTE5omEzU%L=F}T=}dEUlWJ|W;?<_O*W=nSoJ}VRMdEj8EU-Kq4*hp*7zbYmDo#HS}HqW5z!zo5TF5xp5i?>6XJ!}%2=da;NiV=VNny|ffPV6H=_ zY#PNS7@_<}O1TD}_)QCL;X{S}jVa%9$_Yv^9!#-{UmER_v2+|{=tf~|Vb39PStdH}tM8#um_*FC?c>Y0iVc?i+O&Q5dHeeBVnE-O{c$ zbe@QG$1M>06GX!DbbQhuZsB+{iHCnY$ZKyk365r_LPZW4Mb*1p?Quz$n4T0Y3gBY& z{YKXd(TeiMxG5fv_cD$T635bb?O=2tymOLjw>6*xrrs3`l%kTvyPDk!OGBJLCg$FL zQR}zH`yoB6t^*ykWTf1%qj`s4)Tkk&{NBC0DQ8Gj4z||V8l!9mLxcCBpk5x2QxB0~ zB!cd^-puqct#P1zq+QgAZYfqhAFbHd*!x{*LveS#% z{07PkDb@0$Cv`%!c1?3pm?&Y-&xeQhU>#aY4TaVO#T#*SdL%3*{OfTT6``xAO=y5D zVGyO?v>?UV1|{bs&+^l)Xma%(94m?1SFJQI$V>3UgROpp=>bKurm;}!GDPF~D$I!l znC3TI(bZg)ZvFSvuU=_pUGYmxg#UHbr!=ag_j!H0?6|Hxq>MOURXCt)^B-J2c&0}=yerm7=;POr%A1w@^ z>OK>vUEHw6xF9P`L~XUM%%^t)8tm=~YOosWhJdzcqS0Q|Qm)H!DhoJp*&g95(iGMV zM+)A4|IY@jx@nqNE7l!vpu84GYi~Csh(j$^?jc%TLd~D31dQ7zU&bnSQ+wQn64gi1 zg%Zm)nCZdmJ4ge`u698uEwMyb(tz}Z(b|hd%2h_BngWVy{xscY!zexU_{^;@r8>CI zVqj0_kI>Xpd8b8dx3KbB9@5P3q-ojU zR((M<&7I|4Pvw1w%KK{<&5n9+8-vejps9KeeVP^5_>ktdPMZ4vxY0DA`M#H?{yori zy#<<u3qNFUx`_}2+j-+Dew zRT7tw=qK~oGCf&u##{FLA&Nnb>^#@9?5<)~gEqFo&V?3n!F(T4x3SgLoAG<#z~(}+ z;U6U8NI){*=YXK|B%iK8(jrRgM60&xPB(U8&HGCd5KlKUq&bvg=0dTyFx)tf@8rM+ z(w#6|r+`6Gk6+`w6=p7&ATCp+PSQ{(IT>!)O=*T+^b7k)g-tSC`GJk3M=1VC@QfV$ zGIV3)rgf70fh9{?`}-KyGh$MfeqaUJTWXSm*ia%y^6I+iPQtQ_^{yh|Pyx?O8X z9{f7xVFAg*43dYME}9D;p?MfIUHzlAKM_sU>W4H%oitUixGk%QW_uHj(CA+;gQn&0 zpsBC&(8N4qJWeAuof}R1Q#YkPQQ{;2Nuv9lIPMp%dY6oq zzLX}iQCeO+;^R>LQukFc>?nx&J{YJiDQ-SYDHYvT_Ora^zE&JkUfdJ_EfG_FQ)D!T zIM3XnpXPp=BdCPF`o)hz**#EH11L>YLKJ{_SqW5{>>bylLp0Inpa~YWVy<||-s(B~ z>_-2m1UzN6WZZKtbYD2yfz_$sx%bzC8}6##Q>Mt7mPzggW%>kml%@sGq{qiuUiXv< zbI_uCOh7TAoNS>;`+UPlar&MlJ#Og&Os1x*+*xeMEfd^m8JY&Eh^7ykEaTm188#>9 zG+}bwXc_0mSuBg#j0pHe)+eI7r{3_PTe<+CTop&PMqw}?>$c2s6Is-HL(&y@`t&&c zY!BvtnqbMCb3NnM&mx=^XfojN4VI_f`WJx195rVd1J`YRTA%7cS;bH+Pq|?t3n+_# z0)`tbqur_*6fw_3qxVMrD7R`lXwcb_D9hM=-PQ>zv=Xf<<}ey~#^IVqDAT<(^uyh* zzf;8AP8zBw-LB_BgYVN65ciyER+G$ucZ9}%>$Z;9Pxa6m@8KuGt(rop&v){pb*rAE zi03+K>4&&glfCr-TF*Agiru}HreRHJ8kykMpK@n^O>=RKl7mAW#V_?xG)p&+aV5F= zzMwO@=`8FIs^Z*e8j=%gY*TC#-f^I5C<2qSX>e2TjV`qtZNqn$wYo*A7kpfa#Kl0g zD|#2FigjCbAPA#nXbkK}aVNGV-ZIux76rvoMGl#WIZ4SgTCYdA&RM+7asHmZ8NT~B&weC6&PJpw0^^WCOPjSkct&gzms zu7d$b$ooXPXTuSI?l=t<3;m%Z1S5m4u!G5U^*9HXE{9FGUuYvS)pxfhawRS|B+Hhq zFtBYpw)J=zcldagBs9~YORT$&?PkmXX=2?yd}L%DFZ6Z&ptN!uO|I?-tY)kf zp;$ke?2RyKf88^CB3xt?6$Yv@+YH@~^Zs;FJW-sxT;Jg~=e4L_AEY?k$SnQ4n&QnI z!Rr5vR}_2VEREhc)wOs&6zhw{gJ|zg`-}8JiZ2_r`HklJBC{B-oZ}lO!60$Wwpj7Us3FL=UuJ3?n~i7r3h5fU7hv!_g4#n<(P)K^T`YW+eUT7E&qvD+{l}*|RX6!oRTa+eyE= zg=rN2nZjRZCAr+fR0>}@n7dl}^?PK?2hSuX;{@PX6K4sE!)7Y!j9WNZPxX88pj_j_ zN8?69uW3{KtBw{|oTJ7qjBPYok2Q%ce4LDiMykg#RJ{#d@@5)E;rfT+;S@gJ6?Q#v zEA}4~wBSYGE6%i}PGt|#3da(~{@R6g``=3xi}nxG{eG;-SeGwRJyDt-F~R_o15X?` z$BI-PxA<=P5}a>!a~(O1ZFTNAlW@$kF-V9aYT_~CqSPqvu(NFQwG41raEM=e6lTwn{y7<(|Qrw5YMMdI7#kjgGE>MwCmpV(@ zdjq=Hdd_f*mRhl5zLrvXyO``X;{zM z(YY+85N_m=K5IYnu-N0%BlgH}ZUAkdk+NUiqIX-PMh2&cy{;Hgmw^0c)}P){NtV8#%!T3v>#Tb;pD% zTK_;D31UwlY0nyV(!M%XBa*45S*ECn9N78&df2{vi?x`Cigu;lIM2#WHYw8vxk8GC zuW4tROBibc2JD)k3qO_|eoWX_XSU7I=NG3&gxP|RIrFg{!4uaSMmQn}H#IaW8|=q` z))e40Hwb$gOhLz#Fza%DVA3cNcDQC^DNLs5ONu=ost*oY1D0}gxwtEMsQBsO&CcF(tKOR+qlU6?>% zDtu3F6UMO$-&|~59d%}xt=Qo#awcN*6;Be+U zaJ7rp7)GFTeT^wwQ^xt@W=!q6AP z@?T$^8bFryK+y0UmAzo7 ztp{FcQFNFWZ@m|9S3}~0P(CzeL0A`_8h9dMGs|#Zaq4KXIXax0qCYhS&>>TA6Sn;H zF(wyL9=R|t2=64}=;;=+82(Eh{2qiK{t$n$2fv2l2Y2H4=)(7N3vV*~S-|h?5MqKe zFOc)04v||}%FE82&Gv_=CIf&pi?ZP9S7H)Z4x1Wq*hFg2Ds_{u~28 z?PL4osB@PWJjMg=?GI^=;}3+<1Z>K?~(_Cnx&6>B)yo5WS&lA$5#)8B`jUn$=iyf&Nschx$7P+$`Xh9f$%B;yPoOf zZShg(t6t!n9$;@l-p}4nyah7wryj|BnmCRl4$5vs zaeIJSybNPg3Z=6Ca+0!>@A{mz(Z4AgZ9HySR~xN-ApB0qs$n3`c?Z?E2reEpa(+1o@b`XQ|XMyr0St=Ca!&!emeUwCMF#pZ1J0Q&`F0PEx5`&LMn4b^5wNR&aeKKLsy3kpsV7r(+FX|BhFn{Ft+TC`<+;v-&r8_+ z_O3TiHSzxi<39>@hyEW$?Dr>1-u}->onFU?L{U8IenFH6AN{lE1K}fv-`j()ApG!$ z_=`RGYZ-oUC%&Q!-|vBt&G36Z(snX}ON>@}+D?SFQ+g0&9UUU!9R}aSTi>~q;jvmE zFj<*O`87s3u6NifYn_#~tnns#3h!;aTraK59l~ow$`V|hs_`+Yj$)mZDP->3<5Cpk zUFC%iVIfQIj-1Y1wiVPm^F4Jr%tLOfZ^Ad-Sar%|KXeFl2-p?K+Ae^zeOl|>UF+$} zv7OlyJgpggWepv|-x<7Laq46r)8ONsd8;BQ@0t#@%d-qXR-C$|Yc0^taD+-~o({2= zm3Ig_#-IdM=VR)3T!|-)jQ<`)qX<>?6ieq=de7sD#?rAYJ&e-#A$=H27qRq^<0;0{ zX)Ha2(#=SZXXy`$i2lXeP99xBl)ek;16X=HOXnWu-;L6@AYH-I@3Zu_x~}{KDSZRd zBUt*~B3fdh&ZgBm|L(1`|9X}$b5Y0LS)IKq`&Wk$%;0YoQJwvQy|%Z#WJK?uRA+t+ z;6~9Sb=KXm+*4=Iqt2Fg2poav|71L!tW$dH%)${3J$PzAO6h;F^nJCRJX=JRJ{Re? zS^8C$e!Q-;&MXgL5-4dV(yy`f-&nf6i$_a4rB6lrWtRRcORspC|9wiIfb^eO`p+!= zU{{@4?o#^GNI%QcU98R`IGecE$$9JSgNJn%#OkbGrUinNAzXO0PJ#?ydFmt`brRbl zG!TgDToLtyH@eyxm4rN_I)qx5{9_U82S3+1FL|c(<(~Yg9|W;}a9h@+L#SZc{g?4S zx3;T(t`MzmVCN7^KgH75JglF~lrBa3S1kR9PMK(^an{#(rrXqq`31B5UX6G_brDN%W$6nZ=68|Oe?|HZmfphBUwYUc=PCU>(zmem6HMkb59Q&1 zlzyrmGPi*NG!|i#;F)`1K+7jH)^=e9OF#NJjnRxoP1!eqIoK||&iJW$90p#tkk7@k z8-V$;U06skDqB(NzAm0a3~Zb-F9c;HFiLzw){kj-uvA{qStPWXN`&b~FCaeto&p2n~c)*ole zrnU>g488zO%-O(ef{82qQ5@E7gQ z3tsyF_$xmz%0k+O(+qxBC;Sg~=l5Rt`G4i-C7HBcXlC%+JK-Db&U!CDY==mDz|Q)d zE4$Yw)H3*Oo$yEO&MGhc$$#bNW!cp>p^U+A?u0M4JBz&V&-|62S7hhggs&L<2c7VF zcIRF%KM5ZAhy2Wweb*-JVelJ^QZYF1wmUx|;?%waJkSr@H!b^ko6_Fo?o79{Wz}`ha_(XI*U3Ht{1T$~ z&Li};c=E$?PWFDA$RIh!%QDwy3gTl;erB6;z1A>@I&6_mi384+m}GLasT(9MF(FHo zhBgPT{9rmri6ec(RHDO1o^L7V-Is0S?apzYvNtnc!m*})Z!4^mp_qv@A~}||MW$!f z^-oX#kSx0_z>SB}I7#@~(Ii9GhG1{TG#D-`YQKDLK*(xk3+1@n`0+AjCgnP$E7ua1 zE2@#2b1o|s%gH)N<*yJ`SAwTVWb+plv6o{Jg_ZQH07ku!5cv!8CWa=m%| z$HhXKWA%jc@sr01B@Xj=yoxjYlSpL$fen46GA4zSopTF zrF$IA=HRSb;cHj61}1RrN~0S--Bep2XbT+Vt|M7lW0s22BO(lakHWMQ+$`-{yNS#z zWz}uMXKt^U@NhZ=?t8aL?2{MiM~BX;yRdeiSnHEe(?5NobrUjT=jn<)cCrn(T$$Y6 zUL+N1@7b;dHo;Q5#nBBn1jERBR!f}aM4T?yF;OyhUv(m!ejohKW8QsJP)tNmoIR6y zca*;J}_dE{a~d zOaB^`=YO*0#k)8SMpSx#x+OvZQFzzlAjF``Ebrab{o9t(Km3J=9zu-6^rlU}QB%~P zxWr3wvE^DfGI5`EH>H1%7b4_BUx(>6n|?hYdJse$%Ao(fTWXd_=;bgiv{}|^ipZ9| zMb;hU;d~_CZhFP0&(dF321hG!at$(Ooga#uPv%?r(+PdBsHAm3@NyDDH8JTB*Tmo(AW4G`it6 z2}Y4{^=RbK$Zz3i8L_Ix8kiywR@OH56qaMmv%IOn&k9XqZU6KI-wJOc3KXEh)xRxp z^6iCBwhRlIJoMbq5S`=b=qD!+O@wYDS>3`Bd*V3JyTwEH1(P23d3VBhd}2~Z;<)#d zencgBbe6J=K8cWyiEGCWSyjR+R2mquNQQ+Vp3&5N0#nqVW4PeCBIPwWbL+!;cK> z{Vo`?IimVVBYaNHG*6QPBkQK4F*8*qdQSE{6!wnBsCwOgG5~Ay-BQ7L6#fi_?MGvt zlnNgoO`mWTWqgSqu)5}Igk7wC(lo+O_VJ=7<(uwV(pQBLYL#x(Dz9h|mjB`}yiW7d zY>kj($N$S3VKIegX@qPFgH$?&U(g6|QTQc|uzS(EimP?lf4@JkJN{HX?M zdJz4YK3p>}W(8S%+8_$hPZbsu!t)R!{kv_poNDK~>H=z)uc#)eUA|u}5z+voPu65- z+MN10sgc(!c7}Kwl(M)KvD>tyT9{qaJ)=o(HG z#<7kyj#zhPwAo&+cFy(i`CccVAFsY;n^o-`&FCBc-5I?X0^jVWJd;T0n)DOFtPSgnT6vlrXg>@QXAcgU-q3~FZpr$bXV;Nh2(+C3)q52zY zQFY~h;2eI(3#C#a`Y0+SJ%a4Hj9ZpH!i@t(*>LcXKH1N5#GN#h#vjuCmcHsyf}Zed z!gx`3JWQ7LPJlcu2p9ffEjLVKx@lv&->#ZAM=z*;d(uN~zuVBl5WpA>)2+U0bKEBS z(EBF*VBtK&AENQ~p833t9>b;Y>O(kTfi{OtxXRXR{W|F$wKqlNe{vmk$_Za$J7^P1!Go%o2fx?`-EjVwb-Q|@ zuJ&KRS%6Yp&-a){mVfF~P-ifbo;;)mO22b>ziI2&W=>mirUx@ZmN|QE<6El3_hlz> z3@Ot6dBp3E>s+@Y@v^+gP)z?=JL^w%Yg{6f6UWii>-FEM<*P{%;G{a+^K60L-51y5 zSx`#{8`3e3n-0|CO@ykMMNqhqg->*a_pxwOS2&M_8@s|^uy8|H*i;MdRP~)<;j>!P zXSJ&1ong~%%D;{U89zHIeC%QPV+uPShPN_$N4@wV+JYmxFKXAYyK-^Fc-(fX$uW`s z>RtR=UZr1`Ujp!OQZd~hL;U_(mYi*WSDMLT7oTZRPv~d{A42h z#|`=FVC~i;BgK``W(Bhe|ND)sJonQ9dHI}nVzpV(OPEwEzbrMR);5VFa>`4ArJ58f z^A{}@C;jf$^3_m*_4s@`JP>|c1C6C?S4%xP4g@>?aOb3r9-lcp>)B{d_KjPJC8Pug^Uru)&C7%$ z>PW=Vb#-L=qOHH5TNpAq{akj)hV*mkA=A?B!h1DMP;UZ+{wH;gVqJJ(p^O4)9ofye z*zDn{FUt)z)Cf?Qq2BOywf4)d6SS^k2MfLEIs2KJhjsUFRQLA>IAembA44FrhU=o#Zk51F!>Wv zOIo+2Yv9H-ubQ&hrcNRk)ffvs?fHv3DVV}nJYoF>weDI?^5vR{@kLnf?4R=mkW}w# z4407}ku$9{Q+KfjQLc+>?WLNCp_3_N4DE@w{^nXgd|QgbO#iLH!kFT>bO@)se1dTD zsT$MKnuwYENI3P0H+0|DB%iEeU1y{O{YR;S-ZA;=vNRn=ZADFDv?%qU zSSTl^RHxMDycUa?-hqjP8(3|rPO35E{OA7Oh&i*wd8)C2`_94cdj7dNaN`A|#rwXn zRKv@u-l-P81X0y@>g0Xs3R9&y;&pqik?BHS%~>hQhsCZ=Ihv4t&z)#|@N7i5V6JHj zpbTwl+VAO(+Z^}U@^7tL9&r~5u55J@*0Se)6x*tVnKo3#NRH?6mykA8yS?fW_iPvf zy8N>xc>J?f-$*pJz&l&S_|e0dZ#E`ou03J9PwW0&!|#|Sc_B6&tMo*g!rSrEizMbGl^c`~e_SKQzFL|IA6{XIR z}(|1Cv)($4cAHX7g^td$jnnn|G5bdVS-8%|BEr7wz7%$fR8KsdCZhSwC=muPw92 zZ!v0=6LYsr{6INzi*n+Q<$4kSg8ub8@Cue%?ho6Nfh%1n2c{l=5HCwQ<>tRs6&}Kp z6Q0*`a)1u3eW`k+I5B$n?wbkbVWWp(bNF1Sm8?^`ehay>M3B`K%2fN*j(Wf*Mt>@= zeUM-tNnom3!DP%=|57kL^K+fJ0|!x!_k}h);Pcd`m@0ku4%k10e_!E_ecs+Emqo4H zS*3)B)bXNtv7-d^mWK`NEn8U7N zEiv?&n$@oB`GMIxpr<9)uB=i*@n_3$YVV^1lbh|j7JIA|>RE~=dtMRqUsy9xDG|ZQ zfzs{+b1~o=!Q|hp>3BpwSQIOT+LJ7v;!+b5h|1q@;ny;wom4^(RizjW6g=NgalQ(= z^E^7Mp@}+@V51!ZA$+LjcjMpygAj|a^v1j1SL@2Fp)4oC%7@_gsD%=5nkrYFh<#{* z{nuwHrRMj~E1?}d6*$LRh?Out zM0x31UNbxE?=3Yy8ekUb-Hc>ATm+hZsp2fMfoXrY^DmlZ6mm%iBASoHr%FB06Q>_M zFg>CtMF$f60B^J_exNYQ4gV4AO$MY*EX zX9Egl`&0o!mQ0_AmkkL0*nx4odJxNb#g?nE9 zUr}R@OYi^=#ibV@Ri9z0Yq(g6BEv3<_CqTUP2@Kv$-S)fsFucROB#(^GBvgsM_`hK zMUA_WyCEMAStvQ_M)K)O-p_9KhYurLFzga#rG;jtg{7piZjyY%0S~pr(-&?t%02pi z7S<`DQ8`00Vc9oUmU>gl+R?S+Zl7z7r-lF8Ob03fuAifp`H41~=rivw`*)qbJHgF>ZE&qfg>PC5|zxd zYM|niN_YVg7f3vU@(-T<>(BUUzo^6lSw3B)HPMG|Pi69|N(?6Q_e8qS=_9qjNM6&O zx|O$kEa7pO=ly=I`XFQwIQTB2XFXlS(P zZ1n20`-U<&(fH{4@u%22e}4C?9^4CQtn<$8-r)(~BU-K(x+|_!@qTwRen~r-ygsA} zuBHooSgxwtAYrwQ4=a==Br(jV)YQyzd~f2RA*jd}S4bk^dK&T?M{&E=rV{EHs{gum zQz}u1BT3nb*{JDHfSN=h-NtZKW7OFFc+gZk)o2GDwF8^q(|nSjt~C5sIhFQnSZJm& zb0*5PXt`dZ$f$&Hnw6~XM;uxjK=PRi#epiTB%jG-uN(2y@$6~CDp9i%NK2=`+{Fsw zG4_TdgkitqR( zHt9Jg)qN6|2Al~HhT2RViLGmpIy)Y6DB>ws%B$B6dAv)`-)<=_cYfZ zJ)_CER3Y@VHAxsTi=6t3$SU@%om2xmu1wDOu|f#3wc4h6Vf5kZ)SDuKw?QogboKq! zNj|vB7@z$eT7Vc;T@Ot#ZZdzp%DYn6uSL&@mpRI?kf=5_RM<^R0p$u(^IRd9bkL3W zV!vyHs9TA>-AaG_VA3H{TiO%>zr3rMUtZV0sDCw7bhayWCu|jp!xf3&ki5H|Pz%3S z<3k^*&Jz14zfmb)CCZYD1Xp!qoh8i;L;k|W>c$@Uq2my>aDjkTVd@m|65-FPR2B9? zRan12K@swqV&T687osj5$_^Bj>g1D%uu3gG)WY}pvIMD%`VV7fWb{#LtCUy>QwuFf za&-fZ_k}Zz=nqwtO{iKpP1HlM%YZGPF+E<`)jdnR1Sc;!L$by#A=|4d#)KDk;dFJ0 z{6D@zH7kifpj{RBlC9NwhXMsF<=Ty{Yzu~F+ubR~p)c%;B80ajLJ32Vsp&wn^j`A8 z>bxhL%nOG(O5I~7u)N;)=Jmb|^-XqhBYA1&i)*KmUED5{=&MxQ??KZEG6$wDWwFdI zprtYvXE&a{Wa4y7DoAeoi|9A)Ic<;16b!{Gk>xpekyxDC)*V6lN8OX>RHR6k$fXF% zl!6{2ZlE+pQaI*uFGb-5h$?hxegzIbCR?f)doq$W^n~Zn)R}sa@R9=RS^Tzrd4M=Up;T1 z+4z;tyhxOBzandZC^cWC?>W#DS>UUmo0#?0gY-FE_A{c}OZumS!%-r6dAIb@T=qzj zFupowvL?|q#QfC*csaBk+4n^f>_%_kWFtiLjedD0oMQm&Uvf!Wkuat@ef75hjTpb- z3(Hpr@MR~Y`r0Df65Kg$xPx-rmRNp{J^ym0@Ny+Tm5(#qrWlH-yV-50Pn5S(S(~8zriBcTgyNyDr8mo~WLWy?1MQZo1H)I>Lq6R_vivBI?zu+=Hk?p&#Pm zBeo@$E@H({g5y746fsId1ByMO|C?|^2VaMPV zQArkgzDZBuvR@Y6PV7fJgE1n0Z@Q9m%oXviI(P<~NM5bS=O#@@uSiefvS*4)=5vmj zfZ~_)dvuNEDUw|IlQOb6<63h!c|*lwslHv4eCmks^O0%$%*o#$LGzyF3Zz$MO&C@C z8(yX=Ei&f7LDUkvt-ove9Ysqy$slKGKA0ZSOS>8pnUgP$sBoQ#<-4JFVfPC4x9Xs7 zV>$IY#Z#T424*egy7VoaW2lJVGhnDZJ&Q|9fQyMSG0-!_sKTef1{?S`b4i0lx6Pbv zkcj_&Q7D&$Q{orVdY0vPWqm|A&%{Oz3Skc_arHN!I-OXR7KAP**1r6RJu(I z%Uf}&ItCigeR+Pb;|Dh{<5O_C!S98dIKIaveMx`I9k@{(6NA%o3gE(HObpV;#PBIe zdzeDkaGQ^IVz~~xENWZrP5M`+4Neh@m69b_-jZJs>Hp`ZDdy$7N(@RD#JVw_nj73% za}F@JSJzmCVKBgT>ke&zMIuG7isU6nV!2t;Y0B!9Z}}9}uosk^EL)`dpGN!EkytV9 zF6WhFwU!hmQY?`m;laNtgj+wd8SG7pPM;eQ^7W%qg z(d0{A*Y2o(&=iQZN#&iBr2d72iuN)bb;yzLNgkw)X5bcU6s}KI$p@i_ zXKB_bMjsi;kySxOIXpRL?{{nad$7Nt5i>jAoqVEvmUOu)SpIX+=K8Xnl|*H(ANBe5 zAv=96Qx0D0!8ty2yXrLs9Gu20xtBAdk7$FA>F z8T1=s^L^!W{0wIqh^5Tg{fJ>7ebc39zM>Sa&sfUmWlmd}VUHJC>OszqrMY}dEYGQZ zSA|U*3|DmJ14j4`*gj>I_=UsIs>5cBF?Nj?$(Fc9tT?&y<^NTcxw99#Q&b^_4P~3x zm&rf+BWJ>nnc1*|jz^}L`BjG4Z0st8-|?-_jLp7;QA_qa8>euOJ-$3qiqlC>^}~Y% zspv|yaH+~oDvEAs?P5GTZ%HZM@yq-72{+-ygJq!kZ);%!2_j_QLcfzRNj@3Wq z$-b^{+MX&#@rD;VF4qISs0;d^vEX<_KS+~B!`{y5u9l%Zi4q^I!{x*Hw7-=X%2dAn zEH4pFnWd($Zb^B@2URJO;AzRa#;}asDs65R9$$&|S6L>9yhW23o@bee3ni{MVqxJ{ zqW`TEfR#&Pn7{y#;#wN3T}oOmV%4u+7*Dw*hB2K)EU(47;u#P6ioV*Vo-8kUp*`i2 z7_?o`uf~E|HOi&mLFF<8EB;ZX^)1ur*a(;wMQaeXMA1>2(hC36sr#j>ZJLais%H7Z z@l0|-Mc$!c0N`{3CKy~5w^Um+1-^*Ll964u^pTvbpXm0)o-sXjF|jF#pGar&Ffg=@ z%U&dv<)J=` zUrMnkRN6Z*OT(6g?2Oy8{#I&)kLB4rg1Sl`aobc;s-GJREnt3f($8+ym$y=k{&`O- zRR7T^&X&h=G(zhuFhXZHx%K1k$OCQ&eX5`kDH0W#aUR@TUvNw4g=6*Jsy@OQjnK2o zlvip;=-F5}NE&`eR_)ejYLXkuaZFMmO)f1(f0J5*k0-#NK7A= z3PP!28-?)B-;6iJG-*YSG;?2dUI~*) zJZ&PL|6((671zGI_Sxtw(6bnlvAfQj|v^9RJ}xD8#bh9#5t(d7#d;2p_V&#fU>&QR4uC9Q5-13suD>-khx49rB)qb_-k`7+`mPVp zGQO8JLt^M_T@PpW)+}ZO)-wJTs|5Z~u;R45+}FzS`y1%6(Xu}_(I>LV#;^Q|gOe0p zb7>)+%(&LMjYp*WzBHN?M&mqlJr4^^cB2T@Y&b-#W?Z;)9>9oLfa@FX)8tEtv-&C} z!G)3{`!5FuOX0KFT^XfNDD8BXYsq3$M^QCRh!T)9n2DBfr;?GfNMbW?YIcCr9O9T#~dU3f$1yAg&O)pLU zx{}s6uw#WN)zbgJ#F@f4^``$ZAo*9b5QfaGHVwZ}ozGhpHp{$c69lN?- zj>S=|hrDZ5tmjbGH7+*AlaC9s?CZHoe(_;Gh2l8gAob+J5-n#3uv*rC*4K09%;TjA zGo=@*L)pl_xsORh<~?$w>b+a%3mMV`v?2Xf6Tg*|_gOv$FN+bCsJXRnoKX zwVIu={v-WZe41zthjqhTaU5&|ad-w2_YE%_u|*uYl9wmo9%oxt4LRrKL)Q)CltvNn zmsr#KsUIIUcI(!tNx|#FxoootFWdb1oqYbg?Pnzyd__vQEs9z(U{vCHZRO!-ru_Vg z^!$*@yl2K8_ywwLX5-zg@~Xn1s4GL#1GziT#P3sH6=S$4t)%XU`tyO;ZkcEu(fYr#S_ zQyD#C%mR4YCEE{5sUK{;48fD&JwudH7&4R-{CI3ZjL~Zk9GHidUxBo&$5dIoq|dd7 zplbmNI7;HflkU37s~sK+`qF{ej*!TmnLDE$U`!Nuam4nCkvaT+7?Sl(z~HkJE`Pzn zh*1gW?^GOqMul>3zFm)`7|_;~Dd=t*8HcHE6^rpR2xs%0mCsRp2%E$Y@02tq8Agw@fslM5@?zqD%!{CW{ zjl}V*dteR@2Mlo~n~zoiMN_i5w&E`+*;Q^Z2+K3MPYf9{5A~etdv!=+rlFSP6?>-x z1EcnaKkvJ+7uh*FMb;({{1;wut(;*lN#D}}@qv*m$LbWYx0Je~BR5GmqhzddNTSql z{@0oF#s~9`dE=uJC-}WD{*;4lN?wcwgGe-X>^yn@4&Q|_=kqEI`4uhOLw0?&YsU`% z{D7T`0y5g6WjT!hYYwzao9dUnk)}rM$IMDjt`X^bm2UEcD?_t5zsyYw&-k0a&NSu( z#|0R3qOubGc5*u@CC-0SPVoNx+^u9v$nxy<+{xfx+~*oD`Z>dTDzCi$fil2v)aa~LWeo1$b8TN(mb36w_ZUcID-{R-DY16`(#l3F7ExA2O-RD}&PI*khQ|aq( z#`=xyiJ28*31JaC?z$)ToaOg%ZAZNHX$cncFqeb=W%W_&{45T4p^xRho7^Zmes@pw zo7K}+bI55wRLFEPUL|He9(~^?Epslcz|PtaQH7ZF~2S^BvR;>cLDhu{UD5O=xFXU544s}#QJw-9cQ;`_@!*yk3)v=`oj6U}{;`?8_c zl>OX51;)7Mw&V2$ctK*r9ZkBB7&ncW84IyY{Ut*A#@Nttp!oI`2vIkfFMB<3dJ{zcxPP*^lB9xd73O z=)FCn1ILdF#o`oJ%Xmp-`lQgs+@jKkXT$0uhoWSB7`#%DMRO(-G`}1pF~fkz`;FKo zf&B12NfbPNZ3~BEDOgM7URW$~gy z(dHg$o;-AvxicM8uRiDiS)(nE!s$f2hX<2rjYQYu(0p4QTdBOy>2{XKOOx*%L~xXh z-}$tRB&*QZ%B|P#R2WReths(j;8628rd&lShRqa9JI*uLSB~m4#8GV(XXZ!YNJZx+ zIwNV}OY^M1>xHpvFqYx@Hn>86w_+~*_u&L`LvPqfM9>Gg1DP|Fx_zRItwqjpAZ(RKSx5vVM};bTQR4t?GwTp0$1O`B#Q`9O&R5avDC z4s6=CDRV{MM*ejU#IkhV+Z5SY*Jxmu; zxJpUvGnMYv4095vb)i^ZQhe1 z#-UNBphI{NfsWE49o_J8JE&YJ!TW$h>RqJwu)E`~AH? z{$TcApY^O~J(vAl*R!5}`JC{d_KUOY;QCYX28Q2dc?C8P#GmjPn2k{pmd4Uj=spV~ zR*c;j75x^( zyX4>~v6ZZWeWiz~+A$L|UtE~L%xPYjFfWsz0SniUV5WVJToB_a3|A1n zi>srdQy1HiJd@)z5%rpRF#af-2g9ie5wqgpLOHW-*}^K^HZt2*!GkFUwr>9l0!?En z^3m?rVbFG1G|JGREM|&!9#s4Z5tB5N;-ExzLYPwaQYA(=J9G}XLKk-Wqo)^DX?9s4 zU+hZ0EY|FcIvWO)I7p$?0r$E<=PkYEFIuby*zRw0VlK!{{-TxL%t$OlW||ew7BG3* zZhvp&W?QlvyKz2coF8&F3=9}xRKTBx$YDv$sEH_SEPV{dFT!I`023le-VSuikFm-X zek~k;C{)uiJ%%ZnH$AyPqXC#uVsc@os<&5wz|^h~*Gn84>eTNj#V}({pnwjd&_C1dB*;ALleCB_I?lINJcmIw$Ivh%&G=( zZwJ!J!&D}eIp5(I4>XldAO42@XecQo@0-e5 zrgfpMSCxJzm%k}zGd)IiE+5dGu5X3~=26t4e!F0&k$=Ol9SG-(>ZULU*NluS zDWgq!RLLgX)FwaeGMS)Q^@koUIo0m9J%PRISwF{7nFrk$l#;)NRkIBXV@TANJ&Jwn zw|;QjO|@{;aV`V`NdNJtS7WyfU!Mki_CZ$-BE7a%h@FDwIFr{Ip-4TNe1r70AFMbl z-h-={@}P}?uZuzeOk$zI)5u>bwGF(ULY$3ioE25@X=4+)(;Ep0#_=sRHp$842Nyr!XBc&S*^l-jhv-xNtja(f4%`)OZ|g^f#>7s{$6W-~TVq6vBt?ix=q`uznwxFRA z+Csr~4RD9NYD@GQT4Gt)d*FY5=)`z5gp`jxNdB=)#pUPy9Qzk^e;MEx+aZh2c%fJ@ z=iwVRq)^ba&7~*CDVs%&4@aekG1^T73M?CU-DioQE{^eN!PX7ZE3ay-eFtvoUeiBi ztz+#5xB#m%lG<1mnpg(Q0_))GrxMGCL=?^P!yyk?{Z{0Q)TFHYSSEC0+>EEQV0FZ! zy?2S!1?}G4s56V9UccCwuS;CJNx$~BHM{SFM$Z)U*h9%4nEvp8Z%pe?vybhxTMk{@)qhh&RaMr=UArUiixNj* z%Mr*UIO+>ltwLa|2y?-fE~zK*4LMr6Vf+bNHdsSLrRq90WVLv&BrY?=)d&RCotcj=2Y8Rkqm+ zTEl@2T0er;CQ;=1Cgxf2(Jt@wz@;4@b!5$J0u2{q!;owArd8!Y3-DnF7iwjmz2b+r!q?B`S>aO%{O?EGk&5C-rd5ELnEyNuBagqc^4uB3pM>EYtVLJNZbB zLaswHP^@73W=D$P(C4N%G1>wvtkID7cY5f=66v4%lA=p3p<$#7-lcc+MvYasJ(O&O zH@QatFnqHXjdjh|T=EW3_z(0f^dh)uW-v@fqX9rY&kaSz<(az zG)aNxrUNj?Gs3$MTW}z>j-~V&v=vO&|E`Fr(#!ihgahgFB|TZHNZ+i7xTfgw>^1+W z9@}%GQ3@?V*y1r){|w{;Jq(g7oMa&;_+7o$iS76T{&)SnwWXD|kTo@W0y_Vj_$l*ZXrhtWNo%Tl**Ee&zM3S^Lb&HCv+#oI+JcVu>fb^%kahf|X3z3Dz^l zMtXcf=~7#W8MY4=uAVo3S=+T@-}c3e=S^JQHcd#nphH$w9eDXkF- z8idO0OLX3>zY$|NU2#yc=GREoaBHCytId6p6k7?{BpVO*z)++!@A=$`#5aM=?4KWc zOt(`RK`p|M>_?csEu?(o$gzGZ)r{1WRq4hMPtC zhLK}h1r?_$;SvVqdWf+kPB`dq(Z`X{ov@3_z;sFQMEU5Qgx>jFRDdGC7e)Nd538>@ z>5!|VeBI5YyV;f(6X20HNBM3xlbg+ugg>bKrYO?c%LNV*Xu%fc>u4q&y+n}q&nWVH z@4F)Z{V3nX=3~D#li!**FQy{|g|3witMv?FSoAPed z)YHx6+g>7E!~vgU6#4qUDDsvlTTRTod7%r}Mv!C8_Mf*&PwTOId>=_ZZw9r0iz1&j zLrVjveE5ziZesM^SA1V>JJ!&w6j?Wc!r7XT=R3CTm{TQnBI#s;CiloT-;r%f`P!Oc z0SQ;UuBhw-d>?N+wnb(C6-l{Un%`Y3llPkKhqg)c^rlMue4#zfJ-V&X7R9z~14U-* zi5nD>p41Z;{?61JLg$h2?RecWy&cjvS5LMAz|R1nm{1DP-2{d4gr3*|zyZs2z|7=k z69&2tm^4cdvBK};dT;-cm_^b8J=ut2X6nhi_*)3bXhh`sda?m1@?${BRw!mYd8@f4 zbQQ4Wf#j9sdqwhhAeo=0C*{qMll&w4ELZcdC7ZN-EG>G}C;aHx;E*zQav$P8bVioSwXd8sq~w-FK*|4Hi%X z7@wmjOHkj5fED?ChDa7#O0DHo>1+k3*jL*`O zDS(0A7R?;rKM`9Wz=UCXVgd~GwrJ-1-bAcCfJsC2WIRSZ2Cyf6YY?*p;~T6eV==zb zfIa0aMQl|tz6?DXiSdmBY@TlgV#|W@rR&L1jBf;B#lEG8Jr|5muP5mkUlw3y-!q7n z1mjE96At4W2H1Sx0>qvQ#+RZeNf_Tyz}EQYA~rJ^AFC%ij4uebR47?81T0mwy7^+^ydz?WT`9lvR?H2H%Cf z@3!GNc+$X-H&1tfg0&}cD^52}nSM%?@Tv7)e@W(DTxhZCAR({V%41)Y(}xQ+2T11D zWPiz&dr12ZtdOi89YmbyG=P2W4RUEmcJ?sGw2|6)fAJ5EC38lRUyzHx2f3tUop1~7 zk{@>%4xfX)c32V1-r0wI4}G`9>8;WDaXX4en zQMR=QeGHUTByrl6igGX>;!G=b20W%|S|ydh;zSSZGej=g)tI*BUUGN`Y}^Ps=uYKB zoi?};torA)rf~A{4o|rCJ3sr$4o6{$^%sy?vZW8Fd7K&eJo-C$y!D43rine%n7yU1 zfu07`5yK6}X{P`5P$lj@26}pcGQIV54|5`W3y_Keq$2If9_D)`+>8KehUr)j#ava` zW(H_8O>I3TA40fU0m3Zpp&o-RHXC#<^g3)BKK=TTDEkME(Ep-Uto&?bg@IJPp0h-zLR!>rs zLYf~S&9|=YNjjjA)&xjvT3_!;Isy4$peq8T3U>2$Mgu0NZ1y(GNyd;qGMygI?a#7q zzgJ^g3GrM=+Y$w5ZZq3kU&QL+VT3n3waa>_qQhGptj1syva1G?$ymFD+q}J_k*|ri zJGSu>-?|tweQ9=81V6!#JINGfur153>c?gi<@PRiG)dCHzCdvg0L!xzqR=48+Nqrj z(O@O7=aq91yqm}Qc3{j67P4TM#SUyljw?JF2Gw1@%1cap@fVFoZJ)LUWH5dK9X!dv z-;2C>xX}npRtpA^G$j1S^WE2^l1{?o+pm1_fkyHZgbZoxPrgT~@@1afgUOM9=Ec2@ z7ScN;9li$@tsC!8tz0N(h}{COJF!Fo#a8n_dE#&Ny2%)_=85$ z0@5ka>EEc6B=h2C&?8!RFpS*Zj%oi7U;IuZxw+k_Wl*`31li8=q*Fo9^0`rsFb-^6 zMy@J^Gkk7Hqa&3P|Bi9PJ}bGrT{$8zf5wvtFJ$63ynGSY)P+9ncpW<`rZRE%8 z=FqT?P|bx<`gmwaODJV74l#zp(&(fR{s^CYrvV1f5EG2mN=DN1Yu98=I^2D|MEnNi zzoKay_{pvjxt-e!o_#p%lhGj$YmRE4UK0IMV#&&7irT?4fGV+`| zhdg&QmDN8v-0>i1x6WAsa>l4~{6`~JzIf$|B4-B-3qH;LrTFGl=~KSAyx~x;MZ2nN z>Zc(;7av+e8n&MeEoWE6LK%I?8?})Y3y2c}2yHy6S2F4dZ#)@$A++##=+u_b$B49@ zx{Sy8sJ0Z$#$7yd0K3$}FHPl$ZF|K_@J~OGCiz&QKIX~$hF^9%f@9LPh9ZRL{38(=%u1aq)Al>*<#LrX9Gt8gnVsH9&w!*L5Z?QMSv_lscx2L)%e zEuC1EOo}lz(hgK^b|=i)$dlV)+GhRS&sW_v-RXhVtP*_ZDJU3S-d*D74dw{y3?6ip zZ{8M3i^Jw}^xVpS~L-3T^(MkD30h4Eq6w4e9PNu5~5u$_&t3TA{g z$<~|xIm?jJp;DM%VOQU1dwgQm0K%iDg2b~|8ettQ0orPz_$GI_tisDRhGb+^82J&M z);&FFMKN7zGsESXf3%soAydEg9Mj>JWPTV~+u#X-ndebFlxb9!CWX>yPl&i&T}Ca+ zpgC|PVpk3re%pgg%3|Y~Ft|^|lu2Q>u6+Ou_;8hye zyf%65jh>^*amaGMRY#e9@lI=W85E5E-9*RX_s`5OuJw>pURYb5rbw*UUYgYP)6aWg zIq3rr=o45Iv)}E7Hbd;e)(;GIS%9|3`2=Qh>q$$b@eWx<~TgS!>?wsT*G7>saP<&)q8%aCU<_Q`hPy1$}| ziKpVmQ)Tv2E;(^T$?A_mx_aAS7-)tU4laEF5`}AIPkFN18gL0tI`79H?l>dmcN^$0 z*#iwlnvfP)p{{DO-)u;16aRuS3Ws~(W@?V6vL0(Z*AkoDR(dWoHlvN5(g^$7SK4C9 z`X+m>XMann^c)}PZ$;8@?6TLlwuy9m;9fM)fa%NSEA?PbG_3Ibiu3>A3g50Cuy}#% z&Y%RPJV3Fw%#DWS7v)iC#zMId^AP?<+o`Nk9*_sgE7LGrZbRb+kL5%z>ChEu#B>ic z2rN@8^Yi(SAe^+g0~Swxi<)j9OPUO)Ys5t;2OiMlRLV{J>kabVJc=Ul4@~IeX<;5_ z6V7j^9`?WiAntG%tsj+rsm=Si<`#&IUO3T$X)Waez11AmO3*+@k zo>2LABKv4l)}ydEw}@V(DgN1$G!Wy^uGxup&ds}M>t89@DACRbJB~HYw3es9WFHQx zb_t?Qz~&?>P5YBV`6b)0}~A&0h1$YabCZdc(nYJ{3gv$ zztC0-bza}ZTw>r>;G`(wfp*h6SfZ=5Gp%bz$H8unX$+j8TQi!rj-_O0m-d1m_7N9u z!WBFq!d4GYw>#!jvZ2fLE$p+~5?%r=$G@mEVjv|&SZy~l0#7`@O&ao?3!{)tBfVZwrz}lc?6t; zGTU;^W=f*lA)ZIO;6g;`P^4$NTI>9bZV?T;@x9%@=IMy@VDf*~3Z3u9r~ANd?K|O(sqjQ=WxuzEg6dM? zI^Tp6E0}2O*Z!S9)7Dq~=eH>oD;(o|*t2bSj4m-u%586n3L{T6LVZe9>eHPYVBQ?c zzmZtH#>4#P(YDw$;tSi9+5}aLzmFfIA^DzdO)($7aejmMxGl29*2in3k`D8O+O0Z@ z5=VPV%VR3)&cCBXrday)J?l5bRMekejnp%^Q$&d)Jm*Dk zX;Vzm8@JB?!#nZn4;x<)3d3mKb;a0vQ2Q7jhXR0Z_ zWv5U{1TNk_bta#XS^*%7I$T=l!-J{b!c7q*9d5)-=Hq$zFURxa z7bKUwwg=)NDc*Bm#ul7C_b~j+-HU-wf5~it5l|#=2Ka8TD*HKzK*iiBCxR!}8=yUp z#}VDf*P|DAS_jU9iQh#(oYWwU_h=|^Nnt#i$-)`ss(VN@Y97PeCwkCFr1Y;&{>dJP zhLWfb>mkT+eHE=8PGO9+_gri2Jm}P(#sAQs9X<%!P&ig?zOF9!w{ldj-(5V(4gI=S zyboJX*u=u;YH-Ao?_ z=62=@l$h_vV6V7fomLAM^{#`#1k^W6F)e?7yNo>((e^7GVA^xpcY?qm$)lC}xcQg; zZ!hsUCQ;hWe)2W+dU7~#dN;7C0QCkp6`l@kD!3b9Qz0KV75I(UP3!!WK?CD4&BVC= zF87%#cDT#I;^_<+ zvWQ<|c!znU6`KctA|KB3-yF`O{8Wi8+2tr4s@zCVcEWdo z{9D~;5|l%x4=Nn-E{E~?*3*9StQ%5;3^i`Bh7KiEgKgsKxiIa90U_$+aJN;ljLT?@ zSNbqg7LaET%5y97LS6MnY#oRg!2cD*lNG$%SzoCA2=HG#sy^?#+fK8c&c|vu%#Csw z2Wi1E5P4AzE4_!<@6LR7X4WLjtV+1lmm*74Ox}#x&no7a<;9IK@{Ee{n-Dv%VlA_d zYoQY(LO`E)5j(A77iM*6w*WRT5Z^nXD|*9X)3vlGkO=X99+x2^`SxdHsmAbw84cLP44b(NpI8^9|tkDHuE<6_f`Aefj` zI{!v6+;JtG3&IU*ea=rF3gG1!PJ(bNOiyFD2LkfeApKuJUv4rZeQbc=iuBDuUul|y z^icu+*O0ye=r5a!kUl)Xzd9JdSBd`(h(EdYVL!pP7U~8s263l?uLhiLeaKI^0RE34 z?ojYmfOD z>bJn7ek}Y7H~9IV`u#TFiERnf$sEt&k6}J?4*O|11a3<48`%iML4WgVI2!L~TU~`T zH3KGUcl+VHME#BJ0l^deu!c;LE|-!n=>@DSk2>MppV6qb#zK_fk5R?sC4kx2I`=7V z3s<|fQ4sEuit*3mx0~w>e!G3d1((9Z<;7pwH=oiHLr`qu&eMJoLnCrt8?ej>oXP^EwFQtqXt$maq65_j8Ti1&y~ z`-PtzQHk;bciUmMKP0xV(fG9KBrGqI)&T!}RZfdbaa;&K<^uAIF`ePP>Fg_JsOfyf z+KP*yWOpF^Q)>7fE_Ck#^c{ilb5%NV;f<0&CjtIBD&6DK)+uyPfPc11uXkx33cWtS zKTD-cF8rE7juhaZq0;Rx?Yj!y7T_l)}FwK2tF?+l|Sax@b zFRE!OvA*3yHUtC|y4%)52EOTP{RappZwBIf4CNkB<#t+MSLBwfnEZ&U%j+)f3yLnU z2jY8JrHd}@a|*pQz&{yfZ39^`M&lFKrHZU1*n7nKTHw}Iy+<~x--$5Et=m%-Y(s>6 zx9;?25~p%X6WzL7n@CLH&E(c4Y$AQtH~AsAZtO-99eB%g7oA1}G>|V*-Rvfpy867) z#lY&bwNQyaMCIj;pfi4l%eqWc03hA4M2F$VV|{3E!OylH;%n;M%BDsS#@lAthl)zz7<&H#&C1dPllxNm&N+( z>q~dRs=!Dj*j?%a|KK&RZzQ-a$^B0w(D^&5_D`K&A0F9~7TnGLr!j#maKMXvK2^&> z{9iYM!()xeV~OIB5+Gp|l=l~W?CipGeC*U|^%>LIc2CB1<3p5nKu_ZIrJtmh2(7t^ zZbnmRn*>8348t4T7c=RiC#E1-;DM|=Oeu5> zItBo*Z|oa(X{jGZ5+J&eO@#kr;KGjV0m_8pDID{N6#KH%LQ~CUlaEbp^i69dAJ@am z2GbYw_R%O<)7XJy?~A{ZHI4Q==mA%LE>#SzSC%7~C|Hod%)Q(Lb)nP3LP!i(2R^FR zb&nkA>s6476U0UvoaVB#dU*FoH{ zwj*8l3qM{VKi1i&IpqUAUYa|{p-`3=vD)4&C&OU zrH5sGQyCeXueOEg9fvuF!^iVkupg5ssoOwm-OpPZa3J^)k}TdWUt%WSPoIvY$4ey*hlOx}ykzZLg5nY0z!;yX^}^u1d4h`adr1~_|u0iJ7}NgG$t z?8}~{+7n=3Js?h`6GU5%ndpHcj2X5ysJkT|GPZscmCQ9*?Cj=`wdCDBaHlA zO6-zP--4iWiZB?g{zkJQQzPogM%?l$3-diw55Jb;MDgi*FcH20ZKE$qJcu7KyR8na zUttI*+HkR@q6%$c0}Il}s$d~C6xQHdfWxayOd_Ht+r>@DdB!E)8^X-w!uN)qwg|#8&S(u0I$N5^25^QVF*7}U7V_7I!j5?#P*x?YtqCO=3Qm;G6v*?-apW{{(hD{7n?@2$wAu#BNT|E}sK^h9dmoPnxi z5$d(KS1-kebvn{qy)>{d_0}?dLB({9eSE{dzGwR$#kYIWwz5u zQ+xm$XttqN?dQG^;f{ycf2%hdzhDLflN=gn-&hNNXYu)1iv3Q#(ME{|C5*k!?ysK{ zZ8V1&3mFtRkt2MA!-vnZHP!xm-4TN1=Ah&|J;yn%QM|F1MDyNzBa)X%EFsYx# z94aO@Sj@D=HqK%k4>Zt69M}L~n$78oaM0n(;N!> z$sw6Ju-XWxPhgS7I6=wJyIjR7wZ@ZonL|G-vi22cxpP1D#FUke&o5na&_fP-o`12l zB^+P3!K3^8Y3}T{6>sQ-Km$lVB|6gJp6qwJ$eSMfH(QUQQqqYOWi5W&;#^Dhc+i)jjl~ae#S@Lb@oQPHZP%Xd znH7!}bSxnJ=oI_7jdhurS-VO-nqtv|$-3U172ysH)TCE0=Z3mt@=E8`l%n)kF6XZB zWc_<9Sq}Snf#s976u7rw>TOrT^a2URuDUFCxf042SO>^s9>rIwRFDemlex!Tu<)Ib zr=~@ilq!DaT9W6nn?N4(7pBkRLo0(a<@qs=>SqUcQEi2>~h#jp<1iD z-4iRiA-@Wg{DQmSY=1a6zRG*G7wrkK*84%p3G)%I^F zZhjk2$4s(MBIc0Knb3OCQ5xNsQ-cxYswvS+mrbV>Y9YWZBZ)cABH}b>1Od$oT9F zv~@d0ZoAcQVP8t|N|*gtccA=)KCo?SS^>`Ruelw*G0K{OJfU0kmYcbPTxyW~c^^^y?#a{y06~u%U zE^;ccuqfnoSL}f^_ER+Ahd|e_e_a$gfnrfaPPh1NAlwfaPX4{JrG7<5qky&+xXYY3{ zT}#Qj;Iuyxj7OLfYx=oIJnIa8Ivpulr=9l46dXoBU|2u(q!Sw@WqYakgwt*e>L7f7 zTm0NCklfXh!L}a~l^&Wf0=v=TVO(Q=Mm31#=f`G^bKCC=to4Bj&XHYO&9@S4uZf69YVM}xw;g(4g93QJY&DoKsbEQW8Mk<*fh7- zH;*fhXZ7$2J`eM0mUnZ-37DuQ{T#k|;%5?s^ubgur4|@OJqm(znnS|yEfwEdLtyrm zWt8BYLs3;Y8K{2j^70hYAA_K%5&ht>MZdsOy7Y1inFwP>MEIP3TJU8+B^H)&Sqyj< zN22gstfIT4F<+@H!gwtFLUtGyeQ5SS(KjxJEy+-|Upq-Rr1;1o<{dM1VZ2aXh?%706NMMKOl3+9&^iToX=15y#Z{AL99V-d&z zr*SDTZBWPBG)rTxPDc|4aCj?i;Ilq=P4#b83=KH@wOT_M7e?tU_wbcGdt+<8#t8E& zjo~4x_=KdZ0mBh0>*`h%psmx?_KT8R+J(1x_9It4o%>@An6Y!3X*SPFWq{GP6|)kNn2;5vt8>Qbhc|6NtM8yvo+{!cOTUW zu6Ey|HP35gT+f`Gq zNvF>&WnYn)I0y`5*Ek+WYfY=6G2t3sGwr9=inF%5sR{{c?rO2 z^h;h^dshha!$fdcG@E9wO|1MpcYSSo=+=Hu@XLAj&058c8|S!O>n)i2N)1`&f*rj4 zlqJ?$hJHG9A>`ZB^wZ&qphFGO6MP#`F;A;T_*}gG5u$Z2w_6^aEa9!sZ3(_*bpW;3GbTMf1l#R!eR*~wmo%0stRW<9)>n?RXb zp&4M8)TGlz1`XR;169I7Q~YnK?3Ef=-lHku*Hreh`Y8XB%3f3-`Cn4O>?T8)!b3qX z>f{SM&Lof!m;Em_{OA;D9^@sR;IEo;qz+ceDuZ9mFBt z+Agq{xe58$W-Pc{Ueyg%MSi-Izo)|i3m)s*O(*>nJFJGufC?M%a|uPc+0R$Bn>OL1 z1%LPon_dI!jzup}Oa?Rv(%N?5WeQ;ZsP!$s7F-p}pIl+@QCKDbi&TaNjdxswZxXBO+sSD7kP z8>9m>?9oo^e7`W6&mzv=2FS|_1w0!GpY9mCXhI14CVuuXqdWz5$JVp~zTq!Y+0)fI zgP~SD6_M4aE@!agabS?2iYV5?3m7xga$&^WD0Wx1Zfs~v99%)_gwI`$N+DG+=@k-F z*pBLSs0{2&HB6#|rlcdO#xLQZgBEEdsIZ|R%>a^nI8fYrus??$AS(u-YLS6$%x+^7jUv=P$AAwH+m4Nc9(-23sq*B>A zUVrCRQT)leAQ3F9GUi-T>cMpIIblA{}O?J~ljl~rTWz_lql z-SQCMlTO9Wxa@9c1^5Wc>ga^MQe;YD=sMjF9jn=Dv|WLuR7X0B`(p;$BNLsD;sKCK zTjZsv=c10Y16tVr19e@oQ`U+{u^9y)kO{`cF~-HQxzALO zi<%VmMggwDT0DtBHia>lhdLe#hG7hi#e@}Usr7FenA&@II=QdQ(xcsgF(Pu>J^ zg11!~T4?^=$U8voD30adiF^f~gv!X{Y(HqIp}B5hW1y)3uPljY!Dt$6tC>Xbj#?kP zB4q#mYo1Wy>P6sxw>N@!f)PlSe?%a^)f>T^Y6KPkj|f0Kh^~)aS`2HJp`K9w(nS&p zUi-nRxeOc3_zU|5kiR&UfK*?;Xu21^V`1z~@cUA<@Y39Hc4jp=#a8Z&k>6`z4^zAFtR$`vf(;D3)_m%y4V4d=}YV@pjwp&QzEYkri8ctkrH8bFeQSh zq(uJ5|4d2ZS;#ERA2qww)WE^=Q0d&oCEq&OQ}vo~O6l^RVPBP?*Ryi40t=<|N>H@C zs#l2>k>W^cNK{>f__{`~ItvWRk@BaISEk+!7MQE%T(mWER+#3esF>cYj9 z3i%Vq?j`lbW#O9!F4^xW2ftWQlK2M2`e{g@t~J-geYRQm#$M7|Y-MZhtvp4EQMHf7 zLx21X_QwWAGk#f6Gk$4MGvWD2v5%_RlZs|1dNl(LW-A(e@h8PvP_bzW+4hHGRsUa# ztq&+R@5f}$R+elp6`#ehQ1~#fl$ZQb`uyh?!7)T~2V}3Ec_l1e@E4Kp0_y`23t1oIj4{*pG3_p|C1GbaAYpbo;E-prjH zDK@Jrgexk%{9h{2N?a@cq{1@}RIS^A)nU>fIvD@|bhxixEBdzx@EJ(|>N1VP?hro- zdzWc!;F-5|nXKBo%$#X&{48y9MI43LaMN_Q;KL8o@tkBF7d;zGq8^i?X@r7}A6LzMZ;y9%|PZGt29ZtcZ86lK=l zDEu;}Fzm~s7irz=J>c#~*PqU3Q^bLhH#CeZZ$Vi;M719D+Z*k0cCW=20;~MO^)UGo`e%5EGJW8u?DYs` zg4+!FY8V*alH-!S!p>K4{Ji$I1nb>*;C2(3J0QFCR!_yRu+~fXHHDh64vpr5hCU8f{2FRjtU&{_-eLEJh?)3plj(IWzG1-s0!JQ)aE6mH{Ht7{ z=1bk{jOAqPrk|G|n%T8-#jaCK{Ko7MCSuR@#M;?2nZ%cHjxc+#JgNhHA1gzyN{&2) z5wGM5Lp#a38oZCGtOoM>RgOFefV7;O+P4~3k-~&mIFbVt;U#VfI)>aAF1*Z zxUCv|{nzgLmUP2@6#opzzpj2Kc`%9)IMRjG1ss@i@B`byf&=nlF*o%I2eH;(2&0a9 zYkjjE4quMgY=?riJM3O~-hk`mMSCbg=m9OXFJT*urTbNnL9<`?LXUK+M|;zsBh1(o zVSm@o_lYq56|SXvX2zy4e(5#SGybJ84>?p;X$yfPL65<9$79Q0`e)qI#*mfEpNH$j zU-v}tS30c4Al0CmQxOLaO+cxBoO)yU0Q8KM`ybH59vJ2@mIkFSq z;kOyzXK=-z*~#`=gO<|Ag_Wd)6EDI=93co#=g2mEhu=ng2XPIxko_PxYnr`K6J7Cl z;!+5YbEFIA zXH3}EI2O+;fUzg_Kkf;O=)EWGY3a)j6B>xg>uwt~bVarOIh(g;3N*R=fv~JFXf`PK z>*530#1y7eTc_U*4>Kc}tuyp-;1>xl8k*&RdjsHirh}P2OOq8UL5MA*RID(7O?ANg ze4HA#vx>i#Yb@FjJMxrfOgVQn#)jX@@9Y*FD)AlQPkk9@do`^pR6yT2(pi7&9rPo| zUbNvvm=0m{Y>J-}nx7R0az6=?+j@j2t_ZE&@(*3o%A5SIE8x9|A9#ze?~qSl6z{cx zjSLqtQ)da`pGsv%*Ot+x;FA6;NA0d~+1UX*WA(H!HFY%Fah7*ewpJE!n=x!OtCJXKnm5m=e&B0k^%C#?W$l%Dv@WxuM)xURZ7} zUs`S{uPk?zd&^tOkC$I4@35F-Eaq5?8Mb}nEav_e^8kxkXE6`7nBy(xK^Aj@#hhp{ zCt1vQTg-p4nD4QelO4xHD$V08X4YcnEanu8In`q3EoQyNoMthnTg>-b%o!H*V2e4^ zVjf~K54D(wS{G(mc7+{8*)VYNffT(mbQmJg3q;*J7SxF+c1zKVm8Tz+x`6 zm>;*8r&$V}7V}Jtd6vaI+fvwUDOg@?-dVU3_tO^odPN=iVylD0O%@@Zb8scP*_8M>wqM|SPz_yp ztd6T#D{lLjLM-R%47w^xbO&Ay4z8chNr`ppJ7ja2aZ7&Priucw8cB6V(H>wmmK6e0 z2FUvgQYgL`KnlyufiUkXh*^9mfSAiHfElMTzz8OF)7A{gZM&n3Nf=d&`GNfX9 zmXr4}JyJARS1GOz@K&nGCPd^&uFMgLZIvR^A+8AUIm%iB$T9_K5tjy#ma^l3oB}=m zsvyV3X9LLbvI~Ih0%W0rTo8o-a-pna%hO7jVg>0CpTb{@jk1{UvT!k5mOIip2saC< z4lYKVp$3EsTjt#|v#t!wqEHFy6(3Wva<7Gp1*w?7lhtss;-p}>SPK`oWw{b%o(jf^ zMto4>jI(h4b*Dlsrx-`N24&x`^7I$)>*eWh;Rc{y{XzZ+6&@gF;RDu(0TxaN^05dr zRZu5p^oG@yEd|Z;0pyWZw^U5&#lkJzKnR(R(cY~F9VjN^1Iis};o=d6pgI+d7yI{y zjkj=vf??CKYC5<d%A<-|w|>dWicF1a4LX>&5N( zpy;i)aA_EKAB?*}#nVK0FP>)Mc*J#xZ&h(#tm(yh3zvcTD8xTd@eFZGFP>rH2KVCc zs`y~>onCyfh0E;4-&FBTv7#5xv~WXuajS|C5nt=Yhgi6wz4)stK2&_U7awZjhV|kv zs`xN*SuZ}!!VO0}3HAT0iVqi`?Zt;%xGc>3B*?xJ70wbD-~;A;mSWojL-9JlgEL}X zdP!OS1IXy$CO|Q~5PYBD;PODm-|#)q4?>WO)o!P_7-unPZbf<1L z93PRex%-f1`YCPunGCQaE=Fz#$XB?nU4Gb=6Q4k03zu8S8TTKU500k5Uz@bQ&J!j+ zj)>80G@7R=egd%XpCRez5AA$m7&}$cr|_L4;@F3!EeF_Hl0I%ATOgT2p&y~x$&!9T z1pM!O984}HQ~=oY8?G~sY(sxGU(&Dsl_>)xd&~uPf}{n15%8j~{))|$nyWu&PQmY* zxK9)x*5J2x_%e&F51i^*vw=1hQrTnrm88(E_fsYFX=?$DEk~f2$|M79y|hlFGRuIg zbp}<^^mAs5e!D!ei8f85hD7L7Pcu=*gLiTc42go>5b*DkY0U25I&s9LIW78S|L%N^ zOQQ87n>+Kg(Ib=cOf;3m>GNt02XAMFGJS^h8J@aY`=dW8eu!pG|FfGUJA5@O1qtc!9$lzZh-H;9||plq4fiTaWt< z2Tv!x2HVy-2d2=-_nFG~apr5S7vM;kZC(mi3g%Sv7|TY`Me-XDmKtm| zVBDNZm-MGicK;NMF7#(`OP4tT?hTc}=Xfqv$vwcthyOCf!7cDMQogThw(W`esz%_E=5n+L*LW5lnpAqQ2-So;_NVwrM;QpZ&`f_EgRK(y+9| zpV*T%>qU6@j{T};y#*e=V!y0ezZxFe*b_DDUxSAOAc=`cdvEXh*TYP(XU*;dF_BFC z#6`RCmOzT#1MlHX{ES6)pd!0deOtJw3Qnc4J5=767FB?ABjEMIdlVDD<`)|L_k&k* z*!D@=#K4UE7g~GTZ-pIZigl?xwZQY0ADk1gwJOg};5p{E;(iV6l`3*R0iHH=BFoxT zp09!Dkl%U$dEQrfegd8Y{?>o{+08X@!ripr&&1yV+Q0p9$Fn*vgOR5<>dnl0CSqeE zt(`!%M7=d-#l|GsG@kNu3o0AI_`PQRdohrcn`zVi6c_dOC$NFVQ^(fTuReeKWcv6yKT(sFPf5%y%NN?ok%9D;APJqK*-9PFHR)y`OvolDEpnI zzU4JQ-S3QnAU4Z}ZDq-6n;x;h09%AilCyqDv@LVBhi0Fz85f;#Z*tCR_HQ-Aoyi&Z zj*G^Z=W5mg863waSFE-aYu|dYApb z*Sirl?1=xX-VK9-2-Lf=!Fo3)Snslf^=@>q-i->@yAl6g@9qIHf39~)>bqL+pu7jE z?+X`gf(y^!U8lakw5ZH_7T@FGJy7>xvUSSO-UWm}-TMaYTabrQd9dz%>2Lkq&qk;` zSogm0Tk-5O8>aGL-808rc(}E*bgZ(Z3sk-5YQfAIR4Y*{TUe~q<`f%OT6a#G?wDKgh2H2## z>sxGLV1ebb%Y}7q1<;Kb9lAq$s?nEgVlT!|Rj|yWh;Gt_7@yFK36Cn+kfQusqysS_ zz88}oRGlP4?Ku%bhqTLWf$`6 z7)>_Zad6ZReKymt)UW|M9q^j2rvI~Q=2@2=Q~zk)SOX>=wSB1W%xoONL{!2EW;a!t zKBA~T&XPW|C_j$0DDwOC#w{4@&R{-NbOCckJ@Wn%gS=%iWEb)ZQN6slvpLp-> zi@b;WkOt(H!h3n;9EEqtpLiEVBX2}BsX<;jw3nA3tMCr}6K{QlqHhGLQuL*Jd4+6+ zci5kJe+g6c4I}HTA;bK2Y8{YA)}0v(`ZnfI^=)Wf+e*lB z^iO^F6|zW?--+^-+L&3_2IVo>3WEtUUrEpPASPreSSEPzp~zgsgsVYJN>{5I^b}+! zLQ;FL%CcSwH`EFpGMTEx_j@oL&nwt4=StKjV0B8ZW262^vz-1%n&rQ!X&$VmIa5*ar=To3Nr^{IvtH3p4q|+wf~jdvR`mNJ zhzWxfY>0A)Zi1rUg&-ykR4_Ho{gwF61u=Pmf~jfltHk$R5aau+pBJQ=L@LppMM!A| zgns{Pn!6mmQBhAuXYP(`NRDuN!jS#sEYpGHEsbE|}A4QMBRy>FGGh)KYASOjC zSSFr2Cl?Ttz6@e=q=F5x!YNe(n@sS191miAgn|vlmYJMX;yV_^1g(M%vz`X*3njkK zgP0Ur*H#5zfaTCg@XP_aeyZR{dvRJ#JB$LLykV56miO*I(hgenwyCneR%uf$hZY9Y z-l)hs)GO~!tsMaJ&p@=eXepE=f)MWCi!s1^N{J`&y+>fwXgf zD);;UNIPiNn|9%xnsy5}N^RaKlBLM2>y7WbKc#&zVtj276VCi8?L1xU(^<@g#FD0>bHK?4*kn!>|baYKzvrK8{0#E2O7UAK$DKv>TY$D z-+(5+8=whowYojG$xlF&{u!Y0M{0E|Z;|g&-aA0UeP@X6(^_4^P4XWMT^S60sCLU* z@~s`=x9h;F0LBFTCtw(u24jM6{5hQU6nwVISm=m7FcuI#tL+^N2nQjr3|t0QTXF!! z2UB9i1t^&2x5F$5EJ$(*ih~F zfVq_TtU*lLt6;cfLZnc~KM_yE{P0CKKb#bW07WCJ*=-ry2TySOcphfJ+W8E6|;KEiS=t`H@ zzk0%s!I}!&BW8J)@%{vrC!N==9uRu)tdP+CQh!$@=e36?oJ*9w^Zu6ybsA%6(N97?d(!rD4FToQkG?_5vlM9R^j|^{dkr zq#ZOK_lb9)4l$D-`VW;0D;R2RP@VL* zBBJ83O!r+Fb%upL{Fl=ftSk7Bv!i%)0o4Tfav0TdkVg#}aWx`;S+^-FaKnp?jN1(O z)e9hF+-oSfN^wUN{;h+tc0cw4Qj}wh0i;=4e`_SF0a2)UpgXXtMX8K#L_seQW!x=A zh3X7UJrITLL(K+3;YyU%zhZJ{;2IfsO;F8+z7AuNV9%<+hhCtDY7K5on&!=S403rJ(*^v|rQ<*1-OPLd9ZI?|hhqkQ&MpA(T*-ipo`eq2Mhd0*0RiD^P9X?wJU8 zzeH3li}F8X=-tQcO#x@)FJt0MmlPl9B2?RHnN7Kl7G-{6aLKtWtaKZ=z$^5L>UX^% z@Y_h(xZdDOl<%_r_rHBC_lm#_Jh@=MrOe$tYj! zfy0c^th`Q??{1WDDdY2W-f?0xme@Q!3U3U-% zBES0>-lY-wT^fZKr)vhEqV7&PV|2PH+n{@%>+x0}l!bmoxLB7nWv5fFA|R6(=XvqF zA)Udp+?jUwp4|*r3l&Ku&VnP8c*OYE?svDmmds>0?Vn|c^}8V5LG}kfS6nsMMwz5Yyzh8}B}rtB;tGl`MWk0vuwSB}b#(GBp7iOG49cIG!o_!Ea4 znn|2E64xUdpwA6M`uq^tgkZL8L}eRBRJLIxE><*IzOlpkM(l!dyp(VHa6>hT>7#K) zofSNf(S0rPoQry&x$LKM$KTloj5|b;~Q(|!mjw^CEN_sb_k2w zuSv`pRb82k=dr^)pFzIB4aG{hnR(|4bu2^89G!6%!xe^cBX-`Xk#NZ{0+;N(Nz59J zJBgJycDTF|Svgb^?j#5xxBU!5oirNNs9Oh7>2#@5TOQUiKQG}LN9mYxH1-r`6K6>_ zanf?w#9U?*9gx?peaH`Uad=mN7@x&*pW=COV8|w7D(>IlUzhN~(Fpvhqw%Nx8~iI0 z{cK`A3t|4^z91?cgBcL-XzW#jhplRxW>;2*CXb*CZ{%9eUtSV#Q-v)-lEBV zxk@e#lm*x|1KdH#Z^&r_MY{vKQ?G|`% zR;|HXU8I7eR;ClGPRo2z{z`3JS%)CXIdidJEZ)bScP>xwo8^ky+mQZ*qEVAt4UhKz z9Ni?fjaRHa^wR}x-IXb_n8nfv&~H<^b7-8S_Um3ybZU-I4XXE@6}V3{h>Qt!YEF*1 zdgl@Ohw*=rogK@ai9auM=Lj(!2fxYzYjkcMN@wq zFqLP3c{Y|?n%mnSHr}Hw`|9r%C`N*J(hj_Si$Y-FqkH~h;Opn$Z5oeHtiu(M99N!R z=I^ij1A-V=nG$~A_c8_tfzO`%IGfGZVfU176_z+J>(1W_d`g)9V-p264gEQKd(m0* z90U%^K6|AuR~GmaOY+|ng9*P!TH%2I-HCLN>JKK{DIu9&J7oD_lfv#&{OeDP9_A>9Yy$f2Vgg@M2G28w?e4@TlipD$_3fB%!11~*yfi3Q^5gbNG zTitlCw7x49-y#FUZ*KM0Oh1+k%ioP(wZ zzKs20LI2Ln7$$ui21Q{SUakH*P~%R=v(g1)9hbsAiLy?Nz;Kb&iI*9|-@|`q0sqCY zkVrG`Y7!gC`WB1N+L&W+hi)F_`CJ5Us!~8k1J2F)c{bCG=Rheipb^ zJ*}Fy8UKrtqbgtdYL(pfB8TTOmp%O4$|PR(q0%NAbhB;>F{CyB$+Ao;&#;SzDy2f$ zT2-WGLA;$>RTPb&O{uaKX@KKg&eG08knvtYpl`97;IF~`0}>n!c;l6a76(N``_?_X zZL9#B6HY2h4~M+_@NoqH1{LW$SCI2uar1hsP50inOnxOSBds-~+-6sRC;L1#g}{=1 zUNnVN_Ia9en^_TMo)=@aIqzcWXIgEHuQ?2|SZ$EvqD~u_*a9ie{yb4Hlpgjs?<=-K)lSjdjBU}sfmB*?c&VYLenqokq)DgkZ+c4~+xC^)hxx@O&Tzq( zdx+mG&g#(MCW6&Z%rAYZT zgH`~dGM#5oHJ}rKK4;J-s|zgd>~yuC*t0vrV!|{5dg-X$SMD0-(N%PRxZrihV>M^> z=vI8dc>E)yqP2RMOivL6nSx~xbWAv5vuLC+t|hctVx+LzW)Y-Nw9OJLg)}zH7%3EE zvy8QRoJSa8i`B!5^(uoFNh!2?h$2}EClTH8QdnoRq)4H0HcKjK9AH@0pg{$0XV50A zXIcy(KZAAxDh1TapuK>$0{S(BUI9dSyBT!M>X}P;yBPEyAi~?hpw9sjUK4}*0TEs! zLB17nR?ppp=$62EfP}eO0uulds#5|J0TS*n8Mr80D$czRl-evds|O#}O6hb~&jW;3 zEv5Sbz!w0nk-*!^JsbPYj^uKW*)hJ;#Gpl1A5(na zKPtZQC;Q5M!x{Tj$LP>Z!BphE&MXQ#MF2;ds6pMu=xD7yOt0oJC=(DB`gR7*1Vs6p z7-X^bu>5ah&?0LO%fIKJ@-N$0-ZPwkk7_USFNh_z?w!I}PwV>InOdhYGFt0tmVF9? zG67NcItI-IMA;`Y$YMRsvLDN!MSx22O<>RpK!m4eP&FXJQ!;3i^)%B)8H09OPlN5f zou}LXJZvwfk-eC|ul)2d+oy|ueyiZ@vl07tPPg~D@(iJLsJ_lQzj;=wuXBvyuNXAb zdX6#t1%oWsbBy877(@;0oJ~2@un-<p%9DpBv`)T+#en1&0{Fxt#TqZm(w~zsUQNO$kklvR-n&&M0SEFEP#!GiW9t5?LpM zEY?em^H&(O2oQ-nz@QZptz9m`f_B_Q1Y0EPZN0$3xSnddb{?2BJ zM!a(~CGss&Mn0(ZG0ZG76g=a~EF%LX)5wBIGB%Q4uvy}W%wsICMF=uE{67Xl4lMnk zAQ&(x2?j`_U_p`v0?rDCx(PuhjRzRGlRy&i{S4eo;8uW(8Tbl;R5c43cnsj&7=ZUM z@I3+vcRm9@Cy;Q97}!rB;hG7AodkS0A^%W<;|V70J0v)PU_!rLf)fcQe3Jxg0Y5$oail|74TmZQ4prQco`FQ~ zhMNWFcaxS);;g|wZQTYqdLY`rn_9Wn8e~T5B7-skZN;~57&H?Q73nL2e2diZzJhke z82h{g`ajk_FOmMo+2?8Lf4qHO68%rG&(oC$&5A_xym8hbGo-;09v9go**?5}F~Z{t z_AbO($b#32%Q^$vLVTaLcY(y_I})3SV|?~Xd=f~Ez9BJ6AaVLS11$jc%$GgP;6;Fm zkDwS2i$3J1kSi6s>bHsUBg7T2x(%#w1unLuq5mV&iS z0BUM=@JxVVQ%bH03sM6_m&n4@0ugXNJ;-MQGe#Z)eTy{sbWpCJ>U>IqWAZZ0@^L0H z!CZ)ivV@J_&Z#PjxmmD|i75}PCH84mQ8!0gL&Q0M$%tnn$V9Y(finqY&gah=3>hV| zysH=p5hXGU@ShB179i249JT-eBn!Zb0*Fiikeqggun9rd?tj9-og@Y%%CuSFgs`B| zW|@ot>fx23m>1_ zfpP-JBI!Zg;~~#qTjNY6R((sSEdg3^oVozw=m6-f4Ubfbs^fPQPqo`@GBukYt}{v}f?_ z0}j4tAz+?23BS%$j2eoV#5|ln1|9;)^y)YR-z2cKxRCRe8nK6Eb&b6e=&HFdBe2QVdm4RB*sWd zL~uV?k_@|4hTkw;%IXMRcG>baC&RHkih!~;GEE&^&9kf59`v@wTbD%>TTND&^G}ay*lhHue*a60L zBV?dc^$#GA$`&8 zE(_;U@ivRhrjolX2*}H;Kzt3Gh_F_vJ{hpdWpqe2iLYD5*~D==Wqi3&cPMUE#u0^G zh0%e19z{FvqrA$ELaA@D%q)&OD7R)h?~(EcC~UQ6k|?b#2AVleI3dMYSPYbNoIXa1 z$)^}}REUD3mT6Na*evMyBS50ff?j_d;uT!k)5@SvAiB8{4s7qZ@=R-n`90pO7-OD? z{$5JinABS@*B855uL=rZ>v#DT{ouL&w{uqBar-J`dB*(38y0(%-25`nyyR31Z3o3^ z530+w5p)?ZaD#QdbU*+?vU}APkqMh*RBi9m1LjN~{mhO5+lz( z7%7Av1d&w~L~~8Xf;j~h2$pA}{pVZL&GVFidJ<*rnVlIAcNn+&DV5baDM+StX z?s@S`EvvG+VG%22~Z3IYu2R`mJ%>A zoYk2zzr**AD)gkEQqZoG`IYt$WK~6D?DAL>*26O97n0slG(ET)Z9WwmC#f5|V^O~d{Hm^9H;a1o3Ey286vF18Z;o4+VHfrD*W&6Qsu(`i zg6~1En%c3L$IhxVbr@H4;dwr=q zerctrNY%^=P2DjnIcHV z(}b;5!GC9PCc)%J|5Zw_BKT{-UrBHjVECso&MzcbE#iBk$*k>lp#Hdp@9!dS#16%p zfVNg~o%JMtmeL~c3AndP?);Mk^MDV^g;M7qC0H(s6X4*As{5{UL&fSLf_3*^w}}(` zlIrfhZiV-PwnaS$n#)A9LdHzqL}yQgh*_M-+?fBCV6@qZYeH@T>%i9_{-gsK#h z&$6an)E7>Lp-Asb>P?p9<6-2I5XU%sih;8TJb}!%GH@P1_J(Xd0~edcbjDdN1HoCk zo>k+M3%)MXMe7xX(D4b_)Z@&EF~Vl8Jm7fiROy-ajD#Utq5=N8x(wDmHo9L@~dqf0eP~ zVav)n1^C#R`O;y_*~9T$53jv*Az(0tp@G=`_3)5(8rd-a1n?z}kf*5Xy~c4cg!TJ= zM^>;QXZ2!dK4S-V(4A9R?J4>)4C&p;;`ZX$W97_Wn8ghEH;1nYN^o^*9<1mMyO^;y z6WwA4d5&>GF~c`C@xn)ddknkMFEEZF=e`f09%Ew<(U8Hu3 z?tJB@w|cyDgD2Fb9sWe{n=!<1(bst6;uT!vdCe?RAG90t17$7ajX7~}RECEz00dzj zrf0~G0vJnPi#P7)?*FV3GclmCMI|no1F2_1T*rc9X8S`Q(#ji%*{ zDwHd8s9ZSCh$YHF3-r-5)Ku?8rDvmz%dWx4vMXd2o4Z#YQo7!Zt8jN?&z$f@J+3jG z#;wXYwKyIw;8Kg7+!_oK?MfLi5KB?=NEAODrHDkyhoewvhNu{hg27@@%Hb&3EEc62 zj)HrbotI&gN12dgZu}h<<~3&nO3gJ{I8n^T{he7j$vfj3)hXvF7`PIOW zpJB)NhL#u0pMk+EdJs+D2>bohd68I5Y+`~c0>l$R%Gx=TC2}Ch zjCu|OA19E^?sNuj2FMKOWClJ>AhB#@AR2>_8D)`y7~~nJ5$*&A9s@Wx24D&U-y@K9 zy*dVePB63C2@LKhn6SqX$cD4Vy9r$*!SVP`Mk+BV8sQNR5A5#7>&KD??DlK33rIHMemdEtoB3vuLxx74l%gWh( zJqlS6gBsiqc4c6HPFdGL6)aG36)szd8VJ-s4f|vCr6C0ZJzkCR)wDn@Mf$ynlp!D- zK%DA-!-{Y3(aI`k3pKUzP0a?+B3TjM$SvL9wrjb`BDizx zTK?hkB|18YB5nUJ3tgs%%k9X&$d3H4^n-k0?bCfpfuBF^Z%M;1B8)9*LGh;u5H~NR z1*#}Av?~pdvr3Vnjx^PqVeZE*yYODtX3k`Z6{6Pj9<9oi@MisZzNm~7k{c}8$m1$* zL%EjV-1%hOswP_rcQ}g^lI~w*!$z0Is=z%gJ5O3rOXZ~O_NE0&SawZmJvbKfiUE5* z5^t7UDwEU!3roEt%_hz#upok5zNj)OCh$Xou#?@m9p6jo`D*+87;7Tjc1X56mlL3%^KuNLw8pMK#l4KKVPE)a)!q!`=AklF&wJu4tXaXIe zv8_;orLx7?_J2jU`R{?7JAs5scWg`x3{W`q3ouCs2O#B;CoOP=BK;c>Nk<0|>EE6f zxI~f0^=U!n7Aex$ga^17`dUP8MWk>b^i&%DJJzSE4urFo@J0U{UYF^L;+9~#|I@H7 zN=Dtp$6?%fAnCnLD~H@ZV}e$B%XZ+1i(R#@?8^K0w{EU9@^y>DaNe-xsyt^&TXcEm zhR03CT+xECkW{yb-3fs`McAkm*;Yh*rrzE8aVPDWVsBpf12>Dil1+4bi3=q!zZH0g z6>LqKpzggK#%o8??iv3}H?c2@hSaqG$A@=@3IwTL>$*786fP(eOc^|OxaILzGSW;k zp~`z`?T%%FT$p6C9b3Jw#8YjRd%>`8?Vd%;_00HLR~;+-DsOzH{)56+407;FT`O)FlzBhGXhQ@&M& zjY1;cpZpR`R(b!pcE>Zcqicnbi|6et6V)sqJDz#3%+R~QAGNL-z_PtrW!r7CFEDA5 z`q|!3!&$j}otXnkN+qA+D$J=|!sAMSmCfUq?9$N%GC!@d;G(}A7!y;%Zqp*Z?%nW7 z^^vH9e1punjw;G6(`kewQ76?fTK*RXp3vNw0?C(IaUa%|1M31+Oe4zDg7O)XnuH!n z3zSi$V=*FgBsF;?%_SBdSO>(uJmBG8Fb5@}(wbZ{Zh?+~ zY*pc1P!8w;o;wEUk`G{<%q|pCeD0Sy%fwru-f^>xCGZ#8Sydd%%^XUrV?CNqq2t>0I z-I<1u5Eo9>;0TY=mKHd_17K**P`nKB{sn1)TNLleOA98nARruYl%}bQp`2NXyy_iN zFtfa|>~pmp+wkTsd4?~tV7=WKxY7C)`n_=>r(5lQHrQ#FDn`8IA*2A7+$WQPKp zZRg64{ekrBlL6g3MwofUjR$eVcqrk%^w{Pr1 zcqwCi^dAailjGq5UCPCv42QX#uaFw|z6K5~8TQtv=G!n1kO`P0&sxM| z4#+HT>sx^$?;G$H;yy~p$$5R@Svu#U~jPXDdA^b z!Gj9N6x_%fY8+_n7>wc_2Z@E32Xs>uLHSc)VF$4gl>Z9BCMnp2;8Rj?JAzxKpa(&> z6x@MQIX6=n)piA&AsfR*f$+5byRc|yl3cq~6RPSED(8n$Un^YNuY=07o@`$#U7G!@1{jc#OuMb9#sapH|{ zAgaHl(_2T1HE$V=w@F0($$QVIqyEhIa?SB>SyQgTWW~EGbNJrpZ=r+in@9cQ`?mrm zRF5F!&`@XA9AB!hw8BWmHoVG#9JJnt7JFX*ghJhAW=QOQ2t! zMgwft3sGD9#EKw4s8J_@J)|5oxMYiDHcOww9gFToD!uBbgJxhfnqTba8fHjrz z>on_Do{ge6iYqz{H60n=ivBA8^2cS3YXi4DB%JH|ka42VzDxzrljA;^!c|m!?((i! z*||#hCt2VMOVdy6fERM`RPZt=(tky->s5Jp1z4+CzZ|)t79EfAZR6>$- zI)&?exFP3k42KJfzfpdoI0XG6S(D&>7LzEcoo7U@^L&7R$T!a&I>N%Bpkb!t3uBj zrLF(1-X&TVgbWqzu&2aWYNc^Q7-I!oONNB@VlD0iUpREa)$R=&>v){*M4Jxno`B<> zI7jQ)!mmu3gipBtwMyi4Z^^w~29Q0-f1;T2hQataJk>jns6zF8FRm`2yT)}lr30eR z5QWet-WOHtA3HH}SsVLge40KPYkBJ4q_>M7}y^kY_;OWIiTd9s-DqZ9U2JZl?>7^e5>;E>kF&w^Q-I&s_YM} zzpu((T4i5YWq;72oCrBfVtPW;QRz@jTzLntx{LcnN$*gC8V>U6x?-E}bHPC$e;ZyXM}?Q!(fC!Ye*d61p{KevVNF*zbO|$f zq0jUIJNxvmp3YoXPQDvt>+XQLzAQW+c)+9UA0RF5)0@#82MAF(0AuPns}C$9Jmc^6 zDmYxl%}Q9TCCNV|yg%ypUJcyqp`-Q0<0S6FL+-*0+4LzRP~y=YyHZ3O>~XxS?+isI z28unp>dWYMIXo(GWdd$i<2YA_(#~J5OumB(n?2KASebkqN?P1J*@TRCWax@61@0gY z96eMh|KEoT<^Mn*nC0nx8#l7abyxlt$fabV*Qp4`zezP8h6LK^OXBf;(qTM|b@le32nix#+b%MBS>I z@2ebN)?Vn5bCoH&T|4!xtUBWD<$&Dt@d~QTT|1SmjwM+KZf)09-=YErSONccsE&-i z`oP!Q>C4M{s*Aq2iB5)Y=Rn}n_TEe3gDT_M3B7-&l9Qk^uLr)N)Q*Eh$NzCeo~Ug9 zQGMY2_TCFpTad;B&hy*R*6nmgx*w)sk1BAMA@A1VVo ztAX4a9}9dyN&OxA=_=;JSL$#e1ik3{L{d<#)P4bhgLKv^*=x$ip9lI_@;3cxIbGfU zjY8tUaU%SPrVej?S7yD#au9A{0va|{SH}gq88dq$DEXf=9vq=?-6b|A!o6o*+tEnH z)i!|_m$r#h%t9x^?a{U?<;$&aJy`P7EN76{!7)=8GakqZHRHfyLa<}dMdYZyWS(35pYFog3-~OJHF;{Jg$EWMyrJbFLfG1 z9eU@+?K7Hj6S55*g~Y$fszxb1)@c0BXu9mNYABHRxXBuWO4HTyfk&B4x58`_ZIfCP zR7Z2UjCQUes3zJk8;pKEQp!Q7h*xM$0~FMPtuhEr{VhfzZ;}C zXFKv4;sxij0Adl*RYHt_qab4h1crF=|9%j68cIpHOe=&wA;#bGyhmKL@v5stf&VjR z^s|ycSA^J;WYR*qRfRdbE|c}8FQ_?@vX4XiMEIS zQjpj0&Jf%#n;(VyM835AAdhMElTnzp2_0h@BzR4=@bJlgKxP#e`xl(8mO7`P_ab#I zSE-9?Lh~V+E;!qdf}*p7&J&Y2M)Y5!aWCVuzyJS=i^S=lH$enwc%qj>%R@FZy8FAj z99>{@M4Mwa6+SM1e~#lu7@W&xa@`iS^Mj^*rniI5F5i3IWaUw6vo#sN9_x7g=9B)W zP{8`Q*_!HXY=B`o`hol1x0;+O6n4hYuURyE-32}i>>X1uOB%)0Tz1iBKC`#|ai3)( zX)&rw<#>sSQHwU6Il4_(ob6xmJ{*I7NmdRfj7VP(Ip)7-KmqYU4hiZKa~ep-@Q2P; z7qm82G*z4JHnW#A+uH2$dQ`4UHsg|PX1=+mqStT)H=x3ak8er;OU^Z!u{|ujCd9bo zo72zdT$R0rw?Za!)3*3*ejikNYH&W^`2Q%B8k~=bM)Qo$bklqVMZ^Z@D=FfooZx&F z1<KgUie#0C~F1@~*B>^FOwah2>55Rx7%lDlb=Iud&%}RcQH`DI#qN zJ&iUYDC>9UxKQr#9?ZC)K`5)NvMMTpshFQuY_qjh+5D8=xFgawY_(`d)0K=zXFe(D zQ2Ub<6y6*fTvJ$h6+0?-?N*9t?p<=xB(Vd6-{m;`*(-FXdvtXt!SCUXR!tqiZ z-WN(;g`9{znM#qDiG?!fZ-0fR;Jc5#+*%+`&Y#EK!ulI))`0>#>fdM1>w}oV#!^Q9Mf& z?Xf1XM2Q}2A|<-dW7WFv8%&hM5+N6zM?Q|i)^W|t+5cqsa+V0ZkN50gIa*UZ@>KRQ zwfQmjU+;cwkWv~&B!ZO*Ciz5!P1cE_RZK?{y&1IzLp8H2%ed#FwyBybs-aeps7EX? z_iFF3RHetBj!!OrmG8Zs+y3;g%r?Krw%3eSiB1$PB*jNt>CD0upGAiMN7No#ZZ>;p zg&DsJ{F*FE{PtMLMsy!f@0lM3a6x+kTNN{(l>6wo1#HA+p9Nb4nT@c-Ah4#qz+({* zFukF*TVfG7Z5e~#Q)kjo(;hW*6&o;|7lQ#M^>?MqMCvK#YczPC?d{N8q$@14!nY){|4v%4eSS2FlnHuM=o zHTL;jG9xD?G@97e{<6SDsevcIxA zp{6yxqs{a7{_d7|&wP$KyS}$yXWulDZ*Suu@$}dtIF1pdq(P)h8t!6?f$(VClFz8PY`3Ub z{Nr{@6b$U1>cHEeoagu?6~B7nh}`iVg+iaELK$JsmC}$tbQ_JB;M1-M{5MPgQ7Rko z7$u+9cs7-sEXn3AIMoj)iax_F5MIR<($sYs#`#0vpC=?B<%#nCD^cXHE09Fd6|7>;P5zq8Rm`~|x3DmV+&XlS z3ID_ke9xxpWu?Rp)XeVXpl6uU7h+m+{2voP@Xw)I2sGy)e{@%NR!gQL1p;_JhIaC@ zx+zjo0CiJDb(6m;!jKSaml%Q)j$jB$7FY{x%-bSYpS-OF`IpVi+hPvcSnwP5Py80( zp`L2z9yeMD+~WE8+3#_!PI0YHb*7UNC`MDSLGyS0I;3U&Ckr(y5lZ2F0)_`%8WdNsf2SsgGOmma~nUrXo+vijl;w=Ml#lCHhy8sOs>d{ zGp$JO<++M|2D*+QE4u9b6^ua0uQ}D|#&=Y7Cg zK?U|X^lpzWTVM9L4DMBAPB!so;L~l?l=r3<{XJ}2m0Cm-1E6cB()VLEf}HUSVZ2vU zV>RFb7B{y3Xe;x^qc)kt|Ae6Tci+nPV3RlsKpDeB&q}`RYLig|!+_szgJaLU!jp3U zUvF(ZjnRvtBM!G%m}?>3B59t%=go88KC)geHFPz+)9_J4M`XGYJW-vD{r)<6VcYlD ziJp1Oqw2)*#rM_8mG7&QE8kluS5PNfE!D{)tyCu=s*|z*hdR0Be!tH>ZNBqHJt}1X z`|eBSXFlG{oL!pCue}-g1yzQBYpUv7@&)G{uanl1NpGh)|4LX9z4h4>8n!g-Zs=&( zAPETaafu12vjd&ZhqqBw zqw-2*RnZk`8#s@JeEMbr^(HhUku>9~%$3bC)kuk`#@r)dLFjuL)AxSeC3*UpMo3L`kl|U}hK*Zn9`2-~>kvJe`RcIn=gs8`)JfLB{!l&^-dl*uk@0RzK^=w&W&v=O?GHGBV$Q`v~_ zO1NzPO==vuXdI2t2f7Bo-!FZKpOCa*=?wJ#cWHEQUe`Ty-4xZP%e`&`3R`@0Tnqdc z;rPo^*)^k7w|1}0Zl7tg-;M<^lb16U5zlZJKm~8FOAPP42Cf?iuuzky$-D2YoNN3@ z3NJ^vjutv}kIRiuqoOQi2uYD%uzG6S1rA%pYR zb%(B-RBgKZu-Wo*pM@=~8EL}snJ8nz6zTZ7#oiW7$ox@|-!JG)Uh^SzyH-amD+ zj)s3W=+it|6TiozyRs&JpGh}oP2BiJ-X@szIh*S6GQEl!^ocO&%>Vo6K6a_p$6|-- zME9Yxc34ckvz|)3|By?ZSl;=Mee4*j0^<*;kDb$8$L8Ldoym8uA0?wqba-DiTyJ=1 zNJiA>We$r7(-K2|$X~a*vdoZ?h)E)NBHlO=o)+^*L@W6rnD-uXM2u^{S4NrNE2GTs zmr*A5d(0PElsqh@%(6~MiRqQ(!;hTYlYEqgQFWMy!jucznV?*ash6QyDE}k3q*@ z1lEL&AGxB{n3r;us0sRN2m+ETS@v6vip&o8S1i*@@x=Pl9ZEbfoS;f&4v2@5m^6lg>xz{Wqi6 zHN@~}_8C2Xh#pk-K`a6F_pyhsxM?m!?sEJ4va_}ED2PYps&So$(Q*|zYZ{ijifWd< zyald4`Zkq)aT}CnwS#K^pweFo{ixsFHA6gYq8?8y_kCh zc)r$asK%7qtgTQE+?9`dd5}l3^e%8RJNStB{Fg58_1PwVhO1h9UuNfBF0-?ya=G1H zlfGjMvPJJ&;i#bowRliPm5xGEQNDinG?&r*2@kIv|7YZ-o2-ljbgKnSM`_;apb{12 zOrq>@gVv5B>8&Y)&5-_!2zf99@~a&qGq?*GfXk72@Pm2CB{>-H{D(YlY+-q@b_eI2 z>aLu8^-xaO?Ridppxu?7Jn6iORL@u#ZuV^Ka!pPqwR+w#Sp8pju-(JWR(i zeVEQ{iH`q=L}$Yg>Oa!qHQz%gls!zRIKs~zp!2iq|C&zB_t3$poW>wf^5Z;;wnQT3 zm<3Y47ysv9(-OXimVe?XS}P;Po55(k{;z4peh;ls$|zcEC0e1WjMkI?n%0;hTI5T! zcIU97fh9II7<3=XUE_6sinO~Bi*9vpK^#@!{W_#V4GuzZu<=+bKUv^8cSghb0LC6s+#k>D_J)?Lfdf{(T2VZGWt(! zH=9TZl20<@rG7YF*Td;0TMSc{OVK1qHF@A}mt?!_rS!^f z$xIhs*|q;@P?pTEx?5Mp`?Bs1z8H4w-}i*3GG&tZflTCQ9xw~M5Q{G-V~@ldZTnPs z3{gly_vEPB=c~NCZ1)Xm{Nz)``Pb{GYsxe?VS?nC3J%dqpziuWk18RkipTd)lw4m1 zcR0hbUhkbmbM7=@iaPU&ck8AoHx7ha_X+aKlpmPkYAa^?__zbLq5r49OH(!lFFMaW z?WKgLP8v=fG5AaN2`K_UV@j<-T6yI-|D$?c2lgMu8Eb*k%f`cZY3gVf7UkhQ+5l_k zvU382t$NM6(M3;CI>(tJmbJ#}Ou!mGRlbYI2xm}s9tHexHspFNlwr662jv0!R z3V7zmf_+46wG3hlJ-x3oCDx4f#(CL-!enbQ+l!F_=_D?=SI;z<4d~=Vuj0n$*LIxC zEIFN79Mm@Tc=z}eaoxvi9KQtHzRbHnQJz#DQTp%PH(lBIt+_QyuoWk&Q*#ATu*}HZ z0fIt;Xw442(B@lFI$f?BVC7rJVR&Lw5xC!q0Hdephd>O5rHCyH5YUlEn{ z`Zbi*SdX$kWAk#Cyv^st5@1SHuV4B^(bJQNNoJQG?(7t{@s zZ`_`6L_WuC{Dkqv=%B_zpE8j6YEJ;{{~`h}18l~r_H#6I=eEsmR=CY=$uTCo5ghW1+OHZW&`kEkBq209I6e7)m-5&Nhr_8E+sKA)W@ zOfSP+YAEZFuM+p?l(s&UUJ~zomSR)42)Y`_jtaa4akcS}aL%rU_slPCb?&5(eI4!m z5rxx3VIhfD*(2rUk(r~j1EOjWOMT9*lz?OfUc74OdFs-(*SiJvJ(`A;7L9Ki7RcjV zR4?=eC!{c2R&s~)Nw+nFFJc=v1VHk|PKW}*d5SoqSHi}$ zn+1Kg=0pH5Eb!bm&CtFE(y87NsUkN|52pe@l;#LagLfQt?Pg37J%%ZwyEN_QY)!Tu z1iiW4Y~Rr`mNrOf`=)HXly*_db|4^%awMxv`AU?HWiwG!PNLgJX*XVN{Hon7Wi6$Y zI7AxOhtqs5(_sl`H{mpHq1;7L0lE==BYHd7w|9oADe*mmi>lwsvio+=N30Yy(Ur&F zgBh=bbg=0zjUbToZaX%U<0;QlTI|7;W(u?+fKALm>X;jGHe9O zaULZ+w5``A{2_gLqkhQ$>K`8|^Y+*41@-I}*$J0arGs*9eUjxJX@?55!_bqg9b#9D zR+laFiE`aLoH6lsYMUmPSqoJa(Okoh>0U&+?0oNa>NlP3^$;uk6$qsXs!Q}Cpl5SZ zwXs5~bKCc(2j^wPIp6q>1Dm%*=O#*K{CHMG7Tb7{*B${6AM<$Dez)@p`Ya@~EuNgf zGc!AsZ+(lPHG#x0vxKPTZK9%o?1hfELQeR8ecya==F zPx+1~f&=009RD`PL#VvtF3s_rl_@EKEM(&RBV~bvueYM}T)7*%fD}|Q!JcFskv34S zH+C1K)vv0`uZ%1B_Q~RBv_7*IGv+unP9OJ+w4}yy1z+P+x7jN*o3*rm{ZF%ec6r^` z;l{_SaA?I_RlF;eI_VE68fuLfvT!5IXJOF7<_3^nA zG_`*sjG03U84*h4a3>3epYW9@;dm6`IyU+`_NI1FsJP=E&4G@<|JHpXKdE$XljP$3 zoXAesn7njS38gd4tVLpfQO68J_10FR_BKrZbhYYM7<~!B$El5V{Ss&>i#tJ=7ya(L zU>22($Mz^eh}bo)s{?Oc^Ng0`4bWyhhaUB1CwS)@(5NZx znnA9ObHTOls~drr!8WEPoj)bMgRS9%3Z!$qKWn;1kRMbCT8VGtoy0e88sYHT`FZd` z{2U>MpCX3w2cFv#9^`djMF;lP2{e!Bf3kH_it$}<9mIN4j#U+6;0%>v50zok?wAO- z{!VZ!6{w2Ryc{m#N%oGH!}K^MD~H43%O=?~!Yc+#;lGVav3eljB;oVUA4tL{+~1=F zQdw^67@l-P%bBi$_DBT?Pyv1-6##ACEGl%zP-y>8eB}vuY08rhDnk$YI-W-ZoDAhZ zpb4z1!>JafQ_Ez<^t_Ua(wE{xqmhTQ(EvaP-qJug`!owPn^)fw*DThL$CmCzjWk1W zE$sG1=04gJaOl%SETHY6JmJ&0{Njvx6t{8KypDIE{O2Hglur;29X!b>{cF5h&YxZR@)yjs}k=!v&hN%<*kF@6nP+=kR&X5~s;7^Bpxfqexb? zz~^t7bzrrlV-`Y59V4+qe*>1)Ifn6P5SqLoCmSoO2Rj9(2WOolb4dft@Pwg@leraCq>x)V-nmTA$G5&+o?3 zqRyO?ii0Z0KJWY@%)wjOAw0B1-8&aj+olaT79!!E)z%y&hUXlb>pQ8za75*J)k~YT z5ao~VfIOl{@!|gre5_}DtS3IY!$=a(#^kV(((L_`ex1MH(qU#Qhh>L)U)w1Zwn%(s%T3L>ZMJd$*L%|5(Z+aEvKB z^q28vb=N5oQ8gB(uzai)&&G5l-`D}?0=|n9bWd(LP7UX%0p9@ z?cCg%_>ktr>IXIZmyu3F=%C}+85ZQeqj3-M_b1FLn3LmNLrz`Ym@A5w&`CZF6=g&9K?o@lc zGLKnNliQ7PK2S}|_>vsQ#s$nDY31m2fbVFg^Jm10D_!ep-?`fzvlhOdbN!rtsHw7RtQ}R`;H3EsgzD~si=(7H{;*KVtQmh-C!Kry_k+Y zIn+K{F-|+t8v1KEd!cX~;Q9^QkA}{vzGad$Uu-ivWmyR0^(RO@|xTrxok^H_2 zyVBKS+t0SpP>KA(a~O+_8LDH)4+ni~ijN+O56vBne*}Zw=}I$Ba2->n=Bmh@71HL! z%$X`goqEuK{m$E>&b|HaJyA{DYR}$Nn}6O=_7l~mx6fY8uYTZqYVI~=@f~nYdfxuD zySrNd5muA#iGAyixYmoCI3eGgzkTD4{JUphC3AsgM!wsC&t-0f@5R@>C2@26-qOx_ z;8^kanVz>#pHw%U+@TY$UEH=q*M4=*R9rH_;ZQP{bxdJC_HLggHMbXYa&vf0fPO@K zDJ1WE+Zgh`X$<0V2b+ES<8gMe-Stvmd}*K|rzJg9F5|XjKp_N8WwN^6g*QtA#(QK# z<0s=O+Q(zgahY=?aXwKU?8)rGG}n9?<{b8X<z(tZC zlJAe#gnrkOJhzcXZF`BsyQ4kk9AW$%m&cqdq_Xn_%WzpoZd8bF>0BAY^&L609TQgZ z?Fp+ltur^PPZ2H)U zvr%PkrHjwGJ9?M8)HS8SWmmbtx~TG;;d`QI1y9^s&{DwZ^SQ&Vw(R<*!!=6}m(5n$ zTEi<3J=mVtmRfFm9zk4p#kD76KUjH0-D%&YR;3<()!utP z+|!fnzf0z=sb2e4Y?&1oYUMnjoUP=0Gq82UBxKSqIkRcwr8;!LAhTw1w;&u;FDP3c z>Xz%eZf@wpS+wU3&J`qOh$P}yCC`(=bAVtH|E)8g)m z4+~DczkJPu@xSX5h(+TTdD)a3b)SV#JzKM@>w+{ccs2dQc>f`}JEt=p`>9vo#M!`# zOf*z#XV_PrW5>wv#jw~bdx9_ancH)Eyt3fYiT*Fc+b|Jt3d$x5AGM{PTfID3#Px+L zpH1C>RZ_8#o6efpK_zTZKC$dhFT3N`BRsC(-1yxy>RV5!RF~-tWuCo?&zX~>`yCFR zaduHw+{`c0X%@^h^zE2qFM;94@na)5d*#?X+me@gRXT@j5c15$xf`2ZF?&rP@-68e z`79yv*%q9zr#2*yIdn3*>*WSnOT06K^6mNmD0}<3rq1(!{NyAA2uCC&MkKT*2LhM*A7i8qu}iNi_H{Z3U@Xt6LH*1jWxR+6tC#A#EyBsS^7@MK{0|sp4ks z=B(At+NQO(U9GjP&*%5PP6F#b-|y#--|NLIoO7T1@w%`3y080sx>@T3syQm(P=Z(1 ztZsZ{Y4x=G!JWpnbNc#evcuff0ddlr_qBH8*x>Tmbpsh?~>(ZD?o__89(J)7^U-d+SA;SRW1OB+Y3FZdl zUPWe3Rg33yeiiTUd+{kICf{IqW)lCd?MIKB>7S#uU8u6^QEu&=r-+Jz{u5o@X1sOa}S-N_z({?qA=#N@aS)&j=7Y_eaL z%@=1+uQp6fn6Z33YRjzUk|)$valb*8`zsZGV?wYpYR?*fUy-{joW=$#<@Pk?n@$!% zz|9@Cxlcz~l-99};w(zD;8W)+5Nt!-9b$nzl>QN0JRtTx^whg$PjxB-X8@clol4U_ zMmOz>RE#Yi&zKj{qzOh1e)HtusfvHY1g@Af72P=#w7l#`oGJr-?Gb}AGp~(t9ajfs z*}Xl6{d_N{H@s2{i+qGEW%_-6oa!iIH+6|86f_q~_tVs6o$d2MZFkz6DQsPbSp2T| zsq^W<;xl&i<}YI1d4xewnzIx{1B%T906()c#MZTl<>nG&0ZhaAY=c2zcZ9ex`KDU? z#gDV3`N%yH6`t)^#i7fc^2|lfrx;!GM-vvoNQ+57#uhh-Lpw*Ny`fZ^@BuKT;mN~{ zxNX$8yjpMR)Vi!%w2dihc+OjaY06YIyj*Uc01*zq&$TheFa?$hu9BLJDdcGaci)&! zWrI4@RVYP}axy0Y|-*n)xz zS%N~mUl<(}68(aPL}*Oq7=wRbFB&QnWR_xUdyZd_`?WECK_S%>rTj`{%J%h@2@H30 z62E5im~QQ0+EM*({qc9S!8oQ`kOc*15)U(nPG!gej->c0V!OgJ15d$x>~W=&v02PA zH_oJ00fQJU=h*t#uf6818?a^C**xim7+jx+r(H_Dx52EuEe2C#?3+oZX=)N7$-syM z&xpFqw=8{`2n%-n-Tpo;ecT}GI&ON+sAO**HwuZwsyll`o$bc-Ifq#kbALk8Zzu!3 zA{{CqTSTs~34f?ttiwu`&XgPsjm}49Xkvr@yn_eeeGq1>@C`l3cETQ(pI01h)<(L{ zdF3uw(a~l_;5G4tYBKi&-sgSK2!H#kq~rkqRPg-zM~P3&Q!EwM!E_UkQ@i+rN#>2~ zje3{RH;Mb*3HChHtE=8LTm%!Vr_8&QbC z7xtD}Qzgi0|jkV`y?n<-ea-cW5oDL#!Ui#F3kMKtn` zd5nX;vCk8oy(DiDM7>HJa~~IV3!-qp?7ZfmPwL=ePx*d5{VsQF&6Z4$O17=H#&w-8 zpS=P;3^oc^uC@O3`@^!W@gID>>o1-;jGouGOzOan;+22U<<0Aq>nkw`oUf%54J3|e zxx9*cugD$420GAt;Mj*a(>n@g;iuH(V9nLO67X9%yDh1g(>Bv*TK{g^dSD9N3afqW zs!a)5$_C7*#Jnb%aE869^2lbb@+LGcjsBQbB3fL`yd>O)d05#z0l{I77vK(Vq|hHV z#W%p|%5`}%AdkN<$@zuoMJ{hC+0k3ImZqx^l%eWNNe?waT-NdM{J>w~# z3?V_lio%&}CqojTyUh;b$)bkdDgoCiSf@I`f-uaym`r_3?zk&u`~FzsP3W%1moi?7 zg7bPtmmQa#hzfM#_-fyE7iUqV_V2@`iq5@^ZuyOFhwk}X?H&l#-mnl+h61I)og1naCr-Y zgT(fG*MQ}Zs%BW(;xl5q zhfBe!AyCgWUM{n-CFRC48(`wRAPyZQ{+PlWfjP9!HgE>ZVacK-;8!RBpZ^$3>Xz&dmwAJG z_kmcV0PQ?N%nxZi}cj~rKS-(F^6t-?N+1Y)aa;+C0wxn=Vv zPJ^@51F;LNQ!NcVr3&R`kyK8;z}g^8ErS^I3Q0>(lMm(#(Hq%?`)eH0=6u7ol6-Ph z1y^1s%lF8Naz9aqbs&tRy=b`uo?P%iT4K2zmqxtq!Hj7a;wIrK<#NWf(<$qDp9~1k z`Cgc);27~-Km3f$_TWv3IHB5Ts!+UD0T6r5%>~^R*fsYTsrMHdR#mDO zE;j7{nc7uqEGaUSw5Ycg8C;dAuA)?zO92o5{43XVnNZp<<|cBnz84d&TraqAso>Gr zJyqM@GW7cx)Q%Hy!DkgWN=@-n?UyR9m+EZa1XbYko<6F#ABB79J7Vy7{{H8;v^O~vr&V#=8dLaAJv_LtdTmP?;GeC9r6tKPC*#%(M zy)Fi$&C@sZ_9O(c2;<8@)00DcyNE#|5% z)?rg!w8dqB-90aQY-0o)chxq^VT-?L8$ED_XaO+OU@?rn6cwJ0nblmPu1K7tT7_NFeajcf0=;%vmRp3`i9%#^sE=Z8RS4hG$Sp$%Ps?9iCFBE6}ksCR22=SyKW?rpCtRe6{r+g$8b^e6GVHEw` z8)~mT-bZi?%w~Ls8ZeRre-|5r-HY05L2Uzb8J+6eZnN$eH`;3h^O=FKMXC#`NRnB= zrku5oy~q~lFuBlA{)m~ZC|9o2>G+g0b=8wMm&~KHzCEO9uGGcG`<2!?G4-2S<&T)b z^h;~v_6F1C-1wu@*phDzr_QteqejO1M~c1R-cIAaWNtQgyt?}>wr;#6%xwk~Gy6*#5VuQ{8T^Y*{n#SJ0QRIH9C$ z5tniCS#%RNx@1Q{7nA;evga+&!Cyz5a~l#Fu@1-><78JRYxmqGS3S_si;&G_yN3Bz zlYE$W=#;l=-03tZFMC4e&65P-!$QYMxzv$z0dZ`E4<_3~a4BWVG9S^RYOsmQ?0I<) zVk3>hAz|pQu0w%sbZv9dq>g?tiFddgYZ@}ZB)YnZL);(c5HDP7eN`Wv(KG(jL+r_| zhKZ>joHIHm$LUEpKX6%`Xhr--1}vma^b2phi&4%MSA1 zH{VRYGFOcT>~nAH4_s^$AK)Gx_2y5WeIO2+SjOUKwsKtb0J&V%!S@V29e5b*Z50f5 zC=c(oEh2`tn^p2~Z{DPPHhRgMs@&Y@dK!bnu_+tF&;|K=8cAha_J)FkZ-Q&iwr=90 z^&ilk)bE>}+t@Q^-7dwnU0ao0%0)k8iDeE)yA~xZJhXjf+&q1@%bE@M)3~C&JFX!5 z5u~Jpcl0g38@&(293HimTgiR;`yqHAFwEKm+boVvbr*410N4{ry-Isk$hIq_8_s&o(abYFw^On>+q}#^Sx6L0N9Mg7@L* z=;5EvezSn%Huqrr-^A)R-@RZ}XJ>Dk*5Tev>I;rdSDo3TfP4#7QG(Nh>{K(yf`sdg+G=meos zfVAN3UA?vOey=$wsH5I8pNJi~ zlhyw!^f-IyCN9Rg2mH*g%@+}G`gieLtmyxiqWYYBvPsFHyL)%*DBRq$W{avmUZ%H( z(V_S|QQvY{d9-D)?hA3l)#73MTiiNuiuDx3ldf?pt{4PUiY01s$Pev!1DAOKMX=d3 zhp~=KOIh^Z()I^j05z>c_|p|zhed^0#di>dGdp{+U2|tkhg(CF`zVYeD zFCXA_9uoQDoXK*;h$KAc8-Nh}DHeh-o}I$?$1;ie%*3{BKtsYWqCFq~dYJYEULB@~ zl>X0=bW`UK)6b5i2VNOY_xGonN?7U4#yCHaGzL=r7G42^o&Np=Ad2a6S?hWa%br^V zPLw!e*21!$eJ&Sq`z$T3WlG{ORseJ3*(YZFv!AZ|6NKMg0Ne38n3T|5#ec#$tki zOI)1Z>aHWOf^mg#l3@gu5@e0h5_dhb3VD z{a*DjIUqPT!6pphZ!%hvI%BdR$8kSSl~0}6B#+*zN`Fg{{*L;dD|1+WrertGa*1_V zt^7V0u{KoRlPZT7S1=XkM=%y3Sah;kbHKtsO7)~b=>kh8K+Kz(XKmo8dQic4#N%xQ zPsB!pCz{6a(O`?pGuM{S!)|RTTC@`QtgF0<_CN1_o>fj}!g`LnJf{6sC=ud76Jo(q)MYbE9G#gN<@5MN#eUp7 zh87IhXqV?zQD2TSOiJMN+di*tylXhTz44VVRxoo@ProfI-#mXtc}DjPf0Pmmmh!nw za+qtH*rU84me)ga**zoIsV<9V!Ky{Yf{e`|Gh&A6Kbp{Dc0z$tQqyc+dpX|z#4U`@ z;yalkr_i~4w2Vt7&R~WNIuxVC^kCWg|C|OzNK=K}nZ-hv(gfMZv^%??OTjr*O<-)E z2USW-%RFdL2D;G>Kr<%>ij(@MW6I(chPk~Z=ffJ5(bC|*li3g6R)U{p7)gop85#&y z$WK+UpQ)Wjwi^amm(=!&cZwmBWBzwNO2M!m1qM5$M=}4W9_8)I=aYY+N0GEBUy&Z& zV`S|%s8Na~HA)iHC`84GujiwHwXUD#K>e(HnDGo6c50Hilv@b142yEGiRsBV<4vv6Fd%(ye~X9+lB3IdyVY^oy|GsZPr9gNZD_ZWm2J=3Fh?NAFb z$vAH!Ww$fe{<%zGS>j!#GM|PXB>zp$I`E0erPg7|Fea1C-f;)4punI~j;)g@-CLff zn0thn6jzHHy%b{ZWe`zg2Oh?|ie#vL7HJxRi`~^=GCqQA;U>k#1U^)=%z1@f-nFO^Q^^?kKx|ecrV?00CC<0H=aru0 zr?`06XSEl=No6W7?$clX{6a(R?R6Jbah%un-wC%fTi@W`TGOC)RTXRl!&Prsu)aE) z(a&8^lE(TSnVsyH%HFrH9hL*jiF~b$R)XicUjMsqmwe7boWFlzk)Rr-JP$q$>mD=@ zydulsl&{m!Hn8?1b|9016c0Gu4yo0-WD6^Uk2q}&valeCVVYDpz=!I`eFO|{^5sgB zD;QBRxl6}-_-K;b*ixEo5xGs1?Ou;zY-*(o!MeSWAB}?`%cG7)Sb0yO4!N61v^5re#I_G4Y3EIl>)-qqQDcFZ5VCzE zl1`ifai(#@o@bW1;CKzhzFq}>U|>P&1kO{CjGpS+Wqu!nSw+EaC=LQveYGsR zUzP*E&#=UU@w69hF2Yxj?>95@F2_9$ROJrVL;h5Ur2js0`g3+EbEZBo0QHte6L z?yWMG;KGEthU~eLvS4ni3%$y|7QHMcf2q-9OLW*YW0$4i*Q%XXaE#6@p-P@~Z zOzHP6?zfG~Sf)l$C-~@kY)OJ`T$xR0v5f`3EeE`n$0a&QG7xqw_WN{_ffVyhxqZV` zs0?QWNd_@l(QMbTW7^ZVJy~!{6}7Eo)5*07=VqKUbr0Z;RH0=`Y2fyQ$vWP5023bZfWEcs7UdFc#)({`rmtF5v zI{%Mozx=(#lsBcv*l&=q#q=n2V7Hr#Tk0UaYALS!yU3tkTzj&rdJ#@2_9?P6_U1L* zBRdbPnv^V;wC!2Nw!vC3Wr0qa?%?$W9Vf`&+dY;L4wuwIpz*A#J)OS4jPKu-+t*vy z&z)~y#rG;H#yL#pAedP7MDNMJFIu%x{pR%elfQ7yI}}rf$h5Y!vgI6&F0esH(s?Fx z&CZ~@Weu;C$T}F0VwP-djWHV_lc@foOk&K2VO~0PLl;>i@Fm;dqo!r$6+wmHOjcsi z)nbK6HZFa%w@KQa6!)d4(0NB1n9^&@v_NTYti$)4wXd_q24>ZP-u?Tp!PpK*#q-0f zE%xxJ6S0J%?;G9MsjL@j=Vs9L`sYUv$J8^_z+M5{#_s!%<4_np_IrpgQ(E7g9_2rF z0SWrWl?E&BhI z=srsinF>yaexuhXRL~?xpI5?O2Dch59PT)6JP4&OZ9B=a-e>rjw37hk%(ThMdCw{4 zu!eL4kI+_Ec^eFYc^k*ul6jjR%R&!{Eq5=sk2||&b2^Ri&F0L#-|N@9S3Cuy1{d@a z-kR^`rw54!%k*R&GKtq$f*jzg7bY@3un}9MH^##sbLUTEf`Z&5DC(|>K_SW`D50&T z9U5yaeCBq@69k{53{mGMj^py+XWub*_8J6-L1Wym5?4;sU@jtiHw|X5s&!Q#6%jfT zUrHV>ShDlOg{xg2->*G05+x_KWg=G}^vN*ufyE;BwxMH)$O#kb*J}4m9*7VewO;qA z;?{c4aEJUy65S01NPEX^h-LC?>>qzWS%H3sr3Qfegf3pr%&)*6pYe2V<jR=zjb<}s6wN1t-!?U$5 zrCijK;6zgM1ni=HfxZlRo!_CAKpHd`-@?kSEJo1_F%s{B1b>O;#sHd`%Vx?i2z_@K1@{As8Esrx!t?PN`d1 zlpqLPLB>;;3T7&FiZT6tKMwZ&1oo*H6pWz0R}c~?K%Sr$)Z+yqUV0ua$bKvcqfo%@ zb@PfeD4HY$#Nmm&&Dx3&W1)Z_^6b-ZKF-~H3On^bYESmo=q53`=}K>@;py6j(j`HK zp2v7}TmE(G_$l23N;{|Q2bXl`@2&sGK2PC&X8)CsnNzbcyae>j8-7s-4Mf-3IZ?=(=czI|Lw6jqdNIZ#03nix(B@ z3l|jje|?=<@uq{Vs}j#tw0Du{H(;Y(4#a%F5b> z*A4c4O2<1F7W!%)xvKBk8ok>>yKTh&k)mmIjyh^dFz$yhN4~)a`$ym2Y@biDsv{eg zPM}csC50UiH3y|O61Ql4)ybBEOHdoQS z=4Z-Oqh>t21#Ohs&?q;?qe|0TOTZ7=5LD;dl4Y-iOX zvB*xsx%5BnBmy(S_M8<=DPN6=0Ba?fASa5(!z{DDz*D5^X>(4NWyS1%Ejq3Pifh{Yv{+3E(qI%lzCb2UG=W!f8Sx)Lgn)I34H33ggD0ddbOBTqFmf(ria!SaNG%V1i0`mpL0lN# z$MB^(zTiGSiqZL1e3aaND(tHn1wVS}bbt=R{N8yAnv)oZ4;n`9dry>nVQTNi-z0M1mp0md=N4so6|^Yk=X7#e#~- z&oA1!;}@Jlf+2T4e_PGr7&y1EfTH<*Nzv{8RRoIWGXpBYqO$bEEUh|BQ$5izkQaQfTHd zZhw~=C236{$coO*`^LjYR}TKj!z-ae>G!dldmu}8USV{*?u;l=rcyuisyTMI^(d)P zpoXaIK1fBnYf!}1<0ARwE>&hO~pD*j1dP?$(h_B-#qAV~E@QO!VcW zwiHPf!(vuiRbET|0eKwEJD_tZxGV0FKSFB*KOFw zJNnafX-WVX$20veOn--A>s7&&P02Jw5k2*$)P{J@o>bFp&z@}Ap<%UIss43|6573dRR&G(QPPc_N)W) zM3gkj&@mW}!9GS%B~+&E7gU^Uu^KC8A&fZmL6DD@KE>nH zf}&Xtk37+}RPB+g7kUj#1y7mc%FAk7hcF1~A`B+;XBBi5?ePeXD8F1Q;jRX_Yv0WH zj~LwRsK)%cy&ZG?tdddXm-wF1+h$c4JiTsrPBeGKB19K=iv_iK8el z{v%oLWm0!MS#oG>0b|;Wo?JJ)E}f%?*CnObjHHJ~4X3wXgv0f_2*lTLvEiyj+dcef zlH7IQgAVL=@*^S0*k$U(mJRBBF;#t`AWmht2F*FfN$-g5NP35or|8k~@&e@3{)o zUEi+12BG3t5sZol&x+jEFUh_ATV|3$S zze5e>QGVWL<`<0H^KJJxClsOCSRaTVwC7uBBO>t19)XMV_L#`I-s1QjCqK+u9Ibx; zDt87|1ADBE2(^}DnYqkTJ_S2&FynXrB`=&;o`?dzOjd<*?;?bP#h*9L0;9cSw>weZ z^q1S_aqH}`ZId64wk&zU?=N?2s50E(f%+`v$(EV-OZBu;J(E>1_|HwYl=*WIIS0zr zz?*juvv7W#hpJP|G3(0ZLu2?wj5&GLP|-}#tfAMQ#BZ?-XB?Ja(n>s97zggI9mWCE zSHoi>9Jn!(9{BQy>DNZmO z*wMOf8NP$74pq}vlre1tlM`5nMUOJ!etB3DG=NiT@sF&>0g?^Oe3-o@!{Bp`i79k!y=5_4z_kf_?otGSyvYlux@GY`O)li|v zX<3VkuSuP#mXN3liaF9mqn&;~6V4ituFR3_O~7>rCM0!O@n4{kg&t#OB*!~5lYB3t z-GA{u8YqG)hR+j-gF{zInI5OQ$PzQ~`0$V)3qvNb5<_<`r>^*XMYsZFL0lH}d+59A zOURQ);&TN3<%Htji}r~!i_avD&h)v+sRra&0L%$_(05xJFKkVvrHTHB%LEY5hz>3( z*HJC%fX$o~)dJTf(wmb;?Sx7Kuullng(fzk6PMg6A(WN&hs2DQ>!w@=w(YdmDyV=^ zA&2S-;W%^)qA{gX{IP$Ejhf0Ae=#R+KbgITeu_ zui&OXg^ItU%Y!0(+_zHC!N+C$YNo2^n>jheIAsE^wvD!s|G=nO#?UMVXvpcIpfTBS zU{j>LXaT8TWD%5{yjwkJJOj(zXp2vVXhmg0ECwB#gH9qMQkjqdn@p*2pcq|-nL?bE zc4)L8C}He!`UcDi6*1h)h$%oD^cT=hrze}^Dj|g#I!#(8nv2k%Blsz9j4FFugbh6s zK`l&k82jJuN+QSpwhmm;!Uish8J9D-RP>%JL?-79nAjlL0jx`E?C;&R_&Rcv<19WU z43;rTWkRBbO)QOD3o{%C1U~ld&bwnRyH93Ma{-D1lQ=sV}aXaCG7ny zWi=RM6s%00azZuz6@30sY_z4M4!kGQq?_`gNbAk+NXXq4g?r@C6(k0J0-(UI51D_$ z|wa?4nz@3 zBMv{T7=S3fWV}4_E*dx##$57IGe7Z|#FTsG$NRYF!8Lm-qOte_H^q$P5|507>uE;w zd|sC5KE7rluXgbX9+{R~hGdt=z{@ljD9zxJjnVTk6oCe*Nv7Mj(+E{VlS~cWr1gG>ncHmctkjbBSDlbe*~eD%J{B!sZhG^thY*VZto%ah=mfScuOwm~FhxQ43v zei_;wxDw%uJ#69$d3qkZ>WDh%Be*$_LpH{6gVI`ezAE7XY4#CV9&DWiACC`$%!Ga) z!yTsrgP1C=Ih_9$DL;VI0kPn4{xUW(eG0qEsy-pdEj_IBZQvaD-nq^2N%9f+-V_^e zf+pb00f2PqY*wKJ^T5l1d2tK_oCx|xp`}oti2e9QsORt!FfjIHi9Wt0K_7JGKgKeS z^87&>%O$CAfwu5iGJi0Z3g$4}(a&RvSSnk*QO!bo){R3<49f-6ZA zp}Ai`lqmV4-E#$MX&B}nQ15@uHBUo5G`$SFA(#|_phF4nN3g9t7lL+Sug2iM5S3y2 zeaa^bQ+vSaM))uqhAW#;nfV`Wfqnkp+iL&c+Y0O%Zp*_apg>uY1G$C zPYlDvv}Cxil>X63dH{FxhINpX{*RG#)8Zedzdw>5aQra+uOsQEisAIGUp@hKW@~Ow zVYa&AXfP=c!#(TJpoQFJmoYloba)AL@(9|{Ru%{j*xIC6oK=!>};Hz_FoUn zjJ-4pzZ*VAfIjGrv6~^Iherf9{Udo8(1YLM9*@G85T zv3Q)Mb)IUmuuOiwR?PV0`}-5%x$+lmn0K(7MBv@@Z+Mgp!vjL5hZ%pr zh{Nt-Ik&^@rQzh}DC0V&%Q4FEz)&9BNA~_A%pom%T-Wz{PQPz57=`Sq#^CNlS?3NO zh?p%!^1l8s8KYwPP2Zc{Q{W7*3efM0sFh`XDMVM(sZKmJMCI?l#@)zLrNkW4z;5uC z2%)17l1^g6oY%!X*7tUAo|U2_T#%E@v7Ce|c}mDz#*A^!z3+Izt{i_M6W0>wwI@MP zsr)AF%NNEm`^cC>`NLx-Tq+$&cmDK;>2pTXLl68gea1+-bNUa{g^~2ov>&EFFp}<^ z`or|Rk@QgRa5@*?W_<#x5G=#M{bP);t%RNh%Rw|_MBNR|SrAh11&3fAMpV_e@!RuO;VQAaD zvRaY?dnPcPp60Y-hH0#7MKI2wNsEPKOPRxjrrt;0jJex* z4S{EL?T8!Yev2A;WAh1kXh1eeqE>B#@k#Xr*}^L|+)r?i5!TUHP@gs@_u%O1{*1EQ zFW*1{Mu@aNt-DJ~n+V}jcUhly4mYvO|F*%smr`#Z6J$?VWHVLc|N8T&2NiYd*hCtky!?I2}EH6UWnb!5sw1+#TMyFcLbdKKw z(dvJ+n`vph3Iga}L$C$@fBma}_aXd^aj%MeyFBu(0z2?jt$pZKk}x| zw9ZIMnW@Q3ot7gYFrg#dKUjoH{Ue(^$PB&}VLG@YMX-(K7J zw7_cf^A}QP2hW!A@_En2U=E#EMcuT!&6aY$WLfWw`^R)Amh%gG(zSCS5SF`-tw#5X z)eNjdOUhjyp4sN@otGC4`u#6)-oaB|zB}=Ra&r$P-tIqARxiKY+rTfk>YTW71V@~6 zwvwV=810qCkv1%kw^^t1b^_NlS>3;ao_`Jya+J8U|mD`0L{JKs`1{v;hLM3i%*M-$njc5B1;S6T^fm`B+ zZ=M5>zP0Pz>a%?q;Z5w{w0C3w>O_Pe_=>pSqeghv5b@Wqft|NS>HATX{Zte@G+^gC zx6Su-!F*%6`GQy7)R!<{z4=Klz{PQ!*KCgS^d%e|4$IWk3ZScdIM#T<#~yX7@%)@~WDAOLr!z z>L;kVw{|A!D+iNk|ASkO;hrl^zN(!`U!`CAqRIF8&ZJMcBuFfzdc6V%pJy)uXp$9c zgL$fKs@nZ^HR?myq_60|*MWdbMsM|0$JFY`_s=5VKc)W`0rg8`cR#Wk9rPg9C2oc3 zPjUZ~KKuK%?(_7pP09o6EXC-4XE~CjauwL7Q&bPiryAj%=(eszI+uiiwTNBoesJ~F zX$>kbJByu}xF?bN0Rf8p9jcBDyxqs>sqy1>g?lQ20N^`7^}64tboZa=7rEY|G{EqO z?Tq`6c5?oo?d%(AXMdy}t^3|cJ1tT>uSo55MB4ei)J_}YZe0!($9|oON#gX}L_ALD za{ewC*SqFl+o;OuV3nE72^PVMgR}cwzv5>19y7py(%Cf|mnuTDmy)M(OO10AIu%U? z_e^!WM^U@}($O!lTIM;z0d-cSP^nS%lnvEv=n0Cc+R(h*jE?)?l|g*`x8ni zUA|o6JmT4 zuCVVP)m>+*w|qG5-OlK##?Z-JIN)Wf?fe}Yd}p-DKfAB08u7G_C3HqR+h&8l9iYAN zu4u4dmp7(0<9C0Crq3$jkjs1s-CnRR&j~`fuz7i_-Ys+oc-$$dDbJ< z!~1&RS?ptByi@2_Gu?9cAE=AwL)BgUudqoSqBn^y1^bdYRruW_8-G=H??u@?@4jB$ z_j+~P>(vditT^{_nqBFP_sjv(`?tqt>|*W9p(&l+QkjRylhU`X*eO5Bi!}l#;NalN zM5@%j!9#~!exLYBUcB+e@W=KTrzRW+%FTE+6)#j{nQ1RntJhaH6nMuhRdUf!svFF~ zJ_R&2>4_G1Gxc`ut~65IsH|&~qm50~6DO{1(ggcrkmk&^4z15L4p};tCY4k#<8GuP zkVDYtIP0o zR2ZME?(fr1v`(MIC0oFGeP_0-ZlaAStMU`yu&+A@5&G{=38uu==5dBDz zQ;Km#H8-lA-EjMOmwP!S#7zuG*52+jEUd%%$}KbgWm#4u5Y5ZJQ;L6{iVXL{>cdgq znB3;Mm1$#y3P{d;309YXUybiY7X-`28*v|5&L@?N)w4>uMtt<|TbFF@cu^S*9eh#3 ztkSF@A)Hv$@zQ{dseE|UtWvVt{bv*xZ(}Lp9v$sii56b>E2TT2{G& z;kHjL9r#FuHoAB@ldk=JH-tbH+!sf8#BfLO z)>!wc$lX4wW$PYc_TW|M^Fb@uX0C2mrQ^*HY%fER9ZkIV-htF^nu5SR53Rj^6<+b}$`77fHfDv(iG#MU*7M2(CY_~m&fLo?pA zY;tZht9(w(9Y=Mgr?GW@R2@IH6b9X}7L(Q=;Kx#g)rFJ0;+MN$rmUr}Rt-k!8ddIt^u|STx~)-7uio+1ZQs`6LiHu>3AmCE zxlWlF-2<@|fvVEIRa|_#@_al=6!(elPAX`>e7)lLRbQ&ktJ;;3^xabW^6x92|IhTc zaQ<&Ac0|%o;4%((E2XYf*_U4{*j9C3^`)vEAy<+99Hn#j_+Vn@tEmHaaI>>i?q?`< zPn3QAHN;2jySTK=Th->Rg3q_30x~B}s6kgAWgqjc@(aH(Nojd>Hnf;SOZ z_=9<2?L^w-Z=4J0F}}@XM;|G}%yY=-Zq<+I5Pd zT+@x5Jqn?3;haWjAs#(T@rAV`S_AN~I z&N6o`sp2;Iefx!q@mbMA1>e!mY5RREsw<#%Nf#BNRUhP zIcgn+aOY=Q6FtbduO``x18KX9ub2{eRYZC*MGXc|=r&XxX4_-1{bnFu_IN5ia+Y+D z`{B1A|L3>FDvoQ9`BHu~8E(k%iOZqSzWxM?J_NdJ%&79P*l#nEbng3T2pLJEU>4`j zqHGzvWSJB&2kk#d@!vCc!R`a^=mi99*p7U)wfU*r4VejzSB=IhKg*cl6LS-Gu>;?V zkFvgpw(Cp^T;=sp?V&)y*s3zf8UA()!H3*QRQscw%2dvmu2jhEYPkLGi^!FlKR7%zpERIl9UsXKojo*(ySlrtc7dx{z@z=(8?a!51 zfPY&$7lyth&6dxl;NhZ>6sLQUF?2|-w&c~j;UX@hg&iW`gD97j&mGP;N_PZ6Vv!XR zahj(Mr;t-p;^F*)^EtSbPQszCGppJXmpMaX+uv8giKFlIs`GL>mplJE53-vtY(XR2 z_!OP_+9-Eh%rabBfBMFBwo@rgcJ2X6l4A@WBfA>ZM2lrz= zZ1FcF;!NgUl()J8JUrn<8(Z+rl6ErA$|D~eOU3NUaQwK2&HiX6n8%T8tAoz30doj&mKa z?RC|(vqS4}j>+CqtIIU#W~CssQt_|RKc;fxc)w3cL1YmgZ8KGNLNwQ}0!P+Buu|ge zTRCkERF%{xE93XAqr3<;3#W!k8?JoAtJA`y(0|;!r#yw^1y5MmNoBrw=53$NN%tCM zqueTF2)rYvrzVv7j$#mXM`3t+{{pLS(bwjVrI;N0{wVP13QT?AZ$tH!MIvO+WR!;x z2kprH5Dt82QgF6`&%_O{mpqi<@C_~*)0&?8dv3WhBv!8HxM?WooWM+1Ar2t7J$Kir za1S$?EY$$a94oQ*lEI^L2Xc2Qxdqsg0fG+HSo{}}doOpF_IR6n4h?+BW-%J=FMi6| zlt;vrROk!+K9_PpOtI4AZWpeSPbowl{x+trS7cHil9HK$H^r1ixx1qMFERrMsqW2+ zM^vz9sXVCQCKkUTrmUti0j3W7bjmlmyLbz`n2Vns?C($eRKs5EceX8AdetX81=$nE z!86KVheP6RAovHyZGVwvY0LJ5 zo`aKfAEvy(>RI$(+Q)GY_JKE)8~^_JhTH8d*h!I^u1x;2-5fY2wwv8=&^ss?(Y=e1 z@m+s>_$(0mtH%BH<6LY@OiNOW6s&>rn7?>DQ$ACZp^e|-cehbPe7~U%md@>R1QIud zTaMKA$w*zMlNzZ%1x)J!kb?!(=!}Chy)CRpcNbFv$&enDOEzNgF?1wV?{lN~4&hhT zLX86?aPvaOfe2oH?Y-qPPGo zSl`w(NSzzsk$#3NmKr_hRF>q#Z{^(5OedO;k~&kLI@?_sY*Dxpz|99{JFE z^Ba#(kRk?mz4kcP+zXWMPbE`g_gZ=`4%;KSUwOPeW@xj!1OKEA3(f>h^qnlhK|_oe zE8E^*f*JI(5%KlxKs#MbD+#aR(=oK1OUiDq)pf`?Tj}2`ky8lII2k-cE}YLePh@!@ z$-Z<4P>i9fJtS^F+4vfWnu6Zv#O%)N1EPf^L0^6hNdyOfUm6&T#!b@j`-+^OivCxx z*`HN>8C3=}oXd@er4Mc|>j*e6LFV0_+=Ihi7S(5;_PyWNjtUWkJ-Neun<{)j^@Yv! zwOBcg#nyxLPPr0jfO>dtbjgL9NL79a9^K2S4rH+(yXqbnuJ5XO@#EOhzK|bp3v_D0 zL^|m=CA3#_sxJixr{iSl8ZwIZU0)5&2wWBi4vAre(W%7Zw}#KHtFF{6{Dkg7fgY5m z*>pLg2gTXQ?5%A34Z)cQQTNH{p&}#n40Nx6E8aX3JDevcSIDI0rtT~X8t-G=S7>mM zcH-6jFX{R6ZR6C(u|ew+Wms*Y4>9KZoF9tN#DOSx$^vbgEp5&=bU(q=hVCb9=}YJ` zU`q;(K?L{PI23{JpG3pft-oD-A>8*0S^mPBf?rm0q*j6xQ;gKVRM;zz752INeM*vO ztSl>7?J1pBU6IUJ+$$7p@D!|Yuc0ns`3`n>-Fvs;9@KXKl7Nd0XkleKjQeipab8*o;Fm%x zpw9zAac-AZFF+Jhh|mw*XBp8C?9fR10h!D^i8>&i7x;>?re)$e+*5~?a1d{VJWbLC z+Oj~mKa&8Pe3zHy6@O1)r2REadp>$>nD&^q4$}+cKVg62{*VfJ5)s1kLOa4B^meG- zMiNN5&pdWmwTA@G?)NDR%n4#VWsLE!kF|+T5D)C4yQ|%o4Wq^m}j4e+Xnspb3%Dqi0o)Al7WulcHR?8zLB^e^Pz#HoC1dpkRo zLS49DrYhSLaXCR^ZgQ0SMS6|UEPw#4mgzbf!F?x(bAa<$CmrM*6{CR` zrsuRU0YAMS7V=1&`89r|DE|X%rQNJP>%5BS1ze#hvtL`?KOKQ!A>|^JnxMrOdbp;6 zG&YjBOsh-2_2U7wA7&6tZ)>w|NxXscx7r6)l`6Vd#T`w1!-J~Gm%tn?2fB2;?L6K0 z5qMsE0@28%GA5|f;*Qe=AAv0>{alCQys96OTKYIp38aRawfa91d87V0|Dc6%4t)~( zS5S$wc+CRCNBQoJ^fmMu(HF}6nP&PcQq7^KwOyr;JxEt)Q7M`Bxz`lu6&!cGD>A$$ zswYw^IZ}@^q@jkx6}$l+1Vv4M()!Edj|(Irq=AIyYU^MqNA*z6rbMk07rCDu{%lff zVE{vWv_-;>1$SYkDzt(~Vg4xpIT1#J3{>O(egd;89&JlqJg*72cU}YO-81BdEqy-+ zrJDOeCm`gW zKM<$#u*i}oWwrLXgR$pTm}meSQ$QVZYrB+>g<)^9Y0Zkq_AaMcq))T7p0*x~uf&(P z-BK1Wm6Bi(rBzCXR*`&xVl6xl5!Vk=N}0aDkAo|Izflelg<;_QE0LrK{Qiuoqj?UT z&=9hAg^^X8PDzhs;p}xIGT6ZJ2!M_gL}Cdd%3IPp_z;IBXV(WSQM5V}VB)}@!Z?mz zD>SIbIa=x;CvRL7p4tJb;re3KaJ(ywkp*xsU7JkNO1h4%jP#7tLP*AG2EGDc`P#y1J2RIx?A}wRK9US+MM=Pk}!~ zP}cMZ4NT>VVY1OTJ={W`mK&>6$^88*+!hM|%EkEBZ3piVsiy}8snx*2NDZO4!hmtU zrO{n@AnL+)X zg1G1S53*PMt*C4qS${7Lmwz$R4bzL7x|L)xT6_zbDfPZhqg*ByF9kBfSFN;Sv1Cse z@zfdZ&Zd0~A!Ki+kHE4U0_w;mD9(2^W(y$_gyA%Pj7lO50Y=+3c_pPp12z(j1GH9X z>O;FCeR1y62yA9o`pQOaS85n6rf)P|#s~_B{`v2ALdP`6gOTDlHGofK*@Yr?2A&-r z-?JJaG2Zc~{fE*Wul{U#(cagBzG+hX&aX7V#CUFR1poew%CX<0Kh6&$l{lZ#bSWZ@ zo6h{Zanlh^u>X;8IqKl;6;$emCNePR@T5DpMmiB_#K6+JuC2hpuC54U*k_u8Pw@z{ zgTjH2fnS-rPh^h%6$@WBxR(+=ICnGHKPNKA9?d`o(6#I1Na>J9az^X=a78$S)2Hbg z#4}-5;P;yTz7&iGHBrZMA~e~#DKf55t)}a*;fewmG+4(GjPwkDcLTYUSquZ52=;FX z_xB_aQhEx#uQ{v?KmAz~SucSz8s%RRXgAW^kB31K7>ZOG*r3Ve9Ws3$JJWjHy!I1W zo*BH=eKgDy*uHUkQ~;?kiS7xM<}2#O9RR9)f2}XSMrtdtPBWQA8G>;%ekt7b&uMJY zS>YxFYa*aFts!do`XW>!=~g43Ya-hWu$RM?~1(k}OYF5LhJP zJ0g$Js;U_8t|9#tS=vtD@GV`)%ccoFrfcO20r&F?tr5_9HG<d@3N4qy95)p7@V z;iQr}RbD$^t}35<0iJ-nrgZZo7&kKl8>c|m?F6Qb*{IUVRTj2YcR+#q{e6U1ArJ5_ zGRdKTX>j$hlpI*1(LDs8_2}>zOy6qg98Lszg>s0osBrUz<;cnGhilQrEbtz*&cHV4 zr=5@wzdG+|&Z}S_Pke)fz_fQuO%`bV4paEqRH5mzM4C69)+pCA%=A|x)!o+UlJ5?` zg>F%83aK`tB7s=#@F&wv&6y8zbCLcS2q*3?I`giSYYuXO8bt0wvS_=^ks$|Ghlfnn zIRC2gEx_WII#{mJy^ax5!9Xthh`DIp`$Shlq?~EhzsrSAYPJ%n8qCNXdRXH%pDXW5 z9&TWzW*~(?MKqr2ibwJz)R`41k7Z5uhrZD~H;wIzj+AgN4_7Vq`KreE)2Ik|evUb$ zvVs57=-#^lCuyM-t~ZhXK1d&RbH~y5IU406+E7p-jVm-TGL<2lX6U`HYrhH?3N6y$ z=5Fa;s1)QgJsFPZKT^ThUVN681VCH^9~gF`PBUnsj=%WAlY50S5vIO*icU= ziQxjkf8x_xry(B_5nu0E0#(0SgY63uxCg#Or=`&e==AhDm&oYO#sazBKO@FMcPyss zM5Kp-`C(X4_nZec&`U*z`xDKfBM?1X9QRpxlU>7X*dAG6(@~|Ad%C9dgd;oEAg$x^ zw7w*@bMbw|ss)Zs>UurWhV!9+w_$os1OM>|yz?|0R_hku#;oRFSH1 z%Epu>YF2gh?w*ps5gbhH809@8v*7>~ZW|t|J1=fHQuhyWV2U{Ko8j?VX}na{f`=?T zgv`U;H4`cEJ1~B@{}-#9YtPw;uFGl>If^Z=krJSyZ?f!9{DWr1K^T7x-b3PK#U zBYdShp3G-9svcEj>`LPIUB_Lg8hecDxPbVNP5&Q*|QMW6$=QpS!S@o)Q6Qg$rSXW>>BDcXM!ndaoHv+e(4;pbSqboU^<#2JG z3VIsdpzf4QMGmVv_}xifuck2*RzVsr`7L$mind$bZ0wZpZ|H57pNMImdhpFi1IXLV z7M~U&UphzH@C}Z-QzDm4p^ljRpPDNoj9?}kOtFd*hL&XA{5WdPO$ z8b;&#b{_ZMUcG>eWh3`ixtWTeJ2ueSZl)4Hv#NAQ6yToS_fY-~#}8c=`1`)d>F3kI zHb{JZ=(6~r>agm$1)y<}vxakwSZ9S!SWB_|IE3v&d!wlQ(B%yXD~g#5e2+qP6A=N7 zKiiV$od%d2{&O9FW1#EvGJih{uS5edGsxm6Miht6sT;t{w! z{Sys~4FeAwel=rzcer72;K$HQ>BSir-qR#SqXhwrq;rC4*QD^*SPdzRH$0^r#AUfO zm>9yxyA|jt$slkpx>?~#O(&p6RlGyC9J9JyKR3IIdh>rCHMB$TZSu)nvubrU{~v4b z9@f;A?g8)YTnJ%XNq~reN;X7-+SUYH!0L>N$VIdx5fQ13Boe%|ol)vkYxNv8?PdYrHq14E-pzzQ=GO` z+oju4TFI53U|~yFek3ctN@pV%9j(uAS4$XR{8R@KfrOK;OEfNxG%nyY{zC@>CCV!a zuwYe}OX?}4k3lQvLHeAm+0hZ;i#5gNAfGNjJVc@eCpDOTZf;?Q;u{NH)JfRqT zfZ|NV7n=jRd~*psqxn;Ufv4lXjuh+ki7_R7H?RM_s#sT%sQ?p*O)b{E8MI|4tXy1m z#vRh#g~IxSil8pR(snJtPdsFP#4-Mm&oYMD_o~&BkqB7;+HaED)d;>1D}e|VPrx$k zx1czb0H=Qw;3q4-w>@-Q`aU7H8txiGp`+d#02VA(uXf{S$>(_8(}2f4Vvoeu^O-9T z{M3z8?g{PcRX+H?)EfBITDe$DuC`${P&6u76rZ{cyEU_9(W)YS zR>WCE_iJe>e;T=5wdPwf?AjkGGl|$od?g%5#AAJi?JE&aB*$1T`G{&t_m)|W>)@*9 z@M~S_rP3i`9G1ZCfqATWt{LMKxRK{oA(7~oFcYS3QqoDCRKP!gyR4KpCNfa9=2N)* z!+D$=;7=-7X^tpX<$e&u>`qdw`K#)z)J)@C*zlM@6Xq$q4J|tRKJT^X4i*Q@O(-rmx7@5=1_mbQDI+dZkJ?e6EEGmSP4@A_m3xa}87V%mJLD@-3@`WWcwHcJE0 zAGwS}qVErpmbM(S3Brykr5KOH$JlN2drPWSoTAkLAM1v`-$lFP>WOwG{6|96b2R`7 z5<7~cT_=}Fwk|+U2uttCzdPj?tmlP^lQn{cS}pCa;hSQPJPj_MH1}jn1BBd8&7{3e zfK0oz-2BWEj-9vs&GKwTc4BrW#!oqqb{_xRx;0{=kB#HY z=@}qc{MsGF4>G=`vmYb3eoDJTe7^Wk_?{tsi?Yd+_@3Y8U4jyneL&|t_6U+G&Gn|P z{@9wX?Moz@#7-0oAJ_4<_dsMD zLohmZBCPNpo%96q9$mmenSQSelug?Ni_7Bgze(1szNS(qOTpkuvg~`t?|?UM~w7; ze)xCzKf^`;CmHGgIR9^TZ~9!n)s^~;uMk7`Bk?Z9TmX-H`jSB&c{qjC6KMb1eAy}K z;CuS#o&K=~KKkVG1=L%|$b`ehYi{+exzQ90Wnd^Vhfed_5D&Ydp*~&{-b^Z|GzNlY z39t^lbK}iOz$c8M5rb}a`K>5!LZ~L{q-Ih=G%nql4*epKUM4(~2ug)xpJvBDwQh=W zOO~fR?%=-d>6`ZAp&P~Bn!_theOv8vek!x(>X?G3HQ9Yro?3TV-KpN^Uw3YMRZd_R zNut7Aq4V+XblDxf;btYNV^nKMXizn#@g_OhhFFc-i$^DHJO@U+U7kM0Grr+o<&LKU zFB+SnbwXm zNvpG+kl1BnOgk~?tY@d;++z2cnCyOdonZNbyrygJ+IV-Z)?KS}*Cx1Ylian?zZ8+x z_!F2I3hyld5cE-CT2CL5f2O>pf(6B{;VO?0V7B$!_(YpS0XMPr4xIFIPEleg(VjUS z@P#v&_Fz#5C$;=;g*Z=89I-+76IOztb#BE>S$56(hXqh3g^(tbXbl9Kx~_^Oi|Z@6 z#~cev<%W6XMR<*m`Al_Qx$Jnl)N5EC+>Og1T|ta1bSUN_(xg~Xl&q&HIguvR?|RzT zc2O5-%%wj3p#5$>(d|&U**v>LX7@5p<|T%CGHU-V{0>V#P>-NQiYu$Jb-n@Ya z2AR2R0ku4XxG8Q&sxW==dfi>{<_R!puuw!xoRSP=A4Os}NJhs**Jx;Wp7?-XE$vhr zeg18ud~N9+K37hY32aZk>LMggFJSx3qz-U~hr{@GW>RTg5^XoHU-_Dejfmhzj4(cs^ZB zcMC2HYycsLI#F+}t~cnWc(2tvl7&qa<14%O<0Q81&kj!Uf`VKB`1;sT?~LiqEyZvy z6ksP^+dV<=oo4-@Ks$YgN5Ksv%ZZh34J*^1P*}MI!OqK5rum@oJ>_xhz9Q|if*xdC zR?u*&Ks#kx&%Sc)lsP>g%)$Q#n{Qc4!KpdggZt|pNp^?c_4tH$H^_uV)Pzcn&AYNF zNfTg&8v2G-On|lfmf`ii&T}bqF7%e4c>Tzb)Q<3#yJsTP))lw(1-GnKi`;RrHk*MIijd{#JjFc*sA%q^78;&@ya*7_C?%pPWP4{QMkUIu(j$Ry+4Cu zQZ&YRW5U*n7X$2PF{gX;xHRrz<5v^5j`?ITqWOrzczwdwl#gw`DbsDx7 z-*)AUdUbv0kh5jN7bH|TQ`XhJ$a{%|>!jX(nDSw}48Iq_vya%2Y;Eb&ZLq6SLU%&p zk59+*tIg|h)GPd(N8t^s);9ft7%mQSIN>EK$_;5<&LuoOWYfAWtwQyXO|!Sms*IoK zsBD8L;=*N&$MGJn$-lsz|H=k?r_!?9blRaDZ)p&`R2bye@8~zMTo|CXbuUjn(Ww-k zr??k1XUg8KO6pW@GYhR0(Q59DZG`jOcNLbM-4iXidkFtU@j)+3t=ULnXw@7fKrlBX z3!x^8>u;+D+my1br_Xm^fwM$motRtM*bB>|&0IpYssRn3wL-5v-RjtM|2l}`^|RmJ z)SfQvB5*V0)tcQevyD?CF-uw1Pa_@&w=K`nWF6n#Lyi{@lnFb;=9hV_t>)c_p7cTf zb>b9&{ zEfZEzdxD)eQ*zF1{!BBg*Lv_}jDWvtl>Wru3x6H)8Pu2u;g^)_v_aV|q@MU}2!`dS zG%PRRor#O^If40iRgBtb>4vDxzhqQJ$N8=?i#ioJD}?(gA31q+y*{d9%(=IXi+V>d z`b-1gF>+x%rTPDgJ7N9a|AduU<0vxuS++gCZRDce!&RM%!dl>&>uiGibd0Be7C2CN z+~v}3Zj6vYC86rqVo>RyAc1rEQIrM9k(4l5vnK^EP-sVaL>NOY?~Pk@ULN$}fO|yH zQx?_52-CdPx3e2NUK~YumN&Qh{ImgzBI;J5d7E#yX)rawHV)u{6xx%qRu3}5!vs~7 z`oo{t!sY-Vd3_DS4KbQ`?x>VtU88Tnp|r0lywPWTTiS4qU*MPOlk)hcAb6Fs3~taj ziDxg>8S+BGN_~WGx<)HM8O#&mqFB@3|7=(n?>@7ndGWhbu|{0Kjh-rKCkjNhVq9{= z$0_k{ehdWOCZ70Ps2tl1+5@qrl#ZU5ury7UXfo1-m+AtRCRT`{I(?x`AySQi zG+v-nMcQ<2G>TvuUrCs$K~?rKjNPb&+@M->Sp$6||H}z2I?a@ho_$U5%+d3KN4wo~ z%A;LB@$}tFNb!m5#`7xF>zfMFQG#zz1SwqgGEDTEC#KG^my1mXZPATav_icjJ6T)V zP*BH`ck)ULr?M*SwQ6Sf#x!>_fr7?#W0P~eVbK=lk;tXN%uU;FE) zxD-x3Ys0!0?a*rVqSwmArfoChbx!#Cy98@l?GFEr4NyO8XzGFMwe|alK(Qq#8{syw z82(nXPdn7DQ?Ea$_2A|15gndjF}&OlP4&3ThNf;yU5TfeExdN%F z(6z+;z`v5D$VHAPK*Z#VxWr@A^2j^pc=57p-bv*{`@w>x1#WCjXm^gsBY=DlJ%5>g z-#U>iiaA);u%b!ZBAeot72_5JMu+e&aVpnBm){^M)x_fy?^ANgGtRp0aV=JKc>Zv= zHMzx_$`#Kqaa)JCSkquY=C+RHo^X4a$D86qy~zQ~hQoNqcS8qW%S-ie>h*ektJY^= zPc>=xZ3pJ0w|Eu!4?Ce&b8|kIjd1hM7H@;z$h3HS@YM?ETkaCht&457&~pGKL)^T) zMHkyrd{|?M;Cbdw>erbKx=K=^1ka4rr!b;aPqk%d_wyOL~VK{sv)-c1&SEEt|Nfj zcIQ3QZ#j<#TCtwbOBs>NXV3~~#9SRtoqA%&?pIkD)AU<{2JQHFh$a?JM}Za)P!JI( z#oP-!b|F7nv?|!!Mn3PvZa1Tp)`z@!BetYWF zwKP2SZ2Viq^#o?Sy*|L_X+$&8ilwY^6-3aQy!!E2xD&Ksp~GNrdJZi0awopG<|xLc z@g<^Bg1y54*3}moJ)Ko`0QbN-kym_l%eW$;z20Jjy`PR7CcPw&{SNyq6wN`BzoC6Y zc8mLrI}hCktjzbL+bZoN=meZ&;HcR|O}!2y3~24a!-h`%e8=v*FQ^mwgmC)Rx81rp zdJ^}V{)QZghOg+vD?OGLT^zTzrC3GNgrWZrf`t|1b$57d#fN zL@K$F)D2NTsaqgkx<3HlQF;W`SFJg`JzSUI)Wy!!?7LrEBaX<@oW=DRlbWSHi*jNX zJL&i32P|y*j*I{=j*mHev*290$Z5JGYWH}*`; z%J}#H+8TUdal=3lw)(oPg%j(RK72vNJmhhzWD`B(2YMR*sok(KH1O@Ey0cjGA%_Ak zSO-dkF$6m=1g*?Bd*P1&2JV&_c$))1+>H9EvOG)8DntELHqYXm3SY{1`di{u9g0k> z3k}>_`tbNkJ!i|7IAFx5|Hn5x&z&X()#PArBCXA?2xIg16m1z{*?Y=TNMP~QUUcNR zapKrD1}M*|q6Ah&zK<}7u(-mk?IYfRclJ71Z_&JBH11&1xo+TBImrmyEf%}lWP#zI z9L5jh(^sg#`3L}Mglm*s@&2tsVl@(8sAsZGI>W_UFd!7ZV-p%o#D5Ea6~E>NU#sQI z)!;AWX9n9~?@RIURd$odzgm}+{8WD{1|B7P9A*u0t-I#j;O*3w!)EvDxFht#`VBBlAw!zxKLBK#4fDf}1eOgB;qzM@2+=KXG4+tk{qZ30({4d*I0W3-9UoS@9Vr_8-yR=xc|t&mUQnVR$f zpr5FYqvV|wby9O4FT@;C3RkP}C5-wGKE?=>!1MBt`2@E{ZTP54zl!O~t_`FZKPIF~ zd)WVJq@g22xIiU)Gi%?@tQFF!yf8$9LM;<<^!spl7_BA8bfo}}|3iYq{oeRV#0%Rl zI9o%VIQW4tADfa0cf3lfGoA+QZ_?Zcy&6CZe-sJsW%eD6hr9Oihtjz{7{9*(TMBWy z|ES&3`WUM3{b+q3M7*Z|p}y-2QQvz%sP9|^$c~ZqzMLNN;*Nof{$vf&5@P>o&0ShJ zxaM3h-&u3u?xVHByR@B&>reoXTPI}Fq2!h;d;hku$>5eN(#FCMuUtM;(kesf7<|WTDx-QvuWw{vt9=mvc8dChYFkahxb874{J<&vNOef%~RH=#*meu;p#Y z!LpyqP-z9lQXASr3k4s2P}?2MlR*wDA{wESpz|`geAl$VYag#=wrSHn=^)N{*^n05 zP>bxYhHY@wCrdY_Z^}s*_l@AuMB3vd$l$$|)mP1Au|=7{AjS{xNaZtdujF`MfyL76 zUr5TqLObO@0-j-}u$zKi-h~wQ4@OTC+9)V8rRmOtx$;?6yfr3h)p*l?wXb`HH}ET; zH8yC)CAR$GF5appPUEGB+o0zS@qy1ql3Q`ug6qqy^lPRo~VmRSR3Q#+xThN{pQdo{g za}W1Evhcj-V4JXvCb4VDLcm-``5*2==oeB++|GGkjqLh^DzU$Isc7{==KTzmb%hNGs=LJIRZ*DQUMU4Kg$fE_oXhDK^K%ygX}nI1Q>dX~+rdMi3QUhp zVu3=ljf7RC z{1Dczi!X)A2aOA{ow}|JCWM7}s7Ntgmz}^7nx4(^XiOdv047yd0`b=U|B;Qd?^9XK z@-yG-U%c*4O9a}Y7-zAK z6LCm*&H3cZ03=tyS_kgBvDE>cFv)H?K2<^smG?}=_R%Dk|E*YFey2QMefU4Mqv1#G z*z)6cJo`VlW7&_|vF-=$5SaOJ(L+a>?F5|nRcmPJt)?u_*G<8r$(^btW=K;?o!oE_ zKN-$7&d2U)4ff+;Z!(qLI_aGB6y)b05`e}_wq2|3115*PyH2GRi9t3|1 zdiHV3yH+$LI36!7r?0I`S<>k8zfDhlI4A}@-FTYhCmg&rEpNHWG2+TvBAK|9T>X&X zQPe9eq{yjc-O! zL6KOIT)0jaI8bu~?<=}Kgr7Ns@QUaJKS=?XfZ{x3ZQUkv{SxIC^WhBmyt0!v|HVpB zLilw$QVGwuMZAl#jVqj1Wzeej*4){~v8%_v*;d-+w2~M+{B-2-gpKvZmPccDJOd+< zWAVa0;%Ka99#s@)k|?=&LgS6dqG5Lh`{Hr52%{@ilu@pi-zS}LSKjFe` zJOxGOSty8axO9c(F1&YOT(IY{ymhES;e9EGB$|D-&KelzJkbzu~`V z4c|EQ6J;Q1n^RoY64%%g|AWP@s$%0`wYU;F8N(M2q~*fW|2mb=XAM^z5S({dyo~S# z#ZaD$h|+h!*qRak70q?gk;m?NhvVKbPv!#bNjZ#Liz%rtWeDtA844DP+7KY{<-&*2 zQh&Vz`#i-E?Dr@NQhVV&DUZnNqy1L+ivtLO=L+GR$?uQfL?i{pgE1lEMeQBDa4>26 zi(1&iY$j_$Zk?M|RWoTj5z)5*7W;Azj$r)1DYk|jHU%?q%-ZWX$(~Wr>wd2LORTRr zxYU564}M0jp#;?JvL+;_{hfk&jP;PCSkYW7l3CcDM_d_~NKmtwahXLe9~R3ij@>GI z(Gf@}R-SvNU0JrrVVlEPy$)_8JUm?^={z^K5bSR2ZU-rMFs|$paZ>Sy05?zom9UCq zUpu@G>oX3!irJy$l=eat0Y%WOw%0Mj5sE`wH~HSf2s6>|uuD9yUY0lzkilS7USkut-v3aEhMF*^!u z35v>`5_9pyc?R*i4uvZiY?m!{ELQ3t|JS1mcY-OasOYj3LYy@xGkW;3E}y-zed|l`;I( zap6UX;_#BV7dJVDu$ijLx+J}$X1I?az(EZ>KNC^5@`Nbd~?eO^F@mz2(?0< z5vCAiIR8mWpSTVj0J#34yEfLJBgSB&Mx>}Bku^6#Dho{nzb@qy&vL!#wl&*fZ<}79 z$T;qCnAFRj?OD3JG%qWE>PejIV2fTNLAA$hg3?9$%7$gju5oOAIV0o{i0tKapNk3O ziB8fYE4#}PPztGH|F++zXL8{JKK2O2S;AR@0sc1(fm_Xc4sOb6*u?j^+e)&!$JVz^ zhfE-*Q-!MDqHF*T&wi_O@D?H-8##CjqP%3Pt8XAucD-hmQXjfaErVe0C}p>R#~w40 z=h38_l&#|Zo6ujyb&}TP%^KLJ?zn3BwuVdTW(OVsm$@^p_eRaWeJhL)7Z3Wl6rZ~z z`podx8WXz%FIsU!#{XsAsZ%Q|W-?Q%w=^5c+Prk9@HJJ~ZpQ0xmu{Cp;r@ucv_tSw zq~Wa^4DcnNL5@3?aG9bSLBpI^hF-jgy+%PT8=dkRoq1@N;aE)`yJM=wTMM!8Ta?zk z8tOs!>PSf?dd5IMLsw#f#%Kv|{Xr-VhJR4l5T9<3nj?Zw*%B zemud446tP1Ao`W8r+u-Dtr0$@X!A43b9seuPRgV2xYhOT0^#rU6_8`K|4|BI7Z47M z`Jbxkm+KG5nb+fY;3ja}=S`R9xgCzIzP7q+@)YM@%Yic8np*4KpdiYuzFwKdil zdx|SgeBtjcu2}j7_Tcx63{TYXxLoiIynh(}lfuoXVdnx{ol%^Iw~lf>RNS_@26t+| zwfKAfQ~wa*Qhh!~n&x(S#l$aQSKj+YMc2}rwxu<<Mo$mlUF z9^F=*1O8*K{VfuGAe7f|Y`)~j%xtak$fJIfNnOZ;(!LA^Dhn0cZyP4noYZ{SIFGgi zIA8ecvsIZ|J%Q)rRkSvw=-bf#}5SMW8mXmBs z2LK42)O@!WV8*Nh*Pw`5{^bJb<-bPJS&*sxErQHPVko45?_9H0enQr zk#`406Rr*`Zj5IbQ*yTnWzu_Apvbe7*7f0nIKDIPfEm7ggf@!lHWTdQ1p6c#-_aoK zq}YlRSNd=)W0xanzbjUe12LvQ`PKPs;o(TPiHq^|nx1GA8YnY5iD6Cgbhp7*l5mPJ zg#3qzx#2&Ii>bGo(2!n}u!6D&WhSWvd?qu8GN{ZkvCJ;ip|_~f625ma#snHOt3>!T zChg0)YaOQD`_pV~n}RPjrxbA9!TrA88etZdEne<(B- zK8D5{sGZ_5O+45Q+~%o2gxAy+zbc|KgPtl~kS7l)&dnwdAls?++*nXt;`pnw;TdeK z@C?NsVZo7TTd*K6163U5QuXeBYH&}aZ&XAdI?ly4ejBmLReKUKDQVoKIN;GOl3Sm~ zl$?jEQ>tWisw(bFh!}ph0MRye0uHod zqbzFl&+WzA8SvXM4qR~`J3i=TT=#1OPFEVp3+g`|$v45G8SGPtAELjE7jptWKK5WR zTqMJQo(^|tea-+tA=2$^=TgHRvhUh0F@OLIOl-WS2Vd31@%k zIv{(XVU=F*!M7U%)E|t6%x@gj_YlWHYMqD|K3*lfNHyY}0ww9x+D|L%ljM{1D_>2S zK9y5?*xbZPK{>OyA3P=%EQwNc3PD@1a*{rpjyeUilNe))!gu0Z2q=IZ4I38v=CJNL z^4+iQA&F_;8I*)SC2X{48`MaM9>MGlzOmHCSZ|k$jND2^D#@(ob@|82QgP2tG!9du zIozMPCG7`;Sn78A-Tbc9IqrVhKF>n8a~Hu*C)j92UKjq6**WWf zP&&)O2UI$}k-3S}MQvUpEDm4t@w=W@?Rme2C*(N24V3AAvj!Uzc>LTOUy2w5t*5@Z24ftvwL1Y^iujtYS78|fGPO4@tC z0%$Ckm^70WVor#d^922NV|30A{2t6!>rBK>f;Ug(TxekfgF~}et zNubA>P*IBnSeQXwZ+oX&SV$4#`XvA5w$0&roO&C(`R(c^%QoHSQ`JrOZ9I2&TgYu2 zhm}pp=-kDhR<_vXn@?1`ZHe3X&2Ln1v(P_?PigJYInY-^NRC_Q~3-FrTL(?8Sgpz&m*e6oxdS(aNi=Bg~4 znWJSO)#)I?PJ>6=!>6C>NdI74`V~+5zB%b3S$a^Gc3PHsL1wxt8{2S5)-WJzI4^7X zr;Lec0T#d|$l!uDM2IErzb-RusOD7J;PSFiCP9MJI?QP$^E(&EiuS;gK>br0Q19|= zbOs$0&Gbz2EWA&wqXmpHAsN|fv9B5?Jzd&6DehN;aRw=l$V`f72?NEkljLc$=-Ul> z+S2N#|4E)UgvK25v|o$zG?|FUKbEJRqu3wF)6PmUKa!`7r`Qo!+8(SH{zO4(Zkuhw zZt5rX3w%JxJ|2q7KK??CWUFM5SlWioRQu#G%Z@vQn$ zW!j_-yM$M%_7_w~V$vqN-%Q9&9e#31XKa)9tXa}ffJgij2}jgt%za-)mfl_*@;{wiBME zG2=tY$SaPy1KVb?Zu!UaOAM8UVs?tFr|j?ZYZe*?M{mlyo~nu_GX}433N!aLw(zG+ z#p^>KRR+u*kE3Ic6S%dCPL=ya^2&rn*gMOFRTSru)gMppR1?1-&piGytNE?@<5#-H z|M98oujIib>dJc94?@xC)JpBd`&X}cI_3p=z_30g^@tiXAls%D>IhJ))+1|qBiY@b zj46QF02;#GJ;LGn`(Cy-9C8bX<~JOQzp_z#up93r9LzcR8rB#XOXBi!or&b@uH2`s znhkyXC2UpQ5{x*;U>J?y<x>LBK2}(=3tbRGOynMe^@LHkOXh>=x$;tourp z%{dak^FHTd>~bd6wR9!C@|=4;HK!=|pVp7;NXq*h|8TbBw%s9~4X3i==D497wGdk6 z(4|-TKun7EH^u`BVU~y?=DJmEV1Ph3nt*hFC#JZ`c1^S zPEjSk(0mGi66u@6%o40vZX4FE-@>Xwkzj%>+CSqD`uEBm$YTHAh>Xqgm?1r4EOI=h zSV^uP6@@`8L`#CqV#j-d&`>TUJwY)&4nDWJA(#L(ltaz_8pWM9|LzBn{YN9v+WP*m z7+81MCNjDzsF5LW0*&miegM~aAX4`VTljb+coasa7}_gT*}?As zL+(bU)=}FU9}&Y1(G@e%j<`Pf3;TxrPC*zY(h}8*T-^h>?#_Z1=Tgdv-N*iVavydE ztg;DIJJ|wIHLpYjGkpu==|5791d%9C>|cvn55M`yL*rNU)OdQ9%{DZwGi;jU-sEx5 z?RM$s$Q-XcH1}1da6oKJjIf4Iv}z63MpT~sRis-N5GlaDFsh;2wnpZ$tLMy<_F+_} z6)P1*{?9}tdvNRN)>T!^P2DD$p6-s!)4|xHWA?6LR8}S2A1&+bOO9JfW&3q#vuGxJInu6E zor#_SWosTv&*_Im#p?%jFuolvwfei_Nr?N0c( zT~~M`GHZ4Ni1t~pz>y1LA5}grPs?4DsE6_}!G4!uJNu%r83wQOOrKh!E4+kGgAVU1 zd}t>7kk1}U1WTF_cX=ec94?w``GU0UV|>8`zBYlcP2_8n_}XE7Z8BdwoUcvcYg75! zG`@BuUl7NatFj9W_dR4eHX(n%`xxF`?o>LDjjKO4!*Xms>3P%OAyOs0Lm|Vshq}f+ z#MkP$At&P`cH!kns5cEuoQvK)-ivf)J_HFgGN4899!dt8mH1by%~tRQAjo`~DHx-N zX^euI$-c~C$QNE8kpjkFB9MUeg_MqZ_ep3cyd?gz!eWX?-^*NOHlAFwq)@xH);xPAFbo^V#EtM~I8RR@2_nvrxNqQPGPzA_4^Yk%R*tycypc zYvdKrw+UZS9b*rsaj17C4L$D0*y$imwS)ElYyB5;3;WdNbvCwt&jeeWY}}r)L0{+| z;StJev+KzY^q%|+7F#*UFV}{`%a<&=_?ugNp-SWCLUK=tP0@x&+WWc0DbUo#6NEOr zO^eGvP2KuJz2+P0j(8JMW+fyTYqJ6^7>Ng{`LKO%>AM`|M}UUG;3@=r=+ZcB_!`JFzbz2XV zYMS6KS2vZr%ekf%?(+DiXWX^J+_lN>+7a&BRCl=zO%NSm5D_m{R*{7Y@~8q|=1BDP z<5>t|JNXy=5?4Z`!9HZHmu89l1ks#!0>HQ>2ZMMsv(XlMM%HmAI+Ofiz z4L5j;cN5|Hr;&*kpqS{tWxfLQ-%aD;IU?eGV28O;P*^9>qJnek1lXnoBD)kYN7j zJd0C&=11g_OrABRX9bOmiXILS$A(Z&tFYr)_`L+F=)T;p3-izgdmH(<@}G@V*)cTY z5j&l_v0NOQP$fxEDT7fu_*^y`>L2KIxeTtyO_G!$1ruaBv$C6x&@YM-u=wpAQ0Mn3JP^pYOM;ZF*2#8bW)1xO}m5^K}J zx5cI+;MnPiC_8YO737=7nG}O0iXVvBlnFtjDwL$r*T$eGo0nv8;W(;0q)hB~NnY`9 z$c33S4>qOl@CqO?1QZ*r&hpjHBsGe5yPV}u`rtQI6)IojEcizFg1BkXmR&&n5Q2HW z5Or1j{nH=zq44)$5hEE7Er6I|zSlN?giyVX1`Az87XMKe5cJ1BX;JF%UTWJW@3L#o zP~`@z{%owfcazWiYj2kN}aFs*Z6*!W(D&ZQry6FzzH9x;xw27jDhjIT=;(|yEp@? zU%|h#1kQt5YAJuRr{`LCSw{dAlFxgpaAm|oslOJz`2UumVzF2L48Jxh9#R_>Xv*lC z-tkd)4%WGgwA&JkGlb1z30Tum31G3PMk+Zj;ED8SF+o7d;%vg`O3B^-gdk)e`Wsq{MYi|%m2i(NNZW70|U+GAPo1vB~MGR z%q{FXUCGI9-c6RG-{3Mby@+sU3*Awqd&K8pvu6rbR6$pNrQLf9pH*|I{AMu|Z33=; ziJ8j8Og)vBHYm+yj?Wd>^M6q;X}b+y7PA#mwl!bSrI-UlKrqn^S>}$0TA8KjL35ze zvM4dvskFf9UeSZ;`xGQ=SW9KnyTtI5VmK&G zd?sF9s-;%HJ(~J6nlku~uMjdR5YP&|_$zKAACtu9{Rb%na;8!O293&IB27q&)KjE% z2l1(%WXB4f|Du|#JL(c_;z(=ZxvEL!*)q)6x*uCjy*7w>}}}86!i`diidJ} z@#i$x2joG6USheTGtgashvpACg}223cC37{iXrs>@<9uqcwSR1=jIo$Aft1@wF=V2 zkaG;07#t2ww7Z308{HLONsxw8Q9=+9Y2|{K#F0TmQplh`Z5VdJkbKoJ93zDi#-q%R zg@?uWRN8J|-Y{6zq~aBYf5+RGG-qwM&%x?A@w~iP!;PaRz-c0FM@cr!qgW4K<>RFO zKr>|6vUTGZPiR_R-)maAm2I@&8H8{uHsgFRK?9zyd6Qa`F1(Iwg+R`oUqkLIEK{|J`~u3_qHzZr$j1b5oheflD4hG%UMD zz4Xa%EWcn#>M!fILJ?}&dxVUxUlgu|Jgi)JjLPp>5B!o2xTAP}Jn?)?o`#!|_t+5< zzI8*IMkI9juaQF7x>amZc6~5cYUAp9iZ72qn`*F?;XQH*aJAIV#DT9on)5N9Roo-s zJfJR>h6(YuRhskMs+9xH6c@v&;9Hzq1C3*`ZjXjb^Q>xwBpiEr1%Y`~)7KH{#+Fie z9t)^kC=_91JPRlQEWbSyzkPUt6Nx{ixWPvIPerhm7K%I&+{tNe^a86D)+;lko8uEi zgXMpoXPE~p!BRd~H!+x@@bzXJ7e%_w{nj&O7adm((B;TBE|Krhn5H7P=X3nS3k}JM z{!OE?`0l0}VcBy97f^BI#`+6bO5N=t4xHlHyy=3Gapp25ox={ z7LZV-{36}3Kp~uSfEsfxjbI!SDc_?SoFLQ(2S}b|!AKO4J%PzfC>0gF^Q&fR>{V*$ zd25cu?r60nt8-t8TV;A74tm`&L~^dmdqE@Wb?<3fWyu{j7Hww;?plp|n0jtrDx`2; z8cB|Q!oXX(JhRC_3f$PDFh5Y?*3>7cSKbF10I*He-&P2p)9T8zml!1d?Z!cSu_H39 zF-sX!q6H5^+<&Oep{(U!FJJegaPe5HIRa1Vie=VB1#}rWtHJrk2`{ zjgnyw52v=@hqk{><<@Fii#!GE^E06u-a`@S#4rDwPBe-dq0|d*RYB#{xw$MjwcqvQ zk3Z~3A5k5IE7rQ1!QL9ow|F6>cRrfLeas9e!Qj$nS{!QOw^TORn=bJWU7ttV!QadT zQ+fv_Y-|&@)9)bS(2bBpf8j^Ovt&y&&u01sDwk5*X^wFh2&~^SB&dLH-k+fb1SdcL zCE*Wgm2RT!?GU%%{!QcRqj9yLh<_A*7HCYLp!B?jrS*7Mme1eCag$@ttM@z;JQm-n ze8YU!APAJ9-+aaZ-T&6ir-w{d%#2lGqFX0C&51a2*i&rDO?&|3yppoc)L`F&uKQ#3 z0YAVP?pg{0Hxs1cE^*vZ`kyK9!}2AZffD@DcxsS~GD~{@F-KIwLi)_JFNx~?H%j9z z;q@;i9I+&@5>i;IG&42xrblsOF)-tmJD33${vc-Td4dpQ3>sWYz}IR#MG{VbIs>0S z!f6#wED5JqO3V)V3evv`qMDhL5G|mD9uwS`K7DtiNb`>S6ik=VlmBs%>;C`5zoz_ZX`xW3I0oPWPXCnYx9nstDVt+Gf*qDh=bh?*CMA~u~>Od&*=j;r;TggKyaL+NyUTuBOYzF za(btnsZV0WUc3;}L9IzzAI3k>bwr|x!l$P>W>s{n^oPEBz)w}Io<<6q(asNJ`_4oF z()&z@uj2VHAuEZ(8^*#1@71I@car8pQta2ugGmZslBy*M7ZvSQW%36X)1ijqSsqGK zo=%E^ESV(AhqMq9pE^q%hGmD+@%XT>cN%K+|DAo7;)M#@`7R1RYUp{+HBdQBGE7$j=!e)dMl~nS0G*n@v%&Jo&-_8w!~oX zvJRiq!6PyJdZhhrqy-&!3D1eiy_LeVQoeB*cqPoy$AP?amJwCre=E}ddC(Exw~hAw zNrb!D7N*fJ!CyZJ;3*1#@RIflAu`9ur$VvlWw8$-lYc5U3yEIjIvrn+wxh8j0J@)x0#lAX;5)|LSfo4KhqUgVFn7Fr2A}|=d>!tXmaRLwNYAJk1 zP!pp(q>HoXZe8OD&f$`ds7l-N-F7SSKk$sAJ!Bf>kmSk1@yHf|$%S_M6`qz_SQ?y6 z9Hba(2!7oZ8`9~(KKk%7LGm-M6F?Se2gaEF%(MTFX zNof0VYC8^Zao)b;4_%6i@add@`Vjf=Dawlj3fS!T2_HohslTt%b90NSvrCrK1~io! zy(Jyi^@Woeds2)=$K@uG^XNdme)?T7oX_a9(QM|q^|Oa`8~g7&GwtG>8?NWujQiN2 zOcRpbby}voAk#Z#u@>17pA4>AlD@CsQS&`Up;H!Tkq!095?W-#+_IFbvf)hK4;Y0| z?$}qC-jfqm@d(PekSzYREb)RY`Km1SNBSMm?2v#2sVG1#MEr{Lpb^i{XW zdxl5?6K7r=e~ETRTYBi_gSA?@gTo&7i3F?`vGcK((y=SQ^Te?tR)M0>#&%6o?f z{4tH$OsW4Zjrr7fDWGX2I&3SQ**~Jg9-(~yAL%f7#Swl<v?Pp0XkU@Zu&*de-|WJ~d9XW}N~{RE9m8yfbfVdxApfwg zR_wn}pf0dE;)RJ+eXw_mbl!xoMA`+U9M~-6Q37dM-%kO8Vi<=15E3MhqDB9X5&0z1 z8|4}&c7qi@o{rqn^@n>g5#?Bzzo%60;`$a&_+5FoT3^aMu+w$dG~vbafVz40c?AsJ zSz|yZc*{NN=2cRm@8I~nX~KOp2mQ8gd#lsLzA-&p19=*rdp}UMZKZpBevG5omFj=l87vhe-_ ze@{VpLqT|LfxZOGryE8&s)zfiz zEA+`Kd$RiYD{-xPPqTNcpN_>9jA=E^opd#jw_}NYxcc~g>dNe=V_#4sKnjOby&%RsLC*I!B=aY)k(_G5H7w;tw0lnu=RIks6 zpau6h*b+ZT2>6KOYOn+v5jIha!W z+%3cM?D~wDJexg{aVMzfb}zzOHuT|b1u0_vEBC;Vx)tD?2Eoe(Llpen?tIh40eiNg z-Hh?bH{_ea4xHP4pU0Nl8bfeYIDfFuCPeeEeOa0+(h_eyxhPaBbUcY zVKYrxA9UXY##W}XE}L!fg0vgiseq?A;TP2UvZb>pYu@Yv^*=XZ0vc1^M+WeB*y0EX`K zOBwrgg{4XkQ~{nuRRr22B`MuGYuQIN&2Pew3>u7m9+toD_vdBQ6sGIHkaSYQyCUtG zloK{5Qa-Zk0SC3+l9w@)m1Y{4DQXfxVS-Y_9k(S70b!A-Kfns}sik+r$pqFHjbKRO zcCv3+-mrCNH0he`>r+R*`F1CpZAQQGD2eG@Y?B4Qc?18*o84r~x0C+H)3M<2Fi*!e z;y>1D8}VVKqhs7t628oB(U!?)L+GX7$oP&Ct!ms|(3LdX*_-C;CGru<@kpAObHf%J79~Bncuoy?AMu^#(_$8`M2LL`_^8mZ2ndBd{bh_983(il7Y%F z8Widabd4|D+b-Gh8Zq7?ZqI8k-d2eTMSR=G_U4Tatokz-Rtq;jQ{Fa7Nu+e4i~zX;H>^__7VAiA&5SR*N;}$qxrT zk-=V$?zfE1n^gojMg+2pwrurzy|`m{`1~ta)dk2QljH<8k+{a-saw1sz$0$O3T4p9 zhLTj=kP~mhY`})ML&}V=e*>3f=;QCHuVhRxL=5mhp*KT+LI{Q%E;P({iqX!Wpgf=m z7l{Sv3#Eq_v3SC(>v=oyUQ&_5>PG!6>i30e&;->VBH||cU7HR-ZUvJluq`2JaPoy- zz5$ni)&7WYvGtM^#XBjW_B9_=51Qz`;k_y#aYPy^%YXI^ax`zBj_#@45ke}vj<2roCKVi;p!rbm<0_*dBfZ#f+Nt{W40d6@p zM*5!~o=UtyD>HgstlJyAJ|UR^+X)|mE)#N}{TDLR@i!Qm`|Np$lz=qYyYBD?98~v@ zc>|NFz8~-g@+s!ucmv;-31&)=*0ht?V6F0@^hLVizR}7kenArxV^mGq9;LaJ_Je<0 z|CCPazX-o~*8h)XqgSO=!h7l~c(+f-tYrsAN5)pU0baH@zmZb>(;d{z<$FN#2ve z600JE8t3!=SI2Ilg@S3|TKJByk<=4{S))Q(>8G;{7qa-PSsBhnccBRF(O{2z{|joL z0OsA@Abdp}PflT(Yp1P>#0w_YRy4srw=63mpYm&PGszUxR6+N1zT>2U7yehIJGXQ< zg)Wn%?+Eo@Y?%@Ex_IF-%6Es)OSsMSV%il@k=tm?x8ytXd}Oh13#I2Kj;Ng7{7R=X ze1?3hw23e<(lqgtHI3lR@bGAqX8cElml#{xr6` z1zF+#zS~mj^GDyifJ|ECJ#8S!(Q=(EY!Diw5x`OL+dcR#;UDc|y)-I==m&3NZ+3yw z5niCS{Q&>AQOu9=4{(VuevXcxnVMiIo>pZi<;0`47_Lr zpNVbSnGI(T*_qiB$Xt&2M`mYHR}rzeJmBBpr)fD1k)29+o6Kz&8M4>F;lVJ_w8+Sa z=y|HLB~-(yTbwB^&eYBMWo~D(+d16rOmo{-G{FU06W?TOvP&SgSqL_vD&0!O_X#d# z0!$NuLDQy2hlyzTVtHi(r=BvW$9iT~6FX&^+wGJ!@#_W0_Iz(mN^}?AssBIGUHJ6D+ak^sZKgQ&CA%6dVrMm=X+zDYO z4cqrbDw)(}5~+v+m6XXbJ64F|l<;pN&8t0`lNB@7xEXjR^x-z4KPb2H^4vsvIZMc* zf>HU2u^F`APZosrCE468pjKi$-m{-S|X z_jI@iHA9E5Ptil!Y(9sa$Jvy}e&vcNE8RM%R<`b2cPvRDy?8^`ph5s2rT=3{( z-!akBp+8cnf%YgR`9UOQ(j(8tm+1iWQRA?Edc|K>sG`B(Ge+>WBlryHzK-NGp#C}v zcO<$vfIHatuSg*t&lBgZSLT>mi1lt4Rp#uDd+Tx@uz;B$SJow1EVkt6X7Yv%YR7x< z+$^5iB_MC(0X*B@84%F(-kub`yKK6TqF;|#^9h>8a4-H#`VocyNj##kKhwe{!+CP) z{)dSdZG85ogCXrw~(0oU%J9ou*~(r)flh{Zd09>DE>A(^Yqe3DYyXkUMYQjp^%`iCN5Fsk96NW+B)>x!9v zi6gKK09Es(beX0WU883E?jXMI-y{f(Zmdze;#Vm5kM`A<>B~>|)z*h@miAHt?F%2m z8b0^&>46P5W3UxKI6H}kUUiby`|z^Xa%uji+Uhu`YBf$hXik{)Jdh$E%uNp(hFw?1C6|oPuvfkmP+gb16EW>Es!xhh)&g{tN zX~4JvkfVASmH(93N4isWiK>C6eL_%`D1IGM8TwSIr&OaHssx{E1Y!q}3HFaPE4bV` zV1n&XC0SM1_*7}ls?lzh`Mk zz+(YZ*C{wiAfEHrgeV#?kGN78y$omiwQ4kCjI@~2FhoaD<7NJ+ICVPXi{@#}p<7wI zb+a`$!|QPu8|&{xZT|iBDsVNoG5{pRaQ#ryrImGLZ$P`skp1j|>-C_61E;{wK&}pm7HEIu3y@^VWwKD><-RPHeZgW=Dgv%q zs{+SFe=;^c}}$9~djhYt{wjsSUlUY*fIZ2U_Nlyp^`{BgJ^Sw zCQNWlf^R>q?UuSL=%;6iPDr~zX|e%gwMw`^=ILLtPt2Tlp~`-dY!Z86llY}f(`pWf zn$T1$gvIw0uIAJs3avZM6^>cj2jdJ!1!qc3D2aRJd9kIS=m8_-tFd$zYsp-~WXAVc zAv4a4DIl4#y5WaNfh;rTNN8+Ljmh8lE&NuK(70%^v98SMHmeI9qHab@+LA|7AbDJU zwMcij!cI!qkH7J6&eUhmn4&zb{?U$7WOH4uA*n@x75%wM_g&SW0sDIJ&1RA zgm5;)ia^bnN%`ENB1Fwtp+|(@-cek0f`H%_wgp2b#%x#nl47<@7AC3-GJsM+Uhk#I zxD>55F(&`TDI_TEr5)a#AV5m$UJwIe-+-W$pGG!K{y+Ecs(x|RL`X_^Pl2QqT(;%m z{)zgQnzkyB!@;Lm6Nl__Y;`tPIqWIcDo_*W+hW2R>$$9>OP4xWC0-Roun4c=_FiKS zO@)0|;Q|O`g9qagF^3Ot>VGl!K<+M6)Aml&2?)=_4`Qr?4%aeR;6!l_maao^kkuF_ zuv?+u>R~WRv5$pGO15D~+SrnnFjr85cRXW+b*Y~#&MZa7t9M<6Uvpv881Vwh%x>js zp5c3)ocPI-&Hv~dj``o`NI_Tw-v13aOvm=+SIt52dPF;5WwNv{t!7!DK>CuOr;~9%jz5CIR*z zdtNejziNE#sPW{dMp)>D|G}M7UGG+1*Qc_=*Fdc{rCF6*ch=}uT&)llXsO+_^ST76vRFk+hRBN3l z0j>zTvAC|mwU(TqD*KeG;Jj)IoDcx0vo*P8)pDn@x-zE(00^-1y4oRF*2D6JhZA1G zwFie&ShcvaRRU}(L4&4kOZ5=RI>%~2g4)CsGAr7`3y;Iz2JFRHOg`uAByjSE)bP^2 zxEi5@cov%@-50tQPI$>k239|oi7MPfMFOqG(0#;Igc{8xfDUFP$P#FyEP=)-VG`&p zSpt1L7O`qc1nqM|Y6R&s_Ayx!jXi!4-*AHTxj*F_UL>8tkNAe?=*xfb4eMq}9h5+P zLn~LjvBc^mf5EgtCgXp8VD=wo!I&AQtF%mB#6}5uC?3N`?90j0t5g;)28xs1JdQ4< z?&3sgEG=4H`t)q5$DSnIeCBv*3VjSE?(R}SD@5fVD>;6QY;Kcj9sGI#uBD&JS)U=e zG}r_9fo)zAg{HTBok4Z(rZlXZH6{4R5}>SkFfD$$6rUTZO7>0Sif=1%B&HJ_GPM9# zD4*|u2~tz9r!KS~vUcJ#X%wrf z!wIh)GoJj+clxEFn)#eH!UMEi>*58o`5uw^>J&Zw1gNAhbcX%njBKy(5JGUQrTze zovK2gs<>G-eZI<}n)Va36yPR12XU&VI8-a1g(-l2p8r_U(48Ia(8dp$9f?*tB7r`US>>`+4n<`;&lZyuN zi?;vd7k_+ZkD6Ti|G+QGzz6e-mX8&F@dN53>O#gZ!gD+07ypL&G)6i~X=rk@++i}U&tMn^2g0trR0 zyV8I=V@fga(Is0pwflN+z$OLpY^c=NBS;UC=|S^wjeEFIJ3PkuKkiA`AZpm2^rEr* zfbq3=j3+>X!tZ()~M7#*Ossx;?ME?6?)KN_HGjNLT@ z12i43asGFHaWLp*;Bs&My48O_{M>$C3nz5ilqImFY>R+I)njKa*`j5(o!C<5g+p9} zFG>?+f^%J;w*?+H86Q1ZK2LX-oUB{bQUZ1BAX(t{lEHVE^l~bALYnTfe7-Ojmy(9q z%n3Q=#aSkFYNmQaKK`=4Dx3j5_FU^LM)M4=a3`K$u)b1SF(YeSR({r!taVvivR=u0 zC+j=&65MkqE1Cz*uv>GLL5B!!&hdmOR`>vr5Wmc}`c@ye)W@FD%J- zk!b4rpJbV?WtmP^IJ`%Zsd6rH?k;v03A`P_eS&2h!?L|oVQx)9w(;XAdTx8!avTt+{18(>R zCLio3Y~AhT6`b`6-Hq5){1f}OW}>h;l%AhhC|{27KQv(Ac5xLrFV|e|KkeIoPdC<> z?G!W#gYQN-&9O`ul+JWP8budm`8$cyjuDCjx}a(%!~Zw!TR*W?>!E!AkG5)bXJ9{- zi`uHuoq=ZlK zbWgS^p4lL9z(o;UD`YoC2J@T6G+BPiZ;m8LKjJq> zFxWqdTiN>cOeuj9Xssy*FYLA@l9epn^wd0S!imjhgV#sZy5ZNjL-BVt#Wu%rah~Qf zK5efXCoUTl9}|310wKU;ZghT3&xS!VUkFHBORn2M+2Mc;Y$*lE8^=~ikmBjxhsaE(G^476{5RB@2 zfDeCcTa5^ofdkXV7CdO{JSt#R*YZ15S-0`qh7al3f%rPb+ltT@W?b#4PIIUe&u9ai zX0r7VA|)g_NBvM!RjDbT@<}Z+C`59|0xFl^$3@}K>C0P4|4P@oY~j|%4h$gF@Sn* z*EhC;B#oQgYN1hbt96a5-0GOdYPUMJakg8n$HhE#Tw|_VEjF6mYIrJhtB1O)x%28_ zr_}L%>I7*c;S;?U82%T@gL|kdT&kn%5QIh}p@F_Hp{zKH$n%@6HPebn(alB>({Y=t zuQBTqSom_gHP+$seC#jF{B(`k8$0I8dy%r_d5I^M^?T7x|Gts@KNMI55jS; z*?!~psfZWZ77(wIRmEWWKR$ zvW#vWU#nA_6LfWJ5)h^v9^^&6c#Uyq{X{(g+P{p{loz-YVvqsd)vQw+5zt9TW6ro0 z4;nF*Gbe0p#-p~*tlDTcLb)Tx7}wWNj6vB6FQkkAZk1**9Ip`x%U)P$plQ-ng=XK< zKU)vsL$qkM)4O=#;zfr~oqICDcTgoQr;-y9b6C{EpIEzZi9cyUeF%KS>2idmX(xIM zkYgQ&#}xvCxjBp9V1|R4{bRCLn@*O)`D?PfG^X(Zcj*`?A~cTu=~4#O$g~nhdctOZ ztBA7bS7r_c?ti#~+dt_aFa!TANAI$)n6(bdjrjx_<*VhOuZOJG8&`P}cXxJ?QuznM zndzD3H3*+n1SqhNpr~1$1ci#S^Pr+j_G{@pc!5eI-_w*&p-b@PbbJX@3f40Cym_je zokctl%Cfq}A%~=yFE=u$Rrg-3V5;~X1ONa}QL%x#w6fkh+;2wGdrDmo57Y(N5103O z*>+~(X1>g-X(c4_uyjMc=yen)xFit^SK<+mM@Obk1pJQ2hsg8LreE~3vAz91)a^T=}u zBEV+xG&!b@4Es|Cn`C_OZR#i&<3P4D!4Zmghcf4zU$h2o@r~{mn}fE@plzx+RZK;C z`6@@qxWOi|vf_|kJPW?@7D2*^S|fP~eKh@BtqT|s%Gt7ykWt7E-fNx9afl*FcOOLea(>NVn z4(}qU#+|`>wptes0~adFh8s|sN7;!~zXqvNs48S17@mpY_YjAg(f`lXGU^YdpNTQo6OKk9mQc6xQyie3gm#KiQ=MKC=RU}=cS5b?dN-%PjwRIsK7x=Qw z=iLV%-%s3#v>+b$f_`68Mx=Hikd5>Oy&TBhcMur^AD1ET)`7e}1o`-w($nTt)=jD^ zxP+SM+xzql_6-_&zBIsgFz}926C0fkUq*6_leQ-Y`pPH>`Wp-e^QO$r?xrSLO(pov zWDav)p$P(h1h%6K7p}g$uTWa{6~ZhVu=cIIzTQ?n6bV(E6DqH-ugXinF!+?@%)2%j zmd9IlT3Ao!EGmw>Uet&wIS*{E%UNBx%B|B_uYqTTy86DH>w6koq0T7`6zB@n&_3_# z@$}8St~N%ns=1YU-L)|~q^`;1g>l@)*4h}2Cva}_sdIUujca=9@_NMB$@xgX`@_Q5 zH|DHf^32_$+S7+4M2zOrOE2tLn7>VI`b!!dR;_NplFM=K6wSq+jcxA94_$oylBeBs zQF6y{mp*b=^CwTP1`ii#F1u)Ysm-V7b`DEh|H{#?E?T>WHdb$){aJB$_i9-1593Z3 zx8Op2ny1F|I{fu-Sd+FDE**uFk%B(YDyv#^QG#o>8&P4QRIn+nH2(?Sen>tG6?2_@ z$eVe{Cp|>;k?tvLv98;CjXdgu&lU7lEsDVG89EPqhs1>nUWv}T zrF~UZ90B}3f}0^Ae@-LW2|LY0E_)U>)?Y5b`RZ1tvk)|hDxBl#!GYmc&b8wB&PR35 zWNvw$^;YOS^RLll_E~wYbqf&88VUc&o!?Yc``d ztqx2E=&9YRmCcEodwNho<0h)2lIDg_wR%eiZ@+`1x)7RZId@=_m{yC;>Ardlld5$i zy!X{tjT+Y=PVvD*r2D~-hTv`#gwUx3wv~lC=g^}*9 zuXDpF4R2e&YFX9oiQo7}amyxmb>hYoJ;%0g{ZNc;3v8@gy|Z&gXV10=*KY{o#Pxbx z^`6dnPG7XAE>O2;_4X$_KRnR0?Wy+NK|R;@6#|`dql>t`t#x~i2;<|C+Rk$+^zKg7 zgiMJiJ?^c!lReu!>)R3U^4-~=nZ7SZHjLwz+@rJ8ww^X!EViGDw5(cCx?nyUHh-04 ziwWH{7hO5mv@|fe%DKfn_etI{*PM2?VomSU@*J(k^^w^Ro?#q8JCTEec z@;c+fDkCaiXVJvXLt?dO292YdX1eao#?g}r)lD<%9_VSWIVvnY5AS>kUcIt$bKT0- z531K$(vHN!{}G%DziaB!og4zrG_5Ah18hy$nK0Oj%yk1p&Dv}Rq7E8rB-4D5N2rRG zSW;T8DH zL2u;brgw`!oBe$?R`a99p4_w(EvD16FIK|?$GOt(v{LI9)90i>%=hu;xhCrt^OhZa zGx}jp#TuMWXxYHrEjVwehrtZz@YY%RqWov)o}82bvk!MtZu4eSU0cSMcHVu9$(>~N zZ8q1n$ggJKX4BZuGiZctHWzt%yobBnJ#FXH4zF()#LjS47*mo$!9j_ytY~t!;=)grI|01*AOgETb}tD=KPi?vVz_{ur7k`;c_HhUG%Ie zXRp!9Lqb1!FUFwjhe*+$Nzk0aWoHVlM^J&`PHg^v z1;p$tNj}HaC z?;*oCk?eot%h^cNqM-L_)ba&&&H$Z?POi>*!x-`w`7LDecYU?0IA{m*U>gcFK`%~B z#1dJnGo&M=I~LXOC5MPcFhfTs5`3iPp&>Q(pE7PE1HWc+i^RK%XxLLdZReXVh4>=$ zrx;g$`~6wrQH?Y8-AGzX@G-TvGrKSp_>V%4g}BIWMR5vTGRUooU4F0d}!4{9(lK5v(P! zVa`&+h??<^aI=JfrM2EV8(%a7-hM}eL3TSgbGFSYLnr6n9KUdBiFrS8u2b%(o`m(JYF#)s>Zh>dqQEx!Mo+FRmnw*X=iMhuDn znX_#?CZ30dF2^E@{-kK+SHqC={@_3&&`ygk zRvCAa#cnvIk;d4^CYI5!*(PP!$6BY-ukCutY#-~$p8&H|80%6NeuSthrSdDqd8}o5u9f}!(`QZb{^o((5lIT5XJZf%L+tY`-4#!-L zLo*9US2#@VpAO5}#^lCHjirsN8y{|bqVd_r{l5K^=-9S77O~`f`;(;$v^wI%{x|xM z&c8%BHa$pc7ECCgd4k)iay!+H&9E*Hj@1tf@_WR@J?{Fh7%0YF2jn=23pcJ_YI{)E zbUj6t;~dTjwO$oA&W&?7J8XLpE2dhFYdL}A)15Y){wBFvV;!N=kasE0Dq87fk}G?1 z4=)mLfwS4(vyrM~70ylmZ6ke7@$!0c2V>%!y^FUzJhtwDG3a%}8JnwW6jGP@j<1KQ zEmkv~YtE?Ze@x#MTIRDOQ0y}eh(qQyi!g*3tJdaUzXLmEYu9v%qqSsLqG9>B%WUPr z4z26U7%>rEKxo~un&YZIQU}c9fS%)?DzASLp22a^LeM8m!P;Zv}m=x+=8 z|2T5{WX$k05wXP$%xRLly^Ggv{udy?ZK&Bh5DUY{bK!R* z;H&0wl0Vd_A|GJo0}ry`fE5MK42@M9!u9t zhlqf?G7OjcyEN&d^gDV@*JR$=;NLGNTfUFXzIXcTYo~`YVuKkXu4(MVcscwz zZWezS5y!wwFK&%Mg>x!H-It*{u(|W)qO;vIPaNFeq4hsWIoIQ&F;(}?T_ZW?#E!Ht6c5cepGfvsK(*I6G{0G1z8#78H)5(W<`xp`m zhEJFb=ef*DO-^=A#q~ub^Wm&g$9}TerNRAHj9F8%=G5((Z|>tWzu6t?(jFp1W&hhT zkfzJye_!lGJ^L6gi#;5a!Mqj`e}@yZeD&o6sG)JXL%+jO8w7+WU?xpfPmjf9`I4M6a^(FM6Mu*Yt<;HDEHCr^>ZA%|nXzpI2nGqZ!+CasF5%Y9zqHg55T8r9e zQEf_{zHm(U!gY1`wvT^i-HVo$jon9LV9GC0*B!XdliQ(PfB4nw{2xRN?U!rcId^Z3 z051kd1gW2<@W`_3a@KUOc~l3ZuoD=OmnLciXrKqya(+72azwQl8t#l~ z<)*v-rtIUb{iUwL*w!nh(s$GlwmxB|yQ{U*_oZ0Fmle;?ZLG$6jVQa)1Q z#UE<5{Qkzi9j9M=+1bVQxXT40FM)t_lVFCJ*)KgHT0e zrV*AXZ<%?Pt)hS-7ZTN$G8FQcoz35NP4V-k9oT>@PR^|1MEEa1Vw_ZuT4V-+c)gxs zv~t|WA^0l}wva71Zf1-itu0>SG5l8|RqLU|b)D72bWvV!VPACzW1IAnM4kH-SR~g1 z7zJv~UC&_z`1M5)G%XjLjU!t_A5yQ)C!<&ObpZV3{Bn@Q>$qHQOOhWk$k1e9lMF4Yn#`adX|<@&qU7--53Ju^#wZ@66+A|Bb_mh^W24n6_-0lck zC)3A*W)gk;S)Bc4lphf-pQ4mc;p|bWiw>|+5lEjfYIk#d7mD8-n!=!DLObZ&;CUNAyd+4Mn zJxm{~7H9}aHhNv!NFOfGyj*Wp4ZZ*Fy1aNCQwf|0umEMC;5y28_~1af`Y3dc8=Ew| zCgUx)YN%MB<1xC6hu(juTQ$tC=9&TW&YZ3Bcxx^mn&XLw`xadLXZWCc!e=FcIsQ`j zKpQ5pHc%S1VOg}6XcYVCMb9Yqe+NWX}d#N3c+mOTa2 z1q-%xi(Kc%fjSqaUv@dtb_`0@83AA_yH?bYt7uLn<9*NHGsv3T&O>cyDHW4xO;H{0~heC)arT5o+l zJo1Gb^;TZ*!{oKaS-ptHAo`qiSsrz}JbJ_lr@{s*0(*n17ggSt%^k5GM@wQ|efO5m z6k1-yLYtY#FyO>kZ%h3~?`qOXxdGIsuiKX6w#7Bu#C56f7CPvZ3b-`a#eunQxh^`_ zrI-?5XpGy*xt@cw=wu81YNStS(_(7`)(dt=HzI#wYZAe_Y>TcNuABi_7j12|jTCug zgluJkdZlk{ZD#f@dEgtCA_nvGK`^7=!UNwVu6UCTtfGfBN6?z{cN||T(&>t+g>c&h zag9ouK6x@U=k}VE4}+mezL(3u(YexM4dbuef91#!k^Gn*BbW#seCY@2b=#rV&KSzl z4aQM6!1dpSn{)KZAA=K8H2rT^(^o6$J7T1l2h#UlO|MnbTMD!1H2r&U=! z2=lXY`jlbv@FDed52CajY6S*uYO5;kP+-kRDmXUl6PXIJNGIl5oe463{ZNc>R%W#= z4-wue19bz>-`QH+7$3_#g-w}pp2k82|0tf-gYx>kG178+_oy2&vl>%9h^b9}P9KbI zNvUd#>`H;r8rn|z7XDx4ljea&_k%{#c*^ZFr%N}}AjN$>$-=&b%A^eWVUnw!(ebdt zZ(~noKC}xdS;4t@x~(P2qgl6Az~wFCi`&%DJkB7HWt#FNJ6Uv7-+1_@i(*_`%!?@} z;`SVZ{*>$p2HNevR(E(jalN3Fm7t66ox!u_gBKg*@)GIpu&7n5E!jFz4VE6lm;BVB z$Uc^`Kd!$pUMs3;j~7!4SFJ4AjQoa-VTNyq?lMWEDNF81oA>XzIqQS#*VnBxA>!`( zc3*M2+%Ncww804@r9>(uC)BO4lZ(`~*ZGP^NpaDn8|5-N1gshUD~dqEpt*Rq2;z;=Q=NnD_j|7itXG$)7 zw0}=Ju!g_k{F{lBo?Mv8hi%^914vHG>bjBy0ytOI`$>c&FYsrmNYyjM1cpBns`O`i z{~9@d9WD4>0)0CnMXnPN1s0l%W_IT%KbSv!eSvLeUZJhPfzVA3&_xs> z+Yt5SgA8L5xUPqL@iOO(>-6&+WwsfQ=zfZ5hdTTg;d$BtG-v*)(Lq=`2}{1&t6^wr z{sT=XL(}?S&4-(?+nj-r=IL+A@s zquesHGEaf)xO>d2@`@`f$K1nR5S(%#*jaVMrR{b#x|SAVbiWlN@&R|bf<0In%AN(NZM*G zv^AR9-iFi~-()%=btK*Bs>}A!}!%$?|Y-cF*p5}W(Fw%`9qI!_I zvClKRF(kb~nQNWt9(8$QBkvw#NNZ_EsHWsbbGfzFRzMrd_pv@_Y8zkcOzYA~F;u?z zQc)XUUX8ya{GouYn%xh*O?RkO`a6Lu{#H)@h9#HJ1`yXRl-kKszm!wY4oaOxse4%J z=W^<2S5y5pl)8(hek`YcbTu{1>TPAIAIPciUrn`?Q`v2l+LpK>;5%4qu4aD39*JDh zwIzO`JE1-@4E_Td8RY#u3v*L?iou&-Gupzu5%3x)6~ugi{c9yR`{$*Z^p7wFWvG)K@V7Q)K4UJ;jVj*#nj$awEn;EkdGL#?jnNH6@m zL1se5Q5eoIZ01pp(ESFD)}z_oSx|81PHRlenGBzKRF@tn)y)UgElIDmq~vc)Z+4D? z3jeqVtD&@*;FTp~9qm$2i$z1Xra`ajHk+CIa-?D5LVc*gvH{yMd-AU*u7;5aF^lGLbYYwxs>uXD+@>+jEpq;&EU>aDODo3|9UWu#y0V7D5N~>p&1FcRDcwPH zaH9TryXY{x5>VJ`8i(IZauL?BoQW%&joGP^lk&~dAKr$lZ=+}7>xlG=q7JppVlIFa z_#$Zm;Y1Jf=)tWX)}>x^nh$0`WP~`fx6;SX+#|S8T_ic^r3Qv9>jYoG&y>~cCC>xxPY_`)>2nQ5z8)j$!K*7FCN~+cIh~B7 zjE@QRg2X;jff(uCH{t zBd=C!(Z|36p#nShM`bO)QOa7*DrNm&=rBU#h=?F&EF)$smVCLm|KGY^M8lD>`y3%^ z2wnWsx?u4^TPxMmS_;SV!i5M_1r3-Pcwl$Dd$?79xUu@}8_|Jfx*()hJ#-b%CSRY5 z=mZFPeMad{DvxVr@{zz5;BVK9$@{hyzj`CAMLXG5i7PsseyKPr^`FwwHV@z2Y)-rW z%8SWGGjos^{1~O5M7!9%ypy`wZ{3IqfV+!I(Th6vOm5S|-|6~#vO_)T!PbooQ20gk zKBf4ND*(dpF%Fzrfio9%e`MotxzQF%1{_(k?z%a~a7;rHSy|chx+r4dC;3?zTJ+WR zjt)NhsnX|T#5ZSb;~Vn00i;}C>d3~Jl|HMpCt?zXLSx{R4FLhDYWyZMYY zr&VPRH=l^fG3@{fREHnaEDKhIOGH7{$W?^(2&A^0$LZIoClQ#eG3GOB>(&9Q>mGa-g?d zrv_-?e-xc57qz^iyX~MfpZfX;AB6WgTJS7g5mO}<44R3w{`aY*(xi<%{E^6IT`%hl zb2Obw|G17{&E-d~O#Ho)EgRDV#$EQf75ko?64YFUb}Qv ze>^7q5~LE~hez&%eLBGvu`j0AhD8ya?>M14f<>_5R}ruUm?>#&yjQY|_!#K}djRx= z@JZ##7?+YDW_PJEJkZw6ysSx?8Chf4?e8y@Irakm(^|>Re&Gh$*MSxecrZ7zR+;!4 zJGA89%Dh-@vfPNv$3&+iAh&P-7(BWT>v{$3DeSsXKnH8fcNM6uZ07zDF{y5J?w^!} zO+^lrcS>g(ePiwZvaD*;s2dLjvSt(P1m^Pw#tGQ+UZsL!s&BCY;X!?+cZgHFc*p+R zq}*xv?pusNp(9W5M|hwjjigVep*M=zfHvet7^|DBwPr6uK*FDn$+!Q0DTb&+9E)?Y z*=f=`7n`I2!FP@sG0rd)ptT*^lL87*Aky45H_+Ok*g_}Mcn?paUHA#sCR%I!JFq&@ z_cQ%MFZ``)rN>#C4y#Nrb4^FQrpF9jg8FcoR8I(ctoUJkm@Sl9&}_Ix)24=QqXfE* zecL?E9Wm2l42${?V6SLNdSQE7ev5HyvnSL9ckLY-7*l{p@KGHU{h|ZgAa;6gYijR> zNP+F}odwNRo5|@ISI~SJh7g=9Jz_O$3e*?#COm|rR-9*N=X)VFRP3iS#Kb;zytyQy zyL*zDW=W6Gvc(X&1&CCoUbaI|2(HjN9y)0)J{gu@f`8^~B8JbuFKF)MS=Ky!Z-8tc zZESj@%sMtXE>qp1Hk(x^d9<*sS&V6VAkBjvn;Zz^05^Kwiy5tLH%M*N09yt*TrEq+ z{B7gIMS|g_%MdD^rK@G)dg(68Qm8LzE>AtYXjgLs)D_b-Wl2>JM0O?Nwi@HjeO{xy zB|}3F*%MA>xKF!y?}1RoO~naQV*))VMyYA5NnK= z$>p)(WS5%XlCaALHQofF2^wqHyU2f45<)hzDCaP%Ylf%$yvb5J6%`-DiVY91x9j~m zjDD;ZtO4O7V!{o{6KeT_DqV~;`G!q}H^3QPvvUNl-&D>mcG$}3p>mSLHq)tAEu=5y z4z;S*IlQuRvBQ~M>;3&2gbT264z;=#*MjCGtej)4`&~liyyD8aM(FR5$NI7cM|T8! zeEV%xt(pUzTH8EicG~7U)oLWw+7>u%zd$ypImKa4cJt*hZ!DU#sB%$Vt-u*lm_Sub zKM~_IryydsFotVy^LmrlKhy3z703DX^G>$s_$s)x&JJ!ZH8L9Ek;ZNlWuL3UDY)%Q8M{IjeOqn|c`a;A5JLu^%C+{rKuG{8# zXYb9Vt}EznG#+kg=4b9()@&nHP+!sZg^I+Ra9B7%>j&WY%p(>wib-1vRHC{) z54~Y^jxdCW2-l+;w>crrLyN;ZX?(*C+|CqUn8t3h6}b7CV?Deun%jrq^ITmEt`w=Z zdEgPrJ$qR5j?dP;IC{cI9Ya6Ml~ztcHCObfbK4U8dPa#;X>HvlFI{bXO=cX%m{m** z7YM?sh}+AH&U(#^%zT9h{QK^K+WxsL&$loe=(M~BEs8{y&&-XHOTt= zA7y>Yj%5t@v0C!em#%vxU22_nMC;4MRR!sngv{Y>wRR37hG{~>ZILV5FVx}?F}p1h zBwi8P_we?=u{1`lUd4~k0ijddrgptSQizQG~%&Ur9?cv2t4vhX#05h!;Vt2qk?ifCv# z=v24Gc=Wq+J((!6`&dh^FBI=7JQSFK;k3FguiIm-$sF#E)zo-~!L_ugZsXaA84f?! zaIj>^P`S;qh67w%%n=Rj#MBIo&#dx~B&&1RpNMY(eU-lZ&wVsNV}j9`sqh)E(lnJ_ zKrYkfCQZY(UB0TY8q0KU!nDHK(=@wF$hU+@JN6H-ve00XtlOMjmSl4#*v!dio&c$j zP`_bw@1TDGkY(Gr8*v?tkmp9D>yl}&g{2N6ze9$OeantLa~5PPc35Jd=%1-5=w3tr zN`JV$kRPicONOr-#*Cp|uz|$R3VFLBgzT<D6zUG$}*ReGJU!~bja-z6MT zQ>khC20fgD$TEYmI&@Ma0U^6mDn1z!7RnZ(tQMCmj3v$z-9#xi;3`Hd|m;3Pq+x?qobYJdTR<-fS-|85j^jn zZ;ohWp7k{Fg0~L2_K|cxT{H+UORmnY;<%-1EW&aYl@6vl?9tB=e(%%pW%xl?sa?w- zQBTy0Nh`D~7u6SK)Gss}S7^Hz)f>ke=O*$ES#(1vL5iaqR_IYzEIqZ?OsgR5|b;6Sns=rx)SC46h9&&=$>G?oHV9wOr z^>F?qNVBPRkTgK*;lCW~G3AdpF-ugP6e&c?@$twLqC!}4y6K-Z2>8~eeA`R^kZn%X z+8J*Fn(vx2ix1pD10fUsweV-ICMTBY9k9Vkfr6<`8Q{+#Ue+vPN49iuj>(z0x9LWC}?neQd1^>KMM|2nH z%mi!+t${x0U28CWp*!Zgc(dsyF*d8%Y?>veWX(34ex6mm(zqIDpF5{egP8EBx@2N( zQD*&G7~WTA)*Htew1%^uf1(`l=mBf<+>?#D}CEV-~3<8`EDDO&vjnTcgLW7mapV|_p^NM z4395`X7Bbcej5{}eF>y@18jUdfwi0!&?+BmRp8(huN*{sqR!_%enJ<5)e26kEMs^r zeUqR4ZMvf$npIQMUU}`PYt1RX&ol(h9LQ?9PZy;`^V8|6d$$o1E*|A&Qdo{Ky8TtA zo8=RMh_+Wb6R#LVGyg%B@yRK2wXTmSC$LD}E0c7&4pN3FeP0nCwGIz@kGs8RPVl0b zx_3QWPil2(p+3`Ov+CbbTnmwjO36T6D|J5x`W@9N_h^V!U$6A zYQ>N(DGNoN@MIcii}NTu0ycV`%S5ch)wUiX~?E}fDs$7mZ#)l zjY%TIYbSV^b{MA00No{I=H}K<#uT=(Ymc~i{xIL0qXIO4{%GolG`Sxv>AKy=%qC5h z6_*7Vk#1sjwYQNdiQ3&+EO+(@UDZohgdX3F( z0=3Am7BA?cObypxgeT!r=Vy^Jh*zc<9*)BuP&mG1Q^@s#AgrW1&jc<^W|g`Ub-TxB zRv-2$xZQ^E^9-kIIXPZeHMw8dPT$T1K9|c_hUuENDf#c{bw?=aV+Gt0UDHcQ@_CzR zblcam#P{Vyf1I3X_HIwzJHA!83*7#hz|qNaANpg_&hseS?A?tS+iL$!1at~wq4J=D zmpU0f;r&9xNII2xceBam-$)A!TUNpk$$fmk(#PRH$$fl>(#PQk2bM2+O==og;^gtV zK`uWvT7JD;KAXzh>*bN$#WOT4=csHD<9F*zFVgrqBarTch$N@46B=+fk$tUwAvACl zBoP8q@8vG7+>SpB4JvYz(*Xa=Z1ItIsZWJ2F;3m z$qo0PB%%aq;=J@M0X#0SMp`~#lQF<1?0fPz>^JDjjqID{nEVa-8A9l!JaLZ9pWF=pZ-M)ur8T@bLg-@2ej397 zOAVXsCs7sE!}iQO1Tk4u8z*fB@YHq~nP-t;&hl#jmC58`#@mj~1mVhZjfCTD=I{u;sNJwB86fv`(xm>t15z)@1z)^Fe1Z-1;G&ja8V3HIMc zddseUa8kqMuA)c60gNfe5`rB>(O)=_C;Tfs9>$O&=4l}Pm-vWwQT?|I!gmpv4nxt^ zi#YGsMjCP=4OV2oF49{N5vE4$H%1z45rMgFr}HSC56%}x&ke4la-0?U`xgV>!*55w zD`&;IM1}{649YpfoWU8)xW^ywpMxY9{YZcOAJcE4bo!Cj4oWA1R0F;LS9=_s6-F1z z{vse2r+Z{>#wA*o3JQnsdXqYy9osCk1Y}@mg)+?y7URHje3Z;yS5W=2gX)JaO%}ba zSt|BrsIiOV)c!3_OGh($p^0Z_DKl)=c@-ue?pK6_!;>>@cHF(g*%x|BcBQMfniL4( zyM-Qh79QoVSSLKp)=EdPqat~?`Ai)|qY|?I&asRQt zp6ZJ;c<_s;J!1eA=S@Tr%!C{mu;sHRZ1vb#(|-+}H4_J5S2G<~A-zA2_;StFymURi zw3tMlx3Rks);FtH=x^8U+%<{x!kp!00r%#m+vEa}v#Ph6!aeNUT>93a=eQ-q^XBEI ztyyC^ENYkd&#io}4#z#iq|2_q3(b0Xtf4agzfqYM)6Nm9w5qf@IPOF4pxkG`d3I}o zGc*bPU7(%%R0nmuwVFKWTMi1-^o9k~Pv~)!G8h zzeEW3+$0Yl*AoI+PqOc>OrhxwXpZ2rj&jWv8m{94SxO;S(bYnhR#YdKu~-DeHk}HN zGu;|miej!Ffv_Mj45;N_R8CgaRYBdx&ax&UkPNs?-S>LLa7mc@9s_VU0qBAsV8jAe z%KP7h3pk~`BU*l>5YQ@kg|8O^YCKOxQOos0s0XetZ&GwoV0qd1a4Hpq#VO@U6|A<$ zv-Q#wG$wn4&?!+-e~JRzk|Ol3qowJGNZ@RNjITfEYTI3#2HNf#E^NQW3J146=`iJM zTP2+#kUnQ-!>5tJNu_K!o65>v@}RJLec(MLP{Up8*m~`qMAl|1Dc-`xoII zNcHtt9s{o_aL_q`qs;k60hS7K8OspC@a!;vl>S7uKfnCf;_V9g8A)Cc0zC={%NPOY zZ?xC`52C5uaMuG@+Y=L|mrgL`@m8-VObDYCy`y=kPGW4n3aIh2P3|s>0vU;_-Ao=zxQp zg1~PCL#mcFfWU<6q{fxSAmMarmr)l#3n+ z4gVKf!{#@{Jo`IPc(OTtMk{=Q!@sPb9nHFp>8@R)1iKctEGXpqoP2t}OK1xJqSYSS zq>t#0R3ldN_;UT3uYJz(a@+i$%5AfJstrtt;>*z(WTGBSBLTYoX?$i3uyS?1(fxL75wN$nt8Hs=5lkPgY|IM5qre#`I8qjl-N(6^?P( zKAzp5kKEAK6S2NQKiuRCO`_+a%GmM0D;pRv;+=^9bfNU&Eq=9fb`KC z;?hSmyrm^00D?hX0|qS$!$Nb3zFXeVI{1%kEOW%S<|fT>n5U%8aX6@K z3uA_cUVcL~bXRR|x=!37TtvL>yJ2+V+}|&G2=vb9vugQuYd+;2=26S%IJ8{;Bk$Pu zU)lNa`kKxEr1|zSqNa&ztF55-L}cfqA30wB+VIvD+#Ve}oEKiJBKPcE;0 z%|%u9mGk1442Q@HG_@a#j74y|*CN&sB0oqgs5ZmFO!3IhX*|4_RsO>Wjzd`wej@}P zrEVc|y{E;o0pA-wR$qPxwvhHf29JtL?oT!=6;1C4^`Cw4GgVV#kC8oTi{_u@G1r z#qV`3tyk|1TCZ{ka0@@D;O2TxYZ&wW)V(r%|7>BxK?2759ZbKnZ@E5=j*+0&<~=vt zl|R!K^iGirxqgn#?~_zsxE5#;60@*>5|C_Bq~`nr$@1=5Axv04b+2r_Q6a<~J0e68 z56=^#wkTnf&~%Ifv#<&Op4JYFg+MtPl}*5m!uC{WA2!#iY!bWP)r!~D+6xq@{^^79 zzx^uy??v%{QfYVCj|T?PuWdLCeGGtyixtGDVh_N(|K=#>mLgCNH2>s!&^+$gg#A$( zp{;~BqrE}E^=~!_)d+uC>?UU?Y#Q z$F%nGY@N%%0Joa60^eWnb55~3Co5g_45q9xI*u&RtAR;i6Fj^{YgHE*UhegoZ=#Tq zfl0vJ=YLiTvIpl)hV`#vwm4_m6XDnKy6eVno+w(d>il?m8@`=+L?gb3t>JTOIn8w( z3Z9J!+K5;p42#rEUzm+Wp(#5}yL@ z@_H3Mtrg(R1MlK{jCkQswY|9geT#6Rzh=%KsE*ob9nsatsV&&o3mv@p9@P<|I-FRW zYMjm~lw<(nPXY0LN&+gUB&=E4?^XTdeD-_2A7Bm+)OS+b`z3pSO0NF{t$_L$Ssk^) z!Tzx>zF{rr4BhSE!;p?ICXhRyOLX(=)(WtRsx^;Vum(oq`CF#MweK9x_x_d>@1*|1 z5~(hz`eSnTda01ggwR*sbI@^W#gPX?F9qcgHP=UQr-k;ipU}TnTVQx0R-ylTDqoBC zt*LcRp_FT4(e|JhrUz2}Pt)ecu(XLtyZ@(YTXaV>+0>(VQHrQ*=EGa^`36s<**qo4 zuS?t7?3~i9E#UTM7(UZJE<8E`O6gJeZVkqw_fcvol}cL&r#P_X7(~Cr+Foqrpr=B= zL)zYB^q#Hs=Rqx&Q!=ji{iqI_;s>;JTEH0_9&y`!<#b+mr9|vY`(amR zo?;lOZ8L9QKTj_jZ01?ZRP&~vGT(GXQ*@#mcKbXGu0)N^ISUj&aUHd96bOFaJmtjD zBWlRPm~pIsG>+thfcq08m?WZFI-Q3SR_9F(v-&Z}Y~h9qRLRx+?milSyznB%a8|83 zv%*z5x4ULK-ym^LXQsGWnAMMlVXQ0C$bDMjkKnHcXkpo_1wVeZ?Ut9cz3T_Rzo_kf zkb4yVFhFPzTq`YnlI{5~Xzkl@C-0BY6ZO}?3A(-iry~U8++c_sm}e^Ln?ZBHP^G6d zJz}5*4c)Dhc81d2p}U=E4*ZxdcY0QJ#JH;kX$K_)%~L|! z0=URE2|?$SoiF^}$FJksGYp5dgPOy}%`wWJwq+y64Z^4am^?0AyR^N1gT{@kP22m{ zpmE~bsqH;F`29&O;(-hTF4HRf1Y1A2s>{!c?=^hZFRzaN8N}3Hq6M$_QUr=2D6!;} z@N{i&d_M^wylv0s6loN zR9pZ+WDZDI|EJ!uzpu>SZIpd5{og(@&^McZnr2{WtZ$lrnpSmupl|-j(n5DHTg7@u z?wiJHX)1m9RPW5^dz<@xSTowOX9TqcO6N>@cM$zp=iEsJSm!jHjS!c|3x^|Oeea`J zWI2O*JjsmU9p)LMze5XwN}})sImL*|l#m{RXo96brEMCY33&qYMDH%m-ad)Rf@~IC zvmzyS`6`;z;r=tn4z+gC&TCnyh1tkC>Z#}f;8(cMR9MPRot6n&3Vm)Ux1sES?tUW5 z`ClCQAfH(V{=K{mEF-$5kHMfd!#|FC|6Y0rwo&<)&pS_go4&z{g;+8eaZ>#sshGVy zw4s!Sa(B@GM97sOXF)dRlN@seW?p3No?z=Y46^G21}r65MkszUQndDuBd9-4dX}(nvv%JaRi&UWQ}5 z0)CiQOsRf<(z@jAGn)&vB+x0ig;34Z298Zq@{ZGnU)W}R&_<0abCI@bBMY|O@1d^^N95;?s@^e}kuFLgAXwQ6? z_7x0IEHton?7c{#cwrNTXAmAT$w12_@wUCK()YQ@hcSE;bxYt6lVB3ShEOsv?BH)_ z2Psi2@=Joh>!R3o)(|@`Jg5~^P~1b*l09$Twi_qZE_q=hvjQd}ZqWLQhjhV?!5U(` z`Fgw$O&8%!rYBC?LFTG({(~XSZrfC9A=J(ej@$M{ww`9MY-|5DwV{pLFcH#a_)eVN zmgn^DL;K6L%boZ`FcwjZvw$>;5Z`$nFHGl-XtRGU9}g^z+FAOy+sPnQGEjzDi0!1D z2wdy5YxP)-c0Qq6t2v@YJX6IYWQ#WKl^MH7odClr6E*y(_D~N*x-!%5KZCUx-F&?= zme4a;%R@b|ppuzwcqs!5aGa19hkY^Z#IO)a)w1QwE`RCY5am+#lFdEP^p?DA^8H&tvImNoNM}*P;%-on2}P9~!42B9{kT-m((XhW zDwMjZqO^m9s8x?#(X*Am3F97dE(tHavbTlb(gc3UV`DTt6Gu8#)#uv4#XJT3a;-R~ z>X;_*t&*cmE0$h97C0YGpP>~WICCuUW%S*yP1nHa=1lZ`x;9&L_*mdGrFf~fY4S}P zo6TN*5IM5Dn0581nyEi1R9lW_JefKp?cji{$t4lWN?%7n)Tu;@gPIeXL4ra5?{F|i zCPw)yN+#CU&E!nV%?uA}t)Y$^2xxLmmD()(3)T z`CGJzVrOKb=s?nIG#Ql|_Y!n6o5bQws|N0Rg9rI40*z91yu4zCn~*^RX7?fMp<}!6 zlx0NWB$BCE&6)Yh6KFii(Ur82$JkwL`>~HCP1_#k_vY}O!9&OJXxMQ%@O!z-{70}} zVAEEJ`-vuSPaYdUE+^=t3#^HftGd5xdGwGRo~3;sQIoF@5r{_>!vNr_VDV(KSOIW;Eze3-`+u;t+ zWX#)=l5I-L)14k`O3b_Fv=P7KPN$j@^72n7<9EjCp{Dq}xu;`H!}FFbEZuOcJ>SIgFNEkET%!;;3Kcj!t_#N%91H2&koeOZ!MMbH+yE;zF%0Y%N z^o$=kCF=;!M^5LS?@3p$tZko(YT>yhAS7TW~cVxI|9qg`(PWGj5(T_xu%rC&J zyix_}CkJemKcKcmZIyBFcW-WB12L)vSk+|5p1Rr)yBhW<4Ro@k>2ziHPgA_9-KnX% zCC1_1Z8MKw;4nO)>(p4|hLN|2IJRf_H$=-=vZ7`DD>Y}{Xf}`Uh@BR@y99S!G#=b> zG39TyxSiwO=7~)n2#*+>@hzD@pC+VXg?t(>(_$d(X-w_?R_2;4chD?pQhJMUW^IS7 zdN?vlCt8BdZ{Bq)Xq%TWzH@7;Yjbb%R)N`}MR2 zhQGxHGfMVENPJw1X~@+iy-7gM5Rj^uV#o>|Is6V@c?ws-Whj;XJmTj6(sVSCZ*AjG zsMEI-oOm@B+@?G+0~&oXugwgYO)nKd9b7GNah zqQ(mClH`Q6yOuA4-{Y}c=dRG%aW>+(xW!_OIW%ecBHXyZ=yTgS=_!KP{w%B4zZmGU zC)aLGmrfp^SiXxbtQP{P1Cgr!7iI4s*VK{qkKf#c5W`jZWki0o$%Q~bu_UPcsJ0L( z0@hujm8x5x1vE(6c2|)Wb@8*@*kVw+E7-MY?eiq5se$Thus^ibeSj*p3cG5%*0#E9 zwP|f@x7J##R?YW)<_4!#s_0{0~69$&p$xwOfe^f~vkY5SLkqDUS9K zaz6ham99jCTNOfV`=O5(sQ0Va&)?AW=7wFbg|{DidjWmz`eQg;XG34szVjb&U}Qh! zX?l6Jv#DNpNcEz!+xgo^_f2?W>PItPzwhh_F0Og|#Iqw5t$-mbZb@W(8AC6KR?8VTVja~Es5lxzpy>PJ)wc4W^=VU$c+A< z4Kt(hXLmBAF+9j^eoN3M+M?>0hB(k1;(!N1eY%HE!{6O)OSWHD5q9QPyrMC%J@oV|_nJot=K{`_AkQ8n!P(fuq zN3=M9XL+E|a$8@`J4LDlaKEj`J0K#dH7x~f77{w=YACqXLBc0Oin39 z+^51UU`sX^ngx}mGSd8jS(so!ZJgV4Co_q_YD=-&OjcW})s|+prNaV#Dvc0}Are)$ z*d|&G5mnBk7F)WsfogA_!VpB7C!3L-Vd}}4+ypVxYP-j3vsfxM(!|>lWCB60&0@1i zt66@NxmZ23`mweu=lh7RjP$mdlL%FxlebpG6- zfH4*`m`nz9b_nK^J7Ml;Flh|t;~|)j?tt;9F&G2E7%tocUX?{?QKU1?LNi-G+Ty8Q zF$Cjvp`reNoRW#g$&;NYAk*0xPU z|D)1tpl|#VAwAcXUIl$$SGo@-N!Rb8f_>6e`o;L`q2K0@0{tHb)E@>4PX?Ml2&hj7 zu-~DgaNhkUW{pi2H)h?X%08aC}}qT~+1msi;Eup7PZp zbzo=b`%CJYaxF!n<@M^izUU&W?)^|l0lVq6++oM?38m6i{)=d<^c_{9@Jhg%i2F`y zRxw>yPs%fR=Y5Kn{I6KDKfuxDoO`UIrS)m6m`O_n?%N>!97{hFa74F++QqEa<&I1m zpR54s6iYmf>r$51+9ItrNr6mmaSk1BT~7y$)it%mib_021jXe@mFI~spd_*NpMts> zs(H_6N}RdkQDpocSNQ!(oYf)P=%;HSFB5hg?QCVgA(ESZ-A)I<&*6-Cx&JKw*VyR) zTqFH2@_d5-lWg=qNqU}T3zhyzzf5O%7WR5GGS2*2kCTT{wgpOGSca=0!*~_;Ts_az}uoi=Ln6U@?RFZj0?(t2^05i_Tyo;ZC zzA}+3GqT0)lF~O3t_awk>04zV1PXeQ3EIVA+=-z2;DpjK`YXZzRG#sejN5Y*pweAL0xSbag9?e! zVgZjMBu96*F=4%_XNPk0TPd$bV@DxPqiz$8ca?~u?Jn}bJ_t8^tSgOor4?9hcQr!? z1zHT-EZPpE1S9>E=E{_2v?QCvO8Wl4+9a}fO{`K$FeC8lGkf;)t*f!=QAv>#kv}(y z)%U0J-lp>CpEPy2Jc-LcKk?t#HrhVIBY(0mQmjfRy$on$`)`sx@33vO{Y=(DdWf>p zaVnSbgo~>@K9Tt^F{$f}5y+P6Gku>{Q2c#z3g0}1D|*f32S4bOdZbjU%q(r)!J=*5 zMR3Iy^2q+shI4$kF;Ym-_t6H)wwSjV!+o#Z)Af?u7B2Ub?Whu+Elc`eVt!*g+SimY z#IQy5kK;JnujAo2St;~O6?%w01INH>ZXzr8d_Ya(h~@S8lqUZXUx}FN7Zq`+TEkg* zgTv+>imq{QdAcn?4W%nx*3#ozZ^C6Kg1V~;JA{S#ku!%_Z7)|olD9?-OS(J z;R8XBcR~Vo?-nr}#H|WvPVdwvNV`S4KZebi%=b^g;esH*N3}dWW7n;AT-nvjUf!5^Po3;)L81hA19GN=$@zHRboF*6$DA9-~}iDS)c^^UW7 z5A>8cTF#QPZMcH>sjyzl^uUxS*RM^9o@SbOs;;pRO`9sW!FC`BWBY@Wk&Xx#q%%!d zwrO%5iF}ELJISev5JdXl%3+M2ZJd)EfTdlT10P0sR?KWMvag5e-Ole0|o?asr7{RqcqnbPe}o8j*W zkIFKQG`u#EoYY702H(Vli+1NBLpM?`+nw(s0!N*6Gh+b3HBn~_f10=^@guu)kOEQ1 z?9RU!c1*;9rrl*`0RNq3(%W4V4X+?|x4{eG9d_3}6o}etcV!s1O)T^Scs&AZqS~`e zBkZnB!%Guk42hbyA+!ck(cb~lZg5S63}Sb^Xy~FyNFrILg?3j5;tA$&_)N9C{%F`t zpUuYthUX`)d5JIlE3#}fY-BJ42tRLlZesHx1U4J~$nd-qFtib5{{ck4U|3I){k;fp zG5mg_8h-!muFHmYmVcjI#(x>s(P#6XfWg7acpcDA!x{#&8)28>nTgFi5%@ulRR0MX zqwTKm4HARtLedq(?=@)shj?Ya$ zQbseNY8{c|uFmEsXzSh%mzoKrFqCFx zxmEJKla?#nRnCT*M~x{7hdIo^#daj%#l|J3xRQ`Q6Tr#v1y)osD~gvQ}%R z#h<|LWeouKKOT}Tn_O@U zIaHcWSj)8v-@bHt=9;4feeu`%I?60!sj;_wU%{dW1$cg=go?x0oi0yz{xW4BJ4lsz z!t(|Zm%y^*Y0#LZ%zulV{SB+YqG;XqAB>aXjFW@Y<)q-I55H{E{fZjgH33z_@fDOJ zIEG;Jq;xpl-M0udl0KwFx2QALg1|+d3?iBBJdsSMuk7>pYk~^KN&CpG0eLYg(v=4p z4*m&I)VX1}Uas;F6N0kPDusL+EiN7nMI>Z1-}ZF8e=dqN0UM_)eVzEEWzuF<_PsNq z`yIHVf{&VDT#7RIR(i5hRGRm-Q~v+FE&u&W-wQ+e@B26T6NmDPO5Y>tqALTZ%z8r) z6?d;PJd!&fwL`go)E7ih&r5;xS-makH?`fa38z)zF1@sldTzf$);}#*T9p|%;kM#w zRh9G}HMV?ZNKvA$KyzMYA2s^)DEQerIm$lj?uMG0vwsQiU6Bq%pvwxvf+H;yO--&> z7DjQ$6T^Cc6HH%vXL_BI?uFWwE;vfjl6mG{0LWS17R`tWjnexs!M`~1(;esXbh zI2Qq5_AklgXJnDizG$p{Q49{A4lGL7 z5b(-d*@-Dpp{cKmE>3(nCgGwxiInWd>A+0ojgW;NV=pmKU_8pj-UGV!{h_OP!>#db zpXA_Caar5`dM5iyO?vF?XTfdzf!u8isULh ziuKguv9aCa*f++i2i2(1k8qthcFFRdmDP)5_^PV0HT>)YJvArh?}kq`HP?l^O|UzF zDZ?Yt_vP7o>O{p{amk#X#giY+c%B00JN4CYC4s-3C!O(e;`!#R~ z`)yzl7pGA8LAhy5-qFwA+T>3Q^oa_*Sy(&pZX~iQ{i%VP$obWeMd~~^2g#a~<9gr4 z;V-Obz6l7S3$zWfq0)Cmz*SJy(`sS6$S_Mg3GbfB+QWF(<{MlgfM1uSzzTkTLr&xh zQ7!wVsuD?04dnv!N29{xW#TIq_SC`)DtHZT`=kC5sCTDvw>R%Kz8^+P)WYoBTX=V{ zh4Ug&3u@sx9E|D9dp;Y(H>Y!H57&ioX%E#sz{QFE*8=mmIyd3D>88CsFUO5u`(|Gl zxAu)bcpq}mW>uy@#XwVEm4ayC85g7h@Y#A^);*TC2nzPJh46S2M?PbFpJoIx!ZU9O zPPQHaMRpQJ77#^X`D27HTusx)o|ngkuYC?Cm}@t87YB>t`kXMoQ}pydbQpBqcIo1-DNFz!(49<#jid=Mxqtucp9%AK-Go3nJTdFAA+*AIlvD47GbeB8i< zU+hrhopFOSo5ly;WLtaPVTh|0Le{()?mW~p;TKq;q+&{ghdrMX`ydmI@y~eOoDq4? z^n^L$udT_MpxdK@lM3vNX4)$i(j?+=JOkc4b8U;D+&{wIn{6p#^*YC^72E_3wqo6M zKZv2a0s9Z~FYAAYe?mo;;~Y2p?VhlKxYsb1jbnUefUiPYMg4~Z+4)_|kWpGfG}q{KNwoa%$xJDEY)OzzL{DLY!irVUkSfE{-Y44lcQn~N2psp&xZfB-kP2&d;zk+o)ejBX2aUT!- z80_B4+zlFHA2G%(lDe>h<6op~sqrDVL{gm~Lu1MD7*MU3z3HFftb0$TK@6*N-J zD9&##&-i9W=H8B!`gQ%271tBEMD&r5tf(k$%pPlEgd0GK^>LP@6Ifu z$_b-3zn^W7-fHTG&cbNAWRvwx?fZhOx*9il8KLUx@ygIp~v|?`0?CCw5 z=VTo0$u_SnSTfL4f?F3f<=S=yy6Vvc3U+};tfM>m{$G+~>ac>jr7H_&*Du7jPKJSB zNEybn4Tp8oO6tsJcGH)J1igctV=yc=~~El(isX`jSjNk&Q z?w&BB>*=_(H{J|wFT!#POIqRM?jkNNN$701a^sV`ME%oEh!Feu_9Df;w|zgP1xfJ| z#?26Y_VaX~ZII8EOZMzS$z6%n+P{!^Ll@nMc>ZR7OO?YQB)~5f9)F^Kovf$>owk8a z4u4&UIU~C#EweRr?UWopRoX_C9#Efp9&{0O6$KfPLR+JCZm#@|uZmvFist*b(;X(L z&bk80llbPf0TBdjFZ!PJSm@+t+>k)3CB$6*-I?;fGuZ|q&Z|`a3RMcWVHNt7sVi0y zpB|+F(U05WFgXtDO-Y9wNE^EIZM-&QZ);NRv(Q67cuP&nAyT?sb0q`o68NHIdoF*` zt$rM7s-#gA4fJ~mJzEoC_pm1we!htdLK*uP`|>|alWFoLUtSVY)t3Z?M{tMv1z(<~ zvNIpBbAvu$t7IRrkOClr5M!RadFspk@BtgNq58#5VlK9EgKcCT(K-+d&wg9RSSopo zIHtQ-EVBdKR#sW%8b@#+>{eMwRn7ju+{SL;UDDa$K*JF z4H5BoY*vx?Y%XqvdFigSVgvlMVPNf0*-r80Zz`FKTYUFbDr_I~haxVltwZBJhlATX zIJo^>aj0GPZwuMu$jyN_saXjA43^LwS0~2n9tq?u%{I(y!~5Xo$6Pr+i-wsIQz8w<2sHq%oe1pYMdn}>19SQ$M7{V6fr3zVn)aHwxiaLn3j zXw1qi;<@W)e<7B^peFnZf3gxPeW~pS$|U#t?}GE7u_QQfJjHMnFTeic zKgQ#2P3YXqkCVQ{KZEZ-gpuaUlxysH`qqv4sMJ$bDP7l$d*r1K(Y}ETwQ}b8_qu{i}7o!V-To5h{u0FBID)Cc@8rF z$MNLOg-y2i@y&bb4M}-J=Xv`l_sCOuUHfOaFdCdAZ1?g)WZ}l)Im4DaRGFM0@pFjn zdugtMV!V(|AJqOVg2S#I7XXL-3s2z-FVpk_)hU>nbRFNMf>&uD|2ZK5uSlQDfgUx>Oc zH)ZU)Oap;u{>$bqB_{raEB#Zd5Q>Ko@G}7qAsm=+#J6JWiuY*?OkK|2LiiMKA-pfW zKy|P5q^`J(w-C0b)-8&}V+aTG1mu7;lQ^X-IzM4!sPJBROD2xD5ah&Aj`JZ1V|I~QvAc#GkPi|b;V-o-AqX+W+nR#k(RSx zCVrkHg5F2pKv74(YD}<@kAwY0=VZ@QGk)2U>Gi2f=aX(Bq1lvcd7=+eGd zz3|L?!Q_Q@J&1jKu1S@ei1gu`Au~ZNV@E8s2!|P6t_8|Jx&c$OivgcGRo1WFjhTb3 zUB(kPSd3rAi()igK&Ls)ucTr16;)@L$Nx7U+d3iwa{ZlhF@4AXt{WZ^%yaDjAw1wt%N@kH`7to)iolP|P8pBeyKYo}Rr5`uewy(hjjjbX0CC z?SQRXi>19%E&YQ^B5>kHa?!#Y?Xiq5uxa$9z)BPGHNi_Gk1dsM5&RRx=EgtcIR}~I z8lpI}{5~Ml*z>i59(1)977)R|z!8bNzlefl1t|3q4pJ5%#`b<7o!L!N`Bf?0;ut2; zt%$`iI6-irMic$Al8omSG@k&6kK)v_i&3(_%wPGh?Z)%F)Naqq|F+#O%8w#{YPY9u zsNK@yV7r%VWcB2VrBV;U%ftImL+ystcEl$O@;LgDEBJQ>79Xrt))~}v<44%P3hsBP z?M4!71Zg!PqV1+Yt^Zg~pNp{PJEF~RDH#J3QVgZ{1xgE2P)#;jWQSnu9(@nu{flY3 z_&vdbKH2mu7k^@iK95lx=u=3Zvxz>If29weD`)h1?%&d99_7E2J{3ds$-g_LtdA+3 z$wU((llwwuSzliErF|QqxW8lLA3n%h8f_$|eMV+$46Iv+Do3>Dp%C+S#8eG{Z;IlploW)9>b z8UAk5kPPpiIwZrJ<4j(qpv;QZord{d-_C$!GXhmumk{Z+482B+xp6{?^Z+FYMV;mr zZE9>z8XoVx5g4fTnx&~Mfoww<+`aUP(;gvP2DOxE@IcEo8P-gRY|Jv)4EoH=yDVsi z&|2r?k{0fiG0e$Bm|45c7gK_D-OmdNRM%We|95qbmGRaK%ZKrn2pC{L%6P+X!^`S1 zibc$ofzh&HZPmBINz^9$&hK?)3fEs#uy;r`Tk^w;OKmSF*%c9-BauDLOZ{`QtS?ft z$KnG#&M?q5!N#dd;T~d&8p>%^juFvmHx*(9m9Em-`F<({|5W) z9kA7=J77^9UJnBqYzu;9fNUJ316qsMm#MY3=TbT&<;sA63=JuLaGSM{Gb~TR>Dn@K zm&FM);brJAL0v*CQ$Ba_~Y-S-##{8lB_wJd;%T z89nt4>oSxraSnbC#O2v51Q;wM9yz0;h?sQ`ENdBGs)U8w9R@K)+T-VG^b{@}NgONuN7q1hYT&hMG z=~WJn+&@x!i294oJ%VNykC(%$TH0H>Th7|6!tGU2_Np=PDQ~ZewO1wBtM0Z}iT0`_ zdsT|v>a|y)R${>}gF3~&Xrj0%qw$h`(LMHutL%#`_C=XFDzQMd21nqjoP3mQyd0nr zGgawcG|{Vq#z6XxsOGzn>}GddZBM88z6^$q%_%;AvX_ZtYf^llAt=y>(bJNm9)sR+ zJD=;?DjlR@?{+pJ*vEng9+!ILz+CCia-cwZOAcg6d*wj9^acgiZIxc5U-aH8`b95e zP8g!pSl{tvS5IJpil3nV zbX+>}$+}}Rd-ub2AK5n!;}XW`CTWaGIIaSwGV88vRg20lCT!Vb7w;}M<0-C|h*ZOo zW9xcn;z_T^VG}h=iK7_17_-k|j}GaGc8jqsX1h49Q;{06$siXJ4%0#C4RG(D-*qac zJvs!pH#R%$Rq1%7WK44ZKXJ!cmlo*eRejMR@Dt(p(4AH`4%iww`)EDR74|D}@$Lys z8?EzqsQrV10d26(3`SZ`T_nT^ywkKn9*_AP_qW8LHz6#uPJR7w{DDMJnO0vvMXv|H zVEnT6hbCwYZm2HLLbS-D8<;zM0?qDKW z_ZY9!gKESlc|DiqGW@rff%o3axNav_c$KFQ<}@50;bpJ!)wQ&vc9`R`t>w#9xPYdM z#fg~la!RLl-%3kq9h5w>;oVOGX4zEY1*?nB>VyavMTBt-7w8cqCvP8)t@OuT?ToPz_@! z%t3BZrOU;A0~j$dcD3RrI0N-s{YqlWEqEINg=&*q%A|D0UtC3vUyAuTa>QD z#&y0NGe~38Cs{DXFGT7K0Vl*N4KyWq+o094r+bhmTiqYnqv~>99eisMNrv<|gJ%zJ zu07Y~mfEN-G@rTUW?=+Mtt<|zmbG%AKw2XQGNfnZK)ke?0_)t8M89(1czHNQ!iW>o zG2&?A{51+PGEEMn73LS+OPuE%FDNk)U~b8_wl3RKHOQ}X? zcs8!}$8|2_b6j6!)jAlg`By{qwTMw$UV_p#)sPcm+4-&|AGe&M?+s2U1yC;HnWJSl zgCxQJrI~b%n0Lj{jJNf=<=mcjaFpj$Rt3Zd2ieWx!og#hL^JC5X~C@v<=$e`EcnTUJ}d zBy=L0FD9lMTFmln+T}*uiLS7f*C~0sI1$tKuGJBE3>QmGhNJ1IBVtW1dq4ODUHG?% zDY|nvy2Vtm#vl)~SiDzvHO>@~9l0gS!6(n<3)ApKfkQRVFwgu*M%tMDVa>SB!|`P@e2dpC;~c?onrSAJaUStWdWuVq?Ut{I#f&-5 zhxdufZjpyb1QF4{C7?czJA0<^K3>=(as!Fb`QbY4AbiSQ1rMtMNjfTbpb)y?>LS2k zivA)16GDvH>gyax@0DXJEp;Sr(a1q%oH1=A0v8f#V9dQ^+zz*RIkC=waAs+xLhZA;UtamYpbQP*P0@RTlv`km<|7`_y+t>>r7Pn0#LPqxk=C^W6WrY|k^SY`ne{BbPmnl|7Ei zj+4u#r$_E+w|_R39UUzD)Nt9Ar{uEds)O{Nx3tXJG{5ZMl^%5EvI?b_iK3+noC0OE zm`FrVoL4E`AgtD^q~Wr0E0$<(ET*!*r&Msu{$Sa7k9d?THi_<_>>p*E%n4J4FdgFcBazfUU-^@KEA5r3%i8HWM5{4$maQeyA?kV8K^AeDA`Y^MUKa5kMf6bw+ncq& z1jWN9vF*=^Es-sjmNL7G+r;A)=c=JGj`!QoasCGE2vplT;M|k5J&7AjT3qZvHEmNM z@VAsPSczNGRBx{gu`3GdL>2f`_GbM$ygyCimY20YB7|WnzaH>fPtBj*P`_od5L3}m zzoce^kiBH?hJFS5D>?Sz%XeIgnVqp7Nw{sDWa~!4Fl_=QFhv!5LmA*gJKMUpK+3Yg)Ew;~x z&3;WH^5QpR6&!tj$W>mHCR%=L^ zRb6Eb9g3fsn1i>k+1!(V%5X^;iV^EjomHxjD?{*1qptu%8c`7M<@J@_*D`LrV;SH* zVdH}MXk26uj|A`$&u1;i^G8&pwr|S)Zf}SSM00l zQ*pjzET3@&QUNt~d}hjXU!v|VE`NuiyEly0eTNc1Ej|d2Z_(W{+d5WPA0pYAfS9}L?O z@?qOG--o@$$F6-MDX6+9<}287wbgJpa?$M}I_L3RiCOd8YW`x_KbS0^dj9cwP-PZe zL#e%gzdg?P4-s+3(-b!}R|I9-k3WY$a%Nkeo5sdE>xB2IplR^v1nq5CB8v~gpA5oZ z58Mv_?lAl{8Q#T}mKfx-1_y4@g9a@=J2*Rk{FNl$3jXdLFZ^fT+h=>$*W2IC%6qR5 z3axkU3$eeOfk5|>fPE%6WA_;2@z06o2I^9r6=<`fLv8+;X(RhDqL;uA)z961;%x%qg#Lw@^_8Ob24AA1whSfUI>$T*=wCY-P?AI2${k3IaqmhZnR zm+v2fh2MX84>?WFqa|t;oTB)aiEz7St`mFf#Ei+|$Ld6|4_Y9tAb?Zzd!G=GJs~nb zTGEpg<*OAxiyhlrD;}#QP#ob%ODO*3*l^!s5jETQ`7|w^reZ?vtq_kb6nBtrvxZc_LOO^!@a?bgno}yJSv=Yo5V3lYAlQqI$~>#~u>n8l<@d z0B;CTzfvotIrP0CY?fAfh(fEh5)-EfwWq^anX@T&mUcmyupI^`yzNw=E3>uPmycQ+ zyFbUPlFmR?e*i>SvypE;9ypdO_TFod+tgx~@`thKQ3yD+tB7y^4lFoPno5zwMKQUb zigK87vpBf+pP@d3%RCx2=UMMC9;o&+uWV}a(kWN~QSw{->Q49;^! z(PzTEY*o-i&v~$*A5XRO(y#O=kQRQqUA_R64!8t{ zL5RGzdu1GW`fsC_-xi%fXxN>EMzY0_t>Eq^H1il5@|`B12mRA9)K32kL+u2gpv;1|GC*Y$quKo`Y!w0)hTZp^%)f@nHpU5O@SRt=Gm+_qon5u(D~dDR0{?bNsGXd z=daHFbc?@j$R6*M4k9|@(C0FdajOU&k zRhGBI^D@Kp%MDqtMvG2bx~&G1Ni0SV?;;wXi9vz0gZQ4%3R)PLx$)-6K>!!_E4#SK(byH^4{(d!b-MDql0+DGV}5lp<1v<=i!QA zh;M;szp~-{D4fw~9FcEi<9Rk3!@_wSM3e0p6jr*!w@{x6gs1#E7!8D0;DAYEw{p0x z3HoAZLF@02f%3J;Vf>u&1>g_~D^*tWxC7E%gn({ZNn2!_D1>+scpT3KCCDQemE`a*m=Bt`p$4DY;f9HTzTb z9;Kk#wRLseVVD+uPic@tzh%hKd(zi(46FhYF3#n*cxobXBW~j)^r<}7Q9#3|Ayy|g zfgCUrX%@{V#&KYrjTUamLWT4XLQ|$3ZFP>qRbe<}C6G~&B{eJ(W+@q#ZN)s?;1((S>CQ`#o`Zp)H1iGW zP5iISiX6wDxE_NiuHR%O9;Wq`i2o^IvbE(4(Z`-60rk-Ok0j5bAv|Qn2|W9O2mJ@Z zULNPV>8#hhL4-_+{|}^rYx)C)c#9l5zEbXPpaO3@LZDd0FMI38--pHXUReD|Y!2N4 z`#gH%m%z;UX9`J);XQQ22yKF__03)XB5V2o9H@RS$=9kMRKDVpR^AQr5DqOAF32vM zyW&aNNZag~LDef%j-4t=JU4{%qq~^g<_M8dLzdo)I=w}(PZBKQ3-f%->O^uitCMY} zTqnE-{t#>XW4E{cZ$uXifHwj#^ppDn{@H_l!R$Knx$=i#@kMi--Ko$$Oa=_n9Kw+| zzX=w+L^$0?H>NsxL6WFgU9&a0o~f0nEM(QPMt=k zhSEKhN&~X%C21ms*%(Wq5Ce;yMs+mOch^f;JxWlWen0g0aNwTJW82xVFa`p+lt2(p z#&ck^Z*VoE@KhjMtH#A>)YI+cwnas<2_Oi^Sm|q7mc-kw8hdG|5dRg_;FkPRp09>v z%<^SHT5@FnCaGEG5&2Cm*R)$KJXAaawFoXR-Xjn!3K!^ z2dZ(ap8(PBpn&~tpu7ZZq0 zb9=N~#zUSyOl5(#Fu}+62JzY2Em6{biq&n#Ekv%Vse*X#S(R=P8IHa|DS~EA>=$+w z$w|aByyTZ z3^5_1uBT{`GT}s?6QTsI{-xD04fp}YZ#2>A5LUGOai^+t-1Znu$XF`Q(o!+v`M9V-ZHZS} z%IXp+jBvKEhPSccT|rd0iV|3LD;S8dZPEz#CJVMfgW7a~&7)NITvlEQD|-$D9kFfF zBw9ggQlI66WrpriwmZ4!;#8LZ*PBAu-x6ztlSaL^0}sVo(tj)4C9q&Fo;vP?ZX8f3^kfpV>^2) zCZlG|asLzQd2? z=5CwBSClldGEx`d5^v*`k|(!i8G{{1MO`4+EormUdQv7Sp5WuUP|{q!`EsD~O1kXJ z93(rzijdjhJr+LD!)6woXR@sn)osRWARi;LW$deQ({kT z&$Il-R2<}S<>jiM8nQzp?Ik!^49y>1rUFqD7pO4Vcx7B{-rPoE#JxnnU3Sd=xY~f# zcH;^DxN`KW5IQ82iy?NRQ~Y>If-@S$1SO0XRfhYTmpI<5Bb+S-P~D}hy-b~fC; z00nX5HA31l?K<>%e)R^M%PAE)yxG{~(z8 zhYvT@uGzu2pzYE;igBRj@UVKg2lRb}B7p88`o&o6dJ0>I^AI!JRio#xMbp0EyOYp{ z7HV6GoSU^yBNfpXj8Cbr^MlzNYK+hFE0<&0oWX@1#9JU7u3%%C$_SKizKqudFoKrz zbdZN5w4pVQ@@G>1ZM*aKy$`<5c(W&O=0chV6%Iaceox-?CR_*1+tZZcZIZ?l>Bdj9FHJCHorIBn9rXZ3iJls_$caua1s8iY1U#&(IE#I)>aHRGU@zSA-AZsZ#~Y^%t-G$(@&0ja zOkw}{VEmb_5s(LK$PE6mrIkM$F0?rwv_&F^u1@=z5tn9%K37sh;hg09v!1^1(8j*;!AAZ7e}YlLQ(xC(epaqNta~ z`aVivQ2z1cu2{AuwnfmAZlKbLUqOF6CWe~uL-6X>bI6ANmoFb+3=W3rzPfcN5y}__ zN9}(nVMq^RTX!p%UwS*CUBkVwX?;_DTW>=92yV@|QET>&T<_@NGK+(@-OVUGCdVfp$HxOmD{`q_u(u4gIbukN`FX5>*yF!U94&Q zJvHz7C}o-{2j>LFby`{$h=%&SdW$m!Y%?SCsnVwt&PLg^BC>uYG`E1_%pseUaRMtqs!nK{L)qu?WU~MPLsfzrLM6@l&iV<9RXV%<#s# z-@allN$A6q4N4A_HTG!T5o)}rPzblcD!)_PX?8jlBvT7>e!>|m z3a~19Y_d0Qy=As0ltpo;zDK`LCq^D9DckyB8MZrG>3;eyKO7Q__@gj(hDRZ!V5zzs z2urD)LcNt%=uj=tUZ|Nc69~%Ukf9U4UauXG;>?DGueE(j&TNDuX;f62Kh0*?!6|Y+1}Nbzj+nYjq#s>($NX-hq%5Ft~4^?$R~g} zzV$(r7DG7PQMdyqNIDjNh{MY_tp7dbQ{0DdLE;1pI8Cd;q%tjhBNO_ZNjT;`Lj%tE z@D$OhNKQ-hJTztCFl?ud>=lZ#DZ1K#t!zqiY_zd#ipcP|ak}PR4Kooit&nRhn4(L& zCGc$fPWBnzL+&7IqiyV))dHL)v;grbEaTJQm&<~ z&X-gR|I8_}2k>UP?+D)2*H5U2Ooe;S{dt`9emr#;J!+);#b~!ife}%yrI(YA9*#Kn zalCU&&(Td0n_sj#dmJNXMDc}_Io(OYa3bD(B0kNOk{NOAZ}Gipai1KI&k*(aNY$89g-isBG+bmJm+5M}lwrw$stZv$nsvEnG9z;DL-=Z94l}mh&IkIrurR0g5w06xqeC=MdMS$q+Nvi-aIm z+FOQK;t7@+m~z{%ddK1Gq^9wPb9=_oE<)2u zHW*&b$>NTADez^G!X5oczkW-``WGp2lP2^W8R&ou+|Ik(HpNrp9Ili%d37SuprunN zUcVt6$HwJ*xs25?(Q9hzT|p!^1WS z@$0v5cu||TDFQP?n>}9a({Fx@(1pconli(M5ke76pr>ih*dq*$@oPmS<%rFH0bgb< z6r7#urw@)jF4&+Onw- z<~kI3SA8^)@yGn;)0h%^;J~c#Kmc|%jQ7DhV4?V{+uuvcju2v~)h3rTpOMm(a1rRU zuMS5)%%bNO(lVWr9XTBTGZvp+_#IUz`_OQF5sR;Ze<@ZL=B@Zk+bod=E5&zQ;;sY%~PyX`3w=gNuqeG|*|B}&=Ek<>+%JWk-(xdhE# zb54FsWy?~Joz8xtXW-#(C2`|gr7*JF#SM;>?qOMYRs6@TjxfigKVq}hw0DCbOw~%M zl!Oepe1|-?YXO*OTGehogfMi;7>*9&nUx_FU$u6GIl7${x8aD9afAqQ$V96J9GqE0 z9K353Yhw|54=vhML=7%-?T)+s+v`%t2fw{-s(5c1L3XsxH?EmP)&}0H*0qv?@Z+n> zYsXiB=1hFqz3uqA5&UZR*5T_~@T(5#Zg~&7zFu_kS5mVt=0xOQid&!A)RP&Jm)Yb_ z44b7CU5YJVHvTAmP1#^Hav|W|4Ws$ku+#h?u8~T$6p#6f=9u;M0?>@P*b-ql8@JhU z1}5Eh)K$a*0Gs2mZV(?;)aRJXx{RfTjsu672+ z5Iwv}D1MNNY5XoZ_AWZg!$kcTia=^7ncNg5SzLdX(o8i7Rbt#vam|7`}K_k0+qw)4ksaP6b+~zSVr)e)7-c$ND zo_N8=LGAe~KTUh;&Ds=cdmOD#CX`ZUg~zKn1faWB`}gy;iw&N*Gu08bRl-QbdXopq z>R+V7XnYZUDj1!U$6PFoDBT=aJBjAN$$&K_4v3AH5-w7g{w1phCP29F73&V)q&WJ=W4 z-fUfro!M-{T4X4l5to)ky<(J!Au?hdpjyB+3zG*ci2=V>XH;Cq11dxV-9>AJloOZ6 zx*!{Eu_y8aHI3iN=fu=p^uxR6FAUN>RLCLoc|&#VKL`%}@g4QY`O_g4s6B6c3N<|S z<-E|e0)vrpvGw*oaZ@#5#~_3>Um?3h)MHSUk$2fH*TNFf7894Ynnp?suy>fsAA^2_ zsWzw*rp6yzD&JiyjiO38Di1BKjy;2TNX3m;p=;XmE)0BbhRSw0dGZncldz(?u-0mb zs9VIfDdJ#J0?MS`Mj1Rrw~8v|s4S#QIc0_j2!$a`XH4~jLG>j%ti~y{v}Ih|3*)jZ zlQSO5&sZ8g&-_^aic;xC%G_Bg;C^Q6QqOPIhHql`hvteqLaMBs=croRNa@dNUkppv zOq2a)4dM)=UidC0bAt3~tUfbepO=(|D_YR&$%|*0DP@adP=n(g=p}4D%!!p}4e3QB zc5m(~vS($B@edM<3DN>8AY*lYOT-REMpIITIXYF*V#vw&yO4#(8C`VfsV9x9vtHUu z&~kj<(fW*@dQA5ezx%fMVc?x|ByeOn>!-F%#kG?SK&9VR-{i$nYcLCyaeID9wYw;( zHP(Mi$M_98B(3y{9OsD~8{|Pp?@h4uekIuoe67A>3TshFFA)$);?k7Z!r-}$^j|}f zBwwPe7wEfpbL_F~anj~H(`eiMYl;e%3+LJXc?wrsEZr1urvzJll=O$#HJfAloVYT< z3$gx~sMfASB|?~IV$?vatu9JxA-I8DA=m%-WN8h3NX^4IdpTWQ=z~JfoP|Od_OSQb zq?_XaQBjpY7@||+rQjV3NhIhF-uGMD_jo&x8Y9dNv0-9{7{043T;HWfY-cC_Iri>y zgzHW8ow^qfrnP4vB&KraCt`zA;|PKpfn8O3QJ{Pg9r1TN11RAPl}Y~dAOTHNtX-Y0 zvG?hRhE0wpPK57DPCTS%+zuSs{0_w#Q$$)?4sSoCSln?AGl&A3pC1?=*cDM9!}5u?BrMB!XA9H<_;8J{RT)|9h>%Y?xi7}EG4-W1UYVXvD;3+s|iT0jV4qVxWy z?$yVg9M*lncuo%K2MDLArY%;I!isEfCnss~9CmzWnKLwR@`lFm@nT7c6if7)g=zF6 zO4$$fy8i(xmr-4ShV(C7bACagLI+#3zbQb(4irM%XXF zG~sYSh=VCZE^^BB-0nsOEUG80yzsW$IU?DF>``uKUUhaF+S0R+92t@v^-`jTbSgsZ z>!#0y&B>-uK-LFw6{*R+L5)Yqmr=qXOaO-Z>5lr04Ay6v=+xX%pI*5>=HdG2?#MSf z*nJO)&am6_;W|9E!;?OoZ=cwB89k+vb`q_tV=r~!E(A#$-VYnEW;imOj&SM@M6`U! z`owf+pFsGylKD%B?J@e64OlLo?&3$7Sf?c(tpnto|ygco;r8adL7diA5bJU5}0n7IuhDN~>^NyIxij9f^LH88Vg>goY@83*B{^7^ z>ZnWyZ=Ob5$_^8t@w2iWBA;aa>fM2GU1ZXug_C>!g9V77Fs1Uc14`*p`d zd}-sLy!#$92=U&-S59mE$0=Nop3o^S_(A!fRKf)Xq>$+HKck8h>27!aKIbAbmguJ0M+s zv7CSWM?g3}#~Oj(me1M6fR@iG`~m%Ipnq%VUkd%pqJNLjzs2}>sKNI|%&q~V-Ma*c z@6T@k-qSFsalS>#dmG}zo?17`jl}}Gf^C#R8|SFatb9L)1oA29pD3_9?dUS8a_l(# zWPpwUpbpz(#*z!q7rsNV%<;U>(G3)AN4f~IGqSwvpSXVldQ?v_O7Bpd)E6U@#J!kX z`sWy;NiU1vAESN~@|W~y`VvgTbbF1#?4j7klZ8HjP~Xp@yI8tDHSEW{(b#siP&(!% zhsyV244UBe3UxoNwO+(@?Af&`TrYF}9(-GBsPQIETYJpGnjc(|%XW^e)<=}mj{$Kj2 zLt{uCDo%sqO`4QTKj7DH(qk!Mn*;DfCD(du*Hrv% zA;6b+Htkz@^oa;*Ow1=yF=5qbs>7Qa!Ydl6{VPZsTfUdR7t{A+dj<944fm{4zA-kv z>K#38V;@8GHFaD=^Yy@)ry^D^bA;CQ>#=2AvZ4to_QhOPzv7LJ=Mb(L@yX4xXQ~+< zlHa@|obHhFl7Q}0&C#al@1e@K9Lm zLuY;!QJcA?{>*P9o=~owG)uW_py%kEo@r_fv9Mo3G<-riP1Sr2KjoP>i8tApn#TM0 zaE6Mp+jjrjaC)rXdQku9!*K<1b7mLV^Gf<=WX=`vX7mESYG+U0x`?>9b{+0(yp=J~ z_vOH@r4I|Uo_cm++p)1Cu3Zn8|9Bk(tL?zpyu1Tv3KW2*Gt#Wi$o12EW`Ea{mtS%5+ln8y zD$_L!M#TM7jkO$OrF=K`=WNbjM;wNcZxK0A#-s#qz~Y34jDvc;V_}p1;QB2O$8Cyp ztasR(w)WY+#o$9q=fdFnds7Dt3~wdZ_R?4kcgnm1|5`|2;4n8eJ(+y|OXa%k6ORpnxR1LCGM`yV}P}?PIr%7cb*L_wqKilg(k3+_U_?NRoW8{gQHn6a@ScpMR3Z&WE%XIm~g67BdF2ocC4A z>oCiM4Q-jm>&jG(m%LvTjcr|Sm@_sxhR1)<#8k&nY~JV)02ZE zF<0#$*(CNz|0UN5_)woZoR8*@Mz4~u0%?ql^jlO$XX5Qn4(dTWueRrpmg_{5%O5Da zT``)~3U)_mz;S1EckgIpgr>aqraOPMnoPfl_S1OyqGb3lqs=Ob^*Q{Y#$H4LTTWVd zHOdx7f`VA*2={WrZ2@kwl)oLfEle{|0@VHA1uWJOKv=A5+)6+hmV9Bmz45zXFZc-o z@XL9R_-waAhpAZ^Y&Y$Tp_X-S)@O9A&co5iCjEskAR%AqC}X`zM)>aq@t|>7K45Be z?I%1xAI8JvuMo(BC>=W_>EKVfx_1VQXG6DWKe?G};vv?TSS?`OuFn(O*t2ZK>R}G%ut{vP{YIlBdoKU`fwmL6qst;zwsdH8ogr<q0@Bow{S&0rDJ7-`Wjo-8@CNld@YVty6c* zgS1V!G6oW%l}4LJ_a*nqR^74xLi~$lPRw!U%{u2t`X$Sn$T&{x4VBJ}LDe8X;gPdf z*?cB#(z!P49Gc{qk*-a;WK*bXqfQq?Y7<5ewx4XgsxWGs%EgR; z+DT$$iB2`{W4=`2nTuVfSJ0CW^v{+kusw1ZIjtG5qc-$lDPy}bSN5MY` zgE#gR{xh&ZMcaO^j_11j6ic?|J73nrD5txU_rsI)1Kb`1q=l*dFwdD>u{be^9Y8-jHrz^%UOAm2GsNX|bXsbh+ z921^wN`4lO8gSh~Z|b2=aVu3*--BCxx0SP475CaLR%Rm>Oz?kA3F8r~=*JF?&AXVm zkN2u%skkM=p09z?e7bg~uWPI4S|BZr@ip0PRG&1Q9b@M?or&|jJI44QA7O~-ytix* z-+*xo>SH)PhON8Ohhy5E9IPLVeYbGaM7V2E`|Sr~d>@Q)ogDLpLKx|J6BZhPKMT8! z_s0y`ZTNq4Bgj(}|JUJo+pmY>4M)a+RZsy)l&ALKk}zrR>{d=%PW&z%7}JSaA5mx^ z!|%TlsQm9SjX%1RIjNRFO81YM8?t3ic^SWave$ST7a{Nx#+gvOd#5OW?H1-#HCuzv zMgunC;sV|@rraK=b1Fxw#?bf4dc2vvA&hB@nNbzNQ>P$Sm!%{~u-V9v4;d z|BoN`0t>FdUclRuyNlcm6A%?l+XF6$mkLM`?FOiXy|vUd(J1$z;i8m^rf62X2#N+N zW`^d4MI}=#H7o6nhNek|$^x1f^n9PMa~AXc{=9#G{CxQ2^_thb<~6UGGc#w-?3p?8 ziM`V&^`7LFV)qN{A3Ll^|D7LM~)P;J!~DZ&)U!SNqClnWuet5HFp?v~;1YbVJ7 z8K%UXwO6$<#E0L4vvL;D?nffbej5OY6ix@78 z=(jqt4Q~YPcjMA18D8JJcPD1{xLa}K{DuxzM&8vXr9_zXV=^Pmb?K4g?nI9An;6qQ zrCl4NN*-tO;b+f<6F8fT(l zN#wYDA4u2jm2*v6OJV-1Xf&CX*3wmxewKo`LQns}9iln6E9dB>2O3-GEvaxyYmFRt z*AV2lG`2f;N*k)O81wTD5{t3U)vm)AC>0@LDlXWMR(wPA?u1J8)(FcAIn9k=$8PXD zA*nX_k%EHpxE9U@5o6H%;d6Sut95?YyM?KYwtqW&`8j&~g}I@&xB$|?FQHhB@8O4E z;9*%g+N!WBgx~wDM*MCMwL*;2AoRj2<>Nv5c=&P3u6())`M8VuNL=}xaeDYU7*{^h zfAV>t74ym4^B?&L!}x#Zb6tyku4}nAYD!cdCozT=tx%q3tyrD|&Kp|CANWCp%JU~_ zh~)uG)f6h>rfHYuubQS^8mroAk3Dr+>$sw|U(s^YNf(K%lHyXvRZxjg(1M#Z*R!9X z{7-1P(_Q(W67p{l^FQj!|7+)uT1UMr|L^|EAFM0?1j;`_%>SuVN41XcwDu!fZuCF- zSMjd<*gyGmjJ=BTuhMcmyYjCV@~;&0uW;pm#JOAR*zC%G>p%H#(pnW23f-NM&>>yF zI?<)v#(l2EG!4FSeYKW+%c>{f*tnhcai=zu8T)5isz+m&Z@(&g(Jxl(?K`(K`1y@2 z%%(b! zr83UdatlaC*Ep9L!&_n*-*lDnQ|Dr>W2UQ&vq(d@#``6P*R?046%r#3=sD(JFOD_# zSIK6smYdpTbBbVdo@jHj%VvXfme!H(viag8o7{v)^%nSey=_o-r>~Fh6w1a47V+r> zVd2zz?EgvsI~U{8g9`)zJ5U+lq6xHQx?qj}M$ycj}`+yXvzZMZ=SgNUBqM^IX>hoULajuJV ztH!~(d|g5sg0H)$^x!OleyOH9SI}RB{BfgZ;#P^i7YoXD*pZ?^35qKh;Wwz2gH%>b zIUc(y`9{R(kucVXKU@JN5qx#^saMIzS2f&JitxBLkeedp`HEPdlU?;$?#$OX(p^5j zNE)SfyljG-ZQL88FK?1CGDTw@lpW(?`Acf~KvpY1i5U6KC;OfHM)CNMTtV$)Blhxq`z8x`2dwx7$ywP*m8hC%p_5c zc`;RLX4H0S6``5%5BGmmQHR|b-n!BoY)%_pD7%r--FQ}K7MfyUrL!ND4zpd++lvAhgtpSjag!n8d!LVm#uFEQYxy?U&&Vr!@H zEJy8OKl!v@&DC}Jy`|0cS>`340BWkW% zw4vX4hTBeT^;TGUAfdkI_*u<;PBJ>Nj2!lu(mM#dWF#Ax1g+qeX1st3{)Hx z)8^0z6t67c3oxN)m@8R0IxrEZ;Rw%!>5?QhJ6K=TUc8;*9BOvGujPH;l_mO(d$?6X zw#$+2^=^)D)c67DLy`y;7-LihM-1`Z_+#E7wk6%ite#+_d^vo3pPmdf7 zHAbuZDvKK9<*G>hrT&qhjhz|c1+Qr&_4TM^YC3zNi+K+huZ}u24!^M#Z(oG*j9U1x z7&0M6deA~?q)FX>P>ht@r&_jn)i>}86Q#&g)76gYYWr|CRJemG)Ps=bpLr^+Mbl$} zkVlvr>)FNjaT|)8)+3A3&+#IlEZM9QGTdN=YKg)o{+6T=0`?cw2(#kPLJF?0TDbjw ztin_w?qk)`XxiIRK9!Fft7hq~NOIIFi5sbAt-coViqC z3AkU%heg9G+>V#}HZH-7XLwUAR!wj3#Vgen{if}b8Ap=UD$0rTCrwyGeYtE6_%B;Z zm#vL1Tfr_{l8Sy;_Wp-0=|8rtQHB8ZMl1I_)!%i=c`rvFHBJrh%{7q#`ElnT#rUbw z8|ZpX#>&vD$+!$E%vVqOsvRn|U8Uw;>AD7zRc^wi->DKWy)b1GeScPxrgl5!q25`R z?QmDy-PK$Qr3#g#U6O}J@5|Q>wwjmXo7}-n{?V2&nXyhA7F}o#m4#`;`t6tE^dw1z zF!#PssbaKYBT+ZvcjFu#n7nCA@p{uOiYuMUq`lsmhj-SXfuB0CJ73#SzO!uhslQZ? zW>rBG9~!;!v@RCe?HNdUC3NMb4UG?@JkZ}Azo~Sz*We;q+?tTq`yu35{=|Es7$j&+ z-E0iw)=+G9gUVKuC80>AEHa zM^%nvu5=cP%xj~c_?eUWD*I0CRiTqAmu*wJS9_{B2gO$ePCFV|8u;Y&z}I>QVtpIl zah?=$-W^iBD(TMEP!IvmjhM+(t?s3vnxehj178G{iX8X+Y)xrkc+o;idxwOjfdg># z*)5SBh(+8i8^g6yFl)-dtSL{G21fe#c7u>oTodJySyLh=M`MF+pccoIP{hZS9W4N? zCngFz8cOw(&9O4!epdb?9oN`Zf9Qm$zdY2#aaa9)pmG$r>fsrRbk!f~0Sj>Gv2kyx zqUscQ6&Yp5_POUsr+-<{VLt@MQ2>K@`y>0|g8iwmf5v71ZI$B<}5MY35ar;HOa>W_`8K?nTs7^4zB!PyQp#$_@mr04O1 z=5=>!lQ-$QRENN)c)_O;Do5lapZ*lCtvHcuJj7iVbal`jNxJYRO670_ zU8PZ>=~)V~SxOf4nQ-do5RQpW$;$NDZ0t{$`$w{Yv)a#lp>baC<_uIh{2t|ZLWraV zl$exYO<0y~>Zl=s6Nl)zdLicrzDCyqn|-Nj9a0tgZxu=M+T4HR8OL9~LRzkc zWRwklOz~DeS*Wqj&Y$9EO$n3!Iq1(9_KdvRQ<6B5xr)zfCevG1WcY7NQaWW|+6E;B z*9!T3FXnU2SJ``EFjq{n7>WPyiqgP=Mc25$D6Eu*N}{p`MrA#XZl)?jxbnuXIYd zSm`xFSP>r>&c46c!p<$7GN8e1OIYk5?Lq3v6kWYkteA4&`WoJvl0Ri&{*TmL(s zIwcYeo}HDw|BRyqWt1Q(6X)zV$E8IpPRNuPbt&Rgiii(WgL8x5>(W8A`}4 zC-x}5Q?tB9DLFg4+Tx4%8?7lgOQe1x&Vb^UP`vvDw3AFhIK>UX_1UgH`Cn_AeM;IjFQufrtR{1qe5TB)@1C;M^oX>h_0&Zb-y_m|H?Yq3JIKC@UMT|ay6AsM~6IS0RrE8GfGQ2g=$ zzG=0JtMb`ktx%M|#Vg;zTsekUc1sIlcG{$P({=!U@Wn3%9vI@kqC9Kx8!LDPU5>TU zGW@KDQ6Q)npR&=XX|8J41WScH=uNUCD<6cUHJR9TF5@;+Ql+wHHu$>&->t!2`81MV z3E|O7^+B~M2Yql0(+64Nv*fW^;`-lmdcJ#ELL)aP6u8F6Sh|u5?EKTmamWX&TCN7L zkfMbKfRX!cLAMIJt6Y_Hp0rWkf_DCnboamjZl<7LT3lV`P7C?X@o3^*)ZHg6&2==LIM=oaX8Ur4OL= z85X`TNxN6cPfL|Y18X$pr}6t%+QM5W6I505WOHr#^E{@uvn@W$r!LIK?AM*kptK9k zvp@C0z5);K0}7)0Wn3w7xwLy*mbOJ+{+eH%)K}?Oo4WXf9QC+U<2fzaPj?)O6{M(q z@lmx`?iapaT1MjP&tSHEEZrwpP#E+xfx2@eiMns+nev%_WYFfpttU~-M1RrCW#WiEl@GBhKvv!=);of&c-XSKY*~C9@49T|QRM%%l}Tc5zK>w8kOs^0vAjDy&kK7X@Ty$PPHviD z_(>SvLWa>&od5E1WK*j_0x`PFw6cMAOZakQ1;bfBcnY$ZRTi@zIgF00k|=R1yB4WN z&&HoCW^vs{7@t};iHWLJ$VhCP<9!^V@ZZ%m1(RL*G}dt@!7X=aceTzWA4i1(Lp|r0P+X(oZZn+a2i4392CBF zDd=1ZSh!)74K4>eyG?YQCX@_lds zcUe%_28DAj1*b~^zBeA`8in{$#Q*Aw|I^!XjSS$Gjo_ex|J46s(&R3Bqy97gXZ;8A z_2+o;70zI7e^iRHfv($bN|*AZcQ>=pSpT_RdOmGoyHZEzj^M)r*n5R*Hxpyslib&W zQ^&lG<+Ftv_}1HDMGd&xlMrjPOA@OO}7Al-uOJs?6J7=3R}*GVfF6-f44uxh<6RU9ZxhCo#_`7xVS-A9JTP zNQ3Vql#<|Nuqp%Zcx~{;sK3l;O$bhxxX05cAwQ;AWUlnY@A$~9il$`cPvMw{Y0-QM zPK>SyjL{T^#okf|uD?<^xNrhKeT)9p%JJVNuiQp_+S>)Z91I(?_lZuZ+(5<<7dL{d3io6SrNx z`i`M}j0+ymy^#m$KV(JG3FSdf-of=0N=A zRAf5epkKi=aVp5PW4P<4bfc#0+N>!T{S3+?Ke2X1Z|X&^lSy`qruT?)2MbTX%bV zcdngG;UDr#adxMrF0PeC$aK}!?)}$iYom4DN<6K-x>-X#u_5W>#TypW`4>y9Oiqck#J3Ka|;sy#*CH+&;mWaFSEdZLA7ijy0Q(4K|xJL(HZ`p!1_nlQh(9 zdIx;W`THgm!;RDjb$SZcJ*)#*#4_pOgsHv8b3U)2x{uM)Z7|Z2e3N{a6p7&ushU^Z) zTgXrFasd8#BNt{E_)fs`Go|yb?KHVD{0bfm@(dI6i`g{pD8nj0W7s#4HUoGHm;pZ+ z;p$jmK?XpXSVjW)3ja}L@GJmDflzKz<}lN0(gP=fT0jRh0KJEqO-q1r0E;@4t?e|O zL4C2PtD;c~_6^7<1L6OMA0y1B_254PlA${se%6B@1$o)iX46p69iV#9?!fKgX456$ z81NOa5hws=0A@>vDG4^hkzW${P|)F^Yo1oIOB;U$hR-RUY{T=OY($19Ykp3_=Dg;~o`sCr=E<(?Z#J!n zGn>4^%%)xOD9ih1(;M(}6>xHsf&C1!4$vadU63V#UjV)gbULV_%)m|pHG_@<9SrmZ zJb^aYJqJAbjM>!soF{t(d`U;IK|LLP33UW{3E;*_@%ALznY9CXck+BIkEV=zM(=>j zdKUH1FiK{H*=+g_yTUeJ!Hz^6hqxy2L%^G%(+_kjWL}^R zptXp50Qzs>Ish9tk0Z_wlmk3}pSPf|JsStBYj}PvXy^t5+gZ|Sx`6l_Km)I1TY(JE z0JaHq+zB1aAkFwKI<_Z}^s9mGH^7r^0$*04V>fQqvHO4=gxPI6_C!NN!zAT!e=sj}9&Bk>mML@DJe!gKOIWy^aUS6TWPO ztqk~D2^9ScedSFR>kH(7uYE(sh5}~r!>6m*${ZCdNi>_f0d@8SQ_gT5Yh`upSx_bD zQ4A5e<82pMcJ1)$(hp9B2`_!XE7n>B9CaMVHQ^SFMa1K4p$ zYr%D9;8Vn4J=@rWVJ*m4*OS36J&dnt*9|XWTn4qS>olE3S((*5AM>S-wNM_bkoJ9m zd@n-S4q6Pl1eE+m+{RA~?Aa(!HW^e$^?~cW3w581Yt{U*fn5U3gIZR_d{ESPBkb=2TH$*P zbT@)OGZwahe#mbLFaxqC*e^p~b3vtk7+o^Vrk=nMKyOsAMJWH0YbrK_WSM4DDd-O1 z8(=)bZh#gT*GIv&{2*r=kk?#<-vf36%?Q`PP6_N-voOv9hkzXh1)X8C|uCmS{lY?L-sZB2heSr*^~fG01ALc zvx1HJ6!nWdv_Kxl$Ma(nOl^oe2%H4Y0UP0$4PaI>%wK=;{I+C<*@3YLJ?Xw@Hs&{g z3CIERewDKufppx@qM!0)b^n&LiHpsq_g_Q%r}!s4*&5Kd5dIGI70{u;(J%!Y@uY&) zgRcoyunN!{h_4J*u>S@fi!f7!VxeHTx(vW}KA~Wx85pQhhRgjF>{(f-sRo#J>7Ge( z>AvZc*Kr>L^t+H}kb)imF2lxbOfdD6!*`$tWsv>LY}zveK7d}H>d78{)syv5;d_IK zI|(SkpET&%6VN%MN;I8;OsCYd$;dNFs%Q6MjFmt~4tN7zz$xhVoMkpCXM!TE1MT&u z+4K@9K2yxR33~Jmv+3ato?i!kCgK#3e*=CW_?t-ILb@p1xEDOx5kIsKuf(k_7HQst z-E7c2V21-Q0cRlBylpnQ&%vAtVGU^B zT(l?9ZqVNWnGMrV$}4D|m{%s^TA@?$mf5rrd<^&xL63m$038hZAkAs1pkVzL zpk1v;I{>unJXzloPu2?fxObX70XKlTaNqPa^vpmx(2TaT5A-;23Ah9FUx@oU(wD$) z%Y4jFF&EawDA<<}Rt{IN9Y9T#ntc{}x_8W`Do}PK!^~KXIsZqVYz)#`fqg^N>}kYx zgN}9{+AZc(x*W{4;orfFmzlG}VbAQz_8fuvV;<%i&`Sc10h*IgGvI5-8rcXF zY(g&s*abcv82^ldZDu{$A$d|pQPkVLRda=@Z0#^rp1f^3!!fKD`P5(@lnmc(@>Ua5 z>%%0W{5>I$KpAwPe~vVp-hLO?9mqhq;z!(@p`!<12Ka_B3}f|WaKzBj6B`wjk@5m?R}IfvfT=L32DCrZ3b=uSaCIJfPQ$kApiO;K^<}!6OiXT zP#MDE32L@x815-gn@ztWOwUI2oOBpGv+@?MIqr`P9(FCDo+B9kZ=UD-(zF;8Z5~2? zk?^0FV)9Kv+;uSx25ths0SEabUzTD9fawX%)tL^|BLTLXZVME)T2Yf3cpl7Pnj{$v z3%MRT$rSHV%lFkFn%U6-pMHEc%a_s1A(Jyak2x5_OJVyy@GWIF1J~jX@_FzC%Jx3) zHNYaE1J~~kVC(D2e$bp?Y6X85eRB=sJ_UMi=rrkp9pLRi#ZsjI4f8q3LV*@M=Y_wa zW|_5^Qv|`AvAFrDK@}bhQ-@jS5_GtW2p_{l($|~O+dUXtP%xA6yFX)D@&xAYDyHeR z!Ax!a04BM>Y;pqgfIonL0~VkbAYVQKwE>%ePGAR~5n6$-z@GvX@a;???uYO%f_w&F z0X`i3$@yxw7QAn+nr&i@>~ZM6W5rkudJRy3FGG9?=*vJyImURP5s+;*uqg?toj z?gKR=oJ4lPheOs3dJpI%ecbyi^3?1d$UT;sO=~{wG>wC9GBEXBHQQXMW+l*(18%@r z=)9!IJr(=}@GF4tfx_kJ{~u!h19}m-0(AVMW}}PHm$w+$@k>yqGj5C&=~5vJU5s(R z0{2`8%6-smnh)6*KogLTyaPTko5ld+!B@iWeDIAx5AZtR^7BSk0b7&7k6WZ>BRKd< zHbHx$JWJsFEC5_7{E3H zxw|nxMI5tT&#qX6mWmddhw!()XhZL9Tii6posAfX=UK>VVCyi@xCvt*u20E|zN{X$ zCy!#71GsJ!e+R%)4WnCaHmNYKy2FkKkb!bWpq@^y4q%%Xc(S>epSR#%(+_&j0&f9% zWhfWuA}6FM`1e8jH-W}xnBK_k!>`T;!n7-~E4w*~2D zAdd)y`+tOMvrWy$Y*n)}K%)T}phtKd=*gl0HV1Zh;o9W^L%uefK1Z5`Kp`*}ae2VL zDm7aMtN}Lq^kua#Ji(3w8ldwFFbnb+U_9Wn)@+&ztOS%ABO5wBfVBY@AP0!Z3BYq{ z0NVmyhjK;(vw*3X*CNgU3dJ5fc;j(mi?(_Pk`SG7=cn? zH832o0$Ac<8h=)^uM*GDEdg}{o4U_BP0f%MeT?}dXbWVuo6v@b;o(`wFn?;{7vc^B z24FD|3w#WOBkgeD1@LCHRowOY2~+NxN-nF}Igp_{yXArIgS|%3hTqiee(*);&rGwL zjRY!CA7x0p3)l!SJsDIO?tajJVFe*+tVBfu3v`3d?OkZ3cT zib3}Qe*)b;HJb(jA3;9jO+1S_(O-b^kWGPXKInYV!^nFd&{5WDI((qhv=s8?kbexi zW2=EZ3fZo|(8u8acaWtZ?i#4qXP8%9!#Id?3<2L8ax-WuFbMoyP&d%Epv}MmV6GHv zK(KcPpmy6_YBp_w&Pl*)liBnW!pDJ22;TvELFa6{n$2h2m?y#ag^mUMtKb&`51?BN zx(%pA8R|jnAUg}X2UHGh2Xw$tpd5G}mGpYEUz)`0d$KDU6kfZ?cv zk3oM28~}s<({d5_)@|?`x=p}YfJa;~WWHq>!vGa{Gw3f{F_!vj*h%0&2VVfX1T+SH zY8&`j{&#lN&a8! z;Jv^b!O!xa<$oEz{Q}ujkhOzeguZ4ot{v!;piWRTXglbOpvR$C1o|;(BhqdK-&}$D z0POL6Pe~{0$PJeJ`D<9_{7mLfKR4z)bRI(g0qG)*{}w!xBRmjvCg>#4#lQ~W62PKv z+$=ml3iKg5OApwO2W9{t19iXyui|LGHN&Z38$0J{5Ehuo5^3ltT6+=w(1sjede~KhQ+r z1t1f65whK&KLOr5(QbicAQza4xMEOm(gD4Ie7^_%9`rBJdQkb7SWBA4FnZ8TgjvvJ z=%<6e2jIa+@)76=$SOeZK<7BJuFp(RE3g|_c@S+KGUg!e{}`*9A^T~s z*%VlVu?+YQ{A$n|(4(Nmpl0MJ*@NovXDEk}40!hZuL z!x&}@!Y1$wQ9gPCIfU?22-6su4|)dSi@-eaa-bKWe-2Mk@GTkkIuUm6!!`Z}_Z#3h z@X4T*ejoS+;I{$puH&BP{A%D8pa2*Ldow`40Bjf&|3bR057Cbi{&7F* z703eC0JVU5Gk!M!-E#owz(b6y_{U2Y@q8}qlD$C=^c%#h z2Iy8`K0x;RzW-NBI^-ueYuL-UzP0%EF^~L#pV0_U0#D^mM%}DMeeFcL-+*=Csh(xf zpA4N2w4qjjzlXIWq|@X6-vYfCk!~U4dGK-ISAwUy?GJtxcpOH~F93fQ*ann9whveX ztUM`YDnQGCT|fuo6-O{e974SUe;>xU2>KT&2U-d=fV z>>_Lc-3fXg=mf_7p<(y^rD2l+=BkFxL4WLh6ys|H`XT7sz-r(i!Zy$Yz$KvQIOYnV zxzLY?&7NrURnQp*ItiE!m?0kttN`B&bR(!6XeHQ&42m1XF zX4AVT(T_p%5I$RmwNZrM02aTp ztN_xn9;&B&AzulMkH`9Gf+tIDWYl^12kd}+BIqq(58(TAAGY(SK5R3<^A0`~>FXi) zynr@^bzwZ?)m9+Q$wUR~i)XwXPc3^I@mGPQlYQ7Hpce)_2ke60SHMf{_e~2B&ioB+ z1#~>Z4>A9bUHH-Q8iZ$Ioz#3B&(^2pY%l1TfTm-8*l@^VkiTp+4y49!42ezX>$h;< zg3TwMxIn*f^S+C)4vcu)I0YLGT1mR#4?~B+nw0H6=DJEPTMM}w|F$9gC2*n>^$av& z?dv3TbG2G_R_iTO5wH?i0$71HKpDXIWt#9rhzCNZ_AK-pff(c?!Sh!61C$jgf!^W^ zeMZg&y@0UdA=(*eC)PJ>p2hkA>a1ra?h`%-u| z2W4sxExYoYK5P=nff-l>_yTr3G+4U@-2)_}9i=19QFVeT20HzEX<7YVgb(y#JAi(* zNbl2WdJ6F)k**eLTCbu10TBk22hbtS8l;_yc%!>s-}J{llP`bI)NzJkLm>|bUPStE z#Ou)pLo52QMSZmF<DmNS3vduv1KCHw++;0l!uv&XJd?_? z#45+{nQ}a<$a~;D$Vvn2h5BG#*0Nrh2YF$=!3)=20$K7KTJ|vdu>>*+ts7t+pak|h zVY`OYvP!=MlNJa7f`CY1I4~NR0AvCG0^SA+fVIFDpa$3hJAM4oHbDD>KHDR~^Z@c$ z@S}lY2p>i`1XK%5fNXU)jD2x>)(v4VgniNWnn6zidjLDI0+0SrO-?^ag0X;uAuoa+7fn3;@W4<6q-`a(6G~(p=9YWq4zu6EUfOSyVsszp; z{%n$#wE{Fti2>D)(y~*5!--n939=buAOkALY1#2W=U6RUGg`|QfzE|aKVV;imTiUY zq@F0}vydU)JXy;&0$!+dFVy*@9$%lLcZK#%(y~lnJY%9<9k?#$7qx718p;Q>0_hWx z7obc>o5DL9b7Aw&6y%HF!*+nudmML=*ADofHxuo9hL)9t;@SgJ-~rwZa05LG`#vc5 z;YILg65hpG0DI}6?`c^D*1eE|ISbiI*r)fRe6Z~O6L=?3574_>!+Rx|J_ZH>V*q+* z=B0Na42KsGQO2msuGKVkPIa1i(mSO$av z?*MNC4e%`mv;_I>0vH1-!H9Z*{0`6roB>!|pX2R3e_O)yEuH>sBV@zZqpnM|Yzz1q zpk|bZL7#dabQe$yR6tIz%Z&%W9{2!Y^jPcp0{so?GB)D+eT?=4IuGLkkN9iAi|DHZ z0XOLO0|J5mfE3UH62OPTua%X(6>NO z0RH*}Qv|RMvNwP+fDtf3b{n8|#qU6?fC7Nl7_&i}q2r5k^aOMO(+dv=Kk&R3yml|v z%kWIDGbWg%l}| zy?hYn77aX4Yi`5+{McQv69GF7u)%^32V#I|ARIUhc`Z-_>;sMh?x+X1{;&zmI;dqg zgEB1gLdLX4*bnJK00s0s0O6-F`c3R0G!{V#ZC6{5euMFqMSaEt79a>|%s|l}Vjn$w z2;%_|3fT_Obm&t*rST&eGHOHA_fNv7aZWAkhP)~Q(WcR-&p?Ks2`p4M(H&?%u64&< zx3nyko%&pb){mWlG-Q+XC|$QC?x9z}@<5t%j)_L_A{~SD!t;S~{;01S|65~zki$t-%`4rxB7Tdu&l2rcy z*M+Sg&f^`9hK{aw@FPV&)(*ZGln+6y>`fBN_CsY4+)=iN*7?qvy`Hb>w)Y z)zkKXE3*bv?!EH%fUO=Uq!GVG)_7PxSM8{oM|Ec-TSryO?%XHD&Gb@+)c0i=ZaIaj zEgiHgq)P7iu!CDl67GHai>=HHJ07^x=^=S-6lWo6VjzaBS0mHLd)gP{n7Z@w>iiDQ zD(K6Os>GBty=K4HvE}R6DBAvRhq6a?UI({G)TuMLae2hf^h*7ikDT8zanOovwIT0* z%G3^A-5iSAFN=Gnqe9EQMF9w>5`eN4B;vH$J!Vt7gDa6C!P zDv``4#b-zBJ$?`1o)YZ#gWayZ=1+Gxh6{Sle3lVgf0#M-e0o%paoQ3_7c)Obs_fbL z5vLcD`FA{!lQ+}d91)bH;NLv6+Z-qyw#M}&6&&{>t5%|^T4z@&9HAYYhNOvS_}N|^ z*#Eg065v;)9q@8P`mz=xdkS(bpQ=#WBUc-g&Rx(b(=9Q<_Bc;+PV5u3hMDjU>dFk}em< zloENmUsJhi@?!%^x&ogbe5|*{th(Cn3dcMeU4ADs=yl%_RZ4_U2zHGx4w6-Wjba=V z%6zWfvFlNpzoE#-%Dh`p{v683U1dJe?l{&imO1ly`^4P=T$Pxnp}G|31qjC<9By~i z3p&^M%+K2KEuUrCS;0)pA6zM^qFy#qy{zr3mlMvKcE{STdf6bFlO|rEqla+Yx$;}5 z@(HE;pKcGl&&#l%MhfwCy5)#D(>AGTKXeXocRwxe#hWAHtb*I`!R>6JjAiYPvPWgi z7c-z8D8?wG+wLU+T%IU;6NAJoc!l;}((YJKML>Js9T>pP6%0;?!C9_)Skdly%~i&9 z$qBjr!}jVG?c6%j^SBnk

aY>L8q!IxMI3XjQADln7|Xwn(M`VUYEW9&#DR#w*Gl3_GDo^Px};>bk$ z&uG_77w_L(UM8`ABW7=V4kJH3FpnsX)W8 zu)z|XT*QNIsijtclcV`@5;%4Q!=Njjyq$jp4V?6^ou+8?bJCAEP0{G*q#t#fqKOG7 z{Trt#S`*`>tDGjHi5RI=mE#;0uLJDc5ox>0nVAoa<24ZO`Duod;J3sV`d(@gs4u>yi{$C+fPtKj+8OWLOGLc`=sCvNi6OL?AzU>EA;5sKr~ zyG@Nx<5L9h@MZSR4oPI!CS~91`LBO0%WY?4El-4pTPq~33ADrMmu~U9PjjPic0c+( zzyH8m4^nlQmhlI8MrC4-wJBL8#4sYKIPbOBh$SH0O-oVj&k5xp{(mgL`42+*ssE4V z+u@_`!|&{JxpC=b{@g}K5U~k6X+xt=yA&bfvgC6PUJ=m4^>cW!$JTL%mj*SkW-vlEfOw8sE~R@9rB9%ffF4P+qmx|g7H3OX7bnr5(qQlbaRUAO@O?FOhyU8W~o|x=`#V3)gr{XSh*Yjr(KP=~WZoPCz+*SV=655F$ z+jrmxBt~@0^ZZG{9}+3VzOS09mRu(FSD32Gd}v~ps6(vTL%Ly=+Af@_!$K#5_v*7} z+6olx#QM#@w9O}kCk}FmP`#rZE4)w&sYKrS(Hbo;R7vyi_RiM=?>Bq^F>+5D=GqH= z)S}Dm?;zJ{W#DnsItypL<_+~TGN=g4J-35C6{02WTvR7J_jo`>?_B(EvL7CS;znI3 zg{5OdDD|b|lC~mi!`r6vY{?pKkW+357DE)#6r7-Y{|rvB*SOeVqRzi3?CLs$F~BE| z2engt02CUG>Ij~blbnqu?IEK#aAY@nEcp zoKa5AUeS~+pY3T%PRG)t;4~H+*plN~PlgwSf*_X`)>|Wk1|m7Q!?+(7j`PT7H=n|o z1OgvvST+`}n#N1Q7cO5Y9Vuj6Rsw@_q1_j2`sCDt9dhiU^Bw_VuP@+-Xw9>I;$|glP5v4OTU< zY{l<|D*|2*kw$vAa^9`_lh?w*tvTG*NrtWWUivv~xtrRMRNYjh z4Q-Y0NisJT%R^g5dy=vt9Sm(v-;-1r+M2N^X$mur+LdH%dLSmWb>g0+Vj|znOe!u& zis>0kxlWL4eJRt4Fj2ul79C!l3==-ru`qKRWR&Y@n7J7~mrQhVza%54t1nFM@-+2@ zXC*(sP3W^bnK}Y~`Zyw6%!SWdKl)%4rx;gUfG>n3#i*607*`_Q6WyO3@QT=S54T0$ zeLZ~W+Y2YJgfCqR1D*{@_cax}uVGLB^b>UkIPRP6BSshOfmK9pY=O5&SJy{+9Q-&RcyN9HJQ) zwxp5URF)_Z*ve@3k)Y?$-kW|t?M?$jRfO>me5&`r9Beus-BL4rm}nuGJOPMJa?dCP zigpZ#i6nd!&TciZt_S0WgQWW;Ea!Ke4Es-p$-)VBfUD#0Cg5=au*JQ2bD9j|0)mGN z2~35N+com8hvA1;C|0i;i^b`0yWv(OWF~P3^-7I=$CevJj;Qyqysq^SIbv%pB8mxN z1+s>91XBlf=fYgCs5gFg!@AT^D%Z7L!qIQwa;xpnE4R0HZAYYC{GV&^ZW(yVO?kJR z%zRzqedAY~xV2^^X|uX|=azbX;m~7g5ezpd5;nx^59TX#V!NNaLB$)X5B)2D*}gHC zJbL_qqmMnfF>d(24;JV9FrFw93X<+WSP01dPx0kE{*^y9;L!G9uQYJlqC|{V z-t5zav|<9O#6jWp#DGH^sn9@w>M-vF)H_q@#y^kHX$Cr^{`ek)s%-74LP>WAQQl4o z`w_AZ{@C2Ok5(B%^I#)gaJmixD9QWvIM$XZcGsVXJr3uG?pMQSD|g%z_Tz?`u~c7u zr|em#eazl$!vC?9AyJz9BmykI5a6=*mpUC;JyI&b>DT^%f*Znpl{>Uy++fo`hH^Ue zRaFV>c!RwR;ElkWC~>~sWU$XeTI^&tBX`j%$W;w=@PNomf6|=a47Vs4`nlGTE%D${ zCkM@-n?5bmv(;ehO`N66>Fd}Z+MCjZLtwpYE$h_ZNP`^LC~8?|^q z<=)C@{>-bS4t}j{`E7W^7{r=jS|vNK4z(`uFAaZP&)3GzYJNpqwMYy9EdLXz4;45@ zRZv|UUi_F>MZor!N7r2K2rtfe#8XvO-;qM2;&7r>hpMc(rput3H>HRj?-(@{4*C;e z99VHx(JJ)Y0sm9!ID`2UR8*TX>EMS-b{3Ulq&E7e4*CPXti0M>Ll)9rMb}Gl{f{Zh zr^)`@B7(C;3KSN`*h_z!vJs)RfxBMwr=+U*+=E{zixt!aBefV+?fBC#D}Sm2+AmW2 zYRHN_8{7YJ9Qlgciuu}NS+!6Z(CccdG^i>of8#U>IsIp3ADK$}-L)k>VE>7r?mhK8 zR7NVzaCp9?PL)@GJmj&hncV%#cdg<=R>0kjuFvX$zt1XKU4>b`$GY;kbGXH(I_tZ= z^#zmXu&))o_E7WdTI5bG0-me|G+57sK#%of`(l-fuw_piLVlpjb>OatHlMKO_f9MW-i zUwFRy?t|q@Hp4aJ7iyf5s`0PLOK=%0%_8{!< zc^6JapE(aJYz;$mI9~XA6zb1otLJ@J#{`n;x(uvC1{Z+2 zr9oDv^)y2i)!^|}e=;=aQ7+!iCOcAqW>>t@cbePQd*5z4xJ}ty6IZpEOqt`?qmc50 zp~ZDxHP!69(z0_%h!6jFX!{Owpqz6wGXMYK#dU5q)zENdd6EK(-Pjt(41z-`9Jw19 zSCRQZuTLF}I@)=rK3{(1t_$X?e|!o*%*# zwXz!fbTy@I;NxW)uT=G40W)y`dg%^1IECwEZgJ;uw!*gIRGqY)XhD}K>T`xXqNOW* zD`e_6S%-Y_AOIylDcl6B8&kO(37pxoyo1) z*7Dq0+(uwr6Eb?-Q#?3Mo2HCe^Bn#fTL+rgcQvnCpZAAT1@d3HW$#?oCmHiEyAzk> z7IyUzoGZD91d{u1=6W7q(pP&#tXU!8Ds+Vmo^al1lnTnhW51uef!yMna*wKJw& z#@|8w9>ufyS2(NiWAIDD?}Jo|Qs6I*U-<5DIA1|gO~@C<8FwF^Kg086{AJe7m^KG_ zUc|En&oANcYW!`*-#z$i$G6#N^GCEpwTHtqP;V)IlU)=L()JBP`7O&5;atk*1I5-! zv+~$bk+S@&MUe$y3ZCj@0=`=-B+kr<;OJkMs*l!0KDKN-rH7=3!FEq1ObROGyVc3) zMOtTbSEe#Mv%V_~_Tw3+Gm%!zl~IH zdndeL72Hcp#$$9x65kHnrIfuyZQrukJ~xKF-(HevFG-5ZQ6Z{R+Dn2_Dc#qfuFyG3 z-U-cp*#4Lx7tf~k<@WQIfpFXUebdEe#6sY!^;6e`{mb1Z+WeXW?{>_ zbHLbT@wMY}50)w6df0O78p(fWPi>F!Jr(B=f7D!~Bp=HCb9jE&z6jE^;RDL{<29#r zTy3I`?8-C!7p{%omA%;%b~OOzSbV1pUqDL=H2J^%p9(BeM1~}?kCSc{GxcBaK-T!} zZ-<4A+?z=acS{!d*ywosFQi}v%<~|R2z)%xoQ5bw*wal(;Zn0bfp^?~JZ`phPC40X z?eoZ{=6HJ;p-gv0XJW@iXNtgM76*;feKsaMXF8EA*rb^KY6)f+6`9LOb@sQ7LT0m? zG8*U2nNEZpwn1WPp1WL0vW?!TuMU}|RIMzb+BV?Gpt^q|0kU><-|}A`0`A~Cs+LPb z8yHo~tbx{;?!ST5+3~?G|BpkUb)JmbAW^lHko5B;{oPysA4qytt=4GKwwxV8yPLcY zX>4u{-|PYc-AF&A3R~aMd`4xq-?oFRi8o9za;4!Zut+Bbc~g8hPJ+!H2RDa#N5g?q^rDVa->bu zz9HNGp-RpyksIeos>+l`ucUhKP{T$g)~2yqvb2VOcuWH8RbU;=)~X)Y8s|xTWlB`P z)Hq!jOHwZ{vS%f)-~@w7S)R^%b1`=()?9^1H{)g{SEn?aNuOC&RoeQ490CTU9{T>) z$?tAmI&+J|JaWz0OSPP@`euW7IZ`g$|)faE0GH)5R*v_h}mgO#kj^uuNI%)S6RuT>QhOoav)8 zNHEE26Z2nTQa50XU45a8}VLR+A}h|+TLCR$q;%RY_ERQ4*?t_|g=_IxPr zWGBga#pOfW2pLMPT#9>aV^WNsF)7B~V^fUnvJ|7dUT#dl-$8YXQ4^QK>y&q%fnf^?ATsP@j{7-D01@p-P7*+*aO8~y5V>=^z^U-Y-6Nm+ z!yDTt3>G%Xja|#wf(SB*bMO3a<^Zs{`^@+%Dy{wqh>U{uC+dmH&5h^Fj!C0`mX%zTLp*_;2JO zgZM&-$1&U!1oUt<--MHpSN?|gGnLo+2C}%mJcV>lp>cgd9)gMqxYg?y2%-}9M3-~_ zL%BVXa-WWr+xj!g%^RO$T#Fy(*)?Z)3`ks&j0mv&h-C8fD_?bUnjExVGJeRPcd%bC zZs#~33z`hv#`SPJ$TkJ1cyO&bL#1Q%lI(5$NO&$a@Xx@Is`!?15a$GZ~wOu%g(t-3}A{$A^ z?Bm08VhKNXqLVmFunR&{PLNv`K(IFj#qK?>xX1{q7OeE2$)pPQ5|R{Q%zx_Vv!flv zazTB+LCnR21c$0A-Nk;RkJL%T&&0FKXS@&ofiEQL&h)eUU?7A|Lay%(#gpBU$jqTm zF}DO~sq3kX2NZica=b}<_7Wwz{@KyHR`Fk5HVB(P7I0{u8Bc(4I;V=>@` zo~XY@xj4|ScwHo`(?GL|Ii5Ng$fUae;Oxzw74Xw;Sm}*{(KyW>L-pEiKAWb$T@ftZ z0vIEZw@cfzSL-m1P}6Ha^eyK0#;*L`0K0YjpW}kFw?<{$Ee%c-L!pfe%^zs_&;It9 zz){&iwt?!3&H3)Z z8fC$2h&@1c<=)3$W%t#tCuU!X7wE<+Dv(H-O2Wn|zB;ji*#db^j|B!C3?^di6XYAAAzciKjA0%Vm4nzxX@?HljU_(K~iqNaa}g z2HaggY5+(EEaLlx@4$7vw0jTyzi09G;A{%{4nwl!;qtK-qJ7Id^evwb{7H<)AK*^) zzHfm!Fa-b-ap;Ax7cIqJv`&$^f$sSaDEDaDV%ox+i_{++TKbI7nMq~J`<(&-A_VqEI}2q&`g;eO|zl56})C~B4a>t9C9*pn0;OjrBOYv;~(AV%s_uz-hrZ>h8$lBcy zWcpNzKhiK9bdN7>aG8!2KG;LVVYh} zc8{ML>+!~mH?-cx>b(U?ol`ZDBYuQ0OMB2xJO~AJ02cdd2Sv_v5jIZI%Pd^lsoYrS=|`Yt3~KlXN;!( z&2s=T{VyQvH0`@Kam;=Yf#5q2z$RbbA-6t<&8{DDSH|%BKB{5&nM%Lykk&~YU&-sf z!tSz~Y}0Hu39+THr^kZ_v%f9!h$<`8>2MFb$(tZh?Lv4e}_sYDTo6cdquFo^7-y#IE=09AdYVnA!ia~2+g{9RQj8HJMMm2<;fgZXH{@jR zl;9JFBVZ=$wGsA$X=XDTA#agDO*jn=b`cVUi{B92`tmnWvhX%nWWSEr!t)M4Eq-eJ zDnKVZ$ANan?>U9gzxkNAkbOc9~>pjaU zJM(JB44SEjI1AZbYra7VIMt2HPCV(%Uy~bd`blEkCfjvt*Tnu6^XX^tQlK#7>fI7`1 zYTA?-Q0v_~Jd6#fQ}6H9XbMH;kE*iAw~A`%&2~m zr5fWdPm4wH#OJVJX@9b|4 zFu~{DHzI?@snh<>24Ag*UH%9-QwKS9Ds1&fC1k>WKPrJtAAdC=ht{D~<#_mrmZngm z(Le}5!b=!}V@M1>vP<1si@gKqTRae<>M5-~1L#LQBm3>jmb-6Pu6|tvPwfTD)w&3f z74i%i7Wyc!^wpZDiSz8$)njqMF@K_J77>c5XFJ7iYTHP|;1&+fmJZ7M*-vc2hF!$s za0T&S_S1shTnF9q^NAHP&Lc4^Hh8PW5J|P>5$YyDX<|LPcDYlrb?NWo%G)vzNLph$ zW!|sl&Qe17MRpNyRvct!E8*4!F}QKr_IKlm_YOhbm2dDb9b)H}7%9~Y+dNkWw4xMOw;XXpQf@nefxjaxUt$8(5bXFbY9AftG?v;c@g(rR* zCs0&i+Br@G(%3z!af89Dga;kXHITqjBblE;%CBG_Ku=1TZ%N<1;x-uKQ3?bo~Y za-@58ViJUt&kbfV8A(`i9q_MW#dV_XJLBN>j{!39{n5M%L%zle3h~oj&1BDoXY7o2 zmHG$DodJUi!d$ZQiW#fN**`h4_Dl08U#Xv?%s$F&UJbzbYRO!3nV|eBkln(VR3V5 zzdJ#sPmyJ@O#%OJ7ztwc;|HK{6)ZF5K}BI#q0etKUd{Y|W=C-J+Im0~=O zU;p!RV=I1CT8eSuw5ao{`xYUr z3Grx-B*k4zx<9kEuu)18)0`jRpER&oPt13y(BkACxDV!?4jUH3J%!5qE?h(?hP+eZ zqHHj(c?0;6o#G+=guEi180?643imLpPvE%1-n2wh>>-iNi6`h`A{t?n5MaHO5Nwgb za{Uy}ZuQ2H4NHhWxZxdX?#8a>?aQ+D!BG^1E_@suG`|OtHs74Z_ZbZl!5@FYA|AG8 zh?)Vs07u^MkAtQ1hy%C+3F3nG%)(!_{1Vo#GObyy)uydH2P>TBESFbKHFI&CH5w|t z7{toTXzI8hN?w)IrmQn+ufv<;u!sq)RJgi$t4i zdwt8W>KNdt={Lu%lJ38S&1uA1-gWY3r8SsF)&KQ)`FSWVseo^{8=il1DzK37x4iLB z^^u#EmO4qGr`UD+x8zgLZ%p0CTM;8t;mu0GjuPm3%$o)$ui;k&MXxEEk+Tw1exN78 z)kn&-d=U=Blm#qPqDH!178G$=95{23SNwN;iS$x6sd%ev1n zeXGIJZm9PBmrg-89v#O`~XIgLVgeUxxF!3c^6yY&}P? z3+u*}FT5l7ntb8j;t7LmC&K;?zjw0*IhN_T2VyTdZus0-5rGDx!;RLF7a~hlk|xMn zbWJ`E*_KalBFq(Um+Wg^NVtIUd4xj0o-?s2InnjtP4@W)H@F0M(mgZlWDOok@j2+) zT^Yv_BbYSjhLjCU7H7E(^ypg1=u{O8 z_?y@dbEo+9Vs(HiG;^sbu*KcJTG{OBYWDbGPC+W!y1c3AVZ`dTOQI%Tclj9Mcp?nu z6uEor3in(RM>R5ZZVm^jT)2ufBbmhp4>4T~$E6Rie=?r``V9ucpnx5TqTqhH>ml-L zSB%4@^2d(BY!!>AuHjW>!#1r4ObX1HOYoiNx?&81dJ1Ehk`Fq5e(GV?J7KU7<0!co zya#@y{?Cp@=GR*{Ap#hGeebVE-pC9mVn8I=i>MECsU-Z}TPrap)nPtxkIU|3g_1xj zxxap@!cK1hecfoqoqbbl#?clFRb6~+1rx}m?KF{`K8vHWrQ?_<1`*;tD~OLR%xe{J zfoJL_hpH)XpnFBF%JQ7CQ_AY^>4$wxKvlZ!@uf9!93y>g6iFEpB6p#s?yxTZnw&m zTi6U9bU&dvFiLzl_0P$Rhimvl*HTYh%g5oSB8^)$Ed`kIcQvfZw+w>IHmDw~+Fn(a z-_`J8s=-d=&yk^va6}mam6dEsxDA5eq@wPO>894vxws9c_E^A&OL&M}xK&Kda}1ZQ z;6_FM)r%c7H$(vj0?BM66qKEhA`FD%>+l@nlB}FfuH~A|HpXm=F(U%DS*cCyGW&Ky zRVf4pj`WU8h0w@|vYta1DoJ@6r)0VLrBUq=*%L52b@d@+!%+^?R^;lHvn-neL}z9E z2c7tDs9da#$tQW)?8y@}ruA7d&JEj-M8ASruoJd2E0*=@REBuP z>xY~VE1#9RtK-x=iz2nQO2Kq^v$ESS5invPy&_XFoSKdVl=V&^v827_(G%&NAWGTj zEuV^Rv$KTCDo%PW8`vUmxzXD;*IsVrEJWKLX~--Y?=6oRT(2}+hyl)q`#4}f@9<=v z0J|s5n-vaCkSk*BQO zZhK%U7y33(GrVhIgaf*}xEhViN0u-5YC9swG~guGUdenfuHq2qFTk7qQxOvE)nh`w zolw#;T)8?5W=?Gd=6BhZ+Vrk2V0-zjsE>M?9pcsA7;pN$8=s2w(wm-VPtWxnTF@9t zfho?$msY=KFDKGp!Da@aaa?wYpLUk!7g|<5$A{XFl;YH-oQ>jaBG!V% zs_V06ZzlLcBWH^V2?6V45TGHBher5f=Uc=GmnYxFF3Op7vg9bc(sQz5x3c*|Ev~%` z+(UVBd5=G4pgJD8UQuwP$Z5oo->x%(nC3n2Wn5JFZNlVFjpasj^}3h;W-nF!y>Q?` zu99@{&bS~!`u7RZ0((8S6YMbD-VDUF_wr-B^0Low^6FFrx_E8@%PkngEf~u!xQkmr zROgYJiR*q|U_mUBI$|)MY$E0W*9pigGPGp_9IPu1Tt)Qe0pze(h+%rgRY-v)cI#LH zQS82*bAT%qqon=t_~#yQRuDi@H%=8s-_6yexbn%(avZY>1`!)z*!z|YlI6W^r?j$`jJ@$3) zmUU=F(tQ~>YX)_4RAc($>$U4UL>vKzfMKirS}*0T$)ORHyxuZ06i$B(@jaiUcyo%K z*`%Sh>Dn9x$HO<02cSKQJcyCJgxmwo3r2B=%Tww#$rZ^&%(&Lfs(NZD>QTnyQeS6S zcW|6_m*H2$-{3<(>+ndlA8Of^I3fc9isN}4iwfjRYtze#uwR(Ku4I2rzHqrhD?|oc z^RoUQKdDBe9cX$k4@Ekpx|hBN!NqH(S+-N^k@yea_EccJ)g=;mW2DE3*C{^Q)CyY( zc8xb{;%YyT*yDfmnNG#%D8BA-RyQwyB1?zA=fNZ4ZBGN~DVvi)qjAM(PcOl%5azyp z+}gzi3=;C*wd=ON9R|f7Rnv7x%-RP7EPqdJcI)b|ECtR7H9IZD8m@$m;)! z-x%<`EPgM*w{IvM7SH=sZaiKCJathf!`JL4GB&9Yrhy1zU$uwyZSN?1Uwb2OXCE62 z(;Q2<@G$@p6p8XOzOH%T8BlQWy+w#66(O1!+*iTBjT7FWun^uS;FD8jt)6(jstKHg zSH88mIRQ?%J-HOSs9n;qT-m%_yL9OlNZFDmg_3fb_jkFo!G02v6%4!m61U1)Rp;}- zcpqOKS+ja{RLw(i!?ml0)*uM0Nr`vRn`YK5IS@PiExl0<)SUQ8bz|QOrkw;>dRF1) z)SIn=P=yC4m0Lfnbrvq91`?Rim?yNkA`r?Q`QnBgeE5?<_M#&|5;jshLfz}93xA;{m<*$m(2BNgI6Iw9?CjbXQxs&5QuBxT!W zRK~a*+jDTkrF>hvY|~H7*%pU8Y1`gQw5{wTfvD2cfiaB`;^3~P8PVbm6s;L2gJJ2+ zQK=$PY#CxjUQN#~e~QM~bDv+sIlU9Y5zv@Kt9dtYnh^ts2}KDWp4|J>DN6CXYRI~R z4VmI7zh@Rd0lYKua>U!@iz|E-|9TZEu7kI{)`b`vo(D9o?Ssfp;@@`*K}m?LpkR}Z z2y@!W{>;X2o&x4SEeDiI2W@KTBQHgGnIz`huDOWNbmm;lX#~+-=lXPS96>^> z97YZJnTKi#KdCE;hi%|68SmcpQ0JTFJ4VL&Hz@n!AQEt?1 zlp7n?%Z(M+E-*5_sqlBD{rI zl}(HQ-EskM_l~@s!`uBMZ{Oo>ginFVl(#N*%PR>eFUwjE-8Emu%BPS?<#)R@wxJPtzlp^e$W75H0|!oaY!vfgQHh3{}p1LbMm)Cr`yo* zUCV=unmt-YM*Gwf&!^3UK8uIZ5DZ_~{?vmS)?f6LTL|+8Tc%X4EIYf*JKo zWUal#yUoFjdalyt{;5f-avl8&4(wiB=ey%iVSfu*4o}LP#46WelKw}MzB=sZ{p4Wh zoO{34^?Vppxn??Pls8f5aYTgcm%-a&bI$617IKPZJOjZc$Y8t-4hEScXvQVT`83g} zG-=iyrZs^9rxX2Eq9P@D4kuEJAt6?GDx96q(u+>A>fDU=ZbzG?W zuFKU*4kr-JnFF4Dhk?HG5jE+k5Hi8Zf1Ua2^Aj;7**1pz!V8 z_!PxMP8?oEGiKT;sSDLrEJ(+8^xpI#+Y>RWpm+tyY?BIu8%`dx~_cwz}+Wr^v zJh)%k^;uWL{>xo^yBgMB#%ga#JGQMI4p{8?*HbUgFZRwPl9@=qg7Go_lw-aR1KZy> zwRdmhx&lgVc9(zdZ6DWMl!%N$UPv0r-rlX-@U!+Ac=JQ;+8YC7CyvvH67|8vO!N%> zCOwAeCPBiLjY8b`Qb>r>HZBab>H!uA^&fNol{(;mzx-sEAS;YvP#_FzGME7 ze*q!nu)#@GuFWL9oTS@^{ADD)s+KsXR0qP47P1oni{K5zZW8+Jl6(b&7b2S~2&oi7 zRSbVYz{3hpy;^af<8ys|$}dh?qpbE{5w(_1NnDh9K(sHwTa!U6o)n}tXkvM?(k-GI zRx~#(_qn&G;a`yL$j!<-<%x^5Y_gY5irv_}W<3l@ceRdPx@P^ZRyiw!Z5IXuf?~KK zKN$m4A7FTMYaH7u_{O_OIT5?YU+$%o0&)dw^)*X;-4b6wQZwQIF!nA0QI+Zc_?a_T zhNCfvBLddUfH0sIGn%4lG9wad7nu~1Y*!{jEB$_9a+6xxq<=!j)`voL(_mkbG>QU zxRO&V)sd|muJSP$3H2X=Dd110^$$J5n<+b&hy$EIr2a2T5cmYK7*TU*LGa?M$j}Q5 zEfPg>y|B=PDT)>6g~U>a(v9_(^5l1<)e=4^A9AJn0>csWrm7VNt5J&iGq*Es?T`Y^eI?Y*PkF>xaIL z=|{s^BLH2@x9$OcFY@(SF{XV0rg5)1naoq~bWY z=;krvePr(Qm#3ci?#k2=Q4I4e=-e65EF~V=--7U^p!ojE)bUkUr_wnk0pVsm zb$GVnX~e@pUeGY);?x8@6?oD?3;+3^AbbaUXvcf`i-K?p?-_WXJC|X8#Cs;*bMRcl zdoF&v@tcQV2G0UKf50;ud1ql?dpF+i#N)-|!Ltg_YCMzhoIo7mSL}uS4EK=LmNZ(9 zBcIil*avahza43B;GRlT*6$Ut_5(H6tvB&4M-e4UlbR7>^_?J!_#SoUM2-8cAjYjx z@|E%-{Qn*S)oK*T-cbB?{|*|jh*G(oVpoS@DyF6xC}CKrpR7>|W~`3iD$u6xkCeKW zHg!?g$xefYX>Bnyv?Nt-6!?vOvv9AQB<8{e>Ahv=5q$SCsr@N{(6GFGvLP z|5$P(+&U6B@b{s)s}FKZvDpl?82BTPp$Z+chL*%MWx!V|gFh3rkV!LBFQ1Y1h{`;@0u7GFA6=ardY zxPW;HG}l<_(OG4N(y<0WvRxu_gLc;7xKuV0u^qAm>~FJ|N@3PO5b@c0)HNPu5V1<` zPZDY^$ux)N%N^@q4g&s2DG6{q2zWpOgt{VozF^4>#@Ub%j5AjPaKW>k#Ua>n)S-Mr z$t)?0X+YdV5hn(98z4wJOR&u#khEZiBHJ>553@`YZ1&%SZBu^_vrHCjlYS4jP3VO! zxL+#EHntbmQ~DRAPbk%h3pT)(GC;h<0br&9U^fo{ix~i>9{?6P0BmP({d(#gHbA_( z>(HLq(4deYa@{9XX*$iu&Uo7JozdFj}v>BWatIo)zJK zle+Q-Q<|cs%TfuG{ZiT^3CE?+Ql4({9N?}E>Xh66VP=?^Aq(r) zOgt~*slc-kj}y-#JOy~RgU8c|=UqJS;c3Rxil+_FF+88+QGm~*!lS{X#lzw01pEk| zf8rT0lVy+l1bD@Hl~XT)k-PEs{0Q){@6iGxe&d5vy`g>bV^?;ZGdmiM456?n@ssu_ z)jGC4rp?cCDGlpS1~P^_Gln@cq8sLf1!fF)&KTyL(Km%Nk_jk=`wE(!ZQTu#vbut4 z3w`J79)%^EW?zACVS&%NC@%1UStZ6R zbNwXeoWA$J&XJ7spJ2$RAg!2FAn~@%!5t%X&=M`My}dcOLcsFD&|e>UHq@>LZF1^v zUH;{Z?x-whKeZsI*6bhlt2NO7C6t4IGPiM8ZCH`t>3N`>&{qa|!)`pPM zGM#@g5)9d-2{HmPrTh4|Z#Z3& zH&!&isjI7L#sRj~IHZ2i)w-IB=0?N9#|&V+p?jSDP8~~>fy6Y*ANq4GsZPc4I|^zx z=I09wYa*PHYN&%b`>}zXks1-!mks2M4Da>D;*8`rC)CP*@0?xQu@c%7?c$h0apX3p zy26>Qa%P7)ZBeLPv)I`I-*#U?MPMX@8n>pT!`8GrTjP}OxjDic+2&WVEiZN!bAhDA zt@%;nwN2*`)<0J8eNh)+mAE~xsL|D1gt{67D1NJvat}P%m)2Bsft1Ba*s}J*$7Z2{ zE7;Z45Y9C3*45Q5@8lL8J~6KD7sE+g^x|j=o<&jbmg&ugGz2p zYs-|Pm0e&)L>9vhS%1-wIz~ zLjwMyOfIfX27h=Qr*3Wm`tlMx?P4;zoM{4mugk`-o%bmheZC%*N_D; zV(m9+tSpymQJh$(v$6^)BB!Mhw#UE?DV+2Sq@7aR4VEfeGg|vCQkIvyTX=Fb*&p2U zuWQyg22$GAt$$6ugO(WUf__y!at*LR|EvxV0BaurR!r5nA?@Ss;m>8%*V9_GV#oF&!Y-Pj6a4m&DI8e9}PFsp{dqZ#nz&~Upo%a{a zlX}=vPEB$3G+81aE?r#L;&7`@S4dpiIK&8z2dgn6bzMdCB%N<;Gh(3&FxbOa(Ab@I zNi^9ejh%zlB5> zS6FZ|Fno|7CzA|m9r$_(G~e;jxJmg0a6D#33({@{H!OFSO2pvQMb_4 zywKz`;D5vUmXe=M^TYbIr&?*^QcN>Qp2_q%)Ko?5HBQrQk31P_fzxDxctvt~=-a61 zPKkeH4M&Gorz9<^lERGL*Hhwqpgr-QyqpqGe!S|=yWSF@$buNIehk!LVC{blEZkO~ z_E4R8G5`C-vf;S3Z;(Y7{@GCf<@H@}Q;dES&?So%W5iI5PX~@MLW~hdF%AzDqv+7} zryg&R-Hgl|`VB;vY)oNc22$5=aY{9;Zyhj$V`m%Gql^A|_Nm8zmq$a`aM$pebt{^Q z8a+_icyaAZ)CiHwvov^8Cma=?uMj)9v?8PMNt!eL(P&&hAo_g+LXE*rsW|W2`q#oI zf8Qy_mj+Dt;(*Xq145r05Xuh-EdkW2qs3DiQ$3?+g%~jOcLAo92&_ujHiJ!Rl8yES zX!$iRyPh&Of6QUC3i12XB2j|rXIg(qszd+QrBWzKYI1El21Mb z7}JQt=aS>oaV zcv-~@Y%?abv)O36j{Q-GA|;U8tPAWRLe>8qL%ABhu_>MDCIhBF!cF~7 zl_t5-V8|#n>C){6Cz9AF&AjGiCIh;Ohs_Qc|DI4(s5$YwA{3bERV2UAJ z8!!gMDv?J7#ke?74C8OtQWEWQ+L81x-WYb)ra3z^)5MO>F1VDJ^ZU}Nk=u$=orPi} zm#Sybw(*9BQk?UJrijCZ8HOa9JpIFs$5Fa#2<>rhm{p&O0XNyW!@moIh!RPaM3n0e z7(XL%GK@tyrjQ$gqwxTeB2l0pwWBU6Ja2kSFeK5e>tBsvVC{f`#&MTWM-T#^IBB1X z@Yh_c*(lWtyBE~F-x}&)7YywW{l|dNwF5$583-fCoF*FwCb z_rPg^sJk!*qg=eBcPB6~x+lWO4kKT3ZB-dnRAgO*Mi0MYK5hsw+hrwR`iLRQ|AA!C4{zb4?-@WL6?;`Mlt0vsB%Lu-k;M*_y zcM%*{O}I{nP(KQFh@*#}aRzXZjVzfdiZQ_U0w~4E5Ty_&V^Ge>_o67v#806F_3UM& zamPwmEDV^grK@Q0yTug}au$-kf4ZcvsFc#(CZ@ah%KzVVnwO?eohivSZMP3KPWi~g za`uhUxBIUM{Pd4d2V@Qzr9@MBqBU~#{KQBl6mOW(k9fr~FyhSUC(Eu0mZO)f!SAui zZ!-7_<6Gdz#GcJ@iWx=rY(jr%yx1e<6I+fiZwvJH0ilN2aAec2JoIwR$-VM?!dc;V(!=r%aA85}H8 z;-(GCfOsxl_;B-zjp2oJn=9rvJH#OICZ5|k<%~lIt>94ANbHe(Oh8Y(CEAg#s+Box zQI7SK9R05Pa}`ceNWdAgM(7xsj-x3GMADqR(T+Xl`8~J!4jtK+%%)qnu0$D^SSzQj z#k=@Er5+7)jEsMz2+d^ zI~AT5?zz%GJ+m-RSGY#!fA+)D0-XrvDfK_CG?=-+vD_4U^{2Uon4>kE!2&&iK;r6Bz$*0NC>b zz$Q?WZm8GT0bsBF=wM;WHYwGlE86g5zU;#lY(%lD<()29lCu7tF8@1SIPaGJNmuFr z@m2LrRjQVTE*MGN+U2kBf)FT-Cn|Mb(3!Wo$RPFRE`Ke7Asjw?p26r0^;JLgm|I>C zKt2KM6?P^1#ultq!H*%;q+|nk3uG_+LE0a|^K$S0NNI|XD>~L$DDIE4;%A!d5B2Pi zY@c+3w`zK*N9W5#@-!rGs3JM+U`8RO9fA{yI#03&Hj-{tO*M7K=$pFuqL`EiPIaSko&8cM@jgdP2Sw)>QR; zd;!%*QTAyD=vg}HhOHp7Ibe+(HxWcy`p;6@ktGi#klJsSJZoHWE0Hlp z*#w}`J&esy>RRZjb4N25PYw0(uKgDa7oLBlQva-Odm>ww%Ct>mf?}afT9O%7da{bu zJN+QN%d}PUMt^O1)kF*sub$-lvSp){d$$QCG;&pc-7wqu5LpZq^UJ zx@&Od?v7d&LX*k4$m&V48Bj;axp=niAcV||<<%q-y-e$37u~fZqSL>&Nl`3ssTYbD zBNH`*KM|0=qS@7_N-zm239B|Kj2k+Fm&e9{sKj7~DLUl$v=%b-ei(pJVDK%2!eB53 zq(YMzmtOASSH8NyQ@PzdChjwrUa_KFiR2H@xXxF06l=u8x#^@z+o=j~RdEe^MLK)5^@@z zEU|yuf2@+N-rOXsQuw4(^(d-SB#nVuXf#M~xvrdduBSn#DK$wQ!mTbxpJ6 z(@FAwvhY!f9*hWBb~2z0GngBZrs$Bt5=7JB+QH_p0c#6~HwxItFlUv?f^WI8 z>l);AXe0$lV{v<{f3BIWKLYEV{v!fqqiurE)>>jln&QV1fDPfuc(R?#LmNm^*))xU z_Cq>u^(xM^GG>fOn~lfXae+>bd`)H*l|ggV_(?lC9wl&?$($C<5;(Vg7|f6KM8y1B z4K;Lzwd`vzSaqvMjs#1h`4#7@qp{%y3V}Q)tQ{qgM;z!MLM;VA1i|ho3TpMpq1|#U ztX63^lR$U-xenGN=Tabwn6{+;l?UniPHM}o=pQqlBs|G@#^Cu0{e?OeZEiQveUXyd zNg{VtFXMS3>1A?6?=wUdM6zx7qA){BgsJtK(|2jHn=PA(E%Z3ox%hu3f@R%vot+4ANUvVhik_8?jfm5v}RIch6YH=)y(s-tRU*W$#*vlvzqp4d>`RMt zztsrigsWb_vI0l)E60YzU`gwIQ|El*arYQ(D?22TKP$$zXi=IuQF?Xim$ctQ|CCDj zrJ*9)SRfqKlR>({Vx!_lwO{dH5a6Ax71}UssFqEv(FJR+1N8OtzaSpa4Nt*NVtDBT4e-sQNbLmZPdXJ*|nW+rPOR+iWp!KEbb zA7`{<>>Y1xlc6wJA})iFIa^E1gWEg_t-}z3kO8KNNd1HKKucEqq`Hm!uX&H^&HLfs z`sGb#wf|e*w-}`S<7l2)A;TO`8jPrUO@u{%s9;wnH=G~)i#MwXJsYCo!ETMad**Mk4v!-O>!y3Jgxsh`rb3F>K* zZ89u#TGUO2M~O#+CkzjVXAqvjcoOi8z!Qb%W;}^_KKT+dipyftNB>W3`W8In{x>## zDV{BO#uY-Bs3c0`bx-6Vc=zgMnScObp!3^;puzEj}RmdPs!&I-vPoM=d*q3DHY4O$>}dZ5JkaRyNF2-2%PnZGwu1CI2=o8n(qSd_&OpTs`@o1H4X9 zU8diyf(kBV82&9mbwS{3g|gr1uj(AZwg@V+-NC;psD8n(r3UWdu=nOS3o7y@!&eKc zQ}nw@P<=Y;#$ zpD?xHkN6N@wuley*sCSb)+|We6aCzW64kRj^mEp_(+T9hlshPC@x`&5*FmYDbK7TX zpu=yU8D^hJN&-DK2CJjneA538DUm}%dYzpOS1*FnL0Fur0A}4rGoE!O6^v%|O=L_t zm<0ol+JGk9o}fdms@FAW!&d(}F*X+H#6JoR%M$%&967r=>h#*Ub3lx3myo}Uq`aK{ zt}TL*>oGEZLvIDQ3{z;@=9!iD&}1*U19P3T8$z@Yp0(G()|7FRkZS6*9PC(aO@6#= zr@%$ccpPON0qwsw74sG{Rp@I=_W{DACjW|1tFk8yL!Iw|-f6UhRU{6L{aO2kHdo#O zf!uE)%^;rNUVk)mK9fE8XQ#5feLJ_!r1Wrm4Rc;n&A~BC2IkqOca(7>%VtB* zX79E9Zv~iH;D)zGs@;*A9plMLGfpMA4daGx8V_FFZ1P67JmQY>nK!=K z=|eu+?MvATs1*z^5{|B%KnW{e5#xqkaqjIZTK)s%Vir$$+2#Mu85y>C!t=2OrDbmT zdcg53)^ldAu9P>f+&~@~^V<&Os_Jdsj*)}?HuA&aW;uNxqh7*h9u=~WpLQwB)ZY&t zhEH(VeXN&Nt|%`ac1q19x$){*hIS8oETu#CSb(Um)@6>yVy@3qile>)CX zE1DVhy*v{gy+p<3xf1P?Gt`nh+`it$ibk^<`roxI1h1APwhkRvKUu)p!#Mlw=E&o_ zunUe$pfeEnH>?ly-T)jCok;+W?uKoNLhR$8z%v`~a(Pm;TyBnb;Qd}a_nrRW-tk|7 zS0Mmlu%@e5sO&=+{d#5YkgWK-ZoeOV!53_42cXB9!1#AQU{6TJ)F@Hd`>m8&LuT}< z6pcC{9?BOW9uPGogeK$~o?-8i;2^MQych8HsJ3nfW;bj{g%c*-OndgE)6OVn;lgpn z8;%dlUbnw>{dc*_`VXP{=>L#(jNzuKED_B6`7&;4t*n==pS{1wQ&Rn$!@J($Z>532 zJ@1HufrHsO3WrVYv=OI!WI*7Jr+dxuWe1c?o(CdlhHX1B|DoNn5NgkD<*R{Z~9e)xuPUozC6tP-+v0Y8-Ml z=V)r%ekOZ!yGxm%Pg3w-?)OlDVj8$G6^%Eo{?uiLtce)#k9L5I9^UU! zi;Co&rdVA(!96_zl}Etn5=hp|+)+%aXE`bS7cTckkyAr&zK;Lpk7#q;rP37-J+_a3 zMp)$zkoDv9^$~}6?LwM-jz2{)9;<)qO{dt2Px+;qdyTq^R}{xKcxTcjrT)P|>SaBO z%T@1S`NY3jo4KV;G8EI9AHjb|`5;xNF+%_7*{ZOd%hylJ)T7tD`u8!zmZf+{Mr7hF z!rgsv^YismiXYDMpY^6Wbylza1*vvkfBscaK6gv^TC&(!kgQ2srabxKQT?r_CoD@0 z$h5ewZIy*J?=pC0;SAK5HsggWT_eL1?7v%p=~mT7;jaJBnA0d`*=vGV$>`T`+;A>D zF_CS%jS0xqFTi{KKYiuTaPQV?R!o+?5ni!2LO);Yl4(je$y_om18JY93;`METYj)d*s|$0bmbfIzxYwzj#7RJ1#r*1q9|J76AGtojLUW_ zI(MQ}yrMp}Iq097CAZ8^Y&0L}Gw*IAb0XYf2t6;*90w9)cZYWK{8bHnfmyjmb~dyX}Z9WpUZ&8toV-2yq|Gvl;th%t<6%3B`u|85sAlG z)jf<}F01<3y^$_ty&GYMkX2lG*0vS8m;Zs=ZXYM4nYNvK|dNX*OS#&=JdOllD9KqiS|&canC{b!280yfT+NejX5 zLwqt6GrCE2TP0fn02Zlr9g8zB=HOIsd73CJw=Ru3rVu-1(dK zb^1m%ziYs~yFV!p!qmiNjOLQvB1S?;;umzUGD2ZFb?W*3boLQ@Lr7YdfpgfW(A zQYJbF(@3*QNW%bTydwH~;;Pt!$Z(wWq?$%B(DenOG?Y9f(iZi9EGQhHQwB9koqsa0*X zIdx(Ll+zPGQBa#0EnH7=pGo#%pMHZMAc4A(n{`-ceo6m zJ<4Wxx6SH?I>NpxjbC%9YA2Q*Tr~}4J!c=(AiV8FciX=ZK83=&5B7x1g5hOyp{%=` z_7u492d*qXUpLq*PGsm($CaWb4MRXl%-G*%Kk?!0-KG3&YE|4)%V)pU$`FPCg3ctU z<>d8A+YK4tDdRw1WKP>Zi~KNT2)b6?o0Rh zMAaAt?$=6r1@0BnvkZ0{Er@Uwj(^#EujgghqnPweg#-@uyImLM&<(X`--M{WFufx? z!ro8%*{)OC``!QBb+D317y7-a)b?yrZ|(uehNjQ8rKe|DMX~D;*z%8G?6#48;$;nS z*b?!re_4rkO3`dzwLuKws5Za*2gk@^t@?2dvIOx|ac!nY@dYv7TU+#=vrvk1X}dyY`OxLE`SlvGV_OUc~Zv4_BIoEC!u3egYUPxT@m07NqjF8&Ym%N zM&s;hz=N|V4xYC6+w}I>?BhSAy_2&C_QRUwun{I&dBGbuM!WeP{@8=41&p!Vhgt2U zrD5F|M1%3G`LOF|$_wLMrkQ#ex0^YlPt)OxfFg_6+}4dj#W&-Zy}%IC%!>Nht2k)J zl0&oAyUg#H*jTkwQ8ovCYk8&3Os0XBykj!y0;*WVFpUg%u+e0N^ma!79FsUwnfNf9 zIfHSs!yhYv=?Vx(K&~PG11hM$pFI~Fo!=~EkN>40=^i@AXk6wyabbkk`3^6Ku_je5 zi*;+WQk8_eaW1d-e0hk@myy!>QaX%NrNT@m@hFP(wwsONX3)9>SG>BSjRH)TpmcX1 z$pzfcy5qrQ7t7>=Wm1VPZ@{GXEn>MjPhFyk#^lOHv6wq~wx@2jZ2fOnF-VN6UpBKj zS1yn`wB^1wI_GP$WxrVCr$QG19nIyXDS8+PC1SnfQ+vk{|6kUgEyUe^+^5a3GNuy|E=Kj)WO{l5F?2eh5Fw;l=Xip_^Rtj z)4cSX%GP3yZ0jpA1vQVerWsd_rPYd{^#G4Zbsp(J>9annZIHiBfS_6PJW@ z;oFy}7CewxEaSpEaO2FgG^+x`z*~r@Hxwmx6xNjT48iy>&lG)mhT5T#eR|8D|DOVO{Vmh8ysg3YBS)o86fVH6Hs(4bX8A!~6s|I-4RvI=ZqBt0wS z7Q(jee6BrDYsaKrZpWmJviF;`wl0#$cZ*yYcWBbu&h-LIg6QK9$J#w-2H1b2SAH=lIKy<|Wm-7@=JYDQh@L_$}8jY7-c_XdWtzM2Y=V`Y0l zNU!k)4w}=xZeVFR$NgrU`SWJe>d!frlbh~xAw8}1kCU7V=vSYyI+3xxc`A2X{_}ft zhN`WJ%U`L3SS>DRE=4q`!3%p(EaT4!` z7E3*0K-#uCLTIsU=>>*{D1T?0WeyF(TutiS2+O?rP)Wwu#2&$wG?k-=zbEpjfMDC*k!)PDHBz<`W|Jo{?)}%WDXxS+pD5h7 za|-JoQdn{OWD_Q`ZXZ+ntO2|p41FuhY=^_H6u1qGw6p5%87v(CSr(jf%gfZKl-m>7 z%mgND-SLI?y}8WltiG48lx*+Et#q?LnsK*?jmK(u7wo1P{bWrG!J z1_jRBrihDIy^1ys>U!q9l^xtQ?H4HGbltD9`ck`|V>2rl2dkVc-ww;wFCdl*EpJ=J zST^U}^)_4PVQe>Jz~o#|S-L;K2+;!XJ)>occJnqq=0A>=`2RXq5_^Y5?^rSR0z(?; zY1`nVnj88C+%eO-`DcfO2sf+9|LlVTGg-s#O4I1mxWwqenORIh8k;$mNz7t1r!!vB zxpj#1V0rWk-$=`yyAP8E3l63MWEj$ZYhcN8e$HAYjCcSI6=QWUCeZ3n=4X8X%NZ-K z!g5B9Ks~#(N$H<=g~)Ko;74kjIA{AwC|mN+O4~U9K zCuJK>UWS!;vRo3{#h5e9UY_&qpg5C$jzJ$EQ!s>8J;D^khgq!qIeXT+OpM*J5tiFv z^D}FmA;FNmZj2IRHgOu8`6tGbyg!aboXbK7`0uke@~=>h+GB7MU82f)r5oo{=Jeyh zzGBt}{;w2fRyQflR)5kT6f$?L`1B%2wnjnnP{{ zYn@JKx)8vskek)k>1y|MVt<98$h%I=+hk$)hbj#7v;{+-MhnM9>emfM3(M|63&Sl} z_LVebt!q;O9|dE>EM5CbTv_W>a%!CFPR4R>-_moGMMUztOe52wguAsstAc-!+M!<+ z4tuEHZp#n*%x|~5N=^nNhU#I8kI0EsmK@1lhtukeb#RK=nmCdzGc&g1`%2EGno_CV z5y|V-5A_K986!Uk-UB51|3YmT_E3azP%rE$v0d1caSt1xxT2CV_{&XS!m2h1MT!ra zRNO&2G?8sU2vfRp@=j4q%hD@lGTLrFhPY;VSto8AY?t?Rz^px)O3j@M(hOm2D_mj4 zkH%P09TITnVwk5ulOp6{>A|zn#w*}uf{{7N+Uhf5j?~IPgzHle)xBNHhY>#Px$t_(e^uga6$eozLgcP^hs? zSYPZ|Slxqv#|i6MRS9Eh*%N3PCtiCd(Sf zNL^zo6nFUpd1wX#p%#N}*1{zQrJ2FlW{l~AZPQ*1{qlw&RM0am5GN1lWAD1E=Gbb)8^z2 zHtE8fWPuiwso$}W%-Z);ur=uhnR*m#sbVIX(JPiuy&iZ4?w)CGiCQBWX7nUI(0GoS$l%kksXD&*ugbv#ZJkZ6L6yMO~go#6(QA# zMutlpTH+q*vFQUWi08oAfG&mzMV|5QJ$>)Meb@S)|3Jg|i$69-Z+V`#?*Yro{k_|) zMxVUC3S66!yRTG6e86|Mq8?<2hN!;#5pj$s;LM1$*lRg_m&JoY**L~_-*;F$m1@gv zdj?!PXHjp%1KYG=SmTga?>=iz&VSoy%_BX`e)}v84U3}}8p5!H#X{qlHXPAIpjKQ{ z-W}UuIU)p?r|g4Ro<>nk(zY4XuUX~8AA^PZTb^o-Oy?fx5u;0!b896xKwP|7j6o`) zOb!8R4lLGb=u2+@%2oS%Who&AbB!jSuEcRq*yTlfg_^`>>?Wo~e-Zb9{=e=c%B0Aa@3BuS>N5iHTCB81<-o@oUS|X^ z#^}1w)t*2LtgT%DdACF2W}JPR3lm9XmGdX}Q@<`~;yBR|J4r~IAsrcHu+Tp0Z_}r~ zoGT+6`PoB&3(Pi5WXPxIDkUd?=(tr8+2O5;9#&;!3=5-jzEihHW&ROX_@Un>W;Fr1 z@?W%~q{I|frDyo|Q+U^3Q5f4!;TUXZP-RF212#q*hucM4^)Iv(rJt{#dSKT!emLPY zpi_>jvCGsmYf@_Rcbzi+xefAoSt?&fGxk5W?WdBq$u_HCFyDqg_SGp)huin#=6_ju z`Xeu`9$)&}GwqirE7E61*grVq^qp7?p2`H!n~WUiAaL(1U%mvk>e`nZhJ$T7Zu_6v zwo$~Xh$T+Nf+rT2hr=15Y7{f?hZy*2#4!K|w=88XNrc!F#-l&V5~$FHQMmBHKFlT!l$ zfI6UU+52EObGduu&BvqpQ_Xi@!)ff2C^UPCDij!bGryE_;Z8$iPV!33^2-U*>buDO z&@l35P6$K^@St(>e3D40#=FM&;z1<@#z#)|jVYp~wn zsjHIu;m%+`Tmj}&divoaN#gf>k*_F&luy3oohO{@=#Xcr{3UIYV8Da0sL3?+a}sK2 z+0_||QTjF=V;l+GnmSbhlX;8+dLP8NZ#Yz1S9-pyI0X_;mCp%v&(}e03jLZkycDKa zwi$B49PN<9v&0za?2QF&Lix6f*_<}cWSUNsHB>v}Aj;gdVDnH2tk0#>5C*)oK%_-0 z$(I#23s}?RMiD3A5yrN^IZM(0usy+oQNuuszzW~N0UwJoiikF+P;|Lj{ViLT#5fem z4qIQYh9gSt$nFo&xD`o`?7o~1ha%FcFuTE~u=Qn;xT6L+qBy5b)~D+Ex;gWz!sd-v zamq|u7v|xXZD^Z}$-n3RdE?dGNQaHiwUWn*DQ9xkj-x8a$XkF59KXOPrtiQ=0}#q3 zqUsChMr=9iP;mIoc}Mwzf_oyMnLN8@JI7X3wq5o5Lk$Vm^Tr ztacxhBn?~&Zn1h~`m+Y7Pwmo7E=ambil}l{BMrHX*0$x(NslH)YTjN#;=G z;*8>IVe6-FuQ;OyIkWq=)v1Vc+NgIz{kBBy{HI#FOY8yZ>EiI<1=aTgc8`+J0_w^C z!F&nofN%dY$rgcYaR%L*CmjO9z zU!BC!H?9ZHm(e-4Xi#%&;FDr?{f|QNJosb!Oa_)}T+%UFEcq*Nv&_odHyMkYYgG;t zydGo&;iC0RlLI4b^}Z%G>h=gtQ6dPutPO7)^3MhLB#moCx@EibDBN+Qu3m*^<#5yC zavfJ*Kj|oOp3D6umrK{sv8p=UwY*eC5aq5 z4YZ5l*GwfFQWfrsS&oIH1;Pto^EF zl|@?nktJ)Cj2WwIjbfVj7#t&OJEK^P*vw~fBX81=S8`7`Df0KezhLqbm49WMbOpZ* zohM0h#nuoi(JUx4)$Ojs9XBw>|2qfx%2Ja=B#CoD(k*pt-6X4H8sQ$kf-IBYZ{1*m z3D4mIOn43_6P}q%7^aaes(D{OOT~3?leuud`hA=;A8nJy%L_e4&Z;RnPlZY)id|IB z^DR`Qhp*MxbNiBwEVVOB>&WWMC`O%BI*`9e{ai&ST;7*tzxaNx(m%TmPP@=>@OA!c z+cpK;hJ6XO4SOo!>GcBc=>?PXOWto%0!>qbXv#b-Fg6xVy(>$RH7E0Ch_4p8-q$Y= zHqcgxe)U^}OCV>y2R?^r>~KqGiCFE^K)#$xb!1RGN-ouk*P*#;XGVyVi4LHlHFAM_ z4z-?0JP|V6$@f|}{E-T;f4|%RKAGvZ%bE0yx|w#O{@Q@zP7cc>EeWAMvP*r0gU%=K zb#8bB@?r}3edamO5-*Tgl z&&^FZJ~X@Tz1DR{ACMalQdtWLO%*DTM!KgrGI^rZ4=^r4k5z&XS?kQO8?hn zEx@LyDjiV;62@YoE2ziDGzhm!=3iNG6xR1%3)VyEQCm%b%@e#*H|5DyPfE{ zC_r!g2!)Ow4c!^mU(u&fX>M~%QRq)|QK(C)x3sIE%p>f2InuLh*X z{SJ4IAxZ~ot8|F9b@+gDk?6I`2hVPQh!0Sqc(?j~-3NZEi8&bH!khOtU#;P*C`ffP zuAzYECP|H0>QZPg5q@8y2m!g;tCj_Btg!b#Rk%NLe^=d5SNG-F+vdENrYNfxjQ?)x zTz`P3H5Sud*Cl;G?2)j~{rKQDc*v+29J8uE))UY&zAX`fSwxsZJ4xRD z9+vXZ9%EBuJl}b}O4h4hU#08SuJ`H`UeRS9*7MuJ?~cJU6;Jc)vFYd6LU-kj*z|P# zrU&4IHkx4;*sSDCMObvDjsiZUf52OboXK>zy?bYvvGO*{rhdRgeB5B2SehidPwnNup zU2J;c-%*dg<$BkLH>{VnToyXl%fGrLlwotdBU<@sv>N0A`7_A1Pd*`@%ZBs9w^zY- zVTzxD{Zu?3AkS-f#!XYEr&L~^I^mV+Q+@cZ##4tU7jWR+_GA;-BM_552fy5;L0~&8 zxD`?1BoNY-^~dCK9Wrhfr-jnjX(2f%34@Oxgyg8uWHf#+SQjZwi&!2+4_mjpYh@f; z|Fyt})9^})nPL2>iH@flh)VFEHUY+eB}PQg$C2D;`g#NZ^Blm9$NH9Wv~L-o2+0Xt zB-%G;lXUiLZmPU4z!bxhdqxk$>3<)U|tro7w+)F9`WqU-sYm2v-WHY_*I z7~O}MR@Mln8AK&|#$=_?AhL*h0Jk<(v12qFCvyJp1b#e?g%M|{RJ3Qc3r-Hvez%iZ z{dG@*R|FgtljXFNxEFnP51zZJ@6gU|C0CNh<&^x`^-Ol6SASQentS;!Z(OE~v0V^U zIEP=L8E-o;SVhhU7lld7DfpkMP#76~{n23SYk(OEFAuXaq=x=>df*vJWs&gAHI|%D zYGljOn38X{Kf{)dXA-^lWBanw%a)C0+`h1tk!%?_f8w0F>vKhB9LBBj%Dbda*rPZN zR%>O|cc$Ttp;R>NWR6I+8n6ulvaIt7W!Mhz`>1N_N3F&m`y_^bdrd^a%n|&_?`b5Z zi^&uEB+sSfFeMVf@Y|&fCh$M~tJLlDXtwM(xGS2?FwEA>Z~daw1iyg2cA{`IAFO~V zVFz3>B}YgF$ahG^ z>eH@CGu2>j<}0aO+`UN?uPWlgR6z!d)Pn2;!)#$nBQ8Rd%FPtwR}kJ8%;K-mjG|JO zi|;3dKn6m-1AfcHydhr>a61>u z)$6agF{Kz(`JPxQ{9S9PZ=&e^+Up7T?}Rv9MCBc`B~iih@KBqe28q~>8rXihF=zgk zrpn9rNJS5b!+H1Km_(|~&K`J4P?Sx|1X7I$LMe!JFt4M3!OdX=23|X6GfW}+t`rZ$ zECNI*MU*J?W#wPsqmQx(-W2u<$nn1lmD7Sa-xYzoDv5+|?vZ~&sz#0fl;GPP;s3rT zG|;C<(DXwQqi5BO&t~jps$nCpet?sQG-S*pnQp`Az&^KhX_ZjVZ!o!)wv(qTZ-!G4?f%3Bmn_)&&3AP4G za_;?=Y`x3@=m`uTFg6s8P3C>>;uoppIy;GBa zVmCHCX&Qf*!2gBf;A;HaVN>yU!!1*h&*81ozR9&axNn*};!HYp?Jy@$MWVB8W*U=} zHl@JMszx(ij^SkGB%aaRH3cTNES@QVSW*H52`lZjGqW*+6Njx7R)C4{YWrd>9<2L+v)cZ%%RZl0o>!z?>@oo z8ga(BS1`Nr$r$$tW-q~81ap9XLHZl$w@EO!((i7;+)2MX1@lSz-65FI(eFE8{zV|8 zxACjPZ#{k^@w*kjLm-L6jyMz5AlV^`Mpw9xg;$bIpctgB=)rRV+G%IF>ZG(;gy(S~ zJda}Z4lVGUIZDLyXeKk8@C@8qm@fC=0teln0qww7+f2fC<{0u+4P1_4$}$OYs)T~goF?~?k4?(S|5&1>=Q&WO_CL-hHpQ%f+{?#1&!US8gm$&)9a!@ob#{NtJY zO9D59v`2i*!i@&2$m!+Z%f@`OytWJSE}~mr+e^E$6xmg~HfD^;QWnp7vd4yFamJIu zt-+Ktm&Tn+I2N^E0iy^IFy||GArDTA`0~~$wo&0qGJ`S8#Yg~ELjoIwq+}^`5k=dW z;TUNK10hT9&;6G@VJ^;YNRArl#kXwvF4zmR$HQb8)L`R~SCf|0(gCk7A01CLE_NMon(VTWgE1p(V0d9`Na0N%sM8dY4P4+p?G&*4h%`j)!

2G-RH`r3njEAXBXp^Md))GS0-JZ=wat<7^fnP^EJ@$EM5G}!qVkw^7j4tn}kQ5 z3s*i_|zuN7wS09uWkWsiWaV)R(drqk+!N7PA*``$FyF|TE@-(v;HzQK2?6#f8uXip{RwF+9Ca9iW2Y+jiMf0HC0(TjlzVlUuPlN~q#_d`ltvp3(<2Pu zOe1oPHZexSMVHH$Y1;hIQa=Hh{`2nqM|XKtt8=+=ZFH}kKUQ$-nbpNy#xiz>yzNy6 zrMZ2uP?kak{@{O8EU@>Yrcql57lK(-pxGZpH&_hPfBClvCY7SyYHYtR8Ox~zG^_a- z%;$R=G@?xzCuARPD8oBo8B6{{8C!Rflty^KbjuhOa0KMJaMaU7Fcz*$LAnFxVFaGZ zxgq)rfmNB;C%hV+a@eEeeym^dAzg*l;3~`~UWM%sZ{8fil}qZiUsQ0Cvo1kZv>AzV9uceCUFkcSAs_gC1-QI6yDHw92}T_1wJrfft&jm7{VWH z7A4&xwJAUY0*egelKNv<%Hb8%A9sDo3`>V>M(E;9>W}>dEcQ$G-=EYB zF%*_fOtGwPldiC)xv<9PtMNe@&&+befyVHsYSoX(Llxk^-f4NOyLV?|G8r1=3ad|8 zW5YB=w^i9DL>e$MsBch-bGG;oE5u=*rhrGj3a_}+Rd9MKL!;qya{vj=N|PyJwY8S? zPR&X_VW+vZT7&mKeD1wFx#5t1VoQ^s5otM{-Bx$w@QSZzx5cK<-VPZyJd;1rq;JDR z;kWLDxj^D01-&+4?@R^*b3?5W4F*2Y^F;;&7xaAnimyM6ICDl?-@!K&r#W+8`u2AV zqwmI@=fv6QS*p-4J@HJUyaU009sqWF0GNl?AMhT2z%6gdrKE{ZB?kxClrzRXja$~$ zDm-wO8;g=kPHoodYm^-dtWo?hD!Ury+?(XmJDs*C>Si}DY!cI_v9{Ws*7zaS3eeZY z7}M()EMGUK$u|zs;0l93-H6nnp*oXk1W;Xaj8aRSGSnp{=JuFmynR!5^gyuGnX<6+GQ0_LzFzF)(5$-Fjw zYV}@moY%5B4KmBJMqF`h95T4o_X5Oq{Fem&aq3|ej?BlOu{=KO?~2HNP|% zc>Gz*A3|aOSO0?m(M|s0U|9YU!K2D)lv#3m@~)`=O7MRr@C!nDdo_j`n)%WC%}UrU z$)f4q(+azJqJBND!esgkMQYu7>`$)k%D$1U0fgb3hZiai3ecw}oR*pJ4E7=5-{>^YMarz1ltjH3bF7>OpHsc#hgjRHS5R7Y+I z2cb}dw^Kp(_1uq)ciZFLcEWflG5^C3kH%As!Zv$DFtfsHHzJNWMvY(X@UX@Tp^Ei* zs@EW1D~S$Nv;27KTv%qJK}O@|Cn_{&k|^oJzeXR!emrO7v9Hz#x=pOO5e-Q5oj*ar zV3)bK3i?NN{QuD>m$#}&6wAjCXF!(Ds+8`q_;8PVMtq+@cM|SfCLy!~ z#x*_4zaQ0_ zwY=n1TLe?|(vE(m!&7*_(kYM%FS%N!gk_O69%`6J>D3r>*8EnoKNHNuV-o9L#BHij zav8H?2`a{gnU+i>1+3_Hk>=>V>ilO9TUpJd@wkb$Y~8Us3YYQOmxQd5+cWO}cEtsk zPq;_BA||V*fE(t@Wcr|>Xx)w_kokf4I34y{wF>cL$#%TMPWfH0=wUE7QWA5oCG&)$ zrUg1X4G4o>M)Kzr9GAQogUEkeve6r)m;Pe{9l@3NXw$U$t9F!yP@7fNLxPrf;jK}=yR?!+cA%)&buWRve^hv)e9-eX?z}kki+evQY0&6Jyqgez8P^UX0((2)l_3SeY#jpk2Eg~{_3234 z0l|L%!oGku01Em7S^-$v7w|p+uD*bG0iX+z(Co=#K~1uvKu=J#Z3jaC(kIlm4S;9+ z0_p)+)fey<02O@!H2}QQ7qAI{*ZTt20}$v7@PmBV@2~C)dIKQ84H4f0G`KEoX_5Fq zzit=#Kx^n+(hOSDJVKWK`pvTR(|E?q*zE7Ob8@@ygP4q2>#g~gP)k9TKhav_$6!DQ zd>?SJY08)y_+iH9>J+l#2omj|J=4y`;!aP3=RDf&^e;_QKI#NrRsBEK-aW3VE9)CS zIk`bNT7no6X`37fH_=K&0jn(p( z(+?vTs3N~fUr|l7I#IEcR46KZ>q@24C%)@(9TnX-Px@@JVpIwOL9MXbYN)m*-EHAj z55I3$kHJj1CL;ROS}hmhe(?Rk#-QeAm853pOk_4WLWeELHFno?8&*3d zj9X5u4+~#W2)ugC7QIOWhQxlu_yKEhzg5$3tsk&HFI);FI1kz!uDxcMB6^GMhN;)A z;dbk2yVY^c+8~@I5Daxft6j8M@2|G%g)@Ob;Oe1#pLdD1{f7DhTT;Jmg3wEm6ob4R z*9;AITbkYVIRsa&`fIjS;iy!m`*T8a!S;3SqB|7Hg}(-}JZ~}p{Vp|TN823gQ~@P9 zlcCOJ`;Fj{(z<|e)znki>^{D2e(!s2|w# z1U1im_#XU^#{cOjf--9GKL-E7OBg1+0~dYK=cALqf7|EQL1pp>+#9cSUniYO#Ed#W zD)}qKj6uwIq)hoQiV(hd2SvL~3gIa6nikD{nP2;N4@T|a9>+3&h+He<{TaOPr}ttO zhC7_->MkBl!c5kE>FvB2(tKVl!M{l`cqjNb=p8P86@5x>p(6qxNt!%1FNW6pCT`)BaOZqet zEB5+KV0=0{pM(Y-Y>SK$4EYV)M{tqCwOqsiS<%f(ysMi@Uj=1Gd3q-b8LTOpp=k=w zm{yuOCLiBqPyz#U$->b}bD=8P@E5fvzmD$2% zD=MnpOvSEH!;g8e+cv2UKje{W7Q=|>>FSnPCM1!I&^K(U)vsO?rsQ4S75tgPlsN{sAC}Atnr%U7gB+vaxo^T-#U#bgeZ)V)us!iFPhP!{$o;ug2 z)#EPoF2CsLuKjUK(;vod+^@T@D~KEMg1X_&kGK&YmbvCl8drXKRV!)lPtf$7^*fT! ztzEP8^V&1r^{^32Zv&5wXxJtc zW6w-I5OTT;U`p?yyqq8W7bj~Chx4{iPK*`~<-v!T$E`ViFwgr|Ue0%Psu(XvU$J7b z>5yYT!6-6Z8Jlaa#U9geVa(_ZhIjKmzdk#(SOe>igIZ1sBq&-A0>DK_r4Ww4NXaC*7hX0^=N5UFY&y`gz^WhQw{#)X*P# z;fv8Kjzt2DD|O<2RY4CLbfUT#ulQ?j#vX%$64k=t4skHy^y_L36)sWBIZ$kSYn#fUUWnup0+iP9 zbRHMUkyHuePam$|PzPnC-pfwkolP6+dMkH@K@|&g0LQ9^q_T9?OsH0mF)ob}Dl7_9Il=_o;^ZdNTF5%m3Dcj`Pd5O`j7>&aB zIS9DG;$Dp8F370>lb|BN0Rlw3!%lHaw%H{^7%cH9x)U2X{0@dQGuR7q?~FX|C((Ov zOIR*0b(u*R3X}4<=^N}^NLx?`o%IOQBt%J%eq!DR``yqK3XS^X1-THP=X;IWVE1_M zy{gYk^tT1M6Y|ojMBxjPWvmkdjoLB!C%Aazme-F zD57o&oP_vok1rA{t48{`B?QwirxAjrY+SXw(n3!U<<5S^dneaDlq>iMttPwScCMsv z0__CSnig89e$v_j-OF3K9D9f59=pIM-^}&xoZhAAkn>ieweT9jl}AQVberq~i&*SD zz}Qjbs{tZ~p8hs>@gnaxx$c2n;q?F+sJ}vA&N@o?l3GTZ^MygFk$Q95sI>$020DCv zP+GtSJo&R+tepb{WVn!PXBkQR(=Lsu+cyoL#2&85! zdox2gBNfsw*guQp1=gcVAS6s<$5@f8{`a^824Xuecm*5v>pmv!X`hLJwcPYJxWL+ z8g(AXy`Z@g!bM(vC)c|#SC|x_eo?zW?Gmo>?vQtSa)kqw5;BonnwIGq!i3zKYfy5@ zyP6xxs^S>V*6+>eY)2v4)Hb11tB&CWU#oH5YAm!MOz?P6Ahc3&AM5dE(^nF;hi-#P z2%|E2S^fnL7m1-H%LAt_%T3tK%W@I~UN$pf6)($9u=29sCKU3r-y~%6vN;LKyli%Y zftStdbmU$MNzn4Lf~$?W-VM14(kL0CS-$34>m{Ly3avkhHKwyJ*SxC=*!GcWZ2;4{ z0H(VOgzqUu=kFzQpv|s6o$FnjJKWd4rZ}1>O@`3iQEj|i(R104vr2absvXXa6Mje8 z%)yd>`&?RK|E{V&1v+A9MXvDFaQ+*Fvr_&`r2MZ|=6WlEDMuH}3uh>%wNS7T?7iQM z-bmpwdhL8PmwUqJjik+rHIUDa?Lv=~&nzjQ1liSjx!(EI31H1K$Y*$aa=K53qSa>R z3iART--!3Q$9 zapJBjVLt)lrm3P^GC`CQ#Ujz(Z}i^uTo6zAGldD$C}(hl!fa~c8JhEv!d3}*oK%AM zfn3#ff9C_aK7g3AD8&Pm0=lBxM`R}E=D%fj!IYd1U;|S_JjLQBF}9`O4@01s-W9eU zIK?U{*dls0fnjIYDl?Aiv0dzt&$2nSD!YXSgk7t4TI6;MO}+Rldmtk=T-G}?Hbz|@ zspw$K{z-HgLl|J_ji%qg9FTk|2N9nW_J+@L%BS9USL4!DP!fY~p z-&6uHU+=l$M_u)&R(HuWy03H7V(*nhpSfU=k;qBo$Y9R_v93OobEzihbWM)8Ca1F| zhnLnh<6H6_8ty@kb+6B9>6^$!xZ>+TN+NWC9)qhV>b_>mR!(#s(sPl6`z8JBvZp6D zwHqIw2o09RoLiuras5Py)D8``teME;T;$N5vgH(6F!(mC?NzkHB3+BJvWXsVCsM)Lx$X(gp>4G zL67zHIA_So5%Bvp$0ppeuLu=p=I|@D_7&m$iZFh~D1OCgYO_C5SChuU#)$!9fzD+` z6I~1S9#<62NgD{S37U6rd0c0KW<7njh0W3QLWGDMgfV7{SM;cv#j_CqUlflyD-k?g zC`Dmv7%72(_b2YvGO;{Sj(aDFiKOqsiRIJeT+Gkkb0?M;$hnkXedozxTozlfii?Sz zrYtX5ZgvIbPv#=?qx0*KZdCqGBJzfbt^$SY4aKZ?#H>ODw1$Z%Lr*BplIAVpc{vlv z%*K*k8J4Ha@1dYa2-i89wj1ASItU%%bAstm2?O+-bKH;YCv&eMrv9IP<18Y|V8KM; zUaF4kq`pfDVYJXsusEb~Cz)5!oI4oAywS-;w!A*EOU`j`xQ%NWU*tq=zY=wAHf|b0 zoSBH}@ja=GL)7PWywc9A#CTm(fpCO^9k$jWymw1k+wk^RDKxD0GTsjlzu(0B0SO`u zZ|~3>X#E!ba?=L;CrVZ=QrnvNd#K-yN;dH$8@5DG2N8sDsT~JqXlicmpd*8_WOVc- zZsShj&y+*_0G(T=huxi7kPmbOA~$vAOh7>` zjh@yqW`kNhnn&q2($e|SLRrli6E~ap@`b0*Xt{$jo?v$ZePEv{t?*LMi-~a+204v#YfrtNKVx5?8ffkFgjpl^D{Y zHttw_xzy$>+54T=awKoy?|C;L`TCz16n!dOG}f6t6ZT%NKP5v0^<6uBr>fyF)hZ2* zh@aCpFCK`V5p~Zi-*tbdo%LO3+RQ-m4&~tYkSEk!bJ=&&jtK27@`@#_@u{UJO81`E z_V?wTJCiwKW|!jfBgSVYf=m`;*pBC;M&ghndIq=tmGj*fw6iXpJ5#o9V$Hu@(K~4! zaWjG{v)W}tH7jY2Ti#i7WB&fi>Z65GT)#rurLMi86}{m$h3ZtfM4In1h=Lr%O=>|y zD6f;1oQmmV?NfhVth9mWP%Bk>+ zj0v>1<#pnbrc4c23O6V`u*R8vlep&{{EqlOWfx2ArqrxW>)+>donMj^lnbMsyEFy~ zR>{=^I;iOg4vHW)5YnmKUd;lY5`2ylq`4Tnpzmc+nN%?D5$~6o70tQJin*0sP;nR+ za?))!&M;>xUdisx))vg1^=QCjJ%EM36K;<1yqI{lF*!feVa%HX9b&sxX|}4q^<8t3 z|C{gsrSI&^j(TC17b%Q?l+Dmgpa#Z(!81*j8a`U+l86}czFT;gW{HmqZs*(}u@KDx z!r!tzE^JHCFJuXZgVX^B|3Kbp(B5T96Lsy3n20_LzGm>3R_LzZ1^{>+$5UPM=F-N}ZBN;wA96;|Kng(PKAbFP z=|lEX@=`JQwm*JyZrGpmClii?XoK>I&3TiHmi3Y7g(<$ zyGw4&UwZHN`B|J2EG`PNl$wy-c+GE*HWjrFK_{u_+VJ@ExGF(>p@^0yy;+Y0Sfas~{a9}>zE4p~k=F@-rx$XZAdyzOjB)TwYA-fFnh=H!FNwaI-HH;c%H)6(V*n9{EaT~yvYrjqUr zbLj0^)I9^4cCg0h{5iM%Qw_3&%?9_w2#qI%dFwdd5V!p5I`@K0Hbcz$elE=t{iLBQ z%WjQ}dp?wlx42|{^b@>qNMF3gVvU2KI_w1v*W@(Bb{`GhWZ#0#$r6>*5QiH_-W%E% z&!SlzUfdp$aGGPAPsfeD&ybj zfII2ye|C)&qvvo(8B`v;|!wE?dRYIUOSdiBl+++jzFH zV}$Yk#gz7yU0oxDiBfQ+bj`Ao9{mBgc)YYEezg!uP<*b{mTLn}4a;~wI$IZ};g1($+DnjKQMd2B zDfAoSe9=#OqB8+f_Nq+8vMn*m8zTZ#cZVpc`FE;W6q0ZL4~rIgIRZ#V~Wg-KT0@C0wSAn>_rU3(c!mEaxRHEZ%iA zv5r4pT6tRcvch-lW=L6g&(5=}uCU!l3{fE+)S3cELqoScsA`v9I8S*XuXFTk_>3k+ zlVKd5@hlc2+!HB$M=@td*^VcJkLXM3P&Hcnt+e0?CnzQ@?@7Z~|`7Oths>Ut2D%{Cyo7Op9 z%RKJuRR^~;ZG|JbhR+r716cYyeZPLvKlQx(s6M*Z{hrzNhUj`dbMFSN%h7$&p>20S zf4z2N_ud2A+QZ!!4{J9Z_8u^wI!yh}_^-!Mll_FZFS-hMHXJq!hv|#sP&lFv(g*Pm zZYFu-Ls%vy>7IjllEzLfnOHA5&G1^ew$beHz{hVV)E0 z!Y(uJCfXH|Z{Kslo~et<8}LSL>`w}@XO7`++B3)6_w2T3Msj)fOlmUWMRV=8P%dKA z%`GQbUvG(+8G%r&?$R3GQX`A1+;Ei}@rhx;H{0iObg`d+e`uvyZ}2NR%W`z$5swSx zl)@?^KTY0{8)q(js2X)3&$nqbftakLOlq(=`r#!WWaxYr+HRS&?M zpA9w8u_jxI$u`1d4NiBHU&~QNbs=eGdnap6NAjjkxjF9%`K_J(0Gu!@O2sMc>gJ7m zN*tk4U(_zEThacB^~Y5xOvs?#|AgkO_2#PFNZS>;&&#hZtEvj`w3@3kd2=SMHu!7# z4u^>l;4Sc*TrwY@ThiV=;A*`%SPQl--Ec?M?~O?-v+V3n*P3?Lc2BA6leYz`ZafEL ziIwF%STbQO)jIROz#tffT;mmSqs9soDfqxVC{zSiu$SBKn7m1UO=sxys{ zji0<`=g8?w+X!a<%c^M?oCsORDQ75c$g@nb-1>xaLE!=-O%GgCi{cHP2$v5T{wD()7F@?*-9?j95&D5<| z^{Fx4_Rm1T`qy@kaunWC)ou#EBJX#xohma3@66<(Tm3W1KbA;tH2c#EGupd-J5StE zpl2;Gbg`ha`$U_p*gE$}T`Su!G2$&p{MfX0Q|`hsVvtM*iNry1qYT1_6il;6(kGdO zl_Y{VoB8rIqIAx%A8xGkoE&p>m)vB_26Gx0{;Ka`TX{O0G z6Ir#q1*-#z2eJ3Vms&FyiL-oXp44xHx0#!5P4Crwjd0ht(BaS^yDjH`Y}dIU3`n~z ztb8nMx0Tpk!~oiDxyXF*28q8KJ$R+@Ze@CT+9ZMPFoW&*{2FJRo2@rXY=_zPxy_}h z-ZPY8t_4q0QXC5FgdINs&a&su+-&%cB$VQo{S}$x#dvFocgetDRXIWfe2as11X(Ig z#kQuG0zBC@zbcqkTws|W8G@jyd7;C}lnZZl&> ziL6G3svdvrl)bSt*`6bQ?0yPoWzNSnFx_Y$+}XkaZR}5eNmsVOj5LD=f77`x4e2^@ z*!+YOg76+>TTc0T{7m`ttSXt|9P`s+%28=JWc@v>+U+kM&>ai5@S#Oz!Nu2fql1C= zeSTb0NM@!lk*BEGm)IPUNL4X7;26-Iy~hXOntL4Abn*Atd9CimNbH1uCjUEjK6in6 zqvgE;T|CUJo_NndsI7eL1r0u=!)@d8$8bfhqD$#W?g%QEYgH$mk9 zxww#xqH(mp=;Sx58i{(I*XOZ0>-@$2y3rTw+Yn^owL4n=SG&I?5sx}=&(lA+&Ai?7o*$b<98=h4IyUZT#)wkU$ZYwq$F9Idpo6^-R5x|p!(nMc@6`8d$V3neTqv7@K$cnAJEdzSfefnf1)r`=}R z=0no@r4rs@y&qcmmDKi&&`U~m&wqqtpO^irVt@0%yKPQB^!9@0Yq!UWymt4=Ux;d4 zV6pIF+XkA-9AU+2A@dfbQNxBU@NuIp0mSnB#lF|)L9UK=`X${IDc%1{g^5%ILOHnG zu(-eHzX^Ami-PQ>zvCi0kg2_f~*-ql49DkpjBiau31&(MCF+u+Izh0o(1FN$vcbPi@TFHA?bOxPj`dIk?l z5(sb*0saAH@ukFQ8V~qmBmZeGRVCEn3#Vx{w|cGvQLNw3%5`QXr{YGvpmMrwRdsdq z56Wh!B+nwNZ||%O<04;>mu#r}_NGZ;h1YbO!ZvBD-gfNO)T#G5<5t=fit>c9&OPk* zm%D;C9on*Eysc-bWWyGSOC2<^+Fe5pFaKauC~+f~U7;#*=&eQ5OPWKWE!&t`F_u*= zW@=X`xD{M}$@VR{=6G}8LypW%&7s>0bqB{es1PxdJe?I*IlH*^7a1N^|<=g!N(^2QESXg@K0C9!dq$DHn?+qZTE2SmJPS_qqy zJA#EwdOK@y6!usA?lMNJ(HW=JjlC)oo&y!jJx7CGyJ`v9AVT)6;j*^8oK?N+x4jnR z$gFU%s`bo3g|)vTTZ~&qU~&S3EK(RjI|Q*}nXcg5xySTSQlQuy4i!KaPw0SZF)JBo7#KOk;%oTRw`{S*`(!LoN-U!X(LccpywEgpq=-|iAW1I;oJJvxew99zkgnDUWarWH4k?93IFH-(#uiW93f;J$d~uH(dw}2B zoUi-=+_U}YYenyUoMZMk&yO9;=4AMLFtst~v)pezjLjWqobVVIg0;JBUaj;EENXq9ck2`5I@nj<9&8^H-E-S_P3MYUz5~m? zDuR;oG`0=ptdwL%+|9VO$wK49j-a^W@fUfm@chGx@vZC*9EsV_$@mq&Tmj)R<@}CXIz7qhq~mg<)~~MtJ{9NOGD?zt>x5m4?>mWcFq-=domdi zgm=NQnX+Y&_!&u#Z*xtuWiiz*na#y;iMA|xbrwr4Z^C2nG}D_%K8;+C-`lekuG$}* zM>O^`47`(d0d}jq%Hvp7BB)bKVQVvO1-FUpsmM^#M*=@^*iE(v4E${eK zy@B|m*T2ts3BT2@?w${*tp!=;DLM*FQ{;u=$7GE&d85WG8^w))QU{445oo;Ve_5kw zpKRu3>d)DnS&Vtl1&fQif;o$FUaYE#;UW*1EmVn^#dwCDZ3j|Qe-4NM>t{Q^G9MXMVn4{?%$+9 zM^S4jiqn{FWAFuj%bcg+#y*~B$zyGK^6I={a_9WFzbOC5das|EBd@p2YG;* znbok+frA=_-7K4g@nU8tq1I;kBn%catSu>n$9ZY9AS|J>7V=GCp8C`!`}D#B3Rure zdm}dke-lA^^jUb0OB*|>p|0p`#1lao6?JnFR9!X%rE-8EM2eD7T@ zXH&(NwP9S_8r8+}SR1NP%dBh<&Rj}x2o4TOP^d@7#qvx@C-&#MJSi9n|ibQjI32~ZC5yR z&!S4MR}?tRbLM`6_i}zYw{Gh>w*F&(oQhR_#V zkr0ABg`dcFlnb_$K29aH`3;TJFF@mA33y zA_PBlAh}_Cl&DaZN9sg{`n)DzEv0Ov?yLHauoI6e=O2o)yGF$w&>^vL+Y;f<4Cuo@ z{#;`&W&gRK*;oB1@hID}b&28XjJWNi>_=7h3MKNv-G+@71oNq1xQaAdq**f@-az3W z`VAkK+F&-f9wbvSAlmHiJtH2i3UNNWyu7+aPImuA4-WaI-pG|E1n(GVHS@xlfC z-pAR6v-s8Vkm#Pn%ZQ{P!zVNJ?cG?XpkX78hfJK7wESs_@PU*^9OZFRO3MqUC@u2% z2YyG|-HhSy|3_NkZ_}e1Ywg`pcbzL>9o&3uhQ0qHY{8(j9XTVI_g$==R;S-yw<%hW zH4#^WvK*hF;Oq(E3Gm&SkOB>t?1W_rk0!ARt81>^z#VK>X1c0opjydPjA470Fo~tr zN*P{Nix`_yUK^{mDOr8FzGeU})>TD}?Z|EMnBt2ZRwelqZ~4yO7GpbdQ#=;*1@1=w z4Gw=2!pBdm?isRZWVJ@EMZ@Ul>1%wtLG8ttv|Dkn*i2@8LSo{iIz4Q7FlwAuT4Rh~ z`wxWUjKPsS%h49zY-n&^y!gEKVhis2DiKfK-X7h)bHkePQ#VZhB984zCEd4_$G2A> zxn+ZGK#|r4uL$DYa(%vJS%`PeV%jg?*W7friUW9zv}I-)o^!qmAyQS+Y#DV%b7`0|(q*$b8} zcyz()8+F(oBmP3ommt!7ILWs#>mLEt@LK;{W<0H(E#*rJ6K2ehq-E2>s%y)%aCB8N zPmhf;Bo5TJz96)BPbOphKx*vk?~7<_751sr)`x12|GKI9o*~`5k!ZXIk*=p1pEhmU z-e>eU5I|d3A6FbC%D4Q(-yH60)3=2?k`H92ZoPPMigwbbk`2#nxARACkDr=2e*5Gv z;>p_XV5gKI&15pB=3_Kj&R<~!fD7VuTNA&jK40 z6?1`m|5Bey=nn*Zdk%I{WWV}c8UO%kG2DYE4l{E{M+kqRzzgawm2jNERsW*73dT&p z3G)IN$FLXFuc{~6>*hLfCpxrMp|y&|sv#`2;>8idAf#m+>`S)oY z**H6b@vuXMy>t43pw(mMZq!I&C4~#y2^h*xg#RU(@JQOL z{dch}qWyIwvCf{}Cd2N$Czi3fPDPfV`v|((Z|MW< zQMyC|qt4@9jrBK-%Hh4MJw}~)EaH&I=3VVGjuAKt7LTRz#xaOVJbY*$$NG#Bf{MbE zLy2H!1J#~zu`P~$ri-`?b?=~(TVBvwB;R2ThIa>R7iH#8=!O!cvATxDMn zI*B@9TJv|p&*OgkkViar(~6UQ8lcsfZ5fg$Z z#c!Fx?uwDU5L}Cu4EMIzmi*%XLgc|W8S5cX+kMNig=6C)5?U2yVM{i)=k46};{6A< z*h6Hst=i2O(l_Cv+z>LYXh;vj8PmKZ(kl&&M&MzOUL4n4&>=5NUQ!+&(9ZofCFc&r z$1(SE;lAilJ3qQ%$2T5dIMfra65Wc<-2wQ-C9_GZOD?=bVKDiZ8$XfdV16i%ImjuX z;ElG(d?s~PCo1Kjxv4Q36Rp;6#R=ns_V}vUc-G^a;Xe3aQ8a@m*F@wjrMxIXG9Gz~ zT%6_o7X_iKP}{zs_Nk!9Q9J26b`6-wl-&-!PsK`4x%5;>PYMUU)_U_!H(&bpgs)#V zz#X=8hb}tw1KhjPvrBsZ6;B`cw{8i%H_hfgw8C~iIOB7D)yMitNA%=yZtxr?3m?Dq zj^c{iDXBJ>wfc4KcY0tiM`xrqekrG1wJ?2+?*3IzKDefSEH`CU{ex9chxUHS8SVU% z`ORwkN4L4rwe#yd?nB&4bVF!2CQz+9RD+fN{*#yOu8PGsPF2=jP(7=;=8YNf>N$>k z5KP>=GTc{@7-EN#=6L&wA<;Ed`$k>!=73`)L7P_lyk6w9dSQ{0j@PCv)9cJ6hu-80 zf_O9|t!`4@YIDBK?859AWXdNN$g$a+C&xw&uXgvc4fd{}*3FCBx8a-(A%a|L$&HRx z9YKR(3!@y()`qQV=KL~qK8Z#+MMEiTes2ysuE`KI;7z=s^!T!`&VJCx$K@N+waaAy zY8mu*s9N?zRKl#?Y|dR`&V3A__^U_H0KKqgM4{KPW#7^iOlw%WdwFMXg`^CM5RqSM zb1iL|Ph@erDolomQ_Jh%6lcYmYu@Q?n+LpUr%qiDP$ykLwq@-^qFX<4Ng`k6aSe$l zhg|R0iSD50tF9J3G)p}BjO#$ACtoH?1OU`=Fd+s=rdqFhAcJV~6c9BQy`6S-(N0O` zC-|nKZK9f>sM3my;UnPVy?GVt?bv+0+2%7ui1}sWdlepuCS7Wz72cr)N!+J94|ED1 zdhcK_DAO)+bdYF(dRV?;x$G+Y;AOWjnr8R1GoVpfi>%(~Z@ubM$UO>$Pm<*zPW7o@ z%vvHIS?b9m!gZ-pAbv>!3$(L{j)j)#vq3 zUyBF#{E!xBuVQAN_Isl@{eu&5VN#`8)de=3BW-JWms4A7QL(F z7ajfNe@wHxLY&d78ny+w`=$wPv|Hm#sk2CPnCQ~9+`)O38^OA_nSPfnusWB0wOERG zcTW>ur8Gjk5V_Fx^=KSEFOOGj#-}f!+qmJeKrZ* zrGzf^l-b;H$T|wC$67J<62q;BV+(1$HvZtJZKVk1-BkpDAw##5^GxySCzQK!eo)OX zuGl*2f~pTyU(_Wp`%uP>abcrtTZ}@B-cURFrK_Hqwx*G-hltLrOj1wRbnmLG=0p25 zy8YT}zDl%(l5h)ZOKPVJ{dDox?e}gS9l7Zf48cW^hj+=Pb#m|@vSw@1v{6NC!c6?) z+mBS+7Nfp7A&ewb#WDThZ)G2CfczInhxM|Y1sD`j+^oZB(CvhG(Zc^A;$QxvefP9% z_v<2M0~o#TLl;J#^mUEI$SXS|Gx77P-Qnx2oBo+ZO0}s(-=cH3MB6-@tJOp^*ff)q zU-Idr{qDE#sISPkC7U{ODB=`;@?y3Md$yMTu3;P2q@>FF(6V8rNmV{6*WZ!%2jsBTfDfZcahDISC9D0T&nTR203gP{BCO zojv?tZQ67~plrMBSq&t7l)A!mCI`AuhPk3+8q7s=n&W176c5gn;6%b_-_ z+wk>e0dwpH%^^<*>y4de`~%rTogqZgg{DG3w$tLOh-xr=I0d;QSv)JoF2yfzjmFa$ z>bIY~y!cwJu@2YHTR66D^Zd8j93#UYDNV4h*{-x4dE8=!grZt5D^L9c{F_wE<+W?H zb~#(SMqk^Yty-H2XDL;+*Be(gKz13-<_Wn6Se2Ts-h=xM%yKASuU}nNyyaPC+~^<- z-3)tOTyrWfS90oFUW?mn^f7vUZH)88oyJ1w!8Fv>Zd#pJ81fwWlj_)|){oO6QQ8+D zy*s$*3uwwsap4&8S_ye+S$1JI42MZTA~>@buoGV)t)rvG%9iVvC!;;F@09*?BfyxK8=K z9{Gaxqx1^4Ve^QzP0rAwul{3mGbOfAn^mKms==1XcBC+G)vQOiWdenkpN9H0&uWNy zTq!(B$uqms#hC2oOx^Z~uHZgWR%xK%6qfvG525qFW6D}O#q=vmUqBOV*L zR-Q_?l31+h+~?fJy`IonrMknZ)75KOw&#!jc(=|nncGm-=5Mw7ycu0ebcJfUs%3=i z<#RF-hc45?EQYY6=SNv$s(WWzVxH1{7#20ILov8zG5Wp2XqM%i#Qd?jEPV;*Nm$}} z|K{F>b#u{<^=!`zen+A0#8An}E!`!nbuSOt5*{nBXX{t_QwP}kdVkLEaB0~5bSG+= z{wdu`g(iunO8u%y;?N|Es7cDk`m2uXA$FyzR}qwM;pLvkFjTL}tr971IlKKh526A~ zuJ4PDu8vu19i3V+CX!|tYdm$_lC~|blGVLWSATrFYI&XRqcb<2XM5)O=a$42>CRY= z-LxHf{H*ngYVMItPfWb~p>!czqT9mLU8+_q=GVEEtA$TfP_`}0YRR$zE&Rbd0(5|5 zs&%tuK7-a0vwD6MTffgQC2U>Mb* z^u_$XWfUg1uPtcy(OM8&_YMO(7eSm6V=Ef{6^3P1wVpSO)>)Y2I7D&d4A32s?m40r zCQ3yt{F0ZeYb{z{9t34rOUx3ed#Ey@dZCQni;2AR&Ayk zvpS|~{}}T2&IPZ%>dckD@)kU+$eogo?b@r0NH8hH@9TeqrgQheuU3X}vj3yV?{f+ez^uJ0%GFMJkeDk+Zuo;!46HG^OH6k; z$)3+B-~*PI9~sAEH^pZi0oXqC2<{e@|3XC0fgxlxU{KBdL0{6N?@*jAJkV);*3X6I zc!nHqE=(7{+viF#v_W_xlu;e4#26TqqCwU20kv3f8HBXB zI*MVAS6ufPbXQo<`$K&pr<>Enn8(nNR5p*@Ska0*9SXoZmCUA1;m&0(9_27ER`$r^ zq+pQ2*E=LG+j%_w&GGNJHxSJPBOw7oxb10Wyr0`%R_QPDcwv&FY8mf$e!!wzEWS~_ zfVzxR(t9gwp&qgXx<3`CR-lhu^JWZqr^6)O1j@z|xEx+!p*LA>z- z>LX%IRe(vJu5lE)q%Oiua~eXyD2w^BYKcom=Qs{I?QfWBLnxms=cQgD^$->zi*`w~ zyl``})IFLrP47_$!8FO|m+=x`oNkD}in3HsQ3AI~_C z-NYOK{T}^*9yII=K0Px{%Go#)bZpKnI(fP3wQ!^mm$j5ftP9M+J+Jx$b1>2EW5Qtb zhNlF4&0W@)AM0i(r z1q(N6-&6GUrK)`jP%nKkS_ir3yy|CORjSbaiVI_nZ2cenn_MwCxA)ZTb*(Pae3qoy zdI-uA{!3%iHXX@4Yo%!`G)>Tv+@uG>2;LBiu8eE+L|iRyCT1LeJ#cEDyM({nmsRiJ zjE1e}$Vnr3V8g#toh}(P{YQbta|Z-Bj~y(BxX0J36<_lel|@ zu`^NFL(Nfs?!mIXi8C~VEs13E2%haYwTMwn$2*hyx>zy3D&(Zg zwc1&^Jn5_MSGV*9J1b$c{VM7UXzW`AnJ{NEZZ(I?n0z-mkXhjFVwWd#D*;i7>%;J4 zv&LB+sr*N*xqM0HpHl7R#qJ%c_GOHHnGAKbm#=h|&$E=%coilRs$?(XZb}u#(}(fT ziT2o~qPZKW;K3>5%`R7Dwr9`U37SK1V>|W17`yDn4z}i+S@x1Wi~0Fb+!(Z2EH8h^lD(sqad@!-Qb|q$0v7bbxKw-mUkHk1;b?1v zEVJK~1VI)w{}C(+(P2bG<$XrwSx2TO8&W68EwPW48z;n%DwZdB<0miZOt@4WZQxTE zoGxbL!+2|`L7%$ds)dL00^HbXd21N&O%h{UkdJZuV$8P#-q~%kelJ#(SdTYK^p3k0 zE3Ftm_zP93@NsXrKGnuQR*n-7o=H}uihN7U%Zs0YD*c;w{x#9|$^gG)InI^RAwOfT zUYY7vrN-XJ_QWt?jQaT&4=++lU;ABql5=qFA;Z{Z+UKc(o66=c+Y zMUg-HV&C+5XJhrdLv<|D+(c@NVcZ1LHAqvWj?NO?6j3R6jIvorRYs>xHd%GaUrx1I zM_0jS6a99+Kb7MU z_$T_{xXu$(??TY2G3-;Dtum7&S{&^2e{>GQR9rXT1OcG&Im|~Uex+`U3?A#)O};8!7TD;n+#uHPVQ$?PY^QCjL#`BQR1t`|Uq{A})On?W_WEAZCH)($=yN?%vLo zQ~O3hr1+0TxDGX&)(>1BiuLGoKMu;E0|iS<>NfqXDPrlD|73G6`7@uMnlU-lR7~|m z_Psl~QIqzr#z#GtL`%eD#$G=r_M-JeD6n(hRFsLCx#hoya5}_r-}L-rc>Xs$G?g1` z=U4G3e%!~i5S?(5_7gwAb$?>rCSLENn|7pi!jLi*q5<6@hU`3DOg|qwxCuRA@c1GC zNb(^voN?lA^PNxt*rsZU7@`q8dk)8bJod)mlp$KAAR`v}s@O#At|0V`ce-?TesS%N zE!F%I5C0g}9vfe>6?^(~IH;J!MPZ8Mf_z!5J&UHi_mc5w`Tfv|WZm`@=;1ig;#mqw z6-W7N4K90dcei5_hUmT~r<=UG@7N7%ElM!?f$A~blAVWUCP^)glsk>nG? zNwlrQ(41VfXkztoe-*x;(HFfk!FAyGo-B=P?+>1=5E58sabng8U)IR#EIN%l4*q)* zX?JC5q1|QA3a!oxvt*4z3>Q=#>}?pMtq%4zYz?w}c-!u(Ei$5d-Im~^I_zU!W9B;a zmf&N$=b6I$Qt%FGLTz!TC2O=jD;ybEAboj$q~(YX%MLz`vLT&Dj+<3_o%~E0Ka&=m z@$xZYh(_c*S zelf-UCCMp-o5>h$qzvEZFCQFtw<@RyH(#m`RR({m_xBISg#oxJW(=s#F|X6U%3@)md^|mO{)@@>yz8((@{J z=y-Ghb9Gj*Ela~oI$OxO9@jReAdXt_`0Wt=d)n& z$!BQ;mCn&Jq*HP=K{)jBcrYu(3fFLS9(ss8^R3G|d zjc=8|6R{Y&Zli0A$Q1w0ps(3>HiSH=luV#|1|v-Q2$Xu(Mq_A zH2+uqpOpU>{U71JDUz>|BwDNQ&W&TIIM}AvnxAmR0PX~*aIQeG(pwt~zuVO4q!K{% z&Aewy&CNW;?iicvOk#E+H>E3RMYd>!Ul;_RNU_OJM)qg6owlqt!z5YAwu6I#FR(&8vczS-NIY& zZg`3~i25%i-rM?hO1w%ppvL+Wg*n}*XF9)1!Q5W42q!_&OsmN_h7sonC%>AN^ zE&I1Wc_5`&o_RiH$Gn=K#27~Sk}@oo-~O;wAq>)c;m0YhN_bk4m>5ppsz_I+MiL7n z+@$DqSXuHeno|S|p(i;%1VJ718s)tarczm}G%wAfIEdf#={E9Hy9XAxO=`2!~QcZxC;l<7g9w8J|vs5I{3TS1IAM z9;>0WzTu?8eoSF6#}RxO;gn9q#E$C;&AZe1ei_g1u6VhzX15MbQNS}^djjZEblLN6-0uDR{hH_T@XSh!9hKYQ* z@Y4eb6ZtUVX5d99+z7l(6t2^Y&-ENNsxME_{0c9VFT&!>n zB}}2`9L)-Z1T4Yb^B%g75^V$?*rH5b^VWr5CSAo`DY{vwj}y!Kj zwelyw_qie1towYwuUB4A?mhS1bN}Ca?z!ilD_i*nPMKjRP06$*xT`P~gO|V1|KF!1 zVSRR!^3h2>A2FUvSVra9Z(I_wDRjQ_Xxaid9*qk0KiQfuAmyEct$h8KC>XlEwsHfG z^sPOksCQUR_#4geBmw9efo>3N-?&c432UiQ^H)vPhN(#hyy!*B;A#T48Qp2Z6-v(2 zmv;7(4B;}XO7_+KtoTYsd3nhyZSkiWpZS0;#?|~ohK&XUaa&?5Fi_)B8 zmg73~Bi0y%ZU1N>96Cxa?@D16)!tz3_LH!*qkvJ5pOC-5R{PYb&16^>|1JcAWEh0_ z19_R;`k;c;gKV5(o+I1FO`}IXE>7uuJFX$k*7{nuF)O(-BRhIgh?kp6`TMI6hkvI> z@;PmOwHDXos}uaCDGRfT!}G&%4Hfyq6x3Py@Osma-i(b}`d8BKU;<38@Auv{%7=_Fh&C=nutc6 zhWO^h%+0BZD-ny$HG(XGY{^Zh%3A@`A%D_I1L* zPi96#8a_#R>|TFKaZuK2uaQP1+ENgiuk3JtZD?w{%QzkF{KlUqDbOWq{{zLMQJkQ(uMz^_SdN9 z#mp~@RsZ+C=X78_K8N;!QY|Z+G4y0~V`&K|!_ZvXM2m!eTt?B>M!@w8_QokW3!49W=ER7HQA5rXpIDkRKhT9Xwv zlPq`XN`qr5Y?drg*h8;96m78Yu%|+lfUnx#8=HG=C5XPDQa{unzdXZkdZ#%~U62(! z^k8(ky)0%~hKY%1reAA0-}3*tl|{{m-ilf?X(b=E@>t?g(p6Jp{5c{F8M)0-%@IYk zXm5d)O;+E?#k{64jfx83jz#G&`K)@Jjk{wwxN668>sLBL>sihW&DTyw+vT~3RvPT} zc=WJ23SV_|vs_)^2sJd4gP&v8SjJ!Wgye%xR(wD-<%m>QcKx1WzZ^KsOf52AV_ zj`u|k^(UT+bVTfUHtI}sB9qE6<3Ch4PO2OJf)8@r!P~tt-71tE)hDOwOWnEBZfcIG z`$iL=+VJ9h$Oz}s)Wy0s;-W06rFpJ{BR6NJ*i0dZ?9p3~q(Gb2Zc0rpC@+KYy4YM8 zuQP|?UzXXLXpe$2ltz^uHeP))u$QuZao0NEraW-(`p}OGZ~6PBJ?21-t=HFNk`I}q zuSO&{w+^M^*|x}($j2MP_ia-+Tk{MigB@um+K-crF?oL*9r&p2sC?uN{Oz#sSMAOj zdB`pN8fEU%IL)-Dl}oqoS`m?J%d0P~x5q4VL}N0d3i#ZI>ud+~bCuJt!7KLoaOSiY zucEFsJwct0@AcuRPd^HNOS@~d%>;$#T>EhngVeXz3y!&{tTt13nD~}&3#9FoerQ(A z(+bQ7bps2IhK(jO#G`4+MGL}oO5fQJ8P&fS`(3_Ka_ENUKXs} z7vjci^3dhz(|^8_VX&W{RMh`IWef_d0QW|p2JmQTmVRE==lyG$#a~oViY801nY5$- zxH@B2=%?;vn%%ZtjzE159ol*3SfVT;SN6BoqpT=5eU$3Sry~n-V_iw14=4Ap38M5VrJ*|Q!?82uhE|7 z8AR5Er-96JYyQ{j0_e9n(uQiIYoBnaTXyw^Z<;hOJ7m-3)6LClklHlm9r%=%d4_f- zkAWC@u4-I9i#sMUNzu3sU`$F|@LUW=3T)m{sa$mEdLgVRZ{Bl@G%@zL^E0X3Sz&HY z6FFBsfWxfMBDe1S2{dGNSwoKKmgnofG*6wKMM{9?NNs*N?Bz6WGe@XRNfG|#LV-z> zmMGL3zn7Jz`gT#Pv>mKDriJ9WtTg@UYI~35GskZ2e6Fq%8|60nXy_h`d}u5Y){}>p zMDLd`e&B^r=&)KsUYHC6Bm3pIn+^R%vbLGmv`Fh6hoR)>! z74=Wq&P9Zhk$C>e^4(Wtq??7g1#1xYmay%KAet}!<+ENHTe@`Ra+)k~Fh^)Kt^D1m z#I6&4dz{wG@u@^h{LLL&(v@IZFro7wX^9v7v?^q|-|B<8=!2dInEhnxg^O4(yn%M0 zNgDm||B35=L6qU5OGg#sT!a;|0o0bKEg~tRxNXWfJ!1$dJZ9(B-Jj$)9V7kGr>#}s zDUYe{bsdW3XOlim`l6&F%ES&{N-APa6>+ADsU;O!Q^hn>MSMwx&QziIpX%^GFQ481 zP^B?!_HK`df#lT2G{8G~ZG_^8k2$>r(0MEV)NWg>l7b3gMH zf*~|2FtGSqCIi1sH-_OwEdB`wxiH)bgQtjI1K!kn`?fm{ROTE*E|;IB!c`Nv@f%q0 z0P)|Fr|TA8O!Aa*YsquvYfTQ4f*t@o`maHVa^@^ZxIVi@uDn;~G#$r5rYAG00>q$? zO!033%UvPvWAVQ%`w-qrWAw^j9zQfYx?9e@Oz`UKLmQ)^Xn?3(RrxtfB+3jt@gU1| zZK_ z8k=ozkMzPdwYs@s=R3#fwsYO>{gJk}Z?#1l+V@8`9M-^)975Y7)$pR8DKi_v1>HjQ z?Ugp8s(ycco2t_oZx$rwU~)Rwh1({C?)gZvg()0KWJK;Qtfk zt4keW>gFb1rrucDGeWi5L>!=fXWeLHdz)(S63wJ0zcAn~5(YTZwyW!IUsSzM#Z$iK z=Yg>JLGmIxe0BWpYWYP4CL6qHA-)4k^@G*(RWuPvyKxaZ1pS>Rp}g{QjUh|9#Oc?t zy+?N<*b$$$d~}5h5~B$i_a>}&j}T{%d5KtXdT?z z#kX7@4WEb^ES{t9O!00kXo&0e!~?$pI571<5oR(ro#t^(c`^(+%Ah^ptxWf1VT+6=T1OAxC3%w0 zCdDSrp!4;L*hN?>P8FXLP965Hl6fnlso@+{3=0hR#fg*3H>qGb*yTw?c>%qkgs{hx zD6J%qO8J1QEP7eo@{};_DBW7{oafVejp8+*^)}v}fW8{+7kT0uLO_)NfzKYYwabhL zyxh@EeIsCQ-7{>xLoLVZzQKN|-AdmIxqp^D3W+sh55g`~B^=x~a1ZOibM0g8(qc|VQY5IRujmig-XkVz;G zGhSueW8$1nXmw(vsg{>kAdJwjX7~Jk#Ufh5SCM6aANBXoS71L}L z@wN(GNrm24VX##slvGT&RorE(V5%@ZzHY2jF*MD^@k@PmbF3}V{zMYFHz=$fH~pv} zqMUrEu|s!xmP#SyxeeRZu-V8lPx54DnSo z?;%3EGEBz1JP#8n1#2Gawe|}{B7c@x!u;2~o&v;Dimba5JuEcb5~8QA{j}%kcp?Cb zKV-lQm$$I>4LU(F8m&fM)M_@ZjZR9dGc_1#GEVaCz1^)WYUSXl*32nt70tfwUD#pp zG^1=Uf21XZw#*P5f+hwM5MDoF8o7@j~K`p$!j2%yVdrKe%V;p3TSrHAG`mQ>5&odPhs@JMNH+ ziZjg~gMFx(aGB{HW9B`6n^;IMUZYCHvwqM+TpWh?{j66M>OWtg=rD5i(eY0edon`s zN`^|4@U&{j_RWXr(0{`VkeR)gtuh+#sWeIzofFoYa(G=XGh|O{?1(U=Kjj;acPV(>K@!8$9f7Jn5^|bmS%M;avL{W%M=X? zue1JQME@>h*geNn{OPGPESH)l%T`RbH4Fuj2TI zr->ig0yRRJ@$0$lKd6pJ+^FJ_H4Tc6$bpFdRm@sC>Q8;7i)vtn<_>kcElYu`lk?RL z3P!Vs7y#p?xdAzpFf`W@-=9RrLE0i_>u+weL%4vnc3zlk*Y%r8!qZmMrkdTNYBSGk z33Hi47U)0S)~qCP5tVxhj;Szqg@=;BO;Hm9w%62leS0m;9oE>}09}I1ZelnRpfEgX zNf)I1%UV5iX>;Q!oA#-~VP4SuuTwG0O|zzkJK~#8jo!?jQdU#;%eL#Ng`qGRHM;ff z5rCd5q(fdthxixc!MO+Q36aJ_a~DA0wk-UT%D&LpK6h(oT>ZjCYh=8yk^+~}OUeGMKEGbh^CQhihQ=`9rqDy=oLRtL)vt7M$w2Or~!yz+roz(I@&U+H z>B4}#C-XgRje=qU8}D4SyBaE**C93G&lG7i?2abOPH2b1W!A>4X654iMI;bW9)!+B z_T4o#qoJ3)=6Ag_2NcUg%I3MzKL|MtmbE@b+g2^o0mVz!G%084{u3TQ#5Agfv) z?~hOALFn?3ZbjKLBK|L*W>0I{+>J0%_nfb$$@=xjM5Cq#c*xcxZc{*>V3)UYbG2(A zwsOR~PK_Q_+$@(D&XT!KeXU6#Z6wSgT@mhx&OY}WbBymaPcoSz_u5*g&!t2Z&?DL4 zF!eT7>6SRs`kLoWXhU+e9ZEf9XO zzK*{7Rmxs740=_WC(W8scrzn%@1JMI-edeCW%{*Q8HH8%-!R@z(L^LInj6tT_f@d( zFn*Sjlue&SOr}Hpzww_0x{~5Yz&!9N`7bj+f@Q`}$o~)KC&4+=7T!xau!;sb&bxlZ zdciN+978JE{_DcuQnsHacs4s7_{!(krNH=E`V`)FqFqu$T8WVqm!y+8TD^L~A^$_< zXJHq^_c!4PEP@>>aHo8O@pugH2Rag4=Nw$OZE@$c!lJ@&H;KXiNnMx=_r`zY)qJpnD$ zX2km0B@~X2S3)Aux|iK4$9;~cLH^5sBVQK-L~-d9bavD!=1cJhQ}E?pkJy1Jhw8c0 znd@?fNSzT79B$W3^QMf?rMZ8hbGlBa9DB}r=P=Pn@KNIkeLW_m?(Tic9DYxHm{GXJnScUj5 z3uR@Yl6^jjzWeUv&1s_Yy)<6FfBsuqpZRH5$ZY@deKJu$c|0%v$IHNkjAv>F3!pmu zU*oF&x42)AXPN4Af~`S4fAKB2*2S9ZEhvuiEm#Z**Pk?Z$)9JBqQW+N{lQ+ea2ZW{ zB^A$&Pw38&H(wy;|Z-Ey+7l;(SeCntN}3$-(;kyn`S@bjpcN2{X8+2~7!m{3(si zlWbX&UPz&^;_X@NZ3P?Tw>SFUq(^ZP(V9Fd|D(MuzimLzD@qtOSUuyPS;gtS1 zX_Lxfyc`YI-}>8Oo9AccZOjyjUPxu+Lw;ZKc9g+x%lkcY2fbA&C;rWc40d{chV2(% z;s7X&=qp{h>8~!)SLJ(CSIASpUw<)_)R*zRq;wwPgZd6=EQ0L>F+op+mpwZesLS>? zu6I(pE7$ev!}^TQR%iQ*Vtqsj`BU_z_o>@O@i!45@9MasuS!w3zbyVb0#RKZ7xeZ{ zXB1jO+!V2W*?pMHxJ?nolV{HjN4D~f&*1BSVCODM5M$v(S#kL6`!o;`xjYH$ogswA zQ3d5!#NsQ&5}rm;=}B08E+G;IDo^=#bk>vUiSk4oCc=Kjvdy+4iqNgv@#e0j+oAxo z){HiJ6T!*JyYVP9!lYA^R;ZvJdpk7$WYm2)nRxZ_C*#V0;Zn*BrR&3G&W)+-{Y_oP zsxhI1$>xqCQvYcvZg}p)&=bziLRLDRsmQ4G^9V?%iqFrYj53?uWN{Dg23;l`f1h@F z6Qv`Qmh_?f|13gCo71o!$m8?Dl72sr_W_{`$w6Tq^6fF)2sZNHuL!L;K5GTu1*k_% zv$BTApQ&P%>0s|h+#5}lJ+}Qgt^(r@9cr(y6@kJ#M9;;=421U`HgVBd7)=NJt&L&y zAV(^Dh@*zzTa%l-8CTr4U+**4y1+ShhYBqeZ}G-Xj|O)#A-H)5+mQYXu;3FWN#sn{ z#Ag3@dg~6?t98^J>YXoAmiV90$x^;?6~6SQP?*p*UVM^=2|H(P3QfV#U|Gu|RQAxf z@H;|ENBe||&Pn#l^_9{2l`;KU_d)AQiRwqHp+vlOQhzO0H9V1kBh9>D&tl>``(a8; zF%LF8o}NhSLz(dStWC6Lnj>s4QD1-{$8_*CRgMWZDNqT$kHCF56kbyOJqzza-F73rkX}$7If;@5Ns*cbB zdEa3niD)HfBo-X+Im^UAm{&EEFHZK)t>S0M5?g!RU?UDabo?Kjvh^f8`5~Jw_UICb z3Hs!u%3T%>lQs2ECDt#!(YZ=?sNndrnSX)e7?S1U$F?taUHB7p0PLaVWy`6Zi1T7= z1@^Vldu5sw7`ANX_%V9ZX0Ti{2g04~vE41QqQh`~Tn4GNabGepE{?LX0NtEW|4~o$ z7|bJvN}91V3!u+T8;#)q57O6~i$y;Dq zhOLuDm0+KgslN%6(#EWhgyDh6t-Gw36{u5QJ+|JPfL(-Q-;pH559i+;vv!4~d(D@; zOIDss90>39LPp1*n$%y8L&{L;I;*dhZ%~I2zw)IYygsjGp!JDl@PVz5C(~{X_3QFJ zCY~8}c~^7vEtCF)?-HKAxg32n#XsU}=INUt4d5Fk(pSL^jCMNfXhEMtOCZtmI_nru zc#cCmj>C#7S?ejqk9{jppI5Jt7e+V4kC3~os`YPYvhZ;668wX>9FKB+0%w1Dhms!| z-A@`=M2gn(i{TheX#3?fA>uJ}YptrN36`Ei;1$0az2uFWuj-imsd2s63FZHP$ebs;BOb*avW`ew1;ZX2wMSnz;?UP(Pj%!Cgf$h&<~X_|J0_dIl0_4{aS}o z{HMPvVCu}@Pl(rQ4NKPE!0vfLmI@8UUm4x5cU|}+btpd$S?j@*s>;^kqytac^TcYc~Q50^x$ zF!N<*M;E2TR&X@cbHDEe2$$m_L6=@E)Ba-`MCJU8WhLH(eD7oE@L|%SGVN&${0@cW z9wpRREaB*CXUJ0>LmujV@U%pC8biF^G7`pjPXeG3r*iRVHnsG~7==gWdvnp-FNS)( z2?*&>h%JPspJKH}<9LR9f7E0Q9Zf7B1r>)}DWo?j zW-U4e^HnhVktN>MsFkpeFz$7heguNylYTN*2z#RA9Z(@2ry_SL{eC($c#8n-Ve7rC zy|59j=m_Tyv-k?c4@W2b5s_~P_riR8;k$a8FcHST3e3SP{vduif(G@hj00g%3#EyB z`y^)zM7uNn9sN1Q1f-pZXqcIja{~8zs1&U8733Vmh8}6ERqje_J@orKMSKRG{t2* zyLa*6F6Lqn@jToo5P4%`7cz=lh1i=QF4hq08E1esxR|(&Eg{AqC-t`g4*pJbpmPJt z{}V%-rOkhgiKvdNFLOEV?Jn+;46jbKyTlLie+K`*27Jirs^^Dfu2uyc(%<1Qx4Wde zGE#M(hs4I`8+3T;MP;RFUTad4c2DSfr@eMP&AoLUa;OVmt-XjDdfQ>p+!Zp| ze%aV}cId0)1IjBOvqhjW1bbQI!nDPvq|m@Dz~(mZ3>oYdo;=>y%5MvK8vVhY26~G_ zh3KTgWZ1tS2<_@TPihQj{&HNj0fXJ;gq<=IRO)0`QUCmcP(hhAc)BX??oKB*eFwUZ zw7d9=vZqyK>QW}#YWP?fWx_j|wZKOOJyK6a`~VoZEYW$Q4pkuidepD8a>V<-M=|zCF{qv& z-FNRFOH5i#!cyl<=g)S*EXL`cQ`9TNslT<3KB`he_X_RJRu#GUBeu0A9{sraQN~}< zf&%6WU+G6-Z7S~JuuZA~#VcUh_!rPE`@1eGUhyDVrBsNx>|9bM{ej5a7@G{UgmYusW?DfQ9tyM~ewA0!ixy?i6jN|i(k;faAVeqhRgY`;y-Y2uY z{ucK)8jZI9B0LLiheEkC;P9-qVP?v`X&jRYI>q^fb%7S$P~7^R3mJe}vCU&JQTZ4K zp974+E{4ztgh7>Ap)nXt9ZEleB8;(Zt^5p>F%Dx$GGVY`ovJuF+vSNWnT750a+1jK zIut5FipSS1(l?WfFDt9G-aEJRWc&c_dZbKh63c9=?gZ{_YLn_&6^Bu<1UjZPmnjV} zW+^fn=jU zfww4u^28dY<~{?qvA7H$wcbzt_Y}SBE~?-tE}`t4#niU}8>w*0c`}i>oj@eaQWud( zPN=ZYroPKE$jT}$WBJn;l@JZHG_CBM>U&;~nTnCX&mt11<5@1mH;BaTX?7*5)Q->w zsw?S17GF!T6QtO(b1f+p8?B!ynke>_IEtMqby947Tp)I)jTJ!pAuB&SyUygI%FeYX zd0|x^(aqvrEdNpd{J+ZbA7#ge)oiePu@6=I(|?ksKiS^8yBBr>FvJpYw8?KCbv7nK zhy^XB-4U}u$;x%M=_?IYZS6JRXteT<4Mbi>>sXU6Bte|Sj6hq3+T`?iE z#P38R;3_dct`izD0-nLsP*Q?yPYQ>pClqoo^FSEou@Zi5?FVRSzuJg&a|F5N>1*cb zn<;)ZVo#&RpY9C7`@>Of*9A}m*98@+M=5^w`?yii>50PQjB07c=$4<8z7cC|F`U)+ zH>?h%J*>XJDIS@nxzFF@)`S_V*3t?oZ3H1}_1D;*U;~Nlh&PsEdA#-PyvcEYy`m$^%IQNk12PJpOKnSlyqg;?$dvy;wn+x{~6tKi^>kM z2G!>S)EBhvU&4$TQb8R7C@x_@{hzk@&&d<0p7^3sWg+pxs7mHvJla!?%f6U4&3rai z%=7;E&|z3MibtzR&4j|ld869oi7>u&R9PMfOOWmz)n0iIHOtyYd~j5`d?Jj?MA-X* zFsXQSO9fO2{Ar8%qdh;Pynt`HIdcm5J6fh+CaogUDe81;z|Zq(;n0#__slG9%h39J_oJDzGxxD(lM1)MZYw$_L2GgY zG?yGk@`n~RcTcj18SD*VWK*NZQBmaWJawb%4J1iZ;~z&Mr)_Z*s|#$WM(Q)_tsg^e zF9kW_&Ld@QZ3OVdUUcj%j=lxbJ0q~P!oM?ujhxA=fg)tu>|IwoXc`h{gcrW$lU;i< zda)ha$=;qDjs4@aE+BVS%P{qtEWR3^vSpmFpasz~T0qpP(xZ@fhK&}o~V`Y z|<~H?ELv*8U ze}wfmUH;V|0gOS7aQuFW@ORD;(ZA^FNSfAW>u&Xp>l-BQxM4ic*<$2-;v@QS zW@y;7TA zISsdF(<^m>8?*`OmDAHJ??ObjC#4ZL4D>p2_p zBW&jRo{_57ysf&e{JW9cvOYx z8lmTCbhUrgc7*ruFueiXU^>Hxs90wkt7#urdAuoBxvu(Jakn^MCUAB2CjWL*kz& zq!zQE+8jbUJ$syM=zBZBG&l%p@hnCO`b+TCa%F6}FU66&dYpChjUeF4jG_|zy4`Lg z=J=A68vioEk5Z7uRAg&N1LtApCgkq?`4O#U7M3Hn1h3|sD5dthDW%mgb_dUeyK0mO zH*91~(i4n{dWPj^I$>o(^%7XM3FBDA40v)Gn)o!KUCE^9YGIsOE@aDXh}$1rDG#j6*NZ>NjmLAhS^?HX5%8Xy=O5_fFd3p5f07NUO0oP%HRAL zG1}UTfpwcd2m0FNK@150-b(rr7BMqV-%O6axneoKOL+R0Nz3tFEiNCy#+B}nkMj`x zkrAy5Je=8Ugs77{OEkOAE1?3yl$_1{;Sp=#whNzu>L^59?4nN4TldHcxI0uj_ZC&U zHu*z5w!=E+5~*WEtCvtMKtSF1F}fcq|KgL4hrcqSZTWa2{1k;-J|d-7KW{1RM?Xh+ zra%5W6n^EB@}y73+OJI7H==F4jEeS$zfIxEpWw~J@3$%zwYr?g_3e3;Gtp8D71_mW zcRq0#&ismP)O0b5t5$~KHBI|f|M3%f?pBy&ny*^8bCF=}(x)SCM#YMm*@xHe?DS^# zi4_HfUZGsy`WuZk-!yH(ybw*Hy<+>q%ASyw zD>p3oeu!q4`f*LXx)Oq)QT;fXYd^JvA+VwiF ztLNEj)mXZ{#{r5~4MOWq#5IOX(7v<52j)97zV?8xr|_T}h~$&Qd)Y1+`M zFv)YKJi5IUmtxBwS{~`YX7;MDtyQBIb;~r7&Rv^#I5)Uk_gDC9io0h7m3TqX+e&-D z0)8)fuY~qiKo1xgTn7ACuh{dje74Rq^y=G%PRhBhb(Y?~DPkbvg;0Cmo_Mn8shOln zsJrz}HZy7KDWD5kAWH~+IEOkD3nWK?#A<#9~)@=M{e^XuHj{3?{= zs@`TK(OPdjKOgB1CZC6dxpyaCJ3E6>({I70t;=e30~htDc2VMe)(8L5TLH5Q#nS7* zu+~a}7~%l)f9x)X+;#|Vm|T{97O9yugjcFPS?KECiqODwsu9b2)6N@Z({p9*t%i%8 z8X0V+x|sUM)la7=TM(_3S8( zhElHcCf$K{R;3O}iIodN&ip;`(gI@24IA;<@}|$8*CEG^@8WJvLmnXF$75F^nZ^6a zfHywQY6E)C{iiR6^&;!t8r=QRmS3B%D)jhJc~!oWw`Uge0UnKJYw$uVMr_Uy6YkZr zN5H`UK+gpW!NVigmJsVBvev>G#4EW9DId54Awnc#;;6xS9WRdM_Cy&?I$Y{9%2x>bEIQenQd z&T022Gaxs-!3d1sC&`obm$qtIK5PnEe_PemYmfo*>?Kk#l_?{D&Q-NenNhXy!ZjPN z$8UY^PoVJ{kmih7t62`ZUh8|2Pad&04rAS-0vbl>;TMz_0~M^|O)j!^%tS>67igO) z^Y(^#SIgdo0>GnV>eBb_{qVxWelg_Nz8)z3O~k{*ZoFpNyGQ-C;U5>naJ&Hl`RST4 zzp9BN3>VO-#sa+M%}iz5$ELY3QDF}?IGRJ7VEici>KsQ-8@WU3o1uT(b z7H(4kG5SoE(VqtaMgpn$KNwj7yZ5rZGbR$6%W%3SDVM?i9iFv0i2D7Jm-Y9hJ0s^!y&L#mX9%s&D@GoGc!+IM8l;~pox2gi!)^4ytYG~O{sAAQ`{CvcnRxI)^m#q1E!+*KUyD99Z==1GW96^3`m@4 z1Y>j?!F~bCe<7x}>lO<1_Hbbf`U*9M*UN-^^I2mgk1?|1DeLaWn+PP9Qk=^S8I1d+ zl#xQRlui8%M=280tV;eqR>DyJsMXp6Q8FsjZG~V1Y$11T*kqcfZlB$fW^#_rZh=u& zguY?D3dMffi3&-kD*abr(ujrBj_huib$XWo!(-ijdQ?a?DM@$qL-`XQZh}Rf4tc)u z;YDBM-DN^8EL1FSU3(Ue{E7#uQoiiw6Bq03| z_h_uilPjHaL;YOTjsq0R@bS4Z>(?Jv1oDHCrE1Lum`<~-S0;co3vitLWi1r^l^ zca8$}s{9i;b?5#{p2d-1un!EgPN)<+t>==%&wHT2A@4oR|A>;a;B=cC9LCkso%Wrx zBIG@pG9W+-(My~lx14ZpqlcoE6yhr*L?6l_qz}z?tGiVr7Iqr)0MM>BR{YtBY~V)i zxcr_QKo$xWGBVhN-T_{nn*s_j!JF^AoZDJ|bRBAn3cfcqP+vF3zExkX!|ruge}&nx zvx4z_C#~*vRr+a29u2kdi(4OFK6}2E>2h#%*JiFd?T``V@{QD7>|KeTIU&LUBUXI( z&W>>LIV)DUPUp$}!hk9Ym-zfzj7O=SPT%YmDxHJXP#+TA1nBz8DND zVMTWJRjz}H;0K-wgru~$Nxuz*WVOF6Jsk)sfO_N8fsm!`FZ0_2ArH5=iQ6c|b#M*q zCXF-;V4#<3@_P22U)n zji~fI#)NR3hKQV=Wiux1j!5@<9;5hmoQuWhD1IHE&f?D$s*Ifne5X#PO zeY;=$FrK&5q_xXEN72gT5lqoIj-plLT*T{iOnx;? zb#!`4rE%VFt(gWBHrxat^Wt4J?0?DkA+Tov)5`Xo5;bLt!h$(c|qC7Dt*! zagtRKoE(g!Bak}C|CHmEKs)^;egTaI5L~5|6DB zZo9&+98i#Kzm8BrPy7gVG?Gl~l=yS3m0H$VS^BE3H!$QC(k74?q#>{1Cxb$Nqi`;f zdQRmU8Tu=bvBmHYR*@fO*>oL@BR$>K!)(}as{>FB8-CR=V$guXun{W*As9AdMIZ#j zMp_vN!LZ?0QpotQ;eUb&!fH5%4yixZD_~Nuqb62$*_?yDLL{M5+-Ko7o z6I#y@?wXdda~!^BxNs(0pqQkAdwp1&Jb-Bmv!jyx^YE5??u7A25O!ufj6XYEXz`Je zJ4|cn-I8ax@CSEr#Y4l|_Os)-;va{%7M%>X+cD+SbHw>uQ zHhk4WP!ZaP)nk1b-6~or_YG@XMxp)CiHbTkTu2wnt~+55UUu#CL^^FBPlJ1gt}@g6 zW?0=GwF>2lRr+EGPbAma#js1p_yGmP83_6sLXNBL09+hb`4evfGS~>kFPy$&1rcAz z(LJeA(nd56ZV+i;yT09H{^K#|@8XnOvRErk(|`nxfXWK_%2j!52}|Ow>nw>?$yJm$ z7<@_-O(UByO-w@e9~;)zj)5I`Y`Bxw{(U*}o($QcuHz{3Z-;?YtA^2OSmPJhkgr8G zz}83U5%P6KHkqbXI>#Pq)&M*QHN#g8omDsN5VWUmQ+=cj(-9J$n?nH}9xm*o&b4m%ZpgRr=#*av zAY`H3S|BrCzZ+(~LYF=J6$zekhabvBnN~Ep%lT~kgWX~9W`KtsUGH?(-e2qLR`BW8 zxtIe+qFNKBr*N5eCbxBr)}5LBp0QE+XYzMXn7t?Jy1^gM#8bLBxW~=Xju7s9Rt);E zzE=JoE7N`S#7lEQXuIBc_U?42Gb*Frb#SHg#dreTNgk=!*M>`)m6=n33e-uZC%Cz?9N1GNqKUpLD?s zZ}?i55v5=FQ?Ls|z0oyX^_y%k`l0r;tiv!&C}d5YmznA(&vp^gU7+6I1>#Vf0CnD9 z+!|OxO2Vlys46e`WJ8(JmU&5`20E7`O>OY)hktyx*Gc!BI9Lj!qYZ+U0~QXL^w}Ml z6|e}JA+AoqY%@b-88dM10vlPWsVkdi$}vMWHVmMVnZYcndbmHi?#pbb;vzwe6!bNi zSJ#*~Oa8*%kZO0Vdqbn)9C+;bXVwqyOJ+Hw}AmEbWMJ*EF+^HOtBX zc9YvJad6vBj=biG&X6gxV>9gWe$owj=hO*@4y{B)5anlB$EmpOqG=*}uVf5F$D_c0 z0u6akfMmHlcP#!6fx9ONIK;aq2%MLu2MCz$S>GY>)2Vj|7$yj`iTViwHPW;Rx0@q3 zD@>Ms;dhArD0+gJsGT6@mZnY+uye5!?p{77Ky0DC>^sDYCfy+xJwdEjikcwc;3iMF z&-0T4#LDbzzC$c0a)OwonILwa(_qsaMJ4JqtN2K(JlVD0!`!^W3LON$TMV@-kBz$} zxz#@j6TaLE8(6^U%^PZqZr^{3x}cJ5&HDQwZM~@vCZs@go1LfGm0i5Q0x;p(yJ%{I zYM^+I`e3`oZaU`aYeg5dvvJOkl#(Ak&>;;6oNjJ3;OxDFa9*51xXh6g4V*^3RXyHY zDH9E8=U&M~C9-=l;;mADav=UyfMOdz;p`P}2B7EfAYA4q5N?S#0_m`BO)1f z>)f_`0x5CV11Yufp9g5V#eW5y=cNhgH>>-7Id-jFmw{%U}{oBuRG(=A>O zID5G}PX3bs^t||wfb*6#0kz*ja4-axJ{u?hmj3g`iS$1Xq~FVb7@*lJ4h5X&xjRn& z?*Zs#@oxdALz;lLF$9(<8&Ch1XrDfis5BTz^gMSVK+L0KFxi2{R6rukrWUZ}p^~YVKrUAdrDu;^_df`kXRfcWRq~V;7UG}x zlqw%4|M611r3L@-(!%G+|5jirXgK(GtN~%KvG)IF=YlnQxp( zIab^{5kE@WGVVqd2b`!@@u>-v7>2@Gb5?-q>+CW<)55LB2E-0;zvvM6YePP zjysko97fk}cYK$wHb7VU^#t9iT-^k%82(oi?r5=g!W}0OoY8gI+rCSem^!xV^G{6B z)ryZ##E+GJIpL1s?zpG&gv02z+1=lzOEWX0EB#`E?lf*4qh&M6JI!(2V-tj9`JazZ zxSeLL_}I5++@paRw|D<3HsfNGWRRWf1G5(8*M9r2i8+`1X{qwu81`Y+rCYAzpQ|oa z$}qQzYfB3g@XxI+-I7QCHKoc5@~EGu1qBFcXMIGy`JM-vG;4}#8vd$Qy>vK)`KKh3Z0#g~@$c_==`eyFrt zVNOe0rI8mMTb84oOTxVA*OF+J!C9&Q9OaqO^h#OPD*2YzWjBBE)2a;lmY>UR-mkBU zl`HR;Rn3t1{0I^sM3Av7BGWiG1v zg}g_URc(H@SeKB1C)`1FTEg;5`ZVD~WVH#PSn_R}`QN4*Mc3B0%#>+fBceZ-EjS|I z@~~{yi*mf%Rs4lP^CU=qVF1Z%29UgFNc*ROsD6$YI9O)yWHmp#Bzt|f?M{Y2p$zv- zk`*68l+fZ%L*79+B8v|j@)376kvVAiR&nz>3_&F>axJ=^w;u^b;jXzxkzN@MdR!qM zIM+g{5pMp!;U=ZVal7EfPRef+{?hh>aNb^))fdLIny%UK?OOO&&F-d*Zu!Vp{G7kM z&rwmIHKgri@plD^`oF~9&e{bkM#b9=nv7q{rwN}l8zZqLK;r*W*}rCG==2qDGH5n{%qAjJ2Qr$cN-E=ue`QE}oYATc&>HVx z-)Xh=EI$yP%8F}H9js41PQ>tO!iSpem(*YS-ByxFD@@EHPqH%MJ`&t; zHRM}Nt{JyWyh{!*H{hkON-fi(l4en0ZKx)p(>VeRB6AgzRZ^JM!aaBzXX@TuX)3wt zqH(%&jQ{K#D9|Dc%GHpc;SPeblJ>3OKOYTElk|Q|2BAx6vcp}wWk;rICPAzf2Kg}{ z{Hn;gI2=^;<*f*Hhi{u#nWrjYTfGBwOwJImQ~t`~q;S8AMKUl4Tj-uL#Fa_#C_^E} zqH8^KBIZIFZDa}T5^(n`ihK1S?6+g#x6bjl9;_}M{eQnAB+a8=L6eU;G@TJF-GUQome-Jwirso!D;_Mq3NUUf(YIon+O9Rj*i1v(Q6m7j z*pI73X>KFTUv^c#pjx5ynzA(dclOH*XUJd|pDZ&$NFe-{vbU{-BWTt;drF8>ve$J0i&fPdK;2E>HdBt&omzLvzX7aa+#$8k7c8We=5^ z^i$R!Jc$d)OnwKwZRf|{)*Y~WQ<>H70)p^kmVXx(7Wnwch=i;rQ`R0c2YvDud+UBZ zgm{fM*P3h`cel4?t5QPK*W9OxwKS)%ncoz6{fM3O+vT$&4BK415-$)U6+Dg9*}8+J z!QZW@yTy#LQuUK;aS5IqqBCgI!IKNJ71BTaXClzWzVXNajD=C@vnXH1jrv66%B3Yy z{ZqF%X+!Cufy={Z7c5bSq)F)c@M1;Ku==Tmcp7lU9sF z;iVv0t6rL$BZxsTmtIWC5nc|0y{PBsrG&>(KMY9N};f z>{UINm?Lxs!4B%ByK;mhL9j!5ae9vMS`h58o=?aTUJrtG>N!J>@J;-;%h9QqbUDHs zL3l^>VtkJ9W)SQ(JwGi+a0kI&*K^t&;b;)-4ZReXBXkA9-qee+Il?i$=NN%|@FMZE zAvjmjQ9hc-$9RK|kH$C+f;H;6D2&q}*fyOs8RIkvwp}Mq!Z;0rJ+0$47^gw7-|9Fu z#%U1j8J!e~aT)~Mp%Wu8PJ>`Ob$mF+X%MVQ$0;#RgJ8RKk^ zI707SDZZ5pD#*zKEATu?SxU!LG-P|F8%*gJ56A z^O8mQItX?np8MD$+zNty6)#<~jE})UUT(&VA6kUlL3m%s^FtP4I0$wtp8LB+7zu)X z6E9t~2%|x;+wtO{MHmZ$4af5zSOi}XY$Tq$U=d`jz5;m}jhD__gpeTESiJb2MUV%< zeDVA_ix3(Flj*p>S_DN9EJP>$*&>7m!Q?veU5lU$f`#h%vlbyd2&T|+XDmWQ5G+h5 z{m~*s2Emj%alj&|f?(k~zTYCKgJ2OluFoQ9f?$z4>6As76a-W0#9oUqIS8iK@$XoK zDM2uej_a`qF+s2?I_acEhz){8>BJKjAub3Ot>e8GVQLU8M#p(9f;I>itCQZc2-AXK zaXRt;ScLc>*i;?gZ4q=qFs+XJgGJB>!KUe?E{k9Yg2n5^qZT0{2&U8VZi_HI2&UI@ zZ(4-Af?x)n^twg3I|!Db6JPr-j6Y%#5`*xj>$pyfU<`uYrIQX>1XB>~Zk>40BFqSa zCF=NBEy7HlXC{Gr9`O%ruESyrm08a-^OLV7dQ3VffxKcVHtLp|qO`WRhy^Xxfdz&A zz`c#IGj{VKdEu=wk6zcUXn!%Ml-qA9&&WSHI?F3p3Np`BfI(oNCFR~_cu@zCSU^BT zeA!astOTs*H!@GOAI6J-ts&U2Wu7T4CgvXQB}3EUfL8dIW2+^1p9To_u+8y&vqjh%1bZ@`b65m>5bUXVX}9J7r|Vnbn!2*RPZ9{PSQ8$RBG#Ov z;SsexKwBZj8Ym*AuaK6gjLr~h5UI`pwW5rj=3t8vu|;evFm@(MO~q73psl4SGbFZ_ zBHoMkWvR@dZ93L!iwep+-+!NgWAFVgKhDY7Yp=B*Yp?y@do6C~uV5A7_BYgA<*#5n z!i}%1xm~}4nZuQP)m+uDU^~Ozd(_UE#`C)!b{pf>njP ztJGZeuVA~w?Yq?6o?pRU4L4S*xtd?WUJF<5RC9Z$V9q_^;zF3Ew=gSee&^g9j5u*Eib=+R7>0hrGx_9n+~QA{~Yrhvw+>SW^-tO#KtJ6nL3 z43HSKzn{*)W&oD}m=4+v(*eGqjwF@jWD(^ooJ#K|b(D@rTF(b&d|th9h=c{QbyH-@ z5`@K)us~;=j-W`LoIM45)*F`n55U{xd^ViW7x7a?Pt zuJDX>O?a}y<9v{h9d*(8oLcfF0;mA+ejcbSR3|SZF*!ZX1TSR0I+@g0 z0*T`x?se*@v%(6O$H{u#`AAAINyiC~^WN#~8`V+qLfqnUF5;2wYt@oBfO8UL3#M?4 z&#EOKOu=G-MWiDSVUDexk! zQAdUm5S-g0xQYQ})tj|2oQ7>erI+Adu z0yx8fkOpssI;w;xx-|vRs~3`R2+j~sWz0r&MN^;~UM%G^fISbG80oskqmlgS)X8ta zNpL^&h^vS#9-U~WWL&GgA6NErbS+9Ya%PP(u3Ra#DP@~q`>5+_%~pZVm(u3muYD%v zjCLbLa-LaM zbcr?7Jvbd=Yf-Ve$JiQGTz?%~u99latW72Baj=>kfoW~Zxwu@T!g3%*^BaN1uIO2V z6e0Si_ft%!`!AfF)%2mF2g@g~R==K7qKpgbuHMIP@ux~<_&uv+o7!0=E%mt4PEm5yA$)HuwMTx32%4=hYN+u2S%aHMly$AKolBBM)Wx0 zA80d(p$ZFYS0Ls-A>p5OMqVU(2HSZB)q+vIBQ#zRX-W{J3g%F0GEIUaPoOa63v>dS z%9d&K6{&)`0O|zu`0sm6JdRGln5KN^o6>-+B*{v%JelNCU7jK}kIu`}#OI}Gi+q|s zlr@!hNIw=xj|wy?DW+0^<}rozJpmh+!Y*dDSt&hRWx0lwvJ&lTMecJ7-8yNIxq1(s zx=xn2j*VXzr>`B0cWETal0``}T(wolL&IawZdr{hL$WJFRykNeS3X$YIbhnJaw%lC zIb-e?(aM=W3Q`TC&F0v)?^0tGMQQA#ccsSC1%h0B-P88eu49)1v_G>y`dqquS6x9| zES;RnhGMkuc0%CrBb2AKVH;9&asDFOHPd3K~V#A1OE;fmx-qnrF_s zB(ts4UR;;kvM$TEPS>*T=~_X)eKmj8gscQ}j}z3?uLY93YtsGzz*(!dT?iTI{Th*w zy)<|K2o5Lqn&Tp8l&{m-);*m;>kkCQ-5UnK>5RNC6hB0ym{XC^+5;rrWZ5;2IC|cY zRX4m~ONptr4B1j*s~b{mDXN;31;CE##I(%q5`) zx>*-*MRc~~v=9e5{pti4d5xvYHqRwle|E>^G~5rikEL3RGM6K^>a>o{F9){-P%Z@E z=zwl+UghZQIzm0Qmv_`t@hL0^(~`iRXP)H=-}2qOGt_a^dB4pr*28L)YT?HtQdX<~{3pQ*w{wv}7i(*p&xB zLAlAasWq6+?NGb@VP$WNH5a9f`VKA8ZAZN~T3l!rM#`;4 zl@)IZH}6buiOO|+tpAC^WmjB~BgHGOKz0wPtZ`~f z-f69ChKG9?m%q%`+UCQT7X_w_lGg4liAcsN!Pyy9PdD4q zv8ltMVCXr~f4(R$97p`PQEIOh+K&7T^CQ!JURAKM+Pn9G9kfJjr>sT)_ok5hF04FH zj(EIyF3VcJADm5!i#vaZANGpA3bQeUqqjGTNQwKs#1DIV^2_27vQz*!pwMMk=0$tGhQ!`5@U3655I9@m}vfk5|HsRl=-~ z!k{{65vls#{T{LxwuXD3a01tbkyC{0eiEeevN7?12T}2%DIW$%A2>FpF!XWaQjKC4 zN~k2r`ofVC!E9c|kT=CEJ`_R=IAVc`NWTB)M27mX7fBIjh-;Y8jYPqHs$re{6>4C; ztUBL>4$o$#w!L4fUQh-l_@;Hq^Z0$Rx;P+mr$UfEB&0U(bU-RI%f^KF`%wGqw{0@K z62@n5iI}S;(Rc?n_J8q`&X1YSTBb?> z5qg!SlRYg1?o+=gv}>Mb4p4{Uw)HNLU&r8X%#pEm@xNuFXB`$oIYU&iKNB5N9xab< z2u6avO60)~`>1EUa${hX@0ACcPbG{&sQ+Gw0`&EEkzaexw}EUn!>l74o)seMHm&k2 zV%L(~nSih~`kCfG>t0OhdnY?_Ql*u4FQjm9ntU1WrErG?H*o0FLT(+&7O($3-A&Gw z+@bsZ#`HcMuY0N6TW{#Q!}z_!-9kD%ENW%w&4MsGEG#N92xt2NsX@CRyO+og9TFC` zWr&uB9o_OvdFL=b#M8E_B;8&+1~W*J^Kyp0J{t@$QHL`cf~(Z#TEH8as>^`1CJr2v zDOU>{7`{bB4f%L zd4QhX=Fp9N9VLnZQVk(lt)cSNfDEC0(0>afKj^>m{&gQDWu!F(lZ5+FYjEjGoIzwt zlsey+q=1K2`X<64K;pBASVV9teG-KQ^WvS7`71uBnhO$ zKOnB!m97|3e*ks9{#5fyxC^p7mHlE0m!?F-sZ)ykeNnO`g6SSA%$IwTVLeMtQD9r3Rw z@z0%#U&yO}xSe+6Lf<>W^Tux{R;BoM1kI+%=hyjv>P~!bnvChb|B2t8=1bzg`;PcG zkoaeL<2R;E+gmzo5qNt?L~@Id(95qo+HCvK9q=h$e|2a4-t@XZpH46CX_6v%_)eS_ z3n>=kk~?8jy!RE~k@qRs%{%g993**B&bT8l=a3h7pf@kdYyY3T*rWUi!~R!Zl*&8c zQ*r%rXZ+s07_W$@`0dS$@#j0!?ahnw>VIHP!Kyf$Gc~K0^fzYG#FQKE!&{l*hl}g( zaq>2f`Ju%a#YKK{qjIfs#19MQS4PQAFk;nvt#TOt#Qt_Laoi*h71j;X6%+=B1jul^ zNk;@<`>RE1cA$hLndxVpAA89Er^Ei7k#v*_wsVN3S(!gvfM&DKg_XL4JQAeig;9_CLK?+kjE|$P7rKWg4D*uEKisdAq zm-|tRYsn{I%@2m;?_D!Hy1~HRLogi&;sb#wnC*~!-V#VH{xiM^WG{ZTIUR|`t3-EC)J zD@X?|S$7g+5tOe561R~1iFCEFiMoGb(B@rmN`bcGM^o zD=A&qXMUH29oaIIHHC35blA>f0l?got?3~hN4{wODtK|d@Z@_QNkpqvc}lP(u=#AT zJn+g@A0DrT4piRqgPxW)CEY{7w~;WhN$X(iT{pZvSR37L9UnTbEs{@WE7SmI!`(! z<4zsa9hFYt0$ff?#?0tr>wv`%oY z*gFhFT)#}kRc;U>x~sfi0`nO%9oi`~J9m;{u5!d1C&|x*9~p1;!PcO4aq#{Ea{+#; zhHKB%$!eW-C@y|jJT=b!ANUIh{ub+k{}Z31b_-*Cy5ng@@SFiy%=0NX@C$;!hl)^o zPB1Kr=NIVYHzpdP#zOZ;2h2@c-cF&zaVhk_B{PsoUxt>Rp3y!dHZCS4md0Vw&{!Cp zLi86ieoKF}KQiT%+~ZxXL`;A-@UV zt0Ku9Ea;qRb*`5^O2Rar1`ARDI5Nm#_;NA+PKP8~TV>|r=*4qT0-#ziBL&dt@1>a# zcEd27(Ap%M8f$=7Svg9o=%4-vFO=JOUPQQG8vPX??9c`FA3pF3UG$d6U< zm{qv}>Rj-%5g~MsPRGF8I~#|j#ao(qeGAV(--5Dm%1$RISS8DPNY+5s%~$$vjVp16 zucz^?Geqanq>Xl~b&`NJfprEfrt^zUMn)1yjpN(Fnz>Qwa?kBSYgeHPnqDx?eNLI%%-BRR(k9aOR9k9w)Y+gs?@HB;et}&vp?j{^RrWJX&aZ&YfYOt_p30BNvOTe? zNtWQJ*8M?B6mjtK#|e|Tcv_p(9Oo|sJdw=);|&mMW)b>x2Ak@>ynx;ml6qX8ipH~LkTmG_=W7eOv4 z7cH0UT^xB2cU`*3KkjFue;}1!&c{ZErWF)7AO)XV=vmgQQtm7At&f<9r=fBwGTv}c zWkNYUJ38E-yGSUZp@Fd~Tu?p5^!atUc*))3Uhaqf6cOq>M@~i~N`}4%iIbX5t|O5h zou(2R<~?lAEjX87#xMr5Xzb3!{DDw7#!KjXN<#|y%s^!mGC@$?8Ge$xcMB~$_nL|} zRUItv%0m~aAa*lH5O{Qmnxujp;$IoTKw}bYVY~DF^p0D6FfB)7Y?kUaD1Ng4)}Q-8 zs?Qk!5%-=nIz*WMcaMz@w)a9Wro8QEgc8A=J+hMU@2tz2%WFYd<);t4l4phXD3&NM zvN>~&T7UiJpKNrfa^WzpC8&QYP(jm7o0#{K_r+^Jr;h96ZR<-|)2v z$3>bsOV3O4b}vTWM2W*^O1+cOI1I8jk&BiB($kHmC&F=-_IJksenrhVA0KXRu^cDy zAB%8YvYy+6B*YTIRT9do2yTNE*|!}jk}||j)Xw5~%Xv~Vrzh1`H#2N5u6Uj-eqcZ7 ztc7(s7f$sUv3|tB;wR}d(M{Jj*PC~Mr%Fn)2pFWUD5L#gspwG3MBvrHKA0*vL?4o2 z#oec~xrJZKcK=QwucWNmQqopa2;(*-35-9g?`Hh;Z6hQAb8{cm@3aT*Ofd_m1M+GC z`i($eKi25uO+tAdX*TT!)Wy+8ALB~`eeXz&aB=XTtq)1D(g=Y(;qlbFJRTEy;I`oR zFXX!!5By9g@qFy@P~^Gj@wD_WTiT9?ItzD5fTkXBQ-{a%DPV3qrYnG71?(4($M?dr zr3{`FJiozHis#RGUI$(4jj^Tg<2jCJymox)U}%75VSKR0^bgSg9rW#Zj^mrS$!{9c znt}&#C&CcSTefcJyQhDdJl|Hk`I&g>z=g9X>b92WSbzHF_veq#e(ft~Ue~%G0t#RG z+qz>VH-4Y29(v0DlJ2gossi6Xzx&Phxp$xL|IN9-_&WW*-1gwCz9Keh)m^vZf;v31 zu$2V|UmIC_;HlBS4?360DJ}*bGYR|bV_l2#CN?5le^Zi$6+$;HZPR0kzhc7N$S|kkB3?LgB4FQ@C zA9Ccz`cLn#K9MthC{ph4 zfxqNw@^}W`iPS9r0dcf=JP~kH?|VFJuP;OSEL$3i-}%>;E&X_4+0sNj9ltDFx&;q) z0kr+V$L~Gl8xJTc@|wR0`T3{Evuzmi@Ri52aB$hucs$fOk7x2Fk4Ipls5Qjh1LSW! zp3kq~8!(CzP$YR2CB)-H)%QU*zeU*p!f&s~vmZ|c!Zm@$^flxZZVMg?IB((?e=nI3 zM;^ld6CTq~9#7SM0UGMO$D=@4_uw&+FyW@~t3$XJeE$Vc+Q_n{_uw}Ij{=VgkH2)K z)`GDAf@fwlMa_NXrz{0Y4<3Ihc#Ma|b3dL$Jjr+{JU--i!GcE~$$oPA>z=t9>dP;V zA9pmjM*e+#>6fzfr6YJ6g435C$MXfH(5%Mq>NtPRC49e*@0amCAGiuU{fCf#M}Q{n zzF}kP}dIOcP}0n9xfnl>DTxT4NYG<9HP)r_#L06(6IOo4OeKi_>IAD5q`JfapO7N z-Q7Ka-$yH+DJo^y;eTa)lC~2jjC7kM5`t|x(l2`RUw&a25 z%u9ZMZ`%^(qrnfq>u@|w+rrwPyY~C`H+H<$p7`o_?WemR|GNfxVDX$Q4barC9a*{s z&q_R@{wSMlf6XR5Tjm64-p6wV&wP~G2KaTX3D$h?7oZ7;{{VhT{Ynl9(2#btXLf)l z0&NCqHz@QPq#ph2mdCR}9H3blj5a1WSQ8HUA?+(^U#?wVw)6`_um<^h$zSO497a48 z+IRKPphAwUaTU@$X`JnGe%@LhnM){4)Cb4@T^bBToeGGMvha z@sXED^HAflkyhdlm5^=~Le;CH%IR>1UL0L3tazS!EDg%W5Di1qLCn$kVEXAv+Yx^x z&2hl~;fTED=A41#8IL)!4=!*wVM$d#IuRq2Y<$ewC|D^_Ww-mOYl-#QMN%omdtP-<8!uQ%dfpK5#(t#7aRgQKTlonX_zu z#%F&A;bSa3f0w~U3xH|-(@lNhRmqZ-0_5XPO!wR3?!uK*lq&_~z}*7Mb;O4`gP36< z5_v{)>{f*L<1T~F$)1xT7vfHVF>_R2=1b3DCSf@IC?l-+8@aK+ z`DTo4c4c(95W1O82V(hBF#DMMg`4``ACYNivd-z>BE-J_q%!}ezWx&K!8$W`8H~o8 z`mTS+kjoi@m9iX0cSaB^V2(VaQl2JrB;x_GzPBGMMH_C~4CI<_I_IG;O^Ek;DEjA# z^gSrYa{6w}<`AuTC(KGfk!Yi@{oyQq*#*Y(x~iG*&R|~xcRypX5cm8%s7FrD(ii@V zvGfqYGX(HZmOkg7jO8!^umqsa(r5NDmX8U5q%#R_Xoo~b>2)zQicO=8-QJLP=tAD+hJ~4q5iwls}V-p`jA^$Q@dI4FRk#u8$k}P@N=YhoZ z`J#}>YJ$B%TvbLVc)V7Fab^>?FzvN|`Z8gwPyTG2nK1j-bdFUo*oy;ey4#>)4%#NUo81v~EpIQA!}@5bdrnp| zt`cXy2X$F%yo&qWoVcnG6^slQsl=3BPI$${sS?^n_6o5+bJ9%Hl@t2m2^TR)2tOlP zN76fF-Vx~OKq!U=`AWH0`S-2V$<|@Sdyf3V7l~fv=I| zx_cCtzWuJlfyo42NG#u_{0JsKUNctXEHNG0@Qy`Lq5hc><(l ze@5XpiuG;dsh@1?EN=8^<&+O2ZB<=}?++u0_arelg=WtmW-M676w9rv5mr2c8HZ(> z9*1L(4au6=2>Q#V%z)@IY7MZ zNx;+zoYQAs>EsHE3pdbxBCyu8e#GbiEtNc)hTOITx<$x?T?G2BYeFjnHcvNl*h%;q)HjH(9BMnW%LK*`j|DIW0Ft?MiymuJvdv!AX0$=W~$(zh)tznQycLj+cV$zGNJm(RE-_VPf zRGj&qwSIhm6cI*<8#&G8)`&5OwDq3w&LIf`DJ3h_o*e z>o1SHphnd>-{y>gtl4w@t~jut2NNn+Arkjv6}tG`o=z@_-pThi)qe6!ANs}d==yr= z)^V}h)7hNA|B+TF9NZtr(L%NdT1&?Dr*8G(s2b>p4Hs#@cz!L+{#!qN=1trf;5REe zywheEEr!{9@#h{axCdC*j_-&hDo0vqi8X(mTSo$f8ffcp$Mx@Cza8SG;v_yTeUtLa zF?!9o_&i^pR%#<(o^s%0HL41EKwQr_}J`g;l>gKi4I#8#&#|d9^3*!{9h14 z92IW&kwn;ou&JAMYD_*lz%Rx6!52b!u9$2Qwd2s9u@hXv2*^(vL^b-k1E}t065sSz z4_TO3>L#(^*{e0YH@5B#VS0)laG&|T7%X)PTAGgm%V)=9~ll)b|7(-X?i>?iOF~F42 zQG5|RgqHqK595riwBZo=Y_ly87J674fA|@G*cm0mBDC=mzpaL?#icbu@jOyQ z@H19TED0>F7t?FU(&u0q*cpx}Nht*SVPBAJowjS21U49IEH62p-?d{$(wFb6(z-U7k)Ycn9YEES{QlB4#^DM!CmH*2^4bx}0C! zK7SVH%YAT89bOvZg~ToXKv?ll4{PtJfI^Vupq5NR%~o&PV%Qa}ibaT-qN1ivOs4R$ z1x%)oB#+7T{iCWSlN^-7R#Wj#+IzlpAs>@XqB|{O__!pg?LIl_W|~l{)bZtfxV3RL znPd&!%K>gKA(9BO%zg4aF|i_s>22(d6ZuGW`RibQ(MS3I(7`vNYYtFQ44pI=M{#|O z=Z4;i2;;vtYpdGMi!j1=g(|-u`XM5TmW@Hh6NncQfA^Qb{0ZY`GLn5>D<7RmbtMuH z1*F4?xB*Hl`?Fy?!X~whgevbsJwV%Of1NmI-?m-OSc-y`dEDu*< zQP#Z)+PQ1-VZ?{4!2LYlhzjpSC3!D&m*5?0ByWEu-WHR?W-o?olajnwyNmGF8p%6N zSv2IW8|QC~r|BQ?(ckpZf9+dhp-Mw&kQ?6~vgMJ&sqmr5Q80kqe;kslCW^lpEh;lD zB5K89XVA6KUN$7ZJXS#rvQrpOxf1PLhvb1{>8PC;@gaR%hUA%}5KZFmhveByhvbDL z=~u~_PwyeAjOMBvyW$~(%D0BDWHyTIe;zs%-0i-yJaNys2qt8wO#YCgs3ep1NX8`H zGOAKxqaC4kawObDW8ILvYg|0y>9itRw2-w($2eMvPRx`ETlNjf)nnpoM4$K*!d(n> zwBgE;WENk&-5(7t5?P}6>ONk0h{K!_EsAg6$BD5{a6s8Qv^$V=t~+JS$D}SPKODMB z0Ky;nLkmZT`b0G!hg!bgI}zB^Lr4R@Ng1K*ih*i;f9Nzk(=4Cv#W``}^;uSpfgEOb zw+z*MtZf$^I@1_XXC;7U09FHV0f1%z>`g;BtS2*lxc5@rp=*tz{)2lh$E2NE=Te60 z#j}?+iUtmD@92|S#-+POr$qyaik<{T#|edX!|37UT23D;mXGt18< z`Mze^FnwH2KRfE3#4QOjE#5AFKG5ux#{@13>R-J5t)PLQ6&<^!{rk3?wo9wKrF}sY zK^4$9N;MdE%BI5MhK6ag>`bb;yN9KNkXG9*@$qzB-rl|Lld%muE0h6;XoBmLHoKN5kN#J zN}oVlcOUyFo(c??pa5>h#EjiDPS3!_MaYlKa)1;fw`deqJ3cQqHBW^kc;y;p8)S5O zmS7M0ieuL!sD~v(<(8KYw%!9ZOzlDMGVPlxik`!72a~fD zq=Ops=mTLWh&+JL&#g#t_R4Lt}#iw&Gpr&;IZb5pA__o zT%UwC1{H)Eqj7w&yB<{sgv#FoA5(TCJ0#apao>+%jzxH76+okya6OS%f4ZVmN%Dubt$W(Bl@m}q=Pru4s1nd^)LJ&MiyfYV;yV7(n z?asJWDe@E2a?62AQaO}!v^pk6{y?P8QkA0vYke^_O7evUt4jWay086vP@iwpS!$=f z-HYMPXPw|)gtyLeKx;MG6+`-eD-os3Qq|!y!35_6K-9O*2Z$IISN4;1bj`yx3D-ho z94#SnGsK-pOat0@H{Iuh(@Cem4f_NEv|*a5ZE*r)laeI?I$#WJ6HdSfxodd;d;UW( zN&t>IXrFnSG}wAtNJz?{l+6SKBq=aQ@EXA>oDKd)m{XmbcBVWUm+D%0(Y2}12MO(r z1H-`=V*sHW4cEC6FIr5UDVHzy!9W+1UEua3J~^{o&H`+L6Mpj{X3AZz)jY;(yOLn2 z!-%3U9-)UssfHP?DgSxAe~8Nof&vmk1wl{+>u=0NKXlPmko%Rw0IBvO)3R%P)8waUO3r#UOgyfaH49!NOU8XR=2 z!9cQhiNsd_eJjl893VbH*tvB7K!BOwq2jk1u=wh0yqiztMXwYXKPKKe7rZW|@68tj zam+rjsDAswyZviEz3brJP;20+IdXm9J|PUQ5$S@WI?O@CNGQF1UOM+bNGPM{k;6VQ zGDtAo*L_a@-a{3?{&K}ev_r_V%Tn9rf>~S{NV|Ih;DzTnNadqfNrf35Bo$@^Z>@1; zu<8aR!#zBhXE7C$Bk9WF!EzkHFq=@#VAn=@3wW#DH}Nho-W+5swF;}rJv5kVsmin( zhX$)knIl|uw6NsscGCA^KD4#?Md70E!R*96z1x{1wnLkheA=bnDKvQpnQlJjO~aUae)v>NJUq_~Iyzd4Qw8k|#Ivj^2cf07&7COv(xPG={Cn4aDkytQSG5#>#E;P&VW$IKIe?~A@9J7@{ z399+pgpP~O`DkHrVW3gyPQ#&!?ok2}k+thwSj>3@AP}O1Lx{@n#>;7eK71f1tNSck zWgpzda=#0VienxZ?Ss>gnlBXmjg%(O$q^66$#3~x_3aav(9--ciH?b_GFsolmOl8V zJ2F_#2)=&cXWi+b6^WN5zCGp+-EuNJDDRxmKkP4mWJ01`VAd@s@h(_bxk55`#hWUL zIByxj!Fi;B*>-+(z;Ps(m*Vt)@xv)zOr_j54;j^!Th^YQiH^=^XK`KDH-?J_(RBmi zJ?=5Ih$(Y%ZPq!%rMTgg?y>Stk35EwkB-wr+f|N=uRZ!q&+L4t?3Bo1SCd4)VxwPK z!?v+?_5PLFaFY{cE$L)&dUifu7$jZw>+>VM6zO`b9vs&s{YniJJAw2}AFVSxtLmce z4zcEX8Ne@mU=5P2{$arhC-t!4wAFj|fUL*hWaEQ$z-}RPpgMwy5!M`dJ)$nwz#OP0 zuGnHaV|aZ^Ye3C`4M;(Ou%70R6R#KMhuzD>Kt^LyQim7$q#oFyi8BEsbsiP>&@eu{ zM|H)|5iW8`gmrl_f|9ofn3Dt1i@R(ws-1$5cxn3wk>|=W_qC^H*VoYlbud?57iSi< z%Jx0@w(H$-{VM_S2Z|yRx=u8bnqc4Mc>*=s7b|e~e~g0_Lh|+L_!AHwg+9$Ek*;xW z2-2%}7G-zDJ2#&8zv#pfE)bsccF`J< zBw|Hfc3U(yJ0u}2!<9D3D-9b#8UdG^Bb{ zeOk?dw1~RSfSQkotN-e2s#7RTxu(~ACBX_ai;=2Hky~?OLU&?F^Js^OQFMIrtm0pB z9j~)Jby5w2JltV9;!D@wvS@M@?@KMfx8%}q-ZE7x6bslMM%n}(z81G_RH4Yl9NSdM zZhmFP*`T1=$9m35&pt-3>{PF2JKpQiER)8QJKb#Cd;0SMHkwRTxy__hQu8UW0b&$U z2QhLSf`|RaWZd(FnHhd~@yF-V<0-C)pfg|@W9qnQ!gNactVjGF&Y6d4@8pkU?zTyu zNAX=bI$!We3y%ENcfiY_>Rbi*^)FxTZ`ta<##R3X)_gY&^s(AHX>S_Xf#cznCb=VM zTvMH!M2~)3{Y#ugbSq&l(h)xcV#BhV`oEJV(r{mVg4(y2oR=eu=xtBWPH1}@j&ffL z<%AC+V6Y5qX8XqEClvs@?RtE2K8 zPldNxsxgSrEbXMH8YcHq59XZ@rU;Va;^`Qiql+ROOBAIV{B#EY5`NwlZ=VY$Aqw?iL*4Yh*43Y>N zf9aebB5{{*A_$w4HI|Im((S&d1ITyT_-Tw+(Xz41m&j*CpxGd)DqKl+J6IzRy6oS% z2aeWeL_HT2K30j&=0; zVN3edB#BSdkkXSND@-WLHho4!!T9GvOG1au;-N$u3)^h-q0j~EQUcs9w8(wGhuozg6C}(5 z+x=cdx8jHHjBdPn{xggUF46(#W_5DL|Hi6ycU$)doqHPnU_g2ST9P>ft+TM+c^s>v z+l2DbN#1pAaw9e=p8woYOty>(K2iOiArWL9L>&rU1%r_dNxn^_Z@Pj(Yo|Da#JiBtAdbGrXS z&N=Ld{YTEP^Kw2V_4c!#se7z+z-e@y)e&hK=slK*x6+sz9M~U`R$O@V9N(uJOyFxt zG!fyFd@4UIssyq=OTig$;>@SvCcqhFs?N6}6@|Q{|CZ!sOEB8w@=phLBz>NGpy(pn zpESLD*5!|Jx>|_NYd40-V?irYof~pqwjqC(<6QR5ef5s2_ZmgU^l^Fbh;r*whv@hN zuj5>C18L5b%f{tp!-x1DyYwlE|B}F6ww-%=qGda+#CPjpP^Myj$1Vo_8zt136wNqm zQ8J`4&1ak&x)WdYWn2Q?2_Y_rL)E^`8P0e8_D9Ag5;$-|_%VzX^=iqsG4>c+cC1Zz z(HV}RA&%r4ZIke+59}$Gm0LWT(hkZ`V=8J!G^SE%&?_Y=WLQ#y-i-;WLFXfn_HfM2 zs9EG{R_cLT+~!ui(2+Wyit-UI-?tWV0o#~4ZmGnz4_|Pm<=yvzgF9wz@557>Ns`ee zB2paQ8fSczj9_~)+QT3t+?W9uxqpT^Svc=?UPW%6EyRVPt3%*9fA~^(69Wa?yA5c@ zEjE*PG;4ft+$_U6g3I5d68L&f{*^3$@G@_p${7{TnVTxMV?>wxgQE6~cNK!%o~Vo4 zHiBkEK$6_YOFYJU(7EE9Bzu%z8Js`M9}OS(-H`rmzjj{Q2nvv3>ugZJ%bnK2$WN^_t*$6_lhKDXy9j zn3ej5iPk9nZ?NBCd|~jNh|?H4`q($&>jXA&ee83e`l^163@44x19k*3k@23VzRH1- z#u)p|r!crt&U}ijmgCE~&<86Sm{3MaBAZ}%9PMbCqPrJ9cIi_Vb}%XK{3F{w1tHSm z4#9je(ik!*{uu_r}p3Fda)4{URxx?oQ0t6V*}5qX>>%Us6apaj0hm&l%juU;|-Q|2Ha z6T7VLn@^I%5I3J}7fP^O?{D8exCmMDAxE>}VJ|1nLXpcEx~my$N~hqwQr6({V@SyxBiupEGUQW?NgVD2vE#Lkflr6k@5&I2 z20F&31q#wYcvBy4FCA>ha?Ln2@qer!IDZ%<)`cU+u+cK!D^+A(D!flZ1?dTx;G96_gj-5Uw9`nuOCv^NlE<~1NHQwHUi zf8jT{y*w)67q8vt37hQapDedfm*^6U;4S}t9Qml;#BSMMRJ3Ww-M%|;-hL6L)&d)L zVR*d^2k*Z7V7UA&9oqk2isS{DZIhvid*+at#vvW_1w;vh0@n&mn|8(>{`X;AHy{}e z=T|iBH;`VeXyo{}lPevI2Y-kVV(-k`tY3Um?+{C{y0kk`yK`^up}iKfR6gw25GQx| z0o~Ud!u^A_vUeg<0T8}H4%q+s+i zi7y`|`T9FXhgfwDH~zpE0%QP%Ac-_)^Mx?#E${jEXZS)G;eB1s`Nr3H_b>?E(SsPI zPKBbpNJ8nlITeaBi=g!mVJ{g{GheAC&da!%9L~$xe0L=;d0j|$xN+W~KJbPl$a~BN z^_0|ze>{0UTmPWXZa?|gLTnFUPV8s=Y!C}Kepuoc@He?b-I)M%_oA-xHR=_(FcJqf zf1W^j;)d4}F!1?f9-;2#gQUam;*Wy)ps^_@6poP!977}H#?@20K<*ht3qCcLL?02q z`jk5oy~Gp_zi7fq@4(q}&){wtWUY(YGiR_aaZlu6T?Tor#4FZ6HoUF?B}B+^UPZtd z4tcn1=kG{tq1#N>hR4C3nnd?x?Ci}-pJI*|-&=@^j|v1=JPL-=~X@mqG zA>NCiGa&B!d4vb15f<|Z4^D@WxXQ}=Cr$f5#QUqK{gYQU^ZrYw{g=W&Ui7djLB_^I zHI!UO%kyY?IW3Q2YG}E6<;n*N(oLILZK>2$%GRz=a!Mc5DB`(T16_4vRhDX1PJ+5r zwX&huQMx{5XIvfKnnk5*njYfVe74ijkuQa-V?S5DojsRQWR~{ivpM+)p=bqnX%D=L zO1aDVIr;2LR<%3RT=@#Ta$$YjT(pYK&6ZZ%S=G~{*}%)q=ip^Z|RdWz}AkA9vU$l>7?QDI15&YkRKT>$x9k1a_rWo4`t+A}Q?8VUvoRK$&34X6v6X*i-gGSLwi;gr?~j*Lk7ow=7iF zn6jn)+3dMyKv8Htb%Yp+R3$l{O(X?ebdW1FI`Y{xcI7p!3N<(_X#_=+#+lw_RrjMz zTy!wbkz9T{CkN=cKcMWSm$N%OY>$UTMGC99sDbVG5V8Rer@AlKAw}V~#gFXqN{EtE zB>)rUHq6=R5X*gR3oXMsST#dP6bu*3<$lO&k4=>g{rUAyPIb7lxA)tNbTHy%w{w+! z+M_Jyao6ckgoMlwyvjCMu}Y*dlQ57oRYO_Vr88ZpfZy{XSJvG^hxGrEWj|nhj zbu{Ov%fGZ<0|g2;=jY)wO}}G1+F1*tC?3cLuL&Z=OEsiksy+rZ6tMajLa~f;i5G0N z)RMqfC$L4+MVNGE;4rI7=y$NapYyVgTCDD~(K3*r+!L<>Uz5P*-p0Sse+2klCr}_= z4wBW=T$dx!3Um}XuJ^IsY~migw8>+%lm}$hWso6cRr2NUa7+F2cL-x(DX0Fq)0*f6i7A=wywEY7 zK+9=1$*M{i=*F^T+i@=gI*WN0Kr|AYfr!j^Ub{^&(8VS-g9F`!1Lr$QrQmr`olJ6# zc)gssji2P~U&=Nmkfb5U@djCU_w%{Dq)l` zLft*Q2l#{$-B{zCV#FD=C_N9cmISY~Am8u`enD+LPY2b6in7%bsVe``C*-8>ekFf*CNR-I?N1W=I<6TE1 z@HJncP3m%Bi-UJEPgjsu!bLsm+(1=s5cGN#ei@h{)|q5alw2AdIF{T$kB$KPiknLuh?X z{aye~F`TNd-~xz{!rW}ODN)*4+>wnG1^0L>hnvefe=XZivKURIeqI$j*-PyTo*uCIo6YPnxf=HuMRJ)`Fdo(I3 z==-OoTCq@(bE2~9TyteP0%=;nsmxxsKt7YM^(3<~oFaj>ERYtQ0U5Z7;>3OIoCGgV z5;=99h1;Z-b<(CS(xT0ZoM$_mGt)Cm39BCE zGE2`Dd-=oAAxTzHf-K{jW;({4c}dMYSBe&MYKJLFQQ!o-n)o;eqEMGe(+NIxpygez zP~!ryv}d{nHhm$DbyhEz<}ht7nkR5hzwHact~Rc%4@77zQz26Egd;^NX@T{2QVCmt zh-N6MxT~{Bt*GXsGw%Tv#Kz=dEl((l)=FE?Se}qJc~JK>>57+ zZK+?2phz9d?^&oYbC3$tBWzDHk&RkX#;8T8aIMbU6)5NRvaKM=eUq!-r>eVd2!o?~ zD>uA{u=F3KMkZcEr;$;N+Tg7;9qEdm`=vPxI?|;Mo8}RP<9>8V2pWxhSwiks>2+HA z(H=`HsbvfurkEznc`P?pQBDWb>5bV!%OaS#J&gv3j5|9z~v*~GA|dw`6DqD#yv$Kbip z%+6N;$x_G_no)l2T4^;S%|%r)pF4xlA+|jWNsq;_1zhelsisiDekH}wT2qMf%-yJ{ zKim5iLNV2H^?f`eEh?`1XI4?5(Bw-SiY-5*KMrpCnZ%4vC+AOUB5-IAPf~JiM#ZhU}8Pi4xKeSC}zSnlN{+Nw# zzEI#jixsGLwHGX(p-GdW%|~~Rt^)C*Xmbv$NRLKpm!l_|uPBa~Ylsxm2RP|Lt!y4! zv_OGfw2VEPe71(3RXyD*t-n_EoHREN`!uBG`RqdHwVc(J**W=WI!E(|n+JYN>S#9U z<)-`Sro}9GY`~JhRw_XRVeNEgSh0_X`9QBO=V?Tl`yi*zM$2V+2%CE>G6_5g3flhZ zQB-AYS!zsi<|B$vYUhMI&5DcNv4KqIrR>=EH*6+2~oV)*qYM zUs#mn?PA19k;;dEEH1n;dJA-lJgyMEei)WR6g(Y7?8k^pd-~54mh`a&&AEM~98gG= z8_ycTavoGK2HC*xxSWJC{daU*+mdH+Tgi^m~_o z$o#orPtQ@(JRM_K7Hg*~QsrXvEm}QEn9X znOc?oQD$9EJRO>GMl+8s;=7k&CnzBgsD0Jb(J=;DY-J^LIW_YUkZLjVO}kFdin#y* z$&F?aM`AIEAPkU>;XMPlW#Hl71a&+pNOO=dd@bh8z*)Wl>SKpFY_@t!MthU3T%_@^ zWz08cRQCZJbC)s(;X$CjaiHlscVXZ~w&PP4(t#!ivk;7SK#Iy$IbP^FXB{OKn}|Xw zh`{mTYdwEpn~t(S*7yHJ5W(rn-?Q(dT1s>DX#8@>SON3Kg65oKxxZtp-yqTprVgJ` zJj)JzGnK5$HJQtb^4Ux>$!vOz%gkR%7z37OShcUSMX4;>>)|~Bp<IOYJ0u!JMmu1wzp67iv4erydjYM2 zwRe)#C{n3NeF8e&6@M_jxp&bN1eA zuf6uKwbxpEt#9wvT#J7qz7U|&lGw|gsnf_(^aREZL;$M3epShDRcC^HL`y3in{r~R zzg$u?v~I&XQVyiE8P^pOds!ILFdZM_ zQc|+Bmo9+lMsfchq&JWc6;X2o@=E6E3rkkJ7f@O6`4@#m6fOwaw`z5gqM$1h`W?S= z7YeY|*C9ZHl7sRLL#=o(UVGH7&s>+dJV>9|O+oEoK1c3gbl~%>TWRmOv!?w+>_0zD z>;w!!c{96~6erhAP$!fjayv1%J|Tz=6S&B=MD9E8Cl~Cuq@~U4I?7MeS_(4A4Fqjh zuTg3Xfg|xe8*PCbZ|yuw-YrYJ)M8s{ zd4(>}7TSwmJR&I27TNP|*_&3{8|fCxS}?glyP&>cDr&$#*WVu)YJ#;?ur{5%YD4_B z=|s1rlc(u4+H@k0)XBB!MA@gM9@VB38zyZ?fHvKqq^P+}MAxWOYtsX`OrhFzVv?f` z3Dl+&Luj3r%M`>tYSV+cOcS)}VlETv9Y<0MxJ-|5kJ|J{xl9q-bk2WG$T)2}Q8DUF zT&55_DoyhAQ2ZV9fyRSSI1T3Z?jAQQCj`PRIrP`D2M`Y)34+E@klE_ReUSX{>&tN) znE)X8`)-0Ljy!1Lo83?*pVdQ0BgBgb9n-rGa!9`75*}Ol#Gvo+0~E0`6YyK)KYyY> z8%S#6`mf8rjI&er^L^oDi;y*H+w98}r^m({@(?RG_SQA76qiRVs-~(#Hf>2{gRWQ0 z0kB$4ezfGLfc%(P(e>&TW>eZ(3F>84qkM$>I1f&dpwB)CN{FqojQU*U(`~X{A zNSJ<}dPSR^FYi)nJC#NGag}0gcET#FC?})LKc~>NSQ9BIN?7%BR8FB!l4Q2l5?%Gs;HS=s2lh?)+TwwD1nYm6Tx1RZpm3d|~VF5y) z@G{ffb6Fl3!spn$c`8XZc`bVq(^*HAXW*a?L02nQox<|M)M>ojw7y)jQ1mTi)8?oo zndBiaLuFq`+m}mf3ne9mbn(2Jjk=K3X~WA@mQo2$HbqYt>>T39b1c@ahIuTOC|17l}=uqapfYw z)-E7m!MGEQvdL@tH3IfGWGVbD0o(cycGyF};x!L@_p@~CB1xYQ>^1$h=3Pao^;ycjGC7L76b!WP|=4iUdwF+tPWt&1pw>b%v%0Tz>*$;ea^qr z?&l?~KCm{uO`llwr@nHPs#IbxRo(oI))f?I?AQv(goGSd;De0U@0$4&qZo~0`#cO#p0jmdC zLi*ga+Py3y)&MMCAx^9sZ|ic^6%rG59&) z6IyZ{iVr@aC64O3g#P72dGl5Fr8GdJP{oU6K-m{a5TBup(dQP=*Y_5Gen&=S{>Cdd zjV7p#&vqH}+KdGkjQRb>xlUtlz413z<1^Wg1qb4c+9xFv4cYf4>0}>I)2d8QN=o82 zH29e(l^>SN<1>n$=4GYjnOO-q2L(&VsPYzRz~jV6$7z7)*esdC($QnH1TcmttIDJ} ztF)4A+87CDfnKiD=;e^aVXjPNwSNdflhNIz6nY>1E+=QT+6+la25ov$s@JC4fD*W$ z)FdESlF0%i;I-x%QUd$?5?1$_z7UvIWU)AAELIgsE7CP-rK)oI@LZKiA+=;k%6|)q zM|@%NJW$dCaT9LBHCG1Wp^wfq-zOy8)}5JF|J*$kdQta+@C$(yIr zX%;YP#Twu9IsNK&g=N13Rwb(ly?}OFma60hO$A0qp=GWL?Qcx!z6i!fOfU`tRxC zw=kYD2kG+O_}=&-;FITKfg6TS*`MrARbH_MlYvmkz$(3%sPU@_p<-BCp(=S+0|shc zb9}Rsp%qd;tIsLx^3GP$9Su9NGSzQts1Nn54T zNlnq?fdkGN<)$6mb}Ru_P%+eQCHUZDTBE9*TU*K=t}WXLfh;&8V{KVRTh?RsmsEg2 zjlcyH7$m|8d++s(Xw55?)KNE|t-4ti_P{ z0HtO!idGPmz^BJ~Q6m{dP~kKyHO1HTT5#7-5)#dMxEe&O^0-bblE#;|rbEIgQDvxB zC?)`v;V0O2s|LRSE?B$Pw2eg|kY1m9MRrUqkf>zFAE?WvE z_H0So99o}QCXMekb<_I(B4cpjQt1Mt!S(L1EopI%>;opoAJ(eQ;{v5n9j}3p1Yu68 zvT|uYE)vvVP&@L%6P<4lv^kW`#Q0O8yGQOi5`F0Z##1YQ=BeMk3MPo~)aF&VdHjF! z)Si|2{6F#3N{*-AMT-Bw<*AjxR@VyKV zxxOF~H4u_4#eL?G|KIV{I+K>;skPMO+Vn6&tPn8#wq zNT+aoykZ{c`H+v_;)Q*eQF(R47#~j#A9BvP%bZ1S{qkLUaO@l>AJD@05ED5cC-3=+ z_SzhC5GCtt0L zzgkT-hE&TN)rRl=S>@Hb@mH(0jRkDX)wVyB_AEYJ%|NcMf9(f4=pZ`EzAVuaS*x&_d?QXp$ zPP0%DDbyOrt*T0YrBDmY24bDSC%W$pdW9e53vIUomJP&oAOK?26|iqWygTwBB&l*( z9{9bIXvv`C6xq|1ClN;_xZa+&s``*g&ZsU)OHL@Xayl*XnCcp>`dnIqhao!cRYl)) zsS4LzUzVz7t1O%8v`kG&H@~D*lQx&O{D-RKBh>}D4C=z6pfYXw^F^jLE7bA{x`J<} z^M``aGNe8(^zz?E&lM;nrWol3<6}3C zu@{VIZyJZ-OI2%B%8g%XjpwXJy51OXHD0JUeqCUE++>U^Fb^Vv zqs(NS5SO3g&>E*S<=daq4D0#rj@Bo@&f@-qw9GMV;H%8EU42R=r&|k7(W%lrm_R3~ zXoJe0t*M>NuPx^zFBB`SabR+3Y+7mQs)3U&q9SowZn?QVGI`HL_zy+U5ztYx0iC#DwUqJ(^Jtddyzu*_|Yu@F~lI~^Q z`=#`8TJlY zsO-xi>U%;LFi~@+irO9Sw@|-mxLM+ER?SbMYUAi4wmEV57(Z1F)#Te6`*Za0A$||* zMxT92)4kHmmBY?c_9-;|wzQpX?K*{UX7(eh0hT_d8s4j^oyw=1>ApBk?N|Ihbk}pL z;(7K%suoe!G_GGJcDz%3t)tnJ3`3WR-yVp4imFYawG7i79UtY+l)_%+u+%+kn(8Qh z*+@UdAJ%HRbk}1gPM6u?7M1b< zodHkD1NnU*Z%$7q2Hs@{hTaEB7*x%P?FUlTASvjn>>Tdm(;P|L57@8Lt{Zp3i$2PNhI?t{jgEJ&$UB;6i*z?I zMG?sXgmur6qUp_(D~PK!=AEW1ILboh(nXK-O7b!#pWFbA_35ai4NBD36C8P|+B3BB{FRHxyEqDS z9o^ikJ9+#gH6v+S)c!*9uGG{|ZYbZ)741pHSdE|Dlpi16oZf=2Aq{GGbjai5dn(cV zeK1J?F*!wcUo+7lV>a(nGa;%&lG&mGw(pQC3-dUIMu{k>BU*n$XpHpXkNB#mG^#H# z0Hl~-_(Fdq&CYMto=TfV(>Wkc2%&TajU~H1U-c;wljB?MOn!ELU$#b-L4)qCDY&ab zt9n%f`NxkV;}OxGS^Oh`dhPMpxbyl$Q$@+=S0|!>JD%3vNL9O|rSt=S(+&FyjoKJG zjG^35yPuM#fzs(T9nT+DYiMqT8;PYW^!(w~nzYrleUGN%H~cj8?Hrn(sv5mfk|Dv- ztl|aLK;6h}dia(kJ6~y}6D81}OeLzYf&7vC^xeBdqCHO&Iv@Wmb;c+8*s(-+W`UF) z7?_aRr#O;NuK7>pNAa<`zt0vqpA1~h4GO(ppAKU&HP*^Rj?iq!%602{4xsIzbo=?% zX2}uJXeS0Z{R|m=p!J(wOsG3UG7_zt0XiR~p)iTh(&r3+#)m57kDB2&{)lfZpRbrj zx2`xve4* z?T&YUWII;pik6^Z*|gHQuC3$U0f&w)bGUa)+l*mt#wXhITc=EO|DLS6qxmCpjn+7| zZ|=0T_h~wppC+gKOd9$ezi&59|6bMZ7{OT1A)i~bG!-B6vHG@V&?A4ticAjVke&2O zMjazZ=(4(!LlSIJ&r3>{(IYLA^2JzvPmm?|L}2Rl6k|slS%G_uOJ-rI!1a-LK;T?a z^2q_C^6Rqw@i7N0`;GE8Y%^zfhf z^bzTZ=@k7jT>|ZA+bQ}F($-SCWW9>+P>n3**5FdQ_A@?~VK-Kaw=h{sR;!kavQqiW z1Dh4=UWhxeuGFHVxjmz(u6$Z*(txoKG|iP_ZapV$KakR?HclYx@JgDV#dm8pqm}dt zew$H7zXx?IS%uy6xD75#)yHjc6&uF3H(h?-Z(-9ztEQ>?-ldBi!-pi;bVgpJ({kvZ z8zY4h7|!X_^H$SvwTCtMNZ`5^&AZmUgbl$rh5H#v`Ra9vxuVgNMJMD>O5znMb!sC6 zH=|`k>L;bXZEkvMl9rL`O`t6}w7>!;1U8UK?dP#go?fEm(Njx46*ZYYiR z6|`L|!S=FRl9q)Pchs>#G*T*2Rzi2!4{0dfWdxHK0=jMp?09!bq`XmXDqoU?4eJaR zKS^DSUR~{c-bU?@E zC1F>UfSSbFi)aeCKwq~dnik4vRE}-@D;Xm@-ztI4*?DNCR`1Bv8Ztbaf z#W1LQn@*cgmz^I5P3MwO)k^oz7=G2IG&Yc^p3`oJaplRttHIh#*ss#-Z30#wEC z`SeOv-wchi4zwgAQcJfM(`CjIj0BSeHhLM7*1M9CTlC%UZyG0;WYEh+q|T+ZK1-jO zosgWbJFkxdJ+N+OV=Tk80dpmzfSEjczWC{dqPYBQ$DKs}!ayX9Cfr@MuJFFUiIHsZ zGj*q#jIjQ}-=!x_%#`3#lX1#sS=CebZEQUgHhQ3})5mSw>KcqUjl-jr;I_-oTa9Px zje|FhUs{>adQ_5NGOA3>B(?GL)ahcG+;~=N9O^QDb-{S9z<8?7c)Fh)2L`OhgnFa; zrZEw&V>cyICOfa5i7H-DY#7y~Jfmj9JKhn8F8Eym6Fz??U+iaMq6be8{#_hu)6_E& z&3g})omsOz6$x#OVxVsDx5bI0ngS-W%!m*UDSs)SCLX`{KQ|@v#s2k740esB<%R8< ze&(_GsVQ#(?4d8zl-ka_$;9fP(We(_5Y*s!cib^?NcJf#lwwL8W@VIDl2hdk8YlC3 z`+>M0JK{h2c8{9U+IeD}DdGk?2WO=wUDn)WX!Y~bWLEyXB=yNVYCev5Z`Kwt@rVo3 zqH5l2!a_JlpVQ{-vuWgIA!15f7K(GGLh(-`EW)`O;lk{e+LFckYA9gaLvYt({PtuD zS8Y2AtEmMc^LI?hY7Y~SZ;(e+H>r_QVCOX#R?7=aeq$=yyr0EM^kp33i8#p>O2kR) zv_~yJsc8LpMD3~w@sjXqgM1_v*#DG9^t9iM>1p#gnbM;K#{Vc&Qrv>%;9vB#iy!J~ z^Ux%1S6+d=f>YF1xqlWa@d&&oxgE#aW@&@EuTfgtKo^DNy{f=X@;;ZehjJfL*x#aS z+h1(cx@%i+^*twT({|RjYwEQhSsGrf2d1^R+O%Cz=+2ELvAi^W_Z}0&kh4^&w zRWqQAr;Ibc`Bxbp!N>LS10uuo9Dk^dCo;V5pJjL-<56uNcJ8Nf1=;?l1uA}&vNEKs zDTYVHc~PX&u{8!7d_UGeK8UGoGLXl!T?dajP~|H~i@E%qn-9uNqAub6JTFelcrT$k8ztZW zm1D*?1V>}2_2|f^4k|N=*WVd=!oNX^dySuv@#Ikgj-fd?&61QhPxD5QILxwjOC$3} zkZSA3#)N`n-WY#M_ykX83)FT_kwx*ea5en#2-ZU|WUF3@?h4`+U##z(ReUC*xl2!G zRB?AiVV9V9;SnAzyt;D9e2?_E6uRL9z|=ER^H%wins-e?U#z0mQk98wu^3!vICa0j za~7Q2_&FJ}G$3}h;rJtwqE)uXO`Wss28(^MrNE!3K0czFVTou41X%YJaLY;EQPNy3 z&K$UQ9tanVz!#6K`x0p1z`#$?UI|=7>{}-e%Gt^X(6z$IQ` zx0AozxOLk9jonJ#9JQC&Exyk_nYXJUXPI!{6~#TTSlC7(m@3y0la}<4#}h-G-{Hxr z<%2|cFn{k|9^^qBK_TEecx>9G`u$&JC*+bjS0u8LWeRtw@{$bWA8DcR;;PSC7AVt? zgQq+Wy0eRXE%1Rq7gLl_Y`{CfFG!Gu21WW6CCuMO31fNK@&k&5EmVV`wotVoph(sb zMjj><#WX~dhuEU&=*xyAJQpk>MoXS=z2tf-NHc*n4}G0^)q6x32@eC2YzX-TkU}&9 z4x5VvBrt1aivS>!17P==5>OPDJb^q+D2h&wB@eMhNy#(tpyr^n)EH32Biq&lBO%un zuQ-t9U7E^mhzEc`vS>z_Kl{MLk(~HtYC-(QB0?9lmC#^afX9O}pn^D(qj5b)1lMOV zwobjyM+Di|es2V95M@o6)$4)F3benGL5kw6w}C0%9r0%nwhf+f8rAR@o2Y_23UwAQ zVzru^*2o8+n8}?pwnB*LS70LJ(md>~xAUe3J~m=-ktpva@YP6}zwj3CZo}Pt0xn{8 zeGsqqbya;jFCx(w%ZvcJhO3pnHe@I0$N*5RLK_aJdd~b0O)!5HGZgSo&zjCuvO1$L zXKa5|nUGC7+B|^#T>VEW)DLGHEz}w2TPcz}fAe0JwmdSx0D*``-2U}B73)n2-m&Mk z$MxHsa7pvBB`qmps6LQqNAzyk#=#TTYWxVl@wNoQ*vW^ZI1*QXH*ZWyz{D~%1g34? zXh;s6Ey|m5_)cZB(y^uOX8l&j)4oFj9i`ZyUB{{L+ z61NBc4d?4{S9h+PihI_bUE6L5Ui@gbbz*Bhw|T$|XPWDwdC z8koz{88gE^*g|EcKB8|EhsVz3w>*;i@zmhs>(V~-A9+(ca#V`j4!PnyyzQ2b9Fqpy z7K-h^rwyY&(sT*87M|y|_@x+4#sJdFqMX@5SaRm)EDwT{0mb~BlEfG6Z@yrDE~nDs zX)Tw|4q88X$qcbL7^!CC$fa=q^`DYe&7`2pgaM^D#KBnaJii;+R{nsvs8jrIq_>&e z<#$aUITFD@K8P$_({22;A zltM@da#uM+K|mM=B^!b^&s!4~yveXSNRb5JckRaeenZ@q>Ez4#+)kiKgPV85j&b5i zm-CMZNorSTMk6AtG-^m2pCYLp!OH_qpB9Q`$U==}S&A$q!z^T|ioq%5gdcp=D87bg zeA&8Nawfna$EEivZALOoT(_^cF#@66%WH@pZjv@Pwg>K<8TsRspj9>Fw*OYtYLo6* zLwr31HwN2IH{BNpbpPGEWP3a&C@7@3s^7UoJn`qcldFAoo0CxY*(<@NLd>h5(oawi zlhsI;?fB z&teb}8>2Whg)~)oob%V=r-&F?Ncuf|r2qKiD~>(hcS=+7qGoweMav6k$ck^Cm2)Bp z(T~IPYKXIqfrMUNNzF#tM1Gr{hZWZ~ZUiS^vST3r@Aya`pXmDjx>n9x9t6)88CGts z=!PpgUa2e`J1i-5jY_uRt}r)Yu=JVOTn?n^Ip?H(24$%e!_6|yDnT`jtl-h z%s_&n{KwXP(gQ;m_Z<4|G9iQs#xob^PfuwHRH$$WJ7E5198YHQgIFid#{j3 z^F+AO`MEN480S)r$0Hoy7c=~au(zNf<)VO7X0Mmjjg~7O!SpyH=wV#rdDyI^M*=;e zJeLHZ;M5)aV_v0ZIi-yL)B%5VHo+BFtBuulaR=5`E^rVCz51@si6r=f`CD+6 zSMe4No>OSPjJLDptsh9?USI;&gWl#(JC6u4;#_*XAyz}*br2MM3G*f#%dl@=#GEe; z{{bNPlD_k$*+OQtOWW+GlRGbV?!4&Od6E4ulJCIl7vaf4PO-0(H*p}mWG5notW7@r zrnK1>k=RJid+@C2<0-aWWM3osoOYVEk_YBLNsU$Has6cr^i!lx<`sOz6Kf&gOT%xF z?&k1&ndE+nd=*c$G!rgjF9ld6?;prl$4eL4KavL@&YqiI-w^P8@2v$00>iQTB07Rn zgyftMI9|Mn$dJ2+o23eA4*SAIao|XXG%Z8(QU)M4iU1RTvqj=CcA@WyUFQ3X&ku33 z@@a#Js`!}fNDlKwti^1}#X2L&w^UT|vL@Jur|Lj>kq8inI*Q15b5PC^!HEFJ+>5Tj z9Jqj?G;_%36oF=*?=LqhfvseS|z zw9A-z5$yf?AG2OFi^m(&E~b&Hk0789ATJP#DdVh*j${J9T8JM7mGi29-4yb^ATTRA z6GfsgGD+M!Nnb$d5Az4k*}fzGqQa{uUw=wMrNe)gmXo$MiXsZ}M@Ry83>Qgvke4|B z2$IxI++P7VVC%;|&UM>Qc0VN64?2epfA|^sFj?6N|Lr|=tUC!D&KJWg3c*9a$t`fy zPhbT8qRexfef}AmzV;0RQqC$Tpe=tVu{KT!z1CJ z#DK4n*Kg-{Aw>2&SQ)_0o(*qLD2)iSQS~C6e`-569u!n#i$$5oMx6V1R^8)#XZG8v zhh;pY-m~j$3Bk78It2NK+ppD^`3v0E})q+Ms^Qv23 zz~p>s5rUcIjnGXz+jmO! z{KI>;+$I42g7=ldIx6DjYDzBP!N-Vmf5XG_(^+3UAacxgT?TJ|wqp%ttE^eQdW$47 zAZM$Mnvo2do_w(%Vhow~@0dyk69^9Upqz(yOHvS2AlrcJqPHR8YO#%K3agH8Mnh+` ze|RK-b4{hV@Z;X3TzDF}YudjJS>Y0Vd5{oMg3xd1WD*<-L~spzmxDTR!DSPozb%RG z-JuEM<%nc+G&PwligFPzj?hFwOnlB3+l1B8x-h-1S~#O&ocPlg!fd;Sek9`oIjueX zu481hBASXnH-B9H7%h-a*o3SHg=)c9rYHDDt`x|PT&@W_oHDul=uvp%ZKrDEbdc$vnV5(r&1M#^f z>hR^1kmA8%SwwU2p|in;F9OygiVvz6s(Iod`h9o&F}0W%^U+YO>;m52pFHl)mY_B< zzx4Hh2zlmpZ_JiEhMKThgL}4!v`6{xCs9?u;W?7OZnIldAJJB$u-@o@M)PgLkKFEb zQr~tQmuKLEmb*G5`=>-TLu1$?+4B@-NRmXXuDar_prc3B(ux-}xC$OC9Z8g~TQRa) z`ck4Q5!wQ`{snQUSYS!t2+PW=(W_JFa`V#4sUq?84T1}H%iKrb@Jp_o@!EKc+#N@R ze%-y^wd3UbPva4t(B;pIELZp5#yMq1s=q_>^^C#A!+)ji8B&M%>lGjKfh}C-K19~s ztq<-VWkyoTxkjZbX~sWdA@9I#q8 zE=_eyttC8rsVoqrC97HYfHy5!qvj4-r7;1M<>cF_SF0t&o=M(FXao8F&%t@2uNeMX z#|BEyDB|*&S1zPfB3(%>s8cgB1x&1!Q7$C}h5ebl=Rt~b!2!tXWoxj!b<`1=Qz8EnJs9qlXJcnr~3OsV6h7c)L^+_gB#%W&li}Z)@#v0DWs?AAp#}tlq@S#^| zP#`+g+zXw_k>Vrc;B^^gU2l!N3Rhh>4by{^tg~~Wsq;Dbd8?CaoP*OIpYY z!?TN2rvFDIwaOY%rh#-vpAwN#Ampk2c;qmiNotHJU8?C~lx>}Jn+{lgC!TPEgH2lX zUtX~X`z(BBKE-n1@(hdG9VJQ)3Fq{bTr&$aFlmTf6aUz8q|_UJMDR7Ct#j6nx18iC zio+j#HaN#<@-sO&1YJ7_f~n_ij=UImagoeiTEyNz517Q=BzucI zb#=}i;wq30c3cqi`k|=}<_#lk_*{ZPS1;cOAMJ;4MnVDCR#HLymnCv{c_AF;DJ%09 zFOuE#mv_zrsfH-x)cv`Z07X5?)-mt~wWOWuR`8USr6H7XDz7BNZ8MhJ8uH5v1KjZ2?;m_G)wvhVTjqt!uv9AA5b-OI2?(*y15xy8Y8XgG?M0k{K z1RlpLfG6?8*&9)`o(D6wK6U5ctx>|#_K9HFDn`hLrf3=I-64LAJ1bD;O7PobUzP1WPEGtbFV@3r8%B!cU$5AXhN z%-8S#T|2^=w~J2r<2a~Dy`CF%F9->Jh0^&mBjjCk3G?X^ z>9=+8;UV4+j?_GVx-Nu#~~rxj|C}zJB4u5J5hE?SZ8Z_NDVOKZL=6 z00IqEEVzDp9gltSJaJRWGj+|y`I-nW{Pd@55GCw6kKv}eGnqjDKAW76$#0(G`)qMf zHEUxL%z%~kNW~uqua?c1_A_y0Xkg(1VAp%!WBOegcaxdi-=!peK%cw7#1ndxT4#~O zaB))|@y7d{>x1iLMh71WYN}J@U66L?`^h522%6k6+&aQH?)tvUetd zV3m-B;zNzV>JWw7PWYv^qqO-kWV)vZ>(b?bxM#=@;Ut9S?%T4({>cZ1u%e|TB-|bz zh3_L0Z!McyDpmVjn-W-ZN3HYiRte{>)qLuij zK!O6XvIPLN>oYPy!r}Ka8Ofw`&l7*ULEL!rhbzoixO5@XNvM}R#W|83jx8t;qchl3 zO_JjUqm>sr5h+KBp@s3jmyf2BmTkaDz6ycebLOs_XLlgwggB1OGHk02B1^LZ$bzZX>xmk?0^E}^b@BL0tqhV<>)|y21%&azs z?CN_3a9h}DJedD2N5%I+GnL}~?EbFxWIMZ$d7^4CUamaI!1HCJuLI1VV_`BhlccuJ zr=6X2HcRl>#akG(EnWa=jPI-YP2RQ|Ve>RXNRrF*A0$IKH4B;q@^1b&{k9rG>a^6< zb{1*~A$#i_Mhb%62H^Uvy$@Gu_RsU(qj~RIfxXYUzl4MuFu!|^y?ze$aYA;YLI`5N z;|d1hI6}sR5u*)DJcWJYJ0S#_0^3Ql43Qnew?AC>t*b18SufxQ)E+cC%(Xka+|0#& z#x>^+lp@%>GoDErj*o{oRL?$8G|aW{8l)?7hHvA?+n9vmP20YPk5lCKgnA9}oU=vp z65=%!-|M&AZo*gU`N1!^qh)~k6roxCKa=@OLR*-q;qGt2LX)%SO*;>6j4|4MM^M*o z4mn>M_DlbpzV({O1VYT?@P;xNEnrm5lAF0W`(d1XwBC7iz3ad=h`f$F?Y8E3ns=GS zHxYX&6%*k{tTR?stzq$bswEhZG7UP+eu!Z!5A%7brYh|RsX1(@knDCBQnGr{J>df2lX;0cK-`_90%Y(#0wu5KW zi>YcqTX8kn(g}HfhTZoou=9TvwhyO|ex+Rc|5EP#Unw{3e<`>3SIWiyYB_f2xdu^h zHt2v&y-63l;}PY=M!z`0PxoG|Jz<E%IMJ*W~}p{uw{kKRjQ# zf@2d&|ICT=QxVi`~D#KOot~eMw&48ctT|6hV3kA%Tw-*L6i_Xc`O(d(t%G;P3IE&Ec^|#3s zn$Y5Jc4kizEf1P2*wfC>4XAe_0E^XG5pIKw$=PxbA%!3zV!!zc!>QhW^;JP_rKKs~ zvSSgB903TVC~YK@o*g9V4g4LeZLkP(8`|%8IhMUDI9}PLd6*S3-+Wm=`|nw0ivr1l zwg#J)VNgV(NG&4>uI1hXe7L;5{)C_dyDjZmO+J?k>w#ip+uMl2(t6NBvacfFuL$Zp zr&wDKA0ZIODs+()o3w#{FG&1vPGzfwX4uVl-j6`fO>5>5mj3Gm^y*N0baqT5Eq zWC?~vfjE$(8oBfB_03L5IM7hnhoc3~3g_GR!VB@C+2#7{D2JeP|N7=8d~qEa(rabYdKdhTF(L!;nr`OJEEzgEbBOzDBp< z%zbbLZIDVjt_C-U_cpJ$2JlVYaCaMho^OxIULBjsCz{Zbq)0yR?xj_sMR7E~56^b6p(@12E=D$1`HOlTj%5M7#(W=@RdxF(i{<1GvbNWQY$L6H8&Mi!WJC2L%5yM(?yt{njZ|i9(8uE@zh=?TEsQxzY!*; zTnO|A9Bpq8gctU8OFP~}imQ&K90#)rSUu@&Z}*THu*S0$pYIjpNzs6(s~rREh0Y|r zb}>uam|z$Ac(%O#WEb}lLC{;eOV!S-DibKNMA0i_6s;M#QEW`xCxRZexi-41nylaW}BQoGI4@@Tc3L+yAEASkvx zFzooQLC)&G+Ws0<^`5tTyLZQKPN3n`ktJd>C);oJTA4?1CHk2raHr|%rqusRgk+vv*r`(@alSEm( zz}o%88~&E<8*33Q7!uR`zbw9{nzD$;OgQdY?=iCFqh1 zvUW}aoTdWL^6cI#CMr_v7n!w9s5B)nsygLee^YpR3~vPS&3f$-NR)6kZYoGlI!i|p1d7E4JLC->LDhVO{qj0S&k5aHyo-uBz= zeW&QIqXIB&R$L+n!3_^KABX-aHv9~;dMLgb77I3NOa(zY1lAqsZz4{J&#pi2#nLYp z)xNUPQj6GDy-Tgf?^<5pxHARfi`Z;sl6Yb)Y`aAkpPdDw?5)3fJN0{IsEt~GQ`YnV zek&)Yfu~nS(>4jpy&8x^BG;#t3x-sS=nJuY!{7Kjr*#$$4GF-uQ;I)7xlQl4q$9yz z>Mn_LcL(vTvAj+Gk3k{@sYmB;hQNPYpWGJCU()f2EdZIC<(5L#E33P&dYL&xV|;nN z{3)@n)+X6kRF^SSyG7!ZYwU3nHf<=jF^ts=S)$+;mpBH*nPf%?1qZl<)+C7QME!rZn@BcKHc^hiZtmlP{agm1;x5eMj7o zkJ|@$@Bv4eCmdUo=&>F{UJInA%ZG2knmm-=i5Q_?oVzH~*Z*Ax+i4b_t zfytEY1+CbBLEU_rx`k{xte4a^JE%bZ)O-)sJ&RXhzg%1Z^~#v^=(JZ>E-jj7c<+HY zb7`I0emGU#LfCtAaCQ-bM&uN>_`@?HJ}A<&H`kQa<&U1tE2Wp#ffk+kimU3IYixB1 z-=9@MfmjE$h;v-AKcZtcJImMwVG#z76Lo2_H^+-*OT!RYwb@Aure)*2P!_hr$*Tao zFvCa5h^xK1D!A0vxkAZX@ttkYA1^bv;ZQ0pJ0Q#Cl`YvlU1ExTT4wNXvkM^k_`BE8EHK5U?Usokd$qjg z-adV%Q?B>4-|Dv?4j<~#F30iAU-8+keOK1s-K;k;6AZigVi^{LvMr*Z zqc_=P3|Z?~5t~bzM&f*Q*$=xvwt%oL;!i5^QSq$~#x^a&dU;Npd~Uy7-)L+z`uB78 zKc0)a3--hJgTk+wE;id-AU~ykmMYIx5596F(*Fm5c@O7Oiw3 zx9~UK6)~xsHwACEbvl*2?SuYxv(DBg(rqy_F&51s*_-usDdYo*=lK@|aX#FWS#uIm zaoS@1J@4Hzl;3SrEc6Zxi$<*SdG*%mXaKPHt(bYwRQ@_taw`4utAYo#k< zQpQNjw&$k3*F!>@+UDIlJePv%i>p*u}#KOlB%o^oyBF@*HFRH;6b_s0 z2*VVSmPo5j5q;C7>W@aT-lW1+ZG>t6Vr3oOOv5WcaG??+`cS!XlA+;8WU<|lGm~^8 zI)ly@8T=ni^_L}m&0HmYSyh7}VPZluH~4t2E(eJ`Pq9l#k8*3Ykte(0KO0wS4o?vl z*d^=UbWOkQjGC+X?v6HUl3}qx8^suo`fH=+7@`BTQL_y%i<+V~*R+Q!uHI>i@?5#2 zj>RFa3q77#9pP1$~9lPGb036QJ%|pW(y39Nze>yv=9doaMKBd;+OA$iTUP^ zEg@F~{}KO^=DLJ5vxiIT9!8oUDd*3X^ISxl>uX=RFaI@7@io#s=Y8c)5nms1jCjIS z=*x?kJRh5~>-VaaTMSvh*O~Xt+u*NNP)Uwsogp_?TU{+LZuX@aPzY7 z{_>#BS0EKQ?{)n9m(7{7mlq&1l9myH9qH;^Oi*P4R7sX2e!9Z6ba(a~09Ks1FDn<+ z@Bc4N{+D|F_8kRF&0WVLIqfe^TJ?KgE~MxJ(=la#XA)5c0E(vqAMfe43gP=nsSvfB z2fdo3&mjh=j_o=|L>0KQRs&6e>%{%d<=Vlodbeg?@!Hr;VY@WhUjn@^yuuGKR(UW& zxZqIrJEn9wlv=a!if8cD@nb|_O&H^G_C;^}E(MJ2>Wc?O)5xO#yNL=${M7ClD zHOh_%$LMjn%f1WsLViwr{>-)Kl8!~;?jv5!*Mpf2AY{8#EFct*MjkCf*BB>gjT5us z@d?n)&G)my{k4N%Rtb5!I`Q%@5;Gh=yh#nNCQwbbPKZ>)*7Kwhp;T3-x4$zDdTifB zG3WB^dfL!&uID{96Et^RL;LJq-AUYKow0Rd4|p=^jGYqM*~z%H-*khG zCh4-f@#yh)yqdobcE^(b7B6)&6OITGBdp#iYhde*6Pp`>Oe2{I9_RhG<0iyq60}xt zv9zw-{E~g^Mwm<(;(qA26S+JVaO5?=aUWrb8dzPOKAW6nUO)u0DbCI!kL$tCAf00= zE4%ouX4fD9cITtYHpNp-2kfs)4B4@`MBZk8D(3EzHV1Fdx~ikHNSZucM+LMF=12{>HG+*fTumh zw`LH>Nd!_AX>GmvY0@cU5X@;vaMj)4ybjcsZ9ON9$I)E0X)Bfak{1VbG_5DWReyiy zaqIs7+O%V^C&Bm8we`N?_&uxQ>CMUFiB|K|V`ZNAcAet;au9s#?~`D|00)Gg;As_U zY}w$ZuqhE4TCUnEllLb){x9gcny=yhk4hsDV-f%JFG;6k}Qr+{s@9U|| zXT8lieKk_80Jn6=A?0O^#jW;_a%hwn#_X< zAaI9qm#?+`MqV{HTvqA^_=fm@SogavuS#MrQ{AlBYPW8B>=7I5WG2BJjpVBO#%qnC zWXXJMjGtj*KxD8u+`Q(_-s!SI|K&l*UJV9ml8xOftByhL?i*-IB<7%R=qt*(p&!(m z%;NASy_sR!6&FC4!H#@O)th@tW2}IL;e6HUNi_d5^pioXZQU%_Da ze*B&8;Kdo2L*6Y8D>CLqZ-h05Aw;Z--e_nG-dR;16)Z2Hc)hn;{0{u{3@~BupTYbw zqz2;n?_`8n+C7^&)rzw-+We#Mcsu5`m-^2V zuAx}xnI+rBYjE4Se978`CEEjkzUjs7(h>~sPaU3T?_a&UCIKwQrw*kies#qMv|^M< zAj9vI{UB1Y?7?Qeb#N$i#H&nL9fG@NXR5yQ67j;0%gTf$A$$Anj;>A#j#>`IGxrV6 zp~(sT2(CB=F7b$;>jwfYb+m^S*R$)-#70tx7~fv!Sbv7?8NhI1SD!%`$63@G2fOM_ zEJUWKy$zjf4y;?-n9o+8S)D?4pY)RTKlw<29J+?iu(*>L3})SZS%(OC85(XX6EM&b z;}Gc7Q{BhB{dVUVMxHtM4aLF92`Buy#sM2e&V9pOUkThG;7Vj3M2R;ame3+ylni<# zJuKqM!rE|MnZWALpq|XPy~>kp_L&&Wt+#vtgnPYJ2eB*?BN4E5%JbDX;&B%82bzi^ z__MyH%#YnpL3AWuNQ~&A(hf7vy00^)VTXG6doD5aZ{F@EA62Q$6JFt)MAioqQ&p!) zC{|9IQ(yH4H#UgvF7Oj^0yfVK!ilYOOgYoMn+&EkR1s4=e*^Ya*x~!*=-`=l|8S~C zaVD+V0-`Tqas*&P*4vI`=SiQn1nenUDSuRZq zaD<)d{sxs}0E?IBd`zwwR0klJ=gIqq@Vl@Wo=_dT!)Dp)uBLWRIvIHdqkntqY=`K~ z_Tm{44P75g8mS|kfC^R#OE@7!w9Zg-8wInf=M!V&O^lDbC;8vlyba`aR2R0w62MIVzsaK{Frr8dCrH3is+dgk$jCPq}AL z2g?80byPy~c@BCFS4Q&^-31?wzOQ(#>u4DHiW42;8>&CL9RuEFDleIO&SmxEfrqa; z>y1cEp_GDz!vnGJP_Pe;d@(s`#(PxeY45CeiZbTo+uyxK^T^+m-iEN!rBqcMZ}(cN zis8ki{P9xuikL}jV&bT(<6c@7M*k(@?B5SG4@3^Mwzajs$JBo69zHBZpq`mh)gjC9 zA?XM8a@ILuv9?(@F|`fu;cDp)+ioKwuutH?+sSN)bliT z74)xaL*K|2-KuKE-QHP$!S3;5Q{M7QJRf!(1}*rK;kY7x);Z(ubT%fQb|V?%1F2F zeGh9452Kq&A21AXw`DwG(422hl@AU+Hd3JAm71RrzakFz2<||ynL8k>d5|-BA_xQ5 z&)kA7Y4bW94g`0AtncE1@TS-1Cms)@>D-{&Ia|_dS8iTvDc+bzV)7=3%HF)o%pDMZ zOYRw2?RHBcJ>;Kr6!VYFFYi5BInO!xB^gp`IpG|*wxmQa5F}Hu`^KUJw9WVL8EWn; zDP4kI9vj;4h#r8Ph^Gp^_w*}2&Utzt{_p>5%U5^t7i)aoU9VWw6u4=JYEylnW7O-J z_(UeG%6h1nDHu|YAH0gZD64}K3P4I;mptsi4X@*d_k*3^#0CC*m)9F~@9EF+zZw4l z6Q~+YeCBJf9G3O+(BU9l!gAd4x^kkr$MH%-Qsf_vu3uxZO2kwyWkCR6%gWe^bF3c? zTjICSmX(Jam{VRQ^|0UxKgYLTPga!Nfjbwa^2g*KjVv48M2%;9e+eGB&U>qFk$W

=^HcvPUb}w@{ug*DUjGR%(8$-L z3K7p9PZKc)@9N)0Y50DGBBn{=aQ2=T8y4wkq>=osE1}T{1 z&X*POnct0(Moc{%6Xy6Rw6Fp&-b4N}{QVF7eSWO$T`#Sr)pE+Pg-XanFyxltBEKT@ zus?6F{A{@r_q9S%mk-p4*QJQcoCt&xu6Y;wDgCb2GwIk@oJu}2?Dad_oJ={Re$Ic% z>yk$)sitV<3Skh>K_85xpa81{p?gHyqi%c)_C=XCH1wddWP z^Rx+g>e}x;y$pD#;kn|ZD6JR&NxP%H3n>);2+(%cJRHu5Qrz#1?BwQ@w+ecQMq4E|F|BFYHNnG@R1edjA?xom7P-jzOzoCxL7v z+P}e08mT7QMR$<&eR_NDQ@D4%=^4k!`Bg{n@jqnUY3_|Y>lz~u((2n3iIECOwpa63{@)sg( zLU;k>=gr^X?kv9rKhme3kA&f`p0q;47d|e2~5FALGh42`{Ma2CB z;Z%S>ZSmlAd(#NT?vu*y5lV4{D)+k~+|$aABH>L*P59%&B9*XBvVTj>z(b{^{)S?Y zdul@pvsJ?DQt7{`!a9|(RkHgiO_4^ZkknrhzUG$HU*dcCv(r2B(Bkdq18`oG?0=Wx zyeg@`xDRKORQkCLr%bYcCc|+_>P`Y@qon>TzNy4-RKhEgy^{i7FH7pZbd+6-%Xml5txj+3RIkt0i?Ef%S7qU5oGG&rSoJl~VhT0Gwwf zyH|#@LQ;F~(T9_@VU&NW{oho6LRQkLOH(Ro=C2(g-_F{Yo z>S~wNKM&wHT`FBE1DYn;R}2DD30A4SP==Esl`fUxOqJ{f1kPiUeKEdCU4KjJI$5$m zh2NyEX;SGT8CI%fUw9wZ1gU+V3~Rhpnj^y+C)pn-uq={&4wXFY``4KE2?KR}Sh8nQ z-)mLESV?WAj%wAy7^(d+@Z>-hHE^77&p=*M$3&@giVQD7lJ8L$jFLSKal@a@Kzs61 zdkQ6kGD!A^0ZN5i3GL=VNGc&#Y9A}ZiIGaj0FFu+DcO@KAzErrlKLnTr zB~F55Plz5V*&n(OCroM|DZ>esN=L}}gh=+`$RiAs?2%N}(`dROQt1#G1y-^LQ$n!R z9t1Q;0KQIAYmkj)FeeN*TW>?B2?XZ+IY+E@)?)Uw$Trdz+29u`b8UCIc|`ce%qPox#@DkU z2`6sX8s_?WUQzRVQaeJ=3cROtqiG@AFPbRMgu|iao~N3vNI>GZzyddM`zXQYuhfnW zD!(*VCu)_jzTCH8x!L3y!;^i(ErGPY*Ru5%J&@@*E==^N<$;pM&7>THHDLM5v-NXv zdT}k8?Qhe~PWs#>qh(#0$MW^^^m`ARk^?l>)k`rXfUz6${V9BR;QL|#rh%-zSXPt|))^}MT})%IB$`62 zdnKR%uqo4u$9>%VaW54X+|;^|weGf3N#G&q-btmGiZ--HYf85x`xG&=0yL{~fYsK4tzy%5Rry z6()84FRe5C%L@$cQXZ2#U2Reh7T;BUp!F(Qts0l|khIY+xGvi8*g)3_;L}xou=U>( zSz+drG=@E7g~D}f4dZ{5?8DZ7NYxi4=TBu&dCI&AsP;>`oE=i0s$EIBA{$hqywxt8 zA;P1Jep;LRir=M#3NDTkO-j70Wnkr^6iq|%yoezcHYrU!sc=BrW|>+=VlK3N1fNP(T(3p-v+mSC&^=vN2Yizaw36`&l$;Hl0F^PLl#xvqacpf2T9{F!Poli#Q{x3ZD{ZBk=Hp+O8rkr^{z|sl&_6G3G zc}JQ%T`w9bbB)xWDuOg7nVu?{o_~L1c`J1KK}0M9(s-(iddoqTg6uUrN( zn`B}xxKGUJ#@D3X-{@Pv`XMz9|G*RgM(*574owqIAIH@y1B66dTYn>EjMt0tl;PI| zHz-*GxG8}fV|YR0K2wvnUi%~5o+G$D7r-qGea#jhiFP;60B$aZ+fUm}^SSx7*EG=3 z(T&Sw+zyc(SSc$4Ep6Bb+_2ob|0ci_mxFdI5F+lNKju?wa;4SF^kO2Fvw+};g=hdr z4RBN$egYgrWE?|&NWW}?V|DUbnc&Sr=6{FCUiuj&jijk>Kesj8X?*d_PC!WgH~ zB*Q)NBe;6NEvX&Y6)7W}zNQ3_U3AqiO{xYh&nE-$19%)l`eto|CXjR+7>0}Hj^9Z| zT1#9qa83oz_s0m@Hb*huznlJ}ewP7! zNx%EU|JmMPNPGCwrC++h`u5nQ0c=#bfN<8?AHu1j{fHB3EtCDZU5 zlI+ktq&ft>)n(No*C!p@-w;&-$=`_ zD`tlF8WADT*b%V(qs=z!-k`7G2zm~boDN-kFIpfcDqud2tkGG?lw3H=2w0vBx4YAN< zLH5jAAS(A4C=V1X4_Z_~WmZ6fC~mYwvLih1iXKm`%X<69x0+p_pHRbgY;uEQTd2%= zkjVM!2w8TtDYTF|SMGYhfw9>*0AM2=ajLml8*DbRL1$A0*$Rm0C7kO50$ijfZ=QLM zRGV2|XYIagi>FXkQqOl#&v3b(1katBwV7A88_wSSU-g_O*Aw&NK--D&VdbtSPwlg9 z2R}f5K0cz{Qk#j639Vx$N=Ji+JQths547Wz;@FH@Jg>!gdJ65U?GMO1CW*K)fF)ov zL6p_T1U+9iv?NO`v6R?kF&_pI)&G&&px^ivAl7V)nWHl|-K~GZr7-0Bxgs^X7pG7^ z(7&Qd|H4chz!Ac$^E`!J1>f)B=v2a{VB0J@bN`6F2z`FRo_@8;8bn62PWNm zT58k+QlGLF>eT?O6yQ7=VGhAPpEBI?vx-_$)&8FCz_H$1-yrRNuFHZ zU{|VG=FNSs-{q}8V^Y=^p!?N_qx1QuSFIM zvQ&K~XW<6ZcaroSQftS9>ERHuEzM2H(jIZ;EOOe&gnFG!sC;$wVAeL0wOMLyelRPs z_obbOBlvhKw~l$R$dQBj_KP50v&2>@y5y|1XmH0uNA?z-sv#Syp9!w;k zJ-T~rdp#-tiewL`48{JJm^@Lu9Z^ z;%vO1Ph9pq-c3k0QIa>{dq4>QMJdBSwW3iVc9@sj%$jxE_*$A=hmGsgQ|8NIN!nw zHczqW<(;H+s@33x;may?Wm|U=D^%hi3X$48MOkFtk%bk?JcVN^3%-@#+|Rv2!)6zW zd~PXET|3WVOvcQdw4=F*I>LJh6OsE@WuSb_wVV3ox%N;W6e?t{ zUHd>6y?%F)tZFjXUb>sQ0ZZ$Fxi*wgwH)ib+{1o5G>PG4s(luHvK6q;B5?lcQ_~R^ zBfN#M9`6p~8@$N6s{dS1s?v}xapTOS8=XoSY|X~MkwW)NXr7#oyD<|jM%|=$OyE@p zqn}&yFiEU@_+H{qN#cJE_Bk}Dg`qS{j20%Q>N?Wflp!QMCnL17f&CCKoM_mb6-WbKmu9};9(_#?*o zG9<0KZGegXk~kUPxWUBi=*B;gFSlQEmXGN$OR=zu~(KlhxTB#+P!CU2}D zi5sEIhh;%IhNkck5pYB%hI46LAG}i(Z&Gq?tOIP%$=>5h(T%T=Y=0n zN|ntE^ne0}E0Av_C@LtBFC-`umy>B!_=fb1qIn#rWZ7q%8Wc4@lMX$BQbkhgga`0^ zlHmC(S>ncQ5-9P3vUg&rm|n^42{OH2-}WQ^zHboiY{0lS-QPOh|G-p2nQH32Kb%YU z4`z6bWJvS3rahR!^udqQ9~ew;A?e5ZTgN__KJE3iSCSM-;i#^C7-f3>O81ZO`}1IS zo@9^px5hr09aKzXlENW(DAHax)r{m*=OxvQRg^C=eK3+w`r!UNuoioO;PLR&&?VfJ zDz&(Lt~~8Rki5&j4sokVJl4H;C6lHjOr3(k2_cIXHjyUa74))#X$`dRj&$faKiYJt zczsuaV&uZF8G8aEN0bzV@`@O8&twAbosU{vpyw5_B|NP!#KS`+e5j}xr8nu9k4{R@ zSkS_Ly}oDR-uwb((E9FOr5h(KoHZW>nExqFDhOkV;}fDb64<|@;FbKLO}vV3Yrg}p zMWRy4XOdZ-S1H7RjHF`tOp@B95i`k@S1#V!(;y21L>40q3UyxJSMCs6q$Eg=_iaAN zy!atJKg*s`k&u_BPhAKFXa3F z3G6KI;V7YxsNGl=9(&lD-I%+$<2qNgE6RH;%HjwH49>2xB$&9b)VRteA;Ho?yAu+R zj$`22aQmB?Q*B!i+lpz}L|a14QZ^!us%@hwT;Bbi@X47nKV z9n4@Mjrzrl*Mj{O$cL_+H?7*KWCfdzCIPNVq6LCsnI0%h{HXBEe!R^IbVt zigUh_@}_e}rQ4WRl{RZ9_=-YKApG(#plfCRp%rdpx}C+oRM@EMGm>Mpid#S?UZdas z7JQU!`Al*xa+@X-eXl8~7Mc*E6*L?K-&lQGzxeBb8m2)d!>suV9)2qG&!t!Y z=E*jW+Q0Ag>q9;DdhaZP6+U*FYLlM}5=;eZYVqRnCGUjp-XdYSn%c61y7yeP&-@!{@cnzk@SaOa4@u+JD{A)@MW+;ou+ODT)Tc$8 zpO*lqXkY!?=3kIa1pL6>%elkmVkuQoHBVS`J5}qAn-*w$9V((GhF#{BByFw2{47$X z*XdJ~I}1-Pp=(6l{{&uNQlzG+{ctuQm#{L)`iCXfaM9nABklnEhewyF{Qh-D)!mPO0( zoE& z>0+!Ueq($n%I%?qMc&(Q87i@Ru?JL_Zsio6Dv`B{bkzxml~M9v>zI9kY03E*k{ zmm~>%eF}rUCT>H7@0f0m&TtE7YE5suXXBOk zuwJ-Bev9#EV{QfKEj%!URXH*j2dV)&it@9AxsEqv@2+#`!h=I=x`ui)$+*S`GCgAP z{@n@x7Mbg!{9a^k?ls|%HM>*HB&Rh*rg!6kV0Y&7fjk5*dG>~_7mrt!l-$_TB5mG$ zW8;BgqGzc%Z$cnhDUD^D{6l1J>@|%L8Hqo37wo6kq7|1A9tq7D>mafy!!H?WJ4MX; zqhPO-A#RwX6*E@{z{va#ZMQ$HmSLHix$uiG&o^E&_tgA3d@#PIQRhk5!`Oq{G|YDV z5pgtKsEum##IwP(>V#%OBv}=p6b_Q-WcIgEZV2_{8CKG5o(ylBUZ^EMZ3=gjr-EI1 z@O^Ka(`H*5Ktre|apGqRxa^FvX`iwcMA@`Y+Y0dfQ(M6(oAw!-Z7q`8!spl=6Y(%7 z*sERanO$MCt;a97Hh=S{8`^9y;d%Wzx3*xjN4frzEo|!Mts$OmdbeXLB3ibEc(qGB z9_7`#(0eb}AM|Vs5w%N8N|YC10=rFb75#za?)cbOgZ7Qky&7y$Y_`~*1%$zwcO~KV zvR=_dT=-F22j*PA#LLP>8vXX=z&kVE#Zg=vS!QW)LL zV9-n<4dRWT%qBN^T57fqVZ)(e%vjPT-;`z8;Ut>#=R z@r)t(t7 zy}3t%V8ZRE%&|~^_VcMi7f4*0fYu)#j5C9b@Db$Wb_Hnv8=3)eyCH$nI!8_j45cvF^fm;|0P51|SHxNK3~ zdcZ#SmgIY84B?cp&n*vOe_MT1s;SV6_w94nHU{0qj^~f;bJszhC^;0HvHs22jPX^m z8CTn4GospKGfoDN%GmR=%s*=^5kjxDh3r35aAC6LrsOW7@qe3X%MEE;D*2a1{^gN> zgmVyNe=^!ma5S9jOUAh&DF1kV5t;V?CGBL+WwSBOEW4ufdkM8e2HzP>?iA@La<3uz z&Pv!5Ju7tdk^V%~Ru42sIQsElDErjs&?XBJ&P0tOd>%U8E~@%AU^2#^jFBnkMI*&cF}!)WW!7IAGcNjRYNt0vr;5g_-}X>BRKT zbbc+h9MVJo{1@7AL2e9Vj|2JF zI(dmj_AF%nT;j8}Y0-Rk5T8v1mPP5LC!7p|8+=_&yTp#OEG7Ked0Z~T_qpW!Sc2b6 zHjFPM?|sMM$pPB$Y8qzju~!wK!)VZXGH4Ksuyuq?2i&hhYP>zz{ENGm&uEL{(%!fT zDN1 z^nC~*sEuzgID~?Ck_q6u@57*1bpw7jP?m7mUw#{7pxi6`+mD`vlTXb3mCB9)y?h@?h6DckCt@}k zQu<5`&p(5XijG;8ZunkGiU#oq-9q_3z^IJ98Ueb8fbKETqcRvg|0l^l^|LtzA^RbF z_g|Ya^$NmY@D8$pbEn)En<8_f`%r~d*o6vgF=BMz?nKMRuw&R2zFHdPp*<@6F!SZY zX^W9)eL+dzP6^!;iaod|k~U4s5XDaCv2siMNO}l<(ajobF@mu+~+J zafy~VlPFs*Afsp?TU6$DDaGPVdBwUrH54xAOU8LFj0>IQjx@JQ-!g160ShpFiq4Ou znm1`n^$na=YX7IyiRGXi>4fcX0%WnM02R1j(ku`12HHoHyw$%6)G;6unuFguiUD=T`9N$*SFoD3S8HBTO0M5?;6OQd39AAYDXLEc2pUpV? za>Ky;ao${T_e0_owU-QQ0c#R)`u&5j>a&v_0Vu2%dSEeI3k1dNAW`NLX@pA{Uz1^@ zo;Bl#PSMp&7>X-eCJvpWtC={IYYN)$aC_F3&vMtC+x+H|V+BpsMdh=bYR>IGw8Uje zz?uAqD0K|Q?w?c}#vY$r*Rpw&=skRMcb!;Q3vJQn9in+ff8M-~U!-Q%FR{d>)rWV4 zfd!f@F<*7q-iXuUdEeVZ3&VmlQf{=w!R>mB$Gds=%b~pISca=*bX|taV`%!+Q|r-> zZt}cm)*B5Tz6C9lu}j1a89)Zeaksx$<5Dk-m-UcAR)W^&F;1etk>}N#mn1AkgwuDq z>~QOhe%mS9ro04u$KH6RG>gi~{@!ZsFMy>$JXMeoc|lEW`Hxh9W0LJOY{L^S28)9} zwc2Tl)fCIWU?ZR`P9*zS7c^9Z+WFzIER`+(nL}-lW<&Q)j&8H;!hpv&Y!P)dGi&}X zy%^1EK>T}@e=*&AJOU7ehloJYpoG2?eHYoeI<3v4vdN6WdP1_HJ4M*gYJ-eDDLv^4 z^WnLHuFH{|aY+YW5C$;qv8oxo`{>%rH$J*xWda==FW2SV^a< zyq={ar@{YJu{;Vf{!ob-?oT@RNbFPWE^Lg{IBB6lveN`4xFO+rY=D-&B1w4VE^Ks! zn|H`EM|(;5n}2T-kp-%}H9r~J*(-gk1C$TF4#F}6{udU@H}J(?4MF?FL(gz7FcyqU zC878(m#z`I@3_y<-k?iwX~9(YjxGQ+u1)0)gMTZE8>bSJV$bCfCVipzK_-1@yBcPl zS0En7T+mU_Fw}2qzbUcnM458J*MxzC-1jM-l%7Ti=ltmaAHSiO$5PFck}&r!w_PRF z-|FS(k-|TN!nDeIq*vZ~dH&9x@u5-R5Ot{Pak`cC`ECVU)eY!)$O3arkVLGG?@8bwnWkLC(1_iWyf%&HX zAsJ6&jwB@9<)YySkKvjWgdlJB5)o!#(!yPjl>>FZ{$F*6h!f~G&d2ZJlNaD6HM1nB z{td(Ka+k?!vv-^cpbf9|4)Qg~@X?Vthf@|ElM46&mQFfgHtw_Y#0B`#40(+C`?@+OU@W+lPYqWS_WpB);2P-g|Jr<}y$~dKP zi4eCe+Lj$;kvSDgtjWBGJ9w2bLlV0CxhH7hF%&qAP^E$#aKeEl+!h3#AraH&jtby6 zMG{W;|A2P0e?&Xi|DSd>lkb&J1!M@{B=F(2hL(P=4#O(SFsWA-N1x%|CTDg!vh8H) zLj@)U-ZPxXbmXB?FI0xqXJU{n6d@^>En(vyoH>vxB~E{j&d%|mGpVmx65i?Oeo4%W ze2v2cH6%Ry5lQg$*ArQ!mmh8Add)-bU~_h0F(v3QP#HdpY;c+I7Ai74p~OJ`qJjBj zj3oT7pF67%zUk}bCkd)v)aJpaNsp=h5q(I157b1SLwrg1Xak&_36kMg{Z$8rZ*KEo z6PPbg+})crgbkB%AxrfK_M%+(){@YT46KS;{ux+rLTuOJ9wx$~@eJY=Qx4!z;@&F=Rkcv^#;tuist&hq@&S}kge1Ch7cn9iHhUEQ~; z2Db6z2xMUBrJmO{AN*AawnT<-NxlpHjuo&?Pg-{wkh=lf(EKEE|U1 zS#bsdlByQozHNzvP82`DgW30sml|xR7|TM6pGM||RJGwvB;ab9vBX*%Nl1SNzUDvN zv~InPb7+HBlLq%~FK;M6=t7eRmNQ}joNw}7Px$e?F2f&GrV|{dmobEAj{~8 zR*#?_9T08}{~3^U(YW^}Fn0j?2*c_#{&ZX)4KXiYzI^*!lL77=i2!C?Wqy< z^HP~W^v=kR+wuiN!l$1g8gvI)j>Yef5ay8N=(d3oh^lhgia{J$h2aFj0s`TKSd3LH z3d{*czjl>wQgn)%#&9jDrip~uHYg$9piJ@QUQ8_0&3dHfb|A zO}n$nn03<(2A(^cj9TbI+_a)B8mu8e$fR_4_Habts|8~J1rw~0YCUA^ zPld8jR-0r_vz8f<&`Bf&(v>Lvf2S2&Lr7xYN;JrULt_{pZgkJ=BS`v{teP3$>vl~Q20y`fw_zjjBm=Jg? zsS`dRa{Uvt&kVr2N#=wH`cPSP*a`)|f{YK}ms*~dhX@%XTTa|!qs1?1Z`S9CtLkz! zRaLT#R~sI@iH$DtZV;1J<4)wnD0yTNjT7<+Ew|Vaq*7U(Y>+#v%bj&9fCC}cm2I-V zLfCf;@)4w!HV@V0(RybR@YT1Zwj!cjG|nGR(#D*W`-8du7R$7GOt3Snz9aEVcz#J7 zza*YtV&s=3@JkYrLD(ht;UyM+$vFH(W_f(y%E~m&>zJ0?rNI0F8D?n?uG5`!2Sc+- zTZMGaf3uvSjXKVa?dG+O?kU;Jn^t#d|cuCRsvvS&5)YS zez0zSNi4ra?oHREn(w5V7l$;!X?y^GWBm|gGmAu<0shc#nQrFgw_Z}1=H+^Wyk1kz z&u);VDp?9okr}5h2omm!pA?*>-POs~@H;SVlS{YR=iAOQ?)l-s*=B?h*fZW`P-)Bk zf{5APC6f)#r!h_H`Gg*)SYAE9&_bN5*%a01aGKXSd3d{$ zD#CVUK|=BcHD$KlnmG?iW3M(Ps)+DgHXOKzLXY%5{q zc%NF|_st}G{DfK%lBt^K1Jok4y4sg&6)Mo}r}XG}ePZpKswA;YtaS2^I5co(bvv6t-sU zNcK@#i|c$9b{M6R7^2(zh&}BYM&G8#=^wXtNRM_{w|3~ZEp9ElO>k?2x2o&~2fjHl*_dNjA##ZKO(ZOGLoCE=7f7ulK1jvithUaZU^{P1jlVkPds(*4d!J2qX-hgn#4dWv^LQ(4TdjY$du&=u~Aa%+{EEk|_kyH}Irs%3hL(BH94t)cTYM?Z$Swgil)czcH zWo^FjpQA|Apv>v(AzYmp4Gq{_cY%%{A-sXGoY3@3Leo`>nD;?f9yA@tlrE!8+`2IS zC}?W=_-pLYB(=_NOWYb01A7fRace}ALME!>L89t9FA<`ak|EB2eA&4+jL#p+A7_YF z($3D>FO#m3DlaFfe;plqpQ3s4=|JS+f_vH`uD+)?eA;8f?tx6xo_sQe$~1-db#6sS zO!BOKyawt+LO>ow)zJFUASy2tHIQ7`P3lhQ%7Ly|_qPi5eva-*p8x9{+LG|(->9gZRHd}4$^$d6VO4IyqrXlFIr@N; zjlj6vzP*W0aL*$fP9xuBVdI;)FO6mub#Jo@cR_-;Aki&5N_X=Kn=7sEEIK)8^EBA9 zFt#jWiDL)FqKfu-Zj@Ap>g#rkDjbLlEh*ExRn%q|{;Nv1(ei_)WLv01rQZCyK5z8?^g@wc`{(AhurUi$ac{`(11&8dwtW9hP1)#e=?>oH3O7ZLo>m!^J#%JMmJtqS z!42YDc)7X*NI_;z4NDE*^|r6(Zbx?DT&Li_&OY=l-F6sPNq2<>^Pbw#b)qRsraV`7 z_ZW>+qhynvmkG_7$MoP_B(^q)LY^?ismb=K*T92H5OBXvM>x(v+QM`No`)RJkS-{( zVb~-v?axv+p3aJJC`T^zJ;E!8^(ce8mAWJ|uN<0W;FUv?LU|?I`7N1FWNrc?I!)C2 z8>LTU%oHf2b8}(RG>x0U{Lj4q446IRrc(-zWQ}iUI+P;_shyz?Wel|-bZ)M`KpC}o z0shC96w>m;LnVcw#mZ5Om+4b}x!aw{h>42AAXTB3v5%(~Zex~3t=aqm=)G?O=w0$o zOG{nL_m>&_SPIHZxT|c2g)j~%9gcG6M*v^p3({XL`61@+YnX!FhKS8O^&k|YKr738 ze-@QAIR`BdM^8nlG%B}AR>bAv8^7Zs#~c{`f^)qS?8ka<&CI( z(iTE8fskwsNS2h3=`1OS2Q96qgVZsc#-h@Dn%4%w}9 z$0hDdrRV6jZ{1w0&k7TlB)FF(W<}JmD5BEO4f^FD?tf^a9CSdaCd7+%&W~xcbIN_M;R?Fye^tXAPwj`1=p=ZA97Bb zjk%^qE$=EH%O@Al3BMwAZ%|lYzBVYg%Crq}H3g`fm1SPnn=(EmEo=Q(uBI$4dBpV+ zEvBZx1*n569O?kh8zn%#c=h7+sn;$~pSop^jm!ZsdK6}N^VXQz4&EC3R55QIHQUWw z9|B^tZRTay3i3mW^Fw*7{;2}qO4b-S!q}!R;1_U(>U?8=K>{^n;?o&xN?=D?z|Sw% z#E=^4sBd-WH4RF*f4a*wGs0I=>z4t62O@q~>)h_vl$c>I1@2qJEf1n;0j|5vxkct) z)RnwSRdk+)LGJw4(*aBCi}a@wWLlA-+2FldqeMng;tKULjHgmBGDEv>%4L#%z0d3Z0ZSpsa8k5j?Fv?VU~%2%j`Z!?z@bLr& z(TtkN>!uS7`zFql*kmIN&;-9f#c%82Z^3sH@)s9Hmv_6uYNKY=`AVjhr#CZBJ0M&{ z-LD`Fy)k2I2E|Yp@T|h~7@V zxbuE8&We_V9!kggCEAk1U{BaOAPG5f2nH5*sT#{?3a^zY8%ym|Rp zAlhXJDUZ%=ppa-}o%hLQ$lJt56^omou z6n#=hljNR;kSqj7N{W#4SKN)b)EDgBB z#}@x6p1^SN+_*!s#ZSS{n#r7RBA2RY)}h5*|J7nG6jg%uIfw8v_#1eo;SV=>K9=iJ za)-61=QPDLvNB;e=TesRP1Bn~gky&{xpZTelz?@D?$K*?@m%6r)8 ztnmF2&;GqTd}v#EFxCRl;RJDnDN~2OGW=Vb!{E$)rQZ~83Io+N7em;U=veTrAdEVU zk;xs$WQdGxH1V}ERd+%GF<99Y9$Xs*SOiQH`qkgjmy{GumEfDw{{)Uu0p2r=f?Q+% z`HcchOvQl?aI1m+@+qnFy41M*h_gg)f1*uHng)9{SgR4M4sfz>rJ7$8Qwz%Kyn*Sh ze!O+*4bYU>ZDy=JH{Y6nBTHHSFYDs}WGTJz)6jk9=&)02eTpQysI)$b=*L1bOf&keH{>F%0`0m=!lDd|XI?u_v(03;+ zZ1X6aJRa;DMh45ae?YP(BG|$NeXArGrme9s+O&KNqe;uLFzPg`g;AxMEsQeFU{7^~@TyR#iMrw!s9qepk8{q|Y9%JDZDJifD8)5!HTKImrTnLIAii4!i zeGzi=G`@!u+s0-hNT3f0>#>)B`pHq`_t;*XQ65U1G;ZObXs=!5(xSZriu@gDlSiQo zTaWRr$9#!($>PN~%57NN<}Sqopl3(Jm$&^GtG!aA=7?{Z+z<|BZJ{y78=uUr2sZ@% zhwR*tr8~B0mJ$)06r8{@c009e9N&dYpdHMu8uhfXx-02WrH+aqM+23e-SAKg?HX=; zaTZ9#a`GuyP8w-c!Zuo=S;{vZS7I#;J;K+dciFYGb-?mxFG7lf0)o<%!aO+F5 zW7;kJZu0E5bpnee+L~B(>`Nzg>5!H`S2?1>S=Bv%GjId`yt=!Y6ugo!7WNxJYTKew17p1pCel zYK)X3WkJHD^3w^XNZD8~;ldU9CmWNcYxS4tVLPqP4~+&*uC{*@TN z``c$sjnHOL+womM#>U(p+8X#~qWt4EbMbznfpO$NT#!Gu+>wW;K0;ZNr$+~^o!RCoiT<#_ki59A#q&%B@%@tO&Y#qlKcPFH zkji&nl^0$VS==54J3*c0DskDgJI=yg zqRwk}wWE$Wgb_CmD?H#lW?ae(C8EK+y0Yb+B&Pj@#5vd4R5W{i1{@f-(Qd;d+yM$A zoft%Ke4DXAZmxw_hmS zK{pFWC^`~juhtLW(t&s0q_gi1XG-g7Sn;3Gh=#ET4~(f5{?v-ToqKknF@jD6 ztZg0&sMUO;+e|1=Sw}M4%QPNUuo;pq@d*j@82c*dAwA$M(I28nv~{5S3#&-k zXmND*+|i4^b~5TEbn1&K=_(sHq?jA}?+T{<8QQ|JDVHnI%$z^h(msmSzVnK~s~+X> zoL{&-ssS#NF{lW=CV;l7o>y=)-CBTj7?Qol$qwvBCB=%<39sVd?evUAb-OC=uI5{1 zmtkzPy3Oz~$ytlpjD4yd+iSZ@o3%g_n!o^1VFw{JNDF>S8%Hj1SdGY#^I@;sD9dm` zpun>z_FOvLwff~`z1)57ZWY=*J$z&d?{O&-|xrPQNI zZ$!xhKI*YYgWiCv@Sn=(Nn|*sPf-qez}ugo#&pcq9yKvAg~#rwjg->4gUEB(wRuTp zccAO^&SvaT8mZ(ZxJq7v%j!Y01XrmB7T}eBQpP8g{bQ<4hSIF^wv7WEA)U07I)m!m z?1uy}3v_ed@T(uCs4cIOJnD}qQKil`JyJT6^wa-OF@pb%N~Zk-%4+Jt;O1tkn%bdC zC%r<@lX67bh%PbG1#fiL)LwTyBg)+Zc!0s=9@I3b-0|V$QAZ<*7$1#1o(UDQ+hIpO z!I$h3HK;HT;Mw=RAN;=RvKXJp^(neL2uA}y+x7XcKHjw#K3Y&Oa`2r3DBm?dcbs;| zTe#))c~yX~P4>nUzJ@Lb!{B@i6s%)hn-;hY=DB4p@0b{Sxn%9V2ByHRRqnDkD|6Uh zuVI|)6@sjmTBSPyBlXX*K56r?q<+`s5$V0L-HpvE@6GM*u2$IQG{T={kxAppo+CJkc>*iR^(J4+&}9b#0i!b&^!0I?rS6Qjt{05 zVBbBAsvCkSMART6qG}FePj_Wd* zEz<}`BFPRQ#o#!bB(*;(QF~W1I2bBCe@!$QIPGV9XEW^?Qu|EouTo7PYfv$#Q6WN{ z8{y8{6aZ5CbIH-pt8e)!M|+I@du;o4V$3Jq8w3i3S>;DL@f+F_&}k@VcTrvOC_;joL& zE9$sO((pQR(?QMGa#HKeYnAi&n}R>|Cd~}4J7DrIpV{%|fprIpfGFwfl{MRnDqXmA z)>Rekdf)J~mP)NYNiWObcA8k+8M}4H`I+TUU_aUnZ$*6kik)w#!Me+2S-Ju+;BbqG zJZFilbOv&srxZJnI7_n&b#=XlvwW=>O{~6H&yHxO^D<3Ny?)QkMr-liq#V!q zyZj9H$bac zcN%~3XY~2<%j6j+j)gVkXRdBe^{K1IDJYWF=4KC3r_gTI$nxa`LRoI=tOSuMHB!P~ z$W5~Kslth?KoE~)1(7Elzv|MKUlfji1M3*CiL5P4l@ukklSEzrQS~n<%|gz_Q{Z=guM?yP8IeL$j5~Dzj0{?04peAH%U^f72ZSS zraEuo0v49T`b|W{=s2_A>V9wT_BS_gs@S=PyGV(Dqlpy~5$kb}_8ReTOyvSrwfT=K zch-KqtF(%rw6G&e7FFPAdTtn1ud2;wSAr^t6UGGS)c9I}Y>6_RHl>TFA&j!_tQ4fd zom7cMvU}j^L$JStH$J6p%Wtkets??XL@-xIm29=T=M6;4dh*zIS&rrQ4{yEeVlK=^K=TBWk4ekU#@>>xJpm6;zXwj!~H=>c^xkWQNWCFr-2K z1*vS!Uv*uEA=qeL{EogWe+b_Aa;Bf@%+2Q6u-Pi?V9m`7;e1L*V$uvBQ(8iu%Y|xf z*qxrY>#$tE=5HL?;#(>6KPXKv(%!L>%*->`}{^@F`?_=s?Fn^^ z$DwjmPAq9wK5`h}M)M1XAtgRFN3EW@H(WXVvHrO{*~X12cFZGPV`I~j$}PEy^07%yyQu3_X)7i)jV?}+J%gTFpCswBMXs3d4xMf8VX!=uk>$3@0=HL4> zhK1f3!pp4?XsK=kd#3RiVbL`d4!^-Obx!XclG7GBbmX))gVMHuj4phPzmx2cL3j^w zLX8@saeOBtum)nq*sJ@i2fDKGIvF^nM`c~vF6epRL(rs9lnOcqI)kDvl5^RCP4uo`$0lI_bIv{ z=oBBXbjz+Bd@&l~k!z`1vRx9s-hA?-lsd2FbJ|m5_0)Or$*6tn4l)>f)Wxz9G~O9MC-2hrY_ds>&P2Lce{cb=d@$5Yi%k{X3R{mN zv$I}mY>;@_Zr3=$U#dpAeBtn+_wZAb%~tp?A?Wg+p#=(C;_u^OAwCkXcn^`#`ONu< zBS_5FL0kxeNmoN~%}^z;$mF_dufpcsgKMa0Ho3Dxg6{^e3@UJj|6xC0ZPPC(0Tk!H zkOoyvONe?L#WR`ZVWp42VO=a27K|+xUejL~#s8Bc`-? z9Jk3Ddp69bu!S^G1%D-UNX4g};-L)&-Q*i(et z;^uDr7t=nIa$w&tqCj=3l&q8BLfo4;nX4nx3s}DK{UH1#61=Cy*+ib5Pln5pk< z*G1r)f6jOy!pl3bv05BY6(=TNfCaFoxWM7%=apZUH{?lf>@p~A1@q()*D!=-dsHWz z<=JIh#LAmlj)M54xw#>ZrAe%+AbzrAn!JMpr(%yUnz%69#Ph2bx<^3oSZ)1sEp+ra zCDtf>1h7W6JlF8N2AW{U(#LVamwykc1FD%t!?0)d@get`#`rakMaXv3=3ic##W%n) zA!8OH+q8s?(!V9eB}$U4Ugt1dyXYP^M=>M7L$7dlZ?SO#UP z78O|~JUT!Y&>1u&_$k&5?}OK!Lwiwriqc~*cw#;!FBon~P@UeAI&Vphb3ZcPzANuR zt(o&3%et7N8OtiUg40X^#~kH`6r84Gv;}H^LHpgs$2Pp#5%b#y+7}3Ui?mAehUHzi|MJ-S%9Z#jw#gTNe%q;P+dYu(7GKr+Ijvn*E zi!_O52BVn=qEqQH&%KC9MR8z%Gg9$ik>~alM=A%Sl@CM*K*wybm0K4s9*tT@ zm%PwYoJ;Jk3L|12k<47jc>My8#kjp(vHUqpLa=q81SfSF)AcjwVas4>v$}y{*CVxa zY7j2VB|m*F8nSh;jvl$OjJC`mLoJma2{dhT{Q}R$kyM~Q98l3-CrI{yyH zSG4h~yI?MIA2`9pjKThXW(ZM;V{M21{#|7MfAF_(>06eO&;HB+oc~AIx4<=VrF~B( z7m_e4*N9wfG7vz;7D8LV+6n;!UfLB@ytLgFG>E;tucBM6Yq!bJLR5SgLtDYp?l2lb zl!|Gqc-tbjNGEDdeE&01yWjhJzwhOj;mn*l=ghf2=Q+>SaP1Pz z$FGEPjX+z`fhaw3sIJ#)Zy&O5MFPS6(Tj)C&`{aT{3 zOIInKJPo0)oTwKVwXI2C`o1aWxQq+hEb!sBo-|(cgEy9A%0Jqs1%2BXG;Lq{w_RyD zeE78MemrORWruRwIzJnz2wHxtzP4W}?D&!2>bHB9+R3MuZ`2RJqIB-~qI{#@1&4nl zq{+mW14r`~)Y@`PSiII_eBJI=d9(IePlS6+@U1C+$Ocu4cmCM%=8vU`{^WB+n@g zq+4Tg0zfnbrGUE0b9!Sn}%(rqR+NDz?eLVZZq zGjulQU2~qM1x?mDEf{2*DGWU(nP>li$`^XQmjEAZv37`HvXcmKI9J4KGRw#|U_2ul z=8y^XGYsC2mv~qa-MuLDJg!4tSdpVp0gp8)l+&i`Z8IaM&AT8|al0 ze=w;%pAW$Mi8D~g#9q@ti@sFj+a-?|6!b5l!#b`)_5w9yLS3H@sGg*3C4M%$p}brH zlAt9XXtlfnN)rm;zLKc5@e|P@v%RCwb!g@lq)k<%mZZA4);+hl0WaJ0x zQZ4%YW3+j?4!c77RJ>qE@NlSp6|QAt6#${A z8^gF2Pk8**S* zqfe~nlHIe@r%hKT2V@0K*_^QcYVK2-$^f!61~pDf^wOq9{!UX`RwRJic*8BLt)105u{QKWZ)Qo5*1Ii{WBuTH`}s)>hwf zve{(SwTsv?Opyxcc)=6~U?tKLo7;=TvMneg;oE&M&V~wya({fS9zD#{ZoB>Dl|mS#sYTc6!1S`=pf9fpcRZn6o)-U_zWXE-?I1JgnQv%{ft~ zoLGF139Q*6n#|Kp<{UiX=eZcjj1hSG!Ftj2d?0LFjXStiwBjy|8E2>!kJ85H0)ZVM z-t}zY!Oc*}V#ZmgAkRSo7UZqtVSX#X3w!hzmhJklfPaTQ#+L@lF=~brzh3ELYfg;5 zj&s-x-#`1NC6I&Ba)k;KtyiVzzRkFjy>}h`UwjCA`<1f z8;D!uZLw}aUenL*M+p6p;(~liqj|VqT>(!L1cPr-Fp5GIm~vh{C$n|qs-GwjwV$+` z12R$*;mj!mW#K0+*?(ZB{?mIl0pZ!JlXF7?j?WDc;P}Bl*Az0pu;17maQ{wYkFo7f z+kHvt*-R)1F4%q{Ml@Gq?xR2S&WCzEPhgIo#2iH#@9wi^k}~YYzs6?8j2N=2r*3v_ z)sxH`>CniGW@vZK2^_`uIyY82HPpFLqaDtg6B`|bxc{if!`PUO=e=_8zkyeN5p}Kx z9``Q6JT-GxBj~BN2 zuddm%6Qx{WC`ZlK!ls>9L$efcxdFXB604w)=g33Q>Pj4FB`!ayy6pH5(i-=q^Qp_q zr&Ls~=L$BOXA=z0Hp#!z4&qm8M%tT>6>9Trm3cNHl7JVKsb_{$!Ku`&nn~)cG;>xo zqRq$XqM(e$Gxa$$$UI=k#3Dy`Y~$u^G84_{jb%ChFw;YDhxn({{5mkZ!K;NP+md7+9Q*=w9lb7ZTX2@9*JzFeUDb zJE?ufXlY#RgI5@>BTLB77V@VHIh&EQ)JdvuL5)JKRziTnyfWOq0&xY%&uupu?p(oZ zNR$EXJ2%^K`wCR)%8nUsc@PRLp{uvbpdUyQ#nMc`uKBVDXUAyz`Iq`)lC$icSAOP( zIkNVj;$l2DV0u^=gjxqbMKjoxdUOI4-{!irS6vHJnXxj!ZjD+F^#|Sw`Ad zq>8vDl4lFj4&lJ9yG5n7c+63-4@25P=yYlSkW#^Pd=UYVopbtogf-~Hi{j25dp-VA zA4;%h{kdCdpLzs-1v$49Ga}E!5R2}o5$poWltE-y%+~eHyZJ%7StV)$?Prh{ymp(> z=5>h9Al0Y5$S(Y5^m0(xpeBo}t1R%Iz3g?Vh}>8hgDy(!0eOP6YM*lihpx$oT=O8|(puBM_-u=W#f zUp_!f)SS$I1~i* z`#A%BYv{UcViozUGHnwuMTqhWktv=_VwP-wfhpRuKad$7Z<`nYu#(kebZ*gPfPU6y$IV{G)rfe1y~^{yiSY>QrA@X@tdbxZ%MTC=e%tI z=AqGlNId*C(Cx|bYm2M1z|gw(FEGs{W(p5tzF;zWf~WzDh(fMD{HpdJ~P#drIEC2bGjE^!WRZ8Y2XrD zM~fr~OEmsjEGWLp$Q>qA&L`*=C^bQ&>5*Vz66%>s6o)A_fw$z0)cG8$_bsXide?h< zjNeFoOmVE-#HT{svs4aYa4RgNm|)7+8I_%4%6v1#6!k*;Cj08kFl}H`4@L+2B>XB8 zOTVUtZ)zaSc~0Y%((M&AiOXQ~LKvFXh4y;ycB<6%xz~zu&XPh@)XZ3S}nxnxJ^i%eeF&L^5(_B{@et9>1oU zQm3Zc)xPtbJMO_OHl(NlcnP100vd7}+52``wBD2{RDx z!}at*%3~UqFzhnC4`fZBonGBjM9Zpc1)6e=)w~50kR3OO-pCZtrEB|(%%ms4eD-ln zx2-I$OkW(otUa-OTruSQ4Qc5wv|gwqoQ>c0|Gz9 z=|h>mCPtr<_UgzcSb48!%Wh1F)8fwSO|BYg-JFtnc`CnvHCs%1iT1jGg)<|Hd}L+I zmp?{61c0Vn-B%f-IlR5bv%q)LbMqltm~7^sRM1T{3--%-~c}f=X7l3>NK*6lPA54hG`$ zwC-J;DP^qEY*wa2Hk+A}FyTtF9Q-?z{ANdyn36XtZL2>MIw^Z~!kdOFG7(%Q{U({7 zRZ%e&YLm>ss$?;NuLuYA#$m$@3!xxk@yQ>?jAzz%Sm9^GQ%poVDZKXRhT*PAPQD`W zvZ6d0MzP~%aVNj~P1)*$DA;K47x-?NL|TU}Yk*;fIu6#?t?;pY4EqC`4Uf^5w?x%^ z@!|T*g2OV1&@{ov6DXtpT)-#83w}-PITTz~=Kh(;#Me&i{FU%NeiL_^n_O>r0Vx=_ zIB{7UMU!#5lV_4NPnZHeiBIu!n92?nq=zQ_B*L+8E5I3*a1pnD>&G{hC+bUNc)mcM zQ%nw1!Vlz52>2w$R7uZzWhgf)yLN@zKBft1nJHhs@RebvQQ5nfYLIf~ZWNbdGV$j* z1(j6!*p!TOn*rm$y4$lQohZ&66?cXaVGq}9-s+hYGOhuf&+mR6He?3dCY?n)7#$h$@Yv7uJOrv?+Ux(|;KjSlU3BMhywO+hd+z?zC}}7N9v{ zj^A;YA*lN(FU>(ZOU=65Q+v=`^@iQnY-!9;5eTrG4=F%ZusvC921!LRpW~_0YCn)C z;(R;0v8G%vNNeg?&4R8SwjTa%scue<+LjuXIY)KI$@r>#@Z~#|o``O2Pkicv()ZLC z>h*#|st?;2R&{vH�WGSDcS?xag%FU^3^E zv|uA7Pyj#A!a>3o!gz2y&f|6Xr33O;1-vFwwlue+oHNU(wsB^~_+-vZ4utr*7D#!j z@ZCOq7fVA=#xpTXo;w5M2|mtUvD5D^L0AfR8&k=*TX>xtNQI!cze?$%<{hWn?A<$`Omxz+a&*YUmJsvT z0L-JqkOb+zzE5`8Cx@7!&YM#H9=JKABqxd)0Uy(5Uk9F4G*vJv3{T!&gn6gbn?4JO ziMJj?%@!sCY)*p5Y&M(85$aWQn;a$&$mUW4Wdki$Zd>4PvseFGzB{e@LtC-I_Kpqw zpYrl3YD6maQB5N(vrF`ou*9%>?i{SPx=JGtvn}M{N5Cr8f{NexAII;DJ~Dp8cYDTo z$M0Eb{B-|5elTW3#_wM!~3FoAGm+oSpd1qDYJO{vP^D|YGr<8x-Hz~Y)W3$(k1}a+8CQ?KMXk7p+ z8POtgq>t7lX-L0_IVGrxmzx~3%x$IxvmC3^WX7hiLV~}r_$RGn&@o>8?%Qv{P-UiI zZ@n)bRUDB2MfgjGogyLwL;r;F8M(Ga+Z0@XiV>M>Sg z%P{$mgxefkQAbC zRgsz(!zBew2me1RK5V-h>QrQW|6l#(t(oBnJ~FD*1k#Z6gpC2p)Fz6JptoPY4jE-T zP-QBg@5bDOQ6?p1{TNljrNDf-Y~H+}f~S4*jzMUHT%nyMW^x5BcrTDBpSE{O!drK3}5ivc(C+`B$7eRpI#(91+wi4n<<#0sKs22>6*qgkP*FPQI-ENd3C{ zni?ueJwu3hlJ0-$0bo`es{COGLv}X--?omQ;4oDBpGvzV>r2=^+D$JF+Xkily>7w0 zv|i|$vJ7bi?NVxQroU(GjP!@KB7J}|jpCeqG~ z+;=7uv`(Ji`rfp6iswC996#HyedfFw6|XC|&m@U%AQ65b_wq1HUBzEtimkfjk{C9V zFIWn&)QUBQu@%0~oUjnrOSnLn=%Gyof1tsrC$s?hb+i0hm;5&_{Wp}9*`zh6|Hed_ z%_cmVH79x)sQQ{I?Ass|ESZ zOc=b6fN~tOc2WWp3fHy<4hN}oUgILhPw$gAur(>a-Xp)!CGUnMIQcb_=IUy=PwVM8 z?oDWIyl+mwi4SJc+u!4&fI3H+qoNCDj3n8?S^yG_m&Q--ORk9Be$qNa4kBsT&8FXA z(|g$Tt8Dr;HvJLR;uz>OmqE*4LEuLo@wnvG`6YN)PtEAgKJe2C&qe#WtL{GVE?`_P zc7pB-&IQ;jNblfB=3H{_MWy|^hz0AE>~3P6O1q2PnMRNtC%sfilW}QeyWKU1h@z-` zsl6S?hERtiW{2(btFPo>+>k4Vel_Tqs}zJnwow)6PO1g@q3t~pRmiqK=YJJdWk0>-avqY~ zH%gr`nhW;hW)S>}3--U1$IT$EdQ)+E+3ZhGEjjZ;j#6D|r}jkVWGHho2t9Y+%gu9U zFv@kx#x)h?uHr=*rwyyqwr0<@Qf(c&q zo>V)?DlgiMT3VWrZxI=I=-1^h2qYE%l*&=T?~}KYk|0j&C)A<^^Y~?zpEhYK17rR& zq;kX*LUSY8kl(3M5cDg93?_b-P1GVX3YHqYiw>tPe+QX`cGkcMkKQTqf$>tcky><% zgq8R#amLsBK5mGFeMtpw0&rtlPc8b1gnvUhL?7`iHRc1iMg}8+T`Ky*S-qg4se1o! zVGv9sx7EuU>-9UAcJB_QEte?E*T^FvZN2|74J9QZX_3TVf>lfFAhIaR9Y z5p?d|`1}QaW|k;H{~<5uP`kRVMeqDIWyqJQv>5hUF+ zBpnPQK8PcDfC`G3PGczIG_Yd9u8>fn6|P@mj(;xDZSeCpCrHauNWyIy$hf9W+Er72opNB7pqaQke@YnT&cRaqG1 ze%y&Zhh-=gQA_oX4;hv_gJiNVpn$hsN;t1N>eG}hj3&C6PL*s-)y9I^hI#K34Rgx~ zF?ln?Zifv#=#VovmxFIL2QtXYAV4+MBM$z^e>q+JT8 zn8dwPR*Z<=L>ydG-bpCF2rCt3H%;)XzDbHE1a~BZ6Zq%X zqTR%t&H{f^RKWh@GJaKENUCpIyYCN3tpNbL14*meZcbcWILZd(agnMDdf# zl@kg@$DToEZ3AO`?mpQ^K+bYq^Qrw**QHP}Q;C^nq;L;f$KUtL8sNS0iciwG9|3F^ zeMiQ5mk4FVk~C2w$L22xB5^y#^;0ot4Z2a^;iYAwXn8?|^g_mByd>|pij`32&OZDm zty(L#R*CCVkvb-~>VjpH=#28mw&jcp$Q^O1wOp)8x#%2i%6;?al4`N=v)nf>tG0?z zhExp~OQOJK#NNxuvyPdhy)$>&BkmT=#=(cGNukn5!ouvOd|sXqa}jJS2&oERLZbr4 z_hi2=V_R;MvI(sus2pIOdP}u zwxvI;V9N3>0gj}neV2%$#*K0`4frf zwJ8qwH~nGkmN3m>Q`-ZphO2rS*?9dE%82gNV!lN^%-u3*8}APVhp{c{q0H0q?Ru`w zuXECGHzxn4x*;Bu%0W?ScBOOBL&nx>GBQAslS0iUgDEcvpOe-z3xFu#q^;C54SI z{V?0KOMKx(e<*FjmAG<@X7pjm4J4f(1&$SFjECJpuwd4uQxA zbqTU^J=A?h)fywSM}QLy{fK<^JWidrD0_7tY|2K*{FysE(3|YfOzmtE0R!lc-K6B! zUqs<+1=fmJN!+Rsxg9@N)|6^L6(n^E;qbkVPsIHz3qt)n8>C7>Z-?YNjrG`~(J)$D znSasYz7`Ns+x6?T&0O(fp_q60ftyxV*8x#8w4;G|vSKDTuc=tPBY`O1?ogJ-kh%AY zU+0Hn$A@CBDr{R76QG-_i~|}@R@+$V=z}vi)u1^btE%~WJtD351}kgY)<+-FZCyeh zkBOBvO-tI=>*i8!DOb_qe&^Q;sH1tmb7C}g*z^yWqn8gB92wfdNtKaKv#kwO`|ggn zA4Gs*NOis?cDyAP45wR111*vj9Ug1}R#4{OqM^_*j)(Cmee>Sp#cPUf`~1qj=~yb| zbzQz^`3Kg{^NatMu-MVue6|>tqE5!h8hrUezs^_1j#tH8%aAd9bgwCx%g%HH3eKxO zB5kuk_Ket=&eNjO?mVBb*Ppf{+SrRGVv}lGGG*T>d)WE5^*_S~$tLRXvmMM3>@bwB zHufVG69Gl3&Y5DzOmF}Cz)nbuugtdHzr~m0+x5a>_^Z+ugfg7~#pK-cyl5E$D{u0y z!~HhV|H9h|7nU~*zVza^mEHIB%_7)TcOHkETv&0_Wy(6!A51D3DM=HpXYZ9bDXRN= zv+g;i@Acm2hIT$Hc0kV*aib8`L+U!7yGDuGpX6r1R%*PiK;4;KCN zHsm#S#n1)M4F&(EsLlHr5}h0j8W^biZeEWe>j)EF-`=x4httLIB55(zzNTS@7p4_i z-a>J^U-K>EW%&k0k>#&=Jh_M|GX6)|Lgpm-l#bf4C=O$BOfu7A-QepqXiwRz*AxZO z)k(|-EKg=(QTl_;1Goi6)h^PI{7FnLc8ttLzT{yRli3QeMU^g6GNl$7Ma^2|1NT(Y zuygVO=3-K%y5lC9-mU&3GBC%>?vy4f6Mh>kJs#h2ebB<7Q%Vz!3BL}aJ>as(OI&uo zFg{l$>-dG(7Gc&}Tke%Sj*q}&^!EI3ujxCw2K7C9=@l5wv{x~_`5v1=P9>E!EtDPI4NXz6xpZBRf4~DokT7 zB!VF*C7?GmB=_Vg>^(F^)E+6dZd@#?U1ZZr4d2*tY5HP|BQYRKFH+;`0f79@aG0aPkvc^5>FQH9H}9I+$E<(Ab$Br z25qzag(Cwbly;m5{Y<*2=;YGdIO1 zd~kt_{HQwC5mI((OvX`JYU45>TGcBty(t*mBi7|?;IFQ}hx+@GC5hB!m5$`H*#{JL zT}a9uriOh=aTzR2>mALh$<3>J&@HN1DhKq+aOYQcw5Y5YvoyC!&3@Id zFDuTCRhQidDRbYpdONiP^;y-E8|oANXH)dMGYXz609G6w5Kv~0W`iN5&AiJ5C4D}n zgvji_lk{1fia?EB^PzFuN>E~GYnRPn=;)v!5#8LOLGTu$DoSK%@}WUnRIy$^k04@5 z1eu(up-j-OblLNCsuW9BCvZzUJU6>}5jN_w8c~%4bR2||>}Ni~Jrlyve5^#$p}Il4 z3G2mpq`@45bY!_N!ht0Gofh3Q!4Yl*>1LXG>77+KOP?&v3eY{NN{hQ-ii+4SPl&&O z>5aLDNpUXH)YeWWN8%8!?JzneytwpJ+OszxIiP`4(>jntjU-vjk{l{b_@Q8P zTRYI-T~9vD_72GJ)_pMIC`&O7zZBF!r-ht_km@6OWeA%<7&oXOIkL`NcEsR+mdKCz zU7(4C3$~^%n(~^1g3Ad{!9B0Re!nL)L>|^i%b(Z61py5{6M7+zX|A9DI=wb(YYDaM19 zmao(1hCb1v3}(gwD?6%gk{M+r?#$RC)dJlwiXy&Zfo z9bJj64uh1{H9#Zd3|k#nnzba^I#u+ty<-Maa0>V+MPKMuQ=6PTxK3_ z@bmmklD!i6D9t#xPoC97B0~e*(T_DYD&3icCD+)f;G!S1*_B-8d_3kyKQ=F4`6$=i z{LBU30$rUX@7$q}UQKrU%(q@3k=h}TB42U)EHM5^BKP`UnD0OCjm68mFD&;L`11PN zCja`)aSZ%u+Fu~EL*N@7LG`sO->cs|m1&Y8o?8@KWx&_$7V@5}QB)e%tQHi`?V}-> zR9{=a8IIXmi6IY*XP*g22noyn3`tue10pEBVU=`2z+>Z{j!*1HCVmsoZ??7YdH@aK z2%$3B$C31`G8p2WExZg$;`&1sD2yNCI*w{5ZB)39BJ`en!y%In7-ATECYBc1QIP6o zLJap|yOkH33A8B&P{MnA#E;lHut6}8PqN11xkC1vX(N|a=?(G(sb_~E+djnk%_^j&??FbEX zWZ#C%*vFiFH>dr(%>g=hce#UyX__Np)=xymaa3gaD+S#t&!wM@~9LUYM5~KhqUwJ?DSl-BH`l;h4Lm@k?Nz}8|ab= z6tmZD`G}OP!~AVg1UE+)A0=OMHPgBGbh__@W92Me4Oc!TGho=vSlbUR5Gp!=ZkWQtYaliWaA zh5lF>cU)G$rf&aUfS{i?y&zD{Y9Y*L0Zv&EIRf_&Wcl8WdCJ$6m5u^P89+?c=3O}o zP}*Q8HNYaH3If#VSXN5m9ejZ|ct5L7cbf@bj_RN)xbe8@q>XgRNwGDO&~cc(u7A?H zxjwMtythf_PM10(kn}{PwqSC@pM(wGz_P`y2c*_E%p zxBCOS)j+-kc}F(=9{HF;mj9isLBU!ce9IO1@LQW@utj0Dd%v}yL4j|%{)ulj_y>rO*Ur?T5 zCk7#w|5(7!l^!6+0T{ zv8(e9XU-!Uva@JmE{7>SRM3>yx&bjsMeh$$fs#y7#!&$%8&b(YcbHJ)sk??_5FW*< zjR_qhc#XWo1PBHRZXF=?2W(#YBh;3FA+b9K^pE>N|Bjhz-*cXMmDDh_NBt`pf3D+q zQS}?%&PJYuo#$btJL0--hT1qX!1FIvT{=5D8uqxE18~3K*{gQxB@qQGZO5r8^~CN6 zF_i&NXz7qhmTZ8Kd)U+Z{e|>Etb;hQAx{g(U<&t2mV$nqb!m z^UD|4s5_vM;_3(feI8eTbpWwr|18~ZE=eMTY*3+fm^O_>4gJI^~NtY%~eD?K(P_8qNi0XT$5)^6j zvs~neU9mH`L;42wRA1@4cI^O}MK>xtasJ-2h8=&uc3Yx*)A2ZF@2&=QRVV41Z3NS= z?5yf2(2nfb0{R1u^-{i7PYT|A*Z#3s@&nc|=0)BRPM((=LI9I>x=P5ni5vVtdy&3H z!1Xkh<3{OTe{UN)-Xo$7F8;3SC`?e~ae2d#+Vuw{sZBmdBBTbG7 z)H6Y9PrNagUVrACV@_F<{pt@ee4eG-dmVU2?krWprqkv~CigSSaO_-NPVPOqsusMX zO~>P(wsoA?jzR9>_1EO}TUw&eG#$L4fa*>7Msyw695FZtcv7VDM|%gw-Xwor!e zejuofuKp51%hatkWNvYR)RME?mRG8*uhFf3zzOB^+KcV|{{TI`SANFWeQ&2pP8#hhK>dRg)f^64nWmCl7m%q%g*jT(5+4 z@QaP$6hl+O}<}^}@d!B=f8c zHenS+CSx*;d%8jHl7aEZ&nbqhBOiMv8MN`YYM%_Pem^bXbk>*Einw9d1qdsE`A12t1tiG`*zQj?52F?wfIo`(I};o`K@-59 zC_Bmc#!Yt62Z_z5g{Y$g20tbswBM141d|DUp%8}<9A|EboFvR`=oamFwxLy(G=u^X zt|lmcME7R!tnz^~yoihSo`w-~&ZVf5T6!{d0I0Oi`r7?jyiiyOiRbmYYKCnBJlQ9v^&rw*W zK@lXwg8Oze{u!rW;K-RTt?op^$7f?DAML^DNte-YtTqde<|rNJWJLF0e~|DKH+TvI zBA7JLyD?57gSMWAUQRiUJG08AhdgaW_YCyy^SB6ZvgRy!&2IGU*${NzmgG*5yCen2 zceWWbrJkjz7WD18;pBBnXC--kL)^J)n{lG|H9$CN$;O&hedUgL>{PZ7{cL4^&h&{~ zI%!C5ijuVCE!s87-*a1pMINKl&)DSaYD!BeIzjq<0lJ%nPm%#CCIeDdNS@6P;?od9 zO9?jh<&-th5BmxJ`e(a7OH0T{0g$Vf`dAuNsf;42j4brE=S6=~(!ZC`ZYJ@`=-6GD zYpV$UfwK**hAg*i=Y7#`CY!$Dp16IfiT*V@Fq0YWIw>+knP+?GZ;#3j424OxK;u`# zOy*zFEc{d&5chu7U6LK+*C3Ne93=EhFa%%3$}K?zayZxG0C%KR!)2S&7DbP@=5oWx6wiY!vkvLRx$5n<4W0KGV zyk?pk_$T)6qxF~p>*Vdnprw6H1d`5Jb$3BM>tYii>76t(5S$vE{(uER5z7^H7xayY z?n>ynzgA~Ts-mMqBYJpQ7ylZVH4vul{zAXizhPJvL5n>8cUy0YEo?;iWmEg$HKGxj zl#*`ROu5;S*L>k+Zg=EUPWG|(yWDu~@XktgDw3%3aO0tPHq-2>`Hf6SnjZ7&tvBngKiH-hR zT@}k{TG*I9A*WX`5pFitR2cZIruo^5#?!?qm2UP46FX*WpTIuO(#@Aou~}JY?^w<0 zx|B;op`W{ukcI)v4r9&ziS&6IRUJ^1a#HUGsCvzAC0$O25dGSDhaAYzwdmK5+oEf* z&kFFHgyZkX81#x7z+2y3#ZZ z=J4g#ZNtWD%R*gSiB=`q53FPQJaxm2!L&W}3=l1HB%_^Km(j=GZl)@{{D>^mIR&a1 z2TM8F6g-#vq`8{FoMD35<8+Gvi**gq|CHJN$N<2aC!@@BwAMndWkm@z$XD-a*$~y$AhgJR#=+6>O}{f=Q1QY)*#3({+kD^sG<`@PB#7 z=m(;})yWMC<7JHBxxLn(NPuS-(Hv^u3ri;HkE(9$krX)5M%RNQG?iubm+*`qPlI6j zGHs$SgJTmp$9|7s7td?S1lX%E4yO%eXPI%*QMP(%13W4P7DOrll0dji^d;1szYtjE zSxKDLyPoSq73Ma`jXR*C)_#PEG);U^1!Ez^o2ch7M`wG#i@hQDqTKKW`MTbu=jh7@ z{#-9SOy~h4UBhTtE82oWTnT;lBWE3IM{F5!=}OEQJZcoG5a{PB7FYG?u8`qm;3kyspHL{4R%!N7aI>{~_LL4xK|mSep? z*a~V6DgOF{;#>NR@GT`#gbqU2_E&HDcJ}u=!uge%R+p~!Lmi3k=RWl47gD3_e*i2{ zI3+L(qR$P{nU#r8;^#Wh2eeq53$rUNLB@XY_4K3Tf&5C8jY@oH4X(AA|9?XGv>i^F z3UfSL;98Rzn%Y&oH4Q?W?f)^atN5*%%9eL)TC^#^56KzwtcVGw)pB- z=XsOSBpHw)pC;v$eRi=9PjyN`J4VQiK`C`gw>EB1t)Lw%WX9pSNh$a~zV)y$#&7FM zVT}LQUj*Nm_GIIQQ9pjw<)-YdcLd+5e4|2$@hh+QgN(AU(633^GA6M3prU)f|EhD% zNBkPw^(_niQ1a-&Mz;b6msag--0#Ql)4NHmpdHWiif@njuUg4(^J|t$c&)z~-2L_@ zrQ0_P9Hr)cMEV&e3x_ih_sulY+;6=#x4x)y+z3cUfpE) z(-}8QxxZ1{UE~FLno%hYa&&u*^!PPWvh+4Ko%B5JIePo*O)R~IO($K?A>tIxs@IM> z#6q*09%O`Clh*KqST8`?l&Xp(v|XXtFj|AMU~4mz9G}Ocxc{!ejT!8+HaZBvmGwvj2(XGu*pJ zBn&1}hUur0a|~Zx(pC6L3E{kWmei@iuia6lQ1M3I4Hvb(43RYuqDI1$Uur#XPbW!Q zqDD4Xm#0?o9QzEX-poxRcsIE}1=W|kn2gPPA<^iw*x}b$2R&;td!&@;w4mN(b#zD| zX>JG=ojfW!>kp7~W5O^!ZEK)tM$)n@alwRc+5f29px4NRAOSO`(V=Ii;GZ`sv*uA^ zsSnB4fIfU!QdoP-f|0R=mBrD$Y}Ck@I;bS#3+Sk@nV?EauUNWw7E7xRiBMvJ|J+mk z6a2`zx|7PG)$loDZVAerX|xVw5`0eK^f=9`XCou@uU3>jo%(rk`;@E8EFVjB358v} zgT4Xjvwko(U6%uUs?pIoKN`m|hF?YY7&C{<=LZbiPRC+cDMRJGStWEyIfcU|lanJS zIJ$L^%GZ9ZkDfoOgY|JxY~D~QYI{By@3T_z06_uWwEPO^;U^sj zbNDYI1~hke)eXETnM8;p3gN2@_7z)Do!onVO*f`84NCi;$s-^+C#CGIMYe*IDJ-Buf|e4{HE|#nm3KzN^&Dv?mb_}K|$?=PNHfo7AGl`We5-PN;rH*OZ}u6}{9Q93pAYpW)L`lGOKA-%j+ z7RNvpZ%PfSYyY?wF_i~rcbYVRpB3nHRCR#1443$Xp+-iQdu9+;;PD6fb*bS_zATL0 zI8$$1R@t$-b3+r|>K02OKnDZ)r1dP%=kR682S+cJrizN}C8ii6K?dJKVeH)Hy^-3Z zD&T6J17!Phbm-%kl_s7`sw^}VK?I5_t?+@2zjR`o*Qy6v<%YNj!2J&ccuCw7Nv{xt z<0RH;LGW`4@1BP9+v)q$8G?lwUOy?#{$Ty*#W>GbYY9eAVNnDDbMzkK4Azq{L!K+Z zC6I)!;(P`itn83bLql+?HHKo0gkTtKrZtH2eP>q|(J`_!rz_PkM_3T3EEqAxG7=j5 z6I;V6#1Th%_ex|``+Sn1dc%8Z5H?oJ;IrY}d~jRqU3cIej|Pt|Zm#hTb#=6580p>c zd(nYEwcf=!iKVrZWUR#ZEC}3#rm3!o#0bC7;8B`j=f=kepM^1hmloE2n9z8k*xMw6 zrwgDf(4G>1(nRu%b_lFIcPVAO>k}WTml{|Q=z~+awWW`=KFCY++8K3{tD&=A)MfZ) zpEy;iG-)XNp}T-=F!*eWnr5fYlwKt2vuGRAC7a^)x15^Zn5_gUg?%^Rt4v@kkx!>m zBY6RU?xBr(Pn#T%fUU4mZ zmwkyWuxJq3e5jbP?SP$u3FtZWZ{wL^n*{0D{*GcK!)lOh}{!yevvGu zhm}aE?-0JE@j@aWzWAVMIkh#q$^Tp^69>|Svg3PktaQ#|fQB4ZjH$OfNqdr`&C~zA zD9pWMw5A1IcUFl>Y3&icjD5t{<$xkpX7;>F^jfS-pw59FKs>r%C#VwaCuUFA8C6h} zm;-x1>QVCQAVb0_kaUm9^XXnmF$C)E4GODoFZQtdcrZP9ex3^Fn`s=3p*>Uf4cTG= z*%%kPr`Y)zQ*XoZZTo@~t8lu6qh9;UGhA$RSsiLq zmeZ6|N65Di)>jraGPUxkLnq1W61 z;A*{)pFEDM@CP+HTRuy(Xl=31ET>*_WCCWs09eFIJa*K{)jEJ9Vt`pL(-Q|2WPr!x ziHdno3A@PA>=1_i_jfGP>4OSPPZ-8^WYI#DKhlFlxi$UVkp?-Tg%j+JKsyXz#}7D8 zS-bB@=K>Vs^AinQ?$&F!$$6jLUAY}S?r{#vETJFKHpv54^<}Q@j7=!!ZOf{YjlbPC z7&;yli!u$alVCnyx((lbBop{6gN(L(TQNqZeWSDO=XJ0+QK4&7;RN-H{UAA0ZXd_Q zb;;qz0jI2eqU)DC#w)iQeHt!bl2@qkL1#`Ssp%4}EVNL(2W8xEbX>L(27XSbhcV zu>;pBFRTMx<@gxLLrt4@3un2cCP*B}U_THRhzVWM^X(m+nHScAaRCM20iSEC0}No7 z^R`tbNqp*!8B#`cX$1+C15iGuMC7#-h0d zUB@q?drn{G1U=}6ji}3coJ*QO7sb??upi+ygg+y^hwvAKa=B$f?D75yz6i4r1|gh; za3sRX2xAdWK?okpgdBuv2xlOijBqBx83=O`zKn1-!a{^Wus^o~VK71mLLI{Q5DrJk zBMd=Uk8lLS&k%+o{0G8Ngl!1J5gtRRM|cL|WQ0Ehs15jG*jK9Eo* zvXPX|g#87IG97ggq&9wjhtXQhGO+a0;QpDa*$k)d#E`2npUQnjGH-!Upjg%|rm7pwr$L8|0I`UIIL4#oU#X4Nskf z93NfX!wel5YWSNN_dK(T39Bg+NBMV2Vk*|tVy-p|^m!)Y8oX>C&`$DaCN#)T6F>## zg>G)YB}8T@79pwgHZx`vWcjbr=js1L+1r3cRpx)=XU@Db9Bp_T5wKhB4AegR|6l*>dajGnbI$#K-{1RtfA8;WGYg5!_>2)~cm@(*3MYp8c-xv>(qvXS&-`+RW}ZUgpTmi| z&v@I1j|hp2`2n=YJlD7oNok~4j!$^o4^xE11>wY3QF4B`q@xESyU9YEcAi;`HrFEY zkKx3?5#Cmq&5XZ9XFbFBj$k%sM==ww+}_++%x4SZ?MC_}jPwc9lbBO9`*!1OetMLU z80x}&KFHiVAl6#>Gb5qjyBD*;Ha-@fiO>OzXM)i1OdcgyFh|j_WoSJ6F`g`vs4d`+ z`9DJHzmb}URltCB`*_=_2blYiYQj99xrg}?i4TVp9Uo(T?iUiLgcE;7qA{EpXy{t|QMo}{N5 zM~(JN0E3noEQqAzp<$J-K_pW0xU`Y1~}z4UK$L8%Vx}PG&7!g zNBh$t*5${vDAqUs${#m3ejjc*)QIvb0iM1aB=D5`RrJU5j5Pm~|Y+>8Bjmb5)G zBNEjoH=Z7|=9DU&ooiPK6T|+bSCic7ZlJbl)>%bsdr!$^H;=ZB8 zH~72r$TDPoJjnDiD>9x#+DAiehP?dgHA1Z)hMRm9iF?8Ybv1%)hR|BgpX(Lme8+QW zY^?eS?Yey2?}Lzn<`i+;>c;rrLxUq@gN%)m7W~Q4qvrNr*P-$ zYvM%KE`$f}+#MRPvV#hJrnc>GvgRQJK4ne^=&Twwd98gk=ngo2o;uZ4F^ zzo}h(q8b-lqUspm*UbCwXiC0A?7MJ}3T_gckMLa_YZ$m8#$6$BP3)TZIgu=!6nhnS z;a?S&U5KT&jUC0XApXkI?(r(FPG;A$gw#h#S2$E}!GNPNg)R3G3_`o_76%#5o>_<+!_e34drJYK2-_TF+ zZ+2$PWFmb{l`aLT%f%nV9uCsy6(f!*;L0bG+x$EN;O@M_JN9dspq}RJM8i$!IKczK z6XZ@T)Fs9BL3d|Z2Vx%u4L8BAs^5=#wQrr6$+U~y(986u>tS2Ok-qjcw=2Qfqg@wC z9s-RI{a)@{psiQTdy54-B?3ibE^h;V zd3ssiD$4D>Q^om;|&Nklb9g41P$od#Y&J z3aare@2mIKMff5RO+3bJvQ=n(t5@3MwKXXxus>x$^It)4=~#MxaQfL1l&v|kuFEfy z`2}~SUTo9)D9b1hKAiP`dpw>LZGp=o28FJ5wWpwb3tBb}W6G zjA;Ao_Qh~M3XN6zmfDslXtveb5)x|UCp!1ZOZI4fYu6HPH(f&7l@GToN26&EkQQ^& z&|KGaO7~HW`jn{V=5aJP+)zQMETdf}RNzUFqS5|bGBj@#O&ZS>8c!!j2L+D0)B!BdNQE zU0`)mj+Pj8GhOr1@!SI>;`{JSsiV%PKQ83+9MOwmB_S{ah`_m19R+LAF4rxxQ0{rYC2pp3~v6ZVSO6*@>w>j z+20)WA5ppfhjfToZ?Qpf2BT@N3>#v(PLl81Px}}Jjv4spIt8^MO?NGL;cepdy-*40 zNr1n7LV1wA9Cg>gQtAof(8idoBR$}xnErAcYWXK6L5t@OQ74;;+S~}+gHO{fMle93 z+$ZpKz;O|0hc_eUbt(4YJnYByxPznKKqBF}*_KNjZ^o$SiM6|WaG7-d>A0TmR&ZNX zYkF9AM&nf;C>|OK2{`T{^u9#G-3jNm?voohWeLB`(Mjr2rxSK3G?5^jB&-Bo&kbET zgaMhm&KPRkF5u3;lYtvzs2movNapl!eU;uF{xtn2#X6;DOo0vk zc|+QXtc3{m@F#GBhU|#&8mfuWST)_EkCrnV8?M1W>mwt^D?eJ~PMEHo8((yuFP3iq zM~gsUNy&*q_=HnNka6dTrVsH6@eMQRm`pwsAVGhEbVH#VUV2mNqN_%`j`41V$3ogB zp+`g6umkQ1-{(!Udl)f#o-HbtWLf&Gy11Y?x>Pt}rPMRxtQ$OtI?CN#CGJsV$GAUq zTPjyd$JUXN2X6CN2u4xW?2c+u_>btDqBe`ka;42QisJJXL+1=o|#D^7>XLV`e0iaKU``8z~en z9PixFN=}Tq?D`DBA((k}@!9^g2)0w7M!aCTKD~qCjTd`!jV zAZMXBwG~#bRl#X*RiXQ(%1Xpqj|!H%#C-_0OFot(x8i%}4DhRB z+|h7I4X0*)K}FjiLAP4S48uzqy!3f3Vm!C)3bv9lgnSqS7o+5?q zjCs(SN7k!dg*S(#AOh??8b%jWBcw>b4JaM&vo@*ge75A$DMN?e4NCsEvdo7%0xNG2eQb&XRg*UtAhM!^D7Kf%7J%;)G zjLqQ^ByZ7BUK#Q}K3tA$X>8p8&YM4+j=Xup<^20qu3X_oV*Uf^helV;ML(Hn=|EI9 z>yu%3%|;Ojf4N=Fu*UZ-V#o&4#OxO8w`Y_J!!6`~tjO#`JR{;Qtw2n#N~KmH+^EXf zYRsE-^@S|`XWrwqc{B~r0Oo@wobNLdT4$-WHMzV+VxCKz1q}pLr^Br)dA8?>E9Iyl zZo*odpPlVbp4E_Uy6-5MkiXgZBiQG&v;4_L4GE^vM+HtiiUS3c??r}pGc)H@lKOHP z+jaQFqx7vovv0Gsm5y8QZFi%NOB@Vp`!bd~#IfE)6rrb%kHE5xyhVt%M@9txcBoGoLd# zbKOdtLdL;7=cUiwDqDrL&hX`2YuQ@Wk2%~Cb;rt;28Af|LDQ;xga8eh*CuVe7vF!( z=`hwB#g(-p*Ri)MC#c}!15pt&vvtrB%G!64nTuVOIk_XVYURU;8D+pY$L&FV~q4ifEpog^7|4U-GxJZ;g< z{<5cF$Hu73^{T|Z@IjZEIT14s<6&r{ovl|@*J`|lWCGxBxg$Hus}NULPZU0qi7_ao zueuF|^sz!R>KV<$p@PwejA9I!LG%F;nNTt{F6*bzjP)wM^_od;PH_RA(DCpTi+_Z9 z-QIuW+3}|7pXN^3!K84>`iA1R_=ZHxh(h7YB}2hCPN7)CMoxtgXT}8E8wfaxwp>#_ z<@DMcR=LN*#*@h(Ix9^NeY%crP0=>|*xhE3r(hWJgLi^qUB<#HC#S%hZ{EA zA#?0KCfce0v<3W;i970j-7&3cv)oCi|6R9h#W%r-%p6sA1Y$p7dJt>GARM4V=e^_f zbrEIRN(kMOZV-KaisHI8-1FpQM25hY>xfI`9?f-Ms2c6wtj)R!*#} zi)!2D8u4jx#?Z+A1zt(& z+fE05=ovz@`D0rhY z$I_nHhjPOlhfNllT;!5$XDQ_N#zcaSSW|@2BJzMU(3$Bn&4UR=ag6bnUPi$n4i0>P< z8N}z1+=qm9+6PPfjb?)1o8<^oG)EHMeq;0+Yc+l*KFA^t7bW zniPqqZY4vzpGI&J%%Z=RO^oBVP?fAoldj27c%r#2n#wed%la9Pf5O2)xFWl!!sUOf z5<+#&HNfE&^yvxoNetRjioI#MaQD#~#K^XU*D`yF$84mtO{X^t;Ww`F=M;k^PM4cZ zU`RfEbo<1CKHgs{gBupC$P}JoicN^LVwTJ~cHsU!uaB6rxYI|azAo)NaHpf=n(38K zig!OO^~4#V>K6G-q&-FT{+m(lvf>kJ-2<(0lx#16(~5}kDWhL0@)U5RU@9sdka^Vo zYJ3}Gdvg3Hxj99*PU3mP8M{vAd5DuJ-galmOwWFDK4lXlIh$X5Nm3g7nMLL-ZQklX z;%MI9+|s&Oh z?PW-EO@0d-`4ugrK=xR!fEu^jE`X=!MvJ0Xww4@`E(6K4PFddh(xPCyyh%%%@bR0J zrUyQOWe+DCXwovLR_A0k{`Ax8dFk$Nw-@_UR6i*@72RA)iw$q`;+x}7-EtPi< z4*8*Trd6ESUcjZOPTz8C$Gs0ha;IF}*(0DyS-8V~IcX=@q%D`-OFr?z=(lh$pr>(jn0OLQ7Wm8qEqr?zCPW@Fh-I}v)iE^k8r z7iz%}vFnQty&PBW>#(!p1#$+`PoWy!#@kKW)|AnnwZdy4mT%I6uON)@O};fn)udG? zinLF_1B#w4V+nuN5sf^sP5;Qt&~SK4r-@jBg-WLQg}d#d(qH<5+KL-z<y%m`I zv7=P&%3kEOr$!?adQO_uH6(T?dQKgDJ`+- zDNR}p+(7!S`R9xWY*pDXc$6p}V$RYdEMZHEN{uB_H%@&S}bCW-(9UwHde^cNS zQm5Z13DjXrO4%<&a7zi&O^jWM@Z0p9wa4~wOwtI3N#&%Son%86z0u3+5;UAf4IX1O zaMu`HwB{0I%Vu5bCW&Xut=LWXc%JY|6yC$iey!B^M5Xz_+`^fKj}=-9&4rH_&M2IY z>qf66X|1r8bk`yYTNR-dE=j@{Q^&#Ugy2Z3@(SCig)B|rUA|5Wj+SAr2yeEPlwnki zVJ?9$!=ab_hh;dIggMo{h)XP>6A7WEfMbJVwqgGu6eXIpH!XTSK99DK*`L9R10d=!~5*_vbuEyK6DA{ zjg$Z)p^Jm4OE*Tn5+0ACLzs|F0;!@o{5c8$h*^&T5S>>6Z|x#`G9VcVcqx6b*C}h# zHmKW`s(l*2Pi06Jz!ExLs6Mq}9KiA?0W63578KwzyeUGj@Q}U>+hZwT9BqhJ7RTj0 z*rdfBk-(*JHQcs)ya1O^+s@V8g^K#lXabjxW&%T6b#KQ1W+X}ftBsynzT?`;_IqTn z5~b=8;80a5#P|RRX1pdW6-%H;zx@t0%~|?xnSHFSK-Mnd zbc>JfvzTUV;q+11>55jR*lmzn_wZ19Ptk$g8X z{|ol2_1x3tq&;QO@pNaxzds?z$Rua+Po zbOo3rcbxSx)?+W5?!EhIyj$ zd1Q@khm`V*^r|#Sw<@z*`PS47!#qM?;tFo?xsR2S-Qe2UfC&Mnb4Q2o?8bP*{-mHu zxB-Qf*DIopqYV2mWREhoo?HTP4(z$bFIH$?5gX@Jv~mg5q&HPF#c=OzC?GTn{_=4L z5}pm|dR!twG*>uw5cw zd~dtNnAHnB=RYDtvTHTzW@mKdk^P+l{1BLqkz^qbEXE_Iz<98wi{Y!rtfj$+$eEa} zZ4&v1Aw3XJAl>^}P;0yjSrRfB_7{ZPLUDp2sILH9xYwCp>;bnAL<7fC`l(~<)KLFt zqv=D@BUlplVK52WS_AM~Hm)aWZHq|Pg2igMa102NHOIfj?i@N>wJ0I>SURiUJ$HjkTZRL9!*ceAl znY2NsJ;A3*hBY-QstV&V<40W<@W%igljMSbC7CX|T(}ZfCh%Bov#HF&mFkHiVmgK~ zfe^#`=}NEXL%G+yHEGiBI7C{6MqGF;1An?MD8J#1{IP4vxuZ}sl!LE)+k`@ZRaeHz zTc)1Yy0*mn`ZfXw7@t?K^d1&@oyzum$WdRlM93Wafj^^kFG21j;K0hkfjtWa0GM9| zb832ymPL;(Sd{WpT-)5vanoDJS>DeW)jHn1H8F~fACt(k#bZ!6{)p`hcLrE$A`=Py zyYu>4O#IokgzfPDyqNdnRsQ?+L1kGXysJio_U!-k=aMcBPC6J6RV}G6MFgE9R1&Bj zbT6qZMf{wio>RZ~MbP;)J}iIM^w9;w{d%LgEN_xKfgp0Hq+0Bc|&|jBe;9J z@gcK>keID{Dr+;JIhkyGyc(PoczmDPMaB=czN79uxCkv_HEDTl+8F0@&-t=ACTrh@ z%v6$fl?X6XcT|(AViyrS6s{N%<^;8GR2h7pXT^3@#V?HXk;~K`J@h#O2hj}Bg zdfrDJ^U=ShInD~g6F^!x?d<<(eoG7d&v4q`+!RGq3c|;Awi;#MKPx3IQ3P+8w~jRI zS4^6Ci7?8*C6h3fe}H%V5t$Ea;6L}tn9qA5=?>cjeF7dNoRz11? zgJPvs_jp;H)GVRo-@eUUt7t7AHLG%Bi=v<|ww(s-J5CL*pmPgVa9*2>c^Sn-zh4%W z+3Yi<*Qht&G{mTveM7@|8lx9*7W!w|<(>+TzopeOH8)SXI#$qnEsh3sNh;!sW1MmA zGAN5Zqg2luEQ=jUc$9D-a-tsaY0DYFd=dA&$6+E9$;9ZRHJXWG4}Qrju^qraa8ZHl zQR+pb^mGfY`-N8@QG>|_?`1RAHcuCgCX~GE;t|y4n{}-wy{lAn)EE(zErxPRoVS$l zFMw;aKDk{XhA{y2P~a#g@XtZpDUs{GE~CN~d(@Du4l0lb+(q$Cj4Y4p(ohtL8eDf^ zUTa%K)opuC2KR9&X&x0BSTkrJ6R{HCP1#9BKzz{kY`0HS>wM|*_oTkpSP`OzC zT7+%&b<_m+cC!v@2={oaCQvhIiGElajBQu`*o@Q1_0k3mw>Wwzm|rvjdRZhDRL^U+ zr-(XZBU@8NuG1usJvMR?Oq;Gbw=5L(s3Ee+-9o_HQ8H-Of`As;-nbja`VB7|_QNcc z>=uhG>*OGu8)}5jl1sK_?G6#?p=_L0>h#1UHz&~KjE9L7 zNL5!onYYGiJ#J--3@n2>Ef>Fnn@iy6?J9)%A_yvUb+E4JXw{EjRcSfhDgRt4F}GmC z5z!i)t(%|kRkV!w@VzRM*R`C~2h3VzZJaZ2_L`P5bY6di8UXHZ_?)eCt1F0v;a#E{@mNQ5i5CT27#r} z%Ei;8F493mjakTVhj!|M)k46K=o#-Fxu0 zUQw~j67L>W;#4ghwL<3JRS{pZOvSv6Iv2*5{&Lt3ignj^Tj{04$cz^-98SMn`r~1z ztU*@#!vUwvpE?yOFrWY~qDsFb*?@CG$grqcQzB_v@Y%~E_pZ`&hwCgQ3so;7wx`7| zk;uy;?OW)IU2ZuEvnOX{ud!|!^AqSwOQ*J4XV>#z{A3;YNQY#QwIV<*Ks+A96}Q+^?_ zC8AS*O1M9{UL);oQl4DmAD__N)K(ODY0&ZV;5uc~ME}^w%M$XLxy(3(uVof`Eh4WE z+-697$)%_jQ545fev8=OE$#G)p}PUaDtxaZ9d(rpBO2{qvexaLO(dk=FGN+d{Sn`n zC5-e&T<}!25SY_(XsAWeE_2Km8NP&J%WQIGtX!I1dP9GIMv!5emU7?}#B&0lpzUQ> zd_9~HF?#qGfAUqS*M|Vhh%rl6dvbFd!C{WYsL(t1iS5}fB5&&Ax+bAFXCo;0k_M=c zwJ3mmT)CugUJ^Z{(Wz_LLm z(osHWoSm7|VVF(C))vAmu*Bv}1gGFXWX=3NpxMEF_boLk4l^<)zJl(a+ELJvyJ}@+ z?$Se}Xgi(SpiIpf$rxAXL^APv7ReysBJ!=aU63Gj)J1Xc-sAI4JegRzP7wYlu23M1 z+GxmieL;=uR(I2A$QtT)ZSQv7=qB?(1P@D3UvORPhVpNP>*{{D!mpoNFFG8BRBZ4% zQFj#Xb*@V!w_i`We(Z+ADO3!hwbQilvo}P+U9Jn=!wLxPvMTrxaqp^A%$lp2t6=Fi z5L&s`DEBVyVZP3yNmI=Nv1bt~4>%*cqnc_Dt!K->6q)6-^}EWZjiYcGu{RIU_NMqak$$+22$>W=v%fdTH>ac)g=;9$jWosw;&1ui|&Iu6wtjP zpmK^Tdav8;6Fn?P_|2KA!D*E^1SZzPtD6g%0=i$5-szS5_r=3v^C6Yp7oYj(+LApQ z-M^F%gU@?90bXKSB$r@oG&557_iHVZt`y3WK%^wMAY-u$=lTqLoxu{jP&8`c_;%$P zd8e;C%*58o2Fs@s=0%3WPB)Y|Ywc6x%cqXU2mHx^IiZ3$Vx|X~1L8raq1>lhAdj?5 zL_ov#sUqY7Nq=T!@5mv+isOHH-Pml;A_zbvktqKECI1+Ox#9T%9(tM6YnTKun$4n; zxsB8JSw-_rOS>2DoJ$6+du$LfN)wz@tzU@h`|u&~{s4kAO6ORirPH^^9g%U6iA;6V zt=)IHl=yj1wJX$m3bfF?r`*?i$#W;3pKjZ-F4B|8B~tU;%!rwPX-yfkKeE>OX`j6sB}YchGBLzd9ifhJSib?~``0_4pOH57HbxHPZF5B_*6 zIVjJ9H*IRwCI2UHn&b~HxP|XN5i;T}kUfZJq22L3!yf10~I>S1aJxj5xU^|Zbn!ka zE*Ey-#@%UuKsAo9hs?dH%diifKxl3gQ7D1%%*;}!5sJD+hzW1MNrY$LtPlNhXje^< z6vR9|DTPVhWlPPxawClP*=t*5_I)bcCcn9Z+NGgMJea7>ieSQk_>wGX#M6v7Hj;}C%QMk$ zD0Akouii+Oq@D<{@cz<&y}x;=dLvoIdSzJt*`{>8HV{_XY9|0x1yl8f1gv%Y2QJa! zg=~>J{>keu7{@DHBx*bS`UuMeo$WvubRw%TzENa+jTC57kC}`wY~V%&oi}fgwW?UJ zn<}hT(O(Xg`$RxjkOw=b`L=d2@T=lmUE87%M8b~G?~pL#xc3%eqyQlK0))6urUt}G zBkE#1eH~yb$3~XNDwkKh_#(Ny1tVO__3(H>dQLRK@IL9k-sc^H2wO0pm?2*GWcPMZ(t&A$nF0Si3z zQuYFxR2aV(v~)6JjYQyCMO9LmkDbJAk<7m@$@SoR;02G_{<{pPpFg+b2FyBlX03M^ z$lRE|?Y2XD6SPR|vN_h2Q#V$L#;x-D-e+Fl@DHnxTCkh8cHJq}9opcA3v}EPCEu5g zl9x*^FtcBLqjt?-8M!}o%*>^}f|ZqXE0-lGmrOkB9~+5d^EKtXsh~R;<+iv8CZXv5 zqs0edt5EnP6Tzj9Nm^F<%F21omlW&cBTaFKiX|CKFG*%yTFR{b#b*W^MT53+sp7e&wz>b0YpX>bC7;?PICQ_OEHLbpQ95w+H@kWLz`{j4W zbRe40_x5yA(&}D$yV!|Xr>@;^0$AM9%IjSM_>f zXOr}xqGt77xKyf1I)m7=Eriq-6stnz${E)#31@vf-6FY7Am8!&0EFP{FkpNMmGBLJ zG0Q|rVvs%=5<@=8VQj@eG7*J`nUd)QRin?q&EWgxb}Y@@u{88EQ5GDVFcOE4qduGS zi4c!M;AROtKgX^9FfR{fi1#34G-FS-6h^{jAQP{ts~sPK`ry7Oi0ImKFa368Jy30# zJ_(QB!@t7xg5lO1M%FmrWX#oTRLop*jiOwRHyIXNo5>CbPrfjI+M~&_=0_($ui-)b zjQHi?_XvKz`vki%wA~_3)$48;rK#~F(PpYK1A8>pG6~P1BH?vs=g<649RBHoaY*>X zPyFffoj>ubh*`$ar;B`#dFMsGi|1Vzd8`#m0~bJ9el_;K3GG$lf4vNL(0Im}O}YF0 zz7y6I_>B4^_MR=QoP8Zyk6`ldeD)uX{;Ojy+q|MqxHr7a_cvw}KNr97JJa6`T)qm_ z0R4z#B1X?mdox4P={vzqTb~inO(TS5Sxn5%?*w^z5&@bsO6K+|P;)!a^RD>thniDx zIk@63$2u#URB#c%D7a~JP!fN#kyLeMNi{+n-pV~Mol{v^;_to>YC?&FxR~|}xz?=v zA;c+0a*x}PpG3}D+gRzztgKhrvhNnrUG6!ny-MOpYACiq%LqL&1VG*)Mlt5akGUYQ zV%ESPJ{e&f-|q{C^@RHW5jalwEARe?`oqJaKnfCGj$U0?kJ^Tq_L&{TLG-C@6voxWJym`IL3l0)ZH^%MqtDhT^R zK9#Rg>nDQ|ClNjDXaprd>Cop`MFHNmOAawg#EAV$to`61Jg>N|$uklsw6bQ7&0DiK`vcpnAgfSXcbV6I+-HbRNSt7>5}ToLji|3^5vi})Z9&8wRfx~qJb2;fWTL|8=$W^e+|Gi$U{ zg<)=~)WfYI&mk84G12Ko`r;OGBAZsM{{a6IKR|(ru*Dm5Szpm(&vxP+pkuHr{h;sk zibS?)bDKVKZ<mic5a00#ynA|jjp|@sgy*Z8dphbO z{Ap7`PY^^{!;n1wG^$2x3IdoV^WT>MP6rx^v&wk&A`GtW+0<3Md@ZE z-Bm27n;waVr@J}4aSQDgcH6f8SIS@EU>GyJ0WogZPY2w^bq2p4PSr#Wo0G^;>kaw} zOl-y0=!f+=J6bg#5aqKmm)k1f?XO-Hxwqc%K}FAAcTPvQ>M%)y?q7KS>W=UnYgRi+ z=t4U115s%p>zH-?05&(yE8`!`$&=xGRBtG-C&Jlj+e?vqKX|F<*XOUob=<^EgDQI> zsqTAH5arQ zoQYl*7jlXjS7mTrsD-OLIHRp9N8OHCkkQnIupQ0h39OGgFBYS72y%E#Om~V!tzzoc z385*9dHm6JmBfNz+6BEKIcw}IXX%X){3r80Z<5kcIyjwPZ zBmxydw>@X)zxjNC83q3OM@vnw96&D+=MR49e)>o2<_ku#HJL1%K|+Gv^&B?`PG>DS z(7I&@oEv5Ct|fKjLAY*tF+$Js zr=~vn#`lE!AiC9eaVCcd&&EXQ6cii=!+8_y6RDSrIi>hUMZESFuW|eI3Lgjz<``jS zwN7ds4W<(ab%8A)!Lm4(U6mn}AQ4WI{atZeXg?HC*9`C+>@?Ff@buQ|V_sf6YFvHi z;lWPe@t)*u8FG!gnpHr;oajz63;SF9{XsX)ZjnIi_N2sZ1n=wq18z%01;q4abEDxt z*VFAi3C-VkJ=0nLc8$K0tTX!VN;!ay!6`28(T@zkDY^b*Fv2*!5d#MBR3ncI^TEU| zmSj3sYG&8Y%GY>ONQdoWk-cl6=wah5TWiS+StX8+l37b{=)NgEc#!GA#Yg0nEi{!f z2i*B#VNNuGl68_^3G;Kgm}dBL6G6`9VsW{N(1qn<$uSY02^N1%g4jcT5n+Ae?D2}F z>mP}=i)9;LUiJXP#QVkacG;PTUd3YyX4I3DzV=K#W+J%CGqcr1FrLTaH<6+SkyxE~ z9eoM2-(9Q8BKD-?nof@5P9Fnh6W6&~eAIrk-wtcNXhe3+k3~uLxI}MAjUM4HVljJG zQW@xp-|;p`41eb=$InBat%P~>`?upW&a2Q*2fBP#Z?Ar*UQDhqn#oES>?WH6iy${7*5%QNxYcF|Dvs|?4*LEfywgQ44`%5_S3%|9+NPUxAy?8;p8 zETbH2Bpi%ihXnG->sqrP=1$Hf=%@g%9E}X^;$Df|sdTN}&*_&4&Wwe$UYZ%lEDvlY z?vY8K@SceGfbj0a9(nbbf=A=!`Hw0m=094B=fE@@M_5s{C04hrH+W^U;NVn#$IuMHy%j-0m6#Q`W#ES09%6X-fBr^z?F=8(jeL zyb`44_x#SMYC}`Pv@>OqSR~)ihoetvt4{&9>wcd|HyN~=CEe<$a;K?m69-8hKlAG5 z0lnC4-hjp|^q2GHa6K)&fLj}m4R!RkUJNRZT4OMX>uh=VB-VL_3>>{-kN%=CO~7z{ zhXFgJE%E;?WzeqEj(w9}1x5#Q z6;C7S$T^*4(UB~x65;YW=EX|)jNz~7k5smZkLG~aa)*AmDFtiH;pB{kIkOrV*GCMJQ3 z$)%bbxwH+H&8nUaCKqp!m?io0`9{AFTs)CAMPyD}Y)^@?n9HLh^{vp#pr$6nrZn`c z3WJxt{dtq9SKcE2Agc9XJeoTz1CdHVimC<-O?>Iz+!Xxw0DjQ6X%TO2bgsA>lr%-p z{h>jH6i}V{yNyMoysHb1U(#|%ZO*x&L&U6rAXK-uIZt$UC7Tk^MAsxLPeF3 z{q{~LHl`OwDG|Hm3tufWC~+0I$%n1b-4@{dRz+^=tFvAGe6PZ+eftT2!}WLLSAh3+6Xf1$0Iay@qigeDF`?pfvP z=n+G5O;>~rcQ*<<7rPG^r#a}kD=g|_3cMs4j8&SmZOK_h)$oNs!rQ~t9O zVQ_7EQpBc!n-XyWND*OIfxDvP`x%9i=JN8nyaJ2|f1%f;S!L~H=6{QZMy7s7vmtph z#A2vQ{mmUCZMZj!eX-_lNIcjM!4<=e@(3*j%wgE<9V1~TY|p{Oj* z#6)Jkw-S*pZIdM#Ou>{#mh2qV*ms;QiwepYt+98_TGVWI#?EL)ao0G~L&7fgkEIqN z@TSC-NWNqR294tMWUHCn%!V2cw{ydAuWQp_9c;zw(wo+-(XcxJ8^YRGvp&F$ot&dW zKmQ1vY``xXze|@29__<#2Y!FU@1ybHrJSR(#GQs@iS7j{JV#_CF_A^P_k+b%EOkjq zCr(F$e?ia;vljXT-}bX43Qfaib8>dW#0+Nbd!WyLCY%$`DMs9d#ibsWlr9?t0_>N( z9WDki>HC@wob5-L33$04b2;;+9SGhEPJUrQ;jQIvPSG`k7;m73zAxYWW5>W7@}V!w9i2)ZO^63pVY@T?=W>NwU*)`X z4c(Lr-SiE2)A4CPD_)D}?uSH>su`qjO?sbRb&Bt+Bi8=JPd?^c*V{i#`(VvR;&<_< zf=B;||G}3Aw9PGg4W@Mj^cKU9XI#;!L8p|H6xqe!Nkz>N$MSdYWTuOe$8=mOmo;ZZO1B8SM?CW2J6QSp4w`qMFGhSA2 z!be=3Ddt{#mxy>DxirwJr@W_uB30}6(6Up!-6yiW6>%f`Uc@tLk&*fx?fu$s2Ank5 z>8wnZ==BPgTpDi2S!WdK^j5dDSJDjQoA5q*oJ_o1YV`#cxeG1x5Z1yv71E=Fg%(Iz zbkxh}TUrB{gK5&E0I;dB$Y)sfO zmGFpwBIjw+Fr-|YXy%8P*QkxK)evDJT9acmdqFaayfa9KaQ5>gJ2R6Efb{6?-+8gF z4Fi!Z!CD)UfWO~x)EfhC1@Y3=3*O!PgnzdW9*j!fehKJNKEq$thrBL|OxxRBiz0(z zBCF1kPcrfez!iKWH0~kyIrtoaspSJmVHEfW*8;!r)}m;8qcc)8ZZ9blbBWCU8yu`* z&FMfwX2Lz>QlhulwffG?2znLNj{1)3H7hxVc&t-R0+YuR%33C(%8YXGM8o+d603PU zXC8+XYixG#gxwmySZTEq&d@W;kJc2O?6B$Mm9)0_o-TyBG_Fb5r;h(i14p@ zkWfQRpuXQ-#MxEu(qfZcE9dM{!D}CVSlZoTPhH$l=KQW9HC$Ne`dJx8c&&iVq`vos z;-P<_xYJZJM*n8#)C7eqT%W0L084WtA zvT3Ccmdh2C{|nw%wQ~D~)VQSYbW+cIUH8HllP)gx!BP21P<9j-lsT9<_>yOIU5I!8 zAQX_8X(WtXW1xE5n=NXeH`UM2l~y>ynFuxG2Q=U;Yeyoaw3hUAsTvFHXA>Hlg%ZpuQsNuW z5$1F&OE#nH0g~a8w3l`-8Ibwu7rDG=@Y!AJ&zpk(p%@}^7f~mZ+Xxy&n5`mRhh83p zyATrP4K9ntY|3LWJDvZSY4>?HmI9eBgr5lKQKO7NaSHb_*QgG_7PtmrC=}lH77pNM zS2*Y`MC26cT!99ZBRl?t?%xYs^$qs@9q>w=#77A3XY!84G%JZOW5r#y6jf2%A`e`8 zP`hVeF(SB}Ueg`N$wjM^XjvWAdWiNPRJiK?hN0OKbgb0dVE6lK;Zwg$)f{kn$#Sa4MI+{gHYy<`))ERW}&a)Rj?88Pv>;W zs7{bnYrqv%5C`ZpAO@k_rWLPX_EU?sOh)6>eazYm(8W3b$pd{HubbZAA~ni}{lHOF z089o`nN?0ynwRAR{Jvb~Rg#z0<>o;&l|ib{FbBoj| zv!`aDN0zD9lr)V_16d7;J3y94a1=h~vg31MZr=Sxm>CsjCY=1@SPe3Phli^mv5^El z8$6b^=tIvUHykcyp!VST-=AAR!vEgy$nd#~n3iNYK~_2@_iJZ=j3d{r`dD{gchKvtthvS>;urihw*zCzhB5*?TdSJpCxrRQl=xnLa0}+yQe7k zW4lgLJSVMYuIscc3^s@{NvfPk=Gk!rx5>~rKD1pDl&lCcQm--}^RCVLkSipt4Mq>Y zdWBQ1g#~!=rcIu!6i5@O9M;jo)fC_G!aUwPvQ9#xa)NN0dz(~$e?L>`I44e;;cujL z%lSIGDCuKwT3k?y>|Qv8mb9i%gGPvV(KOT~^`;3(A%ZH3{}_Q^o}sr#xJG@9dWMwm z^sd;C;S{OOO+)i;h}TcKR3wKV3U~JqKI58ZLN?=iyw7ObD!}1KNH) zxzezzvvMl%EwA0on;{F1C1K!U+{)6qsRlZqrSdZ&O)(RMg}=~-2i1$@_AUvVDz>q- z5kZZ@cfJ;xQEI@wTMTv-dEQyW8`FiAI*&N_VNJ62Q`|P>!%3TuoacUbHx{Dy(iV*f9UjhP(@1oWe3HiDRWZ%3 zuq?o(=@jn!yx&A{k-^7L+CX<@QCUm>Wz6fjD%e>LQKdQ>+r$X*!S~;e47>*pfM=2A zxN(2Jh@#BNBOk`@VP+Q749BcJFU{A4nS#^E&S6DSMXh|lNX1SQ^-m+f(6@t66J=|s zlSvEQy`nAsz)Aa49f0PK)-XyV&A?LT`JGGG5hzF`9}LNh@$C1_Cy#%|qvI!~p7ygZ zq6jQ!ea*hhIZ@{}@&i($P3H%F}`Cr&f+l?;M zztDl9eO2sw~B{RJ}fl*e_I}_KHk9{8d zSQmO3*F82BF$;$n-jzF(QOMgd~LM$-JO z>g(mt=Mh-JU*O+Y$f9?#C}&ize%3LgnXEeD4;g8HGU>Z*jl^i{c}X27F+j(EmpCb8 zlsLuTe zaZ7I5s2JDyJ8C^MV%)GQWYtSBMKo-Jc$`!Oi5K9@Jfn02YCrOdr%p9szp9 z+2c5Lg~`z^7uP87FbVDmzlF?gqkA3vIvFg4r#k(X)u~EToK~*33v?Fl8H$a50dIIq zBalJ2n)hlWIG9K)@?9^tll|g${iPi#L;EG@DsP7pxUoX+A3OE13kg`5x|(iRKF*3I z&y$>BdM$aby?iXSyqPd^Dk2C>PV3vrH)SyihqcViS4?xkKSxf-M^~5(z3c+ralgt_ z&L|y61y8d$a>6U&`0xtZz@RCz9&a}!&&0+gY`__tUEi<8Y%n~vQ}kJTP+mV&o}Km|h0zoWql&=0qZ05^BDZub?O{Ui7^)fn-4n&N+yC zFY>ykD_rsiAhOwKKNw;K@4$WF0_4k0_}_;9=ixUFzj*wl`1K>6;@9}?MIJAH)P1mF zM*QSuc%FyfLn0BlP3BUSnT;&E_K{hlu(OiseU@qF(r7bWhS*A8klIV5f_=_tC!tb8 znUba}M5@!jbxaF$Zpm%119yJsAq)D?D>%F$d<;E4xb6Mu^J2*m#dVSoY`U_F77@W@ zV8-CGoNsDMZ&yTc^38Ya>T3NFB6T4Y8|a@da@y#g`26=pUTw5LEn8i`rJm72NLMI+5saLBH`sPv8yGRk%zPt8*r?tf-Y0X&3zq=*mEQ)iDo+uSG{y&3@NR z(k|Rt5FgAMO$ip+j{3`@OLxA%#QULB7L@ysq}Wp@gMPNNB5*P7sUlkt8fAZ%J0!Rw ze9f09-}{W*^F33An;0Wq{ejdfSI)9YAYK78e)>7neYfi*=7{{&C+JlblsTeqbu69# zGWGU%EhD|9G3QGOc@y{)M$zjeUTw^IZLIA`VtGWpIl`Yhik9V3ZMB_gV^U*j8B4s^ zM2eOr(W}ZR|KW;pdykb8a>(_{9Sq?$bGnu9Ms5sohr~ zp_iSH7aj95{o1JRb903wL>d-lN#K}5=ekmJ^;SiMTfXfAz3Nelv3TX6m^EAhK{kD* zgtYE@h%!ftd}}lXxOPq@KFZLUp{_hhx*~K0A>Z1?mMds3_P6G&!bMIuI7pCqi@fh~ zUbp;;>&sgfg)8 zm5O$89cgv+Z>D=gJjnS(ri72mQ(oArJa#vB+Jyrc}8NVYNq0gAOU8fmwc z(Lu5_Wi2n!E^{m#l%8;`M8kF%9YJIgMpL}7AsU%M3YuBrvqnvtq9WceFu(Wr9MEld zpXd3%{=VkOxqR=J&-Zix^Hy7Ed>v`|djH!>n|6UC zc2M(*thu2uIL1HlXv+qdrbCg==93gX3w93}Bj@N|Tg-yWgP^-Wb-~qZs)M2$rTKL~ zRUUMHih@-uZq=oEer9Z7DJbiHLg;9wWI2L3-ZW0WjmrCG<3|~SYHWuJ?oZ_A1s7vJ zJGKR(n4p7xN!BR+i;Hnf-}dNkvf-tzwv_E8qdJ&RsU|nld_HXrZjKl%j^0WZYO(z3 z8|?f7*E;KK@O5_F8VJ`Tb?(X`_0odX4K4=VyW?i#F*{QGSvEW(x(BY36wF^|bwexcm57L4$GO1STw88vM05iNGxi7uEM zIT1QLPBkb&uxrK$=|Dq2*4vRv01>aXzS{^~SQEe{lLAy@d)2}F5tlj3(UZS(=GZagL?t(poKo()KWXbf z(kA)hFK{BBkrr43R%h-u< z_X|qknAad2NS?r}Ms9-66x}??$R*}P(y2d5ZpJIh;xT1S_vxH?TK*=TGo5a-)ABoX z+~$1%xrLq7%`|0B44wLvq^VL8{hTa%DP6c#vUu}nY?vvAGDYVCV@N7kVzb*9DAtD# zaM&9vLX}xZVpE?Y`-zn)SlZY%-~h}*LYC}4tI#;%4i1#ODn!W#7B@ddv^p!J3w z$M9^jOAIGylVFCWKYbAgk0FZAIw?y}1_?d^M#c ziKR7dBHenMbZa!omHS=k$tF9E{Ejb}2Z_w<8BK-{;$PDmR<8fE7k(?qVcYayaKo&2 z*qbXt=%#qew4>Q1G!ol(G#RGcWPq9uc~a{Xj~~IF{_x zOH6BuFpthlU2HM1uX-N`H^H;!eumR&Wy}+O3TKk(=IuvTeUNF|aYXEucv7;HNWa+e zeLagOJwwwy=evl4=p_cO|b9K8ErZ5AYi7L}-b^CM(!gY*?N! z4a<^&4Rk1yT3J%4=fBYkHg{QaJ&V`ue*s1+fIams15bNbMxIMpll|)!>$`v13M;t( zeeT2e5109acMO*Cc`KH&L6{2CWSC+z=m8koWGRD7Xt%p$nm6ua-JS0hw$ry=WNn#$ zg|iILL)L&2dge~n~7>QVS9IIxQiTPDwo$wf*1eTsf;h_JN3?viEZS577zUQ0&t%DCcg8llSFaImYduWObFK)^% z-it3LIR!agt8!b zHS9PFevDzq*J3Rl_ODyte~9`ajpsmD>gyQm>|Fq|dC`0?l6(DvW`+qtaxYSSzb9JCF@9;f1%aiw&kdt@# z3T}(D*cozwTFP{|jNLPDytE1T7)P-P8-CQBtqv@tSV^{nxyfZm&{l$is2 zr!BR2#6UI$=MRKqaW$&9HL6!&+<5F=VzHO&9u!+PRzIv4HDvuF)1N$RILR8AVOdc! z05Z2dN`L$;G;2<>-OR8K$@tcgUS}DYv}OC;>}!sLah4NS9Aun2018NM5I&Y;eb3q; zPCo`U;O804aFGk->(NY&N9l1gO~WL(kCXPAq?9U0f=Llt+TfCzl1T>qoa64B8gpIp zxTc*%8YRFKIk_X}Bdc^lUsw=v4Yf*ZyL-TbLmqswN*!9lZ&XbIh`^`gt9b2eB*zHy z$ZHqi9!zO+yHH4O)BeGsT_nP0_dL4r3S~Lf zQ?S&&Okv0IJJfBj!3-xwEWyp5ARnE*VSJEZDrh)%XgyshqsY-WlumO4@u1XS^`x~y z=?ULlGIPxR!gh=Ul~l7N&t9{1NFdy`E*%n)XSXjMLN|R&LAkHdE`h;-&MtFC-3JbX zMl>Cx7N7fVnZg>gcv)R%sCa~0)6mS*k`853Yi*B{?_y)EX?V7!6R6EjMGG!50CC%U zFq7GWJgJ~dI4&NHEt6sBA6*yo@a=8&8D(;w~pCsQ!TLX|cB99z2F|0z1p!Qg%QwP?#3&1zR%F^}YF_tID zk{ZbpvRWOmW|w6=dDezJTwm9qE3m*J8L!oyrD20ch?D0v&t8$gOT~@fX}~f9uUX{s zhIa7P#ivQ6Ya|EOP=CL$hCo!9q8H*l@N!4w zB2(lag!RJ)*G?5y5JR$r>H1GM%`ejE=LX-L7r?T4U*a^o3GDJO-qaVt_5g1AJVs@t zpL~TE-*(5)g;`V_RVPAKHyG3zL%Z#gnu`&w6MI_xTmzkRyWly5oZ5Y-m>mH*y0BJ~ zzFbERNc6+=fedCh`X_Jj())RWc2(YyyMkZh(CCCgI%$vY&<(J_cSjP|v3a0eo`?ne zNZwOXc+3f<3u7o9#!ad}=PqR+CnY1}1Jw!gFp=yFAD7hDw*yO=+Q1%LtT1|ztul^S zVFxB+2jbI}LR;)>BnL*1q2*GjD4^@oXx4;BUF|nIX$mGY3`g$&Jp5j!~EG;kegTwh%3+ zGK5_G>{TaRq%}5oqc{kcio>9T%T7&Ar%W>cf}B8J#ugMtWINBz&jp52ma2A~8?G&G zL(q!xia9i}J9!fJy>`5!!=IBz`ElsOZjNqBq_S7;VcYUfNiNB4ik|hl7uDS-DW9Z> zlC>~bWP@ThWaLFJRHd=Y6slW(8S!VNXvD?O(2Q4|XBCtox+FS^i5@#Byvq>1Ky}h5 z{krNMOceM~gt*fo>pEpZvMQN)s>2&pox??`8@%vi9#i@{_t++tO|GR?2Kn#$N8)`D zq0EaTGaxZM(IJpk=80XLqUXFMCf+aZtCKO)W!z&WIot^Du?5w}SDgtV;^@=`U)--X zkTKdu#;DROsPISOL^3A`QSd;gTIL^*C7Nsk{kaG-Tk=l7C&GRm;97MWBvF8B8G-GD zo*@7cG%{GhZhM4gY*+qWQIUNX=5Y$HU|e0t(k8Xw3IRQdvSyzpVW3rpATWqk9f3M7 zIy!Qoh@*q`50T*LuJEon&7SDTpk36*Kuc_h%yc|A4;j7*sg*v0|6AJ=3uYc8Lz7Hi3@aR za4ylv>p$Cj9k?ahdlf!{K2wXnM0ceqU?3J53?WDp%u!t#oZedtl^Le*d=&1;`3PNq z+}Ab`jeI=jMTS4gl%*~1-i`J)DyW8rCC#rT5a?Sdq52HTVE)x_`}ID??loK(J3cVL z6d0t+3ntOIf`jwy{!2fKiu++V`iC||kpa2xh4Y*+gD@auIKnU-sd15FI zS=_SQ_8oY8_ibPG+P4K{P4OG@!E<|u*ceIDvkgPGJvW?0o`cz1^k=kuG}Sa5J)SnB z0Um5ZrhTyTB}h3DQN3i>%02JWsWH^-DeJP9_{ud%l=IuG#>nVs4PB_AqO~KU5xty% z;*ly}iF$7>rdtf324Vl4ky(!`TIB2#E;3~Z-9V)HE3QL|5616^UC3i8FT_X*gup=} zlnXNt=wc^gUU52ks)c#wBBOJ-QH@)1z?E;OX((Yj^mwFs!Fp@A0qal_(Lq)? z7O0CwDyIx(Iq0g|5%f;DtdByEbii1P_GApNnM-Z4y{$8X1G%Gr)9XExEJO_5>5b{YW;fc2XfK z(%iTre-pTMY1KXGOkt@M+CH%a+a_*pC}MuM^usaS4lhbq&3I(mjR++DsRin367|>K zf{t~q-*{(9gbIg}wwODw$frXF8yjAoSgmrLl63nTmi}!p$<%-d%Id$9Ja;5;m3h z%=sZpF-C|dyIfMVc0)Pxd49g4?yae$7jN?t?udf$Kxo1mA$KfWN!M=iwhez0kN#9? zd0TAwCWUpaszt8;(EHOzq>bHDsW3Q3xdBKxATzoErT5y7cVh!*NrXC_XRZLm9Sj(m z$T7cgg4zkG`QT-ijVs=x{_h%M^Cq21b7&vu4$iM}^QGl3ADxD9n8{(QW6rnu4~cgv z(k)08HNhPeQnQoiG>L73Y9GZQlLC(g?H?j{O%ENhIUYCreFY75Ue0HO6q@bo`m(BzavJb(8BD6tvl z16K;Z2rSR~jP>(4dp+aho5P^|seZnO7>e}ke~5QPSB#JV33RRe<^x@^&FA5a7eacX zE5_LYDmxUCA)l_V>YjMorl3|0PFbH2I`W5#!Q&?muNXYsDnY#1RV$0gmMxr*W96@S z>9C(6pE7MoqCKy)Qy6wz(xh# zurI=iuEkNnI~YA+u?V z%KUQqlc=dF>Ho_A;_-?Nw7ib824*euFQ4nJ+E6lYCG=0JwUWwRCB!W|oo{axCcHN^)Wh260s;*+nBOJR!*BY3qQ4xozkr0-A}pfI$% zpLyf|=yw8I6Dt3R>iFjNZ3`?!w}1E6m)m!;Q&1dq`O14&+BXE0#~sJuq?S;H*fr-Z zXB68Hf!{tno}>Y-yF3mxLX5S1E%{4EV|lqvAsMk@<5Fw(qSA(~v2@|PUaLfPv=O+IgdSwNzC~*DG<>BY~&L`_Vp$Rma94I)K~0YM*<#PN1pG_wJ!<_-EBY zvuatua$WUSYhZP*Au4nH61AA*@7+fbh6g?o0<=(A@j6=9AK4>V7oDSulcd`DqSoL=s=+qSNZmjchUb(@0yd}c@B@oZ=TS<$~T*DY#*PU)vUHC`g zc<=0aD^uV0uFcqGi;c5ohOcDzMnlQ9$?Q}(0|6pCu!Bw_JT7Q>KyAyp z@Cw2F@mY$`>~NhS2?es8j?u$44wphU6@HpOUM5=86x9R0GSbeFUD{+-qujtvTR%64 zZ zfAbBQ`7?iT(28}HLFiYbof0JRQcvn-a=M~!5;u^ycOmvCgw%pC>QRUNI7CtqP^~Y` z1bdSA31y2`?WLOnC|mjat7bjvuv4045{q)>s<1eVXD6{>P|EqQuEAaCO)ZNk8ep;a zTqgW0$TxgeZ6L3Z$9(Q`Azrb4P6bhShn+h6-x0(+M5A4yao=sUA14pa_&a?z#%~i` zFB{EK*6-_b{`LQRT?je;ztyFATBr*) z5TveT^ecq)O;71JeH!<{&Y6rh8Dd*(_P&FaPG>|f9+~`Y^^V&H8Fij6+ePHO*uu~k z!@l;UUC}*7mJ@z*fK+r%;Dus6YErKlPtc7HA{CJuo+W+9Pcyprp8_5)0VgEAv`+P;-IK&sk% zN;U>WPp0LW7=N2)flGQu-a=13X^RaKa1b1La3Cv5+epiwp|b9hD0y6p0zHfl^34G+ z=P@!_;a!}4YRpHW)S*DmE{SNyaZ&^I7|)k?vrY^s#96|Q#2c5=({xwOeyaNt9Jh43 z&j*ZfC%Awi)1M}CyVL2~$8Uo*fU?2WNv9oA0Wm&J9EpKtPZYD*|rFG|FD?Dblfwr7nf~ zXP1E5k@}@1m;o3AqEdoO0Sue2-F)x&_?<$;?=TQCpq@iT>iH|TlNPDxoFJe--e~T> zP-g^m0YY(w;CdDG<519x_i+aNimL^e9oH&cFX4Lppd{&o2vhbbx4qPKFra340Tuy- zCbsO+hU}4Ooo4He4tqh%0Kty9Bb(@+Sa$JPyXnEXA$d)qZNYv&q}kM?JJgRw|2Ad) zV}m9tmf}29N?uef9Xu|2FD*YUX<{S}dkrwOrXQ&F!~KkQ`*R!U!bC}GE8aKYec=Gy z5EQQP6^XoA!iJ<`Mwzug{XK86e8|$gS#s2xHC7HmjS6~5uerZw98CncS)wgyN!CWD z{E!z4S8E%+WfgTk%LXrcYx<%$rn`5X*i#W|n9>gwq||GxmTD9rAca@ubtF&8di#*2 zixx4ne8jiBdSrE7o*cHzA)VvloT$#xM9c#$EUBqI%%mQfcZ%i}H=7Y|iBG$UPnTq8 zm`38g(ZMAyHoNi0{Q9-5qx1Nf@OEv|;Rq0XgiA83C&xFo1Rx)ZQG>H)_G-3Js=Gbt z5-Qmb|G1WG1*9)i=B9QNqYGV3xN5r6Qx5+6lfLu99&Zy8E~uB6>RmpVowjUYDt;xI zF#K)m$6)H`V|jVE(SHl|Y~+!dZuKx=x!v}H4tt4BJs2)D09b68Gc9mf68^Mv6C^^RPLF($m) z%)X{mkIdLf8vcdQ@O?AmMv~480iKp*O{a9~!KyjWxz&%TUSP7K7}XonxX6bIR4Zvi zc9cQ?0m zgR;%VzhFj=Y-JvqXn$UN+;s15~E~U;sSNCiP zsjD#*(~>E188j3i1>Ru)J}qm+xKH(Ek90^v{1!sKnR&BzUc&V3?|0Acv``D;PPP)0ZF}e$K{A z;a&J^lo5mEvZpvsAm#Vl8%98G)6lg)kkA0?i=S0G0Ap(Q1={yF*!SCy?+=855;*jU zayga=@%I=MT;mRmfEL_-d%6tYxu`?{B7waH!C=7OIq5(cTyx0-QQNNz=+rwv9|+4a zj8pkvqIIePW3ENyso)Eo$WomrF6TS~CQr9|6qa<;uzI;eJ#s>zz}H37z^qQU7+Ift$^O8^N2|-^0>zy?3tIIG(Wrz~r z=rcYj%6w0#d+m4iMxTHo&l)F_ooa+x<`=!YIa&0xbYVTEE~vG&(Kf`Vj+Ny+`$x2J zo>}dZ8r35O7hq!}Qta-iX{7XzE@!P6X$bb4k_O`;ot#nptp0Tr-Be9+2$J1+7rcFl z7UbI~_4_xqbXH@m^KFpYiJy+JSoS^Me# z*v1dYLdl2*0A^p?R|ll0Z);!qE4DWFb=h#N9~WIat=4j(?^V_XwR#Hamt!z(lS`_P z<~%!m-YdiYty|`z%UOw!ihTkNMEW#He$+efm4Tpp{vr&mdDmsKR{Q#~_+dZDB58e- zbVK7tH|!0EBEWm6ogX8LFcx3=@_L(ZAPoBtYHMv%2yejFPMYJEOH>!+^Im-w5V}!- zQBHLyT(%}9g*2)k%ld$>o^Oy3NlMk*eD|hp7y^yg<(J8aqai{w(VKa{X*MZ{DKoDg zshSyVI4!}k&5UgjCQ2;Q^VVf~w|DJnSLxu5>p?(oQp|f*zV@W>$iCof zo|jB;yZIg<{_c?@E zNw)n|<<3Qi8@hd!weEuQ+Je1-h{cFw%3sVag59j);Ao>hc97$19S@AJ0;tG&S51?O|CW4Xp5Bmw#UCzPH0ux#}Ua50#Hiby>(-7o_>E#;JO zAWWWT^gmdKx9-2ls7FXfw5P_VWHahFTSut5>AWBS`X|XtA++Gy=DuLxT-*}63ccnNcS>l)oFpZ3nQS3`UpB9Hp_0L1!i5WZGl2K!5 zoK_HJe@R&hCvz3SVZ|HO&uquYa3cZxr={50pa~+8&_~x=Ce`?{g#g_%fEZ~$TI9`Y) zLpgqs=%$Rr;_Ne&#&$w}uxtY3NBI^{!Dr5Qtk6d^!X<5|)kA8uhGvd54&uHhq&E+U zS6%3J{6KTQ!U8NMZOBF$9yb0--}dLxj_=WqYor};+3r{1$tCSj`_w>D7(!|eIq5s@ zLy#ECK^j}*IlV$?P=qz2C?0o~djxi}#RzV4fe#Mm^#rHHPm^{Dem#<-#Hao_RA1X+ zHH?ByBvz$1ns2-(OcPp95|FvMxMNHM6jd5u!cs^TOd|FPxSBC2qdmlSM3l`kOWl1(mA0@wNrdCL0r#{ z9ew-YHyoG%JAGS#x{Wo4F+>^cW|m$B#{4ss`rbp|mhce$&T)_-=0P%urMmWcK)L$2 z_!EYcW=P*H8zzUB#T6tO8tVy?)zh$@3znsZQ*Cw%EVO!msPk$5kO2+#bNM$(z}h4&AzINgveL+UOxq#A z)8qYXDp`0=Ki9HBi9Y*})Xt;7us!wRu=I@d0CE*9j||q!}lq;gE*s$k%?@ zG@88U8W#bbWkX5!gmNo~7_a?~aY^3jhiUT9BTYeq#mb@le@cU62M*Z*J3OB)1;XRb%WCOJHHvx0lE_B!23WkQl@4#XsaBm`J0&(h^8Eb@@H-8g8hz z_Kx>Wt85#+H)stf?3{>u_a;e@CjoyUBh8aiig`hKhlyJ%9LzxeoweRnAkz7J7UcyX zT)~8Kn|JG7XDNI4i_`Ry+PD1i?^$H54Tr~fIy zaZoEKd~Mjp$Vj?>kT0MMp`}sdWe2fJ`@8EvQk;>(FMW}^`(VH&MMTXKmuyy`pLNeJxJT};8Yl?ZLc6zPRHd>V)M z3_MbyLsorhru~DJE(Siuj${`FPAgbaB(Y@^zME$`V?LmW+q}&X31Y7@(P@Z!fskFk zd^!BwD$O0NVa}_*T;Ssb_8H=4$b&iKX&) z!VhvzutHtvmE&Bda^M8}EARwM6UQRWnkdLDi|ggWqOhzW1;wnp$ibKk2zN0ssH!cZ zUm8+Ro-minQSdGWIG>HN8L;S9#Oz-qKt3}?YQiA3wiX3i4+^X+cyT8DOQbu0uwHtG zX_58F^Y8xpOyG#iSV_wz5dDax>+6U*8{YLxw7{d&(47&p;oIywNI&)Y9jYoUkWlrX zwvprEWgOpJxukmj$PP|mQmC(aW5aM@Oz|~MQ5vTZC9}ziy7@BvHB&c9sls_A!o1`4 zWGBIas`x%%Bh<&2LlcQ{-o0pP*`eA;DzhYS19ql;8AE|_uU;{-k{2qopfW^wD+PO_6-&e=F|4_&0`OdFM9nQWwjv{>((!bZ2r_iM} z09%Fo&teBSDp^L!Pq)0SB+3l|!L>W`onKrc6`32wHhzZu7m&B5FaMkWd;Y)WI}Zx^ zJ@du<70B=ZvoI!>c`i=NWEmu=Uzk=hr|a^ae<$q)8UbPeZoXqe8RsMf?!vp($U8>N z8#nXc$LF1V&%OuaV?KOO7@tMRGrccQ#=qxTn(y56Adja>%rg^t-W2nw|L`Bibbh{h z7ipvChS;toq^}p(MV!u+F#TWF_RIO^+6Q%*AG<8HYdG>~`o>U$I%HYDUrU+!nop4l za1R929r^*%u~A=Kc2Zn3jCuO--fiorOpWo5ru%AG)9Ky9#q@O%x7ePYVpN~+HfLc(tL_{BUl&sc2U$coc z6$`QSVszqQ&nFif1t}I`9#u!w%JMZIUs9Vs4e!eSzJgsnQ*P9}0J#u61y0ckV7lIS za+q+gSpIqnO+vW&MCZnfTEx>7>Ay=-=uARXsS%=gP?WRuV(X8hOI!&%Kfk;7(p#Dj z(E^NN3!JsED>OGm{kqG_q;_0*?_4V*ZJ!bWp9H|Ge;#M{d7L^C32DXbWAGQ{t-b4I&o7-bZhg>`fV(jXkKq5+ z9J~jY*xV7L<4V@5BZ?Y;(NidIHNSRreu>oq6}fv>Iq_k*K1gA?=#8oSD*rY)flyxD zx(fA@D$$#6lqhRU0RNrXB?l>06QUbh4k$~mNzQaK34^IH9ikafzj`KWbp7^ zJ*^5(geqy?ml+@WDEuMB&9CS;01&+_Cy2gW*eROZUMsC#R%~Q5Dy;&y7Wpkn2noC7 zCAhY<(Nl{z@buHHZeGG5Glnk6D&x|p!f%|=feFhdi<<#ML+aHLs_a@;$lRMrKFJCb$;OZaSfoc)RnzUQddAsF}^ z$t=}dvtP&=vJ~Rkuj5y(--jrHdQwQ-Qdff1B&BjxtVvLi#k(eKCMX!1q}O!P`*@3# zx*cAyOJZfZr^u?u&wR$~k~n|$vTWwQt+}$e6W)4hC42|LyN6(NGPJ(WA$fuUs%^sN zc={^l5mz)W6}iu*;@;avJVd|*Tbg0C>e7w5hHhF07cRh^IjA}d=(BU`B^zzzX=c@6 z83f~S5>hsn=&2$bRH0w=Ot}OyPmVg$xjJ3@J6W$XLyKK9%Li|feR@r2=xcF!*PdM? z;W%Hc(42NjU%YiDRwvpl%GOynU3@e|CDw5$Pf(s$wtfp*U1CnTq%Y`8pYZ$i2|A?L zfdCWtw`Jxwcnh=Hu}dholBxJO3KK5|1jeq=<W&+B0+5%NCo_Qce3U11(V%B z!@#EX$X*HjrvljLc~K*S_Oj3S$nfQrKoY5;p2^;GVVfG<1vC#$@lf8pWWuY(PxI>C zxb1DwQ>$B7ye54}`#bI-Ox6=XRtQJ75u7zgg!x^8tqG~_781o(LfarFy zE6j_9MJYV9ui|-8|1)rlC-D5b5avYuo`L6u{ojF1ynyEg!gDip*)hj)Q>tMF=CmQc zCdB3ru+l!chB$jX12xu1Shxq+j#=)Z5$bmU)R>)3Lf&pE!`rFGMyBJC@(f!Ph@39E zh;&xN-^Ri#LJXear_&|{;%diQdd~wNW>|~)xYpu)T!k~K0`JeC9G0|}tTp(~{Bu?2 z+&1I4tO?;0HA+*qa@h=0UXgc!FCP_NR%cmUg=f+8Nb~8n=ZJPXa7#!MN)p!bcJC%- zv4KZ`K)RYp1+Ni-DXda)y!^L!o0<*V5Gb_IdA~De-O#diNU4*k@>kN<{9ZJC7?YBOm?>yn6Gyllh5I%bgeNe+?ISE zx7Kpihf?-N3nFqFg%|9NZl$4v-d;O;1soWP4vIWooj8{<)*};*^mgL|ZT6EFGq-tT zWq6l8+-Xey1?3s(>Sc0cvIn=Bo4qbsUW_1ahqk6nuza3)7V4U;O9o5!udn6BJc&m` zRJdDuzU-GF`=J~E#da+;2&L(AT~Iy*+++6hE*ZcBfhxK3A^TexT~G)YohZlJ#PMeg zW>c`%4as9sACzoPNDOqfA(7TZ+df(Bnf$OzbT|KfMiYZ1`oUy-vG2SE?}AHmO*o}Qy_lq7b5IOBkcPkdgwDyS9g|p zQ-O$qSq@0xsX!D>jJU`TNC3Z@x+>6b>W!_09eWU=o?Ocb`iPhVmd)GBZ+l~vthNY# zby)T`ZwN=N_?iDG_)Sr?W1j(6-LMS?nHV3}zo(wWvftX7@Zz#CG;O2WH-`Y~% zuPo;-ymf>2Bq3j=ENY>dyST zaA<52c1B66cKee>+YC$-hraQE;3S3Nd4@NqdZr$`wmdN4h$W}2E*W~#1xnh zLN(Sr^G=0Z;du_XsS?Wb?46jztL2YF;XK0AeJAN;M2nPt0;62`XCOPAR2;|hqu$IT z-h$`XK{wWPp6;eWa`_bLt;V7_t6^4PW`p;vXC)#w6sb1|$B3hICS9fh?sWOJ zh9xi$_6M`S%}zrR268Hm>(0!e>KmkaJcKo2-7-msj4F!bW#Ak0GHFquQAW4AVf%z7 zs@c?88RT@_DFl(T<&Fc@+x_{YgfcNY2dN=Zp4eh(xuuXES5z$j|`lz-^Y)7o`$xBwRLuslbRO?5?@Jkr74?7XU zHcZ2RTFS~xP4)8CMFsoT)f6n57aCYHf8FeoCB;Rp#X@S$x=xIJrLnBa=_NSpA8_M z9Kpv?DYK6)Mf?F^p4rbd2&;n)!{^r5y`D9lw>*)c;5Az?k(wvSoH`T5Idvuob9!)T zJ?;7S4%qBcV#F!a)b-h{inzso#Pd4eFFOZr@gttk^*^`JLxi?%rEUo^$taaYN~04=?oc#kLG2E;jT`WMF!Qh0Y{Ic8AA zp_T3_*N|Z-L2xvKZWIqEgo0+o4P8nI-jJ6AZm2fih3LNodP9H-Z;ImpejM4~_W(N? z7wcIlz^TT~f~?LGLpBa?|I}u`Ie}iyZ?v&&KF+E(l|_S2TI%~lA{2|10!&2Hc2FwS%Ii?IOCPAlO&jyKL@Y3|`$tTW6*+>K*EYZK;x z;)S@Fl853OewZu(DlqN(^m(4|gkQHl z?p}D;JknO+-&0$AfXM+qXl8b*_a4JJn_$wnIG}!HHL=Zz)wDT+*CJ?z93@)5B=x(b zR@gWbKBkTyT0F-uUS}XRCYZ8z-k(4=E;(8#CC>K0f{tH+>-;ZRx7n2WNDt>rWtz5S zIeeU>uftkO^Vs#Q3rh92inv=)O%Ko0AWp`*=btl4hdt>VD^Y)VEF#B_0t-VaeW!N{ zpRRPAq#eF%?oV+jY`{ETb020v^IIM#)1nFsQO%L21&>SG5}^q}m}L@S4Vhu*T^G1# z-!KSit&*}_TARV&<${ z;PbQ(M-O}3=lSWeWV#?N#6QcI-h!=m^=rqf99mz8RBTV9(4HWnJ$HR^{`h$-_DG+m z-}W7nW0lOdFIkn?)HIm%GM!`P&ri>zhZTlUme0He(RRzMW5cy5NK2RbLIK4smgRke z^es`2p1Xb5IH0ZPyQboau!@fdWA2?YFYqiEBXrcm2pyF?O_Ml65lfcpwr0H}QJ3Qg z7>aWgoQ;gukG;+bozAmf2&m!WTi_xvn0s?VCr%OSX<8KOlC}T%F~bSg$P63vti4H& zZ`sA(`N`=_@kz1}9fujq_oQLPD>CArTh~F5=stOH7ny54RUUop4Bhwxd&w8ZggiU! zX8MAg+5xuHQu_w`_pxM7p)kk!Z)bhVuXz)Eb<*uI!G1!drHrcerI$9r@7IvMoWtA1 zP{Z$@_1Y6gcmE*8U%x85eaVE;6(i2Of0V8-^>Lpjh$v~`+5PtKM+~t-dN_3$Ug0OK z!&%}wCp)31ZznioJ6T%a`%R$&*+9`slj7}_kphsh3?M6-oOeAvVLQYJe!uXF$pol`rcK5GhIAtHbC2jo-n zZSq>Vh7B#rT}fsQu;GznLvw23B8n=DhBA$TUSqPq&e<0xMXwZmda6%)4Tz|lV%X6F zR9xLkp2`^Zx2l1p?5j_FkgdNdjDQ4(QY-n{eJCYKo!1zM|2^M~Qh->t-*3k!H5jX&sHj z#PkKD-&C&JC^#O3>S>u5l$+DH(^Gj(ZZ1aAcBW@@HAR z`t2uZM;Bs1h@v#il<@=>VxOxLKuoJZ`)Xt;mN;%8uGPgmVp^;F0(K+0u=Nove1$u~ z!k129YD?bGMZU&8MXX2gL*jbcMeB%fZQ`HbJPj%pM%qU}FJ&$TIGx~k&WbbA%2{e7 zt(X;Pq~)#i`>?;Bi!+mfBzFKw{=;B)YLB9IE}8|s2j{(u3CZYoUNRXi@T@Sn*y%7* zmaZ20r?d2^jk_{d+ZcOIso(J|&p6=e}3$Jx2FbF{}7!MWh_d;xx z6UM?F)y!SG@+4R?PS}Mig?+ab`vP#lqT32ztHnnwk8i~nk<|gl$FOg}x8s$=fb^la zIH17J1+jAFqM5KK<4N9fVIlN@uTIWU^W}@po8i_xCoIPEB+)!EKgq-m*{Xx1t?3e- zeSV`|3#Gj0b@~`ogP-P`3*lWc*!v8CHO?L#?IZd-6Gvb|oQ_sbQ0r*L1VmevgC8`3 zKz7f$i*al2rAyOnQZNdotWtly#dwl+$cEK|;sBgM(CG!rA=a8w`^FDSeb(DXAsCK} zPRg;fv=YHf@%0vSETN8Sbe*zyUB?FlI?be0_M={OL*0+N~Pn2`T;xQTU29 zG4X_JB8*+&7>c^}BmCog?oYaYVp!5qjK>G(K__PunN`H1CGccI_8Q`5+9eC5FcLSn zU(|o+n93s7Yv&dY`?Nj%$G@emE}T1@0n@L4Z}*IJg=XyceX)73hJiCHj?n4O0~ebQ z0VdrRV3KG5ML2kfj8;jZ*#=Zu61V080;nU1DA^RGX@n_<1*B}P^=#{-A7FXUVnBG){y0iPS(%)$z9Kw(Fk-o6~YH$ zx9+^yCl01&Kgjps_^rLzxP>YoiHw?$?`lSkE)Fw`zF8(CE!8Z_BV(Od!PPpo_F?eScCI__&t=L%zcG*F#@P0Fz## z)wB~HQA}vu<7&z88rKU_4~^^j8^%y*+uOc{Qc8Vi3o2Sht8e4;@TJ+Cw`%3!L-O>? zkf5yEOv?kXSN{|CU_52aUlGsl7_Rv2*fL6V%3}sp_Dlp?4=1e0J22^3)O78 zsQ&Ms-#Z>wA8Bsns@2J-5alMcYyvyjs)c?XFs9}e{E;5qs_rtDmMxriVU~$$%vO*I z9?;Wam)LxvC0+9AN_)wYBa5rIZK9JtA&h`(08MauT?6Xb-z+5YhZoOV;tuw7^e-oX ztJ=L=I3Ot_7OKumvUU+$_+1!x2>91sjN8-0^`}fd<)tj!z4_e@UpBA<5VB7Bwz9lt z3o1U~vvvm=B9Zgm8N0T6OQ}!U-nHBRR_f!3O)1L$YOzo`$Tw^Dk;UgN7}VM=BuAxR z?dC0|ejBT7+NzR`4QD?sfg_39Rn1k~>k_kGpd4XJRh7KSN->VSH?{V0Nc z@0Ygtj8YD{4AX>Yc(7>kzD*N6ti?zBNV92_f`5cj&6KH^c)!#=#VNKzS~lL{Bg{ER zzjPpo`;O-5HEHe#ui87*!?5j0xP<9H1M&j*hl(h1utNPA>od!@!=)guFxPoUDPU9m zEzZV&I?w*)BomJ}Y(w!pTXB(0usPD`;@MpXn25KpQZ1h#|Dj}p!w!?!HY z3|kfd9UH7mAqQ4$6#m2X;tU^yXzm8#_@=j%Em2t+sxGqTewv~0}-c*H46LRMdySlc)DVBd@AA&rRb(q;3Mx_ff7$GBMf@s1$)iHHUpEWv$B;n z8yiYiuCyV^hRF4mGG0ia!^*^)(n#J;m8>M(tgO>8g=?r;xw2UhuKtB=cJxul`SFod zLQq0*%rY2ZGiE4M9ttpz_Llvib#ruZPS8Ns$W7TMwi3q(@b01cKZ5wy#P=4@2M{sO z1YfA$SM#{Q9wKGB4+ntIbXYEvX*{x%?Qt~zxo)%b%wyz`f7}Aoyv>k&AU>195IG@k zlQTi;ymqynVQ1ilV0(zlQc2h@=ets?Va?CH@`LV3$-#eYzL`Kb9%giQs;g^>E?aVj zCBiC3CmgPt?{1C{lbJt}g11&_K)4>AZ~l;Y-4udz#(nomI&ol*Td<#i+Lm93P6P#jE~YfpO5f;j^xrur2yQnpQtk4;f#A!t>99+`F^#mgI9*F2*VE5m8(CbY7mvo+k zj}^m0QZoB=T z>2~}42#5Izg!KS}A2bzs6vun{Q_dIyIA5_T`sthVNNaLu$Prk;cqn1^yLKM2cd{uGiISu8 z+9VDIsnGe0gpXPPzkb$I2R9Y5_PJ>4qj4NK|0j)SPEh*i; zoHX3I;T9nM+{-RH9lWcNSXKIQn;%B|0n0;cU#`pVK-(j97A`s!O4j0Ml`e<$Kv;ER zA7W^n5oBu+d_BUxL^Ygt2M0GEVrpu3IqZ~mPU)Z9fCgs&uQOUuK=-5yf2hTT zf0#{WD!*nQfyfm{bnd$mSq-dw+PsySftx`-=V`(Ze7X40mSrUJmMvJ8_elQwM@BAt zs(L98YxtR5Ud)8DFCClDFJ?FMF;rgp$buCsm&W=n4y$kkh2+IZ&qBVa;DcqhppaFA zVF1n>L(qZtl=L}e4A0PF7+?bSA#ewK@Q7+r%VTouKb zkK8|S)FQ2Df#+=Y5&dzmO&jiphk&4vB0`D)6Ba#%>d!mU8E~#(9~4F2g9GrqAmX^> zMNAMw(4eHWF%@&!;*Z>0sG249nk&-C(XpCB{O^zdn$aASpU ziP-OQN4X;ds^4O@F1l0))#)M~K6!%f+24<|S2moQLRYHFo|f6g8!a^*^$+ZnMKwC8#%=ldiD7hR8rTyEm@@e8zJ9(-n7Q zU|B|EWKi*a;*A0Rf)IAW{QhOaEPgY0q{;l zCJaAur6$0`T3c@)yxd6OQaJ_sPqo=^rd0K;U&cCK^UMO}OG-mH8MEXR{<{(0KiXO>v_gM4ig083Yh$`MIgs#3_Fr z!WBv={4F;5aa{VZC{xQgVBqvnBM|!BIC~n!^9OBLT_=`4kbrhW0u7*Gt_S-FbT9$y zn$8QXB6HZLT$%pkTg2Ilz<^ zO4CW&q@uG@WqI&5C zA1judH+PyNDzo_RKffbQ$mH#G_BUVIq`rI(waRBGzoQ2Zi`b!jGNISea1*9$cWK8U(rR&2bspAd+vp7^Mm1Kg=NQTMF>q z^70}qv*Ie3)O3nv8O_Ds$%Xm9b4jND}nbgM!N z_VXljB9^6#en~3eM>xiCpgllH$bD_Q7mi-Y`PSK%%Pdpr^UJF%h%e%3!At44L_B`@ zf=h60SbG8?Sc$hqF6wnvn@^>#X(-st2n-?ZVNcA9Ul{lQ_<9%krpo(&{N&`)q&+}y zgwhKpr=(2_Xp(|$xr{W_5-x5KpcbcFTSzIWn9nH3usTP}u zghQr58W0YL)GiY_AF_>|lIusb7RDBzV6l8CA4wpG_Onn#i~*M#+W9I;#|c7CU`={|^V@Cbt!XXfV1J|vbLvuG)&GH=6ULz_ zc+lWYcnF~Cicdhe3b3EAxe78+AU>vN&J|&^5XMd+m1OO;lt#akxG^QRDEF;Mub-q5 z($l^+L!{KHLP2=tWvHzGE-2(Xhs`(I)F%4l6JVe?+U{xa3JL!tpJ5CBDJc#iFO5LF z?(xr^Hp|3VTe(tVrG$R`2AfX>aPw=5qUndsj_F(QyBs>b3o-Vm0oQ9W_DqK;I`Lb0 z?fUcs1nZ}uv*;+WISQ;OxR!UaJ!_>|xg?${?~N! z^K)F=KMZj9L)P`c@6nr{M-M1dQ?Xs;^&&_v(aqqGG@PeHMtOWf@osh5W5G%dc$yEr z6?iF1(DZWp@Th+lk@|e;gN1+k^=OhTm0n)f3IL2FiKuB}FaCUnK6#I033w_D%qTna zXiK>(p?#SF0j?JR6OF^iv_ULCI8O4#_k1sguCDGwe_4F}-$jAl>Mx6vS=}pHO^}TW zv)WEpSKAfiLx92h*G13AYmS%29XG};pI>f_|F{g^ua_5a`omUk>Ruz@Cyq;ggy6eAHFzMA3rw zs(gk=m4Z|@75o4d462X-^SpqPhhWpaKprxBe(V%n+t_QiHxc`aRuVoE?XK+^V;=*!|*faZ^QR0^p;-5dS%X_ zZ(fE64Pw5+m#K_bUWP#)`h^y`U+RZEV}CYycxWx8{Oe-`gGC{2VvKGSOfw z-^(eVQIa|Acr~(sr$zOimHG!=GEkz3YdWhXP#F6_jD7j~6*(!sm_@};4LrTzh&uJ@ z;KA5P4J=-}&%-FF2ior2IMY4nH3o283b6UMK9`~e^NUY2kjRi~58Pxub%Fqe`NE?oF9 zsNEXYZmIuNtZfUvE7k`G4!%4PXkLH%;9PEMP^;VgP*AJgTo%+uZJr<0YBm=HwQAaT z1g#2;1t@UE?NxAdP;BIm^L{AE>IP1|D`u=tKXq8l@THwPBxY2O5_J9C;TRvF_SDpTa8`Ti-~%$E71X3Nk0F%Kccy~#@c;MbK6^7+`$JUEwE58dC(IDd!nRp)R*I!=ew8$eA5hlSWw1zDon^s#~mj804rn`z% z+lYh7isLz`)R7Q5i>g745%Z{hJ1BHb0h~SY1$H^Rm#4Qf7o11!3wU_7%86>K&VI{HJIbAK-LnVV`)?PtL!)TLZ$H?vj(krLiEjCocX} zL@a(+Vs@THzk2XJith=0o%l-qoNz{n&afq9IDV9ufF!> zAeiD%U#V+jjbDjHz35ucdUWzeug7C*a`U2$5mED<-0xS=Z#(eHTfogX^jA&O554Hv7yp zXi3Q!K!H;j-xhc0-A*zaPSF>HdxS&im+?(l;%Rh@pHq1ME%s(*7!Qbs#(+;pn+YIg@EU> z!PkBw?}~ZDv^046{c`%KPH4z|Pa1OAeKsqkm;~-V0NXipV;;|&eepGgv*()m8i9+S zl>(1gp0yn}JhT#WUVw4J7(K&+OEy8NUlP-hVEoH>t)tEHhPIB)qx}gnO@8wZ{{lk# zc`V0+X%{wU_|2KM-=~b@5?;3{IAzm%ysToGapSmDJUF6kYUV35ICx3$S7th9GyH7Y zp5ga~pG}}^GiO-x3T(3pX!)c&`PnME(7wperrnP>XY#W(QnE}b8Es2^(y#d0#Ax8P zFXKqXOMVNskV2t1nZiZM%6I5TNkZ#L``sSs$KG`o%LcUQ$iE8as8_FCaxb5N$O?iQ zBEfb~0|LRQ;M^OGF29-refrhpV_dq3@-#xVR#W%9!3C~kwz5LaX2c||d!F5pvTa^T z2bX$Ro`U1r_jYu=(edL~P1V_rlU*3-1oO!3!iJ>Tvt}hZP1$2H)P}JgyfkhV5@8q4*FzQ~Et;YDQOx{Vu7|hBHv=#)V-94Cm!!OT(L!ISB@k;x&)HWFo($%dA#zX(r94Fr9`DMRFnK}?-M*TqovY=>y^6t| z0xRq2&@Y+VcYVpeq{(^ttmAHizX`k$2B+W5HmZW15A6nzJeH`sCa5)eaXGEf;+3JX}Jl zO3#3NWaq|!-gt-5Hgo&!(i#Ep&Tty96yUA~1DeR&=Lo>C=12YS_iqlp@00NmZLqY zs}9VWMuH>I_VfQEJ~}B+*`Vm&Va6LU-9Y`KusjW?_HArcRf7W2x9VI=XaYcURJhU( zsK;}yJG^%g`7o7(^19ONplglfyvPYNGg$_p`TT}`7mwXCXy7{)p&!Hw|MztmIoPmb z-#rT7Q_Pn$rys?&aIf~7=svVcgOzRl z8xeF1eu)<1qhT3G!0wQ4aTdU#fLn1o;g_)B#Ya(L5ZB92x2@b2i+qF z95Eq738~B?!>i{ae~>buh737_RD;1G-GZo-l4roAiju!_&UC+~r_G@>bZ)ZSyE}+S zZ#oSdv~O4h3EDdOkdblUH&kA{T;3rCGah=!bay%-{#Xb4C^wr5eED4H_nNJbMk+PD zvIAuvh&FV0a7~dOlv&)SbT88!+XYCM+u?3L$0;YMxrLTukE=WeV{UuX;BX|%^+dk2 z@ST>5&riv~>pmlU@9Dci|A3+~@NhF)C&4zx-+Pr}p7ZB;<~d#9t_ekplF4rQ#fAEX0~w1gH@^mFZ;!g}pPNgV+Iv#*iFHu@t-;?*}A& zrZ^C_P2(##qK&jcOIlDcQ?_qY3zA+VltC4WYNeoHs|ithYbk@o8%HeMhtR?0Wy=f7 z=SP=zV<%!c<#Q5=UeZ`^&TsrdYLX_LZu0vItTk&&dNI5fuaLW;9|=#*8WFNtPz ze3hlANPhkU zi&%^wo`Lfc?Eg{=s3xv`4yL z0eh|a_!^Xb)AR6q3%>UPj~>01A(|EQfvJVlql)w->tYcNvhZ~-ho;;Sg(<;@2Cn!6 zU9n4X8Wa#j%YQS_$s~0DIW8IEDW)Pm2`6ZD<#YgwE8KgL73a97P}=n>1>V`%P_O8n zAp%2sa_Yz?mb>2@MF3HN19UPIZ)e(CTr)J~GpIJ3%4%sdKyxNoNPIVZy#FM6tvR_s z(P7c(CUd!zkgm$2HIaHu2 zM;%mIy$7k-;xyc46;O8XaakXD%Pri~5b9JyC5k)6`K2UeNx zz!IZt9C_>=mkE;KNo@+Py8`CH3#$;a4R4O9u&l9?P1%%Mf;snHm{p`XphSj9+>Pge z>0#0h-pQEqBG7O9%|C#@&^uIG~O^Bg=E2lkGul(C%Zk zaM7So*Bxhdd*UIXkNg5L1oUlSCM!G*f%)$b%xkQ3>7weJUxW%#b9L?N`4>evMFva7 z+wdYrP}VxtuO0xqx|7v+93R`!kr-y9-DxU;jTUAINTXj0DXBu3u@2V|kLXu1+){`1 zX5QQ6QM@arx_L-)i3Q@|UbG!Bu!uu3GLJC7id-Vq?)^bWo>Zy#FM(!7Uu-l#>*5a$FSY?+=U+w4Bg& z0emXh2)ZO+Ay$OSQ{KAu4-GqA$_avwtNlpm>O+EFCyDYvCB?J`0;_r_N6qmGv#4JXTl-aVACRqK5nNov}# zK7BizNA5|_tF*Lr1lkG$Ti~302@cUt?Xp!Gr&6Ope;ny-X<=MA5S>>U*w`_72~==f+(1oZ?F!hHaoix6Q**wsGIlv{ zANuQU`cIU;9nORXturz65yhNBE~V8Ocx96NBX-VC-;OPB9Z!ro`e8w9QXnufvYE}> zv1dm6&PlBablbraT@8Wu{lifWJ1R$)uAO+MBLXTi`SrSt;{T}dsmgP$PCLl+ijn61I@WBs2DnQPQ6Yi-iE6&o zO2WbQ2M0Q}ny_x<>r=H{8aG~&wS=`%xSlHL64$)}?coEg>E9$lSc|qkgmyBFQ_=?m z%M}5VUAOSTyDuUpO)9qn@gSl3vAtv!!`)TURmJ^$oG=8IU( zGyu;?p$-?zQ)SvO_5Y#D0fCM2M~&RDCo07!IH*y6Hb#gVxo&TQKsM^p8}=lm5N<*z z@lRlNf`huyuv^e+kYyGffVd>jTFbf}96eOiL)u9MHeP_mJ2@l2g%3@+NK!IrMQKjm zC*lyiJy&i>Xa_ZpP`##J$lEoyw}Zrav?dhrr-mM<-e9RxF6 zMY%M>-EV@NOu1_((J)2X3=UJKV|ZV@KvR5KWo;F6eW`i+N@+8#;MT0vC@i@KTM;cX ze4qrjY;{(BUM1(t+r3(ur{55zU7axJPsHeDRwvk^6rLP|Z6>9z+*G`&|E`HnE)@i} z?4-4dCe?;jmB90%Wwfe%(yHRcV^53QzpIpC)!ib^6~oPtK|;>EpZahd>+@5Z`!d?Y zEJs&W_@kxGjpt*qyS1F{H}LI&V1SQ~m&}WH^9DY2^&(;?r_xMlMMSdN{?TAPktV4g zGy^AR)29?L<1EVm4&}3q9hgU|2QbDF4Sv^iiW0W$M8Cjteof*a{16oTSx(R-uGf}34L zQO^L}aBi10o6Q?h)$7vIa-|au7f^IQf3N6%BWn-2@VH!c4 z5tW*}U6o4fJ7R9tn7olC37LOX%vr=$+0=^CC5G}l250&Zwq<77ANiI8%eZRFkT=qo z@Tx{J$5*aZ)KwVDC3a>>sCeW+@lHhgB&!BA#a(%0j*Wci49)QtX^uA!9NQvp|Ks4; zo7PBUZwshkqAO1`z!v#Uf2CGhvF;~f&5y&^h_5`~gy3GO9zt->4-kSY8yucL%P?bI zMi5}(13{j=y78|(eeoL_PvC><0UV0AFB(k$7^Qar6cfkruhep>7e5z~#xnrDo9%Pu zG?CSE8?$3NHxgSFHvN{VvE4b5MPm1PlzBWr!R;WYd>u`;ylJrSq@@QAlteQG0aMio zEW{;l{oWENwY0?suGs^DQvTgraLxgHkj0Kj=ii+zk6&u%El6+3i4E0gioTcmgZlxC z#{h%x;Cn!ZMS}Tu!2B)zCM`B33C%4SfIY)@!{E4v9+29++hyc8#atw(BN7UlJpj#@ z?fRhwcAu1}C3SGMbdNJf_gvyP>1hxMb^c=D*yo4%=*=ZiCMMU##rfk)mB ztlZsqkFjlf2ZsH#fXeC9Heo;Y#q5{qCpS4rR@-L zc+T|&+S)B`0j^Tsi~H{9NTBJS4sbkn663&z19k+6{PkI3)2xf|KuGnd24F9={n#== z+9M;2rGC;PA(~He#OaD)I z7fR*!F5!A};`QmOj08>-2ka2&SeFo2HJs_b&vYDPh2_SjVDq%T-WRB8w_y7XXlxR- zT>PE_t7IE(L!fCXW#lzE1MMO-0?*@IwGgz`QnWJ#YiAVJOrMCevX|kqL!}yHz&|b8 z%)%Kk4jfw_Ex0W5Dkg;oJn@Bu)_1!SA)Eq#U%tf??*-`)&1MzgMl%(SvlvP(e5~P; z-C!u?J8vPY3YM^uTXWPAH@~{?j4L{OE$D%;Ha;W82GWLr`;8XiHL=}i$u0~A$Pxa$ z!hri8&1qG9KTEL%xfREbi*Co+L+PkMPVaaP=z?u8v_uwbu(jE9Vm-AJdn@M^92V`q zfKwY#F=0hKR?mZC5s4s~pduFMdDi`jSOkeNPV+2q2;{~1M>nBvu}E@B5T`aTz- zX^nq;NPBUYJYPaT*hkxcwTze5H}Yw|ia)p@tz(oh)yl=BCVTrkz%59-F!3pg9~TTL zL+jMRKr99kK1uKji{B)uq5f8-ZYk=+pkz-BM-d@VT2PA_d&(H9Sg78bBrt0#b`~mQ?3G4DPd;#yUTqHeg zU`lt^S);y>Qvy5c*J|K07mEin7MiV4=2<7JpQz?me53U3drX3P1Uf| zr(1ROJY_& zT&3jjontE&_y$G$jQNao7OEc*g{+bZ+Gev4MjW+Wd=ev!-T{f=nM#Eu)88Yf^L|gP%@QS%SSl@d$*T?C+ABv4v2B(JVwjLD`OqExqRoIe@2VUS=ruY(e z;mA@8XBG<6_!)!ythDfJ_egy;?ymQ-kaA;@cE9WG+6T@-tuvBDJU=rl1yrql)cAu) zWv#s7XJ_-xdEOYzGy3Ow&i*_P=$&9d7kZ1W!%U#9(!DnH=Fje|Pb> zxal4mW}$!FbPsYX^!K0LD?qX3!3A&(Gk&!(D4$F9L8mHwu z`wi7=e)5mMTI99EFfwSrp<|VCDGhP`!{UCwvHS(hLy(1dc-7bYyrnPrv|F8AQdp;G zzV8|0ZG>3{=dxNbMA?q44sNuedc8+xE(tpL=&o%LbS$Uq@O5|wV{@235xw_FZik5F zGdRhp*LxTIY$EdONPhrMHuds5_X#QV8e{oVnp0~*y-#U`5EBMM5@-?<^3D?TlzYy~ z!OGExxpG?X?Ki`e+&AwpM0o@%c(ZZb3t;*7d|xoW9zJr7mwqY~4x2Wfg^Uq8(7!l& z!=JMID-p=SI6>4$!wmoweW-~rGL;aBz>ef!8_>5ZaO8@Ke5ngXbmQ8LC$9#A#-M|O z!CBIYAVVu881bfx9<#x()$4T%H@OXFB8TA#Ns!9CDV_Tr(R~F@cSuSUc?W20uFTT_ z&kxS(;^mYyXMt7TC`@xRRPYkXqZ9EN@R861?t+qQWa89%zr)c7Z{%f7^BuVd2Wa|T zhTm8IBk_cdUp!CiB8+_=B##o|qmUkZ!R;3BHv_Q2KcRrkakAez=p@g3iQZG^P>%bo z7+==Q2*M{-m1Hy5*8Aq^Q)eS;TPc37>G(Aa~P5WG?) zfp;PIK^ijw{EQMr^FjH>BLlYMuop?&J(jJ?WE|jktkqE>_ZuP=^&=?JVclPlPpLts zj8uYyRrIYb*k0#U1;@I%L|}#5PaKZXaviiyfCo6_&&X71v9XE88?QsQbY86bnu2sB zjuY4f{pxF8h$G?UiNdee?z>R{(U~{0Yc7b9C6+_~rZ_tec6f226kd_W#{1U+zu8%v zAJgcsbPDk4w;J_Rr^y_x6mYw05YE@t@##$2brEM%*_nu0IsYnLQOY+D)eboR1$4Ny z*3Yq_Ya(B`6y*Rt?&jy?!rekn7FMWCU(z^A?>5EfVX0^k6wonhNBhn=`x_nhHv+4b zP)2oR{sMUb=dy-so)WPcISwzjsc$SPsqMcXKp-x^F0D5!)vq1avpnsBv{DDBDKh4^ z$VF+f`n4m9^MO%muF7ey1SRI%i3u(?6DAb`3Snq!Lf_KF>$OVn>^g~$OXJ$TPf(`T zRtDLG?qpDNwEEQNA^y>S z%+{wok6YQAy!f1=KIwUwlP~9zz2-)ENfgZd_U}kwKe#poZDMyGAnI+DkGcUO`bSmX z(KnT=k;-jk>(x{)g8KpKLS9$TQn^{)gvNuPpw#s3AKxf7s7)Z`@edTqIAvab!Ifvt zsvu7TX=Dei*Tn8N=K^2CtWFdOHWADx>7w_AkFrQv(1AMth* zU<*zChaZqHo;AZxRx0n?{(D&%_5-N5uI2QObQlv+Sqy7Z79nI{b zpqubx5omL~et?A$Bd?$Bbn&CsO;m7Eci-ix(7P%|A<3Zx#_88T*I$unstm7WV@m%d zl=J!(%LEj4I}4xwHHGDFy~8b~C1SH;>^5hZODd0#wO0rZlv=csAGK_v;+g12D;;iq zxqFmTdBbq;-sqQNka}2Wz>Nl6;zw0+%*dm7x_iDpU9RWGUn(E9 z*9z5$?X64U^mfH8nrrtnUuwXE`!Qd=;pIc?cD*_8Y)5%O@g>xVG<8pQEZd+i+a-Rv zdu#2TLb)FKOOyp+ahnQ`xsewJDw3;Hp4Yq5Df)6C+<{f7!gCsEjIFWeIpA5nO>M1y z4jE*_yuQy1s-E+y_U}2ODDd~sf4(8CigB67wC>EO1|jqOC!h7H3mQcGD}%e>5ja0B zQSVW>OuvxICXt}Lx7W%0#nyQ5ll|PVfS` z0n+@_x>)w?5R&6YZ++MMV87p-ESOW)<*0KTQa6N08?e;*U|37&cCin zH50x(bajKWB`t7Ss*KN!3!cqmgXs^^7$Cqz@-T#tmVLlZi+&=;$;x2#Kr~(bUP8`- zngM*4wh5Cbzna530?ea@tJ$)z2qCV_oN^L88qjuyD-o6)MegY648SiEo|dZ>qbk6> z3}(PN%QAZRW(No|E*bC2ruPdPtZ`dKlA~g@ORb1<&+<<0zgJtX9k%}rb~?X#c-{Jr z4LR8LnD)XBM`enWwf-Oc$-t1^Ur7osz>;Ph{0d#BWI3L8U>D6Oh0>PRGztOj=Dl?Q zgKN}3E1;LsPSHG>n)@(sUWq29v_U%Boeb1RheU5WC6?f!0E8q-GrVKykyrC9ZhZ*k zL3WZz{}s}2i}8*cN-v5RMa)%M-(Oq-g;UcKg54PTg)C6_y9$%gS{EEpnB4Y-M0ucI z{WY~;HN3gnrwN)R46xJFCU8mF*{|ASIqe~Afvr2`Tg5XvOP+^cn#`+*+m@#2%i*4V zN$V~{TQCqR$kXuYzoQZ%;suK#27x?aQ@O0`BRt?(>+3J@ZX)xYN~rr9#?ob$l2?yz zcA&7@OT2nScaXnhaNiBdNAKZ;iwoZU3*jyDv|{|Q&xT#$O|1>6ehL1LC{}6(UKiu* zHLr%{Ep~9~&$}AHV7B*zej2UD7i^9sn5fddeN7>$eRK?&N)sGW>i&K2ni@jU= zun+2Isr=gE`g8DWJ)*C=p`jGT4gA&jsjkr3n8Dta~x+IX10o3=`B832^- z4T|Dx1E?p|DDMg07y1OPq9TdvHhqJ=4&!31?~`e!3iD{3QBBV&^fioWflL=Oux9O! zk1QqpkF@T`<#LQ``=E<1uxY!^qeBL9Q!@DROZ6utWureygeDOT_)wpG!1cgI2JmK~ z7*9`)OVe`{hT0Lzw<%D5 z_a~9rA`yfryNJMqi?{x5K(5BTB!$mff@ehvrZ|%cJ$oy!7=jDpCxVw{UsW6SCa$N` zrnWmFGE8(wZo`Q|KbA3#5WQn)e!G)QwKB~;KYBe7T|rXceyvwaV~uPOdVFp6YS#O- z&3n4nM|2{Wa0nVlkZUJwkSwyy#!i(E@R*Tsic<<$(Plw4qWeVmaqg<1(yhx^N%8|O z0fO(lcIaHHgq~0pnHq(9ZUeNrRKtp&mmP-)szi8S*XKmpREi7<-a~tCD;AVCRRUi~ z%69rUhuKs~d|?7zFVXUa@qFPRITd;GR_k(Dfx~}c)*8Gvl|z$@4?vqKkuM}tLa&VG zhdi*l$BNc_kvIz4nOP6xCBUxOrqX{DWj*o?IKkKol4@c4+uBtD;1$(q5v9siIY&`U_w(K684d78Fr~FuNyo7YsCJ$ z%ts9?W=BHgzvAqM(nWD3FZfNlq#bFxeg@9Z??0gO6-;^6KXbS+ljUcQu-!E%!}QK7 z2egJpU*KmZ@G}$nnL2(Z%}myh{IXc1rrfG2=a=!u+0WRPrGrYii?$3v1pZ>+@L-t% zcj0A5`2kT5%TlE$)ZoD+W26VS$Pa?c;={`lYTb)p$Gt|uSp8!D>qLJHPKI^r_2%UH zPnNarm?!OMt65j(??5+<#KTaC3qIU}}6Gz_jz~wA%QUcciTx z67phRPJ-5cA7j26-}WxXK5;zwqAiRu{yJ@h4};XQvd_RaJh{v<_I{v5q6D0vOCG@W z{7;`N=!{lQRv`#7oU!i7XpfM-cY)tVZUO3CYl_pkKqK(xJZm)&7dDzuh~yX=8$?mgMw270r1{x=Aqi9W6uw>Ot< zF5p%?VuV>%8Fe&r_zZMWd(O~8t-Jje`z!dCX5M0-hp!!93%&+?WASD1y^wK>{Up9e z@x>Z7K6kCNr4nQ)7+v1AWvI;R>vLdrBL;~tp*rZxsXp%gY@p?wSRM8)$Xim~nSXkg zpGMS$aUFzKlO%V!ujP~&vO@x6U0Lf>ZvPJskkeYK`%omu;l4+@FQxuS_a965P1lC* z|0&%Yt`FURAl?7*#`~kvy_)DFDgP1ap1pDZu5_PrBmX|=B7usPEl4q9&b(D)I~ns<$d2k`hOjRmznwqegCze zuD`$OdiG7%pWKx9#7)5TW>Z;_@x{@OI1OE*k!Qu`Xa&-RYxvKlcc2#P8BuPqKMp(N33p5#y} z_$9iniFoIpdYeO;ATz{!R7CUaw1K8sBFmEx420?jOe&fF%p!tA-V^GtT*Y=Hd<@ON zFqm`W68yShnT^9TlSxCHm)Lwm+(yht8KZZpg?L7PMa9*4d!D8<%CFJf{c!kLoqRyy z{o<=#A(Z+u~ZDtWX5YK^6sklIsA(*8o-q+6? zF%(o-=shZIHO{}4@);Ox<5srz6K}iJ-VC%Ct!0f@@U%JFyG43hN+rrKh9oD5;f(+E z2XkHDj|hOVu;B9cA=Y@T!CYX-G7yZe{U3bU$N$GO&;NLK|IN=x?2iH?D+;F{&y(Qm zR6lGAA0kmGMZtTd)V=l$Bx>^h@2&g6r{ycZzR_5;5kx4L)SJ$EtMSg069BV+$@vL1 zhVoo{*Zjbx%9QE>u0cz_zG_>JXMMEpne<@Rcdz==YTpX@48rp7kmHa7^?07a-A8pO zDTZJ2uL-2)LtUnI3EgVr?|*0|C}C3UFtze$f7F@%-MVV_9c}94mpp>S(-`Yt@sU69 zp{F*sX`Ha)yMO=>wpn?Dg`kWiyc?uTf&I^#9lw0n5CZiXoDZAlDG z?f1oVhkZ#w#AnmiHN`>&x%*tjS_Bk$HNE;#55Bg|2_GZw~7s!{^8 z`wytWT%s3vB+`l}uOP8dx$h*e?6FV|^j@XM(rwZMDhn` z;C>iCV>mzK2J5_(U<>xdpBwC!%V7V+K4gF~TriOZyw62llRWH zc4c~xQp4`q?3b`42VYXYTqMG|Bb>=tUi8dvOvwpK3^hRBx}0;tP9ju7-)2pV4t6G* zzRj9Ikxyg6D~zgnrJAxvzRn8dSeRegEgQXtY>OesgVBHtB*0s;b7Jote4L%bIOx)s zi!|9eb9~G4_T!MGHhqSlINaBp?@eL|O^rbbw5Jp}u7+^yXv^f-(i}tn=*qD5^H77vl5c2;&)3+xXvj|J4jO;kal{aek3ob9 zJUC1TH9Vb5Pj9;a{j(iMD8pf${avC=Pv}~T-wtexg^ee7f7yrPikzB?$5-dmd1$k4 z&PKlm)~c~W5hcaPdyfo_P{Rqn8SO2hJNvpgIFtZtD2{a%52hO&v(+O3RXF;t%v1z3 z!L{D$O(bY4+2y+6yXuNuGBG0%d5R1)6$ur=*j+z&cZTW?K%Hc#1{ZXI1CA7=3iJGyk} zwkA@-AOc(^Jd2l;+w6tyCkx{?yB%-E?g%{GS_@9`OWfBk#BZ_pY90{xn5UTe;-u$7Ele0J8Aa_3EH zACYl#kLzL*%$A|41MMm7P)C1bN|tsgQr-1_dI4Znf9CsUtxv~mZz1n%bV`$|10Aaq z%*V5|e5V<2E04>Kz&sj1`QFF!=3~wA4MBh9vF_#mjfG7O{>tMwuQ>*4DL&vgEu&&? zlh-(>dO$Tzb+3wBS9CjwEh3*o8RMWL)*@1CHbmJQoOK)3J^OI9uSn6)Z~IFpA{EEf z?zes;VkBRRw!FB0ny&u52zkpaE~c|ne_Wdo^9+~f`ENe+=1;401=w43^)>LqkmavgXBfYe@9Z-ecG?A+s#cxx;kOLg zu^x$umPH^?g~JrKw32uzT0^($SU0Kph16#VhVTLhdr*4ljc3-H$l?i+Z@?EQ{^TN< zO77v~N)H*J6^`g6p?-;ex(NBrQGDlNe&zu$W#acij1z<3z3U67gJQ6s0PXtqIq8fa z>1K`hRl`xJ#FNhk;NBZ;4fi{h&4oC+jVG!!#nc~hvaL98X5hS8u(f}+s(GgL5>@~y zrt6W_P=8*TS$Z-GgAOMjT`S@8GxN8&4K9UKchYAB_0mI9EBBR1Q7%xRGy0*A#aU6u zJ{I+fYT|=CS?7m%Pvw6kZYF0a`)j0P#!{{h_DD1x$FmO?P@-t&^t%K7O88$a*#4f_ z@}3+?6ZJh2osm4^SeK-UwEfoKgf2!7#o-+P_;ufvRuwSPwkRL`QD))_Iv^_ZX^@W` zo2Qhb3`F*_m);(Lqgw=|-V6Pm15ulyz_XlY%=AqJtE1q7{#I3OTM6qjl@hx^y;xPy zCgM>IOrB0tyQnm9yIT~vk?;~=xghgm8_vVE=E+9vn32|iV}nf9KP zoQfHrAx9`j@<&H_%(AL}^!FFi<0cDOgWPPVu4e6>Izc0+r>-L>Zt_HP!q?@8q8RhWtm~SbXvH_g3i*QvyPh_bS7~tg3i$#eEuYJ?*^SITusU&Y-gv zy=)}vd|2K0~#> zQfEMD6IwuWdn2D_?{D+Icd0=uWF7gsA)NJpJ=cZ9AbDc{_;g~YR@XiLL`lyRUE1!i zk7ph0{zmAs973E9ZIuFH-LN+x-Z`wcR>}0Z@nWBu)jKrC3-sG50jagcXI7ezW1hj| z+st;)M$JXBglU3-5nku(fGho@j45B#C^08Kr37~@p2AvADZ?Fw*0!Y&$C;3e-b`eN zG<}gtGN%t?KL5o_21KP^=~U;b;DVQ9%U-%?*?P8W0%Nake}J`_k4#X~eHOzXuCP1W z9dD`1D~~uT-xtzj{OP(*v!dg}i5(piof}~+u~EHzV_4@wHSV+7;Wy0{`;r>eM}@eW z#)hor8}oH}>Y6os38!lk;WrvKH61mI`UwNAbL-k-J#B`~bA3C2G1pESq=VEoHNFPq z)BZn?_cm}bc{^a1^9t=YUNsHHG*$6)y|V9&dGeSR42X|^?*cDOMX1@dw;!Sm!qFGR zfNi~`LMe0(cuZ>q6_eS}lc7wJ{Pkv}$JivzN|cOwhLqx_JBeoV{_+y&O23&AUK_wc z1u)_gH`!JiDCQsnVmv3oqF z!LC~Z`|3L0h}*Z<{B*ISA1h`E7|lt=jy@puDw@_RWX=UH#M8x~c0e zh)#EvoAP?zumjxgO6>tw=E;vU{U93CFZsa=%wme!t9+KWIQ%1@m00Y;UqkVwUOwwc zvA8Crb)pEUiO5t&@|ExK{1#yR#=ZjJ#KCQzqpuzTdJ&+N5jzTC4t?nlyi` z=x2kk`>^jsw+}I2l+^8S#69ZSb9{;W_i&@>yqDh+v+?n(9%xbfES7wWXMJpKb)BcQ z&KIk}S-Sb|fTuJtGzvo3E!pFQA)XSg+qi+5)5Q^2L{a=dqPaRrW~rud=hr6~;N>M6 z5ycRw66%bgup5ClZGj}4VvNo+#?oT zQp3LdY~gOAzdF{&IbIvlI@&%v)>CNM7Bh>eRd=OgPk6H*SD{{P?IGnjU(UReSeaI` zFESK-EZP^v7M!5Jj@Q;YX2f!;#W{`{gvaqoyYL0}#QSAk38*-xevR;-TkZk4b_VLe zEX7@`bhi;QC}=vmHrc%!>4A0EMW@oW^jnk>$<8wUO$=_F$mx8_w$@vd4dPp zxGDT*ZG{6)J-E?%O5p>zH7Vg(|BN(#Nw?p*_@I&DeMpe zjO=d20p;>SB3PYap^yfWeu&7Jy-@O?-0 z+<&ga#(n!e_n4kQlxL9^YUJx|M>^}Z-h+((vG5}(&6z51hdG?LWGEt=IIx4@0{YS6 zYz0~-S$JMo1C)^N)FB&2ftk=q%}59XUu!SR==0t4cys;VWF z(lNgH3)(GZJT(3y(bj%C*aXc?U6V)9Wfiw7Zfs*U(A(V?x*}F7B)vD&f$@OgB(XRd zQ;IR;lts}@LmL38d+}_34$oJ<4}zkNTCs0@*~p7#&D}!Kd<0fZDLKH3jyEfgE{Ho? z7*})!+s8IGg%ABGR)l{jLg@@+dVRcmj##`xG{s6nER+wx0G@131eUHW3=PXJT{jZGkTk*L|yX~2pj5nNXV|_R|gjd7iajwW$RyV(3UPYEZ5fl2;Dzuu~3RX z_DzV=^op?800|7ndFT(IU{H@UjB4(M-lwzBUO1@=NChtGS-+e0lo))W;v`tpQufb8 z@5u`no{K}UgSNOm+O{pen(9z@p6hM%;wF2eM|ewtaYXa#Ui1(dq|U0Yd3u{lYFuP> z_FW0X52#@U7?0j~m+!(7mFo5?ubZ_rA!tX7{l~d*HtpR(?8(7rfJ?BeLc<2?0Vak6iBmdH$0>zjycl{66xT`RD1&rT4Y_CBA{I&q-sFCevNl#3M>D z*B-y-)7Iv3HE6vo2o$H|1j`jo7eyuY?`TfkZUI3g^w7{e>W|xgRm{zcYkJYA^Q;l- ze-xX19^oVKu$o?M)mc1i1MO=)p39c}g23j>0Yv?76)aN(&(lKN#s}NtYTCSCi8VDI z!P?~8Eoi3r9`B@`aPWMMy6R7hfbBZIU0^kJzIHxo(C+~Fbe8tZcKc;6xVr|Nz*ynk ze}U8CYBB6KC%OV1yYC+E3Y6}y(Q;SD-vR$isdw0U565g!_+D?<4w9O=Tir@;! z-@TOE>k15eaPbN=scte?s)9CL}rpx%VHcaBx~wgoE}S8U;-bHz}~_;oVQEZGkBJg7wzFi=}t3pI3Le zu92b!3Cg5-z9oo-ha<4RJgGe=5QM@P7~qmsJc^8TP*_uSfprvh~c`a8Tz1w0U-U+(UThm zR=vSI0z&{hFSHZM=n!q=Q$Ya0fKMn-vi`jq9M`Q2tOu&`c98k{u=R~=YT7m*AFK}tC54P9 z(A91539k?ivnVS!UzM^3zYY6R_8x>Miv2Nl^#yy{+P4?%ZEM_zr;YgAR#RQwwtG#q zEjnsk4hjTD+Py%ByOf+N1tz-}ZnzPmif{}b?tVB*vebmtf;7fJYgp{PW>%BKWTdl) zcpQ*DeinL!h~!`pBrQm=R1)osuf@;C)-@RX4x+{V>~R0#fmf^bv;DSNba3*s8KA%g z@YEe-RFMjW%H-TUDA+#$%}U#w-=Sx@dyHHTBAsI~A%%Mh7|X-QL#>D=oRgZ4IT?C@ zXK*Nc!m}o}BFR>fkns2wYD7+p1!c0aux+$CVrM(ZdVy+(8mR5fe$>&M4tHxeTXkSu zjc{C)0N5EfBykvbwBUjcbeHi-UA3>5}Ob5HuLQ)JwTxwrUn*yhgro&B_3%gsy+%g+I{4u|n5> za`)j&(2HF&eF55 za`(PpWWjjax(G1*fp6&Ph1|V+4#7o&txMw71mH+V==wf)@5U+t?NhW@eh>rN^U+|^qHthM(SSa@nw4aBOX`%ODsynHOthQb{dy1v1HuFJox{u=r3_GtrJCY3zMr9M`rVp8vuYF%miLe#)Wn_*Ia zEj@VH^tpIQ1B*OG>KylJkqQ1gM6gZQrC3auW8Dk=B5 zMYP%dDB9RDwl@=@T3EBowUS&iD3Z;5FbLvriVnbV~x#SsD;xD zgdU3Q6~Ve*gE*krbl}y81H2Y2@%xMCKHT9F_@`%8fy;-ON~(hSYn-YZrWrtG zOu?O$EI5`anBxQIdUl({@I$Sr9Tf-56R~06*sV=P6l|R}8L&ya?;|eAyB%?MRFnm=SorY9V9&NW^3oxv;g__#~S$de-TJl72@yiS|Q_5SV?K zi%-M2LT&-iq=B|NdmBbK$q^krb4Rp|Pspd;@z7)@cOqMqk6kw*pSG{6+iBCY_&gq~ zG0YD`T&a!G*4qVX;W+_T% zs5Bf(y+&c^p=J!jl#`{;pUe3qzb2;6qbe?eZeL>Y59+W4=0cgmFQdX8VxVP}OQQ=c z>JW^I2E|<)vuaP+_)+sWh`E#07joik<)gN#_E1ku*D|f^#aDNv{3&Nbk)%Ccd*$)Z zA>y+Y5ut94>qlBJc*0=oT*3pg7fep;Vsn@pXO{AwspaA9H&H zjZ3)r4XrU83*^DYzq&^;K_?+2nYoQU(tD*3j{3i9`L?gIgrqSvLT56=0bR?vzEA`g z!&<)Ti+q6#ZOhp{_ZOMmeJ$VgMLy5u#vzaU^UOg!qGz?(G?}&OFRYHT+f~JhQNHpY zEAP+Sk%#a*6DQkj%D9Szd#ycvf^sy#0gI;)81R-5p%^bs4@=laHt}l)-{dizYtXl{gOIGQ!f_Fp=76#! ze&(VHaJP9y^sEiEYJ>0I;yt_wdw0*H2%(c`_c*;^3onj07uy}Nvx=pehc^!xjQZptYnSzOKpASb~FHyp%(FkC(ue-p|DD)5bub*_G>JtCa9B z9+!5Z_H$#i^d!nd`z!{JH^aFg%DpP{Ypo-MU;v^dp8w5B7Di&mZm2>2CRiSar>Nm1 z&NwMS90&P0xK16n232)CJmc2rS1OK4Zb$$&XfIN_)4zbU5lyZa`Z{0pobvP?`(vNK zGU;?>s=snHjFyg9rgS=EcxMLhT*EuP{uN25SETw^jP|ccKE5KQlRS=O@Uz#1XM0ha z+_{hCHty!*kM+yPX4Dl)MMc;Uy)9z5LomnT;31gdYOrEST>bLC7B^KItV|6`mCEH{ z46QE!sU{SB;BAHbNuNp%M}}ck#_)4;iiH6wVIAhOPPP*>cvhump`La5W%cXCx`sfj zPQQXAZ>fCOchh1FQ`fu{W4tVSn%C5=F?eb%4J@Oz*Fjb3|6}Z10Gc|o{%>v`1h~}% zm7?H!6CMV&Z34D})ipsx@X-SGfqm=}DvEBqi>|G-YunuDVnDhJ(N=KnZjwq1R9c|6 zT9qwOrPk^$x_#KLcJV>QZXamzjokn5+?xcu-}nE%uXV_snKNfzXJ*cvIddja=MD?s z9l^tAZ2!q~noL7AdVzb2WF!F(Z1 z`^KF)3GhZRG?{nd1OFttjDh@sXrAts2g2Zoo%Dae9HYAtv6MTGvE!rsM^DXdffG+I);_MkG{d!q9MOVZ? zrZ7ichN<1 zqleuZb+2dVF7(su(UW|KwXa7fV3Ob_O~R2@;kRcE-&`=U84P1GA_o_HzT`5OM9)<0 zuKs|^nBO`8`D~x~D1N~+;PwP=NviW5{mZ7XntPa>YhsEza%T9X!}dFb6irg>BV~pb zJMB#{?5Bsh414sED?_;f-{F{z`|+%A%g15DHKHJm#OHBOK%OmoOx%oWhd7>D z->NhzY@dj}nOfsRBT*1&MyOZMq}oxba6+y$X`pV4FREX^`RWX)!-{BA5SZol3z1Hx zQ)!MgDV?!*OevZq8T;XSe#WN!WBKE0RsEu+pL)<0YIf-?&IRTa9==qGouNZFvipS7 z!=7jfK0@dfExiO^t;KRpkXpY^n02^Bqm3*yd8^rVmm+J_+z4kVL(f2`G&$Dyb??#d zO?4_Yky=&E5vNk^aP>90Jmv3g+9%Xer4bYjR%T5?b+~gT$)fPD6DuZkyUB+w7Sxkw z(zNQ&5%avj7|w_||1SvPMx?QfHMvcGL(uYP2jEIaF(y!=)@XbLjU!#U&s4@7PK$d) z+9MvB0KFcjRS|PUa8Uuclrk2FCtqd}X$sTcLeR1?BO6tu8!!nT@Y}I?dzc=#h4JzD zi{i4dzkmoaz3-kX$!#s~lYHD43k7VI;dw{Jv(RXillpwqq#0^4%HeyQS@bX-)ZACezg$!^|aAw>F`Yh{rpBM4dw;dFc6+_1O`pe91fE%w>2``zFN5Ff?I2@xb8Y} zXHhuWx4`0hNDFRS?mHjuBr>dIg_vOuV@&Us$2HP6&tGU6cVTA-T^iydz%kYCIcuD0 zMq%);@ZSnty1Yc1OjGg1B5cNSV@h$P$-oAVe|*0)1RZ}-K^vDJaB>8jAYjpC+fATB zOUQ*u=_&u1qAK9ZO%b*fM^S`H73h$ZWoGlPqz_^u=cw{<%_=wk5ir1yg&i4#o#0Vr zt41(NEfJe4^~(~eUp{+N>X#9XP{2rvorF<|M-Tm9ME{@(Ec|$gE6J{2_6gg$nK69b zJDttL9^nlbKKG#RYcL_24(t7nn)4F57%hEBj%9~vxvr*L+n)U%F&8Y{ol6Wm@8wLn2M1mW z$*$fUGrPu+U9z6AgW+If4st1pdT!$qOPL|>AB#7#8ILhs`Kog-F^YGNuTEE7InfObsNFh-3cZ5FLkX&P3(`D@fD z(`Jn^&Z3PC{%NK#Om)tc#Jlp}Z z3dw(BS3zelzpM>9sS-R6HjnHQw%-o0GM&?ujCa{KZhd74q-DH9aQmS$L$nEN9)b4J#j z5W(UJZj<`umT*l1;GF8HT#dph-KTMC*j(v8SFT3sOvAUIwmKC|?uUaMo1L^iXT=LB zU!4l8ADISF2gVWZTJISdQz0y(8W(&JH#m75vbd2HB^Lvq$_t?^tq6RiUz%E<; z{K4>EPL;<_SFcKY0S7a6BZ^`p4>Qj3{)rFV<)c*7HH$_JLhT<@jq*EOJ>#O~ z#x7iSw$3W@>CVtA@V?6K20ix9RE>vG4aUZ_}J zqQQdZT>d?k2PIRjP9Sr-XU2aI*xKc1c}IVd#+~r}lZv@DmBsyKwqnPwyjY2#=_Pe2 zQoT^8ZJDsRF$C|ToD4hmIk*rqtgPvI{A@-X0Py5Yc)cCSgc}c`@uSo6xkv52y4&-H z&Xofdu3n0)r}YiN?uR^Y@Bx3F8j9N1y(C~gr1t*pJE6CMB>f^HRozU3F-;@Wy*~pNLnmq`57Vg${JufdOmwE?~@L zi_>BFj*6MZN`Ayz7f>ZKS%(yrN3(bqyMpR0C7v^Dh00`H6mc`S_DFq?wWDwc$N;~! z_42QD5y3ylyA|mj9{)QaSj)~RGBNAd*e=jyBm9LLo9=Ji?={-+6dRLfqtZ~+ixee4 z71CkQ6)s?^ZM`{HVn@H05IHwlc=SBBgb=w$TA3oRD>=W2Uy^o(x|%wq>`5c4Mty{| z^C&X*uIsKrqHbCZV|Cyo#y4q+sNeO#i zH7P(>_#0`E5We5nnM(Zdg0s%#3Vgp%XEcrQ=ee%VR2>L^rp|OI@cndMP#;71ZJjA9 z5MEqoG6lY$tTUwqzE{?nG6Ubs>r8p{%|uCM^*&zboS<`5stk{MaM)VuT<<=?ni_(p z%%r+MTxU8FNWZww)EoF-P-nUp_|8GObxE{Wm+%_q*BNo0%RuIdBpg|FMlBU$3+Cax zq^mO)z=4Y&C{QLz-i5G%Fa=cRk7c&HX{iLACm%u6x>^N&1#hF`IYdzhPKHjiYI z^-Ju<#Y@d=_4)a`@|W{YmD;*ck82`jIZl%hc#ScvwuO#FJu<8otS?_kIpj$@vXL0ySZ7l`2i8cBJcZ z3Ba1n+m4BIG7*ugf)Tx`)U7L&mcPkgMM~SnT>qV6rR^}xb+k1>UfT_~WC0ne?dTe}_pq5L`3-xJ|0IxRc zEDDS9io#Ykiq={DwrVacr$Kx;4|wZoN06nq;TaLB7!<@BUZXU?1fG+K~kkG5)eE(QrcYqV9BBCOX?Jt@N) z*6^Y@fi$dY=oqL@YskvwCs1b6M)2Rw-Hwo> zLaTa%U+05gJ;ASY!LKvHuhYS=e~H_Sgqa#{Y+oPxQWOVptucntQ5|qbCyL|X@5Zk< zfU=q$BO`nLueD+UZ2s5g+8@ufs5Op#3a45P?zns(Ufsh$Dc{thR_@*7RBPdJt3%4m z9F_e}wPIPGUU)1A=blwC>VPUP&dE?fARX83Qc&P&$eVQSJvrWP@xz*7RsW*(OQH!d z$I!Wg@1rp9{G8WEM{N~)*wze=r26= zGoxfw_|?L3a8#e0V%2rI4FbQMw(6QcS^$(qlddcSDyA6ES3Y zn3xQ(>tR~IZVyhCp%WLLEL;}NW$P=_Enj4tU3|r?Bp-ucVDi(Vj04G!tQJm)c%c+q z-DMGB!l$C)Qz=)-9?VJRs(A81)h?L`z&|U2R!AYvh9i?E(^jK+} ztg6kVhqYLkO@)+IO6#8>Q8yd~T?Cik^9H`+chR4lA{`LL@5A1bIw@wlgdbS2C-168 z-n4|f+K_pjwrb8hxPg1y?KX)o6Iw)cCvR%=Pfe`QlkL|Qmgf!RE7bod%y1|-P@fF- zr{MVs3@-lNBRws|&cQ9371rba1OZ`ZQv%&Yvh))C%2jj=~#aJ-z zx^K*g!*3LQGhtR9zYfUtTyWH;*TgERGMM=Nzo?vC4+Kf|DGPPK#Rxx28PM%%WQfIe z$GJLxb)@wi9edOfhy(=DfeLMIg-eGs``aIibDloLn?fBCgnmkM0-l`eZXg1)&6c{Qgzu#GBo%W+1*^%pz;BN0ymN3K+AB^TM^$7cmC^@+g$7Y> zGs;5l51Gf&uDdQ=^cO7=baz{>pjP;*wIM66;+MLI(S9w>RZgV>?Sv(?MJX|!$^hf3 z^fR8Ih;pMmFl$(+QkA4sJCgMdiBn6BSob6Fr8+H7K1jcA{BgN0&pzmv{*s?Ei=*~~ zQ^E0YXvbi_K>h#C`V!VDpxC4J&T#lQsao&%VuKHXV1ZE*DBvqqo*EuT;HD-~s1jo3 zsYbb2tRa(%C9!xZTEl_|`B-Z2p|g)hocS)L^4J+11+BaEZUT#UAB5kC<)t8*E3tHP znW8nm`2(&Nm9o@?@OgDWlW*>qFr8d#|47V#ya}F6jUmz@o5I7@ewdOSYws9}y7xgC zBBvxIKG4v@iCMeDqk#lixbYyCdDw_*)D(U%3MWNJvV>20a+E>g$C!w>IFS&IX^0JA zQU<0i<^<~S1Zalg9gb`G9)Mc|KL^?!35R>r=mo2y1Ysqhs|EOtf#c!g;C8}23P+mH zF8pFG>l3etVs~n}fTT)p`?OjvS@z(IF z4@Fp0gb%Zb%rJ!-4oJk#`o|M38kiv8IUSfF2}Q8noKtv@z=tM-7*=@ary*F83^t-2 z01cH2(_Ev7D|7VMKe)M+syC#(gTu3`j{Gjz!lnwy)8`HeM2n)EHP+(!}bX(c~DMz+L-8`-12oIJLARkG~iMC1z)(L?_Z6mBBplYq*ci2x+jbM@5D11ik ze;ZKFtA;#(bNPWFh;Vz<+#N^n5dJjSdWSRzBhApXD0!-uAy*w;X@OT_GGGgPS=xd4 zm&N#cvDVJiy2SX$#Q4RG@E8sb3{OzL66pyKix@PxTkFlEa(WKc}JHG zT8G;LR|$uCry@5Y;-1dY41+^RnV@k~iGPJirYuaJ#rJ4m3}5$81ej>Am;tpc%sE`9 z6o7Th@GZ3nfd5UuCRR!-rP(KeG__DOy(gtrFv6h+sy=++F70$WbBsb6M#AOEWdYy$ zt&bbA?gFLL;ufeuT3Mu(EQJO8CE>@PI_mz6P)35|Vgb4C3xi~IH~`yu8*E@z05tM^ z6nSAhPtV8iQaH>!9Xx*H;7oA-Hd##VWw{*SXku~ei>l##oHDKb*`U0h7>gK~7Dotf z^LreEMCwCifN6LuWWjpC3`10K>;}aunykrmuAK2$blGs>g`K2gN*@ z|J}oKx45W7`+OYdJ}fcet+3tE!RZ_hRo@Xsu}jg0L)L-U_lLLD=&Ut*aNMOz1{-FN zC*9frFCDk~qQl+MVcWLh#+!Fbi#+<=V4oB9;JXby;J#({Ik>`i(}p2)#&zu59;I^F znQLs_`@#*ecaGx^x~g>#RQ_4FGo}06$;a?43hq|Y)pXRLPQnOO!Mf}T0o}&1pxKwU~6D)T*v-OOMbN)?w zzVRJ4V+K>5&S`;o%e{wGHl5pgMAufg-s4%5_e#sy@JnOEHjWy0TppZj-sMj35wV}<{B|@Q%>J`@H=-;^$ zDrmSmwk_GGw0b-v83^vNhf>{WR4ts35KEhA#`*NZ`DPc7 z9a3A8-fV2M>=(^O2`vsd{msR+VI4dKhw+gR5m`}?VC3nTm(*$jg1rU5V{D&6Vw=fR zOKl9L6@T1hS+NxG`=#}ixpp9cYb@b1XOJec0g4cHU{!Y@6)jM@&Jeij z(j0NlEZ2Qdtg0d5-O!39&C^2#U-yMSmZr2C?Yj4V>V4)X-v6lOyq{LuElplSIU%V$ zU%epdUx15(NwS~dlVm|d3AjXmEYSw`BUwN7mi@%*mN>Pcin!l;-ybj6#QoL_Kk>tZ z(x|{kqTR8tsz^$Rh=U@OYv2`{gEO@dx@^!@%yfEGjtx|R;B+T<0@>}7xHs)~qCS(> znnqArlo)oKFmBe#dmZQ{Rh^xO(4mS+o+{h?pRQ>j*=nMJ2L`ccCXgWaC7~o);&O`5 zxGkRQ7AROTbatK~y&cf_EpfUQ^56l{7F$wJg90kO&Iyratfa^WKiG^qc2UD%JuAt5 zsk|jfy9Byad2pXVr>z&RnjFI4raKC7JK;Y9{~munKZ>TjMaM(A5nR0OqL`GalZ_o% zG$pq0#oTlni}3lgT$mnsjs z4%2X84}aIB48g|@Q-2S3^Xlz zCNVwZnL-FRpJFi6u^9#i_cOUTW2R0{X*jjk(kbS#X%ZezNv}%n;9>hdDN`>$wnc@c zY;$o`Efg&ld-nV zx0TVv`b|KF8U8R-#M(T65x2FMi{5gvHihXK&csJBg?BK8qnY@TOzC(KBa@KC;vC-c zJDg~vsQIr&MO{{jIN(PN`r5_Xemi9Izft3YC7WrW zL3Det4!1Yx<3pwGneQ)cbNequ?=QukyO_d}OzknetueMw_abbL+DZ2h$~}rQFgs=X zG6PB(|4cXCI^HhRsbNsIpP0Wkpe_W!z@q5+Da_*k4ra$sVIKJJV44846Ryq=OAi)Q zd}*1vmI#-W2cWafLbxK0%&Vep`dVpZLJ!6@^*;yZ-rEM|uAk<8&wrP9w+sVW;JRy) z)X_}JWjGeZBb-@&%A_$~1h{i>alO(!feAvgD>>#TI1N{Ew~c`fYhmPCToi+n78(?t zMQz3I0%P903b#maG~MpT&A^by?JJO+JV9HbYaO{bCRta)_alwm!-8W zn#-rR;nQskAHSKT5Jp8ft?)EqLc`O^D%>{CX`>i7%Q{)5+cwN;8xHS;4Rejv7JNut zuTv2|*9BcT_?bPvoMZB&Hbt~aR@=}}KXHcZ-kFsPIc-~FR({p_7bSc24JVDHi z(;l5=SVBcBoIL6-V(^^?QVmK`PKisHc9VW##SL5%_zr5Z5`x;9NS6X(Phu>vP%|^VG7Vc!?KCNOI%_q9hBZ%bpWsr~ z^;R6F`C=ZhlhKlzUK8wLL!((DOWACd<>JtaAoUq^>%N8lHY9Se#xn-}-N-tFOU6ZU zdf50es(7@yQj*p4o_^+?*g_4;gE=F=f5sNLIHqsLq_)enw@hLf2iD&gM7eDuFR`{O zm}Z3(>R-dV*I^LN@*^JGKvfb|LNbMN5xmSQA_rigd-AY|If)l0zc}s3fy!VMG{rlMjlO&N!ySvrhKoiq%Ay3gwo)9iA7s zXqSqc zWADJ6h`?~?ksHe*LcBlHGhk!;9Q+#1k2JmEKYli(%hoR70xhH?APv7WQ$Av>3lbS? z0iI*D@HpPvKXGCUc7pc)EE48r8U*<)@%^E;cpab>0+AAGWh zyv7?!C4>3S+H}L}y-|284*P9b_C`3b8)G;tGL~=f4Q!0^aMCQ;GaADyCNO5Yz{re1 zh(gDVL2`s7NvEAu_G_3NNB$nipDm zipSR3q~zw&^03rsG@ruEH}?-GD*>Bgk?q!>EqaAC&W4P(PjYp zgf}UHgj;tT3iQF8Sj{;R1@qMP34a%ThsQd~TRd-3!RVG^|LaiVIw_XoiOXxCW#+(T z$O5j33%dKM&kdPSZBtmTi{LFZab)6Vr^8JV2h@r zVd*#3|4YmeZYG=;Gc|!;Kxw85bh#LUxZ51gf&p;#4rbh3&L3Fgp5ZuJDb>or5CpTTFqE>CiH5ahnqr zLHKiGs-7Fs$j(=8p9Vw8X`Wk)Q^MO`(r4GSxj%}pw5}1p%|vSzH|VU}c<&ct^g)@ ztM~$F$IDoD3}Qxm{?Ub}hS|1?{z=WGT#ddzS3GMy_aSDjECDpiJ%4H#HyqNJt5 zaYutbyPVHeaIFgFC4H{q4hIy#mhc@4odc>Ois6+<_};3zt@KY_7x5)S&%GtR;F!hH+Z2iFhB0Zs>Jf|~@_g|Ha>eu7^fzj1Jf z@O=bsB)+5ImcpU_&sYL9x++p^3`w;Gyh)1mtQ@m7JwIKas#szuuxo^IL{pX%v~+uR z@R<^2g+w06;gnA*DOs8!qC}CaVwQ~xA^Ug>y$>(LMda)?(dldNJzqLm!4yNQFV+V6 zTtrI77&M=^Qxw7oY4=t=Guq1B>osaHzRf&8+4HK7LX2LaRSam7(Xj$!*bDhx97f^5 zY)Y7{cVlixZtr-Tc9|vEFHu&NTcoV&r4&hC z*eCHP3XNVHy^N}~N53|j%{V3&*|?DDn)xA|GcPB*kT*ZXTP-%S12BmZw&Fn1lcMxM znfYaDKL3>RY5P!L#bm-FLyVQl@>(;^o*lXt4dd7+=`_uS^#?1H?nOJ&_*8Z#qH30n zVk!QXf_)PX5Dr`pZA;f9)w*krkM+&p&Zb*!fAUsVn?3cq7B$nfpO-^0KS^jbQM4(} z_(8O+6+6G9zZu_(mZ!zeZ|HBv1<~@9*m+*`K7|WmkFtC zV6?~!o_F2#{1vd8rOI#6HRnmMKfAmTBYPJSHabTmc+WCj_IjHSEB_7^DQq=(v69&5 zOBre^iV~t8)7(w;GDqw#&wJCBac*Ij2uS(#F=V}-e?X)=m0 zOcE(%pVzaG_fDX+?`egHCETy+3RFyf{$x1?mcS~bggdm9NY>7a+1YW88sR|#?p~-z zxw)GJ`zP;Byb^xN8(w?RBb{|A5c)W)iZZmnLS=N8sb{h9y9r#@nUdQeLqyWy=@1i2E})&7g9_=*(s%S6Z;AI`9AySG$GkPgIG=Q4B_aIaeV6S z`os)d_=K+_NVn0(=(W@_DT*l(Z0FykJUaLiukwf4Oq9QQoF_nbSE;jSH@N8o$^zV|Z%zNWZf+1s=Ced*icevolKz_{l# z?s<%JE~Z+ig!^3#>b+>$avv9cO;HYH1?4?0bC~iSGP3f&m&?f7%l}w!i3yWSam~{5 zAmfwJ`R3ulaLV>wObl-fVLDg-X?Z6hdbPz&E_r#33^Z?_VPtbwd^tPA(0VVRy z4PcqgX1pR{LET$CkC(q%{z>^kq(_?acm265%HQH%kgM_^s4fA|9OjZ-pv7$GixR49 z3c@6n2(c)URGb+xEC2W6EN3;2{{hD@W9IztIM%YItN#Za55_$FzvI}*b}kJxONZ1f z=gKd4%mHP^JX`*m`vK;9kR$7DM@Rm>e2{bXT3V#`Zb1V-NG-T_51X+_Lc>M(Dmu{D z{pFuhYrM@(=$I?D@n6e3sg--%uUpCo<@R=2h`OqO+HoiJAP{uh@c`mZW1xKHZ(s5( zrRGL&P`7o)loKM9>iugVBkn=Dy0>>bSGP80F;O9Pm6W!;GuTz=Y@~?!^O>Je&Yt%2 zP23wma%PU7cB1#;^32+OtmbY^AJ@dC5Z)D;JfKCV5C8 z#F-73{!)rkktb908_A<4PhRIb8IJVDxT1`5DJq0KC7Non?zDRjou6r5 zrwJ?{GU|CGrw;7bumQV2%`#^I55Yh?y5KD)CvyNy+u~W65Wp$$lDy6LID=CMA(sNB z<)c1i?%LVz&$z*ur0IR$Z^f9WPK9y%uPHM1DTe0r;?ot=o#D*JzgnQx%Y<6{DyufO zjKp{43Y5cY&aXnC6@mALK&M%wz?zm{xdwv=#ccUlar`J6JUsqSRNj>7%6x`#aQ7(` zHoRdP$IL#X#sjAKu$$w9rUrCtMf~*O5s63)#PsWg?wqBpx4& zT2zLsH=IUDI?RA+R0x-D^s*2S%CbQS31#u1EE|N75Samv#I^VOf0OY`=TMezY-{Io z6XL%|V_nADfHmm+75tjcX|363wN^(DbnqF+d!9rxDf;4A{+2>O(QoNoqHlhuvtGQ0413M6&&XLXHg`|6YV%Xy9nuAmTF zOj6u|A1YTO&L8#xg|({e+rG}9gV&Dwl8Cd&QpbNgh}+wrqlwKBWb7rNq_-H_lgY32 zs=3ZIFO$LG6$g~0h2pIeJ=Ux72Jcf}!9QIMV%41fFx)?35(HSO~> z;jz+9AAMYaduk6GA$ZF#UIQ`5YR>{g+o9s+JYEPC7E?)cF1?7Ih^H|==PPm1Ub-N! zY7D`}d=!x8g9ixa<*8!v>wM2%(Uy7>y=TQ`>r4voTc$@(qVYV-XtbC*uhQGxh@^^);>b=pZZV6Gq3d(a~uceRhX&z!4Vqq8q07q4lZ2_hO zVMk(T$Bb!IWhtOhi>RcGhi=QQ!@v~prq@&~VK?Z|aWoDc8`ZU+5IG$qa44Cf@3ynt znei`$z;3};EM_!_BTuoyqf{WN-qUoDp@wve`Mr{ktk6y=ZEZIoE}R~g^V$uk>H*_I zn*X-Dq&lHm_~%qT$hcy8Q+Yjw5Z`iH}@1+2A+voe0wz zjG;s>-R<>(utv$`teQ#4j{RDcs#H9uqVW!=-Oyo=J#LQ^rW3Kc4TkVChf5CyKbRvY zp^3|DG#D|pdQALrLtKX;76h4ihw&3Od!DBe0y>v^?m`5WX@t870gu;hT>5AullAYqi@pn&nQ z6jX7|+`!v5l9qM7pQxwz!BeEN*e>Oq6FadY!HZMN(fO{njrX#}Tlvajn7|eGQF<&F zp1P-wtc=`xi&Uu@?*TClmE1*fsALiwgOC z&7b|Mio3H^K5s<3ZFd`fd5!A&7Xn?=)-~iY#GB$Y-m|RO*FA)qH)v0DG?A1;hogZKGCG& z!i>hrKuBdFw$IXb-Qb)#bOHcERN_hmO22mEvhh)B zG!*Q%rl<@L&cw+;qQnH`V@-IYp2;$h%QhB|yPt^DIxAoQN``Y^H_1x&>>SM@r>WVZC zb8^SxShCvlVyI+(bZQa8jx1dq+m|sObV+gXxB+~No6o(%IooyHs?UsOy1v)rP~-65 zs+*^N;l6{xeWSx4G45DbRb`a{)ZnP`gcNXlLYbZVhBxX%JAtQTMUbU&8?=#Siq;Uh zq^|bkcQD>PVvQjc?}*nPyH)L-{ob%lVdsJ3rZrH1E9`{rEfCj057M zxkSIPFmdf-=4m`Yu904ae*$g12JR%SzdwlLIm~k>;kw~WX!~Mne}$s?3T_yweeFi! z3=Ir!XY-Hrny2s;`G`XpV?TTqqYr03x2=yRjmei}*DtvUa^#-p#+@2wOklWqEu?FJ z<7(0sfaZm8zy>6Ssh7Y9)1A|)G(8(vGQwY_@M#yJ=ppG=7$3*^pA`0~$WPT7wAYOh z3H+jTrZ!gSB4#;No8%e(`m3z(U^mY%zzB@FJf)UR>S!}*-0cPqGx{92eHe0WRKi4{ zWTR{jd`9U1w5Qp1#+*BhIm3V_w;iX@jutPDCNtZ!<0_32OgXW^N7?GriN^wKgh`VY zssKAH8FtnZ9>a+3$4M;%wHzAnv6%C?Xir;zV>n<;IDy6~c2Db82|@L7p4a zV$iQ1uLn@etGL@jDRSWPz9S_fZb8w? zX&BiW0=upC`alJby<%%$o#uTWx3&x4xaHC~O}R*nISOAR@Fl!tTU&Q;$k~zG@oYy) zcJ9pT(~gC)cd64t+0JQ9o(2YcjzTAidpI}#ZpZ3aj-`W6cKmoV?w<%Fcdj)hg*?t? zSeRTxMC9dg8HLM_0v4MlVU_Zf@Z)Dbh6nF3@)BUT_C2xs;`Y>2EN8sd-r-fXs(O!k z7sCo_q4yS^cG0A?M<-{Vj!r*x(PzNps7q4YvreOVa}7G*LT2JZFpmi{+0u<7=a&hZ zG)7|>0O)+!q#;ch5N3yg^V8=2qA*sXxAqf6o6;dlVwey`VO0~;DjRr1lC(*qrGZo5 zr7qFP6_&fG^q9yv5n6;lYTkWl%@m_kgK=;NE(baD2*BTXT+ z97s`N{;08iE-&7STA!b^8I9>SL~JvK8!C}9KZL6a0gzr$2`6$> ztE)^QheF%hHppNZFVGO=Mi_I#Q;*5DM?s^g1=0-qvgWMQi5C;%gJfCV453g>d#MsU zcQ{U(F$4?m6_e~-pvhc9q?Y59FDfI|!Eh`jvYYgxV^~KC8YrRJ;pS>O<{jQK4^_8sl`62tUC87U?TZ4|(KAcVJHdYp|tppwRt<@K= zZYwTnf|f|NKxB&RR~vbl_|G@kLY8q(!)S-mx{^E$2BL?N__N_mnAK6- zTwJVrmWV030U9=r;<#cc7vV`>`_}uE)$RM2_}*fwg*nf7s&%VF7{^-u+R>`$bQBQn zJ*;w#=aR=!5>i}wxwyE$&US3ahV$F*)!^KVS!KSuIwS{TuJE;p!mwNG3Bc{~Hu*d! z!n(RIcXjo5Uo@Cc>2=>L>TF#2?rq7ASJScFwe7NbJgSB_+TK>}ZD?zuKkcf+4cz?@ zuQfG1-W+wcsiCrEOiWYLj_!SW&sxPd=N5_O+T@#R+yb$eT@SKVmX*4fs!rsQ)h zW);cux#Tie4miM#@3Nisv@ffJj*kbtNQIscX0z;bPDV9EKiC}1cUx!7&knH{cgA%krX=tF=aMH z;HVM%rJ5O_=$uby;4oTZN|q>vEmDxjn%%(DQ?F*s-t|hXbzB&EC({?!?mX5Ve@{U? z4Gk`yiw3aF6KEK__ZChaorI-|`2qJ+IFkI=Xk?<9-d6-|{mD>0BP>O%JK>&!1i}Ig z0lq@RoKo4^p^nd~8^gIt7x#;&Tg5EJ63Y_9Gy1}6D)+Aly>0Lko<@`eky(D4oZgpY z1gA6^6_h?K`1nrE-DP5_T~K$I?H0_H60bJ4&r&OCedI|M-a>7FO*G1y3(hQ83j8It zLeA{VMe2eCe?#DQ32TC3K-!!bcQE#CSL!q#pDuFc*Y*OccseCCbbJpsPpWugu;PJK z+!-!B(Gqi}G5i$l^d%Ys4P)3KUUZ75onQc-(f5>5H7ydd1K=h7$b!`jAfsQ}A3?rl zhpE*~n^6TP?w+~0jxZ*=K|WH7-p5JH3AQI6jtS>R`VMz-rlTs)q4mchyEAcN(}r>H zGp(_^-;B&X+?#f^H+=ujN!gw?)~+?!BEd8yv-_SA(fe}`N2MK&x-w0RKsh#?bm$kQ z3{27@RCsd0QBmoP!tQmAxdx9M($?(CFl`eHTIN)!1_~w2y0t z4LYS^_Lbuv2K&{n`TUD_xY>2wrW!?{b=>UlF0tjgf4{NmH#N4Qz-N=#lA5X^|1(RP zSF{JbtJxO{*ynTE=T3hurh0!h;|u#2!WTJTSiaDIVW?U4^rknjxK?*pdt~tHP){f` z_rbI@7YaD-JU6oRPG;_J3eq-mkt+<-KEn&K+~}mV(rGW%=ph}##BG`OQBvCPYZRq- zFxBnuv<(Q#nO0U~gQOLo!nCZUwDmPr8Vyt3>`rqc$UZH!W)&pQ(?XNd1a54NH&9M@ zn1CJIXCFZ~-91M@_8L-rn8$71sqT>clHK0uhR6lX>a-USA4r&DsF+!h_WW%jMf!@2 z+_dLz3#qnLtVqFAMC)z~%gd=KEV31({qDA~Y5{OnNomjC7M5oR+^T{!y0cgDT_D$L zuRE>eHmK$oMeiTPp3lWJBV%#TFi++oH>pGo7|0-C;&Bpt1y&}$zR3rkl4BUmaSSt{ zEFqmnf$N+LeunY{wE4+hAmgmz))Rkj$iB!33Y*9(S?op zLf$%yPtq&9)A_z+MOQN4^fqrlDz@Fv=S=H&dqkIQPtMkAwk4z_e;=-WnD_CGsuSwy zwI@z>-@!yXk;~ebKd1d`<`1$BiL%Q$AN#OZ-E)2rAG>>1g_j0h?A2ZtPjuj_Oluep z=e(2Y8Yfx^3DK^Cu^(#yZXKY(uzpHv4bg~Y-j0R5yyuxg>Hr1K9b%;W2N8@;l7qcK z-J%(Z?<3?_;v^^~49XnC+i>nUAsu0H?U1=a4s?own1))$7z?qB$7@JCuJF9t#i{v4>tT(xI~|7Z`m^~pj>ltjJrRyIvCC`O$QCvS z_Yc&<&FR1-{N^gUxGcyB3$WtnKklMu_ZTMU7{T@tESSlv$FDLjJqbKrd<`9_m8rRd z%WD-o3y3VyH#vvsu9$F6!re*aQ*{smQXZi7xFQRD?-Rb06koYn0rf2ToxVD5)Y>`)r_Rph!PPEN?DTWF z)BEs>8ZvLCWbT~|s^Rw41yG`JIoqYezcUnXt;A7=TzI$d4~^=z^@{C2p^*SqxkU(h zrN1&jCs=Vtcuk7iBqC*gjUEtwsW|C_8 z4#iHRTn@`}THBr_Kpc|eZ18?3FJn-Gwhj4Yy9`p&)davK>oak~UFS)rvXCwo$%8lD z5LQwwsL}W(-ds(GoHz`$&cPwxHXyD$gN>A6Cm<}I_Fv!NMm1`H7f5iu<`D|VdT)5< zh9u|BUB(EDC@km5cf<;jM#2(S$e|$N@83edKgZMWedGp$%UD0Xf#i&%mI#>y19`3c z%K>NOX8TuSd4r=S7Mqc2z3xQ}5;zKCU*E%OCgPmd>wD9)v0m+bv&2#V(Ce>h^OsdN zyaw?BvwVWu`O=ckaK_o$w-J{HI{F>1Sm(keNM1^P>zPow(&s!p7~S9~f7Ri{V^scF zxj}Ix*e;#Q`HXK0<4tkKHysmPj(gPQPRQ_`3&#VEM$H&s8eh<%+L)j=b_|TK8!Lxz zpBY3k>_=RRdTG4TXaGL}mGua!S?~^$B+Fciy~Z8X#&*Uq0Zk`_5{#wslYqb+!f_P^ zty^z~ta+vx+*58pvL6zVr>G6@3oyu9@mu6&yLbr_6K-UdB3KHXef|4V0SvKv!d83K zb&7&n40*Eh%b;%xTBLNO2k>Dcx2fMMFQT1!gV64r?JoJ z5R4vtP^GmoT@c#WFeJ{b_LqG(@+Gu{B(UnrKClP=6I$sc%iVgXG4%u5PNV z=l2qyb#Y+e^o@aI{}$W-E!L2vl!xR;KK})_6lE)m#}vFhBJsXJ^tk2at4T`c$m8gy zGyZjB1LQZAa3v_y6L6wK6nD@%@Isq-pG}GJ!5uW?tcfR!rZG$3O;*GlC}`IueWs{d zHozV6eUQJ}$KdobO;!tVQ&;;wSil`={zer3DAB?N@!|F1F54$R`n1d*Rq?NMRc)eA z0$=nl41^z**kQwOFI7z^atp;CcLo~kxOaiEUDy6k@yp}fZ@53ieB8*cP!zs6h`{6C z{9Br;jDhdeUmicIYzbw2>CHZmr@;q+O@n(>O}lwtdeeI<2wlc+8rQ1g{y4qwxT^U~ zyDs_^-31!ceo(BPC<3sBf6sqC0|TaJ8vlmw=)j=eO{-YEA-hl+_kdDo`;I$cOgfWWqOoZjnfUR4@-hYv0uH2eZzfp;m4?I;`yZxqux>@ zDeD{g9Bg;g7yyYH;ckLRQZ<{+OLfV5!)9pb(6nfnCC_20Y9XE=EavGLjo_k@iq5Zi zDKMD=gJ)XNQdrfufiMi)NGWLFKQLsa@k->&?3ekoRrVh(^QM_X%tqa!G%iM+6tad( zmrq;x{14iA)UErr){)G|WBDRI<-t4{v2 zmWnBlv5q#xAO1Or&t)@DZG%oeMDH)ZitBYHQ|`XwJ7p)tY{RAx(lu8Rtc29s1|@SUC(8zNDVHo?-S1+jxb(u-i*#q5laRpzT`C(tmOa5*!q=Nm=@y+*RQ>Uy zaO+xisHBj^xD#i2p;Quzj3wBf8K_pF8gEn-9%SSHB^n%8ATg>~ZFqrx7r7ON@2|;c zgu+)e&0tPCMZbl)V*Jl7*$1_6^dcNk1mJcSmKS<(MVl_FVOgyffU{p>N zz7)@-haXSpjOlcd{OR)G7WQ~J6TR=aq)Ha;a(*zik%It|&N7i#1M-?P0`R^Me$HKx zSkg1fsmGP~wmD7bzAdNYmKDH(OXU6n#gm-9b+(LWx7C&C!2lH^w=1~(~gx4S@ z>n^~%Kgi{x}a8?gkhOT8bShPW8?x3%g@b~xyHM=bj?=y@A(L7Eks;R~t|32(v|6NKCe-`Ie!YNsgd z6w9WTVXc$@he=K6%7=o!*Wp_c^wq)_5%l@sn-}zX;CmqGdj&r1qUHaEKjC>m1mp$- zwu&t)dFM)dAfVYL3Y!r&&be}SFl+-D41^hKCe(yESI!ND3!8xIzM!uRz92^{l){%D zjN1TTe9$MrH$Lcl0luuDZykJ(1bxrK_sgJfEqvyn?)&pX3eY;rx-_)yN>=Wvm&t}<@!k(M1@ zgsJ^^H}5&Y_(Dk%6%Yx2LHPQQ|vw*p4$8Xu~Qrx9} zBoikCL)(i?!|YLP=cl4ezj_DvY>9p1Md6_MSO{*7LMLUt-lSnvR-SL(ly02GV5*8< zNcTZEzI+mow)o?!hT_7L7p)(Z0fs{eXadfzXII-JZeYj}PHv{=lK4NT8wLv&`qi}y zp8c&|c>|h?a#L>-8siLC?g5IsYBOnUXx;;|EC;N z^t>EX#tI%OBId&F_iz3rg}pE}5C*W9r6Au*$8F{vn2|aCGfqI40{L6MypDc(QGyC3 zWU$dD@sqGVv5`WZJ{WlBE#9lL5ZwvZQ;?viP&T*(>+fJwFV=|3(Vmnd-QmH{AhUjwZPMa0lS3NscVFS0j7zx_J7!cRI7DB`#1ii>^dni5q`3q!s*J?VEhXHrjmO z6~@Iu2!*|VoEb`ai3%?At}w9OOnw4S+1QyU*~XBb|Hs?A2Q+nM`{U=FJPAi7JR$j=jwZ781o7fsO{McS00-wEQaA2eswi zfELlhRBdZ*M{l*ASliK7t#uTw=lj_w0d;1+zu)h#+nLDO@3q(7d+oK?UTf_#q3QS! zc2!DwRGE`h+gggh+E5 z`YKL!^BY)$tCYxcDXlj53RKla|JBYQ%_|}7*79&!)(mQYxAxs2IZb`I$EUs1eCtkg zfnbqQXEGtjQexD~-WJ4us0*L6VTaX6BnQ%|fBD|yF2e!a5^FpM%lOyK$yYp5 zqDWk3{26@cbTS}WN=kEznwofpea#~wY0YszPu=;0Me@t3AAYaN1S4BE?Pr$7!5Wrh zOHKMX@cAaR|26+dg3PJg@nRt9{|IfGS`&z1MU`4`l;*d8goh0i)NuV0)YCtr93Ms| z-oz`}E1CWQLEbO0nz!NGQ4ZHf;A_+Em9})er~;Z*)hBeW6RQ3Tv_KA-ixR&LSN!_a z|1NOi(EAN8AT0NYK|dsDnE&Yqk20VC>ut2ePJpjOm=6Kck^M(^S+GM_@2MX+yq_E? z1Ia~-uJSHe?}=B0KMBH9n4?q)-Wb7OtQBM^4_#_b`vFp+8se^^hnadqc=976;~C4Y znmX%u>?|B5alMwm>3g)3HhQ*A#rY@^cs?_qnCW$RQdaT)@-J6hZwp za{UPzt@a023PI_!q!o6G?$8gb#<5|Sr9BcmQ^2mWEvsC~*?z3A{an~K4zgQz7OJxT zhP2r*DuB7hEU*dQD_7PP$qNjLxUVF|bL7a$u411=swtL$q&pgD+xMN=HUs>Y4E*%? zCj1D!!{e{v9TIr8w20dG{4WVexbY+Q4P?n$nmA1-%9*g{6fe#k?o7)sp*^01d=g<)Yv8&oj7pl%ZH0` zqiW$ze-rp|VwC<~wr>PpCB~)Pi~CyOWnx@_0mD3O`cmL2F)qMFk~nz3zD*9WZAa8y2+=idca{eyXaD>(K% zm?xPikllmEaX>d&a2#`oTQ&Z#jN^Fi+mCIz8FT?p3b){{+VqHA2s&7)Qg)_4m@u`N9vSd8 zKM2-$F7)S7wNoxbga(IKklI~$1a${gvxbZ2yBe3hoG2vhYKZ#5fKI(fg zYj^}>yT}%KmQ%1y;$y|6a53rh$o-cBWga34%T?F$8BIR7sX7!+GapI5Yk!`Bdl-j# zhmy{-UEjh%%e<~h*v@5SN#IxEI=ts1h7H=z%^&=3OA5quo+iPak|ADG+fpF1)3Zuj z%KSKkA}?PTy)X+h_=vYRhdOkLE?kDRs%LJ2NUlL=x6&ea9=Dh2?-j%;edQ866K0gm zq*yJd(|WI4^pAAY1v&=1_M}IXO}b?7b^e=6Y+{bGn~r`J{=OP$B;`ykqD>1ZZUH?v zGk0p-qoJ%4qg3GDJ7RwpxMPCoPvomlULvx*Wb6cx zz)hWf-EN%T6-Il)i18s}h#1hAfmB@O@H(J#|A+0OO34hwu~Df^>W}y!0=sN%WPv(+ zF0oOfJdY@pvMLATxEc7c8>ivxo_vp@@-T;{Td92bTl@q&-rEG$bU(X>8#}&>gxT1@ z0Z7KS^UsNcFXLY)DefFYVYrarbg6?bk`)-{Vw0P?oYq-HHfrEa;l+@99 z#;YVn-3bedH0^#I>C(gTn%4G|5O=*6F73oUuR*~-Ppa5-6hj5)a{wV%f-a}}yKG*5 ziM&8Nk6=CwZx7jZXiSO+GPHUvT+VnzHk3^MGE#|+qo?lpCK$}b>aFvaTyqcSjyASJ}OYo?pNZ^wcYpwF){I%Ag8`-#R z(zDTI+7`r7oM8?sa>ImgkG@FG2AdGZWJz8(=|mA!4%w)i`2*%IowC62ON5CT_Zc9BOMp$g?e^Ex&uy>D)Wj?!qZ6JLS2C<1I?@S-k1?;BT9gP6OL0jFS;m?qFmNS z;w{S~g%+qoUTke#j1X9_;#z;3*qRHBd1!23qO5#*8mw1}{NydUKh8X>F*MNm}nra0JxEXFQIWdbe3rUe8kCZOZb5 zNT?f2jUJT2JKrdsg)fjj{0GzLJz9>Nfe1FE>A*F9h&0@m&yFk6u7fwvaSrL(aXm7) zhqD{iNCAPa`3Qeu@uRXE=i$rkf%bsDZqLQJc3ir)w8?EH>$1S`+C7U}j4Ex3->qNa zp<$?oL;kNV&tO$&RUy4v_rCd1EH#`WmM}LsE*BthG=)uN#=hW!J>F6?S*4JsY>HT< z57ufk-S8S%pqE2ATudq0n;s)_DjZEyrTXQ2R7nz(nIIci^v{INhzrstFRgg zIaF)Vl8NB5rsi|Sr23Jms9SfGOu;({Qgp9QzmL39B_-lH`^Qb< z-){s7byoo2X&we)xQ;`_??@RQr)?1Cx&g4yc+li4;!&;!!s=_>SYZuH@X$p+2#AF?(&66(16`~m{w=h%~Re(>=T8CxC{)8MBYZwak z5nXa9>c$6j<8P$U?82O@*tKzGYAz(xvu^;K}>?Z zDJ${MsZyOft(LQfSJ6}s4||E+S~iFC;Q9yCuh!Xl=GMs6v+LCCQCz-XArC9*asLhj zDC|uQog*1?YNIoAc?(1ihiK?J*u2;4;;{~)v)#?xMIw)jENEPbNl@vY8Au^Z0V%B~ z_&@y_W6{@(GnGTprDN^J`3O6jcIEW#pu2WZVBgCe!vp!<<|dEes~(0vy$+^qdC1h# z9OSAk3{qxEK`R`J*8D)U;bPTv5;l)yi-RgX1lrpjwmPsDI;qWRw>h@g>B6r#h`$J% zt<%p#-B(BR22!RMT|%DSDkpcH*6MbN zgLaMzE*$dKaDUF-DtxQ)-C#wzZgccjXri}EUFy1JH1?~>X-@M9Ivl#{wg`v$Mox(6 zm~v4VlXX^*(`1Zh%b;k#=c3<}_DKFzX?(qeH6=)q;*U!W_s4{T#^{JDe_AJbbp#6t ztJ~GdPAYC%qTIf?5=%TLcc8Pt8pgitEw0Dn9;vgasUU)~{ZYRr>brvc$(ZK%5>gcf z5wuA^rOq0T49=-evoqg`7k8at%p*DL_}r@&x4a-fsm>aKA;6WZT^Bi9nWVH^)z5Dp zM@iD%d7XJ67@}@|3TIWnZ5q8-GU>u<>Vr90c=`LwMqmO*r=bThdI^q22Q0d9*si3V zXC=A(JXu36Ok7|D#3uUTE8@Yn4#|uP7bJ_tCq{uLrZ(N@O~q6}vAAZj70)D@y3dcA zRit*_2?MX#F@)i1y?U~D!VtKQvaCpf&ODK3CL9{A&?nhkJDxt`U9# z73?0Z0FEuA;T?eFm<-t;bW{RaUKz;}IYhJ3hR=l5sYW`P^L8*r=2SJ9pdtmBr3AUD zoCd?gqC2e`j>{wUho&l8j4Yw!w4)bv6GDov^5fXsHiDtswsj>Pw{dQbdEWl^O_b?+(LqI z_~`|vJm7czMfV25ZZwUY_|o{1LAuw=mc2p7+Pnh7o)*^@GzCR8mEz*_(lVeg z;;PLn&d@HLf3E_QF2vbeTw9Ix@;mWZNNO(7h1J2p$Dl1_Sj-*MCy>V_$JQ5iQ3bjP z)29NyHKi~IYn|!`EymK~2{EZByP7at2;^hPx&ziRO^$N$B-J;BQ^e&WDSh)g_Wm9s-!W|AE@&E zq9!)csKBI+2yCEa7L#CLZh;nFss}^*;Hb;(0$S6I%$oB?`GruX%7%v@9Gd=@AQukO zUoOh0Bl6y#FY0_uUH_f#!bKQKXNDB+eVCn+KjB-*KF7gu_ZbJ+)Rh5;*i(k24jH0< z$u2>p1zxftB7e#J`L`A+9Ty&a?eJZ;n_YHgbLG#<92xt|A>!(Jk|h?VBP&TxxX#Xz ziT<=7^SCPzPaZvRpB_Cc?0vj?ve!>ZVp>2<&FNzXTLZ*ZGmO48yz>sp%{n9&o$y*&rd5w{4DR=t1s)ryOIm`ZaQHMV(aqNJs@5I7l zbd1G4_MK)1xhxrr{P9O(gHd>LC|n;CVM~GgrGktiB;kN!5kE*OgH*C&iX`CSEg8iL z5?pcoj@(g@Ef%#~GDtK17X(X2p}*cmu}sxjA&dC+J}D+veI=X}6Bor^mVbt5YBTuD z%|!lhrF7@NHUHU^%A}`+6jp}8kCD0Z;$?}){aaRGXG6Lb14=snseq`zLoxO6Pu3^C ztpZzwH__^j;LR|b>5v4j51 zf*PAL&QqymLb#;-lACo2PkSN>&*t`AuRC_ybL=m8JO?t3#-TBx@z%m_|_kZK{+)yS*J)%A*08h^7G@`8QVm*{aSZU5lr zS?F5z01l7acHS%0B|HU}eLxx7l@G%2nAD$+RJ-vhfEG7{!3|ETw3NxRFgXQGwn?9B zvCJ*C72-mH*r@?V=WL2Vn1fb{uEGq1c8E23JHJM;v6Z7BhD< zn6n!wPdGT0r_sdBb`bNzy1Pc`AaWdG#^>taOVR50X!W`gIZZ0YYWjH!yc#+KyV~GP zOn&USluMs>zWC}0p*GR$3h31dYgTKo=bm7tD|%N+ot+J}3Fb7u*gBGF4SO-WjdS$Y z=|YH2tp!KKX?hNt*qmOg_s-JC?_sKbOI59+wnQ_ttr&e0bzl7RrS+VA~JV9mZlQZYzU!%gE znSnmAbMletAUH)czGJ5!ZTJ+r07!^qRAR(@Ce&&tcp z>82ie)9XSp?QgPq;1=p3=a4Avo_g>^nu8RzPw#Hgm9%@;f478rPL~Al4_fzpQiA|xtDE|xH_MC zIXD;CO1%msV{r1g`L5p9+V(W+6@6|emq9hu#=&%bhmchR8;@Sg;Xhl%>q^2ElmC&k zA(>5h5!nu|o_faK%4@#6CMWleu*XVh8krCrLtU|`Z42~iolhRhtu5x`4~(0|u^P@y zNV*l*x9LRXssbMLZk2=ry=)oji!uvUBnRO{k3Im^@4JVlW%JQ;($7&YUJ-6VQwz zL`vZt8sEZX!T$qRH5;>YAKZ^lew%aCJL4EK(I$tWzQVP)mynsxMm!~N+4owZeYliX zcfifIzO=up#8baYRk--p@z~13Yd1BIDrPZ&tnd(JtldxG)H zIQPgN0azRa5WhMt0mMiE@w4ntT1<2ZmIo)wRwrJuA5FFgKB;5q(+1GZn~+fvIdJ+q zo$DKHPkV{vqKl!+#@|kVQ@dv10(iWpkn0@xYb=)XWhu=+2ytPIJeSJFfejLS!|#6fSb&I=!Rlfg=_ zB1@Z8tN`!lgady62 z`)w27m<%e45qPG%7DD+RiHj#S!6SDg?(uE;^xcb1U;Vk{yT4+(+;i9r^@o{6r=6Ov zU$fx`Rx+zdgRyFXf}G< z|DiygA^K%zysP#NX0}~VnV*=N?O0!LYXUc) z=)^zo9KBHmXA$l2W2^#ySFD6QzSL!1HGJH%p`myuW$~%XO9um@WJCeDF7L zCO7$_e@Ysz50|{HUCU8Tl|QbH|20M~?s+C_3dP2=Va2uBB7FaLXO+sg2P}W&i=bj&cB$m8}l)WEl zJP+W$UU5IrrExP*CdL7vt-hb`0j(kHKy9~DzP0daz6B(6b-8x~Q~Jc#QNV!x()e7I zj$T;7N0;+Egcbav$T1@$Un-}nTmmQkJ(u|haVV+D@LBD}I^T}JsrWs0j>xCK6mGVL z5?_q@HwEsEhjHol=@cvqliOzgi5OQTCu-C8YEc7MM)7|pNlxqz%5EWC>U%~3=lX@^+UXn-6zRo;O^^IR~myJ@!a`N|;s z1o-F@od%`K;ra;vw)@;c(CiU=h-~Oj6)FDAkGOUtZOI_yx04vcj9s5<@de_g6R((X zE>FR4bC;;|Z$5Tm>a2CRYJqJDqp&{X!>yB{95!7`$g9&WsR`_31ZztO)ljjIRmhvJ z3Z-#NF!*kd_e!D~oX;d&T;fq0wcj^n=ih#W@d@v^`@ECwBl`M%qV7|)gIcI|FVw;T zffUE2WO}`wor8gE9!K#{PwBNz=`5XMUr8ax zfXALa+Bk^}-(@m}#QZzyx0Rau)D*7oN{1wk#`|rKu$l@Nv)yB>J}7mD_N%GR`BPe4 zY-^-L*%sR9YG8=WC$gq;#zFbq?roB+JHm`cMXG9MLuyo7WGY^{*|MjlPJxV)ENs0d zJzZA{yDK_1I3cWqF8fK;EhB9{J_VG*1hRHju=j;}|&;M(YS^nlZ%~_B!KY zxq>lg8Od^Tl(IOF{&C^Cv#KQr`$QMbN9+Z=l932GnWtTCsV!KU0Kf+TaJ`f%Z1=mcVze(UbGu-^CP&kwJxM2b> z=>Gml@82Kk{QDybs5rvqzkUSQh+CWvrJGoriw0t{xRY4P)J@; zvcr^XUR;E(gQFdu*iE|^Yc-FNk-=2L{aBC0cXy)ZyPq)?JAwma03bRf)uCB-_iCFx zByQm0$xO9L^?nhnitA26m#MhZ4?V@iM;d0~pI{tkd~ex3F#qq=ZYbO_QDVMa82@-U(e zcZ4BT6-9ZL(Hx7N91r7$dj|2M#aMK#`O-uOy=9AY8c>Zx8n;ZssmNG!nGweGdR+FOnZMsxfurazbJq9acB z#=OqE5A=SxVtv~#?k#LMZ{2k6Kk))wB6XAx69#U=L;@^}GnB|x7&KCJ@Gp?z@ z3(IpjhgGv7I>)Tx@QT-#OwF6DOK$JiDppAC=#J9aX&>0{P_h%8y~&l*?T%!-HMFZ2 zoCyK?^u(^-7>`v=+BrS(G_N@;-#3vv-lGj^(vrAO1kJHeWI?uX4Jacd1j6k|7#e8&E{Divwu*R1k-g^kN8OIT8RZGxZ<0>%u%s zg9r!R0r3_Y@Uq|0h-4odQu^n}M%-cgX9irCtcCIo#hUtY7$~hG6pO6PiIib1Zj_a5 zTK_S@bzYNjHETf7^j(>!%<2!^mm(W!KN_3FaYtP%S79$I%`rK3Br-TaoF|a&(l?fJ zs9XcwK%Qa+!x<^upvuL0(>x%Q_U-SMV(>2KKHtxQG>wM_i=a71rOxpjOExsn9TIG+L=}XP8f+S9hc8cRT9#C&l-8_h zRr1S7f=FUX+SK19>6RqfCDPXiS|$7vk_Im6%&^C;h7y?3LkCrBD{oGMpqQc$1`!xaIHr6yH&64k4cx{PDK8@d{l#7_8Z7R?3? zzjv@cW5jx(^P?J5ZG(K_+FBdTu z>b6uu29o6G)3bMs=`vtg>E=6v-7P?M@uVWVRoam6yAB6GuKb!gxd|XjR4WI9Z&W$y2DNeR&x*@r zoxtGW9xP@m?^A91VJ!f}2Gvase$mPSWYv(=SSsclopXh7h8Kz{`W9Ir^HgV!k#Wrw zG;?Ue``jXOCj(A=K-~WbzOMy>6>*+`PyhYIz~0Hqu^HutthtYn5ug_i-q7d7(}XG<-58llo<6f4aoM~upeV3Vnu(m!R6h{^* zUr-h^OXU3#)Di{am&kKMYh<|*6=Cr^q{XCEMd*e&lq!xxYVq_6ef*B_4W?DH!9^9J zRW!9qu_3OoS}0x0RHVf32;0EjpE4aOD^e;L&8e|-m$Hg}RFBu&9AS%GO#h>JVACOs ziwr{lWbzcOPpUO`QDaH#G>2;NBD{jBoYD?ykG$-eiJn-AE738tCapWDJet+y$h(#0 z(Ng(%6sbu~RhEaTO}Hvr0k(!pQ}xIV&rEEchTFICX{ywjFGw|dYVA_0N8TZAUOo}; z31W2@-h^L8dZY!ziixeUu9=QRe*@!cQc3;F7gUb$tdB8P|EdjNDar)eNW8y|vSkws z-?}zB|5&WxA!&TLf=`-+xf_^^WL*zQYcl!iBa!F|*1JP;%0V@an~dpQwuq{JGxSQP zI=h?QF^vN1D6@BxWht~qDbF$5H`~wmnaO#N>r=)@F@|(uJ93eFPI7eeAuXh|GkRoA zcP1GMF^vdFB#nP#65K)AQfzjPwxxKp4=~MnBlOh|S9!P+F6rzRs*0ivfpeOl77a;9 z)4-ep{tER`S!PgOI&n;DYe$fWsz((Is0`n5f>nS0Bw3I#f;=2NPR zqgE~*l5Ko%nCM9m}&Xa^j{G=D9e4o$D}ZrSZrqf&Zn z7d!k;B;(;27rpZ!xjUY@Vdk{tvtD>iWj@#WvL>?ZXne)!d7Q;#V4h*@ntvAVlh^c`C;6j&e-;KpdsNATUa|$H6Td%(zlkNq^>8u#v=mp{Xd9d7 z$oiD>M@U;}DUjwH9!YbAwlZ5!lAUZ$4twjfD5ee*I4x+`Gh5nmxq<$8FKPGxMce15 zpk>XJ!K9kW4V~j)rIwu0z6^wQqdmjzkvjc=V*9@jej+~IM}RmHGRZwh>prF>efB}6 z8%?9)zX!SySbL=ZckVA=z|q)?y7W{llm5X{!#l!YRC=@5zon8gNGDBfBTbO{KUmrd zs?_}EgZZpf;j>uiO;-|qDk^!i*Gc2O@^{AqVPu89iFMkBbxKMONt^#0W0!_?I+Mf5 zS;Tc}#!7cG-I4)3Ud@g<_95^XSXa6;i6W1~|0NNygBNO+OdO#bhyXJ1ukYI3kvIsv zzPigFPwYLO*m*n=0+Ii$AcdwT*8;+$^`u*By}Ox zdnmE+U(RsmUOC?as`s75&UgIf%HHyqD?95iS9XGw zYl5Esi*(we+~v-l#p_p8gISqDFx&M7b9<|8v)K!Wzq~gjlKSdM$jKwg?5}3i-;V!W zaVuWiM~?Jp9|sn83xW8PyFHS5D)RM9s`u5z&Q}BQb_C%4Gyv~W(yoqvk?yQd>~pVx zS&t_HEoxJ|_Cp))Z*m^p=dS2cK9r-7tqRCGvvmjdU54u!PdPcXQ1iypkL&D{{QWw(5NySzG) zo}9gV%*KYgqjy|E+az%GGFz$nLS7xQ)RRNJ!#Jvjg*qv-*8SZ21`{ck{Fe8hN)7~d zNIswXtr_CO(^D^+_eDjvr#zO~{{@f%n4&Y+W>7CGqf@F*2~>}y3XfxDP*C>36ehIQ za8a0)+5ZvpV&3Q;4b10|k@doX~sTy9>B@hqzmFWx_Zah?(rZNcW^Mx)yqMO!T6I3Zws1@D78Y88b_|g`HV+GJ{&R_yn#btYCk)XE_sZEPZbYfv2H^pA4*{v=Ss5jnhE zPt{INxK9pG#PHyP!FP&ZH?i^luL|Jjk_GYqE`SH#i10o17b8;dhltcW==IYq6W2Wn zEN|TD@kHqT5D|JSFguL({rG2373Q7sfE+<#@F0$k^4| z8d-Pj`an?KK!_8ZG_0fS1IZ1X)0Cyg$w4c<;_C%)VaT? zzc|@2Ci=a)qaoFkuI#2s?743B>7avMp9e=f<~Hoh`Jt`gsKwRCFE^Sb!8T_|O$I+` zgpHN65Ag65f6RC;Pi^~sgw{dNs$qlk3d~SdU8v=c5ddRqic9g>%*%Miv!8^E)djuj z#RdF-8S~#ardezYLyFfDmI)`3+)}Z=7}P-=9`FZA{#<)bUu$XluVj|PLRTNGTWy93 zkc4aIjIW5AJEtVm`|2|ILgWa3?9!m<_OMJlkHN~T6e{Imwv5^E>#h)|0V0S zr79@os8>Ia56RqiTRFYDT)QIWy=7ZF4JU=Uon@a07OAp4ToFBIEyO1bwY9VPxUfMt zPxV6BroXSv2&$7~Bsa2(>W1HTNVj%^f!?5FBj>3$ZnS5pqRZtG)J~TY*E;r$AZ&?G zCAPSN#gH;OQyxN5PpMj521J0sC>!#f=Cc2RTqyc*kLoPlp)5O&sXI^Ql(_P-9X&O( z#q|&#e9j04-Hk4P@+e^zqRWG;><}9|ZVfKa0@tC?9L9lEX>kkLkq_I*&CbK{o6TnK zx|oGYgS(vwc5_@#DDNSNWTmKyf}9rzt4ti9w`R_HqCle3yhTAm1Hx$N6Tl4?NP}5r3psSI-N@8@mBX+FyE4;%83CWo1T1!QZWzmmU#1Z{X4jE5 z${CsDX|0vC~Y7FyZK|Gb^aMuH<({+;rwI9)U`IKPqb^>{BwZSu-TXu5_k`E zSc>M`7J6A_UUlUX<()l(QI0v*%7 zzpb8B-lKB%Hk=?$pnf^!=yjdA)EHMZ*9@K7p z&vPUdcCoW+j=ckp`4oBZyz9v74u!8@n5~Li{7B7AHU)PH_V}1VmzYrYwa|Y9S1n@4 z6_=TgV1oaZD&W8Bx{xHvnn*bo&8l%)j=hs+LY2Lw$_}RQ$m$-2?>r7^$VMQSHEW?9e#79 z!;OCE(oB|8DL{m%(s!1?xHgAXUR>Virq3!(fKlHH7`vI-W0J<~pH=UkTpuq9dnYOc zy2_U4?Lm!?rAiuy)5gthAYlFZ+%HDKl4C+*7%;9PT)YUE{r?JAbNdKf>j+$_CJ}2L z%-~YPpZ)e>zK`)%-Nof>=viglM!f4wvJoUs>y~VpF(BDJX7(6wUHyJj{fwaSBhl(Q zH^t6*eoIi}EI@dB1j3qsiD z*vcBwC$h#h5ECe%Ryueru7E{ahobpyL5`^m>V7_B6x|A&gEr}vY;}Wd zi6VO4^7uDJ99gNN@U6@8)|kPyUY4CzK>7rs2yWzq*Ox0U2R}zDT)-;jgnqUfT(NDj z4Tj5#vr2zHCyfg#2OYe=;Db9C#{Z9q50Q6yNIR-HVA(Z*tr43GG*aSn)Vzv}E$BZ@ zC5fAhB`{WEx#=T3&qP1Z(@l7u1i73dyw2FCz+ujajKXeZ466dmqX+lF-!S;=1Av5T zV%-0K@Pu7)gq{X;GeGmDpiUz^q3?g2C+sIZ`2XMuF-{ijvGdnqn>AdUjkl$B&fP;)z*PY69U=m)anJ@4rDEbs+jevX3! zdX4jaBs>)h)%)yvnMp;#)jZho`fz+kA3NEr>~cdZbD8ggKzNBK2de8|gBM#a>qn4# z%oQHm*h_*|1#Ju3^!F?y#xEyKBMq9nCw-1LJMxJRDel2ADVC_J8>O3WWa+>M;SL^x zQHN!>%F}Ywb}*#nRdwF}b)HtmaXg9S2*JSue3Wg^x&n^Uc=3n!wmN6Q(>FJm49Ond%RuEMv}9Mqbb{7kJUP0&`e0BSd3YLkL%3*> z%yn!@!7Y)baPLn^aP>#z=J$=qC&F$VV%cn*Hd@0pUnsgQtCa63BIho3mwT5-hTx=l z5#8{Ee*$^WJm=82ra09eE2W8)In=E*gg-6a+5O>^2ycgyjBNnkkD;`27Pql^?rCKw zMcA8<3Y%{J3)s~yjxKNyt483JS4av^-Iy&W$Od*ntLA!)q1twD*_R+~{x~b-!9-q~ z2RGt4y&e&^9-4ciM}>LS{2|c~ZH6o~nWRa4A7Iu2lZV0ozzD*nc3_U}OjTB=Jvhg< z>P-@*ouN%;sfl4Y27V#rCaID$E4Id(%#=kM@JF(V^0QkkMUO;mRA&)55L z?CTl9aV*suzDlWyQg&Mij+c$#7%X`J$A#*J6If zkZY>i1SfTwa~F2Y3WM*06pLap-w-Zd;#8;C)EJ5^tJj5O?+nh{tj=4#*S1Jog{y$P zy~URNDg&!r3sc~T)h}1#L4v}aQR$273m=VIdzd+g*V5p#W+qwhZM0@MvN#HS)pRka zu2B_7Z2*kpzhSe${(=TFzKg=#g#)s}7y+vY4`qVOhcN#ep@;_8zt%vn50~+;#-g$f z7JjKA{+r;smYclQuv5X{Uzb{wtG*d=R(9?s_2QPT-?o|8EHU(trM5P^*Lyd%vB4V> zyH+wyMTVB~4|gXGD6n!hqlI;PGHHN&wUGtEiI)tMPAV52TR zWlROVl8ZmU$YZJKP!ZQc|KfYzx}0+&SZ5f0saw|888C z3_^G;rWUM|Gjqh%^Ow8*uL(pn53zD{GvY^e82I;NIq~KQbnyKG2lIYpLJHS%bJNX) z4BgwYP6%)dmNFVU)%0d8znqL6e<0SSOj9<@uUXslMl4@O;>aQ=Jl~k1G2-RXZNEI( z!PMOJxFh-BkUTvq$mAes4df-Q42!Mo7F#LSqrO*T`Cp1{G~R1tM=by3zi0!(SCOwG z^=FUP?;EXuHlyiN7#WR8Y2F;G*-SNUj^$^Fbyvn3m2xT7YH}5{)Jq$bS>q{tUwBeb zVb@*$MUn=+3(93_H7Qnvx>P&sC!`jnDfua+Y!ypUE%izgfkPbBEc(KY1%;tM6Ulee zGqF5JGM!=goqGJ0!%P3>yYf3iVJwmS0Y8w>+z_`IeB*fmre*_VrThd^2z`M)#NybR z=b9GB@?%JpwKz6M4t{QfbiFAUb6eW{n((43YYdgMpzxKua)3hB=EXV|kR)f2uMLSV zd50X#A9Rs|x~1>TQh1JryNU~ggoXvVs=^~OJ~K8)S-AO57I}5GDLt0ILEs#m!73o+ zGKRNiCP<9231RWy$-yuYex^fV_&toQ*7Xq0al;~Urz2-irQz4mVolIjp{*CCg@)Tz z-wTBw3}@lSl(=~#eNA50jC&@D>2-SM^qABo%!|y7RtDV4sriy#L+lAdEUvJOq?^65 zu_yGgd>r|{5JeO>c3fv6Ol4(@USYCKlzBpIe=^{;M#oZ;^pcX!{m+MJ*K0L1f_uYa zPlSTr zf^r>mHkg-@ayYGxr~XpD=_Vylx0Te!%YW57tUocVM;kvARQ2A{pSY>#Z>NzgN{e$cr zryaal&XKVxH!<=V6#h>QPJmw9k%r8jE^X6udZhMGrJC01kpXJ)P0#AfLz%23s%f>p ze-hQSl4Ph#pqeU3hAdb=W|9nY1J(3veU+X%;tFmm(VtqPY_jV6AEw9?yw!LMu{t5* z)O@P$jl(;QVZKMB4II@BJ1lIlO$+q>WSu{$j|)}Aabqv7#k$u`(Yrm#M2xCiq|Zwn z&I=t5VN|-gdVElHRJwZ@ECr>@BZwuKqgA?0k`_Wm$!`ixW<4PbsPu8YDF3rk33Mv0 z>*DxKJuHdhTVwgh_3^F27zK(_Nz7DLDW$`UsPw)trvEpTIYpmK_b;LNnfiER9G`}) z3|{EgrRu|Ic+3-&ae8x@UK^SSSaf6c z$@CoZF-8xdD2WJQ@*JHCYwW@AX~W1sip%tQmf>`Ij{gIG7N=S*jG&1>i*GrE4}|&Tzd(RCru4ueV_DvK6E{Ke^;lD=eCO9tThj2KlDbTF@|yXk zI)xmY2wTs8NaE5|n|`z-^Tn}tWWFe7785WDz;`##9iOb%ihE^`bZ#$rnJS+G?l8R?&Z?D$UlA6%T##tm&K+m zGidP`?t>k7i4BW=@%>`_c3?`xbq$H`@oSQa>x#$u(`1ElAW8U;hgwWzo3735RM&VM zrGph9wUs1=e+desvYb#6|1aWOp2PX^zYzgC$JEsujsZv=Z;usm8ZP2AR>MC>N<-O; z?ve8ULB5e8Nkz~;nq?JEB~~+wB>88K z!8ksz&}KBRUg*^>?5o0^-itB_1zrrQfV^=1^gj*3?3)+!8^epFu;EV#-}oHrdqMg@ zjmCR5`nd50I_&9WfspkQO_F+;%d)e$_J&QDIF9D~b&$)5DW!isA^$j%A4@O&6D^b} zn<1tPq@AZ~JiuZ(23bY&SY_PudTDB?Tt-=?_>`ym$Jk0E09kWa?<_V7_u#$><4g4- z9>YXD>NWgr9m&M<5vn-d9{|-wPqABbvyJf3nj*P*ZVvTiHHUAT73##At zFnQA@U5k>*dWJf=m-@_6z@ODYaTs9m-{@@R+S2**sxnOcu6o6et#^lrz6i>nw1)7$ zKouu-A$XyRKcj0^<35Z3i>|uSYp<8Lb{=VbFxv=0*W^!76=ANAOICVoa^c{5d%3s! z}Z_a`L_ueu*3V93zJ*k_%fXf;m}uj9)k0T@b1czk`h~a2q3{ZNseBR0@JS} z4j95*8QmW@NHnj~b%!!{Mvp}ff{eCcioshckc5W6n;2lNjl zPhphQ5w<*amQk{jLmIb~DqTvmH8?kV4n4(hCs{bm4=fPO4=fPOk98!n^(tnN;f98l z%j2PignsZOdX=hXBgtQ?foP_?l4#e9_$yb%X5AvnT=%Le9j&JMss=JioYE<(`{VmC zvzp`}m@#IUSLhNXD9Z)|KktSCLu?HJu!3ayM*yEBksjSRKEJx-E( z7_!=Yg8{)E)?q-;gSp2qVy#Uhd9l{8%CI>E>ab#+1&C=fN#`f&ssrncPsHcQI^*LJ zz&azes`+b;9XJ7<1P-x10f!tZ>pC!49CO;qRE?wh(6s?uO-Q*T!XeqEY|Vh%;C+!n z)z8SuzJQ|w|A@{u7*g{Lr;o@Yhd6d(cO@_z1Oia5()}X_f=TscTk`!yBPZuJ3UeTS zh1wAY^&ZE^yDIGZ5PabzHe&^hVrwcqdMR4m!ijJO@BCH-a#$OvrTH@rVYK}!b0Quu zlcXNT@WTiWd2BdoQ_~-{lU*mxoTkIB)8{BHbcj2wk7Vc1YpZw2D*XG-m-v=f1ooXX z2+$S&eaClPV~-P&r4f-8r{O;%rNwt;_d(#*8L9Dro2XoC@tPI<3$-;} z81oHehl1S-E@wIBE4+2tn|#f!1R3sNzEyut-_n&WQ3T4R<&%=7R^e#;f8R<%e6_Z^UY6>|^UL@ios)J1MA{!C(tg9if0~z@NCh~o6BAPY zWfEXpH(kT~eg8OtpCxInYhXU;drRZz4=YF%<^(RF#Z3u#?UvL$2Kj{`h!jGs+@E&| z$=g!LR86B&>)!u3Cxw;FcqOVTh?@CccW^&L%?!X`2Cgm{j~UfO|w;;i;GF9iwhBx7Wo5@1=8mGgEPgn zJQ6T*p*0_O>A66Lxg@Upq?n#VzEewUeoXaXB}!1|bkf^qV)RYsR4hsFVK6~>Gx-$f z22Yn-W7k>@L$Xt^;I3$E8nbB_CoH>1Y0sCZ(RiCvSshLXZ#KOlnDP~0xosx5``me3 z@(EkaI3ibe>YVvsS))%{qpn$FnqQ|csH9>oH4BWisNfvHJx>={_5P-KhP1v!b*i4? z+*=b=n}+*G8cd)QNP}T?a3%MKz=;iVVuRWfHufVZpg{fPfhNnENt2`=STYgl;^*A82xwFLXGkS3}rXnwC5|(>=quaCE}kb)?v5Cw5i+j z`Pcusz0H387O|ZUi8!D@$Gs-rAVv7zhcTwkS|Ep2lA6SpzB|9^=FAf#XhN%_$SHeC ztd*i(H)K7Yj^8J-S&tjXXFZ;SpD_|~_+1YVN+$&RuM@H!uZhZh{38B3@K>dI;_*xP zE4e*j6{O}U8*(l2UI7KC=Q`EV~aT=sPL7v0-?U6k3cx+NoI@=zUetm{KU5ej! z{AwPRr?*a*r*BB4(ld`z>3@x*#PAu!{WTPBkxx?TH$S4%BT??DsX^(ln1a$5F1_`* zG%D-yi||EdgS}Zvbk^f9T^EF((ayGuPdt7xCMf+}TTuEX{8mo{{3v^ReNcLAp)&na zNoe|ZYiRmrl-c`#*n1barmk!c_~axU@@fUt6bY?4M=*fcVo-ThM~E1K>K%*~)Ui`e zEJT?)ZJEy4hjUA!22^Y{wgT3fhJyj5T9s;j)J_3yREn)Qty-&7YKvpNZAYzRTSfT( z`y@O>eBPOR@AvyYe?28R*^jl?UVE*z*WUZT@hl28ja!T7M(rzo;^%SC;hBzSE7HY0 zU>c{xL)tSyu1HFmCQr&vR3tr%zZ9M)8AVbs{;mUUn_Dh}7uX_(?@7p$iYE=vBwzj= z8q>JR_>5~6Uh1c(aK}PFY8}eOcRT^u+5gixe*9Cjs|pW~dwYNOvWTUgaaW#yBcp%H zU&m#zpaFR!@Ry>(!0%8zb!`;(hpq^xl0K!QS*+N!=+a<2ZaL zyjt*pB8mJZw7jY_jf)4bNVy3we-#hX>(1dF{^DN%o{aIJu>f?vv;lk#=8zsw@DT6? zPZ;tRLtcnn5cx>OySbDUvn}HH|xj=N$Q~NB`j&qv%dgMVQ7dh%}9R63^iO zps43SQwE;pkhk%mX^OvT+!N$G=%uL5XsZh=ax3s;NLS!JR`4)+-^}1WyovzONlwsG zN%;FdjbVX~6FlNqZkxBxU3M);}nc%8;fIpI^gs z0?%*p-5*bXJhSkedrScuJBEZ7h#31+$2k0lrag!6Xmj=g@B8x|9pl8^CVU(?=!yF`$-y`xBcH|?J! z%NTr4#Zx>{o^+-ZcZNY!&i&j!Ne#IRz1%;kWw9bD!iKh1w~b2$|0azMN{V?nDCtSN zB1uL~821&PId~q%LtW{glsz&iY0^|h(hl(Fxlut$$36>4`t~_R(xR%iaSQPL{b0(t zM?Oj!Hv!KAlv#jx@>5sFJ%_(vqi-gBKVe)pek;Of8QyQkUn1Wh`QW_901U+tI#qdwVS#Ms^iWRwme@w?`jSmqpkFnyMOoPsy%PnzQkkF!2MiVlzMF zp2Cozp^Yq#qVNMv@Pil&KM?YYjiLNNt!1tafSFAKa}-fyF4E@tu7l!OdA=*gLQ@x9 z)O-zDg~+ERvx*AulLOVX5C=#isSE7D`jH*gU(S%6st-L}A6#3nb2lnoF=2>C;TCFX z?rfEoQ!65EAi{K&Zeaa2ZB(smlu#ew{y??knd&cFQ&g(hOH)nkkPhG8P8SUTjOMxZ zabMG>ujry?_Qm!B+_c@yv_PIBY+CaS(mrd@4^2U)&uR7GQk&Y}$@hQ$Jnp!Hi4A`w!_kJ$hza>q`kTe zyx#WxGW5j-R$pABme0d3l7NkJc!3eNbYq&0lTm9IFINhDz&t;oJb;iQAFEAd{;}L| zjBH}i8Dqo8YRANPNRT@fHaWn^_g{{{0@rXzo2toY07;RzKfTP!2TW$v%R=wLOq7~9 z?A~r#L8+9|zFIO|-cl0y^z#LvSDP|%?eV21ZSKoMcf%=hl11(dGH=;cgYy zH1JO?ce1(!bn?K$K{S&{JH|miIbgPg)!|BtCg71)pAV&NYYs!E*4OWBRJEhkCSSO^qd6*NzwFom+Y^LT=5zg0#H4ne}f65j9+7 zGwZp!zdq3b=16z+xBZSJXKSyHpxQ~o%~Y=rAd$A2VKG;lJ|Zt7Xj&VBGvb1tn2K%Ae)}BAYP|tLr=8 zxbUXFUVF7!dzDmd8$qhl?D{7%QOTOCQwClo9pPmAr`6ABPLO9N{Muo|ZY_=vI&;33 z?O*-nN#>wm>jh}S{+f`l4Qv3wcGPsz_&PH?K;6Hh9)YCKSLVw1k3R#i&5^U06mz()PYClA-DD#`A)PoR0_d=FB z`9X=#CdQ*ZiSbV_8Xr?MzA{)|Fdvr`)D@)E;Szz$K~dFTzQ-I?xYdM`#!uc;?k9%t zXXSFG=ImdI5yT+Q`9z7~yX2YEu&(TY%HSvy?yO>Q-^;yE@6);aqdl23+dbnkyc*cx zTDBj4aQmwSzMp2-$Cdp9yl*fyZw*j^SucE4Ip7|#R#|I5vHb^eLkemNzaOhxnx##p ziGY|gyhj4CPF|A}tUA&tJH={J>yv(=%N##$#Fe(`%~?{~beS4)sVzD6YDR28+(_DS ziHbKj{m#J2P7k3?KOhEmFXD;nP`5($9y46o+FwQ1<-emm!PIljnY;QWf751XHA!&+ znjNxplzVp1U-HQ>^_gwW(?HzLX4`Mb z_ssNRro;|xxCL`_9#qx;M_Y4S8_vT#rm|&|-%p1;V_-GKze`SSn^Mu{V1SR^v}(kk z+u{n9h|>e(sXwhLX-rOPoAQsgFUPf=U(@CZrRvADHJ7$+#I^ui1}Wsr__p&C+E#~1 z4&HmRpZNL_^7=dFRn>?wZKrrHW?YPcA7W%VGdskirs|{HniIVFlSx7&t08HdJ{b|y zCh#FK4(MsVrI3r`E3Pp0k)6Za5n}v@FV`p zE~D+S#r8c~cjO%e0Vy0*AD zOa1z`=9;#R_nv!S=Ox1CPwMa%dpaah{KZy9-Zd$4tJdB_B1PWD|D1gOiok~^JrZN& z@AnXo4Bu+``;BaZu=W4bA+~SdVNd^c%#8q zz?KxyD2@y*!jLiT(k#<>2NXG4+5VIKupzx%-F75MVtb8z z!>)>K>asMMVg^yRmE_HOiAh74xDhA$y;ngd4{F1HkO0YLY^Yc-37}s5LqL4;<5#9U zeg$hd$zQ)NE)J2@xg`Gy;H;kX!+vOJNSlScIUS;~Eg&DFxk#lK{*WSj3g(k{$$6v= zGO|3Q>q+ZW@*`;d@(Q6fk9@m^Rc=GpGuBUb6l_?`dT6cES`YqXm3~wj?s8wYW)0dPs){bj92NvMw$&6=i(K@715aY{!X%#HG70sHh!*hdvD4)wJc*<;Hg}zgw%Kb_Q-~>HMsE z7mzIPETfqZsQMF^Tiy-awR?xkrJ~epOuI2@&D$P4qVVB+CVjX)IIPw+XM1UsXBS>S zyS<=EuB%n-mKZhnD~4GTFtlRD=edIFI&xPG!xbnUfTA3gzI1=_F)Dx*}3-hbz|0cLpQ>AE@i9l|>A|l&_CEb9{Bq1xdG`%g>w3^Q-IgFcAYBq=9|Z zHOg1lf8163CUmv$7gSN$f~7AO;Xui<9XrE9mu`=e0l|u<3ZrDvMfNA?B3X47 zPu21r!D!V|2jPsC^E`xG`Eun08W1H{0qbYVH@t1)Wk~xO{@4_plKS(CqNyg8m?qel zrYu=ZHMTQVX|n43mY31zaNXoZ65LI(M1reT$0`Z)YSGh6A89y%p57Pb>nnYfub)AZ zx1YfU752`a+J6W_EzYz55_tB%fZxCLdvRo~Ew%4IRJiL5adR=y@P%A~kSGH<$CZxi zK=qD7_;*nqMXXs$=_8opQECOF#gV8|HluW5nZz-aYMCB5Gi$nEM3`#Yq0+!hIXUI( z%jBHc%;|nEKk7y992c<6JR>YC8e-v)Q2J=eH=-b}SxrPy6sPryorAEs^7hkW{rHh< z%lxcInGo+t1!?SZI`cDiYqk+ z4pq<&eTU=04s|#_dcry!2_2L=hkRx`941^+fsf4K4%3tl^(cHa;aJ44I@A;J(J`pQ zl-n_yWjKDFz^*g!l}27L^J^{qpYr)Xw@Q@Nm;}9T`}}A0y`8NT_)T0expZN^<-v&5 zZ=J|8NoD(l{OV*Y*DKbiHJ!Dy>(mVkevZT`rMFCLR4~+)ljz8)=K26b`Pa60eqOol zXEmKTYQaSVzntS=;rN$1ezlQL;rJ4cud?$sPX0{;@8bA(IDR|FZ{+wb9KVg@-{SZ; z;PN@y^-f+eumWLAEGMOkja$21br1=@yS0V=@B*VXAWM4KP zp|$w<^65pGxww{L9m!?#ry7JXXFa^;N;IVLKu)ZxIE0z0GM8VRImOJoEbLpl+yV<~ zmQqbYo>UdupjL37(rVd)pNvMcb~eYpVdpEH{D#R0T$YQ&nabzat7R5;z1CsDp?QA2 zg|D7f)BMuU>eA@6=rQ|TMGn8c?Vt>H@Qh{x1rFQP0gkQdX5V*BH zLKdBBw}#}0m)gVEATG0Xe*V6;BLBP`JHKHGBgQ$s=`CI9O%`j2CA>60e9a5F7Ejw8 z2F!G_8wCE1BTLS#Sdop+P@7Co5vD|M&o`MJYdc71`~jVTp4hJOC!ypDhmi=9T_I7I zS@s{Y?xanBhYPrVSe{zhvMaFWP3RKBplUl|Q0@Lh+rgl;l3?0X=w*=OkkZE>f003$ z7u}FQ|JhNb{3BD#zCpl>e7wQ=g-_{*h>*~$k8B8CVjcdF_Q+wrM3@s&6^Z+C32*jA z%A(Vpb3*LlrB0DIYoMpwisX4YU<~AfBxNiSgFLVyB(2FZhwue_TuS&-#4Na!J!dMK zTFbuyk@U>OWc(Cc(em5Cv$?nxr!f~lS^RMq4!B}rtC6I^b7Y&<|Id3-tj}Q5;P%Bp%*?aV$(fEKK@N zy({^`3CZyj5LAL7*!U6fxN|y4AROX382ac9?d+@yB?>U2fH2P>%3dG99i#KPkkFqV znHah-D`K>Ev7Ik5T0$lcVK`3Y@%$mO=Wmo;!wW~ zvCU?-+`^V*wbBj)wR@{oxEF+5K={yjdU}utYFU^L8kQ!b>1gqL(lp71&m`X|j(^s8 z0GmHDJK~koLyYVjOg$ww9r0NeN`NYh3ioJXIK{RbxR3>lUyMcIB=o0czYAS#1q&Qt zLB1tqez>neapAJ)h20#;6*=$|p#t^i%}rotXgpQajdKtdh{;WVMt`AM6LW@YzJ9 zrr)zd7j`zy?L?XZ5PP|rr@3I|;WkP;$)eh(yw0AhQ`&lpjkmjhUcpBtW z7<>)&0lSjXZzm+A-_)Ws9{*e8M>vl;9AZd>&^!F@fP8-pCNe$gHJo58#1Yli4}^qU zksnXTJU+t6zp*-;@;s#gB$PTxEsHU(%E-t@Lz1S|MISL9r!6UFfI`AZv*pk=ak;aM=%M9DB;PT|k2HG7^w9kP^nPiGM@8ax zZ)l&-T2JI06-7mP5>Y(H-4PllL6ai$mM`{Z5nUSO^?^JiDW@DTzmzi?dgo$~nc z#zsQ>&L`C*_|bDO@9s~Ccm*Zua zUC(iQ-?qIJ1CJ6mBKKgEI~T(b*>U&7m~-7m3qTta&UUdTKygJ(TSict`Q zyL)CZOf7a`vK2$=Ul`d6b^qbYq#+Aoe2QzieLEjh>ZUHt&^`NY195WP9@01V@)b*M z0%@Z_yg10B;N;y{jaFOmmg6hnQ{w|#VE}#Qz(><@{AP}Q)4yB%1jZ23fx` zeh%muBiO$}#c})!3r)pozBhOzW*51=J8Lyy9jJH?UjDL?yP)z*jNDsYyAc7k`m;pM26Z^@CX@ID%*qlCq~1*o6!;PdkN23#Jsz z2!v3qnKDCi6&t5d((bSPAsCZ>pH+h0wB`P-0iegu3fNJM`4dB8sbK1)-1HgNlA#v( zSe`>C9QD&LHD_HCql5XRWyN`FO_He&U1DTkOP^Msaj7}O`*SY&x#==m3?D{oG@|83 z%7k-(QdE;=_}24P$E4qJ>}zo)oPn*-4+&WC*EmjPWUD3$v}qRQnFcFYZT_I$%vXCP z)TG&QCA29S%CuT#FmL(-M=P_Fo;C2VP10CjlU+#xU_FMbiqvuC_iP zeb}V?hH>);D#p;9DIt9r*B~|QiP0Lt15TJ2#TwWuaq)XQ6dPZ0dWfG9J@AAQf^19@nC((A2JFM!td>3|9WG_CQw(|o-Mu14mK3Y23>v7J%9z*S%Zf_S<*3=nSLa#$Tkm(=i$bdm z>?ZseQ&xbq_~mp^xNdHp#Urs`bQ4)LyK<3-^avV{`qaUw$_~8+6St1am=S>ezXOvW zlb#OJL4WGk4YjiylejvgTvEIUdqAey`Hc)%77NxRJ8p~LXoNfe>Zh2HCQh)k71=5F zrHjP!He1+QXu~FrsYC|;cN$bRV_GGH{)0iyI!&8Kz>muk)SWgpf`;pH16!9SA!?y@ zeS3rw?z_)_fcs8tsgamDxbN5aaiae|>W=+)uM7}}|Hf`y1Z`m7N}yxLjYtUcyhC^a zANDlu&`}#kW(mY0gDgiym=<+41}?#I(HT;D79qWF>d{Sm#r3pT(~i|tH~Ba6e|+-~ zjFJd?<_xBY&|*DJGcoYZvP2hIq$NW1&2Gxu@K^uO@YZ0aJlUirCEzM?_U}kY+=bqT zcpm6vbk`iuajlR1@0Jm03(tdHGA@WNNsl>d4;d#Si=jP#h@Zg~X6QXfg<6A*{3_D#4rClNQcu_w^aN(1 zIR3?#+r6{UGc+@j+Wm=DoPUe7k@+8)fD6KOR8-UHt9~x|PIdhA#t+jZ#9M8h*WP0q zdi^{UK_iGO=HS=QLle8_pDhaQyYRP)7-8Mea_+BkF^^@D9__QJ*jLsr97i=*$&K_F%d;PfY=cMU51G$>`3j+=Ak(gAcxn?L&+F3BXf9f zJ0cQ4s+;&5#DVT^9;)`k&?0U^ZUDv>jxLX-NnER^z7rdB1I0~(JeXj{dmH1^cjLV= zEwM4scMwa=FTEXMB{40pz93Vz8^tz!HYJ`$C(fLn;MEsmh8x?&cp9v?9H+W>JT!^|Y=7WyNyoh(EM z*pt)ShV~viz2kQ`*NwjT9Y~1u^V~9iC(;Vlh$eT2?>I6Qdq`jfU4stCHf?KvfcuR3 zl!bNUg!`lL7;s5bOd{NUcxLW-GS4r;1H}0SwV!RVH!U19_dLI`eoQ*um%=s0QoHwh z!+s*ed||(v>sw8yzICkZL*HPB&c9mUI_9IE+t9ZTF_Q?C?X7KlIW@f%R-a?GFI@|zDXQl_ zGl)?(>>XD7se?TIC3mWCzrQN#TgN|ehmL3~{?+;xmllGzBw%}E@)4lKjSN%%bivHO zgBdx$<^s`2oequXZpK#&+SL_S|G(+a3>Ezu!f%)Y(VyvKh%ucGjfuG1Jp~hDdnFpEz8~vFb-tpBPSN~U!FLBOr%kic5 z%NU~5a5RT#h$R&AhCm;@54Z$l7>hB(Zk$45o#Jv9OkB6)!`a2)kJ=v#wFt~3=rL3= zG@p#ja^t3#l0@$)W4sQa=<+1Ts)D3vo1R6up}@3C^Mqz-(65~3D?-YQ2cF2~$FR4QY(E_3x&4(CPs>t?UY);+5^H4sGl ze?yz5QO3RPi29^ZM)(<1s1u73crpwSO}zv$AY=Jg2IE)hQJx9dD@9@%M!t$$M;Xg6 zrYGx$1|U8nRzFtxn5ur+`Q`=ZRVfI!`Jpgd>3R4BcD4$aYif&x6w1z5X$*ddqNszh zESmXyM0ON$BPGlIjGH9s6V(hZqDxx6uuu_0qG}~kXoi#BQp;`wd=xfL9>B7wU>h<| zEOVoUuR@r{Ismt%BT7^M199P0prn)ARD2!wO2U}WDR z0ZbuAH!>;=i;{#W5L;l_^MsKEt^}_9qLCG%ShXJ_N*0zlJIFfL z50NX(^s9jvaDn)n+%bv8SfG|-4yaa;Wzis{LZEt{Vl0q#hbzP|HX087J(hWl84mVU zfGVultXMtOC^I|x&BY_h^73XoTdodEN)0gbwZIT`vYVX;uyjFQ8(oXU_gga`Rbb1& zDRy&9T3x8(^nfu8OC4riwI2pF%%hz1Bs+IJUtL+KYY;|yw}yl?At;>_h)g?+Lp%p* zq5SJpnCre}+|@~`cPJfi2AZpBCwKq@s_OIb?$ap>Hbk(9OAHE!%DUyRK6m&?zCo%Nr$nC{t+4jcB+?zuHT+k zRk^5V?_zzx{R2)i>_C5H($4a)4`bEsPZrNP@c2}HK>pw8TGo|Xwe0ok?b?(rubs0- zpvA7Vs=2{6xjW@^wF5h*cZhIE{sv%T=Yn7MNcSltH&;eVB9=KbDMeleRbKs{(b;_DW+Tof{iomm$doX$nQ9f5#4cu^*gtT=6FmPIfqo|JFtD&JEOeh}q9 zMFuBZU|?T6@)d)1XkET8)X${E4#t2P_bquRt+H~_H4Hc)&y0GK6J;qX(y-^;AAOVV zl|TF=wX)2==pAj!GA=Is{e=6L#wK)T@6t1^AAo;zkR2S08ioleIG=zU2+?c<>B%a` zL>4DZO%_qR znh?-b(7H*UInxZmNGkGbTY>O$ZUM}@F1HT$J=;3IQZp8M9QC~LhkX8(eD>u?g?9ej zLHQUkh5jOIQEFGAAx%IAbJxf-&rU+IUb_Ha!T;&psVFW~k!^)ii)VmQby(!B*JiC3 zZ5G(k(`JQN5=EOiGZp+y|BJUz`k6D%k&KV%aF#?3zf@=6@>Qi${CvP)u?s* z3v$Zjna3Y?mS0@463blB9s)|w7+IhjUx%7vM%5+7j<4*WY-V3UO&~NUTP5gku?@2})|lpy#(H ztgBo&s0XLrugEh)3>HyCW#<+2siNfn=vGnNBL}^}MWPt+^7KO5@hllsjURe7W$RLT zX8LdpR|AGCIO9SX#K^khVJ@ncg=urOvFZV*!!c^g{m;;jNie@;tQzM^>~kpyE?9}C zRW2OZJunWq7lXbCq5NVE7BJr?eSo+WcExV$?1QwR&OTViiOM&ui}j8BTW!!EVc`54 z7JXaq`M&vs@4cqRu(!kZx9?$XG%v`|f7tE`_FMEy(BovQ%pc(LA#LiKX=!vq(2VVK ztCn%69W(&TK$%b<(CG%XzKHfdz?EN&Vi_II88D~&KjgWe=t7G{V$V?-bCkW*;d7uz zn=k6K7hZ%q9PZyxA7DN~uiW%~s=JIX+6Hx)A2)P&LJ-v9wlw!}|H?&rRC*Yd9`t8A157-NJ592m+tbvQ9pUTspnbe;EXd zXaeNx!Kj?4pnn1hqgFyfIksGXD%8MkFtVG?>|04grbbPJf~N z2p$}vY^9NX3&3&Bg@z@^3kSRfCmYvIJI% zeUDbGhyK?^&$kzy>>K#1-DzEqvm^g>JoHZ^TY;IPI%uejHvO*6w5p9`-|}K!mdZkx zMo(gtRMC(}cI+IoJ&GynFV4?!LFj=YMbaHZc9FfbJLKd{%Ho}JZCQ!%*A^}?YFe2r zf`CJgX8o7@{}EV?`?0;py2ofeXtvf_to3$l183dMS(`YkhqHdjSsOX)KF)f;s6S{C zE*fOi3%M~F7quzoObU6L1~UE%+XLUL7ZqSWB&D$J%3%FSvry*L?=eIIUiZEW`aQhn z`}lr1pD;7i>_<&pJitUQU9Hvc5%l|WW-B$jt}bx5u26?Nn(*Btd^2Nr7p!}W2Q&NSp>pPnj)IJl#RENidys)QdcEGR?m!nGX|So1sTX&*Rfqrdn%D+Z%bxi z9@!pZ{@~EeS!U~A$IcF5F1X~NHd_7T7&LXP(r(@BdAq}|-ydp;lrt~Maj!vhGM^CiNzq+cgUml1*9nT_{6-J4mTb_#XlUB)57f(+IX5 z6v}^Xw;rphvQ>NsnYZhYP4W}a6G))()O(Xo@*`gv<}b**a>aLML5J_CB(xv4_fMQd zdvZI>`rUER_fgb_*;(uE!Bq{0qjdUsAuJfDUk(e|4Z^t>PB!kVJu1a*Gaq-1r2z)6 zHDH|uDa}YZ0V%N~pNK>Qb~&3u?O74A*k)keZL~H_t=qI+9{H(_PV93wnQboAh4L@4GOQ@=&1He~!!(4IbThhQ^B2ZO|RQ z^M94@a}SO9Ss5APY4-1=wNohi;Bn4dJ!tJA6?e<*{$o{UFyDtc{Si zDW86;uEe;pSR2)&p?9VasvIbva`;>8oOI7XpTfb&X$?|h&}h=zO=ZLoqQA5q7p(g( z==W3)R@JN@Tp8l8Ei3ECU<0RDNgbgDKyoULA(5A7%q8RR#>vH{npC=JfFsi%ESRLU6@3eZ1Kp-S z))d9G(-f!ote07Wq+AfKA3c1*+!ZS>>UYwPA8DuFvy7`&wA2P7qwPhKjbsY(oTD!w zPe1N)k^~C#DV2QE`2I6;&B zaJQ5ed2ZJBPq2G;!5eG<2XE#YZihGV^l&*)kK~i(CK9dnegxc#8jWtS z9tmH;H0Y0@-TT(ij&=re$<0|}XB-+F%TsFvBz zk%ks4*UO3rn%=wWSRkP^IWhxrSoRu+NX$d1!gZlZMRiHJ1*jl>LYnkFDQvC#Q-x;f z)e|PiItGP-h7~DwYo@KqH9jRVKSdez`|@I$0a9Yhrw2IoyEPy5+pwx+-MyV^3nD{? zdoR0}lMNZekz?2qONlt{#4(D*j{7L?sB}69%Qqo(VM&BRy9AamjayFRfKNmabP>)9 z4JS5iMn%rwcIf)~qqi4L12xX&lnVcc&enz{S%M9HwY{+Tx{6{XNSVLBH4b zCgBHxw`Z0@ggon|=D|{KFs&ao)V}EwfZ=e5rsElA83)0_aI?8catyR589Nfox#?t} zX%|N*h;L@L&yZppMg(+DiKufxPI`KuI>(&>or9Ctu=>8X*COpBByI4uZ6DF2?Xrj< zhVHB7sdNKczScN5*a5ppn(hxYb8-$tOpUf1IEv#iRYs)0Emf+Pp3?6*tlx`1R)@YP zbHA$?PFOIUSv%x{e(#UF?s-pHEw$zNWJQV&HtG*V#cERw)_q3n0nZ4jndsdGmwM{m zp$}*NGt{ehO}C?WbCSS=KZ$zR>D9ZP{POADpG3V2zsG^zzp*0i*1Ot`tjUw$Ft90s*LhrgH*XrG23+DL5piF{3hu)P#5RlP!Kgotnn&VFp$st-735eE} zYaOE2wLdORW0p&YE20?>wC-2db^Us1T@!{x?=cbn5E&DG%b|AxsrA35ch#^KlbPiV z2AY~N2p5+#lbOW0PQ~kv?^e7fmmjo&c5QV(II}=Ps3A&s@cMqLcWa-LKog2;a2Is0 zAe@1^0^7Vg_vxAf+n>*R`3Kc?N;pGwuELw-h3|>Z4UhBbT(Fqv+{J!P=}@?kYLvU+ z>_J7<8?<8-b)i4@A`yL#vVrxcf?9u}##TtmF5h?-`np;PeSaz{zE-$|I(BV;;pD-7 zE%yRJ4)v0vL;MBd(hD`9zTv23*9JlP>u=K$D^QiKsUq*7Z$(Xu;&c88GjbH!G8OF( zPIPV7bU^pRyMb+S>URxIBU36B+?~B`(}utW! z*#Ty38>RU`CZ5}c1F=UNn;MMrR4LkAGDWlw3O_wSiTVq6=-j_ooX7)B=A)AMenu&k zKEWvab>^#WSPx9_!xSQ~2-939vJHFJJ8i(WE*k)opPpv!(*}f7xI6J08zAZcB)&@< zFr9`HSo6C1mNsCzv}vG6=@*URPxwMifJp&i_N@0acuhcTSm)4Z&dV_F`w;`6BZ;w9 z>|0q+1F#SVfLtCvLkbfRE%l72I_+PVO6#(JU4CcIxpra$de}dZF4_R-zq_%2-B#ch z_Kz5V$D}55z8QU5I#^X!Hdwo+tRFmX?Wtr{dR{&;M8uR);hDl`A3;!oq=RaN`h_L7<*v*?%uutM67 zs8|RttPryj(2?CXh$+aBWzPxFxZ^V~g<|gA>HB-9vUc#bZ{I)s82Z3xgD{tc!_w7Z zUf*A|L7j8&o7f=VX3SI~elve%6zASIPTuYNXUU)tV1t&BhI(yK-U4xOPLXjCMw!{` z|Bs6F3S<12*BYS(Bp=ZtOWPp3!c!Ei5c1(OE|U%C9+$R+2S!Dt(V`Xd!?vLfd%zRJ z&3yk>Pdm0nK>bfrVP`u=9{Z~}a@-oAep=0&gFd|uSGQPm0F%rM*zZ{lfO<|dyE zLr83pAF)9&iNppm(IhyO3iUy}rG8u9$Eu|zuucN!u%|JrMe1u;WyXS^H~ z%}@)Z_gXXL{s`e8;`$R?fm= zvuwD5EpZ2T+Y-dsQP#d|Y{`zEw!{Hj66Uid+qUmwvUW)^!hObMTcGUM?|zejnHbor&{~enGrLbnrZQ7LIOJP%9Bm59;%CnHnK5fb@X{SwDMiRrOWJ!D4lp#e5 zZicjF2!`(rI$BDm6}~xDmx{XHri3s1-?b?|HNRX2E$<-lOZ01>_9brQ18ZwL?aL!x z`GtLnkoIj~b|SEWf=&V6g_WgQbfX4&@9z-pn!sJ3fSAu~hWC+gH<$2dU`K z$=_(oVWMU&^M15Gd~dDieSm;n`VB$LWs(5q#czLy_Kd}cTin?VFyzsh2@dsNcl@>P6IdQ3|8gN9bBnlv^DGddHku` z9u70SR&r}rGwCU)PZHT!Lr5kBXO8}_!a0Mpwrf<=YW=$1Y@`q0N784N&`bp#s;=7~ zka;4hVFGnn--y0<>YJcspWd#+Z9YgfPnk96MZ11?@ekNp!~B)%G~lL>5S%U))c9UY zoGQnsXuA`!yvvWIh1v_FVzkvlXDr<)#?niCu{@)`j?*_Z9Hjw8w70D#0y-`#nmN)P zNH-m)N(7oYM&Ttz#fdR@8>$39FWYG$W`C6D+;s{GCnlE(>(72_VS-R%eW#&^y~puN_3B_D!$JOD|z0S(k7k zrMMtK#`PW0iw@`}IcnJL(u*L!ouUfrWSZUnojvTBNqQKalRn8aP2{5z-$j-)j}f1_ znhU-1$ePeag~J}y?x?lyF5^nVWT_+y^e4J1Od6e%#-%FIzhHfj{(Xq~HAPbTMFe>) z1k1~p6gL$=F0L+&ruh5*Zr3+K2H*3C6k1D}@P`T9E0r^taV^zteqCol*lVHGx{f%I zph;X08B4}+=N#Yb8+1ijb7H_<@3_F)588q=BghA4r9a}62?6qY<&kv6o`=P1-$84P zJ=T7zx?|6X!y??^>t`@0?@2+7uiiMhFYOX#SqPvgh%~G!Tu1s?WF@Lcl)RJfZi>Tu z$S-k~!NgAaH6E3ghJo0~(4~dL3?l0z!}L+IRDuc^YA*q>pD{AbJGQ!o!PqUoBsC!R z#F$kH;O>lE=dzZM*11ZH{=jf4QFaIH`i}sS?9}gDI&Ef|)4I>I^e4(|7g|RUpGAnG z%pZ3M*1tldUvLpUk@e0!m@Qm*tHM(L*yVph{g|sTPt~CyHK1di){mXm<`th|4e!v? zRvk>rq_d?8r}Z$rpsF%JsZ%A1>0{QEBywXyuonvv^yuT{eGD~5iNB^WDtcEHAlI`g z(=ck%OuX{^5?Pd!Lh#WM54>P%QXYAmLQPuZ37`a5F3FaRG{a`CA!&^GsG5~d(u}1T z+!G?Wc=A3HA9Bdshbc!YKL56A(5#Zgdj#yO66-aMM?VR!XGz+J@Zov#`XLI4;DtH& zIXAtuVp@Rqq~_y5Ckabnzb%$c$5Tr;WbPU$y!Da^an$)Z966N|HofGU7Jy2q6O&F1 z7pf@Nwt%YF1B7bwS{;foOKvp5fK*khwd#9a|Fy8i^=#YOQ~TRm-dw1;8~_O5+)#kp zQJy49t*j~?RP`r~y^1Q>7Eq|A9lxOL)h`vGoM3>S3j43tx~^`ABRv{0c>n-(JU|VN z$OBjsMGc)Z$3f2C41F#KHdJs^E_XofI%<1}eEVXWiJ~-*sY+T^g8q=j`myU|-C=99 zmq4Msz%@;$zK3A9)aw5#sHl=PFP7vyCu}6-AGRKH_)+RHCM*p{L%!7U2&Yr(=ZM)W za+&}b2IdI*Ju1Q-$Q0qyzS0oPi9;#}scQ9ywXc^cMa-%$(+0bC*!n3VP1ukD;euT| ztp60DrlxchmHEx*#Rr{lb%6DlCqu$cDpgIFq6e9zlqwhDq*~y{>G!**%dK(WJI>)A`` znDFhh@4pIu7If4VsPHt6BZ+d$DGGf#oNch-HFb)W?xA7r^FVQpid#nbLQ(2h2NGVrbY*K|4Fzb?%Ixkrb;T@B?z}mj&zITI&Z;!2UVen!i%kb-#ylauRC= z7nCSgVkDrJ)6+eJDKnHRSyr%Ht7)8y6=TcB9(pyaPrVAYT#eW=qoeM_fEfl?9I;%K zYDTGKt-eovdH8Clz4z*N3lf`ry1knWUwr%4G}uKN=3KAauO->1FOB-WX8i|g${8Uz zF}0z>y9g?hYZN1K-o+RajH<(g`KUB!-_^;=KIlbi;-B0Fy{R-P&YRGvMie;|Sb4JW-{ysO;UYMVel5~CpK_txq^uzj}^-`C5Wm}O#^!X7Z{AK}v;&}?E1 z`aRg1WVK93!!d)pA%5dyrHRFGb)^ z?=c2T6q|VP*Z<$fCKhm_ ztP7hs{5cuCasp2L_E+e9JG&0x#G3sS7r``HHp*?M$XoWaudpLsU#8&Lby(^qIHBy3 zuW$rHzY3d_*A+$Bc>!)5d)S*yj$|As<#?f1NHNq0Y<{~ya7o;c_rq>sE<(JAIas{& zHbP_jkd%+Y0n8R>@#7+8nL)BzRuI^AwhzcpnkXsi;d!b?H;ceKF2<*6biF1T2Wa~|bi17Uee)>p}yUjcmi;U3V-09`Hx zZkSQTG{kOm5o@^%cNrMWKHOz9yWWfgeQX8X+-q=`?KqGL+-1%WXJW8_8Iv)d04@vS z$udPGIa_A#b+!x?VS8|$?`)6|?x!SYn|@7zmoui2?aV-4j>_!>UUodv3wSwGJDbA} zVcy*dyiDdDH^5z<_0^4Vmy@o=T@IfLd6EeHJGQ}u#a`Uy)+u;N-xPN_vm1BW(;Ii$ zlyIlG%l89!xwJR#@+5-0j2)iW;x6ad?*w}`?{f+gcNu$OPb zgPizY*vnmz#lVNKlOx}BZ=9%75ow^S-M7GrD)`r7FW;mYt;6mDd)eEN+r*6e7ho^X z!Z7T@UdB)qC6eIE0efw5Z|vpUz=*gb`pFi-TVt?vVJ|!WcoXd9Oy+Nx7+VNbWa&+? zmnY-s#Vm^#dzlPBNbEJ(%K-J z;4iz4fVV2+?N?3La>*eEoRmYa)7;TCdqqXFXxavUhL&3 zyiBOF%_bkZv6r*S*HgE^ULMoZ{BR37U@c-VKT5LLyRer>wlpV;mD+wuejwP(F)htw zyssvZSN|^TSBsxRN0RcR3J8HuXbPIF<|a zWn404>Vdw@U{WN)FFTT;Pp^evUfnnR@@xvYII(rnpFm-CgD+=$!I$^g|NG#}n5Y^5 zHQ3AU9@xunoMWdBkW~20FklNp%Z)A-G#jjVDw(t%Wfbn z_l>^5P@W3N#z2Ksf_%NTq;u$PUGNlyo{1QG}6%i-6fFJpZMms-Jab%QS- z@qsV9ec;O|unT;dDV4!?`M{Smajx)Hnb)EMe3|JRe7R3!=L27U{f=;T$*DsAj(m9d z52DN8WdpDE`^3GCKJ4YmQW1UGw4JyJ6M+)k8+&K(LoHzEgS@gRjIyUxORH z4$+n#PAI{R#98AK5qsH7{tf8qy!!=%M8sZRLTIsqmK$I%--NZ{jxNmK>*%{7uCeuiNDNUhre8!bu;|sS*WNc8Ob3aG z?#DavK*=>g;#la3KYX+KXgn4)`8%JF0)P2tb67H_#k+vI@t6C=E4*$#`XmMa(TYoS z2)=e7c!f8a$mRT!0D|5bUf~_hgYE!-8I34GWC5UyuX?exEtob81nZqkfa zV{iQBuK671)z|2>ZrsH?Y{!2KfB7bJ(eSvtz+d*#egl2i8*B0Q=AwP#FPHX(zuc$7 z^Wrb(MBO?5vN+lMH{vfp>cd~2#+RME27h^*7k`<=@V53sU#`F&BSE-{_Gs0L=*tx* zwhuenTjsj)mv2WmcHu8q+%Eod#WncLnc`dw_{$YKFaGkFlW?Iir?Rk>*Z@uNmn(eu z%ka)B=XK#PSE&7L;oh`x&MI$!zf2Ua2iLCc?F)bTCLD9iJN0ef_{+Dtcg?GBeHQyR zqJPYDw-ftw{1*KO%`>t0y=w$$xl`xdPV5iZuz6h>yauOt{PQOf8#eoTThm)!?pjA( zG$r0D=me~LxVvJTp>0Kh|hfiQ z=Jw+v{&Fa(v=98{3XZKXvfBv$az!`(a>X6sFT;_kAo$Df>+zQ>9M|A4lUw}&tY>5^ zy6~5YvxBTX@t1$-1AjS_;4dStUfBzOncNoGiNEYdjHwfUIrHC!zbqgiFXAt|PhoYI z;4dG#C1`NV@mqlglTzI${fk3P?-7t*Si)=Ymoq!@mvi&)0DqYjnsdyb>}9FyiId!g zzx)KY$lL|~GAXz9uvqTOp5+q!Wk)ak<*~#`KYRl$>n>il9`x}NNV4T$pSl^A^~<-# z%hvsbmwDIll6Ct4m>h|=|mzwGwmFIV)5zx;y)!cF!l5nOGN|GPx~kLbi-egTlVo%qYoN$RQN&D3$< z3faKpWaJ<3$0i-eeyH2UUnZ60Y$cUAf_vgGW09Z-{_;V|-Qh0_t#66+OS+3jxnBI` zk&f*W5!$o|{&I+jZtCrw@Ha`{{vfg341rm8yc^#1ZBvAV!rF!pg1P-Oz?WVR!R#+W zFp~oSK9osPTOAOX*ZF5E|KNp|1gInyJAfsMsAL}q%oYoG69i`2vIs1?p>zwuuoO%8 z6y*HbKQroSyAOYP^)2w1eGGWrKl5y#_{;k~y9NF-DImPWKl5@A{AH;BDsz1RfnX*m zte?^rw#tzPdGbOqC-#6~uIPqf?tv5R#a|{xHy+4YiT2D!d+rQ>+1oITyPV}@++|+A zCH`{pXE(uL7HRp&UF4scH?zl>gW*BP-4_1xJ9mt~OzH#{YPiimGh`|hcqjgH1!3gf z;xBvoLe7}J=$~0L8O7cW{<60ea%aGNqGvNh(oUhEzgRqd<1df;>?Zij-m+Tr{WEu^ zSWrqX#>CC=mx*-w@RwHuG5FT_%Me9vY?&PRuMox4z_uk2%-&&%=KBWD{sMQNf99Go zJ@A(+Pdy$*lbc!Va{^S;ty5PUe|q=AhGTAu*F`@mpc-4la( zIp*QlV=#L;Zj{8+b=>W#tt2SSh!gIQ?(m49aAH5kmlg+jX#2J>VrE}~B= z(grP20D&16hcNRqx)X%i+d_Ayf9BF#fiR;pyd7~34zpOmez(~_^M!64<|mFd&pzfg zIRuA!!7*5!>u{Lix!w*AGpWEm3H03_4zrKrX`rW19A?|GJHTPCxD^gF(Um~}WA-Y` zUQo<(5sI1d7v-r-UIAJ?4)Sz6Sj@F@95ckfYp|FT`@mxEp@4zJ>}5etf`4YZ4~RLD zT-?wbhk5KVeHcO=y>OUMcHuCSV(JbQw2t)GT>hsiq!Wj^^4lRs9~?PT-i^adQa64O zZty2K%>8gSk*&lVn94lfCL#R~-N3wdkpc#DlSNG+ogFy*cg;AV^gL$2R&80X6 zXF7S&@i#AEbEyc}>=^t{kM5s1L&duDeUQzL+%|{92iZ)G=BYHvj6e%d+rA*Q9Fv?0 z{E2;!J}3>Ru98DfsA6<7Z3j^FXDf;V>{CqkA%o2P7(1U}@9(cx*r!Y^TIl45+WCkg z#D~Y)`6#=qAYgid@WFID&)NC#eEt_fye^0jv$c>44zpuUv12c=zo>N;9F&E;i^~*$ zZkw!J9U{StjdaMnwxcB3f(tI=DlX78NnS|HaTctA({WQ7fgL?uW;;X@5UgmPN{|?N z$qd%EnYWZvI}zi6edBEkgS#$4v?r8 z9cIH$vEdikp@vNz0b6uBLAQimGQ}{(Kiu-;X{AieTl{E*1ae^%Pm+me!)7GUos!Qp zHXEtGDEU2liKJ-CN!gOXBL1Ls37hj%M;HI8XI?#8?QdI7Qu5BDMT{jPsOger|D=^G zj#}mf6{k5P{~z|=J+7%M>l;5gNlrpIT5hID=rjpJz(NOt7oh4upaHzhV60qx#u-B8 zqHpb}^*%aHqK1I9)oA4+wn;1sRGuomh*&y6HAM$1(0ZxWR-IyP-?opn+FGmT_uVJl zyz5+k&+~rX*FWUsoPAk)?X}lhd+oiyo3a*+wnzhiF0AoH%GD&L7TfuxR-q$A`Aw~H z*3tH3_^^h2SaAWTcX1BSE;jyw{06|Q$wryx#GB?MIP#QbQi9H1oGNDhsNwNclHEEo zJ{~tn&573)$Z_G5a%4ihMy{EY5Gt(}$uxlPPL+<#iw!XX4oyt4G!Yu~%}hEaF;v5{ z*dN18pgfaKZS?Mb->)KK!G6DrQVU(}fiuH%S_|Xmek;1hT82zIY1nx&d#}l0xO8xD zw#Bs5cB$4Ji#FTED_3^D(R_KRq50DJotJ>&XIR^8+ZokpF`SRWSIXjTtCrUc zo%G$&`nN3}B`FNHe|RQY4_qxBD@=V7OYfA$L)vy-dlg6+xWPWHN?!FkZ&Lt+i@NLg z`>EgeW7#s#WBhfti=Bpx2Wt(r&7GZ>))_8!TAFR^qADzg=Duny@*>Yk(UbO$t?xKB z!h57DhAw%U)JEz9UbBkSN4EdO(9-uweH}~$%kd+Dx6Bx0TuH0-(wNfOr&ANMrYaR- zCq4?47_S`x+iFVNE4qS?c1Y@NUjvLfHXwFntRyxrrnG@yxwgQU^`)foRJ47zEcUT^ z+vUMe@nT9@W;Xvw4>k_P(uxm`q$$0^raEyDnjcHYOjY{0KTJh2W@3G1AOZDG8ZVTk4Kw}bG!r8mp{k31yifc#0#M*NxqgCP4t?<3jBJesb2W?gF@M`RlBdRL9 zqkcGIRru;J9$6Rdl|4fxh z@u=n_oloLmYHJYH9mI1eeCidx#%H)94pN@eStd)Lqkk9y9U$SF^bf~)%Y&Ldtt`L1 zE4F29jfC3@#tLFvQoAzsn}ocAE>=7vZ+4eX?`_h1;e2vgOQ@a|$jh7Mk=f-fYCUe; z^3FWXT3O!=^`dRLjBfwctkW#N;B?5C-=5X_v*M!fLqeifTwsTX8N=q6e;)|eNwEx( zc{=1tDJz}*eaQ5YD=xDhMaH7}fl4dB`B1D+*!LFWS^shD@N#4M{0I-c#tCnhCa+WU ztWR;0Y-1|E$it?=3Bdc)nWtA=jQu{)~EC>T4|%? z(O%LYqC@rDeCEmJqdL{z1$sr^kvL`cC`Agc!e*7pPya?S>j>E0W;$jC%OfL489%B; zSv3iJrm|{AOo^Tz*2Wx@qDRrMMh{YtOgRM?$3;dd*5+ZGm;R|E>8q|)Cp1j$AU*s( z$?f!m{?M~ZslU(=pBk+12P z`8zfg7|%*+<|UBOvj1>b1Sjn3Hka{}zWQX!6eHm^w2nSyJ}lZ1@}(`|*i>UDd1`4m z+$BF^RFc*z9zF7{q){oqAWt75Y}s|VD-i7v)GLH%^fIMB(AY*YoKeV5(j7w``bX;Z z0ml90l}Yi4RS|#>+X84t%ZsWz+%Yt=I}(tB9>#Y_f=vOxWAdN{M|A4E71WWk?`J66 z=wm+8a@JmUc-L!(QT_##|0lvw6mvll*fI3{=W^o?lDS})L+>{ysa`)!qaWTdwK_rR znc5<|6~jzg3~vnXjpW0o#%Js+4(~d8nCn08 z6%rzqv4s14@K-sC;i^rvGmdImaJcJ}!w!XCy<*s0+PH>%Z<%|z>*K?q2DA`8Xf%+w zM1HiNxSAd^t{^`%3AsoxF__S5Tt?o_l^BoQ0k5=Ys%(0ORc}&w zwmfyXOW#{*e5k?LG&qxS4*3NZYo|i15~}T~hj&dsJWgoLxglK^`L$^x1-#D)fu{yw zYZ=l@%t9VTB)4VU;jXQRjZ;Y)Lb>y>3qB_z9=>4-u~RX0&&2S^rqvW`6W>Si^5M== zz+5i#vC!q~l?o}woY8ak5gnBsCg0Rb#q3H+nDcbz)Y%ERB`aor`l`s55r?~8L<__X z>y0s_4o=cuAWtdt#|w_sKJI*vYBL^N-#f}K)ZmLTl6(h~e$C~;S6PrTj64&DAtg)> zI2KCYXcA$J#%}y0`QqjwDUIu5CHa0fAcVZ&x@S0fkzO%Hbk@f?idV2Jd6V}zp)6Xb zrEs_u<6+#(T55nrpXmfZy3!?4+AxflmJ1(uWgQ+*8%3m$mhV39`u1bnL^&}5e6HBy zADoZ!EZW@e@Tw=wdj%27;T~6_ zW@u>ma1u^qOTaF}Bk;-P4Z&k25#gNEyL)>&$RwpWN$?EF4 z3=h@`y0|i9zL)_0|j<8c_z(vq!9OtUoO?x&)bG-dPbE~~;znkvvK z9@=qfo1eUi-yx_IRf&0R_9lrfj+o<~OH_k>rld~P(@AC7K~}u8xiXv~`l3~VAcKUM zY$1+c!t>zaIrlsUm-iIOHh;e+NrxEu_`I^yQzWeLY}jZtyx=sRLV_#_tT3Z2Q2)!v zWm8Mde)^w2E@g&hwiI;9rpxlOT41bfh^u+C0n$)jLDCa>1VnjOwKSaR`HZq{YcA`m z1=>kcWn(yF%WK}2{!pM3Zwp##m9=@ZTg(C~MC(__SXvwh18Xg1T}3T6rJ)v=`3)&( z*(UXDuy-(oYymtCOV>94Ax#298|QoQdFVl+Q^WYx_V~Bt!9#dQmeU3L2D@h-JA~a) zCz`F#-A7q)GiZ&yXnx6_CcgW1@cZDtNg>KrVrgkx;<7uUSQD|>>4*rW|4(J42$%vkTFwb z-?uL-*frBb`$zD7o6itiUO@i`-;AEHSU}VkwYI~E=q<^I67YxJ>eiJ06=Q?Vujw|~f`n0_k-|65hM7M5{ zkkXOXst*7~4X2^}LyhZRmp8QF>&{wvd&Ri&QvWI2q#3~F*z^uneY&9~dyaf(p8T61 zw++`otXgeo4NA!Unrae2x5OBid4R5^brm_k8JYO29W?i_Q&$UM$;{U+z<&m*vgYkCW!4 zQce$QTp3Y3jAxFOp$dne1oFFLt&hsbkUT_%Pq_5XqNLU1Wn`E<#evBMbB znA}ZN6CYjkGKCUi_3jbcvk_G?L~n#*4k?R?^-wED?uZWKJ4IB2_s2TL$kbg5ua9xx zkLNXpPbr3eoC9BdSBaDnT?^gy$oVk|l!=cW@e4BiV|2D98UEvSHhqSFV&K!UG)prN z1DQ#b5#VR`hIlqBy-r!YI+gPCxF-mhK6?L;vn_I`gkn8j@L)A$T1i>AQLH~}(vm5J z)gfm6m3DFX-e<-I4q5Rb`)i!^kwrWBRQmEO>o8*yaP_xo9IbwlYZOhA52}9;Nd`hl zWMtC8gT=+|(dalYs!SX{B=Tf4#gAXNZv7<7w-QXO8Zgr*h}Y{j%gcwBi6?#6_qA#0 z2QjD1hgJ@s^qv-nhw;f$&Yu+B#Qz}Xg6)asNVOtXvwbtbkz;l4`4=TOEL6620?d*v zSH&`>wo_(=u9R)B;?0ja_`S!Ba;$BCUAJx_OaC}qXlnb!AYX{gV_K*%h2rQ(%ch3X zmZ^1g7A#~~)a(S~!jCWzGox0Vs}07YGEIf859QZ*Kcm2ytOWN}G2>R2^gdIvd$%N>mk#LcK>Wc8I8|OD@*Gh$lVB%oUBJ(fhJI zz~P6$rSNSBI@@ZrT!v^ZC-?Ed)c2%B3}5OQh(3z zPh={VEiLmzbsUsA8~B*YK~o2I1^;iC=kdOF(cA$@}#IV@dmyN>QXToPz7WEW32BU6MZj33G?Y0cEL9_-U; z8&)y<@itr4?5S+vX?axr-*|F`;;iXMhk~y94+=&N6Xiu8k%{tW+7~J1LBB2ZWga^O zX9_9LLWh`YSid_!n0F{f>q#}h{_Om^`Rk?mW54b21k*)DUF9vG?E2YmTuT^b=_+eE zw(GJz{p+hpeVO-($E0$02+HV7R&~O4*>1CqI=0KwMLil%)!NHiY$xTDTr0&(#;luE zBd=|?ITW9G?409WlUO$-cs{Xh1%mC{(tvo?#Mbe_tCN89ZQHe@!gGi1Wd-iHsIapB zWgcXz+h8yC^xZacXnp&2Sb(bIz%y&x)h=N}-8qZ8s@h#`yADn#f=VGmlV9s^3uy)) zI_M@ozHX%8AdHuQ1!%~Kj2fS61@1S|Q85Xajq$Cvt=a`tnO|uz4Zzv7tmgdSOv|W{ z(8!RO(Ru!3Gd7LNlMYMq%bZ`3kSb*TQWJ4mAY--VFu7E{(*=TZyC~@u%KW3tGPQjv z;6y3Q)bwLlQ9aaa&m@E`1*DqadpI*;qV~JeV|dbVo}2WZ4zAIpe_8+L-e#A1e2^tz z!=MqM=J+Q4kgE4waAer9OwbQWWrs`sy{kusj2s>k_h?7}ZT<}bY((rRl$KlMqH|u_ zCqM%0V^B7S8AFZI3qwK^P4D}iTHw9Bfn}@3Arb;yDhAfT0ceBWG2d8%3YCcszSRoZ z-tv~7u^_3e1vAaF-9&g++k3i=pLIhD+7kcv=40)gZ6*C~{FJ;TtgIT(NyvDyB~eyA z$pVE{lUTfp4XE))wRvHRP=Tj1-}+Q`u!3A+XGsyWJ|s$$W5@OB+13r(p;TF7sl$(z zftfvTxI#zBrnAE{96{QbT~u~<5-uB;=JDo*8n}zT!s+ss?40JF$(Y^ek30yBKHSJi zZf-9~u*{ETvcwS{L>DCh=`KE{8F*#klK9$Yi%%Kt7Nwo#a!L?yFsv`9i+m<2$EyF{ ztM@E);AS&i6Uqw6fCGR1;0fA#KrV~kUOp5WT4qU~a~+dxAHsh`?tod9$)77oTcbd0 z)6$ZPS4)E_Q=4Ex+f|l5AZnmbipGnku-~%IUr}`r?NJ87Z%h%G6zB%Ml|jJY{}Sn;=A7`g$wmo~ZDR z$&V5o-N*Lsp$YDvtev&UzWbosbL>0AaK#DhxrfgNHt;bFoA-L#_R9D08+fv{7d&|; zJ(d2_Ptpm(qi;&imWY~$5I%qF8v9Pb6eg2DX+)M_QuGvh?CuLBCN@c_+I<=BL8UNF zp1tA{MaQS5tq&E+r+a0ILPaOk`K1g(9wIZ1Wv;8vD=rv1u!I;7@Vp+;2Zy|hqHH7O zgstSA)dr2Oie-(0?qa10(B>w&#VbP0**eAVx_2zx^}B9NY>dAn;#64yhe}|aOrA@Q z?@H~)k5ul5gbSFWJmbYKi`aCGrxb^BWf*_yLShn%@43Q-f|15#J728q?N`OQF8mCo zxfl4R_~ORj##3EQe2e&`&=eZ`Ez==r-^f1F64BixU_gHzjk5D3V#H+_jjcG99*8v? zPrB>c^v|{D5Qwqn0mS|HJ%qCs7zXMrc$UBP|9f({%85D zpM2DY2tL=I6zexnIc#3W7E*kTwf#zmq)XCmmvjR&*?5(_ObtjKnJUrD;ip(Fqe{+M ztfvyaEin^Qss$$+u^TTuke!6+hKtKTD#e;ID*d%XhNYY9xuEnBcD65HKaRcoHJxPR~EraMe+hsr7Rc|Xc9vh%1HLm1`P-}|ssny;o z>f)qOK^Q+49t|f01&O%!@qNGS+G&f6gDjqgbr<8yO^9I6D37<8)}>vVVKJm#!d+j8 zP*+$GIo^vqI#Pm?Lt-0z>uA~Ds_$@Z4#$YUb=lic@!Q5mQZdm;Zg<~tkTvcmuL!@Z zF1p4GCWR1X6O`ox_|&Hb9B=iM@!hVqFB^*L*S#8LFevSe7U!5Z(-O^ zKqL6l#Z|Sl%U*}7J~X~c%AGv}@xO`ersQp*bDoV22v#yTnL_2?pyy3 zZjvi)RH;P>J}7No>tEi6XJxC{VDVn>vxj>YG~;<~SE)ttnDUgxds7(#bA}g%;U0#t zRqiopq3dYFx)GIMv9#*g@7b_Yv4_E!P$Yrw@}&$WJVkiGiv-T_&WjNq?N6W^0+C^1 zdKSf1m0(ymihC9qR^!=^d!~_5bdEtmGG$3hk;IJr;Y1HY&&tr6kKH_by33y3Rd0_s z>IlzR|JWHt6S)>*oueQzGbv*mGm}4FkoKf}X<|W=C1_4YgKtJPPln~K+)j59x-NSf zikN9kAVpXY`ki{)yKzs12P=kqMHN9m?N(n_!kjJf*6j1cba}aH&a5zAk@swcGZ^s% zKT4V|xXkPD04L8qbc{V^xR`A*beQv|?@Y@rBQ038IR2U8)TOUa9*F9clXVj6 zq_^P(`LU=;uA(6p?@8^2zjIN-ti;U zT<>p1@(_90P^CXF=T~&I(u9)dC=0xgD<@edEs=L#%8xk^CYqEqsobI{dDz{h>i>2%)KjW-W%cqWfr?M_tIRb@yF8~847JQQA(?VRn+CVzex!JfLb^|sY5nF& zEQIXs1ZQfj=@K4P1Ha2I0Kfjzc!|8t3dkCnCCQ2_ux5s|_tZNO=IrTl)r7FjOv!8s z&e;-KhchjjH4HHjA=rM_wNlc=M?JYMu6big+_iF4wJ^Q*T89ws2c7$ct426mV!q%a zLx`+b#ZOms2vXoLOng$dupkH}%J$+WpCus}I|q0@Z@T76&}*!?&Z9}(#w*i zT-q5Kh4@vR#Sj^Vr9J2aK+sRJLi|roN{aCKVEh3@=`DguNe21FIHf!?3Zs}y4B13t z_<=>>NrcBwqdw6>;=Y6Hgr&A=uCLtUM(ncjsm@4?SJbS|ILmnPS${vwGz_bwls4Z& z<&gE4M^obXb&*IzzFzO7qN94(ZyRFl(6M&t6ux(}|V z2*Y8&gWq)7;C%8~N7QdRw<{lG>uvSTlxKXre0`*qsJM)GgbO~ntW;5sgTshh_L?1E zlhkk7<$L9d&`$a0-m=vD zuPTEm@@a=1$xx8ISnhPWBE;hfje3}IR+d`~3w=UjJ1Fmp?X-{WtlugzhLWy{^6N~C z_DXxIs(rMR3=iYjPD8XjmiO-JN%mClo?2ImcV&fzXN$}xMl;49A1$XO#Dk3074g8` zR9y^@4Q2fzQ#Qorq-w?soP4T|m%H5+!*d*z$Lg@~sHq&Le!U}ZdhPUa)3O-b*5(=! z_^NsR!-=)9-4iu6Om))EXz!|5UAE}vSP@6_q+NA%@Yk-nd|=di)-f|Zn|Q%rxmMDa zRTXKRzc`%H`N&j&=BsC z7Del!HY^BwDJC8&E-4bo_sHGNBz|Gcp{Tuw2%n5RlS6=!jNJ=LJ*CtOGat!O=B6vQXV3~a-|<_naMdQP1-M0ObhA0nj|VOK_f zu|1X49rtGN21pJdB+rx_*+406Yr`bi0@7Du7%z-$0P*E{u2R0?QgRi7cc@U_W$0~) z@P;a@UM5wNa)c$*ZrBb&u!8LuK3pjbi%R9qV50HpV58EAiOIXm1=UkkaY>l^4VBkLuKP5yvsP~VW>v`_&M8)0$$vcJocFp?ll(tTC)tV$ z`F4|B<*3~@GA#SmsQfrYbwB^IMor?-r#_+<1ZV^TZ zPQ2-4smh1sY1ynFOQ&g8t;^1i5XNt6PT^I)RwD6?vG8KW3?{+prT@ilXPR8;5C0ci z$n14-dNhGLDRj?hs=kCSB}#?ZkHSc-lP9aABH8Q@?PMx zMN`D2_d;tIFA!nuuUq1kzWaLku|jw6J>1)S4TS@}x8_l<_smJ8_e{3W4d^{fp&zZ) zklqUvKBi3jU6lREv%3yIi%FR<)!XY-tPAgRe^)u<#|@`mJ!q&nJah-b9Dj@mr2| z+=|crQO5v2cURx@V0`Y(4^Qp&ZhW`F)8?Qa%TR*3;XRQ~u?P5LHF^wrxXkji%ju4Vy zi{!+}hD7|@L-MoxQfY<+XQ=YTtZ5U=IX`=KbCD{&;exi!g{{Do1@TI<85j*!g+09Dg4-uI3f20}CdFo@ zz7pG{HTnvjeq)aQK3mhIU_?;zR@`pm6JV^vk=D>hH2!=~lf*O9{j_AdhRfY?2H#l;-wtU<8d>wxF2)UQ_)@NSz@Z&&IaI8dt8 zzcQ1~(Z8ltR1ljWQvy+@BvJkTr|Cg1lcK_)Zk7fKIh^jYxTG6!x?>4WcTPV}cNrp` z(B<42IC3bWvR<({_p}S=z_yBTzz63$$U&4clj4;)xZ>y; zoRb*0yc{=r>&s=D@j{b+%Uo{$Q#;n)D#9m+ z*EzY*TNdm)_50VC;2yj}hRlHfvQ%UfQN}mhO?sO-NC={OO0RR6-CK=n!cK?YftOXA z@RGJF91gu*`pM7I+MhKN0DbnXy0+m#(@TE`ndm`Z4wBhzhpUbDl6F{I$HvIss@JbK<@yw=7+tWp6O7xg5`-r& z$o0`FHZD+X>P+%pJ{=n^GldsW#_x3cEm;C5Hl~prLQSwYSWPk{X>xruij6wOrWxcC zx)jX0wrCVvW_ldi_ho#1Hh!^5+IfUI;kyZYlH#0YE^Gm+kS#>d9Q6}g_2t?m!X}dk zk1Z!`+C!U1iX4iH$0o9pQ;puWuiwC@`nJy9;8SX;Kh3P^<&)oo@hSINg5NEu69S#8 zk4NS{9@T?KS0`-_v?Pa*mhEfRueavFO%$ww~7XCL@s52Gubzho=Te8_l? zWu?w1$RO3&3Kqa0Dn%5J3=9WlW~j-eQ^9?W?U@B0_$I<-HTnw7cLISr1ua zu5f_~zbx1!QVP6oNaeeWmuwx<8SRaZjf++DDYV>y0pN(7II-I?3L@E$YYV79K4ush z1nW3Lh(^eQmsClRwH{fYfNVmZH7Dqt5k9!=C_Ql1lF%`-LX&>IZkA6*5ThQ!$!30# zAUsh$3!D5l;`nDbBr+PIz!ZMxSns&;sr>jz4(o*E5F!U;^TrHZYEX$`p!tlaPBO3p z^=GsuG0t2fM8g6F?xvx|8pZmIuV^ihdEQCh>IEv%s<^lU{!(8px#IyelQvH3ZQ~#; zG@QZcNpTfOmIk1aAEA-STqDuAxN+J*3M8vf(z+m@73M!r&z|lTczNxjKyz|vEKySH z7d-8=B!p21ac#{A5rnVNJx$t*VTEys+hyOsOh^Fv6Ms8fu*^@pm*_E)Nr+5nF3Gc6 z!{q^gNOQRi+FeM81|}D*+`%MoW&1kJX~285jO#BB&hT4_*2ob}(r`V)*pUY0t547i zf=J)w2d+u3rkM>CM{>^7KKa2S)K1)VYDusl{K=bXzKTW{@Fz}T)({%<&ynj!-%U>* zkei$hl)0dvj$7mgON#ueXje`Jg}V(2L;GpNd8S)wgWM2aa)kBq^7eEU@Il$cDYFHJ zydY;j#pUQ_B*~C;10$~zD*u4`(1ucgHlYoR2e;wwvQOHOt8(S^%f4GII1amI{|5g4 z18vC8CbEC8HlUNx*6@DXAxd!*3iufO)CIR3{0?&PIS=pM{XihTxeky)s3U|78MkiQ zHOM*&`cenkI6O!;a68z2^54YCMapcVFFC?*kfWQ}U%=0PK5CPS($)yGvq}7epFL{B zym{Hy7O%)9&EbdP7MMp0NbiubdyduuhBR-GtjF-d9!IaN-y&l~H{}iij`>`n_EGpX zxye;S`$j+v-`p!_N{j&|83O<_N)8>(wNsZv^pjG_joDu8OCP0TqnguCz3?fWI7AZ> zOQW5@iXs_=$bj*BWBT62O2sQ-{3*2j*HK}<+P7~vZkg36r>`x&;}-7-)%|0`T;v`b zH_(i63;a>iJscIlVCo&WoL5)E-?#;4=U|x!W6+>JI&RC;;LE@%`=7y6EY>^q z{o|Klb)hZ&s*r2TU78}Vm*@WP|2b_*q=*9Qm2V9hiJW}rxaC_5nILHO?k=h0y9aUZ z=eN*rLe7|8`Nlv}!ZRC?Z}&L9i+qD!gXDW8C*OCItHJU;lhJ;66@&F(WOJ*!uDfln zw!2?JwSv5Vz0GABAw&0JbD5oPS-aWhG6uW{=WejMh8yh~V?!E{e}hfH*tI^m&0XC$ zc5k-1zLYt?pN?C`E@!Xay`B?5;iBPxi_Oi>zUa)mr@aD|GrHD~h57c*aB$f`JKX+0AH3r{ z_yW$~pD>#t7bk0L&FiyCZ!9tyF z#4U5N{y7iyuQv9cy33b>qtvf|0U?PI(m&tNfo2=q&&%7|kl;*C|33b2)4$L^_ZTFg zk`*Bcr{F!P4$hs-=`LWK-gD05o(tT^_%`*;d6?rkrGF37VJA9~YW)izKt(|ro4BZi z6EmAlg)MWhaP z&n<4u(;vjp68{KoN}i3FMB#wi<@_V)8m=w9t-w1%G*Qj1#Cm9L$lJ|@QizWInZzUt zYiKk4BSJFA)qeeO)7;-p^VKt?ABtbZtO+#af8~xz6mqi7F*V1R(&iJLcW0ggo*Vv= zbLLI7k-6f{w1tfsAnXp~vzM*{qW=jeF+Q1FV-f?w6~f4?pc3_Sd@TKn=KQ0b>G@Mb22nQqXNhq3r%7y8x+ZfO*L*OD#=TuFV)y+q|@0b zE@`9b^abrq zrPTYcj}ssf_Rml!3fT?$(SACx*%_%m%*#pqJC=k3^0dF<NVR9MFXxZuHHma@ z@Mg@ws!L$nfmOTN$ij*UlfqH2*lLJw#-Uq2@IQ@32`I>D=Gd+F$4Aq)yb8{^gG-|83g*iOcKKe0b->*&eLcNEMIw?R%_xSglZd4#}%isQE5?z97Q<_%6@8E z&M`WNi7R1b(;*J5YTh!h647JR(Z@Nq)!7AJ=~9VRu_djj`K&*!4W?P!22`$s;bAYgAZpERq0=k zuIDf)8~5NeTD`suLhSgIE~`Z`ZH=<>wM~VO?>J34iyk>>`D#c}qjio1iMAE}3aCvN z2>Kc+^WdSXuj8?a6L^nUh0WJkww3hq)uJr(b!@U8telfKsJ}q_9>;3Q$k2iWd(Wi-xeF zvhw03MUN~1u9^PDvqg6(tLo9~>2azB9Fpohivb|VA!li)3X-xVZFV!DBb+0sz#&%0 zh~xH(3IbgP_=U3izj+-P`pK{A3p^JTNVXL!+^y{Z#>cj9eN}G2b;w*dcv!1&*uMZb zYTw9lo_FZW9BArsx>ZrOw0iB1h6dS^mRP6iLVo_;Veha+0^+XUi&cU17mCdQ?rlI2T~V&PUtJx4*GV>@>+`aCx_LU6lJrw zr}{T09T02sIr_{p5ZBkoxt`b4CBB+|#L_a2q6{({D**1TJb2JuRu6MMea=uU9Yfe6pD;kZsJ?hON3jK~wQ1?oW>`=l)@-Fe zh_oY!F4>Zn+Puy0vq13z$B1J4^5r;$=s4(A}lD(qEc`nQsWiKaJ(c0~owKbRBzpKdaZ!T-U!*8{s9Gac=3*lpZ`MP=Qb;Nba zB0l!ql?eii!zVKm$`UlGVNcNRk&MNcp+RrqNZx@U3%?<#5ob%UHi*f-q&0iQvhq^L zN8~)r^m0L{knC|yz@F$lzF@@#oCh`eF}gQCPqTQHeQbJ)iA-AL z7J;XwNT5rhEPf2muLz8;ebAxOIoGx4UDZitg36Jljb5HL^%6?8SzIH)`Efrjwv5m6 z(j{q4`;v6~v_&7|IAaVuto&lp7g>JXp23EXDt|G(pHwKrNf_gwNr9#yFKkr!sK{64 z&scsa;$w$KXkxe+d&uc9U+iXZ1DkQX7|0ofMW!&`3pmvy{XjTggroIs6u8B&EqRqRccKJd?`wdH4%`nm9*%WC5Gj>!n!7?*$ zCz&nMrA#C?-Y;3k6iHVKBe=cTf)_+9dCL5yEUnIePLsb1-rg!$RM+S~lCt6ue-L$x&cTbH!)n)54{Mzt6@ zuu7Z1IK^KU?U|J7kIkCjxx%N7g?9KYHJ(PbQ<$9mMHg&;I%8Ytu+3q^>TPpdZ7*?K z4Dq#FwNi(jp(nfZS9aTG9etU`PV$T<+WaUrIi>JrnlVxtF)`uQx>$VkuKGbQl%|>$P zG#>M3(QZ6Upfa%GVjk6Pdj<)dAr!MnM16^DW2lS?Qj={SQfp@++jDpTYOQvz2=hR5J#5QEA)!tBV zZ|*+ITi)Kd8!MnYT~lc7Bktc?jYWncvnZGBdqzhJCV zs8r3zLRr325Ux>T#H!}0RSU2Sj$2EprmaVLGqP%gT4;kiC+|(GR4rCcq?pG*m+A{z z3yRY-wz8l?11d&U^Kp#gW_qjK^b&GOLLCy0M$`PMLBx(3AXWroxpnY6kqh3;NUsqR z<#lg*O;8v!fa>EsejOZy1CR6VJD7~E5>OI19%NuK*G+IQcPj>{9pX63Bgx`8YAI8M zI`G1z0^C5TjFtsM?d8l>M-0iwzKVz_#EPgwZvAhrTCI%CQL4dScmwZWt>({A*3eE6 zi{vwrT&RqQLT8ZF8s%KIGB{EltRCQQn8f*!i+UK+5Jv47ld*Nk0B>)mwdy6%ihVbP zvmU+eVQ^v0KS3w)(|hR@fljU;ZcC|7wK(n9QCX6(0H)g2M<;rQliHhj8ocITOQ#O9 zdcSm{|BEEr=UwZ!wwjU0xV4onGUczZ<}Zh*O;J-{X=TZ1HsLoyT)}AY`ifQzPPR&y zznmQn9cLMiV@3I2JcUh-eL66BHFV&0hGL)t7h{u8{$ix79`0FNGkjYB1M}~p<@c#e zBevt2FA0%g*P2#S7{!(VGh%10!6BhODE@0+Fs=Qb&Kr&WSAswss1oEsA7}EQnc7FQ z!>##?Y)^Sf%c9ap2bxsRLV%Y*E)u96A%$Dr9iGC+uJ;?{_gNeh#-?ndA94yEZZS{c zYjIDd6>@QLQf#29a745$MFZV1S50&SCyu3@Zh$ztb%VvN8&YTt0Rrzy_>JUKhKyDA z%SC^d5s~Tk7L&?|Jg2!l9!gv@pjzlqEe!RLm62WOrc`kRW1Yc&fgjE| zBd8sScewcwGr)&BJ{ie9GjU>cuJ8rn6rnkY=*mKeCpSc5_z?o;XBT0{j~p{X#>fhC zdYN%++iqY-3|$X)tc?{DQ6l`9ds}{lM5;sF{J@xN<3q)ZnYcWJDv1!r&|8q!4I1F!Mv-E z{6FJ6Qsqf#=66C{mArk9V;aR#Sg-o?im$iJrnRaTSF~GIe{RiRoEHna=7gk*tg1zx zko84ZU*7SSVMFseyTbFG-Hmj9+^_1ypyJd!-o_)O{ud-DyFI}9C%Pi8Mu20nk41L~ z%{;2ZLkkwL4%KsI0cVGYHc3F7n+?IgbAcjoqB5W)P&-m+c(ZwDlp_Dl;gz!(8tqw> z{?#|k6<4*u_#UaCL{cLt8K%v<=Je!C7YVRoRrMSa#rUU)OSc9h;1HLGqT@!ziVY1g zw2OjMUDDcXCqkUQ#63acwCLs;Ni*_d{Zqvlz;nm|cIvKK`$yPss2$qUt!{Zi_;|nw zyKO{p49@q?q|IcE=}LRY7}AluU^(5J61b`qHX;l*LPKms^6hMd1~#G`z@M-Y1^f!- zY?=ralFvnQF$N`62>$ge-vOa2pxdR)&jN>Pk#QMe2N`ABp9D&bGDhRWSNhPZQK}UM zIMS_Zpq-z=#U`Unj8SHMmZZo2>`w$_Op@`1k9Z6f%T@y>WTM8D#h)!eL|{jHX|IXI z$ijgUw~BEOE%aG%C`Q*znt6m{K;IBV-0&Z3e+<9E8tZYt?I(lk3`UA-5qcTeX8hn^ zDRsCf~RVG z&C8L$WQ$m8iAkR!8_=^8?xtsZ9)_Ns>DIHl8})1sr)S}V-A>QCotj(qEKFyy`SyCY zKg&&eHdg>W`*X8f0_NcOW&Sd4HrKI&9JjI^^Qc=4Vovv}S>tykxisJ!y1hoM%p~en zW)AfrhI7QVDJ4@(Xw_=5 ztP(o)U;agiJ(uXy*;ebRpptRM{E(&OS|w??jCP)TnC5 zFVLfICF;D!Z=VPa3g-dkt@ygbV>`}ZjiE01BCJ}CJZuT;c_IJ#<+a8?k}~b9n=h!I zuLht=^_h_|_4fB5$Bny}pX_+(6lOl2q|gA7!~Wj#S`gg0+u=!lbG+Mb;2hq1yTP-3 z`QD1P^M2f4JVQdLCKR_gur}LU4O3EYRPkUj6+H^tTE68 z|LpLGK{>b$HQRIHIv8Fuqoh*X2*pLl*X%D%swE}<+N-~0zu9b>2Jq>fyA<&;t7Lnn zLA;E;4>?9q=l6OWQ%PM!rCU|Yh%dE_IsXd<>5{%IaC)F2WRi(VzGo7KwyZqWf9&wE zvwjbuV$j+o#(pwTd140AsY5Bm4&svyn6suob+vuC^9??xrWMglDev~WJ>^#2o_qZI zz_{+y?QZ|+PP$F#_Wuj9UD`GRP67P?LAo6WQ~E>95EE-JZjxzjbh9XooY5hPsz- z&pmjZ=yo!%fN|^7?J#b4YX5EKKZDxu*6sJ%exll^Fqj(FL%w8y%9hD0%01yK%Qj$v z#1PwD*_t060G9$_!i;e*Y4Hn$M`QVMa5dmwjQ4=#abC*1H4e9<5oBwWLt0?9s@kr@ z&8Q40-0&#l4R7Cv^@tB!^#UKLe#C$Guu7LGjoLf_pAn^JUpn{p@Ly_1GbnMGO&*(+Xg0iitY-{86uccI^f4|BWl zv7d9|*YCe)kZfSEbk0?LaLlIe>b`4XVipg$@BMKD;$!UGZRoK>3f=xYg8u*g{yS#u zECU-u9C%`5oc{r5kMrS!lZmN8yNM6~XIRvK(uY6t9@q$-h7#}K!}lZ++k@{&MSS=_ z(Csr|ew@&|@ZTM8TwixUzI`*zgyG~JArgu*cg!yU{cvY_cOr}l;^r`Fp5^n}4eNFo zU}su6W8zLt?8%G0_5^v-W3OpLu%-rGdJ;CJ`*w4JH83b624)4qe78aAn;3MGMsX7Z zX|da&doIb8!AW62tx>>qq~7_l+nN0UeJ8bZs70HkA!Q#^D6Dss9( zC#1Fu_rbmtqqxOP;uVSuJ$kwQN9nAGcBEr5o||$OxZ`-ePPBUt(evDOGKYYcg_`a2 zACb`CJx{+dDK&6aA?6UFx6UC-2jWab&szHC5XG27kT_HC9HMVx-xp^ZJb{p=FNckp zLzpsNA`MthEDWP@TbNNH{d0#yyuk+Mk0iOYalv5UaW#BLGH;kIAm&AYOL_)k6SvIC zt7f?^3pa1-YcqBT_Qob2yv;HEVpA*^o9JzGzilNv;-YHxnZsCu9A=<(RolAL@tU(&65F7px3=~<5ecT84ZKE#PhEjr&l#EHJq_UfDV zT2QUqPbP-x`@b%nHBx7XDqb=pqwsBSU7HJPvR;TLEDauaU6;QEAK^~V$jB(CwSK%n zwt1gd`Zwd?y@J?!F8pFrtysRd^+^h2XQm`$)_jfX*~&4=+~gYeIWE@RLSc5IZGj%h zN# z5In`o0yC0Ay*qGLgM^b?QNg%s&iB13R$n#pdY}K1%&jeeG!i8@LoE%aC;CQuU>pl? zTw6%$TU$^b(Qn;E%4sLd3T8LC=45UyL<1VIvfvyD!+L#V1A@#8vEDK&pBWQ7LiE&>ZX1UX8ZY8c*`1+6>@il3yqG9mQ_0j z$sPLH?Kt+YA@#J-T*MjeAcxm!;Q2 zj>WlR&Q_@AVOgw~#w-amaRkFDVzu3%Q7wrZ3niALS{ym5c}8?xUJhc0PhK{umPtby z=z8UFCO;?5j3rGqrG=UfNhQD{2dc0Fx%X?|CpLP4m0|ZJ0EUcmHurnvH|<{y$8b|LK@C z8}?!(+!K?gs4vz3p_nx1_x|6ANs~ZXM$`eGzCE+ZuTG5hjt+tG4bqc96dY0H$KgdA zg+OUBDJrqwRHNVA57bi97Fv*Qq72n?<5ZGEk-8U~1XblCrJ^#_2UbY&O^>iPTDcdA%c2-Qv~wro+aodO~PYlq*Ari_QSbmMJ|Wc7#fePmr=v zFtq#F96@Mm`Wb$`qTHdVG>#!(c3eRn${;R}FPA4sYK$abP%^g1ITY&}-&%30XS7hK zf5m)>EI5-&YyoP2MjqsqXH8U=i8gifxoSO2|IXDZ=jz1vIY%VPzb9BN>{e_%qj>p( zVpFSPv%CJ>Uw97vE6!7-NS0RWUsCE{RO;6&_10T}W|a1I*kOpBfC0+5Cstfkwi19E z;L>0ppORqEY$mht8!%`zip}xBpqVDjQIwflyiyrp(ZovoplEWA(b#{5U8bwC1Gj7~ z+2;y=JKP{N*xN|hlY0iM-pnh#AT;rLh8zxsCX(zqb;Hm&Ul;^K6GLEVCb(f}DsF~leto4EgJyjry2p({llwSc zVz>F-F=!^-gh8`;5C)BT;R9jNWQi6ithdLY8Ff1h8sh*4&1UC)V9;2Brt<$c2F(Ou z(2%}ah>qbPXexkAXjN<;1VQ6`91t{{ADif~QTK;I^U#CwDfdqgfI(yBAZ7j?7&H|G zgJv^_K~pgpgQlVvgJv^_D034A&E{J$Xf~74wVA`9ap$-JgXX{h2F>OhFlaVw24m3R z+aL^@&CsoP$Dpy^34>-7!Jvt0y%mEd^8qnvtlSaPe=`Qn1oLXB@f**>TknZMGm2o) zaBaK^gC_MK#GtW0=y}Y49R>~hE0xFL1>GkGP49V3>&>U=1`ZhYqUQ7=(3sb7X6zmq zG`Eu*?u_fG2gIOp6L$L}M17PM@UeCMUyng^r#9q4f#(Ecw4oDXl7KouA9D{~KpmDzC9y7O`qh5vgaGf-cfpN>Mx(S2E zf;6o-I5ikIr?56<%wS0lbh*t zpVj~O@KlMVu55Q(fFXrQ_5;huH}1BObB}}3e$bZTw{Y5x#B~2`j-^Qqj1#8Y_DZiH z;T((dZum2!CJx}wkm1{hKT~z;mVUtKyEFcbdko)2wjq6kWZR8DbAR-Q@qs_{U$@}T z{1f)JyZ3zcgW}ITu)Y0f@n@XRL;k?I!Q)nIz$x0~0qiKohBO!#H{s8a^VOKgJb=Aj z?Uwc1VZQnHhR)?nmGE+uMHte+JujZ^1w4#h)rE8@FxFp{F#v59RAF>Ui_Ky1b^mX;Lo6Kx5b~i zwQX+vnX0u9hCeePUCuk=gZ#tzGZO$oI)Fd(+&c(WxbbInZv2@FZ5oF^lTE%j0L?34 zCeyc@@DQ)*j`%aTvcio&)3dx+|2nsFs*DUZD6o6ue?74NHLt~(yAS*?vypf#$pwF| zJc}jMJ{QnzxJCCq5cZ6_3-5$&;l>E>18Gx(oKq zD1tph96lg+^hF~$%-@9Gv1#t=2kRI#HgAhP6H72VtQ?RG10WgbE9yoZnatJL4RW(e(hhGyA+XZrquq0o)nQU2tcxISUq( z;LZpM?o5goIrh#0&;0JKuK2eI@Qm>fZ^3)$L!FULmp%n}ay#qqz)r|Fcoh|_=emXs zTRZ_jvpN3>-V35akKl|7rH+G~!O1CH+rT$|`)d?IatRUV&+r!zq;q@An76t@-BoBw z73mq5+0uL<^?&XnXT9$qV#eGHF;n4&m|4w1%v4kgp?h_<$Ucmjiav~)3JznYg6uKB z4aUrb0gM?Sv%4{7Do|1%#>|8}W6T`!7{HhTGRh!~8Gw%fdgS}Uw>XHIuO2zjH~=t1 z7Qoy9Gd)p#05iwO)ZYtW=08s_e5(&&ro6WP27DP(K+$AHGc0BmMX?O2<9$WrE+j zH@*xhJJ%ohGLPg8#+Rvh5PTVqzFvHpD&Ky58Gq1s=5F{h*WSDvz6{60Lsdh8FXN}V z316lnRxsNSxH4FX#r*=Z=!zr=Fm46`#0-{W&#n>yg=Xz2Cqn^wC5IrdaD_R0JkTEx zVd)pC<6>Z~RbNTf3fw92O4_t(Gm?NXqXELqM+9L8z%yxD0L*;u2AEmDe3=>7Yu^Yl zBXgJA!9mOjIEa}U9w^;G3_n11pn|QR(z{yU96*?P?=}cC9Bm!J)OBgVPed=AxfNd~ z3(zlp2s2#reZkkRNhcEQDeQ?-ywq-G`8tGF^e8E%+W0W3>lp8x_hm&BF6FNJ;adM4$F#|pS@Fp_pp;G3 znu3Pw^y5tWSd*`a^)O9Mwyd)1LrnTm%hnwIc$0pl$!74%G&uHWn)FJOK6rtCf{$MA zqaR`PClz!n#+^}&zo3|adv!Vl0k}Xo_}gn!B%1@_|_lC8L4(`-mV{j6*RdLSPh=1a2&xzPrVh-NM)$@&oud7TVNy&LS>W_P+#s@E$)cIjpC{rgUc~ z?{Fy2(Rwxbx~mtT$Gt}_ft2pX>oHpB%O2-M$Cx%@gP@wvmhPqFfAaI4=(o_fX(yn39yzZLq6W3Ik3SX~$LiWnREwMVwT@7UQt5Gu zcHfy!`k{`tl#zP}!8LAQOaf)1A6il%wx|u3+z8wxUq<7C$>A3*O6MdZUN6#{^W}7;xJAI+I-6B zxS|gl9y5ul6ETIpisE;RYwCeMC84%&2G)`Jit7arU>e9QTg2%zT-u8+s(nw~IN7Qq zAM8v?q_(i+lH6Vy@U;Y44|tU};3jTmq8BSBlml|DC`cOPit(vj6%&< zb&Ya++5gAd+rT$*ocZIc)r<8q21_dm zuX9g?TblQtA*ZVWQ{6bGVZPaIlHc#b`|zdYWV)mK4<)69UL81V+$NM1#l4JacB|#x z`TCaMDPsoAzQuh#vQ^abUWOZTrs*bF^vJ5HXvB@Bg2mAKq@Fv4>+|ehZ=pO!0z2!C z!HBQd-*j>JA)PH0@(Bip7{cNj!COH4Hj85mQZ%p!8>Nwx;cz4ACYG+l1=7ea{3tlw zbr=`q&@cZuQS?srKp zR!_li=VBWu{7}-lUB@z>I+BM=Zk-JzXIRZRBlbm|^VPZ&N#_Xt#D{%hXUnHa=b7O@ zB^l>M-NmGHu<8=%%sI_E9HqcBXZXDQoI#IP;CHU>gX9u#ao)-^(4EZsI#Rf={U5oYtb}^%YmG# zAE1?@;a$msWo3Dp1#3XXmJpH(bvyCb-txHIF4q#3pR-%KXkQe1nH=x1Rol>-tK|Ux zI(0umo+Ix%ro5=92pGB8;qM^5m{{$e&Z>Uek2$)%NO2I2ePt)E4|+hBFLAC6Jlwus zG>T4HYJ#_i)J$Bh8pu}l?S*hS+>Oc9FBZ0i`u1Wj^+kncq+1l0Wnwl4FB}}aPArP6 zX$k~pv`>tyGXVvdJ_^$^K^ITd$(>ROY+GBYz&?U`&wKI8dmmBq;@ph`v7b~Mt7k*J z$Upqo{J@P}I6N_%P35Uo*XFUG%gaVy|6rv8Of;xUG)A04wyO2{9I zqT&LW1_FFQP4JU8sm^p7ogCIDIzfT2VEMUZIoajO2s;z_`uePK&hoPoXP8US#fau} z*R?x|Au0HO|P23qNyZjsYx%X0JDJWVQ@;tToX zpCkAkf`5e!*TJ5CP9w2qj?Dtgyf4^F3w&;=8SkerFkZc-z|TBZWLsGQ>EX5W)n;$C zg;;3(KID%>omu?ky8t3Av%Dyv`7Ook^ut$BSM8Ro!ynN#hbGZ>)6ZUB<}quU$7JmY z`A#;M*Cgzqr)sC()Egw(@pGyUW4JF-`});Do>QhPnM($npr5n=y# z+oD8I@^99MS2b588qdYl1y|gUR%Vsbn%g8C-|H@QyDtQ+>Z8*}$x-8BvGwS0=Bv|n zjLe=}dMfrW1&@=2^qs+C?D3->n$fj?I3ko|BZ{Lt^SqB8M<7h29I6WxhusjxvHDhz=-)+rW6ZLAHE>cgQjicORIx zHfwy#Au|Mgqc}$xIYrdLg`MtTdbR_mIsr{j=IF#~x0-zrVwO>?s6M9k{X3f9y0~CITA&u~*-4_>T?Kdonu+y^|D}gcMAog)LaKUVCn~@Y2LiZScp<9R`wn@b6Sa zR}Vgf`sdV|{^OoZ+mW-ns#lZ#V?Rc<1zq1Pvo{oCG-FTOF&tPEZ1=o=3OUlvmWi#W z{N60Ay8dJT4=LX)`&~m}MU{PcB3WP{Pmq>qq3-=;2jN+Z|c1VWeHNUt00_-9(8n(J1)KUT$tV;2OfcbHF0YW&am1_SCw*V zRnTkZa6JZ9-bj1}Z$S=C*VdFOIV~5HWCY^X^P5yo#fzTl2j;@SB!UeR}Y^J)keF9sh;fLg7G^}@&m|B?#t!iZb& zGPvJUc!j>C`A*Rjv!HuI9uRBH*@+zRnIgCNNrRPh_OTU-3)oUm z_4UhWfTLqyq(KRjq5!2`ibjNpZ-4siKDycCSnz;6&&%l-ae*7}#|}w;n(^F#F~+st z7l>hCe{gkc;p*63!POUX>u_zI9qjzd2AivU2ZUC9C9{*Q9l2tEEWxkT6!&JovY>5^ zJ(9rD`0mGiE44Nemv-5>R9kb`(kk_Boe(5#bD$;IdfWGu%$B^k7l1C`OfY;Q?8C)e zzL&3tBZbmUjA^;B976%Tdb!#~py#Y{kC89R0;ze<^2YJn=dSj0O=kqZ1^SqXjw!UC z4%+K3Bys;c>vlFTWvN1+lAGn{y}oqcr`Dr+avK~A@rSlJ7MBCdPo4ZE)^e}lRq}|H z_s$c%$WY{@(@*L5W&DY{xTlr6xF_W&@1N!MUzeh}*OaQC_ge(-qTc3Ru9nw7Anp&3E2#9(U%RfVOM&b)3|dMt6Yck z6jErN7VL;+I{TD1Qoo(4Ie|$mr_=4TMa&LV{|j+KRQ1w3VZ18A%VNxMYH~@GH>z3> zX@!wXkZWa!wERn#(3=GG4fjH%Kv+{dcRJZ;?-PT)jY16*uTceK_XoxM<29^Mqi#7z_XUB$S;XK`D_C(uSzASe zq-IPU(6g1&kFVeh!;xDH^u!2|xK}lA2{&Y(cXr9+yZ5rgBgu$577AiN^jd_CA6Lbq zLD()NgR1pN3jeMnDLMiFaCjk9KvXlg&%{-Igl#%j!Qq2+eWL4<6GV1-Tfh32`pugmh#OZQwC_}p{@Up| ztD`o+eflxF^IEszgN)k_W-etP*f8Jt0laccH8&f|2FOm$&BlF(o$94@5)j*=d&eHF z+`Ui}k0tlqTgDGxL@l=+T(nOgS`e*#=av)dqnfeljJP0D`SvY?8~US(aI7&FZe$J> zoj$@u?(JUwZZ}W^U)rDnHx7T8WG0JJd*pQH?OP(1;sRWSuFwwn0?xE{{TdWg@E3hh zcCKW6pgF6h_}k-l|8NrWdedD<7k$XlAxDRv(dDV4CGoV!VOx&kqW`S=sG8=}%gvGJ z@uz?_NAdM|ECitDjSn$slgwPbEwOpLF?_!nFDQ#oI&a4G19j^gSN-R9es#FBZ=`8*0@1#`fw{kk`9aae z!q#H8YB9t7YtfEvs>r>je?fb5A3&Ekk2PN27TWO6y}-wYWv_AkezUm2w(asZBm_4% zE_!oS*Vq`PsmNa{JUZ=!;hkH~>h`hH1`YZcsa)Mm^`#Sr2!9l#bXEs~VYl`6Et?-p zpv=)}Z}TS%Y4~Y?7Z=c!qk08$8ndWt)%O92I^O1w8cyh=l@vO(0N2Zj3pU@E0E#F8 z@T0hU9*Jo2VcH^1JSx|mf{jpG=w&DaC2~~)1`37V;qRMQiwUaS1*u^&bT0-#CO4=b zx@Fayq91f$eQV;14m~}qUQNkP`=MvhI??yu!qgQp-9=rv+Q-c>w-xQUpOSDr8d-PC z+;w=$%2l}(7 zXyFy5!&;^e)LD)DMEe^*(2tnGP^K#~J)tdZPHV54r7nr-NsB3LwT$~f3Uu0Gk=`ix1iXj}Jc z1y1pH$S?pvo(xkz)(D1p?Q#8fGzn&#HU5Vl-FDvxME6;8yLVWzcLT9~)N+bC>rXcJ z{Dk>_kz~;X-%E7;dzNI;2HO)|y%~WSx;h@X&Keh`4>DK(7o{^Qp}L8na!aa(A(c3A z1*07`qfxYv+E6E;WSO;(J*!PMG1dq_yG3&i?o{7S^$!Exbg@Eods(Ie9xO$1r~Sqz zd^xPqX*l4FW=#K8mqOh1;k)m@{_DE0?qktk@WaWIjWV*7W~dWeaJgD|#VSg(uwu$J zEA?UmlYD&1r@J{=?shNFs;G8PwS#tvjTnRA^=F#HZSLU1S;0_xLxJ+B7}cW+rTS7g zTA+2LT9C(s_jV|9+xvsm^M}gQ&w0J=RKCFHkj?w2r)Yq~$xuWUStqiidN`@%rGmnJ zF3-}-tv-3-1my@&kZwri_C)qCr>Auti8aEL6NNE@C>w2=4#pm*=#@BaIFb-zsln~7di7DP+=Ev(*f8G}N`QN)>i_6=)U3hU`NF{Ljt_|h)u6$_SqZ@ZU z@a*{)o#$S}M^)@YFJjkfjStS*Q~R zI&op2<-4q(IAIKQTESuH;JhSaB?Z;d*7xt`+@ zBQXiw&4*N{xW$o`=eVz5(Fe~ahEA#ATZA79#?+e?-T>1&)YAqyhx#tZ%JU5q;1u8@x~+pYSGm+|Z|!EJ53(v;3OpmyKBmyUGg*Ghe^L zYJj}4iDl9AFtNxkNm`!ca+FDT4X=G!UDu|6p3krc{sJG0vZFR5auJRy&RU(4SvSbf z2(_ZO9~1J5+Htu-1@wJkT@fWfeE!yNSvD{WJs zxi!8&=nmfnI>=jz>C~8p{Q~e4*>WzoA-PC|hh7%2ZWI)gFVf;hpy~1wS1Doq21?XVV;*w2Qq(QJ(;pE z5Cfz$CPi1oTClS0P+2ir_21Ff$Lg`4BzjX|MFhT?wjtT7V-v$WvIYp#e>kfjU+w!k^+M2kC**n& zOX4gI1~sD%5sP#zdBBw=o|i2D+}9*BG4rYRB9B=wD{x;~9Eq2d z&fHWi`R5;r{92U!Hwb>Wz`5IBiuj&(=_93{W$tJKZZ-b`v^Z-#K5{YcpMN_A#BW%G zrs~R@s>`a>l`r^h0%!a4x(cT1veLTpudU1N&KYYq^IU0DdAKwS4h7y{D#L?T<^Gjh zCg0;Lx2zL3O6lLc-{$ozHOu{zxLGuE1HHUn=|9Sgr(kWvtspHbgmE;TuXR!d6X_i+ z;T=wsqgrng=}m@ku*mb>9&99*Vyi(Ixk9|DWD4)d);X3Tf+7_n0pBv!32D04v5YD- z9=7(r}3?Gsm5TJQt5U}avh<@D!d8$O4}JW*{1611(WQ*Dtgj=Db)|AD&m z!pLPJ$o^%tLp%_*1x9X}IF-FNMP-2;|HP6seYKxS^{}7wt|r zcN2Ep_54jL^h@p<5|mdebx^mY#qvB`*rf`K3Czr045w8=LvmPkA+=n9a4z}+292`F zqpxXs>hwCiwh5oU$44wx^u9XBmQN0BF$qI|BJ6}yMIa)Sg@N|L+rH(1H^bqjz89oh zQZX!|m#_ys(}?9j9cX+J1*=tQ8H7BGF!JevYNd=!3-Nq=wcxzBwn3&!e!E_@PV$k! zm6Bt@hcv`1bISh+k02te!(fQ`rDInPxTcm!N*8G1dV3pPuy?Xh13q)Q+nV1$1DC>p zS~coxI^SOcUPP49BS|sjGz9rO+jD~aeQxMkR>UB95Rp*zCpwal1~MLs>;fGuU(iX_ zk?i)1QEN|m$RKj~@ERvmJxZArLlm;mCuIcSBwE__pEN;%%?NvDgv6N~5PaT2p5MZm!c9P<809R3Dax<8=8T<#I2DSk^a^eM!> z!WEp^DypMwjgqV2`8Uu4yeKhVBFAe5E&in| zl-b;&&IsG|E;4x6T`^gB)Ax;c$)Fe)Xip-W`>Lkt5qEet664OC{=TempPjxpi;Hd#UCw*=pdWaa?~yZ+*UJvnMaBI$lGsPnMzj=JNR7 z>-$S-&EiJrRw8Qi3acD&GKbGU?KpsB>y;1Eq7xNFndWIY`+Q4M<+k$4f32du;aaSB^mzm3q{SrGjzoa&uW& z@XE2^rB{2IX6e4BpH2yHpc}_6kntCXj;ed5DScZUI4fJra?ZU^~2oCNQL6ST*V(K_d;oqFz0CJlu;I@tCBrx$9d zMJurHp(d(9AYBP6HbfB36c*^VB$du_5YjU4ij1auW|5J8nG{~LVL08fp_UbRz@+7R z`Wa`b8vE(iM{*@SGafY$=~aoJRwl4vsHQA!6R~-NVOX&&?>NQ?Ub;C+bx7LZ8W!Dj zH!0Ip7&?h~kf!_`zX@_bf{EZPdOk!;aIUo4R#k)to12c|DKUU(TCeWZ3Z6E|r+ z_}q9Gq{cbje|Wxwg4yn@v^(u`tQ@70VP0mzzj$cI;kiUARf^^G*6a*H{h@5d7rb<_nyeT8cz6bx!ijX_jQ$_kDv9mOUrViDD?c@s`{I7J(i)bu*Bb}gDK zsNW+l%+I}gxJI&z^YiU}ZqI#XZI-4>?x@@D%0et90%c`;+2kBtI9X@(Iz+Z-w?=11 zc(JH8nicU1MQWI4B{oM;XSL?Nh6wre9+-Fp?|8bGpqa?F4-!LJgm|pw?0iGiDtF&$ zEt9m)Y?n2fEm~_Y(uqNpZs?CN=iNfr4fhWhxUmw2HK*TZ+7H1JZz{EMiY0;Q-zxG1 zvh^IxaFuk-ICDlDXLo-BelIC?+dl!@xVd2NAtuPfO@6`dY_u2A$sji!w=n!mSNp`d z9O8qN`AY4!u;M9lk|lXgi(Rx+GRyHnQ!*w!Mt6uI#CyuMeQqwM^S}6n6UpMq7Ic4&!#obR$uEICBZby+_WMm{Xy z)BACIxDh+;bvY9ovx(Q?A_Vc~8N`YWWSE9Z71R}2z+YV+A|0DReO9Dm&s@+@z_sT6 zRyy_$YzF$Uv$-YB3%~>Qc+ACv`0})DKe#%H2H_la7YTo$?qh7}3w)D%?=C*!>KM%q^#A%55S@9u~2(?rEl|%_+(0GGh2-7CpzJ#Ji>YnXYRfHlC`? z{JF~Heg0po4qqvtJmXf>1VOAO7W!2Z+$vrQRzrvqT0%ZuYXb&L#1b%M66`t&3yJA! z#t=>M6c-cZIRMFWfHMk1|IQ7m@IES=cukrk z$E{3(z^-Z&P0MRyjA0NM|Vvj1^oq(GzBzb)tYK!vtqkBijjTl5rlpU>B8jw83~HR?AW2pQY0QiF=i*O)kN zJ#9kfgIVLFVl+QQhrjA#QeG3%YnC*WOJE@1Dv~&jy;nHU7M1z3XA3t}EyYwqOi%M! zcl#>D_n{ISrG&!gRLjf)7!kLMI!vz7jW&+RCM%*($7`lww*NJlc0YA2S%k?29rRPu zt`q#%E6t_&VG(zr87B-eQ?Wv^Gukf-H=&#S)Wm0$*p^S|7=SSbhH{~Zk<2){(Pl*i z^88G9C=s03+`-Pz4A1MdJF`Yv+YzNd0-K8>G-!Bh$kg7@H-NKoWj3{~PdVKt&zZOd zLA#hXUENx&iFVPQ;zNOL9&MljX3fAig)+stcT4VJXyQz6oi=j3cAeJsy6bqy*`NVkQmIt)Yl_kViCHrUV_o#r|o@*VQK8jwHy`y}JK9WM~FVqL9xCGxs! zUC0;pyXYRb>TGIV2A+#F!1IMOBgbFpIkl_d9I*R0^SdFsA!>X5%s?h1e=%U-X4>c* zuM9M-8)&F2?pY!FLdRba;c;w$3CthzA$QjJz^=Ovi-Y>&$2Eh#fd(d3i?pl0J2Ge} ze*C9`bDhkQx{s2w?Ewyp$m^oNI7)~i^m??8qWfNwiTI**5npH{eh&X3y=^540||H*^{DcY^83Yd%Fyf5>3>$8_8~q+C;?oN~>rO+Tsy) zm-8Lju&5hPI#z9(SYPPKpX(^O?aOMZ!nqko+seS{onqAzzf7Up%7srF^pe?fNqu?5EK!d}voo)GL zQZTBahWd;$UZT&aS&u(5UgGWRt5ncijjFlprID*{m>s`u4}YtzKYqT634J&%ZLoDOF%v$T>{O$?*`d z7KERu3~bsO4$pRMEO0z9Kd^2SrK`|Y>hB)hsXti0q=T+V!#R}P!4Rcp8^v(3&;riG z5Mh9DREUA_iQ+5}{R0(U)fT;7sDcuM^~x5C*=NVlN`98ZS3cpN=CCXdaO^M#RH#gL z_!|OSK8_pIw}*m#X3l^OjJc$bGic}^oM%;)^tFJbs7f_A6e#(Jxe;i7!4h*^kDOTS z0yN$+l$ag&sp39)+T}pzVrRq2{hSck;S)0baNrkpEDq7K239Ux1=;0T#SXubgccgy zV@}s4=~aDENfup_o<)YFSJMPqeN6;^bZ;r^)@;YJiitI5N0ED?ly_v$MobPRH+psF zjR)?W8@TTSo@H?;N?_GBTpK;l1cL}E8iwVWEQ5MSn!%6-YRZs20vR~mn}uf(PEHJh zQegO9dEC&U1Kf?|VvxI2HhaLNF=8K&n7cdUdBp>H&fQ1M9b{l#aeSQ<2v8I;FJ-$x zvF9}`n{@0E=Ol29W2Nc9$~@`VW$d6Q%Cq1MA^z5K74c!eNDmUu*E^~|o~SdKBE&c0 zdWU$i3&oa2{H-)HPS%G@I;ZUBYVH*4mBppR-l9lXiCv?}Vu@WVRa4m}vG+^WlqwRt zU8<&njbk6+WO@5tF>P&>@e{ADZ*{spU%I|q)Aco`>)V>HZ`)t257Bod1dij| z#32)t=yS(wC?NjHIvJD`cXMSM6d$NIvl(?oF!(Gid|WID15|1(_*Yp$eT%Y@6Vx~~ zPDKE(UW;()bWJi%WVqF7IA0p>)-S@*YH45GY42Y%HHM~fCL6bgrnNnRk50D5ZQ_8u zPRQ8GWzuk8_QWROua-~egC^-)3UCsITHoM&q=6v73pO0i0YA3IF-YcN+nz-XTueRX zBZaL^^zFTgW34A8vpt%i%9bcujnW!QR?cctrn7=H$L4(=N|u`Pc1a%B{{wubU9;qa zvE35%%ty99vS7%-#O#glFFDz5j_pZ|^_lxbz;s7Qetab?!Z!J0gY?kZ`lMq8Sm>d_ zqwh5WID(5Y5|rDJ1>&oHRa{?CmT#nT3J0_7fK1a~+GT~5=$7K(L8{Uh4j8mO-x|nc z${shLY%^nT2}O_JrCB7laX8dS+rc44CB{II%LauY7+6-MD;y8pFre4&{d7QI*#63p zmHBC@cE~#Ir==NC46V$;(wQeiIP6J@O{;{)1eMV8AtpQ}C@@3abkC1Iq{sMg2V$8{33cjJ)OEZb?>1?`U@$rU5eE9}k^d)IbrR9~Ym#%@+ zru<${<>_XFa;5`_2yz(C$zK$bk4fI*v;H|n^`i;f=+N4gs9Dgdy5_UGbqpt|96a0d z9fkF$HI&>P{uM=olF1H_O38wzYEux>u9T7A=!Vrv+Bc zP#Ps|w$ToqsdVmIr65_Q`z&d?=ls(RbsH|9-*`*IEvIW$o(&C^ra;}j>r2ZwY^(%e z)z3ljb3bNs|6T9j^TMXDZRy0pI@>|UR>3^Ci{yH=%ykvaj$Jr*SaHO>=!l6PI}AVm zVt@Yv_YtAscbiKS<%P^*b9d?7ZA?amd-JoN!lnsoa0%>c`ndj1cYRq_IQ&Wf<_ix- z8w%-L|ANDZm|XgqSodPPd&vcNed8ZWuBWYtyTAqYI4skb@Z3_f7ClLp-vSheai-;a zB=%uKp)xbA!X0}QDyOi5iU->$9oFxWKa{+If*n+q$4UxfI?Csf@5)nQHe;#?CZ2U~ zt4wTjZ{Dmq`BU@e(ZtxO`S>*vFA0uiY{{8oFab4N?hxGcM*Qk$&5LJ$=yC=60moLh1!`4 zeWi0rc8Jrs4tuPzw!u^pYOd9r5WXkupH7BaO>9*$(_|V_s}5rN%|^5bOVc=}$upo< zB7ycwfyqQ zjS?B6L2>90NC&$TjX*I4aJN`3u8 z{B#HGei;BTv&O%!NA@ti9z&5kg0}|ggdAnhs`n9rqwdPF$@qBM8qKGUMqTRH^{-)8!(pZI7T$DxF8!{c_>LFIyl>u@X8nfJ|Kd(nl$;PgtGF`Kft@g0CP6VZ2W5}ks8U!_I zb)lWXqOoJ<<40^!!K4C8Sb4{fnEOS0FKauDV0C$o?=3pshwTCcMck-9*@xxhbJ;+O zZr^1(r*t92z*kiMzV&&n*Gmaaj7!cAvE-*E8S)Mdln}YGZgY18bPWoXg1qCU8+WiC z)BmhyKqd>~llq^p9FTXxc%NI^{~U5Cf3+^nu=P<|yo)H%2nwmXj+=) zXop_S;oXgV{FC*oFXlacO&);h@W#_gw5~WSN=ViR@^N=!EZF82R{j`#;|~ZcpS%{% z9=<><6E3Te4TsYsVp}t;284qi%B`X62l3+1WZQr-P#9>ZBrmO*s)-l6DXA0W0x~$- z$NaDd8z-9U3xrnQTCk;fupBqzSQobPT4)6a2J=j%xPOsZg7Cs(>sMNN;uv{<37i9e zkgsu?Z#Zz~PhYpR4ruORizDw%94a++Y1kuALb9$%{M1F_EA~(q3E2Yg z1BJIYI=uD?A8~N@37&Jn94^p}<*Wn#>m6GP1HwmSi|*4T;fLW*gHaO4?m4;-^I;!G zyihlYpIUL{w$tPL#ix_Y-J%gJ>R@}NL$(G)xY2T$2reb#dFt2;m7*cAxFHsMK2YM9 z@-$`9JK(XnRTXsF74L1Xz{D-;*pf>4?NjDnAx8yxTLdZ)7WY6&9&gdKJuKa-;_Ikj zo^YLZ(kJx~@T^|W!B6}H>O1wrzs2PgxHO2;3ko9){a(SsmPO=yosdTFEy1ZG)?uaJ zmsSuDG`#KPUKpZ3dMX3uHwS~y2b|LcMZ>mGNssSy2L=mMDMK@BN?}vRsZ!hvlG+KS za1T^};^Y)C7xnH|fv|y%YLOfDzzzLYQnISUdn*HrW`@Jh2V7>(s(~KQt)czFKN!bF zJ=O9Y9#;2XNd+HVHv~-wC{e@9&yy{`Qux-%?&Z;qfOS>65AQp<9yZ;F`Lw{G4mNu_ zV1EU1+UzGuCkqQE>^Yv@=?eah5@9g%*Gr~sC+)t`HBPQpfDmwI%K_mc+hdiiY#?tA z?J4)KCqEBDd`Nj1S9ReuZ8SGd2dyje zkLlj71>^Zsj2CFQ85FJqg{cRRR`fz;uRgGNo=jzjVAYi2;+A~ect^)K4^}peuMv(0 zW$%=VKIt&RGJ`r`Z&tK>neR`QninnXV3*up&_goGzmXr}_7M3-A1Mb4(fB$T;2;QZ zj|@~ZL$W2*m&2^CtMtiRe7yVQE&ew$VcOb~quTaW(<94e%TX0|gp5CB4&3NEFRu-K zPj1O)x5(?p+~^j)%Cv2ZY-FXUHmNt7DsJbdAUAKXRDk7Dlz|r0_@kEee0>FRI2w=+ z7Gh%Pl5n_~ZZ+ao&F+P4+2Ql@#_$ypMoQ3l$y%G_lNF7*0x=exDERk+AD4AoumLhf zak?ATrkzm(IZR;gyz{bYV<3mcolOHWlD-_)C-;7_Xrsm_@5|KbrK2)7P_yuy4DZuq z_)@@X1$Zz=u7Iw8bvX*5Zl`u+j03*EE*G+m5K{*M9dCQ)sl&J0j`*}1pS+E*jRLR* zwjAIe`5WS6A{tSx#M0!5*>Wt6SQMF^ilwPuSW)UO=TWmPkFkeY#1nm)M0J3W5)Pa8 zJ&i3l6TNce0A8{-sYcvG4T3TUQk+c7PcM}HpJNZ3+oZPUh(XljR;t!RZ#JEWaKvs- z!5!5{)YQ>D2Ah=>F^rbW_ZVKYznllVimn|#L3?3kYP(45FWu3}AnLzO5cRqGq^*d~ zbEFeJzTdi2PYTZJZ;K%O3P&QI7&Nv$dHB#p<34iuqprp5$$j>ncF)-1!s-7b<4p_eVuO``W_4ZATem@lllh}hYUMOE3M%Ja?qpt zAag84LxXCl2Gar!Rqj7Ap3VUsY5zM14Q)dIqm_tBH7$?ov!0E7HA;4~>UpHDVv0r`Rkg1cNw+uhi9FuLx@s}>fU_-_MB>i@n z?!t)eD9Ylhx1%_xf52Xv#aBOocl@J-;@ENpC}7FW{pA&uks&BF{y|9L{^p0T4pW&3 z9A#bEGgX?VVXbZ&#N8C5gWR#tNXQ=Pl<#>U-s19$)G68J`6C&^;!0s@i}XqKM`bJ7 z%(nOtEKaYE?=|Bd6Pp;9eNu^ol_~75ErUQEL%XLpPuA>d9Y$i^X(YdPN19hGW@Byi zS`3iB_M(R5GdUH^s$CV~3%f1)7jXC3Ov*0aY}l9(HmewnXzwm1m6NmC^2u3wmFqAf z1G0n5X6(_da9bxuS(*R;_BoLU^|@>JRe!zCG`_-q zN$?g@m3!7yNB#mW)9_RUlzAlm{HwOQ4d5juz)9o~GetgqHXfsMY6?#p-yjnYZQ`p9 z8e;9?BP=#vqNN*0S;lZ&8C)6@(&ul}c#J=cyEn(%O53=KWtD@a+|W4x(s=Kkku~D7 zLtFO1@f-3Y#9_G-o`|~tx($lj)=BOjm2gTG*Vl4vW^wnlvZx7KEmwV)RQ-=rq@jHW zl+!YhU5N{4NiUp?nj!ia945kO z=+d$FoS-LMC!7$_3|rRnCEZ;1Dbc1_n|P_w?d~ zPDL9H!qh2iOKL8q&l2I@L)kH zGMZSb5A&Vw?yP>H6Y-F#GIpT|CVX525bSO)f%WLI8juZj;X0{!+j9{tq=TmZs5@#5 z^nM_tNO4Cyt=-c*j1kLd2;o$gphU0iRRkvTN2%YX%%Xwv`580=S;dgYmCKKaI0P9C zB^G(YrRM}LxAnPv8od=UYr-tcHgtqSx@`zaM z)H^tNmk-nHxy-=%kBN`k5(p1{5$E%;OQf(gp117Id=A!?^E7;8|6YV)5HBb1C2B-$ z=7_6HollH$KwP$Qh{A~P--`eY#mpj%Xfp1cNiGpYeW;}Ud+{apY6fN)UM{at7I?hc9v0$-B&kc={25d(d;&hxp$DR6&Y_FP>jiSRlbHZm8b}i;UpZV9`bB5W>I8uc0xGQ^(TezvG&;LEMvRIubBtd(@|wG40mi z!#LKNHtt1=#-1_vMIj7(4YBYi5NH+RIsC$ID%eKfp^^cAVnq?O7D|am$~QO^q3@5H zyPnH&|ELmnNa`XK^$hi|KAJi~A&)yTp0VsScJ0&>G9Rby0eQ%LSe$2i8=>A?AJMlR zZ~e_%HnHuvExM1iP~xL*(Na6e^k%~zmteFZ?GI?n}+JLZ`QL%6<4N>Mn86dI{h^&$nr+{ra zaDc#*>x&F^7}}%6C7#D}=%V3_lWVd~RCi zcWO#-=-iWCwg^JCL`w_YC@x~eQJ7IDZ-*B>zw7#S33~Snkt9;IgzsuIT07m zica2Vj1pVq5_y6PW)($uFqj0AzZA#PF9#Pj+q;{?MfOQqGjtWkW^^W{%Wzz-Tt<-7 z71J@LH9gV}_Zjw53JNqWeSQ_U00*g#Mcr9Yu(0+)x=3ooC_(G8hdM?LrV<+LFr|sCk6BY+&M#h)2(y=iRKU~s`^B<`(gzWRkWAr)EbBxM7 z*}g7jLk)cR&apxB!Dt3iukc`KnBJo9z7b=0ye4`~-c-~11Bq7>rTRIY0Lt8G(tpYY zQ};TGZ19Q1)A_RyY=yh-c9>XO1pX~O6M{x)#{^}oH7lOW=k~`?9FfELFC4zh;aWXW zZgAw4ar=8HzK-&{11rxzz5X=>X<=aFdKTjVgG*emk^ic17coe9jnb)J#o{{!djUFE zjA~@guY%q4=|xc**A=BfWQ%cZ(~c0YaHJB(7#QP~auMb*(27!NT(7R7 z1!N#y%6E1Yi`zbSD5i=%><)(O!F?F$zF#L~p?NA3*R0l?M1;JYluu~Fae{b<(pvSE zH1CTn+^23&LfZe>)7d7RzsKD6%3>>JvIURRn_+)j(6b^cf6t^_=zao(iyN8P8TW4M zw7>~^vRL_;MC%fK8%*~JJ@}tm+jin)PR|;A2*c_$P(|9a3sxZcs#d$bKE(s+dG}?{ zG_Hv6D`*P_bEJ_g1#feRAH+Q*vG%Z(6_1H?oiSV?B;Oz`%M?L^Wwvqei0vh^@|-0D zW=1j{UrZYGFWS@h>ob|{C%TWA#9x^P{e90|GPc**Mr)#fm^U`XyP!&(RqbS3uy#BS&Nh^&7VJ1QMqyew}n(Kni$#D(t?M4IVx3^>doa=gI0+b~<$-yV$8t`_KbM{{YcV=yP+ z$q?AgTNm8m4rR$)MUTtiBu|+(@%+W5-e$AUfc4){8cq8^Q&EOWo4VN z*Av#5CQHhAq1Kdex-N{V5W8kDXQT&Hhrt~F^RY~qo8*;nqhsB|iH*dO_Z2em!a9emNM~dUaCt~; zo~z5Fb!^Pm>6m#Da;h~iZ(c9LI`S-_8j--2ahw|yq>b67q&<7Wf&{rMo!as zO#Kw^5j|yZFBP#gnzQj0t}ODALT#C5ZYg03mGP?dRX&vVaTdqZ8*$?+Gz0lqNY{G$ zbsJhmG<__D!U>io@SLa%8OW{)?RgSw>G54G+;cg;!aJ-g0}WbAIayRvT2wd^n2rr8g8}5&HS;DdyA*x7kXdcH zyt?S}X8v-&_pt$u>KGox$>k?}P!1=s%mY76~*3vYlUi-DzuTM3D0iz4UAtEd(IkZ&v2 zGDkJ1-&MJvu#ah()9aa=)h(#?D7`9J%j|eibu-%n)o~xaM)s}z|DH_0I-lMruLAY% z(U77Fuidx7Tv3t3Z^#;bj354t%y8d?&k<%3EtqA#vHo#kleb$CHsnlvcV*RdMk>r2 zjSi}NGY)0!Q4h2D4q(;^dUBPn_Q{^Qn)L9~j4X(;WtK+%MTT9}WU`&WFkKg)f zz4}A?JsB-j=R!B*g%&8Hssm|?3;Jn(bb{C+_&~HBgv+Lbp#n=QpS;n-qW!(uQolaK^Uhw6#t8;p_07M_MKB z$E38Y??m+Q+usj;sr{Gp_2O zvJ__JR)19W|6rKDQJ%ly!pm;=WjnvAzw)wMeR-_na)o+RKW69}oHpBp`RlH~?B0CY zuH97O-{f9)+1|K`ac{C$ZK^N6Y*%mE+_))Gc)8zvnaSEzUv_z%y*$QWcB|48`S+Tt zuYIGm>T69u|LkioXMXlIhS4y|@nrIshv++F$W&E*jY;4w+fZ@ii_o*br*8MdAIELb zzY!+|=bxUpkNo#X$zObweDCLruxxW9rI55++F87gd`EN7%_xJg4Qu%Rs^+x|q)Ntaz zVOCE|!?ujAIR!2Lo77Ej`ER28%q3O$L-jiy5|I?YNr&Tu{+qP%n=+JA8y{`2^362) zHW-L5@=)C6TCr)NUq3sL>u5OGpeqhskF|L7LA$Vl9NTs2S(LfE^vFF%@x_r{7oWv0 zmSGw^_4S(CtykhV%xZ6|do(`Nw0eDF-J_U&i5F-wrO-e8XYWiz@wK4|AZ?7VrS8(W z>+i)EFFxD;pd-HqKdWBBDgK(l_)RpAe7okU(2M6cPzpYzp%f?IKK|@8Pd%hk-jAx{ z|Cz;AQtgpKeEK6m(8};VW`>lY4)X1zDq6**XQ!afQz-K7_h>yIDesAA@m1BVhu)*V zEHa%=@62-I$>(4CtURBeX{;&bWqv}H9;187^EHU2 zd>%jEHdd6HUwk<~@v|&ojf8R|Z=1ufu;CT|s*D(BreM?V=0Y$7Bx`zHp1S`(wSf9U-hsBL-^EV z!;H$eu2xiKZMfq9=3`E;R=@jJO||y6yJnGZKk}1ZV^>l7q5r-Lj;h_HqrIp;xZ&0x zZM?O5#)j9ge)Hk4eP(QJoGxiq1tarv-3`t48^F1#fJNM2{71KcYTojhA~n(-%xGL&9M$XdB`|w+LPa_9w^C;yXc6GnV6@l z&*XM%<2gp0dd)HQjYe{M^X~rS7kgAaeMhN8n)CCQ_i3Iw^m5^^5$yMZWuFT5wip>t zMlZ`3%@|WN9&P!Pqow@I&hi;Fk=v!>i*n_I$H<&DzEU-)avrJku3n>cvVZWCeOg*+ z%P>8A!fLpw+KQB2Y~$|DxJx zKdLT2pl*_AxAP4mRqA)T2{ZE4wP#wDO#(%l4rjm5vtbc1$)8825PXXMf*Udmm?-Ui zs-u=SW}tDFEp2R|bt1N1$G*A@Ah;&e*E}jvkZ_UUVITf975u2?G0t*q(8S8JDsn7V z2rwbxC-G$iKTZ7vT)vd@;aW1e<5NjWX)?PaBc_k`qKX9Sj>I)bwD zd}VQAkE`dGUFH4>6ud%~ zjdxK=Q1xr@4YJ)Mfq<>#HKY;hQLN0Ex@}U%)Xn&E_|h7rQ44!6%>O4}3^K0GOw6~W z71&qGf~|)ip-%gB8r8QVcGvw|w}{IyX4&PMnS`$~Y>g+YsCFu$XTgkdsc)sNwy#0g zq%)E!cGn;X|1}TjEi=2n=3B;XWphcl(@yp=LWyr#0M0I<%(q2sz4X?39yTn?E?Z}I zpXXaNzO3_8e6ZDS?knEq2QlJ`GyLjm`HD}rE?=i!>xbO}a&(6Es1Cv(zJIkM{A$R` zI%@e^^;(6^z2b%C)r#e71J^3nxLxwY%ciDoORKS4{elY&6S&OGO1adkNGMLxS?eeq zzm~|6!t`?rt6XNCK_)>4$*nVFpCbP^hW)OA#t-l`G(lCxWPRKtIY6=y-|9PEscdxoSTZrH!{U!49#6 zofeF6eDeQS(Ct=GY1DeO+iJ8|;Xf2<*dJ%QnJ8S;k+>=|G=DPHMCbdT$^Y@J$DNiw zq1vCj%j4Liz$S53Ior*8k03zXUUS*yT?Z8cg%Ls2_GLZ_-r>{jZRTu8DA1ZG_7cu&>Sm;)cDxq6B zNBG*FB5rR;QAt{VQw;UeDjZ5l$9&q{yvh+Hv42REgz|qpt^34f!b{&(g71=50dBh} z%c*wmJyVYEO&PmpFe90xi#w{ynq%2;cIDAsRV{`|!&dswI(Lh%OC8gQv6g{0>~T%Q zLx+gEB9TVjzzrs-S#NGw9z%bAtIbQIcJZ zo34<(Z>aV~^e`{VhM|&~d*(})ycLmMFvBE~TBT!(CooOozTWO@%W|Y+U)rldLL3bL zGOaeOhk4W26_DS^o4BtKnK~bL3r&nZS}}Wu)h>nYI_nqQl~Z|SG?~uHw2nCE7iY_s zal5iz3e3l3B1D+W?FsHwR!7CH7tOA*`bp%4GDc@9QC@0mEEa~|Dn7Z&b)B`gxR@>rYhslAYh9a0cE{5ndKe3Rd=?`0I`sQTHlXk z78_@o7iiuF5f$bR_`nvg$B9P@x$>52hrd6}7Ri-tLH{Vt=0~j}W|j@!^U3;;^bq#W z($SqFmR%wXrLL{Cb}mY?pG>x8>MaCx9Xz(^mJv9bS!WP;f{|Jx@K98NRm<9!BlCiu zXw6#$b_W=Mm}Q8Cudp3Md4jJH+K0QIA*{FMUN*?4z|lXnmUL`pJdp5Fi0qv~BX#pC z&6SL-OREyStI|%cs${A1U)gW7BJhS?KYSMt8~V8OGn#1aV{~@h3%mZ#P4%LiY@qsf z8qWLJ_EBnUxtF+d&QXj#yKQ)mV%*_vepbb=_E(EDG-!q3G-`C6Iwn!g2b!l2YW~GD zYrd<&;-I!AvVIZF2m(-3=U;=9FxV4VQqD7> zva96}(x4?5#U|*~8Vv+7_J?UOXfI{IXYtP5iQ7rD?RT1J=k3#=18_$>sk2rUOjj}q zeOFG);(#258BH5=CfAXX6ia2rSWI+8t&<5M-C|muf4WY#MXc7^*90%eokOb=VJXYT zh-UPt9Cph2kJICn=4Jj&q?SCXN(W&-kL?Mec0vqGi_CdHW!&SJCoWo!8<;OfWl5ga#5k?f`3$M+d`aLc!I6=Cco> z={O9CrzI{*dy?_W&qiTS;XHF%l`1mDQVZv<6n3!4gt#rkUw9g|5_v3tGZ7Urj~?{# zooIW5d%ifc(hwZ?mTZ2=?0H2Ll@lY%e|$R0eiMs-yH4aCA6RfI%#f*pv!C&SnpYmH zW7P4P$T?#e<;pBul_c@Up~+X{#rE-1qd3PqUX<1tnAoUJ`gnLlW~O_7XyU}cl+aA~ zdfE_5j)_;2^r1uNg?Unn`3ze>^C_9VN@~25?X4ln%Nx}ulHBI5j!2ssI5T3s#O1a{ zreT0W_ds0|sdKwby&DipZ<+U*w>jp_cE%qyejND=g5}e-Xcs^*qlX+ z6DMG|PKb&RnW;=V%6obO$-p~7zwJ@tgg_JP=ayJ@@9aCy#~$p!+&x>PB^9jJjd^P+^pUA!|6Lru-=? z25r|()^y0dKz~#*lgTWvo&YQO@>Q15r({s%qH&3BPkHB(-@ zx3mOiSneFMH&3f3+rVCi`&?z&Lasu=TM1)xS0wyoQ(*E^T~(+OpghZ6CTw!2AErzK z;b(JqW^!RUm|(5Fk9I4#^L#OJbwpO2TfO|{=~>;qe9LG6!IpBgfz8t{w!O{_l_1jlFz z8Z!Sejn@ka%-HAsnPvUym;NQ~zRTwqAIw-nRfnQg>=V8zRnF|urW<>o0}qkn>E37mAWW6|DeeJU z^%r}eJ%a$k-p7sT(#D2Y842l2VQWdCr2c5b(7$77cDZwo#U{`lXZY@N9-DEuJq>*{|BZu5bYv5bxwP$~xGFk-^^jgQ z8aDs+o~~JeLF)YdJx#dj9t0n!)V|i!6`6mq2da>;iY`W9SpN}~Ht8~DsAR%Z+LFXp z$k~u~Ukts{PU+Rt83}F$oG&)GfzyPEH}3?c{?1zvv}~Sf`twYvX}ZxgJq@*IB&K{g zVv4d(|227wm>)bpEJrGiuUpXl3Ylp-##5g7i+;Vg{397zz8*=$$5>>TCwFDL@F9jKUwcM?8fc6Ji{wNIM z09&E4S9LhUhW zLoAYHh^WrkhOx(Fg}coe{8H!5#X+gNyzoHtQE%zF-Ca}KyL3l(q!y4me_FGdB!IlQ zG5r<4YNxs3cA>jaw&eGLiB;v^2SIr!)Jrb|LY7A5u_Cu!k{2s-$zX?!>LHkOk}Xo9 zY|-nlMitn1*`bt+`qhWFkr8vNmcN|vLU%3L|8i}XFwwa7xs-7a;o6gGlKqlEQvRas zy4(|6x1M-3?DV(q{v|09)E9WVttA~~^DqyeQc?AWL}ieunk$KXc z!mvUWYVHj!d!3o#J?zD`r67a1!|wguyP_x^L@$W&PtAaZhfO{!v;EZ|?3ldXyI>GZ zpOOCK{Pc8Mdii{L>Lg+WG99~`_|Vje=z!CnGH{sB)M=}5AmohbHqWBik1-H5AN>S1 zs;(;t)vn;}scQD)#}`Tw{^0{;iYTx`X8Lh{3vF(E1fxSX!CyzmL4-P*a_#8*2UT0D z+v8?M&CL^BRoZ`2WjmV0`N#Mv%8qD?!fq8OL}?c+G#MyJ+2>YE${viRCrrUT9YD(3Ql0WX_@7U+UaT{n!})N>=iV*pde8#iO2r9NmUyXJAODM|Kk}Za^GS(qZH=u1nt?!RxPE@Dfi9`%9?LkbHU27fVKma14WUm%MQ0 zvSkVBq?t3VpkXmz}@$ucJ zT$Yi%BFW2*>d75hxVh$X9m*IcvPKd)qX#?z-Mz09k&$@En;nk95<*fQ9C@VXE!&!u{C?)7QwdUQ#cRA-9eZz*99t zY75B9FBiIRp=!zYfF`*wW2fabGTb6(WHNH*2SMi2c$=$I6S=+m&dt0aS3tsh!r=6j z9B_5b#;rWorG5!y=3lhTvbN~wq8ZuJFx6IwX^7mp{25;tt%(oUYu6B%N?9DW74~z$2Fwiau zBT0%0#HLoi_XT0ZhR&zg54MVOv?EEF9aj$1 zIoe4m$Q9HVOGAw$`}cEfQk91xd-zF6eI)fX%oUWMErRb0D*xkdND1(# zt?2FuA`g8_x&>+fFJQGVh>QOI%jEe1UuB$y#)rtq*mu|SEp>l%o;yJJc~6k@#Z#)S z-(}J+v1#-(mn4+A@v1&H3l~%_Bk}}+^x<=S(Tfm`!!^1=tPh&Qvat zxusUxAAVroib~+g5Q%K}4i2uf9K^iFS(vs87kPly7|m zfnyOFWbnoUfytEDpzQaQALTs|%HP?h!k4qJ{`X4!l^O#EmGW@A&RP!M%4Y1z$*w ztE0(DG`iF3M#YM|IVIIOCyYb=IbXYOm%m* zPoO(q!7fS_m2S#Ynb@H6bbQ*=?6?B@nY_FZhhVo|`v8TNFDRciFDplrV|s=lK*y~< zuypmr@pzU+K+IsbEKe?9I6g7Sn3%Pyej?p5jU1LE-K=S8MvX~G1lS_1@>JPr6C0jQ z&zmt(dNV!9lo!5em)gySBD!zxBjXz2Mi)(_FhdiSE^Pw34ON>?XcY$#{koi_yl^~p zj73%^T9Uk#mL(9XW1w!d)@<+l-fPo znDYx-rW>x6GArn?}1o7iH&9?&7YPherjhz9C=|r zZ&*-)1d0w*021Jnzv48G7U}%ikFY0v55hJdVaLqhJ$6o@%-=mK zk|T_&xWI2$K;79|Ho#5EDS6XM7vt(nZhDS&vE241cCprJzwEJ8+Wo1uI9~+*bp63yg4OSyL@)?Hk9&>bD^OvTHpy88nM-R<@@&J@b+oLlz; z55RVNkJErQf7o)3Kj^NDTiBOOh=Y7vvR+2xB442CaNKO^{jJ@BeEY^zj-81uhZi~^XZLzjjr^w)TLn0Ou{{%mcCe1)={l!FOjUrgU7VlS5xbO-Ns1H$0@x$Gr zTd8vNc=tlt04oy*DttD3yC~j=RL^^ za5VRQ8N`W*7c6;3-h9V&f9e{1SK$jh0PM8}Sy(UkkcUs`Qmc@8dF=$B_bR+$<89gN zbIyj-Kmh>S$RXTKzLe~WbaZ^okff7J&-V3&$E1aHV3bH3Fv2*{bT6!UBs3fhe_%4d zy;`X`zEA*Dj~Tj4?`K?ocm>DjzQ}l7lqS$?G-ggFxU83$?2@x(nzd8#<3b8SJh}C% zI=)5+@9Qxo@zpzP93?xEfsmG^hcP3FQQQ+<1HdCQc%Gz#m=Iq?3{gTL^ce5Os)UrN zBfR?fr>9yABtHl_3FW|7FygDlv&kG^qwr5p*z|Al8g8nU{x#I~cSQvBJ^%MHjdq8| zVItBK7Qt+ckkj1LIE#gDF6_&=M?`usbZrd6oRdYqm*=4eljtvuL(L=JWn$~ZwaeE3 zr1=S|DLMzbl7A!Y(<1D;DjZPwaM#=!f?KG$1t>_k{%JOPg)DlxCA9Q?2Tk;;i={{Oz6XC^?*Ngm zXQR@g0G(4PtiMtI))?WI-VkdDDeuK6<$cdvt0ZRKBWs8($~G%AEp4w!xQ57wuQfzo zJi19nOa!T=L%67N(B;jWaEJ=l%{-4vG;dPP1Mx4{0GazfWG-)Z#uH@nLS!pX2STC& zqzH9(&u09ZXk501>W7f(6Lc_^e#YktPZ)0N$NVCkP!(G+>MQFX7dMOqRdWzHFLB}A zCNZeW)<4eQHu#bwktmT<65#+V+;$3!=&-=MjzpUSM z)M?Y*8B<@y_fnOF5(Q#>Ay3Y`WurDON60t3wNtq&M6WFNLYv-=nvqnB+3A3coZ{^4TyL?UHS_v~^Wlx|rR90L$&bn1nYXFl*#P<*@ zwMv^LeLZ|pImvlkuc@`)Jn4JMRTP0o7 z>kjaJx)nfkzZ$ZtXfNq@aQ3>RxD204Em@hvPITmHF+s-LiE?sn{+C--L@v!*N=MI zADx`ADMwD3>}6@w1IO%Sq|NEx1uN20H-WWB!lF9Lmdo5OPNFkHL^{=);3PSfXb&|j z(?2Rk7R=}CrRa`n(*jGltQP|tRur%i?!$plORGm>ZsT3dc(xTxlzsE2k`;At-gP95 zys(gY-DaHaad8Ae-sAcZlSRln_7hejd5=Cg0^{jkYyoQwrz+I-C>0ZhE6oAfoIvS{?kFy|2j!N9SDLPV+uS6M)jh`ji ze@va+E~d)57=QOPGVSAo%Ue`G(ZD=;alBO{v80wKg)IHHYNS;oP12>>jKv|rkCe>I z-M`^U@y=5oStSOX!I;=ser4fOWDvcj-EKpAa>4CqkD~wOmQ(gARStWZ{i8r{qj$_6 zTdw`tO^MBS9i4;Cjb67|=`fSS&4P3~V?7o7j?%np6kcWjjci-e?zy6(8g1DPQ4U>7 z*DQp0Y=Fd1mh7U7{y;g}AEUAMCD5`JltUxIsC4e;%|}PZvb1a!Ws-}Yr`73!Wp|H> zUB*^f-%QUOoZm-gyg|8CtV-#LOc)bS8l&h{OqCJX1SXzRx5_(nwU-XPp;Rp#aZKsf zNL<;@-*=Kjy#J=U?&^=i$ zi;811gGxsWK}b{d4Ai3UCPm=f4&G$R+-=p!%>!SlOrq;__dg%|`W}LvdpxpWG=FaN z%4CfD7kSOQci0}94W=&yXMLdtRjz21y%iv0?U4>S$SjfPeFIVF^GD2)JwAWdXgD8a ze)19Es{Qo|tUExUvLWZG#p?3i4c&c6ym zM(|6j$^aY~GFy}P(y~M(7WpLWId!!!y)!?@vFIhqOqY8sV928jBXg3Z#1Svi9D7bZ-mVM5{2HQ@xukF}f$Dc)3myLIZ}VR} zqdNM~xaBUC31jT@B{|x$5E5ovpUqzjr?;#0-e!KSWwD~RSxykueghCSfB};U#sp} z;MzoU-xw=m?|G_OKgv9tuBA2X9nyL<1?I8kHm}O0G-s!IObnwFv+Q#jglVZw(u^QL zm9SkcU)8lh6Mj!ecR2`%rxQR!XrMgoNw8JO&l0H`CC+sxxi5_{Gk}AGf)V2@6%nch z;@bAIJxoZ_tYBn^&&ZoenM05HwI_kNS^W5E2=1$!3HgHa4r+wFn`m%y`3jNhAmxxy zS)WMkc1hoWFHXOI3fU-MD_iWL9ju7RiIY%sSFlw#R;V?J9gAQ>oB5v(PJISv{}6lL zoOGGWwP(IU>tw1cGR>vCI1SsKqq%q+xcLsoF09mCfbV0_=^6YuSaOy5W43)EY z0p?&S&6&F_OQ{nqE}7w=Aq1Nqed!d#v_<2C;`WT_8`cBud>Lz|0nDATX)f^E5e$xpQWRG?+~ zgpzJ1;$&vkxm#W7%QLG~620+P&#|HNg{g&M=gvp2`1Bp2h@bmFd)i&ybk%qT4q9z( zjRts^f2puwb2?aJ*X8^x$FUoL58s4mtepd_m`byGEtNsgGGWCM3jVy}p#@5JKpx79 zMb^%{h$9gH7ELv~;kHC-X%yMVz!i!dR>|#RS@~qOEC^Ry!_L^U7iA&)3<;*-VcNeR zH}8NJv5as_orAvYG=H+`|7a74+Fb)pM>wld<5<7%cb+1cILNw=sLqaRl4>7zXIMdZ zs&Is>tx#pn4XzZ9l(l|?5R%Ev|m>cddzutdn^)W?nTjQ>@R!e2PQNb(vNU7wZiZI z@;?OHSF1fEnq7ArU1*B6OX2NfMd<=xxXW+t2>bF+*4aQ5YE2NgfVgs4Zc|&A0`UN= zu=@F|BfjgdzGa>nxL)4dy?jGprA)-#oUu}fU%wwZ*sja-6)Q6c7YWqxKmYUNsQDX; zf`nI?vg%uoHeC%@Q?Vw@9YMRl9Dt6@n(%}B0muEB;6FCNb@`a+qy2rykHhfem;}7I zsHaV>{jr-VbGPXnZEEfrLd>#<#>q1>C5Pr>Z-AqK3`y$kySPc(cd^^}*$kJYj3{MjFLvXkT#_@FP|Fy}$4gQ|$C1@!ACx6n1nH84CEKc2;h($1xwO;Wp8)$u|((qsFYVa`h0T&IfSsqyw@+Q1lySh zRYG%$jLU!4A%-5!uSy%O_Kjc-+%%2zhvFy|RT@+JJ{$-*OazrCvOc5lQNC9=8-Qy{ zFFcpE2Cr%ro%MW&ZySkpC6pT{HL-hXUJk+ zw~V&8iZQXYkKzvB5@<^l4U6h5#fe0h)Hyf~5*^a%sYLMf@p`yZ&`fxC4LvhEGrUQX zVno5(BFe75%ZSmf;zjJyi20(FpyaSQIiE))On9=fnsvG%s30=7QWD{ijPMDoDkYH) zL8~xF5>+{k&Y3oZe367I48jF89gl4yh!UdTP1J5G5#io34I`c}D%506s=^$fl8cf% zEY$q)%3W~@^Ex4u+ndzYpL~Gsc$ZMaAfJ5&c4^6flU9b&prj$r5K~{E=`bz7Otp7KGk;)|S62X}uMFoHs?vz)GFK$Dmm;~Zivi|R z^++jCq~ptocB!amb_4+3Qo3C@VurSkdlsEDi;zMnd%isD<-PqYUP@h!kY4%83wzZU zy(jN@b*lDbgRWr5(P&Tjcb}eH@j%#sbdmf4h*ZCo_O7_CQ51wRs!=jI~AfkHopYjQ!PR2C&*d`@rBF-{8ApRz>%2hU0GYo z?Ut0=^BEV61H#<7qIO}c4%X^sQ4m-tN3bG$$z)GZr>H(9dRbvsft^)Jv8gtbDMp7> zJ~j%nier()?+_u7H2dV^_JwLyqhGuIWyYU7U4$01elfZ7i^P&otY5sW3$6*P z(c*TGd4$51+Q9gG%x$c?Y<}Q6UFz!iGn#h3Wcq415f-iaLbLiF^nEpdmM`BMPukM`Fc1#C9+rjtF4>T}sKcrRwPA}~mJ=QN}r z6@foZ3RW=EmqO+kzqzIV=GJ_POAKQAXqXc$UlBgJHq3usj=+g7(=BK1^XaI03+QEq z%LzFlPhic0hy~h0;1~sZLEl~Ko45Wo2wB8sD*ME(La8G*AIwv3#?%$h8M|h!2`Bv) zqc>pfuFich+-8G0%}Ji{5k-m>V5tfcXSCEnm>?Vlw6mTrT0k0S0vbiQzlj5 zq4D}8QiM`Y@#5R&Gf-H+Q&QJW(b;lHTO)rv4uo3&4Bb8d+8 zLLnU(6&1sV>JuQ;r+$w#afkP-Be(5U-sFRdy6B?q2kDH%Ja;^8JFe;Yg3pv{y3(3x z)97cxRb)zW7!9P4DL?Qxq3q9%1LR=A`d8ANNyd zn_K3e6f?@TZzh@Fv41!QFCYe~hf9ii?#XUKnx}oP_N?*b&$)EnHJ(7JW$!q&PwWzn zT|?-6=|g9amtmUdOER({!F-1y$=XGI?+X*-O6*O>QiD@-efr5}TGag$VT!>Kw@fT@ z{tb;`rKyVhe7UO`{@IEnM;wC%yW6h({br_zp^8U_keee`ZSE?PQOu6wgEFk>6g(=H z+nQ|=wVfzdL1joOSfcqd#mP|1s3PqFFss%0lLebo#e`z?GFIaYo$S2*@m*$1V>Houu4&w{Q1;2rN-s^M_)i`zGY9 zR$UURD?Fs(f%}0Nc&c=i^XLhi#GwP(FB4Uju*gOXA&IRPLNO|LdnV0cwvW)weJnw2c7Jui=Kso zJP}#2bwp%A(?xnJ2T}_zBPJhV*V2f-8~g-VA{uO7L;cAMnj+e5phOsDDK zp#zatDFge1^1X=iD7h1NESsO09VpAb!WKg2B8v}K^e(EBnw*=Fyy!)HrrQu!C`p{8 zPLVKodZ=!!t%q0{7U1wPxbS&X2%qqhr&7Dlk?Cq-w6G%iPoIH$wFR`r|G_doN=HJzWBl> z&B>dP7X&k}V??*yi{_puodVC0t6lI^%!a8! z?aU@o2^ogYzkbqHY7-S0aMehko9Bv=v(Jv>qLN!bwb}y{5l?Z|runzhUbciyOW zc4R&7S@iRM>Mj4&JJ5Md(fCj1nd;vA2po2>X2+ke=mO7mF(Yd(G#;`ehD!4wgBVveuE^9Xj};l^zB+Pl$qt{t#Uf9aLP! z0;ISq8ZgCGDgYH%1t!tMibHVmN)kQXvI(9xSHbDCN)e!+@q2F^Lq*Xxif=7Sz2cS4@h|t<<5ZWLr z7!N`_Kjb;>R3@a_6;;y?+Op5scYAAGZgylPJE|V^5|_X4O|0?u_fJtY9%n{+1_UDR z`1D}wfje$pVB<$e{>6ltbV2(;K=F>PxEC8_je(VADoFcOv4yK9C=c}+{pQJRj2}Fh zv*G}(;|y+O7R5y<@-Of{gFb=i7|(icG9+xV!4g5!MkD^=iKy|qQuFB#m}FGJB8`XC z6VH$;RM;LunLzXUb5M|Hn32{P-09$DV?uC~&_zZ)2I?%{xLVwt^Rev?lt5tS8GpyI zIM}_I@Yn=3(s!K$ym9elpTyR_Or5q$og)#&hS3?*Db*FJ=E@BN4Hgn(af+&)fLL!*2A{ygVTXsT!^f@+$hE$SW zObf;4q>sR_@JOj%RA`PqEunp9{~YBMe{A3!!Uj(3K2aUiD^fl5bH|OynL&!Q#zpK; zk#2wgSH-Pk(lWg|IIUwwbe^4I5Pcv`6vjmJC*HK@7XyRl&o?m%44D~#2rCcis$}J% zOWdRj%s8R{@HyRh$mqxW@Ss>pNRm(|Gb?5#q2_jitG10V`+bwtnSO#0%XwT7sl)RU z6P~rCYSD}8uKX?&E2J9Ah4R2(1==xp+YOz}CnTPuZ2pZ}?>`x4e~!hW?!{pM?fVCB z6$cDv>ST4n&%x&gnb2f)_Mt~&Pxc7-+v-M=|o@UiLP1B z^(UOGQ9IzwU3r!vUUVIbVWv!yx$)H-T|0CVmMz3f#t00xR%Lxv4ini*tK1TIL_o9U zbUQ8C-Mjv}Ws~vbg}^59S%ZdL;df+k#|PNw6sLroBu2MZTH0(MO)1kX_7({1z0DGh zcM2Yo=x8k9iS8=rS*!{aJDNgSpoMS#fns?OB>hW8xr5h$K%R`k-6^#hxesp?%F4dV zH4ZppwW@`rAE9sN?s?WK3s4P+&2K?eDLE!;m4H>~+rpQv>l8K7o*-=mPspJny2l#r zb5`?kBrFV$DsYLG5{mWxz`KI9Hld+M39^UGVCIX$(Df3l4A;*Err83k#l~&7V03zT ztsmnD7g0N^pwon#C>?e>4Iaj4stev7)*}Y{!tZ@K)uawYp-^@J0cc-=^9~a^!8ojV@C&nv=441JdYbH%a*kY zOy)@AT^2CA+}t>UOMTjj_8JF3e@fM69flB@kHNwo;7?%fx$YZ1A9=L6UGbwFPZsF2MR4$mRV zg@1T>3!u)fiP9$}lf~luS}{5OVkK@IWg%WnjNK5D|JF(EO~PE7&qH79wc#04v+$je znlbeR0Qun*xv!v!-a=ovqQ}ji#5(Oh52Y=lvUSRuLYBkB*?mK+j z#W@JhRA}<8>U1?8XA+T2rsAgH`D*Cp($6o|3f!xhc7P1JY6X0EH`kCvHHzwpBSaVn zgUGbKvt}NV*mUOk4~_dK+9bQ@+d>_MWRB`vK{=OG<{i9q3B|o{E#498jOUXhhdB~x zB3Nl499v%jHN;m(@ZcLc!k{kIsO`8(`EE+k?(?x>kwo7Hkj@xVvFlQ1>{uAS=J)PH z=g?f4#B3&d{_X4ynQ-8Bagy6E$59soykA)RCh;54yn@EgC^AKAwoFW7sk|6bldLZq zK87KcE)f+6L-_;eKN0O65v4_~iYBJSctnpPwU>JuL^flm9&%~7EW*Kv+?ixlyBQky zq~O5;cWaq=CfymI3@8%fwgJbH$9CN&ums_@h~%x4J)zNMO$zRRtmq$ZLFm{ifymR_ zwYR;iU)|+3gf{Q7a0Mh9c?g#?7$lHNy27E{?Fl(_UP%615?`@vlJ#f=GU@eeA9ur- z+!b>0V3Xn;!IzsyfVL=m^^S2j97p>hd(Mzk-PMy^0qqGlo&Y`n1jrTONVw5xgNoZ-MkKn-lLY~x5^w}M3m$nF#iG4@iDhk=VQngW5@*8uC~2 z<6~?PtHbgRM=#4?VadYTSfv8Dm`d3iyk1q&ImsHYgR!qbA_xp^;o5q9uY z!S#UL-zP7sQRhyE=hwg*Dc3kDPnQr?kXM)hkMu;c+%X)6w+I|V0>|XpZ!UTxF!md* z)ow3Vje=O1ZXz0{+K^MwMo|=zvCh>1Jf48ZTkVvkPz~;`B$og&ye+pZwOV@ifr?QI zL48UDsb=-hmma=H%l^Wf-}@GTIV^><6Z1W|w92^k7MZo-0IB|Q_nUmnCQeX2>Z=gu zPt{>6?Q^0Z3;UjIIO0wFn&{c6+o5XHq;T%V%u+4o(jGv;-CTIBgXbBQ>;jSTyb9g> zjp&0r(FbdM{Sex21jT14%f!~=}>#$A{-}*BOm)L^a zraa%h??Hx&bhJtxgwA`f=tMjI?D0DsH5EZF1&*W7MowU&4+JsG#`@QYZvTqvzDA@2 z+O_-0BB%MDhpVc~QyvpXRU?MTv0A{Rn%y2jmLeVe+m!vkWqRC#7m$^35P`{}U+`y9 zk@845sdf3mlN-*p0Z>Aw9ROgR4HtMWP2!`mN`zI@1g1nyV94~wT{e(8m#%0bte{R& z&O+EgmKyLPn(rQxFrVH$d2hHQyg!lWR56w^r_BYuwmWgdOo zp1^RFCXjQ~i6I6wXF>)M`ej{90LLA&puVm2mvzo@K763#yBT`#at`4el$CXGzUa0q zFc>+S1Z`1veFr};-0w&_#0u9t(J9KAkqz<-@ipOVafkf&u>KMb{SsuNv@V+0F#f&>zmGzP^@tcR{mQxrB`2QF5@ zWOREO1>xZA#uCzF`mXbHlov|7b{g2VY)TwLilEIO6CbxWhCJWko8+91WY+OLul*jd z9fJEC)Mxowbz+rz<>$B&lMydBY)V|dO7FJZ79}Rv1eJYzefTjMI2*d}TaqT4R5ch? z?Z**9t0M8xrsn2V*M8HgunSKYKJ_Ftmw`QBRTg2s56hSB)wC=Y`T{D0pGxi*?axHk z=+9{$1OX*(tB(TJ`d-aI(6ysn)zkX_X{i2{7Vb|!*T4Kp{S8I`T*NJSjMtM>5H0r)m zw@UJ_@Up|cyTa&K6sk|8)nP7a*VoBA<`i$6QUfDir0<}qP9?5)tW7E2Hljutm#0W( za2DB3eg&Zg{MARiR5?&Xh8*l(F=&7B4sWA=vVNYelj2f#(B6DS#LXjBY{{`)R5pLF zZZlg*pUx&>Y#qk*h4I`R0bnKo&?jE75Y;{^nhb_?5`hYz_dT^31rVsZ)`{9OEL<9i zM$1z!nqi{-xf$fWA$0IOFyjp5<)X4>f(4mAD-=3`1R<>}v}_hPg}k`Z@svuQnj~B` zsUjSJQ_L)G5(#Tazc7nrr6n&d8XtZMmJFC?C_KR>bBm)gH{ZP|v6)Il{cJlct{ZJ3 z;6g8qjg02Pg>)f9NUy)$Hqyd{kg$$_@X!Q<3@CoWOhWgfR$dcsIWXEMeHBgvC)H8r zU{SZq;&#NhsVsFW3)e*OjVKN+1H$-U8b%F>t`D~b;o4-I&XcPekaQ|s zy8Y1-T(UXH+aeD2UmWJi9*A%$I&*DCf@}$Au?fhQtwF9^HVqSQndMEJ?wv7F z#K@NycwdoxqZ-~N>-rG%{FH!@?%$wc)zi; zvey%^uBLALMz`Z&+n+aPJm9a5kCkXRjzqL<*ht0;6PZ*;w^eWCHjqGax_~C?3em6I zxc(N1_neUMEuD5m1O_zw zAM#s-@dWQN@g0|Wh*F61Fz9q$c1%*Etcet4x4w9eNT8M)Nn7lcbti9ZOW#;$5ZdB6DZk6vZQSVIDQ}xf+Ty~$ zVkObsGo+F&kwa~PF`l}SizH!a2sA?knjvZxh!Ic1V0xecxeIejR;XmdY_TP|wiUZO zx#1g&tKvG1ScM4V2zsa@m4&%vZk-~@jG6J?KxXVrvdCrV(6%dMMJoAYYn<2-N0nsP zR|OSFLR+P?>pO+bm4jEUldQ=mX?x;m)fC<_j=D0At`DVUqp8_Vt*))S6uxEi(KOx;)D$XH;>fU6>d)W$rWcl|InqX-#*`!+@KP6h}?gX zSewdhyJwS`4fhN=$tt?zG;fGa%JbEMn@%7ctc0~w+%@u?@hML=`Fj%fe=y(~cYv&A zSmZAbEBcB@XzKp$1D@mqsU#F$4}^B4uGk^yQ~26&fkt3pU_MH$05NW^%gF3_;%)cN z$!-65yYBegTmdNsb{n$9H#RN8{q{8h=ihn5&+^75^N(P6TV+S<&grjePy%;-10c7^ za4Y1Ns(#Jxfi1F2TdH>3aMeWsS5I=us}o(((5h4g1d5lAtGR3vm{TWeSdo)W_KYdn z2G*1-GcT4c->*g`Nv1*vjg5@RtCO>$K-EeK9$YI9J>=E{I+@XJ;)-o=|1u(NmHkOX z`7a~%e|($!cs5dGil1a6yl^FNKY2G6zs(gt#ew_F^Fu-mLYJh`6vw>{)HwTWUvSc^ zRI!yV8c!M5zb#0lxUHme`oQNCeNM6@#??a+e)SmWcJg9SU4Y0-t7}U+^|0%z)rt zC*jt=@|K|jhk}J3_Y{2lZCdtw$~fn3ZqCoNm`xs22q6p#s{S@zG?PN8PNB~lpUA3Tzk`=}1*aml)+rKM z;Y@>I2Z+G%e}5nL_P@XTllKZGNh)kBb$)uq6A-eY!~0Jg0D=KUK!hNLUQB|XCQ;~r z{Ezns5Ka>0}A_1|nThK~oRPMpRPs>h4<7d9As z35k9VV#Jz%l8_X7{T;}dUmPPQfyE($9jEjiu z>bwMZS+((gLuQasHM1MRuabMOvH8q+=u1~|WCNpU^>ZLyX?Uk!Tw5Wnw!e*;;}D6Wo#GD^-)ez6ARQWbyR zz+8`Of=ln4)}ScYNnC4uV2rIZ>ZAt`-p`DlsOCM!{gXvaij$>qQ47oeg!lnPe?%wl z#Cbqp4IZaFqB)>HqBuZyGT1r^^J(b@sNN_w#T#CsF?S{J7_KSVprg(0a^Y8|p>`kj zFST$+9M6=#TOC1iez&~JXp6uJS#e5`+kT;Y-G;Vx8|wbBfooe2R5!EM_5qus7z&h) z@bYsqAt+&qDM7xihG79z20YjbAD)2}_X}e@n6+ zFU&qg*I>D-UJ50ek}%}0y~Y>)ANJlouBjvc8=ssckibz1U_`-s5{(4wg@9IcwK+jR z@X`V*UbeejgP;h=rJ`$Bf>xuYt(SI1*WFF1RJ2l+-q6-9Q0rQYTe0@8Emdi)wJmo6 z(er!HIYH@epWSDF-{0BA`5L~TS|*Kw&)4`Ug$40|F}n< z=o_JX-{v*6Eq}KA>I(-rX<*fDL)>Y3{gGlc`%vr$#m{t>eBGI6(VL zA#nN-o92lsg-?v+>@*9`qdIa-xO0i%c`qeJSis(H|*Bf|o9HxUTqoL6IUa(AeaTtx<$u*PX-5QiS0PTib^?S)q7u z22Bb-gyvqZy>PA%$%+(6h-BaC{vn|hj6nK=+6bOpR_GMVwdhZ+)-gm%zkY-qt68ART_Wc$l3V?^v1QNTH`~jXh|AAYkiwz6bkO7$b@W zeBpu5p7$YZDktn{9K8hwlsHmZ?-C2UK8!W9>bZ3#__Xp!vB*js zYj#>xdW$07GN{d>OtB2sTRhqjj<;dId78yDbDxG2>DUOU1TG{@xHcMsg zgpfH_#G}4bq+H@H>Ugx+BQz%&`y{2^~H|o0Mo;ntr=miFt%aZv;9H`NYEJfFn8pysHIkU(078#aZ zJ1vTx4m8!E6i2$=;x;}7Y-+QpQKX&D~-Z zrK_~qVyQPe+8EMeE}bo&&jPK3t#|w^MU?6FVfZ>2Gh;_NofRFV8xUDDl@r!Ln#PS;Hnq+;+NWo?qx*?PCi0WKhY4| z5A?Ny?uLLDfJji1N^IXz|B@qbyQb#SI|ADOd}-NV2?G6=lJ-eIxB~zVh;HaKgFcWZ zkYKZ#r}U|=>Uii>5;0o*P^u%(;ql@aCePt(xhddtsq`sITPH0m`G%16B4=x-_PFap z>>-?PAyVt64Rd3MOAT>B@o>HG1KJ5nZJ&Z(-?&uK+Ty=k$RNJB_!v6~Cwtqy9G~s_MCG&3Gr3WyQfIiOjP-;5#ZXB|@;L!> zfe&e3D4ep~t-pJw_>R`5D=#P_>V0+E%L?sbv2fdaH14s#3Q2o4M~_$6*Wzl=jPxdNO;DUW-7mS?;}74BfBPGQ0w zG7>Tx#|X^{PsZ`xZY2r^oBz{|(tR)?M@ZaF0Si_xxB!=;i9h7TPZ7VTsr*WP$%dIq8ev8GT}STs ztAuJfx)JykGMYd(Lq-SaqvMeU1`-@9_k@7U!O)31Xkoe^X$j&}lOQ z9NTB3$&RbIYbl^QM$AD)(!DiR4E>S#NVEy-VJ#9)k%?~BnrSK2y2A&kl`lW zIOL6`G0v1nG5vj*wxQ{wu>K0lzbFNWLM!hVTGM-!v~wb9XGGH8!}A_#V!ho-6Dhtn zDmtmdETG$x{g8`OwB6`2Ksa7a(o2?3s#(N?qj2OCtt6h%FKvRfVArP+sSiV&pdoBO zLYr`4gt$exRSq}kMr+Zq8+eK|P>rGxW#q1~ALfh)u8>nO&3tTHFwBqk*U6uQDZgAJ zqw;h&nhznQ7*uW${NM(qd;m-%&R{g>2W8LHDU(`TQSzKceoKdkHNU1=9sVcTuYQeSgz= z8ZRV;;Gioo!*mY6-o)E_u>@)AU^y%BbG*bxqd79TND2|xmw?^4a?RClAo;x5ptZCC zEVXDCMAk!JpQYaVBM=X-5XakbC&c{eykMHb_6`jTd719`gg8%FUKPV=!f8s|TQtmc zjCL;5Q5p~jb>vDX>LgPYe7!7(1$+vFBq3H}J3`Y?y5d1Z+yN;*Mwx@uU$-Bmd6{15 zmkq>!LG*WslJl2=GDydZBcY06*I)|5+X9unilz}najw&xpp1)C!K8h%&*Du~FuD1j z>Ps+ZoOxarA+_mULT<~(P&;k^3_0nS83p2f3iRupZ_(bCW&u~FpcY^+j-LauS13{N zxZm`aCc*TjfHMYYw0rGp`hvQH?z=zx2lpp}P85X!0&`K&eJEJ44=b|TB}gs!^z^)- z`#Vie#o<$tjK7P#IVbii3`2C(rk$#h24a{gM#sSuo$73Vr|K6=%e#W<9f?-kyEJ;q z%W^~?f2O~ig*Z1$admIeXww+ioCE#G%f%aApRoQS9Sg*Hhp9)D50`A-qIvSuy`-4| zrC1!H+0jt9QvYV8{>^Xm>UZCuX$FLUBjzzj3J2@2h~f9u0FlND+CPg4?bG;XNo+?! z2Ay(~?yVba5a?^PS+_D){Ptvo^*!VeL?gxJ`w zQtEA&L}~iso*M2KB->|#?h`4idtM(?O(y2ve4TzXLdVQgO&BW#;ae&{0=;Nh7$VTR z9(9fV3$Zq%bvwFy6rK02ZWpe&$B{=yS1G>J*?K4mGd)7yao{^j-48-bC`LeO_=HE? z4Iy>~q$KV;AvS?3o23k9rbyw4oq}khSUJ+DRcs`v(&D|6Q0*B|yZc^W(zH8Yre6Sy zqKR0aiC#y@cFYB&JzfUciR0%^C)s|2gJu>b;rKnpUn9Tp;P5?~3(2%6B13vpWxe|X zd_#6YM{p<>es-}tu*9fC5bM#rS_qS0*PR?3GWyrfHwBF1Gnq2Yd^Hp|Tq^SMSvQnd zL#-h%3*qhypj*lQ(PWXPHl4QoGzPN(#1K`isgkPYSXW1Z?;)Bl?gctIPICFuZo8j) z+x|!!*7O%4ME(deI>_wX=%&DCJPsQ2NwDpuPAa%)M}qalc@yS980=^4 z93{3J_E}grtf!xF!-4|30C_D@oOUNLv5OIFuYEnt$Js96H&K!%fd5+NG)iJ{LMO7G zy6vKW`doc_!n-(u0;hpWejRRfk5%jw#VD7MZj#g`>gJk{NAY0*$~9pXKd9b;Lxbqn z4rW}KDTa(Tf{B(k+N~u)K{3#Tn0QH(j}qufae`5@pSX0MyrEnY7U?;%Mful0GrpQM zQ*kA@=YY~d_YtU^8n3DNOFydk;%3*L0`~4iG1avT_~ChoLk1RGeiA|=C<~-In|`DX zLsw0%R*)#L;`@aW)^?$y>#nt4Fr23iDXvY>$VfX4A5)xU%N?mRTQD1?eUolJu=omz z@<=b`FUl-5+vWads=*kBPBscW;~qP6e?05GH-E8pi(MK|3=lXIlWK0vy2Ldfu6&cm zH>&o&r|snhg#E5qJGA#P#O*;rMCVR@J6HLi^@uB#4~~gb ztB@n3(6;nD-uqm53_PRrP5}$wSlDYJOD-OwhuoV-(p5Kp$^lX^j&zFzwu=N}ta3Gq zc)jKNt8_;7(>+dzI*yjuKP6O13NFM^+fPKr4XS^+p?&7y>?a^Sxl z_%8?k%YpxL;J+OBF9-h1f&cd$px+$gZ;)ch5HEK^@SmLL`phc#=fpdvXc&$FA?vG$ z@s&UpP&zl#T)Z^W+>Lm$5E=Hjr9a}zi>9G}eusziqJ?;2my8rA{&DhcnpOr+ikmef zc;DkAc(3L7%_~e=jt2=WRw|VW`no4RGV+my+^XcPtejLXzc4k`YE84Ikx40qnOSN1 zlQPrNC#B})@@JjkZ+hcE{!}$Ey2__ff%szHB1ain{@9% z3|WO_=>)^735GN>aa?fiplO@CiWUUk0uK-vU1Z-2gH4nbm+dpan(%4*+^#EHDn32uuNH01?0= zz+&LHz;YlLSPMJ@>;Rqv{?qagBh3*&75vXwxQxu6zmOPA!N2}(@PujOADr+T1KQ1y zQE14XIN(VpiH_+5o+Q{55;}RxLsP@1C8wmOS<{ziWUg45wJJL&cXeKVLE+0D;^X#q>eB!L=$XRnqVLqf4v{{MTkc$Ld zeW++0|xj`NzGrPdLe8R)X+DRtk!Ir3Zucm#Hod-Om+cBNutaGpHWt7a&~r30hf{dI11&m3$wB~M9N!>6C%V~ z6yzl47UUU4M-Z){NZEbA#GgeN&spZh%zh+sLCmtqAh9H=^0bKlD&^+o z0?k0_k;+KSwiXq*ij#7n9-Nd-enw7VRvJfh1CMB;eljT!eklVG94yi?Fc;cZuB?#F zI%{5zo`?+ z4@$WtqVJ_y^Aa(9IIiaa!P(qUdqox zDFY<+NDFlZiS6vNizSF*`BpknO3W|JEJ#ktvL=cZbHzfT=&WL=CJ-jbm}qy!$;{5T z=1E=NOYC$gZ!AryeCAF}oo-0u(yRp-J*c3FLtSuKkq5!pf-Im? ze|bz9m<6FZak`n@Ba7zEBlklRUF=EBT$P*kbN}T~>F66`z|Uz5Pfp`#ccHWxawl?; zMY$4f7=u9=w;Tc|Sv|-bc zY1^kgOz=@?K5f-|vlB8MGZL(G@I4)CHD{PFmpR_#s%9~|^SI)N@C$P|Dt5#%s?a0oZS%U#k6v|;}s z0%kkHBY=fcoI5{{L(5c>L4>Y{2eGtZ`iCD(7-+phy;>=wZIPGFpwFNim_7^e@qswka9E_{xY-EtVNg%rg50V z7GfZ#4Kd(>fd2nt{8hl7PFFI-Bg-a4+A6*<7pBQeLHTTh|D4GlPTO2=YVf?&A%ff|`k5Iqxg^972 z#Mzb@(IvVgVrKs=9Ld7N$BX>;ASnfj1w~+OA~;~pmg?+QKZ@_F8^vD-J_XJKe+7;L zPJqf#FlchzQt=0YYT!-a6mSms82Adf4w%M6+fsd!o3qB6H@=?*;_@R$a=Yf^iI0n+ zVrNcFPE9RbMX4Fjq4g7U#h}z25GmRyv&N${)Bapgv^o(>9P7QjsmhRI(SbxtBJw}v zpK1AjLI>7Fkeak0G?yqpX|P~WT27Z-)45r+@gT8Wl*=;yUVKB^uV@+wc5p}<$AL+( zg~C>_98xdZz&@7^Dpj(HvW-BI2ktVtCz0b%Mjs53xp|^B9fXqw6Qx{+Yq%K_JKG!< zGJe3~GdqVvhsMe)-|B%Y&#kNSb2CB5jEDNnOO$=)hF8`6r5ZIq<25zE{!KN%y;jW! z)Twz%x5>z*;|Mzm_donCd|Sr2}8X7h<6kD9R_Ih?Qr)YPQVH5-Jpyy zD5D5io;Gm(+rQGaav3>TQDx>xBZRcv#l(HU`uJz-=11;V40FAlRhTb4o|$Up)?{G) zh9wwAM#vv3kGTsb{oJDLOsu}Sm6pJ| zOuA>osFsKAQ4H4{6Wkd?CR0xRhkx&?y*^TN&FbJzHJO66(ejpJp8H15g-zx| zgZV~zai}I(AIyE@V2xF2GI@5JzYOl)jS zQc_HAZcK4;%=Yau4oA$yP}2&%1a3C+Qn~lyCG;r~C8#Ps~Q2cVGRVr2kLK`h~c>g)k0=T=$9m00+_kLWF7%eT!W42kG^Cm7$qb1<>4;a|}4pO)+Rn}7;-!AwXE>_tEs zumo5*$D5CJ>iCP_dGU^Ky!dO^y!gpa6276?i?3|OsnYQ8o9oT5N1QCc9^=iI!SqAA z^Dy6n`=Ud~_koTu(1EwAP*CJ954++In492tm*;^7xH-a`x9{#Vk4%X$e-A7G(gDKJ zZ(k|V1mC;jL}OgjF8#a_KUNV0`SvTlW|&_Aw*VRshVYZLn1fsN;*rN79_ur6CCa$; zHsO8u(p8;%tuV@mra4N#?#)GB3h=3Hd4zd?Mud4fP+5j|CrCrHo(=adfN-tmWNKnS zJxs$DeP(46N(AJ98=$&!+dOGSg!wq)EqsFT=TS%g&pQ5lF&&Zl-q!F0e?u}O%zlVB z9p=0n_5{Qq0vO>}Hp!cRq$t9?8jt~`xWjxM<76&l|xT<95OqO!elkP50(o@Y}_s7+1Y8)uovDy9jd_PzD5}4wHfLfH6eH zHz6-lFC%AA7QU<&F4_nmhCH)8eR)NgH$P^YHyPFJ^JE|lm;vxW1aJ!FE+=)eFiOJ*gzp3Y$?pjnL)(C~zby!~vvDZJ@MM&-wh3(ndJ&iKmrzdI2J{n{KLJ;Lqs(_;dOi_herRokxf^LNp`0cl8gvhb zes0z<%H;a2PoC)ot^p!M=RyZ$|PFi6eQx2^@b3{;%@hyfIeKXM}t6pas93 z=|cIP<_5GE@dG8;(qPeF#`x%Y1=2m|t>-HNM?GzKo}B!E_7SEw@9z=j3fQY)_6f4u z<1jA+KZ$NN|7wp9&!WGeE#4O3_Xot?1k42108O&HWuH7~pA60?ANb_4S;oWH4ZF7?lVb&o`nCeEtKyO&Qir2%9 z6&Se=`)F#n*BXmy+`*A%Pp?R`YDlEn3%CjtUWzbx!JH0o2s_%;YhL26<{zs47-lK(+OJjoK73Cz;g6B#d>|Eg?2SJ2JRky?0W1WH+R+yqkS7of zT!+kF12!RSJq5yxU={$6$<_P|@_~&da32(Jd)f#eEFycKWzS__`#3QH8eEP^8gm6_Lvvy`pheVF?#S1zq=8)CX4C# zdKFHQDd_07#Mm4s@c2^*fDH=!eL$*cZ!O;)=> z_(>4BM2zXb_2%tB7VHAz@%TH9`v~iSa^R8g1mPo?p8y{M^gaFO$p35LD)2pU8~6bT z8;$V@@A6w=C$K937I^8

bX?7ok3*U=9UF071Y$IpVtO`0Fr(r*ORAVT^fWAxo(1 zn=l`Pxe|CA_A5XV>@BT=@ORk120m4S2QXF84>ccRo`U`uj5hUkbee|;_L+6S49MVm z+TMQ?gj})R#oybhUWI+`yt(sAH+7i5x@Gf`0F@>h`-VF>4RCmX-?pLKTwA;0@7!aNwd=`ENU&> zOMw*s4Swf=Ecmm?HyZE)d;zq}2Kv(&rw7$n3FJ$ABXuE%zX!;?||{3@gT;S4hgV)5T-Z$9|AAOz&{u;0t(>nph)vsgkOfaW)LA)VgDQK z&9GO(?1lLg{GNq9W-uYEV7>_RF8r3j{t4_V&q(v9Ftsp?QH}{_KFn}n6LxBOxL=2T z2e2CUSeWN=hJ88ggAo2MOdfgFdK2;k>~$~$;P%E+gJC1h6JU;mses=Pm_x_Y4g+F=G+-M*K=VS(OCH1gZz;?lfG2@7 zGrakEm|q5?jRnDt?1JCBz)OI%JQIJ9Tr0@M1C{$Q+mRoJjyeNNw1ipu(Sr z*)yTf{CAi`5IzK^4(2qN*MaX4HuOP!BL{OU%=ZA_@qOkG;hqPx9%d2DzXGqp-U)L* zOdYTrSPEvEXCaIY>oc42K4A@@n(M~r!tbxJ|7I%mDNHrYDTNq$K0qrV z&3K@4nv@3n5vDJ1H-&5FgtCe-`I4(KaWTo!v$PdM6AFf&PtkDcwW~k5-IT6bvE1&4 zW7`dRa^Kmzr$rkw7OaTKm=a@PmCJqSE)5MIJviYSj@*@9z#X!qed_CctLyxNl39IB zdo6yg|B7$WESRUG=`Vycitxx>eJE{3rhf#iHLI(ms6YNkT^FLShL2H%rw)!!W6odE zaCd8)1Wn2jVtMU$Z%13Q+7PfOk1dEXS}Jd^cHW*noLTL-%_ie%_r`Mn}h7T{?#K zjhV$wti@SW;}xdT+v7%yKV`K&d%H5!rOy9if{Wg_=D5vz+dSLAxV<3ITGN=P(Tj0jLA-;6>t*rDWT_^M8SBeLjV00H z>AsV3jAU>`t#j^eF!H2q&LJc*u*0Hd>0?5g7HBLHx0gk*Q=%2|X*jVugNB`M71AdUv4q`5LZn(0t-yr~WUTMau@Uv@3*Do`!%yAq8uP{l2PxM> z))dustayEr;b~u^Cf(be^}zkM6{~Q*(D_u&>cHEnBZLGqC*-rmOuvD7LWBg#^KTeY;V~d#0mjy9%FDdi)kCp39OX>NJ70>u+rz>_SZ$~Ri zWNh4>-rc?oo~&Za7=OnJ4s}6H>mPh18m3P*%GuFTO#+#-7uS1>Vj$kvvl+jaR@i!b zK{_rwfMR~Aj+_tCSZ?;>W+xEOhZfh@1ytAJTn<|sja6Sarn=4uSBvBtUtJdr*AJ3w za&=u8T;Eeyb=?eDzmu%~uzpLe`04vM)LgQFU0J1MUqr*E+OAR`_IIG9Nwj(5SNUIw zHh+2+!6nhU%=QH}5$SVk;xduxp6Lm%d$6AH`cR6Ebd9da=UqMuTZ3pD^}~?ML(VBr zDnP;e)CcBSYMx~9Lv`C3YSq>BR^fgj+iA%kG@qijGpnoQEK_5%)l*lM{LGFTr>)jy zKUPy``>V^|So5{*Ey-T38)7@*vda8zHPkw?1qZ1qrE5$MP!Aj>`=S^}X*Zoz*~(ph zPHN(cah%g&d#RV6ENYY)?r688d1$|J9_Xz;B7`SX;Wzw2+f<^d*U2r;-m&bEZO@&Q zSE|Jl4Bu<*rfr)lRezWwZ`!DtZpQ(;XGYX6(lqVUoZWMDkEX_BuYKE7$DZ#!`Wihl zq0AV!t2cJ3*U?2(!z?x8MiF^ayasmb4ehdsN(GKSm0N$%o|K=dt5j69P)j2$UD|YS zB{*p46r8qRmNArT>G=nsy?LwFw4rzX?J9Z2Q(E2cd&3$3gfWa|eQ%Ybxq&Hp;XT*k z2MWttc+rC1r%LXiqJ;6sJyhZJPF3prq!x#m?nAD~vtpB0w}R%$ST}1;nZ3A~&(n@$ z$4X|=*f%pwRw|jzztD5AAfQ8W;9HzE!jB1k%@glFw`W?e%jhW$bWP#fcZlB&ghiw{FBi zt)8K5Pl-b{bs7_Fv$WVXrpVrH)$G2&KMr9Ty_m?~h?L;aPC41W-*VyX;sZ073ul9I z+t-C~nrZoai+9gp%HIq24=oq(x_wX&-_t(|EOQ!DE%0Ex$4(iy{Dh{uJiKvYZ{5UR z=cHb!DMN$b?h|a|gx>1%S#?3Zr+Wn44%GYggY@E|PidiNsIIB8xrrP*3htmXc5v|BjU2Z3XcjuZUhYRP|>9zC<@X1cNr}=5Odf}95&)zGHjP<@z;RxAPCD*BXgAd6(f4s2> z_h}*)KE?~B2gl%iAex3!7-ol8>;g*hQruO?4ozCNF?JCpB&9Gowp(y~Mp^tGrTRGKxZcQ(eQz*s*dX|6 z*)HeyUBTPML%T<|AkbK3dJlQvP;Xk*AezW%cOBYI6GxpwyW_0fLEy|%*&R9GRB&$4 z$w9ap5rH_~*L5Z~?vHu8_ARd5@fX7#!S-ek8K)`MdpU{=i}jqXrU#wDq32wEv*AjR zd>#{|(7nmTaYBZO(}rY)mcj3s%rF!VMhiCfi!$jc5{H!^{HY0yeB$QuRu zheoxF)q*;61f_EKSdAmW|&2W3An? z#h}^p{0devQ-MgxF^YaFaNbJ(qzpVBVtc5k>9}UwOM5iOap99#Vsio0YU(M|^!Bt3 zAvL)5>AFmt<9Xt*HJ%6l$hbX7ss`=R`0K@}HX~(5nI;yuP|L3Ty>IGpdOrteB|)p3 zDm1K$9jP1DGw!uOpJTrP2QQ8O`Oh5@F>$<`HZU? zEb-aO)R@{lQ5jm{Gm3rY1N)f3fRJj(kBzsw>uz;BZ*?0U_iK5U!!6t#=D<(ya@^U~ zQpss=&>mZ#i3{BiT3`zrJa^CB2t6j+dY86;6TYYG#Qw|WcEoe0Y%h%m=a8+L?B<|QV-S44AD5*DO^F5w+KZBNNxG{mA{Mocbvn_Ag z!nI0&`&46V(l_E=gyQJ=iSQeomu3CEpIfKccbh*XrnB8R+ey2TDH%-y%N{TDDR&ax z@$R}ex*Ol?w)@nKK4ISy#MwhjjmB9)(Z*R@seoF)A_?t^#=7omCtvs1?kEM}ju)4B zl7#D|+8NSV(_MGG+xbej!Rl9XMxbM_IIcBxH*M9Nt@)fPtb_F2--9auJuo&m3t^#~ zaVna;xxi06^WJ)vSWgJ=H$GK2_gEEUctfCFQ^VpS&obR!yVM7Fbkh$1FF(H# z#kiV2K_vrgY+JjF4;5SIFzLNAf4zSwX82S$+IDtt3mq34m){*5?!|}J#^SWp$;DGA z<9@2mYNE^U<{h20Lt0to`^Ti|^GRsU#Us3$W0)$X^*H3naGW0dLv&AekBe|?rE@Qg zsm%+ArjJw7HNf(r;{3z*`|kc53dFe>CTDZvby?kZZ@p8oIBY!21o{R#j+eX~ zzpj1%>!%v$yk=-ZX$?1ObmtVy-mH>a?+mUq;T{-T9?IeQg4LPbmoPE4yW3T$cj>a= z7j{vlUdh-!N{pIP`#CpyjSE8LRq`-*9E-+;`83IiTNkCX#Hrlkof2rATH<5^jm8qE zY)iRO8_(F5cH^RBZJ5k3(+^96x`gh_j5DFzmOy!H<^4*WiY+@o0}-~l-GRp8wmIEf z%Kb~6sx96(Y|-6YcK#LjFVG|Qi7l#oGu_SBJKeBe5NV#tr0Csrk==2>>W;>}Yet1_ z7R~joE2VS5aqPVX`M_6cr1I3n;MRtlA+N01Mu?ee)1h~nKJMZ4_w z$d(YN(lL6Y+Z|E2Ceyo*ZR2Uq$+~VxH&f(R7(fQj{$z-MU9Ufld~{r!uBWRi?&8VhJbiR@Vhon(QO&(MZ#9tD6Fiphb@z-&*o3P}iS|(M<~y__UZq*|_D1zmE*pJt zDy~*9!vq;EHSC63ci~pFX?C?N$W$e_ymQN_xZjEi>u$5%i^GO3LF>jFv|w+%Q?+=n z+CB^Sg1>IWCFVv2m@L=pWn!z-8?#VnCrLhbtGq5CXtmMJsHcpkB9X9S$dc7XL+#78 zs*y!&v~L99EAYV5Pv~t)sPs&b+?aLQnY5Mtf*{>eQC0`VnpoXD+!S! z%9c$%&bVcgISUrUTu!QWZbx@rNtibL=yO*RKJ(KSsP)FdH{(|+ej~43tsf`T>qjJ9 zVRg^kvNM&d?JB9gwTEz#+UfZaZrsnSzXSRhiMYMW%GFru8b{c+-`er)E#sA~&Yj6r zuZh7omz6m`J$62m+jsh;N5*P)lwG^ZqaKDbEv;gtCCU6+yR?;1~g zB;4>anlijo#%i=5du8Y|#_mg}TNmYed5L)0E~;ghX~z-6wPD)OA&443`*kL2I$2h* z24)!1HnWvbhEFJs9>$%Z_@FLEW7KKml@sL2>$;Mbr&8TjVjQ8xknV6X#IcP_Sf}3c zw=TOHp>!Nd80UW34Lo9!*3{ZZ)azszi{QO@>gehho^CwfRoB?%Z0M@EHf+3l`|?z} zVNhP@Rq^a#eVrF}w{SGN-#KQ-D_yz9jgB+BxCYLsE;HT4xr|k6qxV)BZ3dh?F1xv6 zMW|7;LLWqB;q*rW%j#b2f=DSZL-9bFh9K6{9urg}Th6IAcMG<^bkVznO29v=zUbJ$ zx2wF4MZ=aDnIMzYx((~ZtsZ&vlTdZEyFDa>K7+2W=t_R33voo9rcWM*4zHJ_kg6oh zpSy}o(YURJaeI{9yb-O@Ui4Wut7!4;H<;7&NH9P7t%bUcU16g7mdh&sHteKFU2&Il zXP3>^1$>~LxZ$K@5XYIwe>Pxei!bY$815{-dFL?Fgh^j zb~#JB=pCTA*LHgNR$W59k}rFh&HFjo2CFEAbb1Udpgd*toK*djH_Mm0ixHu8Q}DmFQ$#VJ%lv zoc@O2Id|w~Yr)`3-DUTBTyc5ItNDho`MN;Hvj}L;8$90Ktr?V&Xt$H9XkQ4rf^NO7 zSf^iH%|v}D7~RlNa-6oQLjR|oWr7Fh+tOSC*X4=*p3bZ=PvPq6EyX8s=z7K5g0(H#D)#?mg2db~LJ}iUPA)Tk;&LU)s4xdm?Y@;Y4m=KkE zh!@JzaGQTuiBSe`S6ytw;HJ&vayR2n9r0{X#I+vrO&`Y?>V2E9$;wl(ut6KsXfz+| zZK2{Se6bv-T~nl=*5{7{>Qix9jeDdBCBkr3U2#c`n`ZlHxZ#RgEQIFs1&vcneVd!q z*3W62w?x-h>Wa^3SgV)Lb&|Ri!DxSHYraXn{KI=pozVoqW%XWO!S%R&12h{~7 zF}Pxf#wZte1WMEdqnI{KXxgc<{hemF-CkTRDsO9-V9k|PRMXcRG_O8yXKiQ27MX)v zXgSr1jd@rPyqZ3u!*Ze%+sB5@vh_vMPT)aB5Z$Pt>71{3R%{ZJ)F4Uo#{MKnI-}aC zxFg>QGE;SDu)Y}2z*h!WJM4|eI_r*gI*)Z)pC4wcq1+1oULHJC5%+Q@tH8YhV|F3) z4CPq2LDi1!jR!mHUhF(g=gaV&ro^N9S>N;#8tp9iYRBHj7dq?y-060cmIWd!5_|)m zT7~7CVTtdtKXsnN>Nf6K%8l?yn%wp$T3YGnU+?a$cf8QJz4O=~Ix8l7({LqSKWHZl zhKoKpC>WCu!$M#FdpSQ}G26$p@#)TL$C0{Cou?ZG>tdPZcb!eIXpX*Gj3Mf#&{VBC z@hVo)-_wN%>MNzfDZG$7e)L9D5iLJ{G?_gVm9J}jqO1Alyb3fWb#B`@Csb;+=Ff35YmMCcxlpmeckBoc zT|y`8gXkgRuBUZ@j4rpHKnPuKH9zNTOQTip?-S11ouJB^DVw@N<&5fV&X74qE4EAR zRP7i`CG?`;atCA_Zo`YEv19x&K4T`D?rp$*t%hIu1gO$SXjv5&vj?o@;^ z+F1&tkEi~1{Yaxvr99m`$a=+_WyX#e)i|ZIy8KMtluqZAPD9?X^3eou=_+cx=X+SE z_#W^*KeC0zeV8W)8S1^=ASeMTr^Ok$SUxfQjWqx0g$8Xl%65$HbRO>jx9n=yy&Ci) zq$qrJgt#USyiwR^mHL4)PkqQced$b#;T4~XG>JdX;hhzWhaw}}NJ_gc;Qo_(j-XDR z20a>$fW>2fCzpD7ylnk-bRL@r6^4Th=!dC~rcc`-F(X!d%4sj&1t>bp&nHaz~nNc?U{9-6lMQO^LTVoIlYDVr-;Oai(pUCsM7T1o$hkoNXPfXI)E&qoKC>fx%-J405(mj~_*kk%JB2u(lqWF|~Y6EtW4jSf8hyG+XK5 z=QipaBJ=7R9c8?2Csd!VG=KL$=j_oils){O;6otqrg$$>;C*f{VUmBtv zeb@FTwYZ)qsNHn5AEhq%50eX-w-n=7fe(g0P2yXV@`3j7*@<9NR2fAY3696(j@}=r=q|WGajX zyq!{3B4w%+2aSL7w_RvQ4x7IgH&?F6$q;2}l5Aav16_fTYxsa$S(;1WPm~FqhFUz7 zhl9!YavUVr&?L+4P!aJ#6iPQak!4Z$Dm>uc$H&(C$X3D;x3Xi2a`92dEta%5wfWMA@;Ty2ug>LBu64}^}Wh979^NQglUt%Stg*shF7=tSw8P-?Fb#PN0F>>7l5F;+sVPwMO zcnzYxaJRHm=htCm()B8xrz<+B4B3B_zai%$YNt-_Dt%WsM2x{~){)InXoEZG9&!w$ z^Y~e2rQUdp_RSbAHe~|B@&3T1>=+jsz=-pL(>fyg5$abi`sr@Bv%cKq0kr6TXgB@P z{%=|VUnF1+e6`(l)fLn7WqUO382%9<%1PW|$PxFh%!SyPDB`(#{ziYDVH{WBW3kBoO8m&7lb)ixSr{CfLrmZ(%TO zr!{`iUiU$}^MiJS$1qZ&;q06)u$?{|+ELurf%8t?->4VHykhQJ@%HAxJGC5^M&ZKr6*o8a-3v*O#K=a{FQ>`d0v z+BlS*FFO1y&JSh%pK@BehayJbP+pv(V2$YW8-`!7u}W!p6MD^hoK(zE#~oUKt7x>v#0o+&whTfp9-DJbCGA8s3BuKkK*j+1xdhj%0LIv4F7SD&k4= zIJ$C}LdmlRtDA%94G|{MHAx-!O#2L~qqZvJN=1e!WmuYvI=h|W`I3%fP zA|(gvC8}v3@(!+xPBtrnm1tF=&UieXoAU+iiiznGy%uS%DddUliSJ zMfxhHG~f1H${1v5JJ$vaz8iuZBW$N$R{mbg&i6V>^h`+#sq{FgXFbZ)#}>4oIKIbQ z7vKIy$Vj}xKCoxlfl5zjY`eqm<$M%RuKdg$RM^lZIA~$W3wyfp9L57|2z@h@IX#Zl zJG^kkz06QL$QjXoQenL%)W|-5ljt69=ic-ZpPc^vJ7F5_7?pEIyX_%LAllPHP3N?B zsVUKfXUd z6YEo&r`P-H>u++?H%?Hp+9f(|q{rb@rvb!ZDr)^vSl@P1;T+T6`~wCR=L7Ay0hF;l zN!ha*8*rffM^Kz}DA*BP0J`J6+GF4J5}#cB`*(^o+BAi8aJx-K$%Ay*yhXx2+ih}c zsdBds7CqD`PG2wJMPEYot%UYlOLPuFHk@{N6G?Il^Bn$J>sxxy4EHR@-cJ>Km7xp2fwHv+}PAs z?I^5kYI8QVS>MrGzG%Z&Dp*>r^rcI`SeQw8s#-DeN&cGeBPtY5{RG?blLzyB!fkEk1=WhyH1Xg)GjnpPsl=^K<6w*77FaOoQoTX|cMO1h$5 z)nWlDlos1xX!|+$wb}kmEw(?=ClPt^%J76UFvIm;rkaAltTuCUxnH<~{*0VHjJ85I5HBrsCqlgvz^c!)l+B&`mpcKaXo)(eQ89KzQ0WT3Dyv#nyT7$DW*>$Cx3DQ(c+()OKL zKYR!UF5MCEw!gp3W6Rp8JPaf7>*rbBqBi=?ltX5nN4>=|>tfra0u6KT`5~cgE~V5( z7j1J}biap-r-&2L?}hre} zK8^J!ZKqnv#21NpQH*RbmML({cYl2$bbT5Zz35)3LdAUV0sO$;+LiutnoYh4H^lf- z#vt$JU|&~~5MK-^VtFp63>uinIXM*zYqD4@t+N|?L4%R5kjsinx0Z$N)+@@Qck6$! z+p!3yc_$Og-PXWYz3c9@R$<#23BXm>gVO1q>dT&*z401LZw3FAe*Gz4?{yk!hFxui z^7*N?NZGVdb7`@EMEc~Gx*w(FT~w^A+%ZKvv!-EQ(UvGkcppEgw0Yc$ z<;Mq&|Gx3#*1C^dogcS07io1Lw~jLg9`_i3yYXUc-T7A3$iexRmN#B#o#9#6(7GA# z((!JqSoHgQ>kR+8zqM}0cUZcz)?$6F>1^wC{Xu4KIY`=!*BmFAD%NVzYWH@y)rw=c z?NlrF0FS-gI#%UGc>$o4*zsKCgBLH~z7;ZeOc&M{C7$ zZRNU?O!HLfJHBM{8>V3=KAV(Rd@YV739pC~m0kfdgxA8l4XsnFz3QH6rBQ5KM2*x9 z{%mRG48_S&t$`15`gf(G3||PVJXpVkUU}oj)@o;Lovqbb*jkaK#jt4oOmM8=5>AlD z^$1#8x2`p+TWId|wDLTy-|)OLpZ zZ6|$;5FB3;98!+GXD~gX9W&*MGiZ#`Wq8XWuNXWCefi(eq8=bQh6jF$oQfVn+xySu zpYEVz8uZSu`}bR6PwTfki(AI413bCo8z<0rqjry@(zUOyH|ElKcN%hjQhrXcWvI99 zY|ECRTFm{}kvo(vyNBY-YIZ_}!55!fVKf@FxqrT?+tb3O@SJPTi1z|LEw-K(BU7v| z5%rd?vt?e7oq@3>NU3XY;f#{M?WdL?m8}&IP~#fs41Kh@D*A*SH(MO#7ite_z{F40 zw(nYw-k>uWG=@I-{QI>BX8d@ZZmZc<#rj}Za;i5?O)b!yn64YW4PW^*PQ^sekxQT9G?QB`^W_?>&_AH!8=1{hGVW-k8*vYHt%N6nlW5l5?C7!%QI7e+y{ zZP&=kT6=b8G#rrj888#bc4x*&q$t2r)7%CuR$bZ!YRhf)Su!b01ycME+~51$0kUWJ zd3|5MmtN-HbI+g8Ip=de=W{;)?%)#6LB1ZSNv4WYH4eYXA&9?o&M=_esJ7^2Y!0V% zw+}Ay3Vka24666Ob3*%ot^U&}-2nm~au@wQs`(t#d{|tyf3SC}%2n%f?;SkoZHRzn zYv#Ml4Wj2o#|eaA5xohd+g|#B9Nq(h-3aA6 z$GBb+ql8wnrMk)=Sm^#eDNzQAJNlxzsHpFVGHxCl?V_V-ntYIYn$Wg(yzSvj?RSHL-w{K~zIaWI+*d2|)fo5JN>EJp*nDq(Ud`w$Z!-80{jbon zU*cXz+U)x<3Nu>t1^gy}Cu2~ePq2a~aQ%wpfq4x@eLi;tN8&JV71UFHmn1drWby~- zBgP&B)-gcVhY#Og{c6A~*V8^BV9xk{?LH|a3OHL(M8SDrPS&H$qU{k)Qg{9U+L%5_ zh~EfrcroPixPm3r{mami4$?B&SB(!0vb0H%lBF3_x6!cQV>ekh4}|Tduko`gCWFPk zif`l*WZ45P1iN`2o%_N-n5nu9^NxH(ZeDxQ`@)`4ld`vyQ6dKM)*5LSf6{^VW7rdb@YKQ_a3fU%(iZFX^ zqEAVPVTfBnCZ1<3Mx(2K7eR95 zZ>Oh(LgL;JR8=b6ZudO-7j>za z_}zcfHEbw%?kP=E1l!~GY{=U-aSR4mSu%c`X3CfvZC*+YB zy9P=aQ-INYE;ezZ653F##Z%rDrap~YvIH8N-I;X3Jz6I{CFhWuqe)snz{6k? zjNELs^}T+x$&#ToIhpr4097==&r=}B6`UZ+z>l><%Z&TR+R2le)f3H>N$TfN%jdHD zx6_N}Nc(2P(BaX@J{`5>c{XbIED_86q}}AR{A@L8*Z4}mVVTlvGH&lTc$GQ%+UMxS z+zJzE|J!i;*nn?s-zGD@GT;^ZS%dbyw82ZdsW~b!(NhctZ23i}dG|{LumWtXIS^6f ztV}yvdhEHQrL`;@(YCw4mODn*nA)D}57jEWclFnr{-NGq9oOj9%LDF#7WY6UM<&>C zgdliPEKv~`eFG`L1Pt!y27qie>Mc_zJ@A+AX9wDz9SA%-Q2%*MgAEJl6XxXV2HPod z{Wttu)4nPlX!rlT`!@qEPYxt+R5sYyN%iOW%DS(9J@80E_hSRlhY@_k9Iqbe*>$$- zhzB)yWdw!FAKBXd%Yn9{fk44PUl%GD7+Or%DdwoL!IqaKD(dBTe)-jkfk!^*et4iI zf1vMaC9DN28^2mU@W{#Tya8hPFg9=Q2L@1Qt+>I4_Q%qSAoBm&0GCK<(_NlK5hlrm zNvb$>FoVDZe%?O7mJ8aQTDdzL^a?s%!&DG7Ebl?Rsgb(W{$JQuff# zcxCw21MB&~+<_{ykdN&3-iR&LM7%kD@J=}qTM0OSlULp$@&~MbPTOp>3iw=K5*4^> z0E@C{ZB$p5$~|MiVt1v9XGiD9>CGi_yFPWMWO=oG(LPB*wl*hOTP&6o)3o$%3Uxz> zRDE2`#_gUhV&#@!N(MPNJ!lUe7|c>NMWoJ^?5~zCdY@?$AEpb{11~7baft zaEXo?V7DNLo?gc(&zHK~1^0Vhzk`(_;8ma)Gd0|4|(UKw@8G`V}AzttaV8|V)V^h1~+b4GR}gTJlq`~I>U zd{uA1R%bPEs=#;se!*qHlST!;?T3KP#c5Fqz~LSv9jjkEM&oo}^&7vw5T5JszC{#p zr~28c6&#BlN?X2-oaHb_0m{>6n5~*8Dz9Sgi*@0%#_T|OOJynR#o0ks97m9YNWpTH zC_!RYF^E|uNrLK|qFzk6NlDVT6wPQ{6dmFX6hqNb zhL)(0A5*HkMe4TD#zC!i8`aH_ewRH$QQ1F3q^W<`{0KcHU4i;Xw5dNrgg<J3_r_ zxw8uwKY6iGy>Piw^k4m!UWStRA=%m39~Mn%6QN?@+U?MT*bJP<_-ucA24Z4qv$U4p zD8o#@p1ICoAT$oC4P2-Am$~cusVsxd0qcQWXZBxFsDKFVn z9Xzl3qr`N($ePzLV}40x7)-wup;pTR40rzBE0c!znrXw?OJ=pR^U;&nieUUa~ z$t&gKvmRh9Uq>y9;u0=dhAc2D53?Gf44*Zs-;&X6XYQ1iL;>}(zvb_gE=yNt6GN#N zla#mMMLSUkwi2}OA^0sFhY!&M6ObG%X}T4Uj}UnG5_mr)@SeIbHlB!9s8WjldEqDHdE&y@cmm!} ze+utj#%lln0q=+Z2fR}VyhjMUdne${AbX4T;04f7aGTO7FWq?n2adlgJEtWtjR`u5 zISnC)Q=@!g9y*^s|8!Blx_BC_tO?m8Hk)8x>u>V;bm!k&{qF9D3vCS-0u2}XmdAkB z)h|=0O#76C!qjGdP+goQ*#AEm!$$t4tw{nm5>oly5W;m%%gY!w=@`vYDhRWiH~C18 zjb<5b<~D=2pyLcrL0SOjzBo%!6s5uml!&pYzH7>Ca>zv=@=jCTl^0qAGutXJ1j;WY z=fK5)@C=aXrA(U}_$bnybZC@TiyZrFs+ zCW4T@E~VEv3#=nkA0&)G@d9b`K_$`OoQnJ;GI^&GyE5AJ_=)fa8XT7ROBPM=3_qsd zPb&LvoR_c`T)@FqTtA>T(>p)KFjp!cRaAc2?Yz+Hf4t3kA@J~p`m7i(fPqXja@w(Utgy(N2o)ZY02+n3qp2%!$_ca7cS*=f#uS|nrxl&${}KQvA;5S`dfzulufP0n=|z1c|J8p>hYdaQ zkJW>7g@3SB7~1;Fk?!diAWN#z*K##xZ(OZ)?H7wH-JQ_J-*`f6o2bdAvHz zw7q-2`|P91DDRXLxLL@xs&)S)&zVX8c!&?f}Soe*tlm0cpG{8p@Rq9e?5ox1c?=C z%iVXLg^=qogQD&;1in*@`>XRuLzDD;7V}(x&HL%L_VTma3BA%2~uZ+jg&~ftR%U@&yZ>-5B>N|1X4wBD%m)e z_UpG{=MnNje*Ww5T;t64`4k~7$ceF%A&v)=zecEl&=ttj52*uho(CDKKddICCft`# z7?&XB*iwzUiO;Jy;5r=@7KXP3&b!|vW7a{`TO>d55_N}5RG#RrJKwr%Z(H5@K;8M| zDKUMi;Xw=M3ul7Gc6ZhJ*5KdTs?P_i&iAn~$#;b{4?=wtHF=Te{ zB{6*s3is3JtL5U>W1?2UsG&1r&n@yc-IM3N^v<{j?qr4kG~+dGQAlBVuSU1IcBS$0 z^Rue|HGQ!D{3wjM$H%}OLq=sBADEog)B!as_Hz5AU?4QhSmT_Z;tFZq((~G{qd*pM(?FB{+~76Ot93s=pPde^RgYd0dx7ql zM^)1zSFMWZ)M~XJ8iwd9Ukz>;msf}51 zavf3y=?GV&>NJf27}_41?K-5brscjy?P*#~^{YbtNSsWaQZ=7Kx`L`z`D?Z9bd;-8 zg#4}a6xSgUiUjFMSEC4}Fc!q@J{gkdgG1S!WU7ke&i_9EIxrjtBHZvqGq+YsTtvFM z#6i7Sa~L~^y#5Jg*tmOZ8wCE3D&el9*HzjGzkeTA0mk$&V_8kra7XFm<@u%(_44rW zOSWi!(G-zf73t+(Q{>Ytz4@lGH!a;oe=^nV<6f#@3$NZ%wJQXL8 z2l~&s-}@e2EIJWgB449c-|sD%v!>=t&vD|os5^5`i{%mnXImf1M0_3r2Z&Z{+Z3{O zS*M^P{09veD8Tm&-E})1vQQVJ!uDM!wFnn=rjYKkO#Fudm8j?3RAriWwn6(DlSa{9 zBCQ?2+Qm$oQp+%DS}nz-8MGoM&7!55v>Y4?(h7unbRV6AT@z|Z$O$t)Y_75G++t=$ z)MJUyWt1C5FR6>$$?`&J_sk=@X*uoxHL;BEg{*o<(n+(`&U%l-{7FqVyK6C`zBBrK9u( z+Lox0%ksnP=h#Ohr+`);`47Iuvg~92#+~Ui9h4;#X`l-DNI4iPCie8dVA3UY_L~&TbE^!a?Kdxo8Hhu7E`SAR?xKz00 zxNgW0GYqi^PvF;p-yFn%dI%S*ygEM)7pulEE)q`{aI_4EBrY80+oP=8lBVMNQ}witfnKFU`e6-=b%8;L(qdBk`%RY!#6 ziRau9c`ldK=Mv5D-!M*(U*Y-aA)Y^tSeI*Y9qZ@$BS=4ps~J~4t~y*kTpMuZ;(7pM zIyQdddNEtLi_d#r>}mLY#f$7z*B-$|?f4}3cYMW*c*>hL$$fV0b}frR38x;6be|c! zRYbZ^^R5?NuDWe`ixn-sV84s_NY6WBq~*cUR1wi~lCb2Xk)F4|9ZNedYdOJ#A@3WG z%sVLZynO-b6OG@Hc$$X7%`B0${EgIiBNE07o_A7_O(Pe#{DstaJ@R}-_1i;r+u8V+ z6uzySUXy#?{t(69+~nV*C4P3#i#$zbLPFkgs^vqJA@hAX@?>L)^qXwD?0)J31J~Ds z{3jBy{_eG5{49~ap;2Cdmr>w72={;ot4X?NcURTJa0h-u{!E!H(u-NR1rG|B@vZON z48jJbcL;A*NXO@|Fo(?7;vb)@&*8a7+FYvyrEmKKd0RX2mb_xS?ca6PDt&*@QlF~G zTlRwFNBm)Zz9HXh+EZj>u4O-AetaWseqZT-Q@imyyxAi?Jce0#Xps6EmF!es9l^O; zDXR#VDZGQPx*D4pOOiTz6Gga#|*6UHllBMty! ztZwk`X=I!>zVB9({3|AwLhcma{SfK);<1j*BPtoY-1jok2Gq*gw25AjL;*}W+42cJ zDzZz%{9GL3zux1fUVuwXT5fWd)Ty{F^%YL{<*1(S{5I^<#c_A^!p{gSBgf5XV#qzn z&vT-avEc^h4eI`i?8pWa-i;TFV;AX;3(tt35PeuQTQ{D~`0;3(YO!(rQO{U=d6N_jCWn=d4ubJfbU(ksu;V8BKLQo%>JTbVLN(@_f!vA8OgpH#aJ~)6eZb ztjJj!+Ak4n7AMT+_NC1nho`|*!}(T*j7>b02rajtTYgCHUlGE6PEJ9!I>LCAH_Q$i zW?N^~)7dbN729Pj^91uK)3Jb}NQ|drDt9}<)1xZQ4NdXNyBm^12SeSpeAgl6SM0g{ z_t71x6oNT?Q9+j_Qw_^^zf6}UQij!=;t_&jeTSB6r8PZb&HlsF4lLgv9nXy3m}t zr`3ube-g!KRPEq>r<7eMb;Z+VSgzsWc>!Zn{m!T_Ls|7CkH51y(i<`sWK7?-?n_TU zVLHGyH-&z9j2~=Ne)Z4qcmGM=^=1h7et$uaI-+GW-+Y)fy+8f8=uWiE@X#i^7*N_} zd7t%nOryNw$RnZ9dKkvYy!jZI!_vr%1~EE&RC+c&@C<)U)jJuZ^#lu{hFM(s_fP1< zk|vpX7tp?gp(t|(Y+Gb_a6dtY)xHMilhHbODLHvtGG$B3=oRC;MX)%J!gN~;dCj() zWv9WoT37ITaf3+k;v|}u8Nf&2yYV63%!F}no+3Agw@Vt5fPW7vj;alBh1e+f-LR}x zwgkT4J$J3CZW(J@N%+_3a2pZES~*#NJXG>JJ* zASr+q>xg+7>zx8mvY~9@{9TBl3fOa#!9nPf`Cziy?l98;`%#7Fj99Z*>=A36jAqS& zNuDTq;cMTz%9O6Hy3P`(I94h`OHOfILt;)vsOs7%)DbOfzuy9+eldi5m#bh)3R|+d z@}4Gfuash?k2%H{LgD#Q%@Mgb(ZoyzA%Uky&bCnCAACWra>pFHV=gQ+j8fjq2!RL= zE6{m{Hz%U=W;z?Lc2rdtZ;o(fkb<)gippUL9j@4TeH27(0W!{0lsGD%DJdIkyW}Z0 z+T@gI@`!>Au+(3W6sNOA{SwV;s&WoHr@miecJ6$t@DOkGe@h6w)R3h#e*7IA5%4s7 zVw2-IrS(sv9ZJfq&dCT_GL(gPeLw3S(eP5^muNZgU%Yui2~FVSG`q+#7`K>R7|nN% zwg;cp(=EGry(6%T7sz{_=cfB_qnOO;gR{2N(&GpvDE$YIxo{sD)#no;i2I^mN$gr_ zpNx=cs*k~*fa)F!<6G4z?}>PjYDoNMB{AsqEPfEck_8MjeC{kubvEQ z+P3L~2^Pdu#TAW9j|=S>J)=-9; z^`&IzQFj*?6jboO0TnUTuPwtfDs6?CM0wARDK2n&K zt|fq!RO{a5wZ%%^AJ1x2g#K->|5yP2Z9e(qAA#TVzk% z#U@sreU7KXV_W}$Fo)%Q-=SOP@WmhJu;}2}9QM6GK8G)a=g`Hu0ELH((EV1J#iFy} zS>#qlB<~k$UC-C=lR&)_MvUK#70YlXzc*HA{k!9JmfVUL9^FUZjA6v4qE?}*LcXu% z$EqH^1-|BS_}&?>YuQih`WxUPoLSl?mK&o9ZDcIGz)WFQnB=!4oPsgh`T92{Fs=?y zC1@-{6+rSlXB?@X&a;i^R*p@K^VsykB&?^%dl8cwzli)x*6B%g;pZdmfrm<@ElGSy zUf?PZ(sDAoup5bwAn|sRc!?wy#`9k3Nqu|ZQTOo?EVrq=M=uFnAnUE&&qB!ROrZ>h zcNgc`Iue@1D~jv?K=jY~&!m-&Q%v30Jn$H{E`iU#^S`dtWfIV4KZ8Ge#)w~-Go_8k zz8#}lVZ8w0)D0s_#7?SZ)1q+6URHS&hI%42Ng`||hWKu-iZ=dMQAKSu|9M?p_|32{r1 zZ=suXXL&tc-9CCHZ3a8l%v3KRtrv6Ke|0h3zpAfDGv)|wqSECd^Hd(uaSEg-`CY!_ zpJBTIKWJJ*m`^pS8H3rHdy}8D%qgLUuRQtmh+QUZwbrXV)OlWUymy0a!>n>~uZ*&b z-^jX+jdo?I;B{=P&$KzjMhL6jxlP!^x%MH4nzq#^8H-02ZI1yB zhh2W;MHNR|t&2vQ7`xb(v;h1^B^8Bl<5tRQ>GbDK-vU*=roK(P90m1%6<3EP%xkvrUzw*lAQ@W^Ta-UW#rKuvV7~bJhFs=DFS-CBVdLwC4 z;P~9`1~k zU2>SVCj}no$uszDiqbRfflR%lC4&#FAzacJiae+&j6+n8PEbvD4#y?p4ViLbsp)cf z6D%T24(~{Uc|@#$WTh4{l;$^JFfQ-SXb;KDib z$yLMPCIs`mp%Pg`3VQXDqVNh|!1+sPw*7;B)zbHh)9&G<{X0uJ>A*=&FKYvP?PwX` z0|R_Hi4Nt3g$$QHz-13|*+0O@F}vTE_l%=>Hdj2SX-ueKmI-`3p$iWHhCD5Pw=SGt zaex;cz`eka7g8X+1QwIu%xE%_Y<|8lmUl=eFN#U*TBvgPUG8We!SAVsfsL0f%SazL z$k#1XS{9N;_M;@v#w^?!ZM}2YE^hmVw?EYKF(2q7gB?6#x860JFV0`sE5Z4gjeIhB zxQWh}<-d1~#B*X}PRZOSAq8mms#=)^IS(7c;Y(qM`bT1XbU=Spv?FF_b2AYbZ7{D} zM}G6;a<udrkkNdJJ)u|sGY|(X~XR()Jf_ig#xdfA(DWdWH@Whnn+OTa92Ec zA|j6hYk-~J?&oX7!Fq#-vADddt^?ZYGy_&Qw}iAa-f>S7@*9y~6Dxu47kSwykQ-&2 zQ6Py5*54g2R=V=mVx`O@@z0u~rWt0nIhHV{B{a8$Y*gd5>T#eWacO|{Ch6qVsF`Dk z|KFowvHX8ReBGNj^>o`Bg0BnsKrvZe1P7JdZ_aO4h4=kOcoOS=Q;j@e#>v9s_xio^ z$`V!)v>&~taZkj;&ZE#y*4%_f*rO*wm6l|<>u!4G4UA1c1L%b?wo~2T^BadeCq#Rg z-kR`b0n-U@mn4_J|b=dU%@qVWXksljL&o(McszWejDURSm#;z-GJu@QW?uh zp0-qu(3bNzY0HLDT(Jz1BTX3Q?t3b_u;3;{1x$&wyPtQaNZYQAf{ojk8GTq%xB^D+ zNdHbqA0+8uBns~y#qyjLliW2^#lGmCF-rP8GvI(toUlAg^%T~pVJ1N+Q^~|c8u?K} zCRyW8O${;@|MR}ka@ERb-JkM<&#Ef6IO3?BoT2tO3TWwJY>{5i0vpOt^!ab2t~!5B z#9Pnh?$}MaEdsRvdB6E6%(H4O>#?yG%@T2b zDs|eU?t)R*WR$dNwXVEwojcuc(%$4b&1#__$z^gW|Z~m<>v_@61#`WY49`t`* zu`dUaUPJ3W8nThQ)(yEYlR+a-X_^$b?bkbv}eAlwd9ESV~??Ni?$P zEXES?`-Srd(btQ(Y`7o7??(K}K_mKcPc`uT%Qt8;4!N^OfK34K4$dQqS`?SqWmhH0 z3o}Q^?rRThyk_wdq^W_et}L+Hu*w&Rk|J|03%-EK?P31<7K>> zsz32{)t;n8SHY0WMfPOp3Nl*N4HQy#$Ya_Acg-7gCt%cD-Wwt3R)GwF7*u#{Nz*2( zv$%%BH5QtO*T|#VcbzSqas#K}h7o6qB+x+mV6hCjcY{u&42(SS*O1{0C92Xhpxp@a z+6*5T1;lvW>gO#`C1}Z3%n36$K_g6(sMIL3>JpgTPlx~S%?|Q%(ENP}{_zpk&02i# zaUbS)OxCGcI>p1VF0U_C19zpiP5f(g$m{dO0qwF}hV?tSAkF$4eW8P@gN>m^UvL`b z_hnJFiH5Wg%dk_m+ctr9m(HLPdb-c@#a{A_57x8AWJsv){+chg)7cz#C4WjnY4^YQ z6#aiCcv8&IN#iK%Nj{Qmw}DK*1{ zcn8M4*V|uLni+6;=A{A9eunC9BRXE7S?Dco-*OTzmD&uRbC{uS{}aZe2KVXz4S7ar zbV~npiduzx?1L@4uTN}+8zMoCn&cZ6c?#+GRlPFm1%+Xk&#SA+uN8&rRCRUp1_!lN zz{LA&eL;Uh^;F8|%i1wV0&(?@FE#DEUaR{3b%ay^tF!{Am~tH$B(F{rt28ZQA4_#C znuIAH$HS8RwAi;MM6D$yC7LzW>h@g?g)dwO8u^GYMOX=kWv*o^_kUf7C1Z&^@HcG3 zG;oVmM6PDzUsDvky2ko7` zC|Z8YpI8|P0j642?<9o&^y)ybpuO;F;nxv3#QQd@Tnn}SVpSto0E=bI5U{mZ;4s3- z8(M(x0ukV?ExaYeXRr)iU8OcUuDARDfk{|RCgCkI32ee)S%XNxdGfdK3v&E`U~kd& z_FeB`twNdL2&@?A$3Sy54ne2=L>mM6`cE@qb|N}e@}UpUMnE)Y|s997!OSfc%>k)Bu<6IDuXe~ErJi!|{pGi%GFejff zen&!xH)LR2tZXz*69X2LK#-;net`anqbcfDtc4kNfiJXX@GpoV`Zhm=e0tg{>RUud zSx;QUsp>LsOOmvFH%esZVoGbZvh)))4mtTz@!ay4lOk>VlG2JzvXbR`X*LeLy5rZ{ zcl{i5esUCZev+^f(+8g*x}GD$K#Dt=N2O&P`r)A`K~*I!pV*|m>T=ciI&pt^twDZb zZ9vJ}IS8|WyWqzTBJF58lvymSU}0JEPyVgVfi8ac%h7?iuQe!wUrK}NhGw^pGw6zPzJ1@dXjGmat}^4fi@eIHA{@szZ3H#20;%FY)Z1#Mc<=sqk5d(mAiS2k*xGtS9p$uzKV5x8l1GUI*l6X^@+d zDZ+Ss3>?{v-xXuz4EhQ(=nw`Y@U-~DNb;!=kN923PqzBPdDl|(blH7W-qTZ{9Y{eW*4ZE} zCh>d48H$9*!H>DWChN0_PF~9=JdV>@FL|_jhi#vU9OA~DWrKsuRK`#FIWtXB)Kx?m zc!@H0Lx5_Ep$v1gQlnyfg8yYqyoMO;Olu6)d??Gjsx4y_O>p8yvV1<8SUzVa7Rxw7 zA`4OdM;rgdb6JgejRN6!xJR@r!iamb<^6bx58wCxm;0p}=!=bjz+^ zRAWYF-)2gh2ZqYbKt~BZp}XZO;p!8=o@Ks|ZJ5JB%ht_f@V!M{&NFLt*yN3&!Bc%Af52XC4*tg z(yT~wFC`hL4;ue?wI}#B5mB3&w&oG@Dzr(E|Dgzc2YoSPdEjlva^@UknS*B{KdZf} zmj%v^=xvzRClpYuMkd3j?(3146bDvTzR9u$Z)nR!eQS8c?|nl9rM-NE%#lKurqZ00 zwMi$LQbb@dG%rR4{&_R_rKnob=&KzZtW~un^9SE|#sfW`(0Y8K64lz0CprH4TK8we zu3{fyIbO}ep#)pwmZ|r9;&DT8)blVkF*NfAQCWPg&lO!2d!;7ABYc1DjkMcb-obTV z9~r*ZID+);8Y&dZ3LNF#8WM%J&^5Ydds^-C>u@TYU{Y+Si zOHt4tui38Z@rx`Ukv$R~1UG~|5}Lv_+a>iZ8N9-V;WgVKaGuDMoEGK>3jcu@N>p9H zhbLHC|ACNR*nqN{`UTi}CyKath35xCs4xg19Rg9(nXb0)0-ZPg*3|^3Qdid=`%hi` z&1ky*w3>pj6RrB+%u0DasmK4`L>CW}E^bE`%iC(ZPZyHl_-9*cy1i|^y-D~s#~+Fg z(*geofN5+XXBGd@p1^pw0u_8C*)ap~vZ+g;xFT?@1w zcPh@doE9Lz*%&VCZF7azw`}CSf#w6Q`VZwb-JYrAD@!;ZYI+79uVyD-Y*XTNxc$m+ zd%&?wMr5fIvRcu2^B(=}4OPH5_v1VQ7kCxWO#ZC?7uuZxJ zWAbHA8!>1d2f~qT#QNaG_d3LLm$xn83#MvKswiMk%CW;%(jU2@;1zfvY zl!U)IIRup)0$(^@7c%~*38V-&n@^)exTeD4kpj-Q9Q&RBrtU#ZA4nJ$EjtPue1m5Kr@k~nV9jjgnW}AYjKal{-aucUvU~OHBmwNJdb>SWqwNBs|nNg-BY8gULUFR0)>1&0!TP&#`M9Dt_!>s7%PxXNTwjPf>9z+i4f?& zjrs^RV<*OdWaE74dUh&Di#+Y4Kk{y?}Hd+!u%#dUp`Es!G7j^qVE zpa&IfJmgC3W%o7GgvFKlAOcrjULGfLMA3QgNpnBF?1a@F(Hi0F42i9Aw8#H;#UZ;G z7Ratc&G#RIrt4dBN@$Wo2`1>nY*937Jh>Tru)z?05?1x@fAQ2b3$-9%mP3m_Th7LZ zF^|w%ImfB6^gAFp2;hqXakeN(vn+7MsZs2ZM{oSd!O)h4O4|Z@iMMW#+zi5eSHl8A&mc)pND~t| z7^H8YmpD9WHj9EEi;A9+<=vnhACIyQZXr3*%g$2FJ| zt|zqqltk+vGBgiqekHAr5nudx)N||#1b({9{1($fPYit;pRMd2(p}=eHQmDnE}f2H zzBS#+#fVbPshmXgmYRK;-Lxf%HXY?t6Jz50UBCCh91&-QcrSPbms_`G&tyRL^DtB$ zBH)1gs~_R9;}|A43$UQ|aae#nuyoyVK;l^@MsLQKd-Zghq&-R_&3$pAl7_iLdH182 zF(6G01_r|e(x+d5Zp+rjyMM#GJkXtZ%xgDUE6TOnBz7v1ais+i?Z(GxIXl_brVqx2^BZSf9#g)W8Q{G+BTe2b zFlgc(H|IZ&y}f|&Wsn1BTt?M6@WRm9lqg1?c?x_Y#`+nex8|l^ej`g`mjsi-rm`?8 z{{ifW`*RY%(Z=jZiRLOdr)1uhlC?mJuX^KK2jFd5{VH<)AA!4pI3coQGQ8yYb~!b? z@f4eIN0V3@IVLA)^+&VQiVPzp#%jV`a?lLR4-y_n@w>vw4d@OVm^0d<$za-@WjdfuR20vzT5w{Unn2)^arVqsoPYJ0F< zPh^XmRK!mCI_#8v?h8X?bBX}28}7}7f0{=hk1p0fC+ckU(66}gIWF5Pq;^<_vym_r z#!Fq_5L<^e!HpSmC`90ma3#Pl;wajijCq)h=U-vGDL>D7p@C@P<*8>qZ z=f8dg-=lv_fX$<}6Tzcd<=PZ7p65a3=9sIaDC7719Iq*kGT7Jq%BZ5x9A-j=ik!&Lvmh}Fx#2J1}2PC2_F_qTkxgq1k5h%h=ko^pS| zTb-wH|D!G#4|e%0Lu9A&%I}BY*=-hY$XYREu`64Cdl@_QqPbF5+ySv8Ws9IHA7Zl* znGKetb))P}mxY;qi-hY@<6KhwP*-w{&Px3Eh!K zttpALz4IX|x7i3T<$XP2LSem|w~LF{(;Xm;^p47`l;}xP7-PJ|+uyZ`r{_H+bH7Y5 zz*@oE90cjc0l=^=HjO_31CwU$;hJbnNM5@5u)>%>#NyLjwxm0d@}S~mdhXAL+IK&O zGyZeDBUuu7jvVq2<5S{+XJOEq7LBC{X}AlR++E6saD&CTm= zN%5%Bs^Gn^IjL@Ze7e{kzv~)YbsN0vTa4n*aj%d5F!yx-3g>3 z98!ga#X?j}{u!qXffSh%Inw#K*W@O;?p_JLIKJtQMREFEW=J@0N=%>1O^J6P%c5y_ z9u}Km#TnEJX)}HyDWs3juUQ_)%P{grD4o9a|T1^Y^xhz;y_IK?UyRonkA-0GHE7yM`7iq zldFjE>QjX&QG+yN%cvMEOccidXh21_oK$j zgY0j;lA!-?kA4Xr=YHhsOmzR5cU3As_fnDGjS-OEgOl_ovgM(VzzHb4lDV)NT1?mg zujCGL%l;O{QI?G}Y~E&lpPz>){6y2_d5CPT<5O>amtVv{iM7W13+$3D<)e`E2AT=` zW_|l4Rsc4Bt6*ho`bjan`h(Tg(M!ynEr~$yHeGUMDScU|EsH}I!_bvg62oj4iW-bo z(-GeK2PhUv)Bmdut8wS`Ihnl~Dj^`TZRxFWfmqo-3X|bG>{5ZJOA4y(fD07ClI06+ zR$1&Jw-+{8zH0S-sJvPL5I*1$q9&OwCCmrLqQGGq93;rE?VZ1YLLz6lrHx}McJdN~ zzgdYWr(wnBPXSRc7K#uyYkbh`6606IbTNs5L+`kf6l-IOc1DlEc{@^Bv28)oEhVgb ze=v*RSfIcO_EFybJ_)qxP}_4}6n02R&hp9D?TG?H4^`7s>%7g_I5R>)dWS2+50!Ds zv}Y^7ES^K$T#A>_Wp`5@SyWZ~$c!zH2vIx{q_(P;I2IES_s^PC`Z3PPqIJi&g*IwW zZY=%F7qDBJvEf;>q&PVh`0+ZvE@SEK`$f66z?s6VCtm zAaSHL9U}8RBS8t3*GMw^k82a|=nEig_!AM?iHLC_T8EgNAzt&nDEAK|D0P1mn;+9d zPhEMc`B7EZvQXFG{avU0^?w)^>YOW$0o`odHnMeDXqnFwBfSDW;!L3QjE7GouTpO;}brw=g=6P z)a8yq&JIVkaXGsk{1a%j`~H!ma?M*(_NCJa_TE1b!LF|+)UtB~Jb$2Wq;b!|TF*4f zvPb&A;ds3x<#Glo2TBOb#OU8D9uvR=_0h zAZT#!H#g?XL2tdFyA`-9as3r^_c$&w(xteFd`(leaQ;GEcHQv&rmg=hF{}|=j^c_7 z)8-dwT?|ef>uq6k$LPeaBo({4P(|i|N&{niTblj-DNSvJ3Z2TGrUF<*F^waSiW*)ngEp~}Hbxvk_qVe(%NHM(=vWEDy)bT;# zqKU}OU{cN~4I2Y<0%huW0gXy7!a69(ku!+yUEZOV`0HK9uYWMCR60{{%Sj0tY)akI zQ;S;V1<4`On5BS=jW7e!s!a;@HPOr0rkZ3sSaEUGKB~oX{=)QYI^TZD_ z+WAIpM(FdWDA{W9iq!0ASjG&a6R}H*SN;4OHC+ae&j~249X|*xj9>8YF|C>I=R)Bg zm{O;wrhjWoP0;<%585Qs?i`cu;194QGOf7{2bvT!wwy}*% zosLkAq)_)*A!E}IP;Lg-Ob@Q1{Xv&-e;dL=BWHRe$=ETTao1SJJ*kbsaJKQG)SVgT zmfy;ja;dkaO~_vLv7M%DJ?4swwL{_&GO4tQA!7m2;6Uto^)xNj(Yi-@+-nU(x<|+j z+#n2`Hf{Gr1Ixp&U*>}A3|xp?PMFi|D51`KBOSKb`{>M07WiAgi?5DxttP{=-`I zw2Txr1ltXL>xJ8_V0%{bdf5qUyMKL;!~TRcSj}?{MY~{D+h_%@qwx1*{usIg| zBw?}5LAJp0I_zA|yP;reymjUemiv`KXZ+&SoUGHfmCP-9Y^m|KXt84@ZCiP(n879k z`(KNE_@=qQBi9%YM|gEj^5ha(lgtro&spZHj*W0zesI+WLocdw@E!X+Htndj-*mwPUmFhDQX2izi@vFCnpPpWpVVwhaM7%@(i|o zi^}n5IhmcEPmN2hbjtC%Qo?oVQ%$i;(lc}y2BGs$OC=@d-!eR0?0t~VE+=!Iy+JgA zzcv*XxV3o{=1WU#PzL9=j$U0YW1~BlN+;v2VHsMQTD47_{<^Q>JyCYTAxzLfS z$yu;TPYdSeoiDT7I9XllCPkToDq2Hxinz`m@>x)Hg%y{J%5H<2zXwsB1?9+Hs3-3@ z@x|n1Tl1VFw%B=*SzxO;S;a|{!!I&!ziDDt8GfSwh9%&_Ky|EKLqWFZTb8a6Z`hq%6F=?DWO59 zN>>ae%Gi1@3g7&J(;1(4W3{}V8w+2oPA5czUi)NBW1G^Mjx}D0dMF;X@xj*Y$8g4ja?ajsh)|e$} zD(>U4)2=gx+Wo3P8)5|7ph*vE#%Y5_pbdEww1FVFGxk2O%DL=T;?S_WByLZA@Zfspr_AeI=)E-|_Fm_* zTd56(z`2l!5q>OE?p$~))o{kncP_gXp`Ee{=fa9xi^STT%WkDB&e#RcWw+85XY69< zvRmnjGd12>G$sZnJ&$lMi$IOe*H4Gx2+F(#Ydy}Q1i=yuhgAG`%4(ep2|+2EM+X&g zg?A0^yb(;H1S=4Nk~^m*Yz@XN**#YgjF}hT7+f~*78rvuc38h*g4!ihLw^au49@>% zsO6bq7$G;qDo#ta|3nWEjI|o(_<#%TF-s1lh7O$$Cdaq_gzB}X#<#|c+gHNEaeb>m z_{Kv#G^moN$ymg4(@UEO32I$F|NV)82OO8&S|n;MiU$$WOTz>zOh#BWgdm022C&By z3MLRLDe)jFyg1Mv^ubze`b}7iy*UEXCZM7uC55g%sI%|T#&Az8z5aoDoMy1 zo(IV@t07BDS}m*F_;k(+rDIVYN`bhcC_#p|z8RNe6rLjOr*LQk@`&YAGjyL0w7;GP zCCumzC}CbA%GYceoN=o`9pZz3*1Ic5P(QcGOUNDp1BVW@>LsaA_{!X6!u#0!%%b$A zEbUl+Uzj@XeBJeKqArDf`(-YBb&Pv(b(vL~(x&a$B4|Fi6GKBrJwkEtOGh&6es2-F4ne z3v}7N{<@3v2*Cif$bp?qQ5maZo1r5dSD6RGQ1$a^7%cDs9o|O1Raf)f_BfdoL zP7gBr+(H&aK;9uS9 z|K0v+&o{_C^2x2~3!22`s@_N(e=^ydUe*3-g~cVL+TwxAO%;A@K2E6mnRzvkS-bnl!{BtW=#jD|U_XH6C_B zd0$K1!Tt?$-P-F-^oIStGHPG?1MD;}U3yf%Zq6o7Pvvc*ApgU?W|zoV)z3!u1Q#|% z!f5F4P&i3Fg(Sv?M<*+dvqLvCXI8?jXSYQf%lJ~isB{65Zn5zRLTDeIx8KA;HcSM+ zcPhMv#^&pD%wB706a`t0<0mdq#%KA~xJ*D7-fQ0adfpiC9MljKilBq=-SvOw39lMS zFnW$P2(?KEpLc0g_>du-7UDBuIkd!zm(^JWjPW6`X(-G6S&QN|J;6tmT_g+0}vz@kCLh}CVRKMR8~BB&3DjTj9RjlHhbyBTbMDy>-E@G@O@X3Xz5GTx&zi`|9YER>I!pN`>isxUsKR+9WQN z^pnl>5p1R%xm2O7pIwargqB0vX3J2C6h=y z#~(I(Y3aUl@L+2s)tXK8wc|5V^W^>yBndmRu?4l=!#5xDh5q7iWvOT56$#&#W|L`$ zAT9DxeB*{0P_*39;r9TVJ&1f*MtRlw?Ql1c?yD$=gS2Q^|#snx2qwYIe_wZ{7XS}SOM%wInd37Mzzz*kTEFmRYDTQ*Dt5N%`PHLh8TR8}xzsEL zE04>-0HhnJ@y?v^6pWA5oc`kVIeD%<27e%TdKW4cY($whUZRtd1bbv&eKf?&qLEoq zg%bPkp_9D#ykkrhY!8eXUhN7vqM0gZ3+A**(R# zx=jt9_b&K-2cA{ndqZCn&M6YY`*EhWEdb(id@lF}NsBk#9=TVcnK@APzG!V|emXzSwE7Ln$wayjOxI7qWhZaJ4B?uNS2T5^SQcls5fW!^_dUjqQ9g* zY`)SgBD2!XLf!p+h6@Taizrh|Te?IE;NB5b9t6BZYgcR2nEmg4-oF*j6 z?MnKWG=gp#5EDcm|nb#bV}X)?;^$0Qpw=OYCx1!KW|fxN=cVI4c~<1b5> z;Qm=&;*HK9cxnL@cTu4$z7u=EhwxzD&SjRYek<)^6)Q8F?`8U?x9;RZh>Do7V1p9p z3W9PIoQ}C5{*cXM6>jB6HI5FFf|NnlXQ$3 z*DTp(qE`zxIYgw*R5qE(`|YjG*C|gWi(kIjE`^AR>PO4L>zbvDYc9h4Mi|~JkDH#q z(~86K-_rBj`geI}N3%StSZ;dp4&<%0Cn!;0_Ya|c&~&s(4c2?;3oND}AD_L`EEnW! zAcaj&dsq`hNz(MHV7F^`@D4`di&v*{K3kQfpiYhBxHPWHW|AyQS6gZ>7u0FevNSfA z1e$!fT@2fN**Fq&YQTNaH;#L*pCuW6SXljo-an%hBb;&xd`&Q>0ojyx6_wS&1hb$say%L1ue<>U^JO~8zR5Eej zXB>WMy^3B|8LL=UPE&Y=JAmGN+JITkAX4qu`0DcGv?Q4MRaJL?5;D9f?;mQ2s+Dj2 zDNstlfC4&eAnGaJp43MzMaa9L*HV2NK1tm8i-eAaf+I*3>Mp>O2ATdF=p%iKhuB2q zL;QBocfyc1{O-Whh{uEHWjrt885hK%DY_4KMa-W_VOj(Q>!pVxWJ8%r%<@7vpL6W8 zLn>YntvTvcljt;3;;BA-d3B$yC9l|Y^AhU$_F$*EPp?b@4Gg=EN3oY`>8PD zf9Ry^=5tZnuu(_nsOhcX63^n@msj`Nge%;|VFhz2=H`a6_1U?qgbhq-i7@NtZ0*aJ zM!mO+RkRMvYfzE)MV`9LNAuOJlfsklS$!Q4)GD)= zCsi$1Wj{`vHdo0$AGD0QxR^F=t{`g#H-Z*#zu>@??*79omz#IU#5K{QLfD$)@i;E8 zzLA|zu~nig*?ZP0;_hCWH!DJn3!|XpxKmdchec!2b|t#D4>S?*AM7PEY24g+GMB zApB8)e{w(kOWb^+OuT#}laWg>Z;>c^FWo)?M3$W=5E(VRAtaW~B&@!SS#24285nc{ zcO$r?b!uvDKHsxLe|hzFbQ@B7#}apc=jA?4*#4&9I7f>KNy=z?+Jz;f3GfMI0*@g$ zqDI{XBJ$q=!8*&Bzo2@GJd5(O0EOl*6tV#*8o~#Fm>WJoL7)8shWiI#nEdZyxO(Yd z5uuatQ3pj3X5C&D{5|9hz93wnkmu?qLt0^#eughA{EOw(CBW&BjT|7cZ!YyyNDxt= z$bLM{RW9+6;E8O`8x+Qs!n{jcnbUVZUz+=AsB{!rh$5rzKbogz6ChX9B8zalzu>N! z6rs0j3fF|t1Vrt-bQg|jPy2s`!y6K{b1HuU$0rmH-83o)%0_~fEEpC8KC=3Idm}Ax z(c^a1TPzPUk=$Zx8Oy@WY1-c*ZFT1#2GTx(dd6C213Wba zZ{Y5wHtZZs0Y$(7vuqCWkTk0D?`cNS%{rP?pL1#}fGp#8LvS-mWnI21^^Rbe5q77bba{T;mP!!!k_wakyf zZsisb-5S0#R4p1+8fQ@l^b=9%#DO~BqwqxqUga3shkVA5kZWlsB;28ot90UiDTtUV*5WF_j5bw=yUK}e5WxnZV5i-- zR_*;nRMF(#+Tt!Z`L?RlntZmVD*LlquD4 z*Nj+iKHZ=2=F_|b$grNT{_$f31jWiJ-Ty|c)XO(s4QSV%!zKjw(nrGbg+ouhYgjXH zM;#1!j$gusK!=iEQrQvzL$&S)T<8o+@?GK82fM2_hir|Mhg0EOg+435Qw5nbTnT&8 zcmj|of5P(vp0juWyViWs=;qA~Gij)fDmunnrd(kHC zeXx)$Din8ru()WUIH#vyw#D37L@9isl1;1;uXY3{kwS))MQKBfyWF!wd9gn|CXjwv z*a4X%A=o+g&uRS&2Lyb3+&QSS3fNZz`!1nLcjd(*kEibf8dOZhn7a@R|B-qtNBe_? z4q)LCx##?a{|7AC`P-JaDIn#tewwj}C?bvn7m-1^TqslvT%gcTg+lM*!Zn5jkx}>* z`5t$h{~au`a?kt!4VD3IuOr7SFZ}|Rug`{HiTDL9D75vzz(Vg?{|8vM{y)KD{@Akk z7qIO4FR;A$UtkIQj%rE%ypQ65PBz+O|Ie@hp#weQIV-G_eh(b5QTAECAe;?nDZ|64 zRoz23_l4FOpqt`@r3?0E7Mlf5xBSwI?d|=GqGlt8<9a{-IlXi~f?3terok;=$=)p8F zD~ub;Ls+LL>_4}^bb&ZNINjPmp~c;036}eWem^cPOh`eIv9bl?`|Tf|VMqQv)i8lB zLx~;0K#JN?F`Fb0x7bXIgcBH}oJw3w2 zh4~0fZ=KEn6=2lA)fW49yV11GA{By9r85{4n z6b4c@BK?4jW>|^zo<9W6#2tYzZd!C<97)(oRYo0g#L{{chM_utMGUipMcDs%#*h<8 z*vVwXk>cr)bf*UgAtWKAo>0Ia4Im8#TplYktiQ6XluiW>Ve855H z%?$ivSf{Wf%R@>}SlP_~9-3U-?;vz)pZs2sLBlyti%%+N99k#HKw6w*!+&XEy7sYw zB=p7@e5xP>AUX7$Kx9tFq5lJY%hEIUtq^JNtCJ(0jv>RJVyxDi>||ZPpECRAbHTIm zD+6cYdfe!Mz0%+}>Kt|D@<3cL?WJFQU;M?lhWa6~;6~1)OsbYWyZY*kl%#cV+te-! z_NZy6-wvO7k_KEg9hyonn+pCy#*0(5qa$T0l70gake&Q}yuHca>JD>zB?7w}iFQ?i zh9;nnmmxc6+!ppfp)~=lc{y2Bg|veUiy9|2c1s*_6W>o6-x@b*cWdj1`b=|vZvE$y z+9i&-Nt>Kp+(h^$cFdc^&71goIyA+l!84%EPHlr93!R9;9qv*H&z`fqz1fdSWxQY~ z0Wh6(Y5&omq`$5JZ^Md6bwP8`)d^qwXVc)dJG%g?+FljEW}XD>tWbi z!ZF&tSGAM2IzXm&eHXL$tZX2A{(ZFC!SVgcIdrx5wwtW{FRwxLcPMA`22^UNHu~I9q+yxf} z(XGX#wOB;Y;R+f5m;C6$2J4r6DHe{QcH38;5lD_o8n_DO@1`CxDL$5-L34yv7p2DF zJEy-7fO_4;dQ`w0QTI-h;Ca_{ZCct?aRG_EKJ9NW2H_WsodZ1)ny^Ba9ct*KEGkRv zk7wADNz5SARr;MOIAV%p3{giWIhYJHF_cz0E`gEq)8~=dW-GDBx9#8jZ?pk&> zjiujCiOn{lDD%Nww*y~u2R5hi(I#Psw%8`Px_*S+qO~Q^Q^`9qxTPh&Wo=1Rmpmf{ zxK7AtGN8HouX!^iX=xLpPKS3!6FSM{52m*tAEt~g3$O2k?fLeo-LTb!xIu`pt<_Zf zDD>rn9NUis8-TA&1+M+r_Gld2r{QbYz0d`t4rvhn!9X}YG5!@u#podvCC$8c8!gmW zI6&}*ZM^n8UDn?draemoS~)P8mhBQvQxdEU=wbq;Tlngi`6-fPwfwg=w3s$U%UeV7 z+okYz(qHEwTS+{AZ_w#8UxBkB{AMZ4Zr?xy?g`!g{y=E$ptLO2I7P@!)1XH}OJn4& z9h_E2OQ{d2V2cx#g%`jC3XwSRGBjI#j_ zuM{{()}-4YBGIhzxO2P3^zjjP(3teYgW3l*NOXDyb!G#2S}urN+9mcwN06{q9<`EZ zmDLC7N1~$o1Nxh)sP3Y_jSBil&W=3!=N<0}0pTYfLy%JuwSx8(ZSM}>kxuFZ6Q4p^ z)F~$&n|o+_jw3}8=}GfKZa91NYWq%rix|B;#)Y3c`Ncx~Sf2}Deaq8w#QLZ3!;F3V zksaHQ;44**s6@JJRDTWq13j~;9|6my)b%i}!|tVZc=cdeQ-XdzdurA8zaOb`+7MnV z52qTjs3Fn5Sx8t+fvkTf+_UkBZf&@I!;uELT~AA-?Ld@MemsRgwjSNEVZZB$$8|(^ zV31Ic^9V~ZQAgpSX+PzRvlp_S>jR=F{~8cM1MM> zAfhElaKU`>5k2EW0jrPbRVkXxB+=7|BA<#?uv{s$se1X5DML#18~`(sCdEoyJh zom z1ogGZ{+8WspGAYdVyFc?c9lJoeudsM24bXah20d2q3_fBW7t`2ll`G!jPRb?AJZ;j zH`ynI^3Zo9eLpt(NI^1Xi26Zx?ud<3eOq+6hturmD7q5qu+y^$MbM7>gdo}t`tV?o zXQU8BNm8#222~Fif++I!ieM046BSw|4L{4+{-!eh=5SiD3+P^%lQBt;z+!(=ipKQf zVFaWynG%ES$fTk4iWW^U$RIhA6wE;3ak8NgfgoTBTj)&+gHsv$ptU;{p%2=%u*R4| zlcmxcVS5k%?Ea5J4VRlvf0PE#Mu~^hIGQMt(zRZ0`i6$W0{FW=KTR!qc542ARYNi;qnr~3rA0&!6 z#z*W=Q<$hf)HBrW{0=c=5y3TThh<2&MfLm)IXR1vq2x0D4kO2?Kl*VWku#Cciazb` z8x$Nr`v)I}eF~~DG5$JStP60$u%G&RXneu680>H)9nj!X@7R!;720luL(cIh^}9}{ zVg5;>1b9aolZ7$5h=s40aA7TAxx?iHC1>r?6-rUqK(mUW> zg?i=46m6bQ=Xyb%hF(h1dsp8I#f5vRR}pvIdX1()fYU-uXYMIGSz`DOqUXIu??%zC zyG1`nZ}AIdLx~n;xBlCb(GJ5=z7y7JYsFFJ1nW7MLR7X(0q>apwZs`&E^def@c!+j zF>>>!R(Dqe-Kensh2+hY)UQT@wrKwlv2`tO=yo}&X>0^;uJF3M;G2=osMhVo+K9Y( zh4MBb)|CV*scmsqR%~5O?E^aEL`iX)yc^dM>|mm!#8N1sCPYUSMJB_Q`~)aFMsD`oAQvBH(`(6RxP06V(&3^-qE| zAK31@`S3I&`u{E0{b|6ZeGOkLKl!;GhQ6S@7l}S^S9W`b@9*P1SmD8=k+8sWxgkM! zxr7PRx`l*X#|!lJC7-7hSz!cVCXtCyzu(VWdoVkrY~2?$u72L#xEs9S(f)r>Kh`3; z6Z{(G>b|_0Qp<07=fpx#V2b34$6yCMsmN9clh-CvXc8Gs6jS)$UqEIyHBwfsDn}kw3bcT-saGG&NASXOjK_w4-eg&hnKygH&IhCNrOhJK z*VyB?nI*Iu^S#wLV7cS=WT&*U%Ozrra%NJUME3_c05wBFFJ0t7n1q>B8*X${psa<& zXr&u2X!oPa`lI}K$*3zGU2M=Z<5GjnW z(D=5)0uR$5->kG><{hwk;It1z?}P+MTIT9QRr4U7{LIfW&)?=>B3GsnBBuRfkn_3j z7c#}#uldXg4OGGNS*1yN#vXnKmCcoy-8TH@%V#`)-E{avD5B%bdXvw&%x5>L@E4zr zl4h!x4EIN@)7C^2G)jXZ*ZI{e;K;E0L|-saf}eavw(WGz4;MlTA#~2M_VVqroRcUK z+ITdjBxQO-i0VgONt+5AI#`1>SO}>Eu2fi)LFx*72Jfu!PHxb?LsLEttWla?=ku|s zBKZ%}<8`;aU1>S)x1aE%+_{tj^5rmvByncq6(pPed^{^nSi#721X_}kP^JbUvE?Am zgiF%dOLsnK&VBFmz3*B6dOO$cL#R^*`0bz5=FgSozA+8I#q#VTRj!9*=V>gT2odr} zC|-o5Lb`UPP{+ggpxOU%=BC#Lj7d82|wMALF_$AxzK}};Mp*(?D-lZkg%3zbd zto)e82Q3K9Z1WfI=c7_s-D%#j-R43_xyq42kPuA^bEeSpaZ?DMmv>Qu)4eoEFK!d* z&ECA!=L6OgoQ!BR^G)-3!{0u_6(ALj(@Q2fuKP#O!k!3mRo#gG77ymOuN^21 z6IHOR$57T6!Ll|px-NKSA>4Kw?mi79rDJhHqX3kDR=yhmhCF z4SXwzgpObBLv-gJviI@maR1YTz!IuAe}}q)N2veD_aC7OLDd&|s;_rpAQXa9f7)?b z{Yl~TI;fc!EQ5U5AK`j~(vuMCa-ZxE4VL`5P%{2*(ipy?&H;o)Po~&D=OgS9;JaLG z`j|HyqrH+PrZ#kF&88u|cJct_82op%NR(nafpBR-x2Em#W&@HN8n2@IB5lK%^?h|-wKt>O+GgIcq4IhzR_=Dy#lF` z+QT^;Dg#~?6;ypYxI=7jhgSpQ`3dLo5fr?EbqtL0_4|mozlEwiS9s@*{uG~t%KGBx zWi|b$vX0&@%k#^!whp>I&5Z}}SKr|^&%+SCJ81c>&f`q6)u~=kRMufK)^Jr$xy{i+ z+k&)FMhWPmR=#%^HtQlPS2m6SaHYUqqa2@4)d|8iA$8HK&v_Z8TW7LyZdezrYP8oH zAwSm{_4;rwQO{DIEa1ErFsy`pP!WVBic{q*yJLaTI34jOz*{cFl{HE)!+^6_j`UyW ztGoGU6`2YQskVrQ3D#B2t0N_uL-QnX$i?997YuCY&1CH#P%BaG%GgT4p4R5rr+bRLavkBZ)KW;#s{cszby91TG|=xEJj| z&U-%N(f{Zy?Ej`lrOL7*v*;w#iOcNKm8TLT_0i?xR3??mVx1zA1-URaIyI_2OrH?L z!J=|vLXyr@;BvDO^u*uj(Wl~)V`8ddAKc|Oi1i^3NHu^t5B}(-?O}#CUTi8t$R+DfQ2`vXh2GpI5+cWog}Tt+rpP;n8oE6nbbQvX)GmP$GpI{2 z>uPO@>od~R&ke)c_F7d$681R8r6PZyrOc*vCN)7tQhd@$GtvFG&^7}`Yd z;T6MIa0dgEW@qia7^m3eNr$Lf3IQEv8IcH^KK3g#!q#L1scrI$C`J2F-s!=&r)A?Q zzI|)jKkv+#=G-5PDvTlF7$Z$sJ8jc%@fbq%{ZRNZa_;F=X7S=}5SQ|M? zGRA|YBcHPYJu>Ebp^jktHtQW7H+QB)1WQE;oiNHl*b`+Dkz?kd5{HyHx+|WE$zdh#lHihOj|}@^dYG9LE|^Lha723_ z!V29R*ywE&b(Y=y6a_snzqDZ2UM$6rz0KbdUt-vC>{C0q5A1Kz6#yGeISwI`A;JC$ z@Xbs+%%4?8BN7p5!Ei$Wa_j1=SeJbuVYfIG#Fo-xE4k9spl(X-5X;`5Ix+T;Lo9&~ zkK5_4X!IVG>n4j4AlTzcsAV$HV7X&DWdbbY5X;bD$8^dF@IS4d#6!LXeOUE$h3iig z?fBclmffnn*Q5^j6=+~Nx_WT(H#OXrT9Ra2inRpSv01aLq(!rI?-DS|@p8`_AGFLP z4N5)JawbxxAvj|}(RK3i^6G6LxaYyYlAdu3F{{s21@*`1zDK=Qq`N-|K>=VOB8?cn z>CxsCJX7!_;TeZVkLMYms6dWi77z9%c^(GX_-Q;pp;B0H86KwNo8u;;i|dEec0}DA zrh|8w_q%2=jP5FL`ktS`$k-V6eEp}q=`=sX!F0|brtkP%NmA5<>da3jon|`CWbt?W z;V{d${8uv2aJwYuTfSNP!^_WTXs6}H4(2-w?{%VU|&iNy0IzeGt+F36W= zN@fgWa6cQ@!Gx=MNYwcNgu-WjTAnI(#FOQ1Lt&+>Kg!-s2>|Mfq-;2KhwM4X7t0E4 zy|%OJ+L6b)_@gUTJvExeoqXNMvPplk+1_etGo5&9@uX9W)~IY{nkCz9rk(tvm8$Zm z3Y_z8%QXf6D{*Z9YrdqaNNs~|@9&2dEZ4LOm1(SMr!wcCe0IL7V2;Mrz|U3YOR{q$ z*>gmuwyv}ps_b-4*2s>T)YJ+7_n&|nDX)8^?f~!K%P+@C(Jp?{5-FYk+xW6mOy@S< zzmv~+6@7qh433)wgi|8Q1fKy7;rtYZ=)u|%|41;*E`$lYUjjeF6$`ti3(2T{AEgvw z%M>}bCjG1o;a1l%P{(-odx41rjWJCYhn%bA^CCDiR z%#~SF`f{7;G8EB`vf%yTyleF8Gbu)!COl8lfLFsEEaeGIxnnwduy5lgIEeL6=rbHS zm^4`VIE{)3NQ^W=GqrKC5 z@s0B9_XMyPW_F9*t6;~!&^=$<$D0M&*7`u->QgWY4+F&%LUI4GA3pLK)Bo{?;tw*! zltP_Mw$oR(lj+pLS*dPpA5iLU*5yqOl*SO#2A+F^x{a+*>_b_!AW5^NUf-u3c2F}J zSH-mn2O*H)Kn+oe65VLz){Li|v5{KV)Ft#CpDCi*b$uwOzl2h(Et?r@eBY#s&*7C8 zt!oa`wLr1ee~}kXNvs#KqT@M+&Xij8!7O1Vi zzfXIkzxaWcYOnG14%(U z{e%X?rO++f83)(tkgy91mYQ+Z@g>pbBFH|b-|$NWyy&7SJ)ync`NZ7ucND?4t-d}Z zMQNW(-OFZ5(v~Ng{Cu;-I;;;18`~z}3@%V`F$#IgCAy(B`{EvcRWfe4FP?c&z#L@K z`iQ>e6@3mZv1P)l5KYX@qYl}0>b^x|RCz`o?^abG>_QspjoGC55>3)lx8_fk$(2#M z%V4s)mw``U7VQG%>*{E`=8D!R(JBh$FxoDuy^(s%E0mLy%Qnx^eac%#fZYAcKF1qC zmC&lYhS}g8q9EBu@8N3>(#qw13o82TufA_fSKBz4fYz9`@Y+S+?*c39D`-;XP3GbD z(C8L%a-w;q1h&|)2Uj_){yUgu@>fwPLC3lm1KL@jV~Th>_b|jfozhfZhZy50NV|qH zy!M9xMGooP_>_p!7wI!R_W=kNDH|E=*@2=lzyiH9l%Hh?gk?yE-)9kp_fD@SxH}|n zmRidNQ@){)U z=TAU}(ny^27TtvuSg`H5~3**u8ae>M05;A(VZS`T5% z5Ke6t9E#L^3@OEGqW~SvzBcU&9^eD_=&%UVUG0Sh49_jT{)gW0e`MU6wL+hs$JjrI z=OUiVcrM_fyyhm4-ZhKK=$91LH{cnSl&ayJZEJuIz)QW3?F61?sMn$oAl+!wt>~8WtM!4z3kwyD~{V~`F+S9ae%HGWNe9P}R#XB~U zbxzw_tt~Uo2*vT_xEYb-UyYX^)vEysI)i1-NJiN7RY4z$*fx)KOyaN^b6FEN8z~&K zsM*~oh*79RXxk&sYtz#4V7x>7-6yo`7UiDb_G;IBpcw;?UH~UiY;U06Ogz23|C`=N zVL;ycO|RYhKBTK=y1a7CBi65bVHu=9pj>SIs@Hz26C6N$p4Y^yGzot~x<+Bqas~MN zKRiDK@rbQNdlQzy+`&G;*zLZs|0jOOb=vLdY1bnZ9sSJI1*2o_;n+D9LS;Cxs@mlH zEw090W4$%4oc03U9dSE-wqF^l7j#wCw!%S#L#uK6yt8OAHfP*34vlkmtV5%pj=3Ck zh)w0BrKpyYPNe+{TI-=&@@5>!`ddm*_O-nG=u)Gcd={B=SoFx?9oalPge~_98@0>I z2aM}E!tE6=VCIG`;NzRfRRKP_4%zmA+#!5qh{!47rS(Hm#~~5+sC6?iiT@U3;u^(+ zh4|;tF%cXPQTY;2VL&~?LtN6p>cFOPl z4&HE?f{O%|&yn462!qgQ-3nT-&!M#b49<_=!lQxAFeSLhPg>(DFR*9d)+=GQrYuGy zqvskPbcW!_0P`5KX|M9(ds_Cm$Lwj*;6zL~$E~#kUt{XVEO%Cqahe5E>hGTh&zLc} znZ!7Q6bh4~ATNQHM@^K4FT->nvwYQa@Sf8yPTJ<%|6J#?ig7M1o;Y8f1`C;(ImD^9 zeXenYlbAhEIdL1(B_T2C^p@@x4SKI`KpoxmWfvzVPjS$aKtJv5ol$W;CV5iLc>wrQ z0c3%oTx9p%fi)87T#TiZdy}`m)f;wRP8;Y8&iJ=^5fPC9??xVs=bRttc!m)TY71uv zwW#S%SECA537rzaXd#o?IF-ZA*c=)lMuUmFL8BF%C(S_D}oX%sw?ZY-!H&H8Lq}~yuVUiX|G+?6{;e*KSUtQv7m1irEv=Z+i|(& z%gTpyp(k4Qg=wHnu zI%sr%p^h)WOjH()W~K_gLdhgvWBQtI;U`Mjhl91~B^*cnh`4Rnpn9ggb>~B8g=5+C zEF8Ivb-Dz*5o3#zb}mgydTi>ITs3oap1R;YQNeO`cB#pz7H?s$B#V5>nnllPS|(|7 z)ubR{ze(KbiZH&cXZq9eMBt166u%J3gsibRMhbT4yCpfw_n;hLq+ z6BsNDT$gBHL;z2}2QOCOcf$GG(+cp8wrOwjKv^rc-1o%k3JBT*#1Va*OC+tqCATCT z#`rMqzzx9ry#mkU-10JGr0atl>;)(aU*cUts4N@ytGF_wN_&=feQ=q5Ef}0J6aF=6 z=ywP`%lQ350&a{x+00l}r&z=tgK4J2sSd0(rzt z(;i0XUN$C__5q^(00CRs@L)jc7~(mA1+zmW39h!wyu;YsU@zI<38_kBT|$UUB(Cx1 zu;%Jrd{9D>MG^Z>o;3zH%S-9DRCO!Qa>3YAx~l}|-)uxE9vY9B$7fTo9i*&VNZFM9)&Z2vnSG)d5TmA5ax!{&OUe^0k{zr*1=~n*5mnq8S80S+tKubJqA#$Kc`p4iR_O; za#2D00o`)*DAS{9di(juZ+bOIllvZK1N-`SDJ%ka1+PI$AuSbpz#kv&wO@EI#E1rX zr{|g5^|N||M-w=BCnOp?=6)Madq8^)?+W`tHZIQbhR1M&FY|^Q-&m1koSl^P68w|H z8xG2?pV3R_q9zqqwfF>((4Vws^u~&@9K=^6(?20YBJwh%auxJy?B{~B9^HK6N6&x% z{6fu*^$=TZJSD)X?t= zhmktg8213a=z+BXV_G|}6C%gdUikb`jnHXPH4+=6gHZJ;{ zL%?0>&R*>3=wET-QKPP~SIdl1m>(QnH!!R!>L4aplyJd`Eq0}_&rwn0=(-XLLK`%; zYf}_8(V8;26^%&fx=+|Tce&jx9NMZ~9t{g;whEaDyA);=j|J(1qN1X6-gOTkuV4nO zZyrlWc5NJ-KxIG>fvC*oj1#Fp&Pp20zfTNBrs1as4zHi`3X3T7clB}@a4V7`0? zPwnoLfkpUTif09$DR`FSUmAYX@nquZ0`8u~F9TX3WchN~{y`dn<^V@ttI~9tU;QH- z@1f7K?vlZI`hC~iuJ(Jnp(q5=KLeLRvD`46qTz`H-E9yyZtnU1>KE}}1i#S|m}+i% zrCkCs)Ow2VaR`PtnmjRF)AAz6DHOU=IyQOM9LQA*HVo;c!e-8Xo-Hwb$Xh-{|F2m`mPjWcVnB_9;JOJmU|65pj%}Ne0$}6Sw6QJ8OYfi#CmKCoN zzaZYdl`ZYOKxJTZ5Np;j;2ZOS2_r*fOO8V$?2q1d#gmR`>D6fFRJ6D|TGA@daV0)+ z)kIF2MBOH)!$d`a9thnBv7CVQpv&+IJg*1)2T$#|$S76kE!K4?zj~9 zBY<63wbfKrHDUBa^LO;}Eu0%0<4}E)KLEAR(xJl3T2n>@UVeoT89bKYWv!`m5MGjK znsDI-X%u)d&@^Gf3(`pNLe)!gc+SeV$eZQDzQ1ca@lMBnKNYkna!!K&>3E0JHkT<@ zzO(!R_C`&L3e&CjLI8_xxU5$Y8SbO4V&yfH)s7FYz;z^;NRd(M_<(W~h%pt8AmfnH zKE>JUN%(wgR=mK(#dN=+VVnMON?0ewIAdT@j<&;xc1R#c z$?<@$c0h*GENvFCdwv)+}>~rAuV0RnG;FWcu6g z2qRBB7jNLVggK^%p{Ql+Mm%i~M&>F>Ow$wjxzN`M;-s$MLa}`n7P|MtPpRyWq;-EJ z)ovIyDVh_;T62T!#)($PG{vNc z@5zh#p;JXr10ZtRkwKH`Yg%6G(IooJGq5d1LC4`xZS~WpP4P|3n~K0kT^X=iOu@}~ zkI%2(BJH!j1B2%9+g8I@%WkoZSFsafhpt=Tp;yk{o;DQYO@${C&uQ?PLb@L~0b@`k z@*D_Yn?Sew8V(0+i{=+vSZtIoGMZ?cEFb;EB@hc-A#e-4QN&>xM&*pOfaM~cE4)9m zGw09_i*gX|z;!fXCpR&c*;(=+dv%gg#T~d||LzV#1)E#Y#iDY=q||8cz!f-{M0imO zi!^xYgrLr_VRnCD94jQoOy1L~ZfWw_kMXwMajp5Z&2PU>ebYXp-1ZvN`9WyNL$}Kz zCw-Zjuf~jSacFnby(cWOfMhlX`$DY3{qp*%mZeZK8JWFlebvh!{Jp2*Jtlu-?CYi zAt%+1H)AKe6mOHdxSBD8*b%HUyK%j{YH6v65Qm%CYBjl9Hfk7~^N*We>D%a=#$)}1 z!YieHl`G95bK-XFzumEsz%=RHANr$nV@UT#a`h$B_-%iX=U5=u64n2e8zXXAhN5da zEb4AcYRDU${*L$gjmZ)Cx*-lNaKmcHt~lgD8W&RL{oa-L2N0F5 zW@*%19I0iz-57v4T4il5AhwJ) zSH@1%iIV)AP#YW7rmX(;?HzIaRoUBwk8=Q3&bW@3$*GqJb{FAg&ox3+D9a&5aexsG zMdzW3=)8LS-OdBNUrE~;0N-f2r+?6T+CM6OVNR-PrJ+unr7joQ&)q~H(fO@9jAvsU z?!IOgD*8LK7}=w|%*0oVc(xb;eOXNBY+ja$$>foRZzoD^HKx4Ot2Eyb@P=&2Eb&y% zrE|T7SS5E%BX0{wDGw?Yr`afOU z_=Ly-6^G~{_*#nA=<-%cI;jMR@8_atPOPLjzX9^f|+{ZMQ>03fiA!d~DYK zhfYmCCW9#1svr;51=s2^P2tYG6M-0R>JHM5aP9&& zmL2PLKkbMk-6DzRE6vfPOF6wBJd_>R&T=9d;=tm3oH|9^Es`GX782mhL^v1+T(ny# zeEoJ0om^hDsDaT#UxF5*46S6H@+fDZ!HE8kQU+u<(Y46qWc{CMRNvMLN%HRtXxyRKBVK;pXNXP{<}Q2 zOQ0{;=wxams+<}MMj?5R*ZY$^vpuOr(;N1+0pkjU+q8WJe@9E+)q!-}~;i zY9cHWy34``q`N!~k4PF!$R}de1p3>5LF+TI3e!Ao|G$HSjiz_j^&ZVB+=fM({x(2k zYd5PX+Z_gzIpqvgR>p^JUm*?t328O+gTF5@d%InX#NqCN8Xzk#t4nI_kg_AInkX~E ziXx^-CL!TnF?Dc(2Tl>*bZ8{x>by2k%iFHwRI(1~?xZkLukg5FLSc>b1?$ij2*2#> z^fFg{4-@LMZnv_-O>hMTfhUE)U>k$!bYK6QbhhCA~WN2F|dv8-)6kdvou`?&H;$AR>+7?@M7pQFST>W^FFA}ZH4Ln*KRF(o%I zf@St>eR>YFB@S9uHNaMHCmgkuuxE zao7NuWM$wiG-vNVsKVINm1;^Lkrh*LN_|omGNO`$O{`UFU6CC6)8%GOQBQ55cXJ zMbewV`O}oFvhiaqH33A12Dv)1=r5ig1;2RW?ChZn#jLy_-B-3jg@;nG${s=N zllPZV+QMpq*i-Nh+Cp}GJctj*$cY{6Wl<|`qvPl~jDhx@1H^PT+yNpxEA;U9*U$uz z5Y^<58-bquS?t+s0=31_oI;-;I;DNjw}ac?!02+R=T<1Mvy=+_y&)<94YXpZSBU>b zyEtR6thI22IX7&Vc~|bPLblS|@nrp%#2&Ff(NXTgPr28w-e2BI|8(^8oE<~kIVui#Y#R_r!G^;IBNQ_NCi;($xpkVK=#%X?=I8PKU{% z@;n>9OPM+#S#6uMIiDDHD(>p#mC(AM#3rFbQyXOCq7y7b=7Q$9S-NQfbVT$j;(|48)51^L(QOS73Js{FjCD z*aP;LX^E*g{sNBt7kU2$*$%g_e%wI+`OnLCZ1L5PCH29rE83oC#VPTJX0zhbS1Gtr zvPtuXrDSXtr$}<6WNc!psA_}iVrs@vLJD>Y+-->1xE=l}@04yLPSFZ^O7uEsxkyIo zj}6Ol`lg0O%?s4N+E$wV@w~%f7*`66D@ImHYOyeMC;QxuzQ*{xO?Ns^LD@yJxxQI3 zRq;E8Y%WgoMJb|n&U|sXC?!%RqR5*njVcLrM9FZ9c`AYNCXlj9dZ_aKn~W@hEZJ&X zUJ3t$q%}cuA`k1YM)j3u^%qS}wfh@s(^oMKM;B`+H@TNTx9ypvb^u}xC=QJQHPG}O zS`jXS)o&o)C|T=ke{E?}wYqIBO&V{W?5q|pf5@WuXN zng+*xc{27uDkFOw>n5$}RFPy!k+kBnZMpB9Y-PeFanj{^4YI?7+ok8Ux_^*{gtOW; z;vRsP&>%a1{+z6I7+I0AZ4zMq>`i^rU*={1Q-j*9n~}0jwy4RsYENUrF4=8mJD8Gg z7ytSyT#UiNyV18sJZU$x_yOP1<=sa=bDRZ=4@-gH!O*S;hT*oPA%4}IMajNJt9&ct z^Cn%)sGyrM`6A#|3cL<07qQAHe;{wNDEmE4s~cJx^{YtChRVq?O-Y-4-3e0QxIxyI zk^R%W^J}*4x&QjM*u(HQQfH`lkp@}2Y*kYuK=Ni9McxRDtXZb z-?{ijb9{M!>n;5)KUa^EWsFFHOkkSWPqN)Ht<9*}PhLvz9dn~=3r2J{G-RYGQEyA;L`a9A;r zUqDMmC!{!RL_?3l!wnsZV=~f zx{Wc8F>E1+MeyIlKno=#V`<;qCyeb{#=c`;)pmoeytSg-W-~yi#q-8KcblW7&bM(P z@w~n-0|Th3&hy&7CMW)U+p^Ey=yktlqHekN_!{GUuhAU~AB?Bh`8->N$a)&t7zwXk zJwkAuxccw=9%`tbCm%8d@-;TO{RZYH@HgDs+mLsMeHTyg@`&#xo zD)zK=o7~Obo-MSh-Az?BCi{9JfLn+={c*exIFgq(XYKn-!>h68G*i^ z)HmyXShH_z-IY3T%n6inwf?87Ek1Vq_xnVvpWXdc&tCPxJv|@d4~&>J?O|hgju)}) z!95)wL)qRi?;9UAIl&a%zM&^K?|){W@1WP`H}!m^K7Xj^BK>nn&EEI^ru+972~pqQ z6XkiNW-#%VJuc8{pnoq2F8u0z8J?tnyJ|X)ps&pPA{(& zy`(z+1sQh&0d6eoVz5(11%Q@To3(*~REYB65(V^Bf2*IKG$C2uS}t?moT|*r7mb^# zYg9D;cxd-w<*~8*JY)Aw8LO*NwEc)&1osm{uwv)6UHmNW6zV?XAB7Cx@I>ymXPV|@ zCk@Sh(QxuW^~ily8(OP2Xwk<#v=e($)syRb>eOsx&4zeG$FdRLIJc%1frouau~hQfzj1A3|-(Hft8+pUK!2`*2w!DpTr=db~EgR)%XV z%MP9E#PS@g_9O;VVFvca%C<6{49P$9_*NNad*}r)w?GFaq+Scl?->Fz@Tc^!-`kLiFOe^_5>P6G( z!@F&*59(vK-xxO4qM2!RK3|r)D%}V1Ce7)~WDuPhQO;DogpmKUGHWv*{O;Mgg;`v_G1D9~r)R!;uJNhl6!GJ*tM)6BG{-mB7&9T^6-lZ& zV=S(f!`owW79@2b4 zl4Z__ChS{T=FHr}ZBK_kHaGXFbV$-^=;lwW-S1Sr^s{cBtIn>o(S9CQ^HO|H-89MMxf}d)2_G3O4U6Vb(}g0k!- ze@LKT_L8Cy&U}&!AI5pls4F{{UJ^dd@A3%AeNQypI(p~)&k?pnEE9U$(#o`r_3#G+zD~GK}UZ^u3P_2A0_dV65 z`QbETUGhTd%3QPq;Bgxq0!Z~E@oUqfB zN&o;V9(5&ZD^KFmZ0`(fN%j?sm(^%jL^|UN7T6a`Ym*nPu&*43Wn{U%oYq*i(Ows< zbl51=s9l>o4Olvtqp$S_>|37Bqb6_>-5t zbb(f|>?MgYh;p)X?GM6hc=~Xwe&^cLM%rv(x>P3M7xZ9zPQ55uLxjJ-W5P}y8h+|H zu)VBCnJP^kma0n)wo^vG(6-U@#iJp6Go|#@v0)UyWIp0VhOTu#=X!K5|KP*tN%O7-=ur;{?BnSIcq#mbGfO{xFG8YKwP*jspn1L(*s7}a z0oF}UK#f06b=d}uYuhuMHfR!Ct6nr{Mr&=H4@x6r^!QW3VLN(sohT;V&bC*x?OD%N zJiq#C*)AsIZSqL*;|=-yZ|-gNJlpO0iGx6$sQ_GQk-zUErT>TluOi%Nsn>D)G8_4Fh}+PDubMfukdfWFEG)QT^ZLO`gweL+r3jy&K&`O|sn?wU)5)vmsz0E<36Sl@qw$+x>rlnR} z?5I}F|F=&-+xLIJ@A7tJbw$ zp@4}m8ll!)QX?Umj?;%07FaE7`YeAx+x(<%Fr-3lsMJH4^#7p#Gn{CF`Ns;`1_AGZ@fy?Bs7$H0wX?2L*FYsX{)BswoZJHX~5i zA2T(AXe7_P;gV0Kx^}qif<{$it0}$(27m_ogbXL}jPWM=I6+Ez=(w*nlCLFxn^~YC zbg8Cit5O?HA2x`j`?_=?b(Sad3j*~2bEpeT?hV3=K)>K)Ia>(d*#hsbHO=7+maw(? ziPk*btIllXtWZK?!ji12;uj}j=<)!iC$mjkAf9LILNF6JRH83Al>Jt$&gL}RlwG~9 z!8TcM>tL_%$7=cef!8(8<|ljkN|CKX*@a5GWx7o|{KDckR_&T>`?E^tde9_^*P zWh==d#2%x4M`V~b{-J;y2{=0Kxh!eY z9ICA&b=~i)>%QA{#iK6MkR|?*Ceygg5qHRJG;}!)y+*UsU{+bf+ooyQ&;xTBgPEG9 z(Nl+_m$hWVCvtQQh9GgB*&hLPp=eQ=sd|&p=Dam3=gO^Aib|YM6!+RAw~~hrrf(4@ z1Yz4u{sNDp1Qp?fl0U~Y_7d<-h?Ex$CJeFtmzD^`Ft$VuKb$^1o_&28vykyIQRTC! zIVItT1w^g0^H%=JfE2J>&t<0uf?cz&WUMR2NMPst__uz4oPHQ54`*(xmerr)o?4hv zD&NZtt_bnh{1h#iDG`T(OPx2cgcs5u^FrgEo%C~(E~Fjf1_P&m?4aZOgLaAS=Ucgp z#q8^7jD3CSRx!!$dG*%uc^O;IEha{SzLg}rMGKDDe;p==qByEiID_e@sOVtyp63NO z!upAMHwdUlzpV%Jw*~q-nwq}FAfORIi`)SDe3iJjFK!`RgV-=^ZPFfjs0gcY#(R%m z0I)W*X}Hkq+zx4#6K7reaIUClPDH>*5wr3iyj2c8IFjh0ft~W*H!Eg*6h1t?L3haY zO*_qoKfg&FZmjCFE~Ie(++qKjh=hiID0>d_f5E?A5G5TYx-$L#gWzJforGF@Vyn@x za$*``1Ti?R03I#*1>UNi)&Q!i z2M`K3<_GZlUY_qprf?P5?&^{`reCm#Vd>Fq@$H97!j9L$-F0rgDL2NcXqGOHamF-n ziVauEHPZ0-W@er*L%6Em6f3{#Pm*HpB;AeZtl{xQdEtLeUmiVog2p7bcBWx2deAQ@T(hbU- zH9hH)%S#PY3QJMRSE~(Ct0kZ5?9bJ7Ki4&l@0ZTJ4lXOc7oB}wP50Qd`MH{|(M&`Z zuqsk;>)NuO!h)V>mh||2DV_A?B*Xv=nAR@`k`O@y-fY{A;jNQaeuG!MRCfcnrz4r3 z-kPr=IyeHKU?T*AbjgIJ64`3W#L9s65_$n~m_q?Li!a9ys#}h%hAe&@qzpS&e|ReZ z%H!>3rd&uhhffS|AoDK(d!GOMEikQCoF%+?3p?grBiQeM=VOrC){BU3jrwDJJmLv{ zl1e$rUx;WkNnplUPIN1_7+?LSTx;icY|AxOd#W00bRkgHoga35(A(AH?AoU^pK|%M zQk!JDgSx?kvOY6?pdnI!x|e04(IdOlA6ZATjWoCnX1eBhnF%H*un;3gSykmp6vN)cQW-s`PUDQnO6 zvO)FsxLS8_edr99snb7Xkp^ z{{{891E#rJc2XLw$Xn{~XVUgCrFG${hD@rcpN6l6ynw1Z{%QW?TLYoxEsQ}3&2!!H zGd0a+a5oybW?NWLdbZeye|mo>b6}onYa$`mG|99@-UshW^pz@MTOn@hPdH zm+7x&EW3IMBb}8YG~the++)Id^Fh7K;e@KW?|;5;2vYm;=3i4%*c1GvNZAIyqZ zTve5Q5-Q8kmw|I;>5bo{<^3Kb1`&W%bXZVb<4elhD_)%{p2dY#HfxTF!qcUap~&SM?&mN56rCqIUVsYy5_xP!vX(Ic3UAv2SJXPLHP9@$h~6){-3A zyKOR^bd3lxBfltv=?N5Ci zd_;ErXZ&P&2feb9Yc3MjxFo&^pyNy>yuDdu{Z-+!5 zL0T5?qGv2gNv06#_V0rio;AR;`}Fnd!(t&dV{b|_%`PIlw51%gLvfs{qj7Njpx2alAt1TGXWO@QQYMjw zlIAOQP&K{+48%`WDnW@%mpF(FsI>(nvElOBET{SZ&WRzA%vr7vJ20^Z`|B0aGIX{2 z0(se5(IVb>6ZG(cU)CabYfsXfu@GhdgJg!rQ;x1W^S<@WtI31sWK|aiH{(X0@wutSt-sl1Z;g%8FUEq6E|xvs}}<@guq(6(80(!ZR8kd$6m z4mP;zP6U%XFUj2OCfJ0zIYCNl&)rOFB=|&F{La|pUy!*lH@NJ1$^Yotc9A9n{(*pI z5TN-=mi1TsT;xHM<-%#Bq2?zqwpLzg;CkGBh2u$m@9{ADk44Z5sh{91fmIs@WVOHE zJZmyYBjgMiPCg8yk6SigclB;@9os?}0yg}#G;2Yz&`;U`+$KATc~$dPVL09>2qBG) zyzn>JAj`_E-ag~wx@0QcQI1W&?)V2c*_z+Vwoj-XIFQ~WozcU8Vk0mQFf{w0sox@x zPV&3Nh`m(*O{{UB(l;7(;_Z+vfC;USH2h_Rw;TO{0qs~nfpQWVp z((h-)57VV7tX+H`ZB(;8i~K4;1BCjVo|K~+9~G*bLf5n?8aVZGP@&CY>7GZ~FLHWJ zTsh93A4p)tv*@e(6&bFx6R50A_~jkj5t#Ma*>TjFGaTW2DT}~tRW!b{ zCO{lP4^KR&=8}8*Pk~NLhRoDAQ{p`*sEpcy5Nx-eM{XI^5)2UtnDm||RPTUd zA#JuMn|CRaf9RHWC%xh9dW+y7j9fK%Xmq*ylo$N!QGT4&GQHJK5UevcDP3t!b#)zb zCA}M)m3ii%tHZB;Hov>|o*~)`99SGxVVoq*SH05PyTdO%0W*2>U~iA8k2RiU*pycb<$h0Sy|1qiO|&B@Zh^Rq5hg7snd}3h;@fw zR)%q+?ycCWs%BDSZ)#RU&6@^Yr$Ohn8b#Ny0W?)rJN)>MS&w984!#*XIP7}*H^nyz z%#UUY@;~=o_sGvKp3vwobrbrvjyfmm&+|=qKSyE0P5s@}RS`cEgWY`Aw4=9pgy`>~ zGPI?J@Zy2l53VaG3ci?>3@U9mmGRs;?MtaREeLw`v^PV`mQ)L+uUznJ3S;^o#@B(W zwp7fOm=JMOp0)Fhqzsp#`3b@uRYEbN19x=7vAMgeo9B+;#Ly!HXa5HIIVjuVcfh2m zE$@cC1dEO^S%zblP>7U%KOB{mH9v@&byV7H)P-X&8`4`^(Xz+1x5o@ z2?XF`>Usa#)BDF({|>)!M?V&MdSgUDc4_Z9xO@0p+W`3;FD4UH26h9s6+e7kYdO4;;yqhPgU)_SAg1M$4O zr%xs|!Wxn;30Nv&S4(8;CEn4G;iGw`kN!npd3idV9LUVy;FTV|Ai-=<72BD!3+QlT zdMJBGz|Mb>kNJW!rx`>y4vB?N@?Fx@#%efQHOsF`#zt|>J*$)J2_t=PSIxEO;iUDWn+h+A9{h-0}TQB`)*YVaV9Bk z0_8;cH*O6)-T)gfVKc%_z?TdD9fH09>ew40)o(}}u!J)y>`v4L>BmC8rPj^<`R8w@ zk=sAe4)JH@SFO*h25SRx9c5D|PMDFhG%jF`z@a$6R)8y}B8v3t1E5#Y0W6dDAiN*M zq+jK|Ef~Za2?9mI-(bdvs~Z9UTsCaFfwVPa|LO)I-lrR${4wfP#e+=LWF{?|Qc0*H z^XDs6fsdB24r0Vnpapb<$Z(u-`|TSDbNB4eKHQf*bErqjN)cl6&6(1Tzp|71PMl%? zb?o0EeJ9>J_7_p#i4$Um>O1k~vA^8cccNu!`@P$yGbUwJ;#~^(Q%P$MlvV$2m_95% zHfy{>Z8+>VZ3f{>!9|ME9Vj!t^A=0TnPf9m(f%{X4eS-eX`(tzp;)nfUA0u207JQe z%Kzn8)>e-2>(BklzFK~cAU5DNM&%GA{f_@fF$wLN#9t=>Kgrwao>h0!;h#8~UPy7L z_P;D(tJe6{iK+04lRZF)mnG(df%yk-&G=}&4}#&-%XtVMSnq>i`IEn{e)XOQ#j7VX z{c5U6LajA_{&aERqZRArvnSsA z=zj6p6DQIzFK17@`O*EcX92g4>Dw;R&3_3uzv*Jxnqy_vPY%<4o!*aTNzFFHX}{JE zQ16X5c$k%6@)on~jL1Z$gB^Gu=i4Ysj!W3h1ZM0Q%-;Tuwe?@{=Fk6)eYOA7(INj4 zZt9USIKU?}_Yd&-{!Y3!=T5r%Hk=Xj=MfRo4+eiB_H~Q!H zR~bMoVfil(MLY`yzh@LuiWEg$v%|CfrpipEM>6G0D1-g4x+S_ZugaDa9(B19Cb^i| zuI0v|5r}u31b@p=akQv*TSzYIzGu@mBbFz#*pQ7iG5B6*DJ!u5s`$ zvg<#A7t3yN;c>1PHpIp)V}?XF7!o!dUmjy>7MFq9Tt*k2Od46dB{OW(#m8kyT_MYq zx#OvY9T^XQ^!ntik^$+!y{DOh7arVqT9B@$PctXeq^Y>4VPV?p*F{+wX$UTHPFX;2 zxEs5`$Op3J7hD%)AIF}Sup-P;>A<;I_`YampA@_4{YCvZJ}E8{uUCJQGqP{N`RtdS zFFpoC%9($}!m04gbF%EEuI$HL*{QA%L#UThH_Vc*KeJSZPg(OpEmDqNTfOUA)Iz&8>V#KFKU3SwkVLt+j!N#G#iKyWd_MbngWcSCi z`&$_0yZi9N?6(Wy9USDz@mnVB--k=S&Tq0#p*-2}b3{z1@Lt#vvi(|w1HI7bQ0n?y z`PXlX+o{7MkNsAPh9Uc{9r};oBKf2pkyewP$fAt&XwjB ziKvQg;_$qUKVqrO=w^c|wlRu4oq@aCad{srCMUOU3Wqqw1z{hDxF|(AfkinJ^xutE z)BhS}l?6IwGFO!hRyC_^0`|yOBk?fob=~$eY&9y3hQfFDDL>p-Sr#qUx~{l)dnWPJ?mNzvXMf-&mH@vv0Yv-=8Xy1+GQ6 z%VjH!t|GqMrAF6k+0)Ov$S-feE;VKw4Fx%sKP^|W;!TTZ9P1}Em6aP9YQ2f(_ppT@ zLm6Mkg*t5eGGz^XqhSP65gkk=r?-+;joj3^O#gh!DI3rBO5eZ<#Cm8ZlL5DJ(nh@P zUqw9I=7BE+H-tZ4Mwg@Xjh;(9D6_}fvW;mLfdo<0kYFzFr%3v0- z6B~Z6{AyXqfc18p>bHDtZX|8q_IXu*B><0r`-W`ak^?E2V+-Z@d~cswjgU#69XH{} zYBj6i!rCi^$Ld28h-{msGyRk5hQhlWYa!|M?v$QHe7~f+zH}#y7?@brA3`%#71=n? z2@RW&a;8$&6e_#{PF2yve8a#QA9ts|#_z6p*YDYTL1dI9xqdci5_lPo^wM|E5GS2B z3$`ydn7!%UxSFLZk=b~)oUlzP^KKu3BY3F&NMO!V$X}$4rBINoKe?fQcrQ8c6GHl< zhifOEr-;F4=;z{@PM8fdrq3QdXLw%vu!J>LGGZm_jVg&IhUMR>+lFP^FT{HNUP`do z(D^A2U%?zrtl1g!G6hJ(B`UlNU`nJge-%wKS#`*S0}&M=e!jDI&)rnPQ7}nZ{XSN4 zqy~W;S46MGLZ>DT(HV;~BQxfK*WVgs;Cr;b#DB~nPE5+w{d&sr66Pet%CT`~%J$05 zQ_4lSa^WyULjCh(J{PEp7k^KJ`RLb@SKmITf7@xbCAk#1&dc0@3#IVXAgO&~Z;O9z z>0XlTzy5^@{AbH@Cvx!L@#EY3V8=FR1N|%N$ngz>*^CGA6g-Sn)D`LfMk+v<<82e! z4Me*W?O47y8&^=G38|xCFIT`fAVp++U8SNnpScz*!zx5tS01oBEXX8f^^ zF*qUKfZR%)xZzvFpM=uiv)2;I0|0>kV;AlrO^#JhZbRegXYKgCP78%(qrauYX(qlF zwAttbj&-+J3KHzQr;H6yw3V4P;J`Ors{m_9{bt(lrm#>=C+dft={A(>qIbZHc z4`$NtBfZQJ6@Ia2MQUK-7RQQI(w9t8#IE!@avXogEBFg+i6DQ=)v$50;zbNQf310t zJ-+ZE_7J~=my+csj1tx1)+K7e^bp}U|!hwCsfO)N z``(LrQf~9jC(Gy%2chPd`o?imleP0^{alfL3}uXE7)UMvq%2~ zfsO4|aqQ!y96ZIfKOs2lR>UWYsp`vQTHt6}8OQgK$a45(MdNDQf z)BbPCs(4hw&O=`iFK&?l{beJGnV;aUVn#B;gi*v{PNAPi+PD+b9eZuoNbQ0>)^>`7 z1KWy^Msio7E?yxu;3d&Nc0MVADDAO(YU9Xbf}|!s&@#bkw(=PWlx)|$dd;3%&F#-$ z$4yXv+@**os6KjEqVoMN@u=T{2O$!0^vClc<*|>-;#vgYnoNpg_%RPmlz$1@K;yut zZ7x+D%xIguaX1`{L>04ty3ih{B`ObG{2R=`Q>nJV5wV$N*##($g&DR7{l`MUo8fV? z_&gg%P77v?bDD)@d8{8nR1x;9xe+gFyo|#!ZnAE)&y(i?{@M22h$oIxf9mZHLOgvm zXZ5Ci>7}MZ;QYdCHA`%BMwFMFv6q~r4HXq*42<2;6=PJyUgcAYC__7GSR;T_82&~J zlta$gA@U6uPa^YAPGrVgB@=tasr-z5;Mbn`B*9@L;#&=vx>fc#T%tyXSsWUoKk2Mf z(ID;>4HBzLpl$HtR$1*OFCTpxWt69VwI?C2z50pC{3XOr( zg}k+IIjy@$|Hw=$*yW@n{`k>v?7B@ClizjD**k8=-`wvwado8S9jA7cIN9N3<;aI? z2nvK#RZLn8wfc3Ye->Yru*gEK@C`~BV~`~uaTXqNuHY|IH3ikU7lQ;M`Lpwuw0K`F3$>v*ogIW|m7BUW%=tLN zDNhYz(%$p(T`00r&IQ+m^ZZ(SL*Q!K9ASDIr&U0Ep3cBYKVCsS4}o2 z(ySoxFzvD=BR-_m*xFK6#)hAXO|GBIV3(b1tU9Rwfb?yYKhzgFWAE@WSwR03z7(NKM{zK9TU)66Vm(VU?u|3E#$9bALYo;9cJN0jl zjf}_d&5UNKDQKL=Zq@iV*G;O^Fj3#ioYr~nnNDt|(=yXZ;*!h}cOO3xCp4X_kCQsB zsqSbeH`NJ?!tw57K}eYIp6cXOPPqR@%@rQkL_IkP%E;=F`q`QWQN}Q|Kn=q^b{-0f zMm{}|PfvAa4!4l>w5#4sQNeH$lrSmFhBHZ0`A?&~ON=gLyTm=g>9ju1jdxo7`Tooj zoBHbauuf~K8*;G3nFec${p_4x^yLY+pOX_h`+xS5>xu;3K@|s)?TF zPj>nN3DTZ+-*Rx*9BCK5lwXO|eZ%3jKEwUuNc-Bm@sJDWZz5bq#jtbZ>B``QyU~m4 z0;BV)^*2*kf+}j|a--8^s1NGSNAw`(vlI-2J(OJLe!kIPRrP*80#k-<)k`2Htaj zj6Q|qvt_`cy+=$YiZ$6arusUW3iC9C;YPTRIJh&8{$IT{ijZoj`yG_HiyLr|9p8Su zIZ@bs?m!~)-R(Z);QAf?m%QgDv#K+yz~iCk{69K0ZlKR;y~o|>;NEidd%W9=GyyvT zTI^AW#yhQ1?!ykQhwmD$gt4=CZJIF@O*O~C6pr99=kJbsfZl$=y$=n};JO@XA7a7| zIO*yRw*yJ{a&3-sxA$Aoxnb#rkB84qK66(1v0&p7lm7z^F%5y68XC9P9CYp9ByR8_ z29F10e6~|1Q5Y0mgCTvYan+wWEz8~ia&Z50SgIVJ@#1rR#}3LrdLX##hU?eYCc7IQ zPRpZQy`!JpEa2XTx4&^)9MJM_Jo&&DFvFW#n&0w+DkS_{>BmNvF&U#LZ;DRzZ*8a< zaP6;_HyBOEgzh;FUjbneF;+zXC7IB3zkiyho^4j&F?2#i7L-K^8{s=Ls^JvD}dGmZfVE#>aV99$`n zgY2dQ5~;fcjZ|>OWHL7HO)>^{85NbmY{$lT5{AO#uhu0FCEW9oz%Qc?!3it25~_OF z$T7j>u6RY2@l{HMc^i50#o(M+{DVdiaj4YEpNIXad3;s z)b^hm9iz!m;|h^qqMVlL?i2@?;jrB6P+t{Y?fWfJXgpg19J0)CKkVRA9N0?%+jw() zpxwFYOE$c@L26Rf)Cs#PV~9q&xrc?@#AfL?JtLdh{_EbFbL8dlm*-Sx&Iqe-LNTOa z$oZ=}*PNbra8hri(e+Kw+ndLUM|irZcvY9Xip^amUAAl4)@84-qG(~|`^&ysHf8CS zOocM}0aa|IBXM@D%8{5#ewL7*RU41Qr~(lgDLO=Xj{}|>M;|;zI-FsTerOYjpNlDJA4NI)aL>}8QFc09>4j%2~l z68!L4SbkxA#rN56$W^gR=L!qXE}aV+bWmGb9})=~k5l?Ws54NEphBFEC`y$26bKG|bs5Na#y6WEc{hbGAy@ z`3b6Q5EoS@nOa^~R-}@w(1qlx#>s~~?oKEeE)vF02ywX*}=eKJNm0!eV(;u(tCC?pWGXU%ziw?%P*4HC4)&iCYZvJn?A} z`i8b_Wqh~8Nw>4tyDEp+`OD-5eaj3iZ~3+xG6R-{ZE9^XAg@P1SQPR{Xz>gH^*Q>}AIh%so_4n7ZjIj{TzAdqQfP3{n1V}f=!aXSMgqN()`}Ne* z6^gayuby73+xUBjpP>+u^2l&klQRUlxNOv@JQs`cr9~oMmy?UItIPv|rrhcoFp)^f z==^VwE{%*X`I!7+<1-lB1u=3PbNLYUe;nIlcR?4oyvs6^jLmjHl<*80+Y^a-(`_^c^o3pmU!$>|8l2vaY2$oGxbNz6?kwdZx-7$; z*aFl|qW$qKdg0vp1UIRxA56&9NWTYiRh>5!c?czP3F;d4A<@hLR?gx+WJOw;ZI1}- z_{#wUv(0H`)klGsdqo|7+P!=;XZs$6(o)Di+#$BTPn|W_d~){o`+IQ5Jk4M^0;6ml zUT|8(UY)2s&p3Ap+}As~>z$S(odA_*y9kG>gOl#xQlf;Sc;MH8_nfokA3H&8 z0mqV{^!-elf+|r>Di#%)>HIQ3?N@YM--F9r6J>GcuU;0-jcbWL>}QvuI`v=Z;;?+6 zoWPbOD2XHL=0P#FCZITMdbg6C$tXw}6v2nWa}nG&+~Kv01(&`80XEkVG;g)qJS5C6 zHC05e)%IMVOJdE>yE+7(Y{B|{Z;W}@fG@Qw=`*JlhsW85sB-XVz?J+V%6+ucxhsk5 z@3d5RYF`uK8bonY`4$8=T)k!dYLnFcZ+uSX{@n?&jtt6gtUfX_AuG?ndJ8M&#kFL? z*k=E^_xBl72#vvLh>M9DceM)4_iw>eqyvTh4vVaP4|-U-Sl)(_92NnaSsKAOa4*gp z0aPnwJ?00|?(OKnYVOTW%PJlnUKOzuI+#rQ@`STo#OVo6E))>d?!{S(;xI{6ut4)n zv_MmM8=njLF>XQ~FLJMSS{8Sz^{4=gb>s)dDfj6Kn;hiUqOr2ED69NK*$(EWkih6A zl>dd(bz0_is$UjqRFl9J?)ufev6FkL6RT-p3c+A@JSrRyPFZ`gPu@5Ti~N= z0Gh3zU#z3^w*%zfNnIxRPL zYo8ElcvCIGEt6_9GwE^vZmZp?GQ%eYC$8+nO<^n>WVahM{uPZ(jcP2;Ahruh)VE5z z!Q{lDz52PV@hr@n_C7*OjL#zW{5B({2~rqW65fZEl;0eMr?1>(yP>u zG9){RflrU-ukRJ1Qfw8*vv4>?y^Tf$tWWzDjy*tXAI;<2A4lX3P^zy(1sY}=C>6i| z0~Wa2htW5+1C6oz^Z`WnI~-sUcIqu8ZLmw$Uxi_YYnN3 zS_%385Tg;mxFxt`NT3&>C@G*U_0?NF6v`<3Nr42Wx{R2T^Ttze3#s{cQ4*TedB2j1 z<#wx}NgEL;=IN3~f)xrXZyJT)q>F->R9Cv{Gae>NN_k*+0;9Mnn5$BZ1TPfF?%jPx zzyl)BK`Z~-;R6NWkidkZ9SuETO;Ac?=uFJl2;vw!zeDkz02lGa#F?SEQ$^BoK@>Xs zY6yiad}jbx#DesfsS26Gf9-~&kg89h;O`WD^iATjs>g~ytGX73u8U}-+Co`HL z9#(Rk;m@Vs{?$vy6@9101c4?PK*cvc+g&5R-d@q|9{I_9b;9dprfSdAs`=&UU z-u>#B&WxvpGUJ9#%q!`S_y`0jxp$wy7>J}PitMRdV53q8Gx8MLylTq| z^SbI@_piwHJU7x&4)(t2SOmE76-^5DA;zE-X#5mA11}jbHE#bvqdY9E4syKEW{j=Q zP+sg%98^H=IH*|AthLfJg^NV}T8>5NbNlRj^n!xer_joDg|{Jg9fgGAv?gtF`)zT z*gvJ%KkX^$jbPLdyQ@36>JE#pL;IW1VeC*_X`)x+>q+Tbh~bk1WB+3Ci<%OK*bwa= zxRm1FOCKKgsRDfxWUgv_{&{*4o4^b_YgcLSV-^J@s>1V7XxY$ApB95cTvbFA@ofLy zfVd*6z`4c*Rb|kegmVe-d_qPj1fk0JG~#n0+|%n+0$qbHfoX`F(<3seswykvil?wF zt|xAml6w2UfdQ=iYcgio7ZKzqHa~=RFYn-%cQ}@JSpL?5JnD$+)kOYdWb{BWDH_OC}?^ zU~Bd3)}vFjFVk#@dCC^xpq1=~;d#hLN~O-nFZOyL`~aH{!S+XuaVL!?Sgh(31V*M3 z@jZ~oR{gsVetB7b3}yt}*{i<1 zskwcDByU;d*P+Q{c~gCPJth(g3`nO6lFz51^M=dIWp8zur;+9_y6OL#R9#RffBjmA zSo<`Mb&q$0N+{3x9VoAUimnb*n{MX?%_01-1S|d?PSRl!bP)0AePMBMK=P6Hl%im` zpcjRV4u^F0CB~@=H2qk!$zW%y8oP|Hs;UMROYABQLzQtGuad@6Qd`Kx8&c-iZ;8f3 zLP~vbu(glah}5g;>KA?M-ZTDtG8voTjz{xDLJsY6#@aWJ1HFa!2JahwA^RyJZ}r_JnNs-ScV`KhXV$##WZdiXmNjx9FKD!wx|6Fek^Gd zkvs;j#%wAZu)E*Kr&8|ScF?v*GteR4;%thom>lS|taG1k=Z?1{RSfkI!5?ER8yYho zCWa1C^e?!>Xnq#Gm#9w*$*!;*##A_yljb%DR0kVQ zE@8vtig2kPE2v~Le?&4&i3l({+B9kV_PW*-9Ul4_jC_@tm886Vi=DJXl2l(-)VHuEX&u>ApmrfmJVJi$L#7{% zN*IjfB$5LO!HL8TL$)p$UxVbqLir@>eClB&lR+Ku%B!eReEsq==#6IuLp(<_RPx!^ zY+AZ`D^ot?buYlEleo0@v;jgSP+vlweBKS9vO0mrO(RIFQws7wrbq>kg3$WX1~RN% zs4b5M!TB3Qy6KsZKggqF8m;|leahO-)du}7o?}9J=1yudgdBRgPo-zXiEJh(er_h zV66rKgI?zX+AUYwJg*5eRJO&4G(|OUoyZ1v$4L1&+Fc5;lOe>sGr6hgOI6KQ9hNL_F={zs}E`! zmCMLv$b#x{bQFW{QRz-p^=*W2!{Hm27c1TH9bvp(rrB zxkt%(i3;i-eyniE+wk-Hp1*}RpcR8~J_sbWArj9GUlscmtep}RHEH5urh{zowhC`l zFcZ}njmQEx6oM4ZR(X&Y`{hhOa#QveblBrh%ZF~7)60@@8})KHt<$QN6k0=O&rGI6 ztUqJt;lN+Xg+v3tqxQpocmF6Yuob)YZJfT%va$`|)lc501-4T6%Wd3CZJ-6V5*kMC z`~b4_tB*QuPr09LV9kHf|b070+TCcY`CAaGVmCHdMdoYzlHuZsQ^eIH59) zJG!ucI<~*_1=UvfJ#EgW0xqHrdnOppKt?wjD?KjAu6IJ%6jmrH=J_D4)8hI$@<23dikCnT`%8K z`Bh}SBw%Jo*ULe&UKWw{@*O?8zplBnUOpgg@$01^j(7RhW{?GwP`50OtQInhw!Ygl zr!FO{Mf(j6!UIkctHqPfua>Xra?lv^o<^372OFQ~Ua!3LT0fQx;V*Xxu#aT6I-47~ zl2%JQm5g;jeMX6gww$)?t5s zPXjptP3L(^?L%H;tdv-zD~BL!6ibrvSdcR3_0Tvojao<@=V@#f`pRYyN3s=y4CI<= z@M=lwEw;TB(93+^7WtPq;JA(4X;-|rB@&)a!OS^^R}Zvu541WSY_$ZpYD0x_MEW3@ z>jDCzq-MzW0m57Y2YJ42Tq_sX>WFK#NLmShI#Fm~(gs3pQABYHm~0j#aHoX`nPz{l zGB#65`uV~2b4uxsjQ1K-H=clRk1;l7Ww2Zm!1_l7JYN;q*p1_0jYpgd6OgxB8s32D zJ@eA>9AVUzuiUh=W=@kBp&lA3;_SY6X8;Q7Lm*{_P8ED;j4bQwE@LeN#GWnYl z@h`d`(%$Hr{jP=kuElYw#d4{|hAUZAljKG?=*g{SVp0UUk$l#^75ZVa*IWC9ws&a5 zS=u1U%Rdg+7IhG86&@LZ?bOhpr)qw6f7-%*+Tu9hVma4hyNP2zq&&+c@yb?q;uC|9gi zSdO=N_R}{G=m$tw2AFO=cP8H=mCGosOEA=EX0|ocsug}Gh@D}LP zVtWTu5fqA8k^1+W8_8-kN{q+nbjNEu=ro)^)qN+>Z5CE{>rXe2eM<=QB~A?;uRqqz zyJi_fQ6}LOI*MCT;O)TEj+`|uppPP36>WKnZ$BVBwQ!Cd)no=F_cX8GGMy(7C1eZQ z5Hd#|!3J+%Z|pDW+i+}kw~!UAPY7UxSI-go)VYHzWu;q57yR>0pX_ znkUyj+JZnGmAHiqiRu#C7#nUhDeF#ztT%ma$#3x#)A+UFH?Kv_|9Z5vC9Oq^--Rt| zEv-*zsa;6=*dWnowA3yjk98#!(u_DRQt6KrV;|D&xSoh~x6+@)R%}Ha`Ats!LoKaj zQ0kQ=noTYJ%)_Mg2ERjoK8~_9Rr?~1lnkMK9aVBPMa8D?m-(b5^qsYFacsQpO+bvtAzr*fkDGq1)1n-UXkA+?c1+t{~X zc;;nchhK6?(_x{iP)xEXUfvwA@keA-^cd9aLbNMnfbtmz_Iocew0nM1?t~BT?tk`O`!S-k>rVCsR7@b5(rf`OKt^ zzgz0<+B{mhgS3;tgvaAgB9k8}R#uRd3RiHj-&KN(Q<&{)C4_B67f8tT4y-&6rS{y^*r!E~mbsJoWYe@r z6yIFUSz2ZB;iZ#L{d_M!^-t-sn_rP>^@Es9!dA}6=|XHf15 zc5Z^*5ooszHLG=k!3vqO_dW~#va@p9%r2%)GQZ{wCXOElKNJW?XN>x z8Pr1#dyqY>C8(lNU=M8xvIlj~J@Buc_%1;K7^{7- z$oZUX+|%aslOHX-10b^aGy_^(a(ESy+d7_V+xsRG1=bA0e&Dv)K$*s*qQt(Ws zb^LZp2+lQI2g8$`Zi(|$1mqkuzY`o5XkP}!vdsX7fX)z|(a~nEzu9rD*|N3S_M{-E zp425$PaLhQ_G=p;SXF6h-(}{{Sr{dW8%CQ!dIQgPJEH-L2m*ww)Mz_G&+}eXGu78l zvZ2{0iQ6WSy$Yu+b5jl#7}X;~?8- z5oMN!xw?@-I(ViQQ3-M91@6LTZe_D$WwT{EL0fGuab5d{ z+7t;j;x{-w=^MOB(%eG`X^X@cG~FmW%vfeMBQiRQd``yhqeVE)B-JaLtEzO)vM$}a z{0$Uw$S{;0vX9Oxkmqq5k2)HOkqkXSIXd(*S!{eW8>Hij>)6;meuUWgz!nwu9R{?5 z92)WQ)p|AQu~CAX@g$>91a3U;Jw|q@dz-m?n;rKyTYhQsqzYgmoz=`uZ+6UVhH)YJ zmnI+5XfIL9YfXko3PtTuEKQZnP)_howT3ZGj0(pNT;Cg7GtE`uoD73+4K8cN%n($- zp+8(cF0|c5o8Sio{IubK5ODv_aBnp=8d<_1kIEswzW-_eR{J2L(op)FJAK0{$yLsrK#X>Qmu zgW%XnV83P*_S%yGqUS5XKBZ4W7U6!Xz*#-t+81HlN98;LevcU5I!7lw*}01lG{WX? zkbt$s-y+Ep+>Tu=haVhy%UHq>So;Z8xUvZeMsf8pXrjP#gz^NF$+n%N*25>2mupMJ z@(%^Pw6E?PT?K?&Q)t5l}gFIgcs|zO* z@Ip}nO$fmI4oVPKOqEh3?-1t}5oLh-_!v(KyBPCz@Pw#FMmvDxBOxT`TutPt&SM~j z=*v%fRnvG!GSY{&6q0NwP^tZ_!E9rhX^l9sUNKpyP~iH(a8;V`4Buu_uV$QbK0jv$ zGFZ)6n}kRH-G(G1REFD+D|`$s2=^@;8(jtGFOpkDDJsi!IFK0VTeWE0^0^HIQ#Vsj zeRfzD^P~gN95NkRShb&pi(`9A4 z4T`}M+0vj8{aw3Om`M4$Xew&5s7@8MzM&K@*_O9S_iPnZZ9jR4i$<7c{Ka8M*{;%g zymXo&jN0ngK{yQUAThp}zw`PKO&v3Oo=MIKaGH2B`4 z&9cp=zRbin5|{wRUmx9R5qZFK{T32hMiV^Kd0Ykjw8P%wY2)4R*tmCXj(2UAa+~^F zCbo)HK-Na>DBdP-w-K&p3c6ANjXVA<`vb#BFdEk}4ykbC?M?+=v^#l%nfx*t3S`;T zTge7n`P5PGp+Pk+z~HOX#A)KlbgZW~6?KSh>#3ZLHaj6oMp1LO5Pw@lgUe;Dd4qYf z!(z+dZOi%n?BJ)KSl38MpfQS4AjyCG=js%cRl9HHtR`d8hzg5smx7XR z6XrCM2o3m%Z*HJ7Rm(5+ANEqp7@Phtq=<>ZPlhDDhjnkTanIQt>uu#WUL@w_FO5Vo z#f2OxYAR~42oEYXwO^IQmmwE~kWVE%3Ml_TM@h3KLUS5kng{CQb3*i-FttZKTOZwd+oK?-h1t}Uu&-=RFtmSG>`fYFf9*`%)*e!G&D>K z(;joTCYoA7kWXVBYL*XrmMiOlKPfUBQNVv2v zBYb)?56iKnbQhK?&SzTp82XwSZDIaZz@ZL?pXjCSq~_1fqQ{2hOc>Ni==p4KUjVaV7Loef-=D^wJjve7m z#q+6Jw!m;$=clZYg~mJP1>_lOz8VUaeR2v|@8<~l&>c4nhZ`|B)THcDd>^?<$MVW9fZv2qeHP$=lQ&IPzRzJ)fXYIjj0XEiY5BOwr;K}BWr<$e2=Cbwj z^=}M3(Hy8~?nv{Jj*lTR+{i<@T;V}kjY#6j5jh{1*7&HIMTOL8=d+Won$r1M*p5RY zbgut+U~zNcf##0I#NN2V3)6u8MRGISUqD)Z98GMMIgYc(HZw6!+n7ked$6=*&Y!T4 ziIgsT**<0nHoCPV`jh2ou!02TLL6{D(4|{H z0hXLX3#qah)Y&3ir;e1=*_|$Z;hhcTBMTGPca8n9tGlK4YEMWm+PS<_ULJ=uFiwRx z3Z6hx_I=qUAhzs&?rZr`xp3cbN$=Agw=_$)G@D`ci&9>{+8Qx;W_hAv;@Dd$JccVD zn`2qR<-O@;%398dy!X6FFh>~t^f#Nhv1Js|#wV`+B3K@KZeUb%U{rI*sAlOkZ`pD= z@%=i7GokWZr_pKUm2NF^Fx|<}n80}`O+aki!Mlado#E0s6U}L6UG|-bzjmlM0^?Gw zbCkzu1gk66ooLQ>W|&j|4ItE@e5qZrZ|%4+o0L64gD=6Q6|C-@)-+%0#Cn-Km5*^# z!8#=~i^9&3*{}jx1kVh<;cv?wSIX|Xa=nj!;-zatfn)~u6Yt)9g%K9w&60!ON@d}; zK|Ut%zPGr~|6QN0Pv!Uc7caIgP`whlrnA%``q#cZXQSsmad(uqTg>~5*E!4nmNX}` zG6L`2&B@T$inOd%ZB?3Y1KyU{Z(oV6e#a}l<1KFU|9WXvRdLlO6@0O-ZOfnKDNDbr z^OjEW>wzwBV24-QLH$wopuC1%bd4ja*>fyN_T=^(&Dv{fXH++=Mb+2VpBp7Ujn1-xF#>n&R#FId85Ddhbp70XU3@tf7+3ru!!eEg8x6N+!#LYXMZe%*v%^uqH0Yr} zVxcO)^RJdOyx`^2rkku-x6P@w=vS<{DIQid2A=hHiZ29y>6QM|Tb3`k!iIz>TaHg5=4?O6Ve(o)^$k7{+?}B_yT70M2G*ILX z%=b$9UfOZ|R4ydM3C@H*m;DJ38#GaonC^pXI!6!O10>CXIbP|f-pmUJNKJ9{2A%T0yXX8N!b-C?AR;*Dl0^aSImDuiR@{pelS!|i` zsjra&Th{CxW&iV*x~^zm4*O>)1nY{m4h&@JU!FBP^vv%aHfA4V*`WFYt{A z6Vf7iVKZ#hEu#64)xCuK6-V-}ggZc$9r@94uZ-{r^!^J2XDX6Qd(OPVt(IZ4@NiV= zU(T#dd9L%U6$z0mlb1$3pHz{#^0uWDo}Yq8KiI)?R*PO~XL6Ja%TqpecjN)(`ai}k zs1Z3hJFD`q*sYu~%*R4+fPem3=O}Khh5K0gG%4bY5I?TXW}Cl$-hFDZKv1urd*4G_ z=%I zQP&DPU$21a;b<&t|CBE;UwDhL?E%JPf(P$E0pRo)TYUIyEF~r#f2KVDqE0@WElt0V zqfBuf$F?8gkp3$ijAMjODv3_O1;Yasu^9JGn!->&7WFC)u5_y}(Y_S#ax0>E6MLV< zg42+ezxr$_&9){Y#dMipNUs=C*AlG%38)J{VeB_mDEXCPHoHbUm->f1Y=PA9-iqQ11UGZ}H4{&D8%<-tX1dq)f+)88wJB z(>fQm{O{_heVwydHvG7PQ|+AnCJ!G|Z*a=&DIRBhy3eUe&vzR5US}R}a^A=5xKs><#~Pa4}5$BnaaZ4!cq`2IGcu$9m8 z8Uv|086B6Ke6gaN^7WFnI{d{mWqD|DAmECt3fb_9Lx4JtLA< zW@9AcegQyLGz*~}HJ`Bby{8=8uG-ot`}foB{Sr@1m#yr0U$XZ}&pP>?zBaEf7ICf0 zx!*r|2EOVZY7QYLy5b@m>mxj=R!`y6cqPuWLQ@~r_x2Ubmgn(N&t=hj3GCJjOB977 z{2(qN#p?Zpr|j3mjvlqk03KfJfEj|txrlTt$Ccv`G@8(#miyIkNL>_(#|$=DRe-y5 zC=;%v$6KX)6~(1_KwBe5JdpCW<6SkwQng|U5vbg%H~@<==`ZBE4a?wCb%B!>9c3$q zT?Q!mhR1M1an-p`X3ISLuJE_=v&AP?b#A|0{Mtcrfo<+gK>JpfiouSQruI+;Z+$Q6R5zH?RM&VlL0TE3ht*wW=%jx;xC&ZbSn*CH{zufg(;hK(U-=MFHt}fLW38LEM#Z`UMdk0<=OI{OzwiY;4Qa&b{3bF zR*ZP4<(G;?U17){1Q5IC>CEmTk#Bkj_yx$ z4CRaH8JkXHI2JB5Tf@Tm$=0!JN@B_o$ao1Cnc?p{w#-J)hvE-6;($8znIfSotI32v z@ocAp%TG97nDSa;d;2*)@@QlQv}jAS#&jzbgHc@irOFF63WbnZmm}|C?-ra%z_N62 zsX|_~DS}TeSiP#csu9v&FUVL|A+=&fRk_NxnyTYm;b2`<@e<{teyK3n%2fqLl*l@3 zAw|MIijq(1R>=Ar;;SlF6_iuoFI*x0x=~!9Dqg^VSCp)5gl})hzF@JS!aqQ`nzu&W zx1zCt+0I1R+1!?0;k(?PT*lzrmi;& z7O6^#8xgj>%m{xISr$f=Jkl60KB7>|6=qVYFci?OkgtDeYeZM>5UdqquvgsKnHXEB zNV(}tc@I27Em@7es}hT8`5{PLjHS4^I&9&LS}&@dwS68;7~rH{iI|$K=&zoqq2b6< z+SV>`^vWuou%?y%UFElHUZW$HIb?#(-P8Zac+@Pd-L(qA{AVq0S>U!t|4dcYOrqIZ z9$oz(jcdk5I$&~GfaNu!)|wSpeQP7s6m2gNjH8^2v1W00T_c{=;d@S0eynu@s~CJ| z{ptWy?=O3c)yvjiOf$kviBnptY}MfmL<@OwVDi?5Iv@;lrRN&kLo+}O9*FB0LQ<%K z3>88!E}fAgd4 zk8Qcu_VR0Ok3r1p18E!LNoB`PO+^`8$1_v~HqPBjA@+u*4Z&Bx+5oIt-A~o(33aJ) z;aSP1UIG2G@gkBOx}Vx?6R_@Qibp7;>=7BOm~di$pGth48ou=qetcH?s_@81i~Unz4j)+&(Yw&^jSr!Cl8zwuEu_em z*Rx`x7^U6*S8?;Ic6WRnT`Tmi6vZj(K2=qNx{})2O%mO;5UVD!RXv&N&`L;1R-z4< zK@`Y89=;E7fq&C5rWyOeEm?_5`>6)le6;s(DJY0=CYZ5Bt&VKceAQ6I?B!}JvVlaa z%cx>Ag|>nu4uW~_ZVAmD*JA=diuv=8Vs`#0<}HdjGfURbtOs7hR(-G$C0ev=_@MzsAP=Eh*&CQw0LbS+EXUpLUa9QAjf<;uJ!ip^X5@nA9W2lNFlokIVCJ~U? zG(YJKxCjkZKO80;6|lF#{-)t~^)3j+sU+)Qm@*-@pkP8);(w&9f+d}MvT}c!IgzFy zBl-f`eABmFTdx!{_OVt>Kq?wD1hWh<#vj9EA{E>A5R3?zoFBtb-DaN-!}J42`(v1i z1oQV`R^r0fKg`N_p*+{YP$pp6S%nh>sz_yt2_uPAVLbi|&27||QdHxS5I!Iv zMy_F9#?<4%eZ<_^1daMXaR0|X6PTJW z;n*!dstBxaDuS)nbxp_i4@>Ks?CYAYpU?Fr8iXco_vOl-^@T!0ahIwuZv2_b%j*hl zefpyjem@LOVN!-=nk-dLCg4_w&$~61O>F+R?j5e&uP;bypQ&oNOJ;&mN(g-pmeHZ_nym+NwS*lSKx8RBB-leDyt~7xYg}~%AIZ% zU$oU|c1Nyx^Cru%CB4<+_G2k$tE!$9nZCKet+(v*w?7zPPj}mk3$2;SM}bKt?I zz=KWFLrrLgmNVR(NtN%fJCZ$P-;`bR24|}78V_??=LZ%v1qum(9l~{&CG*L&%KBJ> zd%&HZd@D_+8>Rl4>N!?^!otN>8`X0kTKlql@jm4o;#SyFL%XW0l3tOo|4h2GiJxnq z#wv`3XtvhVoz#6$nQe4iC&jsApIsL*SI|}@&23xLK$AIcVUgE9xoNF7JP(p`!*{`e zu?bFg{CjMZV>_~%cD`A5l9mG0e<_I*D|>IxwdJbppEpkHlFzQ^`27y?#r8LznP!sr z+``$uv!u7#ru%VFmT19pH%{0o_|aZ&zuR99-P+%AaJ0w8T5PuJNeUR3nA?hr)HYA$ zS>ISXn^+}@f~rUf-=b9QT*+m{0x)IIE&8fry;-F{Yf1lB@Al6%lMahfNGz(r#<*ud z*%VMVN%AIW1+_agd<=|X+w{e@RVo`wK5JX$Z*L80?6-N0Imsy>j;;LQP~w>@s<+;O z{l|9(E;R-&HNuGM@!Z~wzHOc2hXWTI1H+AYg4y>vK0C#a0_PfMe-%72W8Y7@A5Wgx zkTZB9{^T(}J^vA+c|Dw^+SZbp4Cf<#$BFI+sj5xyvWl&$R%`UvV>+eh2fl0!eA!4% z{xS6K_p8?JS@Vv3bskswzGMI8_k{M({g)bd9a`rbJgWM1Y}~++#!e|CaHJ8&py&Rd z`lA=e#|<1tR94{A#@X)%52eD(Xca8F@Axd0GMHgDPB(C{G0;yX;3=~!v8pPmeTRAn zjKaE7tD018?wWmOV9F{=n+u!M^5_CH*znJZ0e3lj7Rj^y!*a86H~AfMD_?cb%|VXfB+g`!X0T3Fd#`I(St)2ebNF~h-5 zdF62(g|id=Gt`q6s20g+1v90}_|Ti_*fU(ClU0ckDJSvLy>y_qF|eUgvNvY#Cnjh+v9v%=H0|Kkenc(r%=zoAA z9vOJKF|eu;6KDVDDx>&fe~so!?5A&x)nBpHh-1Ni829~E)mBmcjhJR}>-9l@zR9HP z+e@6Yv@x)>arIG1Ug%3!Fy1L^goVWRci`}IPA+Rm^91Xy$#=Q*#wU^|*5(ZU0s@0i zq855nsyypj(Ef(LYL{xqg1%GSEf(&abS76nY}NlvWw!Pm?Ue2wc%(7#2&EBA!xZk+CR##HVzQ6*II2!Atcu#_VKR0t8FS8Ur#`#}|WUUFBZzUGD97SaMa<#*Zcud$}QS ziMBxiG9+I?f$z-*_1gW)6+f`VF`Lr;^Zp3E~N^WIR z4i7_fbJ^Y{L#B(kIgBjp53Z(X4_sf*z+W4vV?S@8_c&bNTLVWC{$=2B1LPEk-c&m@ z6VaF7SkiqK!H*5Q8Ui;ueakY~^8vq3b!CP4b$3Hxcf)KvcHm$d~ii zJ)!;QAqU)d&sshq`LQ~E&7;W=xN`>oGyd^1@GB(W2C4F*P*hc?x4BjBqP`Phetk}# zKWo_v)$_CF{w_zr(Ei9d9xIAAL6?gCNaYvVsk-s__)M8SUKnrlN31_W7K67p1h%s- zdMjA@!5KlN-LIO6`Q;I=ZS$_|OTxMnXS6UI?4NiuKd=#1%?NC0Sp9mC)1|4^Nj8U? z?{uai*BT>}g}-kIyh6yLnuEIW`~-lscdGf+9pimz;&#=^HqU#Pbz`xD&mNnf=8mmA zEHatGHCPbk^Lpm(X_3G_>4WG^1Nt*^9cOU9b-EXrN22#@yDX z9+^zL#Wato7JYhkpTB)QT$Isi@XK0Va^FE3ALfRDnHr?$7s2f8MP|3Lrh=q$x`oS^ z2K$&)79`y)YLZ#+E$}U{tyMc0Fu6P1N^1l>&Pa%XDPmnhWiN=hcE8JaLoOrTXD$16 zaNV9)XGH0YIc=}b7%klaUV760M;F#snF~pJv-JZ`udm%N(%tYBKvf2&G)Pk#S{~u> zru?4RmPD4#Fc1n$VPGcBgDKqq|prr(61^Z}bpbAi$W&ON;o_46>*;*D-_QIf zSqp*55K`w95_T)ve0W|$%lWbmNEx~iK3AdoU)e?kUC5Eeaj_ zXAn~v>Ym=m#{n`k_F{@Wl1lj+^&a{~@PMM@)6JRr!F*%c+@LF=>Lov_pRb(*c@Hlr ziiS6<&ROh9E?Vu{s%v_0u{piAmo+w9u?3uqcMd26Ua&%Z(2yj|8Yei)B7`!$oh(BV z;)MnHULa&n>pE_xZEF->Ab=kB7L^zS-|G|bXyk@(NLs|>4Z3`tcDloyW@z7Rj`j zzZmn#H~4@70rn!1)&2En(7zwS9}0T-e6a8E!1G{=D}j}prRO)7O@`r1u+(S7QXis` zfgcu9wA;_3C+{+*_SNpjmZ&A!^}+onXuBLD-qAxophK|7QsOtL~#4P zL(JeL`kM;-YtU1ofXgm|kmIn0x{CUc(mubQ*1}y&qrEBr9tI;k4?6apW2z&_HC4i; z!oh(4VHy9y*D_cg1~E(Xp1*IA^jY;cC3FO6&)AIaXS{}XJ*luSa=Dc4PI9~s`N=%q z+q5L&s4X;Uo1tQYH#yMqXj%PTD=~gq{FSV+N~lkIwA|2+?^ypB#%$K&apQ7=%Y5m( zR^r8>(Pa2#;#las#QGGxBJ-{9;@ZTFTIgP|JVQM2jInc@q58p02K$s{zW_QaH#6=^ z`Peu(!a+Y)p(*ev;bJ{eawx2kSd`CYo(nR1GCQuMv~ev9E^D=1P8(F?hVH){dSeTH zm*P5WKm*rNaqL}`PJW6Gv!L@r^z~lg zCiseimDe`4=e;XK6&J))WTKFN9kR3Hg65<8>^%IKpXL?WCE9>$&V9f&F1HKjCaHj; zi{*EIjhM{VOH)haC3n=p*%L}LBdsC|KcyviQjz`(rIM<1TX1YS|N729VMLT(X!-4N zyoojV>!&X-$*X^Es$BDS{q!l*rs_k)*tifzo_|XqxhHX0bX8M!k11UOI1MIVj33jUjhpZftfjfI1mZ9vSm#d7Hjb& z!MZo%xecG7BDhTVY@af=JZDwgAK>IKe+shU-;nDP`jyy<`WI8euTO-1vV_K4*~Sy- z>+9()juT-X#CUmr1Qy@+k$7|t#^g}-jrlD1J1n^#X!~Hzib4G=vqPe#a`PzPD&Sbjae${T0G8kf`2QAs7r#WXFAfGdTPhc{1MX&m z``Iu+gA+80;+I%?-%-C+e-^ZV7EFHuG`Gg!$EU3RB-n8{SkXf{_N zZ2(d8DXl+vLxL;L{(ew;KZq5y-LfA}|B!=u{By-Rw)+uVrB&M>ejl;fq?6!NYW}*d z`rV*DCOwLxhuYkisPhSu+jb$GbymxH!-tV5{jg&4Swv)h9q&d-j)PysI_;eU-y#?2(Y z3f?j-;|7EEX&k55D2h3Oe-Hom2xKVo1D1V#DAEK=;>L^|emje-q(}v4aMBRdDJ)i%W=&8X zYCT2fgJ;8X-2Qa9lkr?rdOE1irv8G4wf(7}=7}Ks2|*_)n}c< zB!Rs8(IB51W^n>_$&V_-0I(lP-JIEsZZ7*Hk>Zlu7qQ01ZwLunVsoi~zWlR(6?ipK zQM@;gD<*mWT~JUIDU}Tg_Vo8Ek5OjjH3B=%2OZmKxm$B9C!HmX^!)^fUu_O9r$2z` z$G4M6bj3Ng|BQ8|4P{Eli4G>)bdYWDi~yERKU@89zy0zCr0Qa@l_#heJO#l1C$#SR zG$_c+Q!DI0+lM4H*jLXJPr(u1UBmYem7bM~K0rB$>CEA(KfsVB0vwMMNqGA{Pbtmr z4-aEv(ymzh#!b~8~>{%`f~+WODgj|Oe8P^^=r>>=LXvB7p!#rtlE>>cgc z{uf)HDqU$?uO3*(ntU{Xdq>Tq7|Kg~7a=ad_1~bPC&X5{D3KBC;_dS`g-05XP9UE6 z;{i?HRsiH<;618_cIKz=j7-vmPNA7vm$&UeSQ61V2JeTIrzn8*w>FF<+UNISgoa`> z>iC>%@%K`^X7d62=#5Ba5AAe{Fq?!?TB$|ngi+QW$lKTl&a~u*V%1r{B9Y}_*A%d(U z#kI4m-MY%szM}7T+pVezH+Ffq}N>l^ADdxVP)D4Dph%V|GLi%DvSJWf{=U7Bc7M?^2lj>}zN zI&Nl^3<=z=GmA62$7zeT4s)bl>z@aQ081>|C7_csrpT|-c6TIyyv2t6X~>^HZsuy1 zd!F2k2a4C=k6&d*1+Yik-+{d>UQx8cIPe^(Sz|~zVL~y481(3?&O5|jtrWS&J<5Kl z4);jL5B)fi(X9&cnNYe_ULCywS8p9tHocXm#5qlkn7qb3Ch&gUK@Zn)psuBsRga$> z*k9MNzixKuEwWagn(l;43%vCc<-8Rv6~fn5%8zZgo#W-UoK@K3{waT+bfLCc!A-+BP>!7`+ZUzf0X7tWJ7qtJrj=!CfBhyW* z@z5OmTsqsqlczl22~UOGZ?FY<|+xr;Ya|;T!)3BNz?TA0Mi_ zMchKdJW5OGV2=1kCi{(C^HD7}iqU}9(d2?{qVA?rZK76t^HM4V)hLysCdWPo?@Su5 zB{|sfc-_(1uj8=i4J@rIQwC9IfLS%PyM$+{q{r<&wP4M8e5V-n1kzjncHS2a?Xrl2 zfz-v1>SB)@bO(X+C>$TA_m;FxQkO6BZ}9t~Evx;-GyQijxF-sY*XfRTYC?rO0_ixa zP`KjjyLvT4J?90@+T5a=;i8Yf?HOceQ8L+6a*el^x$nMKgA}bcG22ih;#G;Ppr#gf zvHQjrosb#awTwrvQM*ANbqh6=-F+j??s!CHesUfp6XiaT1hPGh?8Os&C7|i>3(K@i zEX)03v!5(ewfUGizoEC!^KrhE-ksPu4)Pq{^Jt3h9u`v6GySOU)~LG|ICKdwaftDhuN5AJ`S;W*{5buat9-`pfD!U8BNb%!9hb_ zD@9KnD=(A5h71i04hFA6ZxbZ0dQt7VyfBm4i)!6TPLh0O`_A(M*u;^SGOx?QxMPyi zCwJuKAQA1IFvpG$#<6^wFCuPjSJJB{8SVuA#dQsOT$Hcbk)tu!;;bPhK~{GDD)}2f zu}M0)$v%zRO)EtS5w0Ys!kq{-&_5g6gxFTa4hrJgL0C?E0ue+0^C(s6e75_}Zj=4v8X%~`p|#R+9}Q)PXj|7& z{aTGvp3m&Oo7vLX+kb&=}lc){sKH1J`WlHQ! zzBfM{P|N@n97D4{49_Q5ga74xazH^?GtY zlB^S`ya-$v$~SY-!f$!6@$S zyDJj*2gq7}X;vD-M-KZ8V(|)5j5vMRv^;vrn9473MQvVQToQq?TkHu$=R#FX*OVtrms;n;d(3tzalvsD2<-vpZIR0hy3wBNOgm zoXN4Kl=bzvoQPs1Cybdhi_@i}TpmgKBQCsC5B^z7L-6#u&{9##OdnxaSYfIir zatFBe=WE1nbXi@k(q-i@)lJ8pAKh3YEi|rWvXaJXejJ!5eDr)%MS>$MvHEw_PQ&7t z;Ghzsk2>vUVy`G#==_EjI=BtaTywSKj*Ya?;l~DMY#e(2>f~s{+G@aETRS8@XgBZD4@4c;Y*h^Iu(g=Z!{$@GjTS?;e09+S!$p7mw&$;Gtz+j(aV+mqJF;Y@StKo@ z(AJSOZ_bq}+yzB?Q9c*U5R&DlC{rTU zJ0$V)6BZ^JA%SKwRzMrtnT$eVOh^?ij{3foD!MydZoa(b&hwL$)nlrsnK8AeI#_X& zQjH~Y7NJIo5#iZBVq_*i^0-f)AM2P9UzCa!sVO0!jq)ksvhy*&_P&IsO&NQY7U@5v zW%>_k$+&|?y98Km_bqy(U!PAt;M8*zDW2%)W6GP3rA<6GJt~7U?mII_u_$qA#`C%A zl022o0&Pa)fopNbch8v=#yx|y5NplYk*oIPsR8qkARrGOI1@7}ZG84*^Bu+jzz!Zz z8Ta&$U~}H-zQ1+Jj%Uu;Eb71K>1`G)t~n0bKoZ{i@d;RTfItw%%i&Xv9F1{jwDIG# z`h3O3W3h3$2wW_^sMk*+Z9pSzUD}~KjT~^WHc5W1M!c3Xl0UMNl-hzX758w(nX22h zYWB)|*4M#N5uw-TG`=;Q`tNvWYm)1~I%`VMs}fCGeSD(HsEVQppRFWwfYE!*{FwOF{@s! zFc;$V)?BLBD$L9E849yQ1aM6|ems8sbW(oM0grQElu&

F0Mgn0k94szwcPym@_2>EA_}!xdxL3tY=TwjHs<(yh zju!-*Kk+$HyMqI`G*RWP>akrabJ`vA1;4P*Jyq#dINO?4m|~q{vB<=2NY65~F*?3| zgSAA_cvra`XC=MZF6=brCX+F1+*XDEJrA*e6yYPP197b8*?Ov$?g4vXHRYq87e8?Psb65;-rBp`RugzSw>&sFWm*g-0>&q z)%!R-P;N+V9~PyQU~lM{Z;obi$>f5&9ecj)Zi%0vBMuSoc{-9;t5I9O3D;{>yTj+v z_3{@hLAsjv%4l&<~|Tdz+9N#I#)D+({MfjiL5-ug%pDFFFUd zJMOi)`r*Si=!o}rS9`0W_9hqGTVAKo-X;m{O~_ejZxx*b*6qJ94vexClvfa_$ZW3)~O{dA1Sdiolv(k@l%oFU^*^ztOfJ4z$z9_5Y4nv|oJ3Vq>X965w~QJ&*U+SaL!A+fLP6v0`&Z_gPRt_U`&Z%6rY z%iD^ImC|lT<>(KjNFdyqnS7fiIKG`LXuF+yomX_ZBt71i&wkjL(*Szix6F#Z)ZXV?d9HS!zo|7(c={B)Kwv|G0M>3o#i@d$eKinBy5{y^$}iPr^kvytAy&1wtzQi5@7oB}&&8Qns7vZYv3aE=cd zrq;a>t{7S@N&K1Ta@ve_*Xn=cb@#TY{e$az>;6%~3jW}MD zK6JY}@jI%A40y+xowdDreHl<+`6!lG;LsXmoF< zjB0yrXSb}nmXwigw}T}q<~Gd8#*q3vi4@{K*Nrh064nC}@>_!Fsg|}@I3rbFVQXHJ#?{XSG zN7?itU#d=ZI(OPa9I`fhr;~d~vEtv9yUx7(bOg(GlA&6D$AO&O9SSJBJxh+9!qcE$ z*j+ms2Xas*PKwRDgA<%>6+-0+QlXx35k93@SA7{SII)rV3Q6+I++80{k{Et+iWh~u zKrt}6l}gu@<`ktlE2R1SF1|!1#2b!wr8)IK(sZ3KeZomQX#el|(%9nufNz=1&84)} z^-kR-n&IHA&pM~$kW)N1;th%urc99sop^4hQ?gzs8BB6tJNt)PB_}IXmTk2sm#OSE z&Sl%IUIwdEA8J`;b%xLpwa=XT(&^acwC{3qn_WJJDoT3e^G(WFlmVaE?q4Nk)GQNb z&%3K%9|2j7LMg#_pTMmbhVADmUHt{&84}l`jeH(Ovg-BD@O+ogpEwB0Gvh+LcE+%N4PT7ie9E7x!)E~lc1dOF{OY+t#=w=Cm41=}w=jkcMtf@e7$ z=`Q2aN5-+vHXi12CJf)|vOey=3jQn#UXoO~HB`aroXhgp| zxnX1u<+MsH;>m&%v8De-CNb}(VvD{7og?2ak-Rz@zRh>}Hp1zMbotgukwU@Y+W^tG zvt7Og{g-dS@U0@L@*XbCt=0|2+^yDiG4So+seVpJnA2`>avGO!B@*G{bX^tE!9${h ziI=;sOVAJG-(JB#CH&)D{`GJ=JYD|ndfY#`=--Ym{~omdXQO%8in>b|>h44<>h46V zPI*8UB0!oIxe+}o$!OleY?;q zT-U-b-+ult-+qB_73o6VZKk^0EY{sGr+#X6TxhkQZsiVBQuy{i>uxSZ;_zLe?&6rp zACVn8ed>1J@IxySVd}=cPCAAYt)Y^}C^WIxgy3@LXFT`Y0OocJu=mv^2 za-`ggBngcYPBx``N9H%J7*#Sh>$wROqo1R{xTjSqN%s!<$e4HMyd>r8*8P(3YcL%q zPubb(*hRS%(uVtKj_?8atTmTJ={k+2Hec=wVqf;E+z{J8@BV_`qY({7?imt8)7~1R zh#f2}+i=53Mq?|@)#?2k_`-eGN&}@8CvJv@_t{_!eJTXAT+h6=ouLEP_3_4+_Au8E z9k}iDSg+!oa9DPY&D<(6U5O$;Y(QyP_|gq>@jEU%!v;20sJ4C6$6C=XVq5LjZac%C z`a0B2srY%}gZ$|OV4(mf{|R~1=}@7TR-=kFTH@Xl?Db2+NRX1(n!Ln!V$X0k`7*b# zb*W$Atnq=C34udD>K(C5bwaXZUu3dvZu!1@O7+mW9_+5Ks^sNg(YLu!p2#;_Yg1M6 zM`RIZ3(cD+PvP$0M6t8nl`V&KEH>R`S zm$=vS?kcx@V{}nTzA>sODc?9at*3maBec{wjMI@nrCEdgH{69rnpK&f6=m(8pA~KO z%Fgjo_RNo`FZNk`=f|G|-S1UL<~scZOKia>sdbk%{Iu48P)T3tkGPCG*DjDu^BOxbCS zDmBQ<$EflRUX}^9bBs}z`Ib3ZQFDyZmie`FvZCi02Mf&LjaQZQIk5U_9!{k--^#U@ zLM>~sAjR_mejqUp5(~jypgd55Iaz~XD=n$BPI5L|ccA+Fn`7R=Sr#6vKDr50>&H|{ z3k`L`m)E#-O0rXO4&GdOT2*R9gVDu{}n>3;azHCi60L_X)8M(ft5?xyFe&BN!;Lr3^#GT5>mk;rl)79Quls^|K2NNK-ycm9p~Ym34rev^|Lx0-qT&~hR_5kss+5YXOm(;HpMUOtlsoO{S2MfR7+V)#35D8P zvcWB;YDwFsR`!?^uY;hgeMm`O{KdoBv#5#87mk;i6DnOfpQclDa)e%X{|0pCpgqqY zA&l+ZZ4%^i*3^k1lEf%x)`Z&Rn%Yu>to#dMzIT(NON}x9zcR}1xZZd@j+;vPD1%Zn zRj`{V)ER29is}qCT3ohnZ|`E81tHYn%VirTfXi`YWR+!1sCBR85tT7%b^TWU_2OdB zaD3bv-`&f%F%v^2iHG=Z*@+HZUsOP;-OXZ^<=xL@scN>4#vqj+Hx4WY7X0Ool4JSC zp+#1Bwcn#64nd6bhe(`vyI=>uZ1>OE?K>rv%f2Z%&Qld}-%#8}k6f-Mb>f!ZRMKy1 zE8>D|e0pk@r1JF%lTu+g(G6SQ>mTmjEu5$=q^qKI)qQT3e(`Y3a$%fHkF`zk724>e zSmC;J<)mXZq$~36Zm?3A;JCv5|U>+Z;VOP zxu*-mXo7MujMuM0m8RM(6BTsc&ZN;eqYihU6%eLexiMccH1GcGKW@;6UEd-DkLuK2 ztW%FM6Sy}hB3-U5KtdELfzmJHm7`|m`tDmd`;#IhNZIcZbl=ySnX6cJ=mu1*LtSIr(0mLiJ?Wlg9h#A&CnH1A!pRIbN;I9B zM=7Q!q(akAt(2$6pG_5p4M-DL;C)u%24YH_^)NH*#%qcgA={ypwj`5oNL&S_Pai7Y zk|qr$(-9PH%@o#;rc;^S-+jnrzKrDEmGcmsJ{o@tM(|AL2FMa!Pe?{eg>h}ngz{#z zk&?KkLe=c0Hw(e=ZKiNkY0xuBP#^S={LH2Cb55o(f*5>f z&6-!#!(B$FOV2?lcd-A`+u#fM2c%ml)JNw7CUjM{+M`Ory-3cA^AX&#lRZN8E5cbHo134Nguv@Y5<;)pQ+AOZclN$6XKGc-Gn+70hj?x~Y!7VYK}zta(P< za75ndTJzjWk$G6a**&r^S1xFVLGzkx!87QFBZRI>Jx%UvjjELHH^#T+;F%(@_#{>0rG#Ipn3PY(RSbEf9G{a=k>?^KY#s^ z|NkOw!T(#tp+q@EANfytX9yOrTsPWfu4kFQt~)MW7oTM&QzSW074xmjFg*rOpa{Wo z6LGMdLKKf8cmfulGs*U7l2v~X+udEZf4=TG?y^0SBD-wwc+B=Q6d~9?P8@6xBl=&q zqexc$HEjF4Y&)(ycDZbaQ)HLz^^e&Op$NhDZsK4&km!He?nAO_8*KM=*{;0q_{3$~ zk0QHl=l@gLz9c8p)5g+zKzEm2e6{OQeaHp7%V0OuWp~|m$5NMFzU48yGybuAkK|-G zNU-}i1>x`Gc5jlbdM@lny6om(cg%L#{qu3VY5&;0{K)Q`WZ}yNQCY&ArrwnoHkm)Fn*%~# zBazoES6(k%cd)L!Y98ek^xt{y6!Xfv6M26~}3R&<8kIqS{CnccG;zN;S+JBTJR)8WNQ90rG&>I%(x; zo7>Jq;iZAGoY3O3dta`NQW<_}i8>_H52B|_DK}Mc06(vVrWY$JHyFe4?P+5YO-}Kj zdxc^{WfhWXcX<3n@K63hS02xQr%giZx4)B&hH_e8qJBS?l2@N>F_u0fjAxfy94A`3 z#^VHvr2Z3STQq7@0LKc-hoNk84QXdv9Oqi#27b%twzklq88gDiQq{z-J> z;s#O5DtsUCO0X|}2f_n5r1^o;Wbv~gQ-rqmBq`x&aAt^|nVy+ zuhAg)kC%(fA?b0Ei&`cRN|zc&k>6o7_286bt|qf0@=6X4*Gwm8Vg~C2>Gl;im=xrs zfcf&w7OP>Ia1gtR6IvdfoVe<>mi^sh3=v@#qY<;u5!_nRPV_}3mj(}0zQ(Pl@CROb z4{|bbeypQkNy>D)(tYLIix;fQm6wJLgRgF*t0|u)r1^>5>Sp2MDm)v15l*A-p7MN4 zj^XtnI{$q*+fOgHIl73m(x;U6AC~c@<@9zw`G`Jwer=)K>(hi6tGL-@N?9rV_;8Ug zQCZ#U{~ul70@u`$J$!Q$5(ro2Wk5hpE(rvb77{DqqczbYzIG+mi0pP(q9D@tU!}HE z*LE|Z#X#wQC3Y34yPI4^kxDCRRn)SZ#FnDMZcBaOvlayr?XIG=wiWW7b8qZ+_xrxz zFTb0aGv}On&zw1PW@gZDgNv@=S!C@@@;nA7#?sk`{7i6VjXlVoSrjuJ>WtUyblil{ zT6mP`Z+28C)Y`!Y3;yfu=*e_Fyy>h{@|bn_Mhj^}bXZQU{S0^B8`CxUVfLC0tz(&S z%s%Kju>ax6`2-N**U;m)*T6EkO5a}V546E1ByV{fn$?0pU(LDYoeZrIdGEqNY=b2H zmZvm)!G@|0kV+Z(3&MG2iz@gQDqC#dNH0ma;IOn~N_Z+-^T$b`#gdV2h=y;dLtJMp zH2DJ`R}{qcJHEX?cFP<7Q+uy`6xVLu81g2M83LG_DqyCBE6!azZ^8xVJ8zQrFi18y zk!<2|D8P9w&>>=Pd1J9*L1DwW&}+17+fBIOJo*;-vp_SRyvWnsy~%Q~2WUp!@{ZwY zF8Q~8OS>v>LS430-Xt}TNGv=_Kal)BKmy03Bz(X7!oN)_cD;79OWHDgQ%Ex=Y$;E1 z9w@8Esy;l9U#vm_ib||OnjRJMwN!+$Rt1gw>Pi65niQl6yMf`7e4F9d%XMd zz6W-ahJx=?^iTw!>%*sIb^*LK68W6w`27cosSQufPEeIwY+L%|Xax9`ZP2#(A~|ZjPPN2F6i^o)LKK@5qQ@`pqlm@ccQA z5_nlhv&7#fZk9Iu5>q5?$ooD;ZP<7d?m|sbcLBUrmnuen`;lM8>yO%|7`-iaD9FEI zLEhPW)BEPlN8{u0AOvFDg!_ZPM|aC>fanR7_@8fj|AHkBH;Eg?Q5#l`C%1W=^?>6I z;QaBXcRP=B)1Nc@;G7BMI*;-^p!fnPZ{PI(0a3Dh{ZvlmK`>Li%;T&CoMQo;H*R_h zc${-!6V`WN#A6IE$iBH?NeTbPP{|zfC6ctk6xQ(lnAVle63t<_8J%@f?gUD66r8OI zl9y`YP#8D7ByTLmKraKSv12$nGk2El06@PtHUWfR!&49FB zz_i^dxarOMsk~Y+Fi>92JYqT^UJPWyeAD|(pu7xd%iYP~p! z==j^YP-~X(lBZ2-%6wWxUg7C}9AtMrnkEx&dKtccZu^M}(^V#UR^BG&l4cM&dfhI# zFZ#zaiQ7qWNl(HsMULbK2L7bL;nBuv7#0#s&_XE30dwy)b*W|!5xg{psEfrVudP+%=U6!HMS zi&H#IXp%lC?Fp;%LyzkH!4jiZ!m&>ZjZZ7NIIT?%FI&iAN+Rcx0J4z%vG9DtC;(=| zmOqZU(5u_Ta8EdvXBy(Q92m6iI>fh)uLiyD!OBPFnS!C4hEqquP``EXiUWotxUtvV zBO)wMw+HB2k*-p7=ZisaD`p`3HeTHw%ZL93!Vd?+j}Ll}^Wg*jZYOm%YVYUYC>u8V z;oW)O78m4;taZC}xKThtdE!4nWeJ9}9}jxp9(>fngZMPvPnF_qo4F3+^54KbyaDKs zOlS8GdiP^oU^=<3kZ%VYEJ>8PUqtTlxUT{(-xt7|t6|Vv#p8m-G?zFX<|$GoL{Su5 z=dpy7yuk%URTYf1vcN9uJcZ*NJgKamj_gxm8opT91xoSBoHmQRgLH}`!FE|~%ihMl zwRQGdnZ43FWhEHC&hgmSl{8K(awp^LEkuFyzDi2Iz%;dqYh{hgapz=tGhLSpIGQyh zwYiOT)0+0yH5MRE2jVr#YOB)fJatv(@9(!ZaVc3mF4=%lLrap?=GHaV)dG57u3rjz zYpCqPT)#Qx9-Bl#S$E0XpnXgyCd8M%&(FaqbH2})i++%8;7ytCtQz#D{Z!Hwp zA$$;R0O!~x<^d6L@id7*GZyO@%5vGDH-oQZ5aNk^5Z5&zd18YnwTPS}K`}FD$vj@R zdr`v%&4!=qN_t0H3MX@Y=eQXmZ( zgI>j>G;j$ZJ`n}x6>4%pHtD;u>Bp)$u!Jaei7W-YTvdu3nk6+~-6$?7SyPNK`_#4k z8mMe)*;8ENazkKe)t!Z>6N`IC?p7(kBSXr}X_FSnML-M*i~RAbak! z!DZ&^3}&pYD5%tlPac(KKU!$aLBt(}m{@pQ>AM?bIzkvp?q1AQ!@RBY z%IEEb=nCH-gVy@3>-xs}u_Z$R!TtFEK;()>sI$k=Ra1K-|J6oWYfEkZerRd={F*^C z3p0^~;r84%ctt6Toaa3`>BBRdF;lf``+psg8V7LU>pDp zFWkTd<~vqKniH}*>Za$V@J985xpnIxtD4(jY*DC%cgPBp{kf~5;`6cM$^8K!u3c9f z0y~zge@a95J19RGO4Bd1$6<$pMYpo3J1ageW&jEa}Bjo$tYd5^F-2hf- z(>+(Kgm*TN@HkHa4p_nRIO}hCU*>V3!|houv%Lq`tQs~Ca zuF%6%-R59-k2k#yew>o= zsdx{hxPOi06qr8(o2YcnjT~`iPVyGsVRPx`fOu z9M|w{3Yo&UjMf3{Sl*!lDeQ}YF63<(m-{nE*VGNbxeze;fLC|H<`Sk@2y9GG=LYV5E0eG7L^%luwJkOaMV0V}B?YMWq`rvZiV)Vbq5C43Zm!}%~I8pf%zb6W$7?M*O37jLZQuY0a&gNFmV8e z75IAtup)Ow!B@$BFa}`!LcBI7uujiGtQ^-)#KORU-}xVYErx`{r!m}HKj3K!+uww; z;9dmP;-?NVYI!sjxEfVX=e?RAu5S_05LAmF0Sy%ab?FF8_te4ZE@bt{4=xPGV&(Jk zy8-TliHOEoPM$OU4z!pEUiyUK)Y;RxU;RtrE37q|lnlMWX-P!Tq_5Fmp#iVXr9&xwvMD4Q6JG?2+&vX^h<$06zI=% zpb8C$2|+m7gx{82zH!4&!Y>BAzZ@WCe9$kkp~~dAtHGKr8E|+f%87<&Tp* zlEU@F`!OU5Bn(u^23mf+jyZS=GTRP@(bRzM zm>izXP19M~1du%&)(lslC-FR|+t*o_0n8>KO;A65oA@-1<%0$x$k^VAi{d|Hn!UM|3D z4kESvaG-r029GUS;~MD~0Jb$6CWeBuqIQ?n`qAfh9IUuxO^fgP{-!W%l~QPyfCX@J z9#b^yBPHjg;d};&1{ESIZq9@0^`hN#}7!q{1fQ4>#WehwN_zBSck#uYO1k#DiO_=Ji%27 z{RoFO+ZrrncvqasL_^nF*QN*HZ#=aHOoi?ItLq6a=sC?n0IfX5_ZZ^9q`~u3I1U{& zK1SZ+bG6|*|I+wxt_RL~)ZSTl-COXe9Lf=gFNgF~{ZQ*-V&yY5h1oR}KuIZ5f}Y`4ppChfUnjrDwg+!-Z~9U7aX+-FV#Fc3 z>#k=o+yC(-wL?4BwYC3ITN(?&2wDGM5QXdMpW2&($5CKnKxZo`-W|mVCBMXY0%M3O zW{l64(UkBoy7!G8GnJ5#QE$6ptw$)^y5e_Bh^j88W`j_HRyp{YH8 zwguYP6NsaV5Xv?9QMsPGqq*)4eN?Wg0v|ZyQur@_`s+f`CL^$B%ym~7W*(~h=XKri z2Y(w4M^ngPzl-^Q7S6)|DvGhL)c=Aguv-N>$jo5~MSXU4pf^wHyF5JOeR`&-)jp|rV2TaK6eO)lE|w|-XWk6$Ae?i(GPtss|p zk~94+Ej&pwq#Cxf;Mwk!zCZg7oj?goAo354D^Y$tHxWxWh*~@fZ3LGP(k+bG)?_2R-Wd0;FEpFe{gm*+0BR4^tZgqhx`wOphDfX9kWI1 zg-jhNB!1WJK3H_`Ky)yYNwfv6b_Bs-)HjMMu=J;;ML9mW3o{(0$5E&>F%+5(SZrB0 zDBDn}_Ub`i&M!?=lV$y|@J`E60#sL|#&4o#-Qm8q!d7Sz4y*{N|1XGo-S7I>@(-Fm zqEfFbLI^Wg;8d`v9~_z40;8;K@Myjn{j9ut+9o)OC3AWD0772C^cR--UBB%ozsAgI z*Cpd%m;DhhFXP!U7=C1fl7?;Yv=`s@4zh{l*GSg#Z2!WDz+An&-Bpa!~4gp3i=mWN0R3aPO zuM364KZz0H(al&is$vvx`OFCFU%41z|#_k)$WgI_K?J{rQ~&VK<`m0_30E2b-GScRQ`*7=l>m zZSI2^v8>xU%gI^EUjI*l(!@HH~B}?m6=dkmVHY5;^ znUX_+IKuu3kD|}m|5q!v?hg?NY2^QfW2mGVVSLKpLl-2sS!z$ORrQ1~bJHuhUWVS| z2r8+|?($Q;-pMI{_c2t;;W*Z}0NVrnD!#*`^(ZUYR1C;DEAA`53A!Yy4DS*%C9h(; zfYT$`BmX}*8+n|DE01u#7G>q8m-W3`Q0krBECcdPak3#*Vk$tlu0Ri8vXRe+g!~Tw zOY)7MM$JqAlN?q__H;vO-{xsgbcKMj-@C$5fMXbmr0iS=L;o`v1E#|qzToxf@za8@n~SU0&y3~&GU!txy`b;;uQr3c=k{w zVLuHc`4|Sfl5Xz`L|uknw|6ltiI<|Yr@*F~u^C$6W0VduCMLNEW#*F{{8#+&9mWCR zx#)!`V!zYoc1c&bJ4Rd7{Vtn>3&miyq>O&m$%>A=4f+hGH?LluH-0J3u*6uX^K z&PFSVN0_wLPc_TVsjxf~5TNuyRu^Md`Ea*46Wy^G1bOEF;~AjCJjGqz`n;ukVL#l7%nDp+7nq%1i2F2-{C zicinZGVr?DG1jA2aseUU_G=0?<^A-U+pB~i=F{Wr5c@QS%@{o_ZX2x~>h>yOEFRpw zT-34dXM^x!(#2!JAgm-u&bI9D@z?y4wH9=TndJnS+e?A|2;+#x{{X=xiObaZ9R> za^4)W>ydvSgjXE}3>QMYZ(gg8f)853dUK3k^`k26 za?#)yM|S&EvY!=64*5fX1_<6pr`xIC@3N9obVKrVDqIl@#iJ4CD6hz{>e^c_00-u% z$1xilcs|}0#%qve*oiY~BdcX1=4K`^Gjs{@&+Tk^;u?7Z*)5WH4yJs_%;1iNkaPq%)#dy+ zZ=f2nNx;sWxT=Xv!k|VhOay?*s1^Z2+5m57Z~!kM0LFNKP9G=G+XQ-G7!v^eL^)Of zush3;m9oi7!vB+(5CEj1Kfw#A+^?=eRx>g8S?QTWMmF4*VBH)whpArRvRT57E3HQ7 zsrkk>6f=qKDx}%XNto&*AL6#f>*(jcq!+X>)!YdQ*~o{p;ZU=8(FsZgATz2^W3AIr z8BuiML)ZrA^G0(idIvk%#zse%OmJ8pgC%FE%`y(7xrVf$Ii|@~bdA6LRvjR`Wrwf| z!A8b}lztvt#ZqbSx+2VW1^zX>@S^35DU%Y!YbyT_ok&UX~ z!k3>Pvmc@)((unvpwN*&BJyi;MeMM4$!;B;y_;gsNJz_7nd4xVfvm|Py?_7yN`3h^Au~eiL~fV0`~8QpN6%kyXrmvvy!BU` z;qY7xq#1}W$<6t9-MiFK#6_4~o68z&XW#$WaYmA&bst}~kO5OHUf3W(eE6;*W);haTs5e1|^7d7<$!-b<~geHsZ1($-^ z%?bJbvT@WN0=aSm&Z7?516Q6?DdW0NB{bt|=DaP>e> zjq*(S=bx|de2wk+0i24r$1!u6c3a2&W|?(&IYXC;--wV)1l#~_e2E1hPt`xv{54}QqyoSh;>;x zh>CT)s3uM*-y4{No|=k!6tyl|>Ob-%>;1JC=lCOK*S1Ph>n0 zzhj9Mffc{-V=L?4wQAw$^Jj!6M)LuMFlvHWErYTkr!gkTNL8l*nL|DgKuS)6fOL{C z%9d2QMLS{dGert9vwO`mWl!73zN#;Nrl?G|CIO@0;)h+|!jejE(!|8rpe;qcE9{=) zC6x(q!9shbAFhyteV2+Zf7OOp5ncMGKTwlUaafh-YJ|#s1|t({vi@&J4))YEk0QT7 z*q>w%$ZOIULLA;r_5$f!er7>4Efmz37~FXt0AeBGJvEB+gO}vekr82RDWJ-R?6l!T z@BF!rq!&$EjYXSSo%L*pC24KZGiB~wyLD$JE9{0N8*H<8S!Opt^43oAto~5$s_acg zEfNesOekE_B_n^vs7em)pW@k_aAifNLAQXKG~Kd51V|ZE{sER6tEU_XL~$FA)I^Ec z+M$w_x?Q`B-I8gnvdCju6~k+$+6VkaFO7$YVLN;FF88i8GlGvCvhk4vX*+1r;o`=X zdPv-nj0a^Wzwqs1VOrlaP)zEOt9kx?_gP78`j#?7>4II31(@ji58(qQPp;hF#B#dg zb3aeaIp26t*1e1E5}#~oLi#F!ehBF8=~kZJ#?x2v^d0`GBGI43=|&VAGsTVcnsk0! zNmmfPP&`iri&u+E1wrIh3wI&G`(Nnu7HVY846tu-H(WO1Yu+*YKh}f>#8+Ab2Vw!GsRewm|Sd9E7;g|Fq!0H8_xd zNe1?(0LJY%{nt2Y_9sfUc+-0piMVECmUI(ucmbho=UE->5=W zg)RZ7)`kk4S}BklmK_w0zkMkv|HE%2U_%Mx1QNw9&Hg?h&)7>{H@>beX5?^QbWg2D zSeL?C(#N`jtw%kzr5r1VIbwHgABJb9I~zTmWeT{>jl;FHBUx`_Cr96)Z5?pQq8sD| z%VU_b@4kje7&#uJp-sC9$y{`B*TMw!OPWxaR{K!=N?VV}!A{7ii)Pt)9Zkg>leRL9j?K9x;Dc_EespJxoyMtc zl6}Zsyb+V~FHB1O8v79N;MfV<>yd|p=TY}xJlLOjL}U&nwnpv{+rC6oRhu@-$7?>Gq+09lVs1uz}?=^b3aJ4K&OgISldR(cNADrY?S zEHjQ{6WweQdFu+K!ReGZohz`88F>X9wBPiD^kJYK=vZhv`a>&Uf+YAL37sNch|Hr` z`XC9N;ouOGU9BbFyrwnS^{*U43-U$ezg zJbSIas8p(Y@oOpUIKUqt58(20HORrwAy1H~8;8KNhWG3YZX9Altsp!X@d=Luk$q=b zN)uU$-a!BI!6|o?PSbx5bH(tm$v=aEIU@+1oUgbqLpV+WaWgVz+}pCW%JRjpmanxd z&Be@Q+1x{P#pBe9wcoC-+-faTnzf-M^~!3v`6&gC321hdxIu^e5bF|rBoZSiwP;E$ zi5#1xkc$}936W6(IH}a41xr9D&Ko2YVVp&CYa&!=Q19(4n(vbe1F)^)+8y zFfp`AVVN|{$7M-Ulsv?x1P~i7i53g4i3q{4wjk&n5IgL0yoUY?u$xz%zS91U(C15i zn;`3LV$_8w_-LH=Me=F7&Owj@@Dhq}1TKLVs;btsJ9%`IJ)4FyAg^30sy|^*X7ZVHTAF3` zN|i)eUtVvAYqlV5Gif~Lp?B_9Ybr-l<@RF=JH-XBFSL(1*_D}Bt6$>8>l-$s2TBz1 zVJrNhKmFhp=X~X!4{5_6zk>E)VyDbKFabt8pqeS)HcbQuKll9GexNdrggf<~#dADq zQ&y&emCH;VIT&#^4jeqMzVG~oomb$tr#&Ch>9((M9$kpV0^FfRLR|myZ)>9F9vS7_ z<#Fm)Hj9Nh#`V;d_5cspyekSCR&SJ|k%DnhRt%GgW>A87u-E>$m>+ay#s93pNekk1 z&Ad|0+Ud?#o)hfT{|NS@etSew>kuQC;<-y4Q*j>9M?W{(&K6~cFyrh)vge{5#jn_$ zl&wT$bBZccpmsGs@@iH`F%I6@pn5>seM6jYF?o@1CC)9N7kr*~`Z9@DaLgeZbhw?L zL(db~$>f8!95ASx5gu@RMUH{EE+ec^3C_{a$2+So{&B?5#-3$B45^}~G@ zj*S5miphL5Yz(=}CyI?FchCXqQYeno|BegC;b5Is2Q?5QW3-hloEp+`>?lQv$dNM9 z#*TIrqeV~Q5B|n(as}y_;99!1x3bq>ceuN{qj7q5Rp-jay?_H@fvGnRxN0};$mB=Z z2S{X(085<+KAq4O?)Y(p=j)MUBWKdp^Km`i>uZm2~V zBgrvj#jT9gUhV9KoCwx@e?{QltJ=Gry|77p^DBsi9Ohwn8}C+c1o~=Ld-WEF@clf4 zgh)_ykY;o@UM270fAU>+Wn}VI)m|jWCf%?DWA-^e=ku_Wr-KI9!#nr}cSe9^l5)W@ zhY)n++yx4WiCdDt#M|)|=#R)&1UCnzsEM6-(PXm#A%_G%yE7O94+H{B@E>EviA*gd z8S3n19vla*edx+P@D+PX^42bsC5oY$Cz2(}IE9iH37O^(>8)-QX5 z&hGHfnkAWKD!1Qlqe0ec7B32NB!oMPXPF*}X`~t%NdLLLIGZINBu|?q)n<9z zW=XSI(jmRsAXHg<}6rV^o0>U0q*z2uF)k=+&`ViVvZskv89o1O2g4s5hR_$S6cf@@# zJZp>Oc3rsOwORBR^|pwjntxu#iwp3pw3&*4h;trco_9O_&@gU53kZjA4LTx#6{228 zR3-!%*me%sER)DJ2%H=bLv53>< zbA@%k|6{D4(VqVj!&;zvY=%&Qs-f6_tE5OXGyNZzbrxOv-!EtBve>MMEIPdl0OQg- z;X9uHPGID`C}UL32GUGvMilO(;DE`=(?3D#q9_@YpfjEfaCXw^9-hbFF7MR=7u_yu zFS|ElFAd@3D5j0GOwbAaZ$Q`wHBg*y6RG9HoOayD{Uh%NX|^7v*?9pU`7JtddbVhw z+ki;9^G~=U|LH1B0M$GgHVSbT*6IQ3S*J91oKU zkWu|HgueMpiG}O*5<5kVkj3k9Bv6 zd>XySD{-?y9LwwAi!eI3^Au>@+0-L$@~2DSH?fZkgy1kfjSY!o!xbsYJm1CBuB(?) z<)rTtMxnyFH!~RabSuITtFT;dOo>t~Ni?cOiR(iXL1Va$GHE87pU~u)c8@&h9v-L zqod#(2gEIo>t<8k21DB@&Vc+l@9gdZT=J7C7;~4brv`%9G?Ip1=5n`pp##dv z`&4}qcWkk}#rle8h)u755$^C>lWy^5)`{jB)~LP@@6gxrdhr1ytF18)_7+Q5kE7e| za0$MCel|=b<~P4KvU+GW|93+ub&fKzltrUAIq4Nk!x;18)muyERDa9QiG3Zz+vJz$ z9--S`_QPtRnV!ECZuze;S*AeSob|L7)H_B&z4LpFJBNmef7XUDqw~Ui1IvbxM^Euin|zue@-C)8faNXCp95_I zI7>JBL9G{FOm|FopNuIhYJBC2j57c5SAYQ_4{9HS>BJND%8FU_Fe@xobKl zDvnG%NLM^dF?!w80hM2S5XDM@P2zp4Bf?6Zc*eXi0wt3(C14qwUcaV z((6gl5+=IhK3GgNqytlh+z(51${`7k&)Hn}T<0Jh!1@5;N4|rjp^%Y|D7PAxQ|V+L z7Kc5`wo(sqm4Orw+NRg5Sa$X6c1U}fq-ukWeSJe_Sk4s4pkfJSR8z)J7|5mRQ?Q{H zxt-KvcX>0m*+Q2emF-OHp2kpn6no;Ht>fOsi0TK5=m&TP3}fH;9X!H8mEC2YZ-6aFphto|B%)PL=}ClTEehZTyHdhOhRO`cg@-{ch<>U8(lo_QkQmK~`ia0X|j-So;{1$x7vx zd)nAU_c(UahV2gASS}QgFf{C|!foQJ+KcU{{P2!uVnm;B(gxK#7q@>*XMgTzC;dK@ z-5wF7s<{Zq0We&57w(#d#+yHcS_X*9QA`G#5O1R?)h2LH(u!@M52B-sRhxRWk*x3jX8M`TyQ;E_)pu3v zFIIrkr&+8Sgt$OKHU4&d-eyM%@_FH6k@jC;a{%{ttJYpj)LvCR58N*4#G-v$b;ouv z!D-rZxU2pr?#JLEox4dfAKN2~S`R@d>GO|NfKpzy;^HHn{7l-NpkqecP7X3r&yIGm z>6#RiU$3RFN6GAWU7uf23`E++ zyh=RMepfL-!OG7Te9Lv>LQxD|kpnk)pLczB;j>n{;%O?rWKSF|)lt6AhaTs*+&r8l z;JQBtH060HK7zwH4?9b(81@xlQ=$DA00WuXQU*V5eMg{e^VEUU+p9U6*F z(7}cDoe_$Ug5%-RZn7VlE|R;NFDOolU;*k*(3AHNwpVg1UpR2N3%#yg7f|+O`4mHX zSw6AAzT&iBh>Byey@$7QG%WXL<31m>P1lPTcJ$im9gVz_Z6+$r!kElT7PfP$VK)O9_5B8hBJ8ye zr^I2=JDdubyB!uCvHEpSq{0aj$G{{1yr8Oxxq`*!cELSu`{@3KG zGE6zdr(+|Tk21xXvooed8JaF+EE&znGb7^kSrGxfZ4MZB=w(+|>)_hQgptf4#cbI8 zSl2mQr;b&88ESLNj0u!^iPXrZ>pH$qTl_5)f@uymsJmd)SJj#L(uU{)KI|;h^LUSrZ{er?k-waWBFQf|su#iWU8W2kiEur4 z0S6=~i})P4_?CgiFVI5rgj)PbV+QX*1=c=pHWC&|Ay~MuJo+S)hUVw-NHT|XU&4YT zeZf&(g5rvpnw-NqA7+}GxU`(|nUXFsXhat1p(GZ3gb8^K6QZ-|<5xm?#Lw38I&?53 z`ZCz4*45HGrWlj;vQ>2UB#ODm>sZ=FFp3JPVJ1OcH*tV5>u8wbM_HTP2$Bif7d7n! z%Ohl8i0nD%8RmIjH9}7D(b1>l^stK38BYVw#Yi1}D&Ri_epmd3eRrWf=q%xxy;;6Y zT9=@YUKuP%q?(ziCT;k@Z$1HSln;UP{|ztkWx`aGkC8v#1H|m&Z`j51ti|(uY;x+h z2%2?DV71DY=vk+NEzz+l={6%)KKu%scpkRo$!zi@W}MRQi?eq=Xq^^!^zgJpdp~W) zUfh1)A6K_!%X%~Gu$uiadfk4#U95PZB&svODpMSQ7higP@FmnhPa}Xe$+UUKOJxXb+D z$1d9b2BZkcv!P8ueL<^(+0Zra{61SPy>DLpawZPON+uaP8;qSWJn)?u97bWXgW-UB z)Zd^LX`Ub1c0x4wNT`to(NQ0LZ8~h31jgb*=}4!%nco5dl}I%7cF<&kiVtLY=+BS} z!kvSJpk|}t#}T}h(e>aQe}Orq%k}L!#gG_QdWt{tryKY9AIkG0iVmprXqyJs(AH|n zvRc_ewZv}Pt&I~Dhu9JB`=uy&(0yx06e+`4SvJ_x*G4HChizI>k@gg*GR;~M*mUFe ze8XM;?$~oCUSa9`1Qu~3-~lOvv3Pf^ml5mukT{&J@#NanuSH;6*M1JXEN`;O7U)@Z zimo7%Er_U&$lff5rGs0oW!2*q&&4Z-M5@+v=|>UWsKPafU|nZJ0Ri<>Wg$NG#LuSF z*{iUXbL#jbM|`VLqd_L|qrxh!MLp5nFUgabGWf5qu=LY&v6h%#;lEom3ns`xEqf{=w$0lw_ zIzYF#`;|*Q2cM=Z-lcB88D6T^=GR`S3uiyOSHF!d2xHIDaQU>4j`CcQR8Ob~g_n?y z-?{NMB%)#2FcTMAKk)UIo8?s8Eb7m$O&2=u?C%T%qktN&$7e)!{RS{@f0Obhme*|S z`3&6e`BP;@v13?Om~xAH%g%D;R>Q`+`jjvJ(BtXyB+Z~JYH4%fgl6eEFUC+Z%q5oh zz$Mb2B)EpVhGu4XK2}1<@)eBX5&E9~38CW-phzp}(9R;}oa)TE_8LEw8!(an*>AR8 z7u@ad`Wu%sd7wNk%6qbPjW1LLRt2_Dv}&+|c|)iez9&1$OFf@uPK>uebwVBZR%ruO zdc6lbofCVzqF3x@Yd(H!S;kaTl(CfEx@>!DDeK_W<5+dHGT)<0Ik%YgY;e=rFTw+3 zqz5S*@0G4n>Q=FkCe5?MjE4CYb5;w-mto{kYQmI)|M&Pt_7A8OVyMw33W!mnC!s*=u=N9?Ywn= zE?qI5V%0b_CA~>kOrcb-pW_=MG{cHdsNAY^*i`2Fb2pxYwo=gn!>2+Q6klk8HneSl ziLEg&m6+5MFDxx(%L|fvK)bSR>Xf!1OO%m`jVrQPwwf#sj8lPea+aDMC3wyPhF(ku z=GelP!`+7_OF6TQIiuw>s*)&Imjlxh4GjOPU!SwQ@6Y|8bBj&Z)o;?-D!)16xK2I6 z1RFBP2I0_3+JW-@Y3mioKC`GIL#L*hwk`(W)pox5_jL`o$M}6tIT%ynSo?t=&qbF> zYUj9<^oxHLW>ZCN9!F>U{0`Z1n`-Rly>#~9{5EyGLmj=P(L;PaPP?aDJ@G6UH5~RU z`o?qW7@M5pYBxDQn>QH za=7>1rk-Id2pdX@FeOD=)YD7Vlg%5$Zy(uejtif0;_NiKViu4I>y`GI6c-{k$BqHB z9P^RUTu7ujAHGrMA4YK@W6kxWxUOUFkm-kx(Aj$G$lmU*PkizjpS98Lk5lfGGmjju z`{JA6OH%$o6_&Z9O>;xpxwv1XUGG*;Zrl}MI?y9s4tgP{2r9Dg zmm{D-G0#7(>g}m`#;>~8BQ?QV(bAK>*dN!V`bQ5|#Uj7z?>*9m&=rNzpt}H>HhehT zai_;?jva|FP1?a|qY~Y+GIddOcM%2{cTn_ z-oF;Q-pBd5tv%2svSF=a8_}{!ZFGgsU$$g-^cQTm;jH_l^l^V~3t~tY_@N`~R^dd` zzR2GrF{SFG3t7Iim{ze4b=bule0zs=ne-jF5eV=!?&0hj6f=+pRxXVnDXQY$mYR~) z)j{^LrRs@!$;%D}srK|_XH%O_FU|`yefofj>k=KM+sqboSJ$%I2heC3_GFN9Je z2hL)DRZr;gat5pc&e`Bg)i-^CYUd@5a{xltVYA@W6P>Mw+ArLOJ)EHtz>Qhi%4jN0PO z>vrzooLg+_uwfZxb6z}N%+WM?5@0X&Rh2dCSoxr0`;}egSgGnl!X>?hV>A_ z(sbMzVh(xt z-zcO$5NJ_{#U5qV6FGHUN>gf3hna+7S=+JqG@XS|hk9biRL}BW^QUJTm+Vdn^VE4f z8$6Cx6aOT}X?!*`nk~blDn;MO-0j+?-9kb3BX|29^R)2d;MLKz^q{|ZNq=Ib+t~_9 z0m%q8+FCLeu`KF%n|fl^E1?@4aImYcR2}wU856yhO@oIue|U96D{U@im}uUVJ$sjb zONWPv+ukYy%df9yt^HjX6ZhE>@T@%=w!hPM*cE#CQc$Uj@)d+J@!v4+g7D_i+h@X# ztg|zWQ-z&Ba^zs#B~BF%r^lQ}J*;IU~Nj(7?0SwQorn687uysH|Ux}-4 za?7du-TZ3GJs(#M@N0)Xg4crn6jad(15EobVQry~z5T#5v})q*2ZkYjp#~6(dZNXM zONcVpPzZD`;s4;W;cJ^K50J#rS}buE#I2O z(>KxwCLcDZ_-<90X3j9c+hlx5hl#w2^{2@HXZ9)RORPFMj%8OR?>2(2a)e3ZN4+H3 z%3SsgBtPj1I=gKIB7g-BMd?;0gA=qi))nh{JY`Z?b;Q~v6(C8%ICaM9!ig-R~Y5l8buf^w50N*Ku-j?*b9G z0QDhET#vW=63vZ@g3F1xMJNn|Fq=~EC@N=u0kP(5ufR$6#O`j|F)HeM2;F{k7@~B9 zNHMA_%$~%Q z!N@);s`iV4uOHlr9;CB>L2dDJaDm!9j&=NW zUKuWCfFm_W4xM0qp;S{H1DE2z^7g3ECMtFo^)Hv_?@D;)MmTw@bgK8AuXpeN&;X~t z4mnv5uypS83^_&4PR}dVqXdf2FDv0_PFzzrAH$ZN2IVmW8bs`Yl#$h#o(i9zN;w3h z!k%{{>hS*%&iq#DzDq5i81%dX2eU+`KNE)egOAXz+!&dbWRMqpL;&B2n@z` zVmhr;`B^3{{fGZVRtCI0-vtrWABFT)u7g-f9>(*myk_wk`?~G1TlOT6`?YNHPVb^K zVB7A=D2D^|ki5cy5$St=s%GAq?XfaN)BVZ&z%F$1$EZWI_u8~E9b;=_w#TC)r&Zgi zA^$iHJmDaVV$Ohl$fRAb_;j>S`!W;K7G&=o>R45$s=ZnlUi&2+UrHF)%VxphD@@5$ zObMJYaei#?WhMdFrbZ!&Vhpga+ZPLWx@hv ze+FK3mN{6c%+cK)t6)!KOJ^FWRD~Ec=Z34N0aoOhqNupiFO!(ywQrPL*RD4oqHJGo zw5~5-yLP=Inwlx?9Gj?~t$68TPVbC(qk7!tYs$&{lCH(&hMt-H@v=7}Cts9Z8$G!* z`dY}W*^(K|>QL6n+WRE~6;0k?-?7H0O)7-zqHM!_GTP-ztiDyE&*qGNQHAWh0J zM6GZ?FrOdE{u=K7SM12)G*J*$k(_A`vIn`fDI^xl0~!%7@ELuBH`gt*2RStHpuFZnDA|CDN#0T$);Y*&w2Hb= zSlz%zDqP1vnM3Zl7M=z@E-V+|IAt;wT}(^=<`;Hc?MwS(=xileAFblq?->D&IAzx) zX3Alcv~Gec?KJGw+JiW4>b4Uj_9wtH_=(L;SE1ykXmFKOx6=kGC>(DeThuy=!E3*< z68o{xY#QG99Q5itAs2LFCSBq3V-~F=6=Ok$(u|+4hav_1>?UC4syUVI#zvetpN4yk z&koSi9(YSFjnmA8Y=P{c827E!8dao~*qq`@4X*-dm^y6E=PP3Dunmg2xK}Z)x7~?* zWVI#|f4V4ZY~pN9;xme(1V%dqJC5mlPBFnc%UJ$^7wFD;Si>nSi=W(}HlOMh6|6n= zmJ8BWnur2GX~E-|uX4;6=UqW;=zyd7Zv2P&?YyjYs1%NCG8^HNf?%>a04|Y2!pe09U3(#MIEIj^=!09W;7p)|WS|F3NscUVku`$*)(@@UvAb5K99_r&&>{dY zHsOI3@bjrim3KC^iNW_PArv`j(W!7i+gl6+g{<%QBY}QQKEM#IoHXMfu#A5NcX zFJu410gGViyn=QJ)R{L)iv}uFiLF&DN`gd1XbX0Fu{xu)Slg*HmRhR_$jQE}z4mSGwbx#kfO6Y$khq;KRp@ouncviU`ZwO`I4kkQPlI@rR%0^NY*&1fTd38TG)d{pie#&bGV;Y+ zmIlA|xRGUwS5R5JCRX+cDd=E4XImuCuxyQRz@ZRG|nBh7Ym+^CKdPnUH%rPjfEA7*s7H2r}Z&Fr4A z%IREWSgaDXl=fLu0fKVWgd4*+y_S?%Cb8T?REW|kFMIMYWn3^#@Kmd8cQws515^;T+?4hm2tP5i9CU&Br#A4>%AbmTE4ju z_r~|7R}Iq(!&u`iW}k-jKFBJ=_@u1!X;i$j%U5V(jSaG^`FJjY;)Vo`6g(-)DR=(c z03=s~CR9eUIUHUoKR*ww^jh8i-4lSc2@J#MU;(&yWk2GVHKzXfyzxyRe<%gw#%6g; z)HHrKJ}VdDlQkZZ0b72|_#t7bw@pNj_dIf@=xq}+9zGATmXT!%g;JmK9NvY$qXIqh z$VvDMXZ1^_o?k&|d+U8z;l#C6?jgxlYJSfou1lV(?WxeS-DyTWdoIoFV9zMSKQGrN zE%?Nv5f>?Yw%kIqFKnca=s0WJh838&)LW!vqJ|R4W+fX4!j-@uxdoe#cLjSt%0!XmnJ@9Z+-&rIu}C7I5Yv^rp(<} z69RNsx9D|k22V_hL5r4oHl}{<*3wk2P93cIbS{{rsh_i66%&*4jCvI+5we}S#M z;Nt_lSA3~g@x2-&%%D!l2yhu}ti z$E_&V`Rwy5w%H<~KNK@@jnK?bes=fFr+;n-*`xYBIZb3z~&$sPn-8=~6 zC4OD#_+>d99$N!SA4V~*d%T$UwC|}khIx#^HeS-y#U9MgFk~|~7K9qICBO^CjVH#7 za|l{7nGZsR_<42nC^s8z9`?;G>9`d`Z^{c^bZFD6-Acvu9e86t=<~-w*iF;*>eecE znXALPWYfDW*W!Efn60Dq;E@d1JnqTku6Y5E9m9{hd9u2Ba@V}T$Bx&{Q`oE-o_Tz) z;7gLbNBk!B?kcTxxD0=&Vv9|788gk1psBI(Kd7 z$B$<6I^3S>1Lbv!89P3mb<{#|z83p#!L(H7`4-o8+=^w5W}hutWrfD@E~^@oj$&2} zB+XC!vISZA!#xi@Aur5f9;iIyThLP9NX{Z!Uf3L94)7_vhvNT7971E3Z$ry2SI7Q$ z*~$#xhND}rJ154UHmApSoXMcEya463jkePGW3KtqjYl#zZ1T)!UGrs*`J@)K^$*I` zL42@Y3$px>vf}!US3?_jTZ7E&;*{@x6Q7bkGX-;$;M?#lRO@B>tQyQ@ZO+hAUGZ|IV?u9GQ$KQ-b216hfvI)Tcs|5*7DRbD;bGWY3tW$#B+dDH#MeCBxFU&Qa`gEw;}F|lcV zjWf;J)2w}4(?m>)KlotdmJnr%JpMKRSa`=aUxir96BDsu+a`>S2TG!vTqZ%!PuJv1 zI&>MDT-L9JuDj~eg!Amd*b0bD&HWJ_u@&Z$2sl1MSB1xDjc-lfJ1G%0=Fz=R=T0~1 z=g~MoSxB!APR#1S^k@oU#hzp+OxBC?Xq^(WRHgs0&JPez0yf*Lt=F7s4;GgX;`vg)2GFEYL8mJ5~%HH|GvP?^XZNSwDzwF&WZj#^U%FKmJfF< zAZ!-Ad%O0NV(SuoR?Y)iuKbm+HOOCB>MyKZ>5hL_sQzFFUQrkNyb|A0%h_5#7cflS ztP5v%Su@Vm)-9y{hF^6H#SPbU#Pa9hPl#La=AaJ#3QMVcM9YFrM=UMxIs?pG$7nCC z8{6=1VoAq4@36+gvB-duOv#34vAj{i$qmHCIwyW}EOAqZ&T?e;GeO|=O2btYRmRPY3~GwNR}e@UlWc@^y7X01LS>D9C7Kwrfb52 ze?b<(XIJhf@gHZi0X41(tN*rGXLFG;A(0#Ke>(ycV zq9z)&Ou6jLa-G~DJDc)4XoT z@WZiLkP@_Z86Tc{%m3|Iy*c$3at^e>)Su`DrX596Z?$qD*M`h5kTlNM6nulIe}kU8 zl~0YTzx#lD5{Qabd8zO(s*`ui^f!sVAXPt)D&_fKz=hvai~4SDiB^}ABG+Raq9Fbx zStgBF%V_PoKI3}4ZNSc{CF_z5&!R5xWQP~dQmA4oS7kIwyO%pzuFIEaE|H$w)I@3q zCDJoH_Oo1vPcJ>Y{596w4q~xALGHXo;+y!lgyn>gUZzQzRaZwWtp701BakhxnYv@F zOX}ZVm|kiM(3ZUzY6^&1oTpmR7QF1%EV|KyK{=yqS+*P|HXr)Zx0?c^AZ0BHoUw74 zsw6P_z@~%|ak9}#c#Bu>{J=PkMDN|&{nMe>;p2lE+K|QJo>Q)!)GDv0eb5A3bxU&~ z5{?A+{8PN_(g8TwIBLuoWoRVM->uU=P<|?^4i3O<5?8Fg+Wm6C!JQSGuYPkT(YgDZ ztxoMX>CUP9UwPOWbFsylvVXU-SL!$&a>VWLTOIY-xf8rdG%=A5%-GlG+45bc9SqcoI5j~88&k(m*>fy@^9i2MmVsuT`QD+g7nDU zrxnVUQ9s&E|2^t8pu;8FiKZ@DNsMGucnc{S~$wrB-*^l@+n6ZRYbblXgx|lirq? zm>N>p$$DR9az{OE*oDZ|Y~gdzhLj#&<^^mnPW{IN%YB6qW>+wgLCe$T7S02Y!SF}xAy_P73a1$A>>UvH@QPhc z6}DZa=Gg1Ouh~{qKnKJ8+&892lNXz3)X8Mar;|DdY{nQSatl>8Gt1Lr@OXgt?D>qf zEitXb)H$N>yld@i%v#ZQIGL?H;Y-^00V;XhM-tMg++wEgP06lZH|t+{Pp4J(2fMUC zzY!lAVOlP-46$)ba*B<#s15EGA` z1QVJCOv~%t-k4YBiUo40Kz_(0#IRR>>RXwBzx^z;GA;so4R{S_KF}mmQV>2=C`*Z= zh9d}QT%$iHZf}GJUv((cAQpz-&;}K>Tq#j}532kewp)`}V+;&UvW?3U&C!90%Xgc*0`lA?1rH(1co;)hUliE$>!%+;PR*dl_FG6`xWTof!c!kq z?i;hZOV)`RX9o~EsOYl!AERPH^RiK*LxCj)DS+aA-IsU896ch!zB`^V8yS^<@hP8u z2V)rVNoRdnFVaH;Y%O7B9Y8*Ev={g*BcYtCMl2&QVYhfsLt zat+o7Gu#gdva(U8yUIr*&v^^hW*XaeIJlWYWT4r8@tC;f3$Bhe+rPO$+zCO1GpCF% z-Zxkj9-9u3#3IqZ8uebd%PjffeewQViMJTx();4s2QQ6uutu*MZMH+S(04a7AHs#0 zNlO2_7swreMlTqxegA#qKSyxu7R3!!^R$kzZT)4MkV4bn#N!pED*p~%dECR`H9~&d zXMAK!RF%bWX82%M$idAad@v~d+~XAo=ax1mV<>t`U8nCJTv(xeLS}2|*cYoYu#&Q@ zP#A~BYj$O+%JziL&B>TMUp05`P1Wv>?B=PcBCX) zOT5|vqo#{-#7jVW6EgGj2_m=wN)%9lQ?f-l10=p z({`$5Zn;6H&gn5_`1h43vDa!ZytfZH?HGYG9V?Zn>mK1{{Ja+wyXI9upTpESw*PJU z;|bm`U`GeNy@pUct}F%#T_KXtW#aPhhS$hYFdQije=Ao9*Qxo&GadaM-%L(0z?iX> zgVrz5F4!~nXE0md-;C(4;>qY@cS4PKiw}_(F(Dln;S_D5$DM3Eh<}Z3N|YcvX0$f%edCiOsaHqk9`{1HJ%V5du2l!rq5bNxGzpE+TB`DAMM@(v zvX4Jb^~B?{AZpaQ#JCXSggvBVb%vUf!zKuDe>kj>@%hF_e15UhU^1jwOy#1x_hn-* zj`EXVR`|Jg4Fpasqwo4IaeD=SzPvCsWs1U3C_Y$c+-1PZnzTCMF~VSZI+oZt&(jn! zT084~<0B(2`f@3=Gd=#<mOww4E)`Qc^`hgMB|FUBknb*LwDedp-mD1<)}h6#)^cWNrP z|H8NNrQyP7r}2+qwbK@lt^>(crjH`WyL}h})79qGTd7g;6}eS_u;XpE^0W_3j7gi6 zJI`-r^HMhEZELbg9cId;13dNCx!3SVc!O|nSLAUoy@t-`_S}B%S^>@7K1%1V`m_~t z_1}BF>xYqxVVe85j$DKr&k@IHGyFLIMJ#ubOfzJKVdvpc6ezlEz;STL71ov6s)5;5 zanEYHScNMOHKaBG)j zjthY$>u2-b&B~rI7$ zzm}e_{mlO02P4AfUT^LQ)5~r+BCwQeZDX=RL5GU2Y6>IDVkL`Bs=4!2i8ED>!f<_I zWJ#fP3tfOK&))$Bx;@H`-2nyShqzDZb>iu}mA!Y=H+qfd?uc)CR<`QS#Ucc$TJm-8 z-bP1k%-&o_tgdF*5v#=`^BHN!6CGEhxg{gL6b{D0lfJl#XX1MnLuq`as5IWBvMs*Z zcB?nI>8y1BV;^>8bu6Fx-rj4D*pN$dF?|o~zT7r$DAy&71&sU4& zu2|Z)d+CXtDVIxN^iU^f;0C5FFBJBwWiP7A7T-K7UHQ_E znVrHzNN}!>&)1DB)+0{U+<2Y zX4@O3E-5s#7CEGnj>OWG#;mebRd+@0|Mc$IlLl5U;A}A(5i+Q9?H_v26d#Ct{DA?t zuHXGs4qoe81FA}^Lk%-HgFgU~mCD%~RsC*l4omtRfu0%SYe&>fM^tj1g+@!5NrfIq zbc6&a+b_|UOJc6AcW$k=d|JHOu9rMzkWdFNPaNli&FS0+$%$p#6CanARjB4}O59kb zqR~uTg`cTIW&fQ7qs6jar8tlbtEX+dIY)uA9`{rI?u7Jh>Ag5s)8`$_+PFC+*9gZF z5y>5ALpnC8N)>(oLY7O0ZD^Xku!1$dAm=M`?AcK(3um&% zblKG`_}Y0Wa*gTDjj0;t(h2>V>G}yw_HLF-Ww6%(%ljZ4FYJqExv5g+D+*y-Pvvx` z$X;k>D}A!7W(bvKg@tV8GI`;YDn|HaS%@wJ^h+3ER|Z z`e4R<=(;{wVqSV(v<{7b7tWV1oI|ZvHo9fF%2Ly!hhLq1x@mAuDB}3VFb9#N*RaY8 z9{&7$Vfo2tlOm5yuZe7znxZF*r7p`EJ~oeq&lJ9ERYSh?29yCd%q<<$R{kyUz@fx_2_~4Dp%9cZL@kgKeEWb55&Al-p8PVK!QHM zyfQzq~6oD7#y?Ts)Jfg)v!&hmpuof;{7ml8T z(wb?*^AXET8^|Xk;*+6Yb<#5s?yYTBG#JuMv=xxHJnB2EJAre&zNVLpKiab259%ob zmFL#WHC2|B*>Y3ojOA|y`!%};*Nk`*;9{(oZ=Ihw-BtoN@BKN$}5@-=g` z%21On(Ezpy?u3?w6n3$d`xz>f3SKr~@PS}6AFvqWzQv_5Hu2gR^DPMqn`R^%Y>5b9 z%uktHP_YWf?;dSF$``VnmB}+ffSJRt%*vB33M`VFz01X0BCDKCCs#q%i17Wn%5KP+ z9pYTjEWYYf9=K|3LRy_VM6?U3JmO>W`fkl*y}zR!j=gP=GIO!F=ZSm!3Dx4cH~o7) zUkYbRsxlZbK=fm#J-?v9+P9)D-x9j^D9ho+{K9_F)~!r-`m=>uPF;DQ+FZTUzyy{cX%cXjDVMSv9E9sj9M7}?d5wuEE?jcnm!6NM9;#7 z(As7wn59hXH%Mh$pTIWbjJ_wADsK*#$eF`2tg(eDDHLT^U-}}qodz*K%w#{FP>97c z$UyCQ&yJ!tbK!eAIhQau|oaO=I&3Kx%%1_1u*09{iV;eHp&J5168!VI12Kj1o$RvJ>Hk&BX(};|5 zpv57B;}iP%0)Fm2)~>*%_-FLH%F=TIan9fu?g1gwpAesgZsoPzie@WMj+uZ1EnwM? z3z&L!v#2fpi5Fzcm2Bl<5s$aWZ~{jE*4%YqZbk;*6_K?#Yc;mHYS^jvwXp_lG9`H zh3G5v%*bz88zlV3Y9G)%`~=JGfNr>99t}K=`YiOtyzDh`!G8G#TbbnZuT@b# z{HV{`X0Eo2nft$huWVY)S=}fBZZ6QYhQz;IG{)5Z8$U7yS;P4tBHAff4PB=V+R4f_ zr}@d7he|#U#J*ZPTe-!%S!0gzUJ6>!>Ch@+8|JTv_45pdzNQh72LA~Dq4EJzk#}!% zb%mUnRc-ND2p{3yvlypV`C!d3+=Dv@P+d4oNiJI%DhfOeqo^}%DA4B@h%)GJd^v30 zj9BGYC$Jf^z=QoS>!zp;cPq@A$vcMK=$$`iP={_mXNdbH|ify}8*O;)MlNTb_|Oh`jr^gbW2+u@<+A3L{#E@Kr5!XN-zd;ZKBXwLLpa@<{;A^^Gy>e+y3t@mWRRCO*-z7D9=VG4JNF z_$({^h7CYv*_gL-jCn@tl-o9!Vo7XjP}w%(L$ax1s<^lZw~Q_V8p_;hn@!gB_4`9} z?D2((&v#hAtxq|-U>Ub-jIr+A6nl-2-OQH6ByS3mmnde`fBeaK=o?`jjU?uy8&ena zTjdXTOJW#h{oVTu_P750z1^Ex>kk*#)x|_BkKU<^iBYb=|2pNJ+a)ntW&Q2Vrot4~ z8xQM#|CW1_s=c7F4%Njz3+U60uSk{YoE7m7!j(tA=b`j^+!@p!&<*ybp?Jve)^GIQ zAl$tFSD3x+NRV^L6`$yc`|X+FBMNf_XN@%n-BteK z#-AU6^XR(O#inRjv`kzvNw1kSU+Om%@n0Q2XSs()$2r%6f8MFG7{f>Jok5PcTy5?y^Dl0X22~>Re8Ks1su4Lf&O}v~%Mx}`YrYG)-^*$ZBKQ9P1x{_uYvOPuPS){?oUn+j`C$glL{t?RHURcrZpgE01o6bwMcYnCVJwf(9)vlJ^k6G(W$Q6&jIc$fgUe|Cd4Z7U$833Sci$)1)otqJ+XSh|wx32}N@Y ztL$aQ4nC-8AfGF(SE}RJtS{ih>x_)UD5*2D4kO7btOIpHrFBMSYn@;?g9*QV4fBZ^G*N+nf{+z9 zA@%}&n2@hY|5*8S{GP^FBDwzgOund@Wkw2gPU{$Hh zI|BWu2-52NeKVBAT;Ab)?;Y2CdH#HwAD1TmQvrX4N2&HF!i6lQOfnY$>~mL?d2G&$%9|fKq7~R(;`+Oo z&QCF|(etNTS<&ZGQ_>wSfMKwBm8BoTbSj61VrX~B+4Q_MPC9MHRj*9{h+{|UvI891 zfpy~2Ku%>Dj)^*rT-iM6&`P2o8dZi5I^tNNns8UH{Gupat7VP4{oxGLPgo95lEyiIQrBoLntS_l2jEbX&_w<9KZ!?y`kUW zT|Zxw)Cyls$rlO};d#{(P7VE)>OQU5Y|^H%TpUw#K|BjQl)4BZig@9R)81+1-p7B& z9i$9CUicOL6`5i%lW&NLeCp7Va5#Fm!8oJNpY4UbLzBdt^DzVSXj=oni06^Cepv}6 z(Q3p$W1~;_=rm?EKN-I&i|>+3|8F--dr}rG!z=#gfVK53{w_#14*LMwOSXM$}5t~a+OWL@HVrN@rKox0eog8q@06>y7mpgZZMGbvWq`_$daFMT*!LR!i^Z*E47 zj_$I9$I3=!*SSk@N>uQ7lqd5|Q(^MYTV=qq#48bp5NHA=;c4oRU%d>rJ^%0g-~X5| z3h;zNN>Jtod2BEp4euFxvvhdG^X4|aCb?Y}pIr3Z095$@B}Ow|7uwxvist&&;U>T6 za~)L$I&nAk>gmUq(t`~~t-yeZ&!T}8&ol#))&Rp?tg`7yHHkYL;0@~OFgPM-YW%66 zZu7UEZ@A#jl?ssyW}a2AYVp`)2-n#@nn${DY&!x0xQf1)X#VHl|%iUclGZ;C3#_!E9OG}J$gGl#sOocPUb6C%e2jeSt zKIh~|((&%~bb!Gapf}Rt5kD)B&G>`2BszI+c8Kx`Mb1#kjMAQ|CD9T6AI;@yp%^vT z=N>CG-Xas;?o`VvkdWHeK~8+uDlEkRQ%H3Ah=7(q!Yvy6Gq%vza?VXo+vLk_v}P`*aDektsbU6$}o(*lL|(}c{c!w>=$9=f5QAuEhB zVef=AAgJ|b7+xJa>hL_?w0TVATWW{FMy0%R*8esOw(j*A&Y|&_Sv=tiDw+=A&}k?; z?idFD^ug_y70NiLw_>;iPp&ZuC3t>~(H1U!%D>;x0(Kf2LD2%S1>+X6g(>S{^$Qls zw!OpK0pE=WM7VzPryf~C9 ze?H7l5K)OP8Z%z@@3~azkxczLY^^D-bKmn)e)7SY6^RE+d!9@k&__+{N##c+}jX)ZjmA(+vNTY2jUJvc77+jc4kxJvNDI95wz43 zY&d259W>F(rZ02JndmJe=JeaB0bvv%lxQLoQ_AqzBScW?cDS6ql{x_Z3BBz&2IDj} zq)h*Q4hOwEn97!SvhYcOxPSSmH@j>|%9Qy+^QDqizf-MBElYvC_bmKfVol-=MkML_ zs3}Cx#Z%|9lo{pd4K{T^RM8NdsIm-bB6t2vc$k_O=kD`6r- zuM3et7qp2kqsId?XIANThFG=69ultU_K1Q1nrx_N|C?8IW?HV!1QKGX>Vh2AJk z;rVu+4=?x!vk1147aN6toWj7ib$c%4dT_q=1DyAJXx9nXrw1 zIn_cNEgQ1(o}IxQTobw~zbuUtpTV0RV&-Orw#(c%Pc=U;TE#~Hlj&(pm;m!j84Qpw z!B`WRQN1O0uTE|@$n7>SB(sYYg^JL=zj$4a8ScM$?SJtK-xDtI=?Lc%w42W`2tw7< z(q~1HSobSlBf0!8=w+(XA5pYQcgzg68g^Bc?RYCF`WzEW^ZekAf_B(-o41Y%zazA% zO{k~vGEL_Vva&uz?#)!Hn}gjPMCSdSgPjYYX}^P>qS!+qU_4yWARLGyEOVUEP8t8 zXq7~NK|ahWYwO+UAAE_4Gi@vJlih#F8DdvOE18HxT7~{#dgvla`pi`6;&%s99(!op zP21~5T+Um+~a z(~3yxBeG{?*^QBXi!g8o_ad)7+bjHqdWB`&&Y(J~V0NHQ5q*r=t1xRAV7Y$^SM$Up zib@G2`4P#5otJ3sWl(UTU||kTzW+DOa2Gn>^a*K{L^F#r7#Wp8CCs8Ejg5(EoS0hL zDvKWV*Q($asa(PNeW~Qx6;R?o;RbY>p6^oTR&YW%FqV3d6J%=P34e3*S=7w(q)t zwN%`>LtVmkN`oo@lamxTW89xZ(pOzITtRanFL2X*UTBtk12r-Qjj zt{h-Cp2lgN;2*}Or{T*eh3B@Gl=ua;0r2U>^xGuqO)<|!DFgig|QwX(4R{DYA-VpOW8f0A#=V^U>TP+dR-KkaG7uDsogca`p~ zp1ZT6tgLizVDzsb>QOcZ-m3sz?EqQ1?W>%C9n<4#%W&S~vCMAJC=5n%NA)^2819chMiZoM~ z%9NkN%gZ$>I}XJxdAjSH$rxE-3Bjga*0vI3m?jz0q`05#qMU`4Ls~c@-Ftx@iopcx z*x@0KZEsvmtXp$BGOcgU19z^()@lOeG1>%83=@Ml?`QD5Ho?4(Cm88|=xv!@;?DS0 zmoS@BaCJRW%Rh*SI@0J5(TBY)!p|tZE$zpB@K~1+PiYU{sM(IfH6YUkX-rkEZklS> zWOEuPy&2pP0(Ykw15TxX39ZYhlDtWc?70%h#E^RvQ zqxjf?!gn6(@W?4Yq-{gD+uU52Uy1cPWzpN&uJ$rVG;<~xe)5{-d%xIa+jFrI@mDYR ztZtPxSUwd7ECJ}wU<`8&VtcD)K|@N~xz-8M?XYM`1i7iIZZkV>rMe>^&$HI*+zT|- z($wiMHKeD;y2S`HTrKRIg9ctF;}uM=?uyFSk?!N!A#s&e+I&q1eR>2dw>+R1jg~2{ zz-&9SJLm$&e$=ChlEfT)OskAUw(ySF zUH5o*Z%=afo)QjG8ak+42|*+Srom&UvqdI+OatmogZKTHgFO8=f(!WvSN*x7ECh!ftV3g-2kP7Y=#;GA7}hgxrC&$Ts8Vcf5uN(eq@*Vrx# z`>0&pj0FB%8>A>MD)fRv*~kiIV%K(#cg@{!N_c@%Ts9SmpZiazgnFu3ES!SoegWf@ z*BpcOBn@5D0}K+(@BI6bfF)Zxk&x4d|HuUfaV|~Qa9WAyI0a?JF?|g?MLb*8+fNBE z5_Pn)yZ%R}7U)yQs%FS)l@f76+1($c!O$%sB|i^9f$2V!rRmp>`;a91oarx!wRp`SB=7dz5$N^@aY-q zvz&_jr`vMMZaF3FpnAe@#F8z2|8*)M!oBj87o5p>pW3A;zwA`P@7;N)?8{CGzo+th zGXeea@j6RRCA{lie2QF#BQ=Fm@pm7U6Jb~+NeP|y`C{kkEQIp}{4YE}1&gyznea+9 z1;!Hgj8lTRp_iy=h{qMZA8?2C${{=w z9-u574vI-RN$NSCxEV=5JC&X_M;@D$T_*~gB!p1gqo<%XEAr49yWE{{N*Hk?S=l+U zRhn~1*g|FI$lwv30T)fN!Y2!FP?`{V3O<$`p^6>wznKm#Z2GyQai0gT2=2**+Jn?S zAMv;XMe+3v{B_>8ho0gebSj!Tr=@wev$)ylkW6jXI^78U>@Y_23WrgLp4zW;dL$$e zKce6j2j40H9)h<2&_ zlTKkjC3>6h`BpNAN%}tRblKLsKkc-C+9`ZZ*{S-T*RW0^2^6i+40k6Y3WKOrQ%b7- zV#SZ&%FNL;L+YV4J@o)`$|`pGG?{f$y*0cljJ~4ktszd05_YJalLe31Eyc*a^03Rn z+F#PrSq=(zn<;-&va{}D(9VjQGvdYoK~gr3A%w2OHd*+BFw?AOG|^0KIzoHoriITZ zy8-xDhvUlch%*2zkPG2oRC0WeQ2&}bUG^k*Q>WeDDYz(4XSl~-`>!ueKLA9{1#s4L zNLAqPR7T`;GZ?C0kNTDF`c8Xor{JJGJv-TBV@^+EJsw<{S%*dfB<3g%TtKwc+diuT zZ?)`>h8foMD*cXz2d##x+#LBGY^aK9wK$o6eR zV`tpkI_=MQ3OlHn(}0^zO8P@9cbD5`_36qZ`eTQjtcH#58R`vgmkH0(n7*tK?^Eh0 zJIn20Fk%}2-76EGp&a5&0lQsxNltxP1MpwDi#qN9)hYarz@ITV0RHhwD|b5p{_)^5 z`tD9AE3Bfr}Fby1gC_7+g-ar!$bWZr`!&g*puLkRzw0QIPQPN)6RPT>~>YO@F` zCD{)uCB8VK(_!bT*v$c(tPfq{ocfmJ#Emz%zGXk^w!Ic2d_ya^Cs)U9)x>h+VNQtm zdl}3>!H+~A|Kiqm+LfI`48eCAG&KAVuiUMn;h(ArjCKZIG(b;Ub|$r>vrJI_h$o}I z>#5U#t>o$(|25?12i$=q3~LP>q%~@889k!LFPZRy2slY_5i%eQm>)sWxd@at`-oI%PPt8rQ+VR%JKf{>{7B`cg#ZS*py|Iff*y5Pj$2?Hr9P{i?MT|vC6Gl8X z8v^#sjnO?|cT=X^vva4-`5IEoZNB}f9}73BN$v1^AWBS2C@$@)IF*sq8h`^X^4LDO zP{a9_@EqaDhY?uH8+-se3V)q!PrBgoI0Ktm^?;|Qn~2pFf(frfIyw|l22c7FPeHgy z>EarK>swm__!Dvu)#eAR$sq2QH^jBs&wDf?6DEA@uV4wT!#;ebHs#r|L-ZR3p9f04ixHkFn*BPHI{oq1|yUSzm@(8D?79pNt^;9oSlM!XQ z7wZ^2RTBbIiJ}w2HL2ah_wd0v(xl@aM<*y8VJ95(r0EfcnH4=UjGyB&;UO{aEl+dc z#dMeLsXmtnTB-I!9vXwagbTF^m^hcV-E{^Et@rStw0#&ep~as$lw%`o_})Qn@Y|^SRuJ zVuR17JHCsJPD{T#l6W7TLYEI?ke;o3Ke|?YF?yhoX-)#({&LPF8W0`#75Akp(7v5I zRQZF?X}KgHuj)Zn?mHjpbVFE#2=>$u5kK{2Oh=85$Ti|QeMGo4v*xeIaJ2#y?;RiZ z7U4DO`zD0j)OMA`VIjr?-_hUt{CH5Y8`R2bY6X3@=X;v`@yDr63!};x z>;9WS6|9p$EQbg?et^-xm0+WV%i7GI$XsDL0Z?|!s*t;C=NU@cKzi`BEE=N-xIi;(Di=|K+)HU^5Js1T??!kDJ@c6%AL?0a=k0S(Q`%hsEQj#B!=(p~{_~risWALr< z@py}1JUb2}gSjrJ!V3|Hr{HbW7intKA)kG%TOY?Lmm(UVbVryhbrP68c(Pkh^_)>P zE2|V$)9?wFsgRNe{|e|>cW!3M*hxMB>nTUBGvLqsZm}p54^ya({H&>{lP`(P&mtGM z`I5B!EK(fEm!#%rkq6|WNj2PjWznQ9lh?_Lr1K~BaPy@(Q4v{1mibWz$wTY2=37t- zesvjL82khHDPhjHNE1CX7WhP&ChTIC^qwqn&qVroCk&RylrD(XP3{}{?uGO12I@`1 zfLq5;m>;?j=O>0#RHkVfkeC~T@s{9DXyx*x!n%{dyUzWa)*#%BIH7=k!nLgJKms3* z5OMU=Wjo-o_2BorNO{_y(&MnzjHl%JQ)>KmsLT`pSqpju!mlW4K+?ne`X%ol|C_`1 zVebPky&c~2spYHUJ4?_HVT|biCzfl)x0k?Uu6){;4HF#l@cnZF>g3Z~8tNZ;IByF1 z_|S#HGs%GDXE0vg_%ZPu9?2svNkYLS)@m=8Jla?#TExRsNyhe*0IOG%HH}UdGl^~b zCk-CtC*_jG5R`%#)=8d#$)!>+g=Bd&V8ETw+~z;FTG@usYDsl*1Ib)Z z9(SV(8)sm`jTduVR-L`+y2M;A8lm^Mm3j2W$ ztFYgS#r^lbmJatD9riamgt8MD>2mvj?@w)Zrfoa3qcIBBF$K$5y!IZ*O-eZ_dek(i zBgC$dk z*$#2CRZw0CtyWZrH^kLUb*zefQYCC(naye2PG#3;07aLDq~e3Qgs4j$hCIXJn=nBA5KhY7>$h+)J-_j2E(vHgg z7>J#>lokKfO?sNmk=A4-E>&sPNNU*mY^!vRT*OH*(9l#B!)pURjqgEjX_p{`0>cP% zJB`c1 zALP-zHK?eds&)qy&NaB(y`ZR*N9M~PY_P8@MrZ=7y&eWEQOu|uz^%oXWb4{{1_sl8p|a0*hwuqn7{yY$V=S` z4HD2g8mxBdiqO`8SiAU0fm87jg|*n+0=eZVdg8QGfu;|@=+&tM%;^E;lAL_WeE1Mq z`^uc1X0)?*%CB+TsSfoMPwM+R#NueBq*-RV7pStql#u@TCsx$NG1E3xpBD zvrZj&Nw#$hysBeX8gS|m?pq|)OGGkS;PhQrR4uVul*2zPsW`bjJp7r7k8nv5|G6Ym zi0Q3mcYR8c_`or>vR_$%cJx1d*DSb2Jfnau1EVX>t6d)EcG>^Y_xqFXvXdk)6VLW5 z%$DNBjYQg$hOl1p!WbTB!IgF!-v3lQRSAfK?x<;KMlpDidG$l9rrI33p*qziLN&1~pA8 ze8pl`o3{JU>MM*e(2jWpQpl?!5=Pcwn(5kUtQS^CfeWWs+p*@xSDd^W%ty7PezHX5 z7;(U%Len1j7#6Zl?%a9tlZDfq_8l2|yvqt1`G zz{2P`rs?-=l^xOeQiH2@9DVesYaFa;HLY=4X3>B2?NwZP^rXk0)c45AwntA2iF9z6 zOXio|SfhMc;Hs88?dlLAHds4)=!lzVBxWWSA|I;Tq>FxKSWWGh>A56@v$Ch!wa6y@m zpZ;=yt$H^OPG!*@%Z(H3*RQIt*tM$ET=)%9Df2OT6?DCPt%0Kf*SQACINR>;Q1lE* z?I$M?HKFlm+s-;u>l+v0Oo|3O)pCu7Q*xaf4WJ56lSr+j)e=kZ3G@r@UX+bPTm$Gl zQ5J$s#i}KkHVpY-fyBJ?ws#jAZMpg0vWwR>jt+k7z60%%RY@tJpyv@6Ob57wPIvFn|RgYd+) zWw`vzk+S_2wz5+5kvmSyDCh4Ox>c}M0>2mcWEuv|bgX}S?TNz4YJ<(EGaS%>dz<@( zs^7-=8!6Z%5&m#uM>wa<9TUX~Vc;=ZSupg(uNQ~?*uTw0iSaOw4gCW8m%#`45#C}c zvH8ReE8P-GR0qWhEWYDg7f#!;2RDZ;SUn(ui-e9?L9Q{C29*6CVzbn24IhNUulOXnBLkr5p+A)1FAU>yAEQ*Pajt-$jAM zU0I2zUvMNDU6@m{Y%MRU=d)gGZp9##|vQjLW7g)9Y1gzCy>(AdQ z`tra>y+JP>Zk1LiHK?hxLv)TkqNqx;s+HlvMM_K)^GqPeG3x8>#u(x^zHV3M!S$KL z=F?=5x#iqlrTZseo*SKU8KH?{G#XfE)c2pOG1iH>4qGH{TWuc`85cew;P9cZ%$4J< z@ZqD}fcxP~(%uJJ1CA<@-{b&WF|w17bV(j|oXR^vQu2Fb%O?K8l^v61e61ZEe3 zY3CfLQ#D57c_?jw(lB6pZrYD3-E@z*!dUW-Kh4rr*U?4RDLU>5y%mAm!T*E%!L#gz zXCFpiFn!4{{p(dcY@nL~7JV@RFL;nG=}Lv${(?(BLs!dT7rht_!iRO3rU2nWRju+gA*~iiH^2-^G59sd zFbw|NF>I~zn5DvFVberV%|PYwb%+IW!uLKqf70H!(qyUj;N&zrwZDei$97=m3;4<1 z_N5WijD_PUpxum6$Cww$s>R+~lzCvEQrM*0##y48apj(4EG=E5k+Tj>U zDt<|D$M--T8+J){T|UYsc9hzG-d^)n9UE$2-`=y%#fCWb(SHE$B21J^JWn(be3N}< z``#cbx2nCTdSRqkvT2)G68j;8`45<}?KR`DivL$w>h_xI1V4=E-~9)SAKROTGUM$G z{^rLr=(jzzeedmZpfacZ;%2-yoTS-|7zRq$WtXH0kq(V?u;eH0f{R={sG`0~+m%}w z5%s~>$3c$cZXY?WoGzjM>DtZJR0dF*{&KHfi>ORRZ4VvaJMElXgn_{xbozSYbV;$& zdoL~b$3kkqc6{%20yw$7rvU_4tWxmb_wd3wCwxV`$@rY0IS^y;licAy2aP|;hq72$wFW5RVSqJP zh-4sv26h}j!nge=_$FOGu9JRaNZ8r-)^Xu&%GkS7xOhA^yjl?(7n>fN8@n=geeBlQ zow1G0QXL&-{`IIc>@9I>AokLs3M66AQPrAUU6}FC_*o3vx?N?^aK(Q;uG}6#$9r`W zt?LorB1Q43<5fw@IF1hp?)q~8KdEDPMQ>2Q`{DM$!F{3*hpcVaaR|n1MTBsMJzRU} z`26%m0gE#$w!ong+n^}V4Kd_~>T|;Yvzg1&)X1Bod1+eQityC1W=)T@IV?|)U_JUr zh#U~k7N$trD$UojmpRA^z)*ijEgj?9o;&Wa6$#H%Q_m=HJ%+dPEs8DSTXMIo+_HYl z)-5}?G;V3x^7WSClJy}a>!-h<(61kli2|ZSJ$l3UvSROH^G;c+sYbdEp)i1lGS#ro z)FWMINX>_Di2U)uAw?z1*&```3SR|vbx)+Qo!U%=9xY;;O@c0UCG;b;k9 zM8Ihh3Wtcom)4nr1<{$#TkS>bOFNv{LO}dR(AHq-OimyYkW>;B z5$cS=mRiMk#CBTi*#C>Rbn30O_GZa5g6Gh8~QCQldd>Pv>kN?soEW^IO1&cVsl z(hN==rjcKZ_Ne4z2sjjgsX?-D^3z2M#MG&?;%nq!@>mC(6*H*LVqpjGFalv?j{a!? zGAAb*mu93U19lbN5G3NG77{z5;xt{5; z=xcpdaU@XGhifzkz6&|xRo{f9^Gejo#x`vv9?naa@e>FaZ1rBCelZ&E1`kH_gbPo;b5S^?Am6g0K~FT3mc%pUE~H+=!uQ1F{R z;hR3bc|Q`GS#10n`*X655^fb&;gRovDlbpAFppiEM;*DwSYxfpt65l6QnR*cCwF6$ z8-e@_R1BxKi(@VVkew;Xqm?9ns_Vo9oV?;{#knlj-JhQolVyaY$!o}qLv+pAnk&{4 z(c1Mr0%I+qP;m@;FpyM7dc${7xHv8eOm1c`qHPMN6^|@`N@QHXeQN0KzTn$^!rOfa zmFpehN9yjKgyzMEs zG0vgsF*?X?2Ea6J0GnGy0q^jO~6vN7p%_+CO?YYFN{!`T-0GdO5B9 zw!X4R1&6Dj6k#r>a3E;Y1XK3gp6W58gU!&??Eq(6r%F=RzB}YDi3W}BC1dR+chnG( zNJ+vG@-f}NeWDMU8SW?3`vUGSg46qid;0hf2^bn4<1OG} z$gTA1=cxg*^lB(Ozfi%=I~qh2&9?Ly14s4QeTACBhk@WQOit2nvC?Rr^Newu+)ETa zXJIku8ITx74n5XkC4*CO#cYZ3keY15U8Ioi`4;Qkn}t^#XUpIkG4hUz5WPL$dpYU}r|0k*~lz0wfWAO%o^NU>pM?KKtOkzBb$r7KQ7ooZs>JM^g z6YG((Q5iw#ts2IKGX*dcBf{OsGn?gB*9)_{v_l{E z2HZD;Cwql=dikda*Qm!Idpg(JA3w_$HS``LL&2e5h~?^(x!7M&(c%oX@O*^(U>uf} z@rpSGIr+J>#!ntzr`>@2Ik{Gy>;)TM5a`{gNZ5s^WN<{ z?wYDz@NN&v3~!keUkv<;g#O6Su~%vGV3MOde**^z01i~&BUHKX`KNkYvkuk&x|g5Q zyDqC2BzTf$CftN6W9rT~ynW~I#vK1JddthXCys%+y=VF4-W1KY_C~ks1zz8~J-gp)F0xo95KaPsD zCLgAB$S`u1X@lAvtl|jgfl$GnKos7EeJallrtM6{S4gvVL4tJw34KcP4VH3AZM>BJ zkO=>a-^tT6qc6Uj{`NuL>CZW3#nmZ_XJ6zRf=SDsvy0vu5*MX+S8i#ePRid)B@<&q zmjW|7^ywPfF2JhNVbHZ-->kvKg2Y<1uT)&oBPzVC6+3AmHSX*$35!>;p7%wV+R$t1 zu3&I2O*2ZJm?am@i2}~07Z?Y>us{ERyfyw;FsRxPlJ>En?YuBXKTi|2Xrb8l3u6p$ zvbK;gDB2UjjmtCMk-2RQ>?p-;A;N2CDEr+3M9fyriECDd1ZUfSE z^(1LBN&9`O%sAsnf{YsjBtV~$gCUx?AieYrl;&xw-WBIh*t^c?0l#vIqr2Bm>xp-w zv$R&(lYobPY)-w(l4Y2oK0bZpmQ5QgH|k4dPp?`qxW4zp- z{iphFhqm48IPt!t4({L-g7RB5SATE{Sh93k2-DNnZno+Swt6|u{2g0i zZPU1>ym%!%{+|vdV!jBGT$77zrcD^%?gqyal{TR3*40uUM~v#-5LOYUW3YFY?Mu*7 z0&G{HZ=d?XmJ6+0=0t?dH|9h!Re^7$;rFDhZkaoR&2DeY#decJ+ZwNQM=;ep{?_yW z=5YIb$`56f_5mqv(T3}&mc!8QZAx&z`Io^X?g)AHj^??>$*)Z-h-T()0*rmz?h8c7 zTVLJmSg+ZzY7%GVUV@~y*CyncTc&9!iyeCxIk z&6X_ca4Lc3O9t#>F9_~~&8*ahHs!*g8L`&lM3^R8vy=_8EpFL1%Yyy78TbIOEO-4t}htHDZ`w*&It+MF$!#LKiHCE$} z86)#pfqt!tS^KuEL3X!SiR1fy%gALo&P-~G0oJnu*K=GvpLA_XWOcUeHTAJbI3D)F zGmvCj)JH(crO#k3uBzXWpSZ5zQb_orXNG2~Jok_L0AQhXI<3eYH_7xl6VMucs?vQ7 zyau<%{KImwr{J5AW!ipGvDY%(Gw|go9pK?E_YXu0fUqg@ex!rfnx(MIwlshackF*- zHIYGaOxdVK|FDbgT>3W<;`Av9*@;Ali`V9hbig1FI?!@(JmI`xkaJC4_6*Iyg%Aj&UYsr4 ztURXn5s9Sp;~U*5Dsi1-P35A4wL5453IYI!(pJzV22RQgJ|Zosz$C`w7n|=}OKVTT z$&lrXo`Ls6mREZU{vICdgUn-Y`+6ONP>Jm}3+7yM&szdhnsU^5G_-=@8}wn8T}VSQ(t^vt=NuH1*Er6a_Dk1Cx^IwXPS? z4@pFOenn!rDixkrFiFe0l7}f;zBJS(W~|$K(q^srWEPCc*CAuxtz4yZLn+y;%D`lu z&2v4Ev3nn!*OB2N^%~D4ct?#ppyB5EAV|#XbM<;L^HG@f=OELW_R-M!(>xA(>$Q2JEw zP#-pBh7K2_B?{&;iHop0$az>lt4l47A*R~UhJ4&SUZ!LVW}+Qn97e|?b8*&sA~+4( z$5059O$nc?dKzh5T|Kr(SUjDr%A{@8DwMCAGX^ts`GT$8DD1WlHDDzoj=auP?8(W9 zu6PlYL@$I>4A=9s(7z^&bSs?-;cljGMHNq?iYNTTYJf?{T+e@iAmb!bdHz5#8$L|T z7xkDKtL&GjNK5Cd^mgC zc8N4nCn+^ScOoTCY@*WVLQxsn`2{!+g9|>~)FFrUzKGVk&_Ini8G%kx@lvYh5><(4 z)V0*Fdq|zLN6RTHuI80QAI)8^NV*Rz_x;9at0EHf?fJyDJ~=v#5^m(UXbr5&L%^XwGTD-HX(r%U`9(P}e zBOv$z;P^e1=ZT1^ss&a;tx#N_ixSPkjJ(2ZRyx&Xk?IDsEG6=8`(Z_OTwVo+PjTtU zdnj+kp(R#Kp%-U7S+Ozm?k=9EaqCI^o4oi@B3bqstF!dkt0+b(|A zUhBJTH9E)pAsT6|rU;r2eRH!lR%6|LIg8d?u(-A<^IShP0rT!q0jI>!gv7ZFyguc zdrJ$2NA`7mT%ooa<<5-i37B1Q0ZhxADV;cb;{|%{X@Cvo^_!f=)&OD95Z zS-x*^#vPYE+GW|to3-if2Z!6W54QV%=;r5BX-{Z6+8^8y_0m$!47fvd6u;t?`Dm*J z**zz2!gutchocrng61cX!~O&MKb4*+$iKy1MZtE1C5%tJuMaRX7+x z9TN%Pf#J~l@i+ipHDOi6bGk+v>#(-A881HNW3w8h3YET(cDMYJT0+wA5NFc`{~;1= zIpd8%`BeJfZqC!xT{{!%zQ1GWX171o&HqKLq>z}gBqpn&0%{gGW5YBD5}6ybUwbUd zr`#`-%J5*oIaLmy@OQ744$fejl_I~}##U58a%W#Tld_$-x`zDgVq-%~S&mhmIlbIzk6`!uZcjfjw(VdZ|^qreUbG`y6v;5x(G4Fx{ zO8ywViS`F0Z^Mq{%bpmCkI&uY#&IfF(Z-eIGz&I%FIxsL$5l{FCMF+w^JY=+=Te7! zBMeE-_lb}c=7mL9E((3!1%VKBPs35Oi6Qr>6w&V)|6Sr$GR+=okx!;~befj5OYus_9sr zr!igJmZX6I26ZwB;yk*aNVL#cb`w{8(<~o(Ve>eEZGOg3-7Sg_qaee8?860v{Khao zchVDO;QX@RrJ!Bk*GUF!3iP|8`CarH=#S^>crU$%_fZe9IFqfo#y3kTlQ>?Wx9I^c ziT~42(&5M&5F2j`Bbl1G2dTsI)Uu)*vcdmYw<(c4TfiSx0>6~v`CoUpsf&6Ucd|IF zPb9;La2~$43km#-yCoyUN9|ue+#Ouh&A&v!;WSC*Z=9%ms!;yM)3(@eGcveZ{v5^5 z({P77VCBcnNr{z7H*Nf!N^4Wt6h(5Gk5}g+l2%t?)0*%~0$zwKpfvMX z!-Q@#JBaazpGg5Ah=ZLK|ApD8B9VvmMX|CWZ8!GBg4%9D+s)f4nOWXpbQry?sBz)B z7OJatB-9nUjWQ~i&i5uFn$4S6!4I$S_Tz#d0om=atGHD&w%xz`cpOlx(< zHcy_!lGt0K@?W+PUiHp)dL!TPjF{)2haEawNQFzQ1HKcC7d_(HVjYp3%0_qy7M zC(*8`hp=-muNQ;=LKu#snc+g{Gaza)DHFFlBwh_Y2szCdU8SxZm=1g;}%mm z2oIc6yr!n(K!Ru3wim6vjUeK=HT-O#r=f1IS>*Y_c$94{B=kf8L{iF|TZcBJUB8w9 zCFcneABOP9@beG!T(DuUSqUC>W1_Kx(o&~2oZEwgyJUVV1su=>H|!NQ?B&l<@3bjx z@}i7LL_frDlA?#6*&AH5S9p3ae}++)p$T7u!~)d!dC6@I;!KTPRqQbfVr zYW^`1a4r$N1Ww4y6zHIjQdn`}-ns<*;d_agW=>c24z~D#y*S8J^N&iHA@Y|L3F)N@ z=IlKXA>{7mcZ>B*u6hesc3^>osmTR-`V7Sqw&?->my{0_xfeAMrtjrjD6QM|IG;mc zI2{LCrWb9Tp=`?IXNJ?J?fpn8SoZRbBI-9UK>L^obM>H#)&@9Ju$C-5X+lRpt{!4-|RdXHQCQR>yuy{H}GVwDh4GR&;9R(S6l&a{wc>aGzij%3nfJ{K= z6z}qOM5bz%rd?FGMRG(!{xoH1jWHnahvI9)G%isEFUXNjb5TvGP3)<#g=ZMpyb6PR zJj)neg6z!EJ^e!J(9u2q{yqGIl+P%;qb{cO5N1LAAu1R27@}OLpP>cyqXGC0ir}4l zAQ^hl7W*aqP(OY@fw=DX^o4*sB@IY%N=&myF}I_HLTYug0pr`HLR4XUUs#Ar2EHh- zXf4Bg2q31WFYO8Jrd0s{8l}&DZcm|N@J-;jBMcw36)Cz02UbMSZBjU^`aa}P&=`>B zQ#XnNkrP{4!*3C(6r%^hHjA$fKjRVy6b!RjQD|=679JIFE=TmL++%u(NTV~--WT9k zNNAICuPD26F35A{DLB^ZdH`;-e&wOXHuQ*9EKgwB8#TwJ{|&d4?MMI3yg!4u&*t7c|c(k?#C; z)1Q*IpbSo~A~8(oh=$+nfyI0&#Y?G9Yla@#6L4(~KC(x6WDozch<^hAYf51;2RJs% zl1dv%{38@HL$gWXjr4}6fu8Q2Ij$~uaNZtQvwf(*&leJaW7yg{z#_@L;iTi~iLvoY zh@VZb*zO6c`RH)$9rP4t>;WJ^31;sZ%JB2|Nq|7Lc>t6gPO7A*I~dK|=!LvmxLj64 zgj5ij#<=>1rtAq$-ZOxOHz=1brPuTK(2MK5-0pH!_PQ(E?Z@Q$6M8<0N^zZ!9c>GE z6HlX*Q#EwC9mZ_>=(eieN51LKW(RDH@PNPKYkr=XZBn|B=jZ2$?+>R7IevbY_@19$ zajJOy9+xp%h{HdQpZHvgu$cYn?RpTiO;sGdN8D}Wr&GjeXvJ5>Q~gr-y%etBnC|jM zOBp7GBkmE4a7$q3C#UCRq!$~)ab_tl+Ax83Puf)CekyMiL&aSdSi+C@qyJHZN>$Gw z@X+IM(ZTVE?+YSC?noE+jp387DhwFJpa1MKW6mn^>Zde1VMa}CHcam+wNKhz>Q4(}_Aer#77I0_2+T(t$}?J-2Mbe{-v`gUF<`8@R)*wmUdy zb%KKHsowE6w}EW#xU1C(cct`x$(<~?7P9x>=(eft{olD=@}l+dX^Q(Wxn%_~a#oYh zH`iYENr>A~@G%%1xJtvD+m&G2mISeo)G_x#zKPH@?C(Ooi<)Kp|LMdh-`!OyH3gg0 z4*X18k|3r|Qq=udt0din+}FDxT&QnVQF!GAdF5t>rM(N950x7$Irt?)##9=u_!lU_ z@CEtsB}LHPHTh2yKa!&>Ce@mbB{iKo)?FzMW=t*`3hqINjA+GlH%3)QDvj%R3lGe}ngw{9+ldqBc^0i^|?#J&d| z=qvN+6Jv5!cs_p%_A_DF`J=Gc{(r;H{weJH{ss28$=2N8jFR_m5pIT-U)se*)@Fd6 zU>xU_w>HQcx=5V% zb2IRT0iTZ{!r`e6Kd(@7&xNFpT8aD}Se4CC8)kG>mgHDnGMp|}uFWxI)2HR30ZfP>^LL{_NBT043xO4nnU5#pq z-By9!NcTaQ++}w$PL1SZLb{Q}o*IEXk`ajA5K&qAOv-2fJQ0lNl8#ch9(kM=te``p zG0N_ShmbVF$#gw5I$!2vyS(ZVNezwCaU1hok@~uOD_u`lPm6IMNsr2addoqhwrJx` z%8I+~7o($z{l}v0((ksUTLbAv6IMqNNDOb z8sSKw^jyeWQhFgI91eIs3vCiC2LfCSqlJ7nu!C$4PlIz(UV52 zMWZiIjlMiYFFhqBM)%Px;V&90nw67rL0}H!nT)+S-OO(UPXJyOysYWdkkAtF42Qf% z({M;|2XIzOyUdp60OlR71YI<10n!Yj`qHYvgFCvWvQ-6E92Q&Y0?@3I_`y#{R1Vq%=jm z_zXccH7AySkmQk19Lc6#%hJ0h68J{8Ni+28KtPBIE)NL54)BYK4u(eqZX?5&Q$EWh z0T9ij9c(L70?(3zE*D=E%DgX*;!5IPg9K@Dhen7|%@DCCk!_0tXX295g zBQvnX=wdv}al@Z%!}IC@!}5VblVm8GGp;ARLOATU2;DJDmpWEV{ugMcUs;5Fj^ z9vU-r8Z|9A#6=wc%x-A^ivRjtp>xih1w!X6+`o{<oMxuj7tdx5T*YGq0X*(@LUQ-v&^J_8W2m`S})Aj;y{ zs&_&I14O6yC?L13b5<=|^^Z{1M-+BcOtg9%z8H_0QC*@wfVtbtemfS7Cuz|IOXLZR z@V39SDHJ|7y@%O?CZlu~zn@ca-_te|BhiJk;W$hAi&?x!c^uoVR{|FzME^~>4V}nbE!Om5)5n7gf z8^v-v_+)wtEq?w*YAxPHpM+B};}`t>E@hv2EXSeU{Lx}NLcS5c`=j;2djLHu#taHl-@z3BRc_wA$m<1T>89 z5gE*UgjN2L7ecFBya^+f@KoYAy%2h^tgQRg!ndOH-i%)N@;iJv5mwi(D(X@ijd3Xp zS)9r1{c>TMzw|#tLXm%D1Iifzq$Pgnm*IcpIUsMUpg4U%KC+&^kn&-_zDsVRuTmsi z;Mebwo7U0Sb0L)+s$j9$?20QZVO5`v($Wrfiw*U&{ngo#!(MIuEPs2WGqN$czQEs@ zF=*o-@Yl>V$E2=63xN1&Poytf0%HIu`N!A9q67TgUz3c$wv105T$CO$LDnFBW+< zT8A~&A}a0ilPRr)!*RP-Z$8NX!*?9UduAuDQSsH*2)lgM**MwUFf`F0{Fz_)nV)~h zhb(5RsCkSsypb+ZF4jo&ueafi&jZ40Xr5DY3sLJ}sNc7CgYhFGilb!UvYbwYPu*XbUGK7PD(fSO^wcm_C$Lz|=(X6xaU6sVt>qil) z=%W-s=vJW#w-q}3$3iKmxNlak{r`>gC!v9Tp?cXU&VblsPM~Cl&0} z`0G168>4fi0%*t1aUN8HcXYhgoX4NUk6yMu)UicetUI#nU+RS3e>hF{tu#(3<9`yJ zPh+%Ww(xu>STUT2sEVKiJ_JE29$z&S6vo}jx;wC6yA4<&(4HE5E2Di?tQZm_tR!es zR{N@$AM=8nKkUG#!v>7Ro+sg3CTA_nJNr8@8|g^5^`{HDuH)}H*mUbQ*Osqcu5HND zqdv2+bGR@1cpo9OpXM|@pZ)m#8GRoHkD=+d_$foyVf@)n9?XdDlsNPxzO8000$gH% zwVb#yV2(vDmk2dbP8A54qbXz;mE$g_rn8!3hBKm%hjYaYXKAw=ha0t9wtS69n@yO~ z>B@-SvXwG4+VF=ySd4QI`m~70drk{@f=d$v@F#wX9}b!uIxX~0(^O}g+F%ul>Oev_bv7V{8#=Z{@CsD)WkHFifA>Mf8GdF zQ@~EOBuRMcQ44C$M#9)>p-f`Q z0GPg|9%R^w@7t{aaweViY{0y-}*Zi1^(2&}d(&EFNs^*7x?YqYE zAMHBm!2RI;mCagLM=qiq5a`nmX2|^OcSEeWB%+XHcPtgw?>Pf(o7WXLfDLr}Afu-;VJs?z9Z=N|%Bh2p36-bidlYB|ln4b_bSU?oP)m zb`QmQE6KcVkBOs@JvCaGC00qSrF|8((T{XWPk+2pOy_76e(__nnno!VaCWd5VhetS zA@-MLu`K+NSDZr}1PtVE#dGv3$`>i%ci;a@z^zXkoYwD_M0FO`p&*4x$(UI-vy)Po zwMmg%MunAC>_JY4kVKS0bR(sAI?{jqusI-z5Lk5w>We3UM-y<-k+%q5L`R=QvgtPb z^bI0xDa7WW921aYG)H>=0OgWCf%WIF z--b1!5eHp4f@{`Rocmu9?ccCOZV^Y+vv`+8D3vcfZ$n$V6gll8FH#?GgRh5kh|4a(8I9;0jcAc_bdE-Jk4AW;2-j$Y ze>7sJ6tSgUmY%7olsc`&FNC9iL|6Et{l{)cH4p_r)@Y{|`A|5y3lUC7SS%4&P=EYq zJN3s;+R-0{Z6LmT%O29q@-Er3<=%tXXZyqJ2iv1NrEP8MtllO5KfDfEwPlCCf~FFU z6eu;U*wD8%Z1nH0QQVI$O-y&IrJtsjt~f;?Bo4(VcjWd@eMRr+r&NG@_up=VAhObJ zwP`R%3y+4`r$HQ%As>oH`H6%9`0Jt3Zz_{IGH63f`Ngz4f-nU?wBtDEYx@z}FEysB zD>vruy8<`nT34kwjyHC!udIB$(jhaL|HbPLcDs`@0F(Xgx8aWO7k5dV-%zd&qb7~9g5~vk>+7xYQ9{P+_33zF@sAYV z_4sR}#)hyIhn|2r9$)(nrxWn#F?0r6DAM5awX`OZQi_-Qa}~w|vEDR(>oOEHfQXC* z@*z4rdt+oWtCUewyEV}fm`yNN3lsfEj zs~hC%wQ@yybED-%F;Sh5--YPSnv;fL!1tl%_}{fo%j~pMb5j#OQy4C^HOv_^+;C#c z*%Mr3Qp4Igbam0HWjzli_POQJuGFn*yM}wUuD;5HeOhD3gvob}6$GDaSD^E+7S~Qg z=Z=HJjVDeGB9A$#p^(GVDxZY^)IxX&h?R30S>^a5ni)3x3O+zxag;QA_T!A5tq_Qmif67G0P(@SBPBZntL>FIm;jqSp#?YQgfc$jC$ zNo-1pl#j!|?JEAVwDhJ;zweo%=9?5{9#{XA58O%bVloQ(N89M2Nf`^E|B6S0*#ywH z0X2#FP4z2odMm%_qFqciE*v>R{s*i!5^Y3UyY@Km2cUi&`WbAi||Do#C&)biZ})0qDSK<(n4%B4lo^-`b^*G zcLU2J?PH=n6lPl1+tW6%%$6;a=8wir`DvU?EMFSq3@JYSzm#E^){e65CHLZgv<>U; zX-A8?cmH9Fks8ABJrL7Nv&8SkWF!ky+TCIovZuyKGsqv8fFvs`t~Rmvf1jDfUEZk8 zc39Lt9O22sm!{Df*K7j^6OgP0GZafL3;W|%LKtG_s7YB+CBQRSwo# z_O~t7Tv4$dhkbYStofd>wU+qcy-sxG2Q+MnE*YU%nZ`#W&`eCzg@vg(O+pz|9_ge0UM>e>}|SL?c-6ZOC$92pMRXYrRQMFDI) z(azGnFCQr{sZ!*3ro^UjS2Jyf?&P>DEHmYM$d2uQ9-F-*s<9!G`EG(@nGQzoniQ&hJ8Pzq)m6Kw9G?Cz+rx0Kb4N3^Qg>o6QDA{S* z{&Ldg7VVt&1@k+&`?;ug58o!Hn<+ESBvGE2KRpAFDr~%8uF?v#I#xSsYjHe#yj|}u z#LePtVp;!e>YLMP!a-&aL{qGjN(A%7agcU z5tXx9Rd4N>tMWxYTQxs`s`Mq7Ma{hI)Yh(Ay*j5;k*8uRE*{K}?#$O43uKl0r}GL( zM81;Dr0buqZQQZLIGd2sGI7eojL%3mZk&gN&QZTU&%G(TG=*i|-!}q(eDrUF$ zL=HQ&hVORO+DRh?@pjiQ+_-Mg7JC^RwvI}}xm~qJH%p=ePKLsI<(zV|2`2@xGrJaQ zI@ORixvA#(OWOI4gMd}L5yvBSj^UTIwJ&6jrYV`W{KV!1kuV^>vFrR^ zFuMxYrVBpIJ!kozCOrJl2rz6;7o5!f%yQLmdRe+#Uw6K`DI zBxh=3xlmsZ%Ottyza>~Whx#92rTkyPf(tkiFHgh&1na*4D_ExYVP=Rr;()0x?)`SD zj?`q(8-IGx_UOif>mjouqND)c&nHa<<)&(K^LJ6}EF(HfW9hxSXe?zSK8vmlC^`}w zTr6e@c2UP#>MIK=tvFG|vkKlEx%(m4H&STDRr^etU6f5IbySASJ%dm#C7yXPR5$M5 zX#Wyn2HKmIAU!mdVT$NB5q6{pj|N8}UyHI_ZaOT{3P(nu`}v=?A;Z{H#t|qLK%o`2 z;Z_7Vf<+rSqwR>pdh}zg>r972uoi*6BTk~GYIv3gPhB$eem}!Cq-t)lhdp^b+QCkO z$|;Xn1@jblG9g&-9b^?fzmf18IfQx+_HxO$u@ZqM=;44G=;<^RYW_2G0OkAqu}4_i4)sBz%fF^ z5yC@4)ATGE>Jpx%&x9OriFjW5H$1^ZxA43W9`{YVQ9=GSnz8`jLy$hGNVvO_i4P_t zrYA$jl4{1eO@?yHKG#;_*bVH`)hNyi+%f$#)w?wHri>^dOM{c?DXyV;H?v zKjNab1Qre`sK`z%MJq{kn6rc4N9{0$pyf7N-pNL+BKcyJ`VEw$Nxq=%MSB{+!V$M? zj-Fp50{WWar&EV8x}X~^!n04(4lV%?k%56z5wVKH{SvH1U+gTB0|q1)r}u;#v>Cvj zu%z4~$zg*33XzguD#Fi@@yWN~-^Qmg{~JDKOUWFWFCa*0$2UP+o;Q0^feXyO}4)E{OdsFT3BCX}awq*~&okeo8J2_=(JwQPVe6 zrAD1z46Znb)y9@K-mzwNxl@JZZ6lO2dU(RT>wg35K7w_h1k1^#S#1=UgaXLb+On3~=au?|r<)S(jpE`<{Edg?mRq^G@%ChKHN~-f;L*60oLH;sP z^$E>X1*a@p9ZBO@Cbi=dYDY>}^;C#l&3H;ey0i#;no)OHh1INXm1_89?T%O0<`yE& z5AqZJaYy?f44gH@c!LeaQ0a?BFd=$geoQ5b*b;bV_bE>Dhu8EBnG!;E8|zkL#7m&E zz&p}Y#mCckxxnR#K9#E;CS!PGf0AQpaXbqZ8E3uj9o1)Fo-97h_pI>-G4GqI3B!Lh z^vYT0vtld-#X?46L+!?JAu?>=W&q`74A6$EpTG zms_J1pNp|M0%bEFE|kB> z^13#^uFa|59%CG~YkRTiZ1UR8lbV)DEj54{pJZnEK9z|DhLI%cC=9eAK{4{mwxCjk z@-sl8rE62U-E7ju%Oo&WGKS&*d?B0omglUO0NzIcF`CwYoUiSg4$OC4pH51j}MCRcZck0lOeQzjHEjCiserkEq^acNc`9G{iwGm z4fU?~Av)<+H05s>^P5BUt%#cV@3^^2I&o}!wc13Yne&ujs+Z@jqr1`K-f?yB{Zw>#gW7D+ z8(ZKp5&H?cLM3nU8Z2JgptgDq>3Crc_jr*S7xs!U3pjBv5paAh5)gY!b#J`1!6t%i zcTjQyO7r@n{%fKGQfi}o?{I^52UPW;Av7U{RaabVn}D>KAJvG|Rl&*!=|;wU0rMfO z-NDWL;ub_rj(cdqeO?&nDfx%!d(AX&afa6$u~}nNWg3;RL92>nUW3=mz~LJ`QTw(n zh{_o5()OmA*;G1*;M0f`IkqjrS_Z#w6p}|^FfoEvtV#I=oR%ke6!b_lDZUs{e!*u` zeBI-a$ldftQUHoX)Xwnt7xBD;o0emonPCBWP1brLjc|wy1 zzpu-p3*mBoc0yrnqsA$py}EFG<1%N&?ApR{jT@ZG+3>4)K+(8^tI0}xE_>;mXKNzo zG$-Z<<`8dC6jwt*tx`Z@KBw?0M0pxH=VeL!imnhm*FMMXgdCMhTa}YrXx9;!Te)O- zRi!b)r>%%rP&{xleA2pvOG+Y^ADP zZAO&t>B!QrKj*)pcMJ+^2+)9r@j^*GhnX$3zBtw!(fVSfSK0caBC)Ir_oAu9tzyrm z&z;($-kW&>EH)-yb`~*lIm}{V`%96|XSctkaK5r#8R1j-54Db5{2V@IhC=ofB_(-A zsE)W3p6xISn`%Bko$Xjtchw<((xLaNdUQ23s~T}*=aOXm$obFtzY$(WL-Z<|x1*UL ztA%#dSpQ7!gDW|uc%sC=MTszBiOFHI1k7IQ-K~zuYLiCzb1VN>iko=3{?Dz$9<3v? zoi-vJPD{#!X?3eoQfG>LD)(QToc+yeuQ#Dp{`qjLw#VGQ>zJZPlir8DSFbu?Cb{o< zEu_L&K}nAwX?Cmp5GA!?j!R+Pn_9))Sc1_`5rryRtJK)YT#ay0Zd#(t+Rd6%8Y5OI(VoCd|A(pi_ zGnF+!ld=c}tqx18ldXD$sqST~?qS@*6nqveWva8w+^*kK)MC76-w#7aR#n8z?WLea zOi@ov&5D|b0AgSd&;%OLN}$RURQyzDLkPP+603K&>lNe~n2m|_VR|XVOBD__RoM(z zH~=?kZ?_Q4d=zu1yQPzoAh+iBitdrWH7>5ysS)8!$M8qC~V*!Mu?&p zlqG2JGAF5!X5);Y7NgTdI4UtkDkCW9rNGPxa=hG`!!sh$~mM;=2cKJvb+v zNp3tkN+Em7^jcX^dFl+;tOJ(T2B zy@GFV)wWR5$%3t+q|a0h_&!{<1=S)sznty1YWbH$sWr;=1^LY29=?*ol1k8gU`RMO zN@t+iQe|O^GHx2WcG702(He&#Df45oZRFftStZ6ej8Jj=V(#Fk?~Bny83Qhv6${_4 zt(dffB}(%z6)n4lL{^tv52J%b#K05fuPzl`yNb{Qnpq_gdXs{?OUhw-0Da_>@@MGUht{-<{0!?R0xg{dZ&FyRx}YCVf9}qLgY?YVS@0KnE^!yU zLC>G>gijbeXY4HKq38WO3%bKkk^}zfJK?$p{{x-$UjPiN zPw<}){1?ZMh~olwYHsZ^KcL( zg4aC5CEC@C=B!wvbic*%Z%~GnTceJ82pi1(F@ISrXHvG`L0&oSrU-;3X3(y(V^NCv zJogVD>v#rXjzwkhr?E4IF+Ixy{tCFh7<$bU+~pBo^Pm#^B>{;R@KRyi2XN+~+_VC7 zDi;;9IBpi2p>$rzwL`yd$M4+9sDfREBS zA*Z2CGu0fM!YW}LhI@^li+yY-Nj-j(h`Vyo!v*-XpU^pFho>jDEb717h=-~^4V7uO ztE9bb>KC#6ono6hYi{co71u|4FX^t`rUn`V{z#U*>Vd-^veLyQLm07VqeIQ$J$4yDW=6!9^bUN#YlaM9`dG_K_y| zkcT@;VGE_O!GzLjp# zc@pOi=I|EcY+MR3h*XHrI%6!pgSg@z3a?wu#aeUc;#&e{HK-l9Gbq|7*o(E+;uvbX z2{JM~wv6%E~yPHgNeb zi5OUL&d?YISyP&*{DrI6acNRJ1jl`pjdJiGv|!0@Er+9_mWCBFn;QNLX)$j4E(9S? z^}%f{I0K+*!+B->V2dNtr!J~xOyA&IV&y;#w6ii_on5`dU`xn~tUrY4i%SBol|zSG zf`?j!ztCb@q8B`y#J4tHMKV$^qrE4(vTPNJKt6`BF9Nr=t|fEUbxXK0#^@OH5^+Rz$5$S+~V8*FU>tzV$fiI<@Sje8hz z+YVCWn%IGBA&0!WK?B=iE=H2PxOGaZCoWl^#{%Mc{`VrpZ9hV6Ac(6Zh}c%&)M7Of z%#lwBX2CTau@D>cwIr2sB!uO)lc+y9XXI?C>I&S-(XlAu?6h*~o;)sQi+v-EI0vtG znzs(Ry;)5l)Xyc9{$X5?!RV4$BmkC9B=zbHm=%vl$6!ll491l(N>tjwNE z+G}=}HL`LEroqF%&+qP42-dvJdM+F>N z4PcvvXe?M-=)7p3S->4~_H23T)k6rFu+J7<4VI(J&A--_0h#fp)7~5ieJQE!frNdzJ@l27@1EPOW5eIqG)}G`||9J4I zc_!rUIUF&VG!YP1a`t~td# zP80?>L~^`m_^P?g`~{7lr7DNqJgJ6tB-a=nvEKZen86KF`QT2Y27Gn-!9$zg#r0Tc zRe+YnP3HdFEZ4bzFvsc^{$Nhlu|IH82Zc)Gq-g#)RjuMGH|Uf1Osg@>rXi948wJ*F zu)Dw-v;yY_aTpk+c@DpTqP){6g#RVIA7Bl>W)ixaf?n2h3T&cF_>TYMpAqHnYre%N zZ#DCqC`|QtpeV@2IX2qM%fd?A4wTE;k!vb1Zuf!84EV@qy?BU!K?KqUAeW*b34?o^ z`3)4*?+&^J`I)Zfp{{2Co@V|!bvbi$o!h*%uEe~e&S-w<;tBrul=LHw`5`VL)nHzc zsx@!*ztVgu%2>=?N!A3Lo2fcwB2E`VOySHorsXBaEPi}8|Cp4~zp0r^xD@qeQ*-dO zX8utMbPK9}_n|YdHV?hr?0>mg+>i(elVBF@AQakW7PVh@i#&moZuoiG(yYItPybji zaRM%zo{2I&|D_u2bsvg`m=vCCR-tTTa!h84+MTT6U!u-}&%9*CdhHZ^Nt26 z1-QnUKTaWQeB+9-K#ef^K!wz}U+^wi7#|?GGLt!yU*Y{v90aNKSn>Rh?=U zCui_@g|Zur3VpvG4Bqrk1AG7W`0-AoGqNetpVBO(G~4rN|CvfS$A#A@d6Eo|i?qFG zkT=ts-vGByT!LegIX_FCWfsRm(-c)^16|W?XD?J%Dl+4L<5NhtH^HxQUYs>AK5K23 zJ*y$hZOxlv%}dWZk##nUZgaBcv99!|J2vtM{sb!e&$&O+bY9R? zACNWk`zg$D(>=g2HSdkyb>zR{#u--(f1Spw)c3@tPZj3BsqX=7!M9XrNiON0ipWcj zF(xY_9@ph1k130bMsZ{B;1o-eXTLjJIomXQ+(MU=Q!HEfgd+Hv8|O*1Y32D=RcBnK zTy^gO#WBb-aaY&$z3Rb5Wz#$n1u9-l&9qrg zZHm4P-^qDKOYsS}ZPJpMa>%lkFS7$CX8qdo6V)$|F~_cJP#crkl?|*4e(E?b>WE;R zBezBOr{$s-kZvG*$ zVXCmEM$agV&v1jgc{kSSBUi_AYPhjTu3>Q_SPT$`dk>>X8RH5X)lIE&aQH_0kcMa7 zW#*4b(@3Nh+U5!DepR-U7nmZ9An|(d#-du4BhM`|DYk**`AWA#UETPwL@T1kBUDc> ztfp~dFj!*{*E#$m3Je&v9lNOdh8(vju>T;{KUu8KuYRom@7?^JQvF3dET%v6tKEQY zmg6sVjZw{9T*ysGiaIJtZq*Pv^8R>UOL?%pTWX8L*iB1-Jf$$h-J`kqNNG_V>d;jNjS>T^8;EqrB3|_;Y*~o(bm#=q$ zi>l23$IqO(!Eh9Y%ZPwAb6|!`+QQ%k&~{QPrJB;Su`p=EH>z zzJ~~5o%k>i($V7WGzn{c$zg(p9t5Ks0@y|=`4cL=Ffe^o90~1h&(nS#)!>02)LEr*1q%4hF|*6rfw%CJa(GsFF;h727-J zdg!fhf-XosQ`}vC54V4#45aTWdL|sBg7>LzL<#-=g27_Ji!RPrFyL0fUdn*!{wsoc z@VuAl;;9OP?L&VpNy0&YE#q`@^$t(e@`I}jru$+){zy4Gd0`q=W5zkvWfTuPs%Pj{ zJ$wE2d@a`VSJ!1%oY;?1ROD;3POQf$1W`TWdAA{@%jDZuQlP}7c_*YKR#O$S_ysud z1H*^1_0R0&3;q!ZHy*0oq}(WOsGmm^C2Bc^KIceFmRc<8l5C45q(s)a)?x{TE((3_ zA~4*R@XqquZhG(Vy+@eh0${jmvS^kUKS1g02&mph*S8%m-vr{Kj4lP}3ZaO;2>(sL z7gW79F8^iZd6)1YrC~+B@0}q>gV#A6Y6C4?pY1Vw0BdrZLSpsvyYGt|ZoLKz!rKM^8ZX=|e+tkvy^O-pU+sx9}FdQanj0t9EN+;+)z< zE}&I9(RaY(S}@UG>a8-atcmuFx6*PC;M4I2^Jn6@ARBPp^ z!GaAEgd<3h);3~9M4n8+^&7Oe(E5%RD~h_ABW;gE^FD?Q$aY?1LcRNsh!vW@rn8?5 z=K{1((oLgBdOk8ar)lU!zY+6y6^$eD4si+c-B)j)FFn#5Q!!({KIt&Ecl8B+rF=Ld zVQQi@VQXSo!uyG_x27f2&!etIR2Ruas4kEm;vMcgr*9necih6C>)-w~1oH6R>jWmV zq8v_ZR=nUHA@_(C2*RGF_22idUq90QHj2rh@K}{)@%2|1BJH8t&o^CuUD) z7aCQD@H-4^f5Qa~N|||le7Jg^u}&4gN1C8al=}x5+D8=qO(((#;+$79N=q05Qj1z+ zXmar1UZllWeg!%beGv9Ki^B#4yVDT;O7RKSY+$BK7p6uU!e53pw23b>{TXogD{cY&gVr*P& zY4Wq*C@vs8)GLTt!|dEO z!@f$y>)|fOM8XRk6xF!PF$q=QdSi?+g-9^J@14Vk#DvD!@uE2Ejo~>5cJdfgObHSo zIf}`T*)lll6~_Juq%`Knq(Sbd81jCe8q00bR9?0@1IV)db+7Q&GlYrR6PTFggwg>M zbBR349EarbbNv6SH|ARL11uy*&@~ob6$>OfiTniWlAMr&`u9m+EIMnhkA6m60Sp*; z3Rx5H-^hvU8xsT;Lpw+dkp}uXt)s@5CV@|>yyx4WRoFa{qHcR3DVpRLP0813e{bdV ztJh>zm#*l|6-=I}YIUp5Zz%OVjg3RsI?|}q_NT1)q@l3fuFiEqc_S;Di|Fzk+1)5! zG}pmK^G;?-XI5tOad(a+=6Ze(4PndCdlvn0(KG!Fu9f!^*tQ~~E%XVDU43??Wc%fm zr`z%F4~Qt86aKjV?(5OZObE`s&tgS3<8IqR`hw&79A8m zr#Tg~*zHNfH3#<#vbXiqun>d@=>#khT=akY+a0IRo*u>kLXe$Sxq z--)F~+6*NxdIHXXi7LjE%uQLLLk@_G{vY)(qVg0KTwK>;%l|*+vp{X}LLv>}eJn)} z5fX^z9)49#S8~BXFK44jh7(7R_@7F7{rn2r5lA#5+(93GO%iS}M}$a!{&>po-(#q) z$+xvNiSkUe6+|z-wgUZSBmc84>^_2&KK`<;n?xVu6L+gE4^!0mjN3!E5xW9EHlN7n zTgpfgN-FS8_!qs+P@S!T*eFW)n%*e?xA@6XEQ~aae)VGvcTD=6OPE0w-;{kLdv4^k zoP)>ADB+^7Fmw#ix!GuM)BmNtcYo2|nP0Rw{C~Fh*+hHlU$lpPBuW_kMSB9~dAMK^ z@v}%MqW?puwqK@1E4=_Fn)CF&ir#l1P#XwCVFkUcS5H^KriHyJUoZJab^%P+aCBMt zGqu2lI^!#~+SO#;Li3O9&3vX&bV*<*j|R4)`CP!J>Yz70HHU1XC^p*81=ev5?`sEK z%%<9;Hupua3g3{pRm{iT6~o;X&f)So=@KsR&2K;W^JNutIS1YaF8Vb4RL`pFR14dp zHdvQ8(?)61%@>Kiw4gcRkKujv?H{Asy6-%%bdB_?*$Xtz{Wtf z6v`IsW|_7&+(Ft>O;W~WV&2Shi*{B#%OrKO8 zVxoM}{K*u^XM04t{3x6lBFX^ArnuVhEr-ScF{{E!uHVu3qey#TUxXw&^Bt|9DEZ94 z<AI^9JNbrQsDLo~ZM!>IuOf)G|x~q+=?Q86|brr(HTJ8ztBFyBFj~Q?V;4b0z#Izz{ukUD%r9xcoF{RrR zC)`Od_LKogy#tPMqfjubB?-7fm`Weq3ME(T+?U*^P`J$mLvm-<;cmRj-DcXdlAYg+ zuQIn;p4|BaJ$vG!Q{846J|fgC0j#8o96Ec-@Dm7YwmgnCf8Y(`7qu4HzV8XJ9`vT< ziTI<=-NN4=2!FuABH-Yd+_&~`!@=cNR5@I(KCRsK7l8UNdZk67-|xKuK{r?S`Zbuy zZY$1At>B%C%%$4Zo3x)t{F)!|W~Lr5I5XZespEjxW8Arv;T~;AySGQ_C?%}N0c^X_npa(f z+`+t4~f|oe=pPz;c2iN`2#!Scm#eJ@@R;OKCQE>(MaA!;I+HVsn%vRm| zDb$~*s9A2Z`-H~EYAPybUd)cLWz(KM_LO>M;kMVthScX$#+Ip%P5MI2zm@W@>~`ob zrPThAuVR)gnVG+cxwuGzB6oFXE;{~PANNRZVDtg1{4vVROO?DhNqMP)H~Yr2T(tpo7L1UTPU-;#sTf$ zMups#&#bih_~nfXSz`_k-^LtvdSJt5?Jh@I4gpuDke21pK2oM&%W~+7R;G}Y<IY2!#!?#9SFZ|f%is*S=q?#eKhJ-Z+TJQIh&Y@cW~D5-VDMB zd1Lw&VCE$0eRV7r>j2XiEi}F{>^?Q@JY0U)+N--1!>#JMYunmv3h3$#S2)YB)=*M( zahqeJJ*xR4t!wfLp$TQ9_X#SR8+EGoMP$7zJV0+585~=u;zcA*a8AWCeKc35^YPD2 zH=RH@J|T$uhe&L!LcxHllN1=enMaRC%w!{lUv;ESJ1LSKpfz%hpjaUBb33nE;3io%*@U@o~@<@ za`&NTPFknfWY=WuO*L9y8h`}aH028&9$*!ENq21Wxs;ws zLLa=t^wyQuhG2V%ZPl(1uRc;|_v(Iuh;bp1Mlmg+{RTcdNbb&_}8^AX~= zdBW<6Z}TwYg1lK@w4gepE)2g3GU!To$UvQ;j}lzDc^#ivr2DwVri-P|>_r{ng)f>C zbFsSgj86McV{{C=+^9JweLs(5zsSPJQ5F}Kb9tAt;@cv@^%|ktZ$BLo+d3ngsE4LQlsk*AV}wq(=N>!>k5Yfn6^2Vln9q04j)+k#pAB6Ck(sQ&GR`Sx zsMfVb;n+xN{<*Ux$^|Wu1V+d;F3i`D89p!l)SGnbjnQ-OX{k6ymaGg*)?8l?Ixdet z3r&Ihd)RYX7eOE>`|~>9^4?VT5cUaU=ZZw}YsY)u3)0g_?$1KlS@226#(Siv<-{gz zrP|Rd>x^x}MVib6z#J02v-%^t4)nV@Yg|n1Uk=;SfW8Z$5&1 z_JmyY+zS<91;Ro|M;~Twx^PXxchz~eB2HN7L*Q5NtWR~Csm_>StOewkErvrh>sI#j zCjd;7YWinPn2_mc61Tr+@{rhDG{#iL1J%L>rJI7 zDmzF3U!gSeTS@l6-Bjw(^! z%PIMbv?QDC3Ao2q)$U9k*M+ut=GSpYZl$NxXC^Z@x zdi$sdF5LP&LJwbG?_JxvdQgjdm_8jg-tE_gLt-CR{XCaewXPTYebCo$cRYg;!MGd) z^>9NW>M%oRPjgXvHFmCWf9uCh>IQoSLJI*`9d|S5PYDjO#vIfr;xWHf*h48~p+*xN z2zlowac+s^xxVt>Lt!|zXf(TA-uE*SpP?_RYnOp41rWd*R95Rjg<{BG&qT^@aHQmAci>vFfHPE)Fk+%eUuYQ=^;uCqJhZF}hzlAfn@oB-la|b-L+}2@9!)n~(*n`ds&neCqIg=5T%H z5Z2ImTYvI)T%&o6veSN1Hfo}*zRq8E@yI(4&wCEnyAENgSoW%SlmgsgTy~#v9AhuY zl8;{zh8>-Owgg5T3*WalZ+&~i(K*$YAes0EpDAIWHYMqjloO70HT~#PUUi7Z^c{!M zs#qTLSoj;E*S}YF^1d}IyzIj{CDZ)u7A7K%a1!P8%!a;kiesb+p-G)N`n#caOsmkwDv3zpwO7d2g+Qi^7@8yA+jOelb6x17OuakM2ckdebP^o?<8z;{X{nj)?9qSm zE*nFGg%08!6Gn*iztX!JldZ@*6noj&c7y z8h!kdIG^+zegAcBO=x33VT{X}h;#}-Xng)asoVPz2@P*ubesPfR@^PW6m2>H7mkpB z`<{ys%W@BnGf^9-T0$MCip~D4tQ>Y(E$-toWpWvH#;YEShFuTXiQXkw22i@x6W{?%>oz8>hi zCvZ41{vx&MFXO|}1vyY8te5~r#5dv2m;T;=q~r7x-u{oY(=u+7uw$ZgzWI{%W(zN4 zQr>Ji9}437jTY-yKYZQIJ0-lx2!i1z#!dg-54fr=k@l1ha+ zc2JJJW#H7(i*Td$JlU|h2!<|JlX25G7llO1C|XMp&XEaCk6!!vEXZQo8|kE;M)^8J zVF49GPnaT6^#4{LtiB+qs6&51z1!YmON9GtMiWVaY}PZnr|3>O4k>9uU?Vs=2*5cYmrGz)BdqaO2*@EP3PkD2jRMRxEGrogUDkS3<;<~Knp(NY~&Ew#-L;pfxcSGS>s&!bTh2?5~; z+RkALB!x*(SYk>-Y+_bIYGNKQ4RPlYkcmZHs9j-{FmuwtG~4;SBpo&;$0R4|_9TQ- z=kZWjik~#)oQN#zr$6u~&p`GVq&-r3SX*9j@tW=A^@_yGg8XYXcZf}FnTozo?WRe6 zjijp+eLDFdCjGeN2ZoK#;P~fZ-+~l!wwq9qGOq>E(X9}biJOdn1{VKIh z9`bdeO&%O=#|6%|fS7Y!#QDOJl$Ji%dQWnTD@jD*HbNl>#-;utwPxA%q*(GLi?Kpm z+;{P*_lz0UNvT3?3mA17ISDdN9~gJxHK{lsx@$xwcH3Ia7N! zj!F5p@%)?-WlP__4?Kz%*G;;Q3-?j|3CbLncaCN9A%?!75e7N_;Tdm+6r8hZUkl+* z95+>-mVrpgnR4h#ZfR$!B}z8Oz$UN00?Cj~Ck6GJ)SqNVb=LW^b^A(2E;sk>pX&Lh zS@iS^Y8Sjk{i~r6>uaK84g*8W*Z~yq`^*C{ltS|q|)wda%xwj z#=$FKoDJf#ms8{ z_<>L!LTT$AGWR;k>eS-{&X^gpf~N17C{Qry@iVe!nwNd7cSX0dC@6=@{hIwc3X5*OtQMJ(1JQlAe^~9M7 zxD%y$Tnf!ZILR34ZT9pw_x3isoXx`J-RNU+Dm!R|4~WmU88H*Mh>W!S2WYx;5!5dQ zvn_vk8Dy1~2)ItFD2}x(BTgc;mzvPD)OfEuxsO%3f(pu|1?&&xjBI?VC6j= zIPBZXkZIc%eu^xJ=a*Bv_^TT5`kT!UlXDs_a7lCJszA#FBrC%oB!eim2>r-mV*xd_#th_L+Xx|YT?0VxJ5%rN5Gt^EJgs2X#q5#*8+doGqqoR zAXcJk<{kCgSnp6X4f=v^*u&qY!5SnhFf-L_b>%wS@?q zd~$o*$oai}?sU)jy{_YX(U71foI7a0Yk+#{z!*0bwi<9{lANgJm(lc1SY}%$vn`_~ zsj)HqiDW!ry}Mrz?>=C?9zxq#&G`1qaKMFe=#gp4nRb@M?1!YaYkH)3vL=O28?(L= zW~Pe?@>mAKS3?$g4J_Z_^8q7A0ndY;qkCQLdxdWr08Eg0te9v!Ka{|waf!**l{UXi z7*Q`r|3gS^8HvxpqNMv@VQ3CpjmVB-q&w_e*yl^)3N|q%GY@E3#Vlyu9Dg;0TgWMn zuWLH3C<$F(`gIldU{DxnLcfZ3;)1B4lG5{vk=DI^``bLNdtF=i3a1E|^`TH=3oI!u zQIu(9B{SD`v76J(XW|&mDv2ddQhRmrXZ@wSULJ_%I%x|<$W#l?fH;|DtzuoIWc^Yg za;UPiG(D6)9>Pvuw#+|s27{UYxZy5!_j48Nj;~&Qr9bMW+3exfS1QhFFY1&yL;6*n zldDrih2zl=rS_B!C95m0ICRmiRkYWG5*{N`8Tc#+m5e;Px6k#A=h3~c#e0Qzf*VNg zQCKe$j)(e3ityR(vF;@)IJ_m$u`S}apoDz!9Ewd|BFhO)^CMBj@#x2dW1`pPxVgjf zR=P?$Luw|o3K~NkRUO;Cnl^?{Vup-}$=(C{kWMjt>tPX`oCow%Usmhm13PQJ~=iHvoX`W@1 zo5{Xtp0c&q?%EljSXh+vN!qu$^7IJ!AT;XK_R@S^Om0AWq)8VFnHqfnK!f))@I}W> z-JAhM2zxIXD5agBy0Jry39|1bJg8{Z`_;pajUv* zZ@;+I54c{cVa+q4R2D)G9F%=Uw1zr1dY@JG=V_uiTa^4#)R{I}wP1@<^aLSfK*|?c zq9(=YPa*Su;-U~SAmvil=9eX$3iI;N+lP*B{7V*mz#jeXS}*}L==y=1I`luo|JDtE zc>IS)C)+$}NBhqOMf1l`YX=@?4lO;D;V?yD4K%cjrksK0f>kocHyRDo@AzQ2vACGmId)g!~rKAw_rDG~S$S-uJc> z$?*xIqnMqurZmP%cCJv5J*m#LSGb?A*y5h_#;k$oFvd_7 zf$Fdv(^Ph;(K%L;8e({rRU|Oj-mLXrBQJY#{#zF870owF3>xzdqap>-{?cheDAE9T z%H<}s17BwAVznui)aKw^CgrQ9IT{u;8yc+KjXu13&AzWHok{sUWia2tq-@)R42t8( zfY89^f1q_u9_yEx0oA)$n{okIecCOcWmNv=}V} zjuk=V7^dVZCoR?lh;E;&0AIS#+FPAcBGzANIN-cO6qBc!zaGSQoWxzDm8QWCy#b(%3KU zO+{Zct}bz}F3vhUTMZ%=@jo}Df-GDwPcAwB%Or6LgQOOrs%oVQ!ah%X-h9w&C|LV> zu?`qF7+A$7Z;9!unVhecs5FYtFc2?(YEh)Ztr}w}E-`Fks~$xTP4Pv1)?CEr!B055 zMUe*o*RKq68U=XzVg(9;D!BR)avb=`qA-G_L$RwLBJse7c7vwyLx%$Mtf4pra{}H0 zEddK|*-F5}ny-$HRL6_|K=zV<+?E~Q0WAq33YWhx#a_EgQ}}*bf=2qjBfy4A?IDJK zc5t`X{#|h-TlHUF!|c00HwPOuG3a5{JzisMa@BhD#~f!UV5`#cZmhBb?_sgYvt^1k z^u4I5adoOYd3Kihzww%avpA+76JRH1QkAdS!5l*2rz1w`%;Z_Js%6m0GHJdWM%un% ztfIoTR(9}v zCLjAoF6J|1ae8681vRbP`_DXA)ABv+;8JFx{w~9l0mUcSs=Jut?6;scWGkZM zU7zQ*>DU)@Sj7xnLalahjFo7wJZ~e)Ri&Za+`QeWm3Ao2XaKaXm?V@t9_46u0|_7*BlinQAAxrim%T9Y{qg{a)S-tGU~ zm>mKwjzTGNm&jLB{t&}EQ;T2VJN3dnbajS@Ej-Sp$3a|x@tiI`W8IJ3-Q>BusrT-t zs>i&aFP)C?euHxuL-;xaw4}EXpb9%d^ui}OahkQClqfCPslJwBD+lXKXp$aSyV6k3 zDjxM}NgCy}}2(%L`>z0Izv{Cbx6rZP3HZBK7%q)WV*BpoQ#zPzy$1 z3xoTB6HVj?_;})dRJ!T?+bUJmdNB)3<^}$|4nO`L67hEy*{japmfc+8%~6_)>Hedr z_hR78`EV`HXwu$kOkg$dzYTX?Hs9WIk~Je@$doP0YIylBp823i0b191HAiKopEuUY z?^DJo9Llf17%NfN6jNk_?2@AO;U%SApmS+mbS(E0J?)9Kz7pizSZ;Fe*toPwQR)Tb zt?YHqGUzS1`jd5;mwQd|h(F`#>y)uap%-T_pBVr##@S57mqfYhxheWthU&ws-dyp=LI3psCF>saY9cl*yIQ!%YGh29(U z7usmzv0<#tKXK(nJ+$-3V`lA~#a4YWPVgVK>oq5j+=Bl#);tN7ttc&=vO*|~U$MJz z&I%Wl$g@ZRB z(?x8UXZrJfJI*j=fBuN@F_AV%X&Ofl+R5%gJKrC=y`2wy?fB=h;uFeyt{Zuu?8YRX z-F@38pm=LMUtCDFv$&_KZjNu?T*Y`tJ6Xh1*_Q9zG58+JGKT%EIR=vVEerK&Ud?qm z!f6H-Wi&$7ao3WQih@UE!@25)?BgY+G=Xx~$CU`{XO`?Y zZ1u@rP4^9I|758U)%a+@IpNaoYp#6B^f%O-cCFkJu(@qXS%7RnC*9n>uq=Tc&`Dlz z`Sq5x_gd1oHkV)hF2ih_Kz zA5^{8OLo@Lt+tafIMK1q)2`Hn0h`yAV{psTTH08}G8)CI2gdD0o`9+`oMp{5F)|@?oX?eWp zWhY&SoC9h^V4@yalhjUaIryoJI~M*rd*s&1Uh?(;T2>ui9ajy#|7x`@E2MfiE_OxA#w?PQ;%~HA{bu&&Jul!cF2@~NKbczS zmg|~!m${B_E6ZUQHk-Ioa)naLDs zG7%H9Q<2N&^0~%bQ*J(9t!vZ>eX_Z+7u%_Kyi=}M6Cz$Q0S}{YV7hjL@Lk={h#tKG zZjD*VBkqmSxA)@g113mr^uQssxptxLp;P zqJ6V`(s=9tK+bw8rG2pdPuwI}33Wn6H_j?iUjQg^mr@4Q@ZaC@(0Gqh|Hb&=6b7;! zK93Z@cvzJOB=&Nl6h^6fr23QUZxcQ1ckjGIVxN4*6E)z8Tk;q10KQ16b`cO~$3b;n zN;woo;R~xn!6KnWQ0qgA&u&ZqsfZPZ;nkBe`8Aq9T}yMNllq|oLh;#I%w;Dt_HXUj zM_QjCa&$t?;^%LW&H9CuK0{-g{~qGkl!=y5qod@b2}OS8y}g8jqWI9Cm>ypx(#rbB_ZVq;MR==iPyZ36&^|a|^VCG^Z3&Rn{FR5f;((HA>Qo z*F>f5&T(a?YR^lv{;RgIcj4Z^9FH-J$j98>M5x459pEBj-$t#djM*Qn-xvzX3)V^k zfs^j*qyE&m=AD06y@1%6;()K;J!gF+XIbxB51V>R)=XZk6qQw-#oV)GrLFhiiwj?n zhCdMCg#RMifBruHsA?!f+~aT$KI0t2GOD-`VmKDrqv&{boD1$@zX|r?9sWRPsBq^V zemBJClyafN2~A5zblid^7ecfbv>g1`zWE7rA@;OPC8Us-5WoU{eQcs3HMBVF0e)cIv$=r_ic!T>(kAUGZ$MJ!;qrS`_f|sW zWL6NH(eBJXK0SK6%D_vfKQq0?v!NmLxk@fb|7r+AuoXZb?mRWdJJ-W{gn^`y-fjyY z#s!TwVRaR&!h2*LZ-fXV;`hhJ$ZvyJy(Kik^c?2sY zY7mW+7@6((>Xsd6mIQ%hmGNnh_9!W=64&Qhy6qW%ypPSbZy$b>1j;Ccs`ORkwNDOs zmV#N#TAv!PeTtr8le zBXu!+oQsT)p9hWIu3rEF$mw&>c%ABOcNo{)RZ5UlQf)if^(s)mE;}XR7Q$$r$EZt) zcjs^&te#f8$M@J7ey}=3^MuI#bGSMq4py^fBMh{~Rr`GKY0T|6cB2Y?{P?pfd+EvD z8dXrAYI5|;hYy$ciBZT4<_2uPY7rlMxEMuWQD9>c31K>VgB?OoV25K|_-}%!fA{ul z>s3cw^Audn?!!-SKERsO7<90jAhfO?x9IM$mmY#dqO-SQLo#?HL(ToJhTm6gTwkd% zPj&0=30U(OV6HEVM}QEL`*UYYt((s+IOy*lspDnZ_a&#Jw$16p`SVszo!sUsL9~a&&X=Z|e`gM3?Zx zFX}eFe0+=I@H+Lz;^Vm4Y%3nd_2y+xv-;%+2t3UWR_u#@M{pMwJ=Oe2FX6opc-Ley zhrsTQ0^Y^P{_vM-CTYHx`QIX5Qe}(a4-^p#b@UnZpf7MTA^d#MNZZq%wx@gBo_77$ z)575zz#sH-UoP$R)upY1I6R|m!6$b+5GO9WxbclhMW?sKWl-E{@!X3!Ybk=w-Mm|S zJ&IXtFk_mxy(41KhyMe>Rc&R-w-owC%CC{sJ_%MhuM16=C5CHWdmD^!UKgG&Pb6Nr zVlh0m_rfvI*^@sGK8v+SXTQFZj?HU_7D2-xU`aK(Z$gy9)zy{lTZE5x5za6A4}*@) zgf{s@69LFYfIsb*+9HFCDWP7=^Xp#XJ|QpGpV7mp=(Z zR23wdZk@8DIGEST6BP+Xnm*bMCL%`03FtBAo4u z&Oad>`2}41$8Lj*V+pGDfQm1oozYtB18gnv-#clDiyfoxQ^)Jo{kSI(#7JJRouy( zUn@LKt-2LxyZ)Qr@kHmea>9)6uOgR^913 zQ_pd4_IBh2C!~Dc*yn5+d8^*@R=w-3df@{Knl-dizh7y-;$=>&T(8$7(#~XUpo zGq$sagkN7x3u#X?M8=GG>ieAUdS0!E_M#yzr#R=Ew9roeV<`h)OH3NyBejR3F86$z zk)1~TSmy-8gb5B!`*_yPOOO+kU2R5Z=;(RLF_vr7r%LEz*2$-Z;u}(G;0BBEU38$n zP*D&e8R@F;bFrSzdRIriaF`(F+D2zcR;k=h@1Y1Tp<0eZN|6|muFsu?_C_;v;LxN0x*&l4dq+i9@k4Zf(_3?Jr(_G&H(?)GMk?+)AR!zNK1|e%5n){8Xq25(p zFYKY_+)jjhlh{B)LHLzc4Q1fOsPrUJCrUpDlaJOi%I9sXhxX5T*~ku5u*OqS@7h`~ zJSoCkGs;Wu6X6X<1&GDfBTo!Biu|C_St7V?Tn+3Zt^6%`$!0J?MzWvZp}IlO@9JIF zdSN3~=UQE#pc*y(_(5$fo*7vgqUR)imZfZ01a_G)5cbn93( zlrDxHYQb2~MYY-c0>T{u#Se$U)bxlWa%ig~VJO|62F)%MY)ER-YRd;n?ON0ih_4?u zsWorQlAc7w^CUauZ5CHt%~KofFnB6+-rQImQYH;AUKeiA#End=@7wpTC#K#ttzHPF zjudMqjYJ~xoM%eC=$VaESVTc=(psE{Npv2ThSggJ<2G0uUrz=-W>>a%x|IR(Z4tOC zDo##mO%Z*DpsI5^N6P!kH#fJmeDE_UHBZ6cfz);~w#=1aamwa|=D7p!C{9}37f7z7 z4?bh!<{N$OWrI7DL}cKi1-vZwswwtkY&zf9CB=%O^^Vv8q#`LPm0T5aCO+HGjYIIc zRM-S8I!3=KAW1<=v^aUC8=1i83^OK;4k3&diC*sFPY_eXUNscX{d zLJiU~O*XX8CcC3JO>PwPAk{ZF1ZLQ%ew0n3rdRV7SwnTC6c<;)vv*RUl(*~p_D%7e zsdK$iC;Zh8B#fERi9Ao8zaQaSWW^RUw#63pmhku%ZcAKzi?S?E%7t%?t9+$#!+dmF z_fp*kvEOh7uTP50XPK|D{8t~)>MwfpMQCQw6&FHyc_{xC0;@)okAF)QkA=DiGX~N^*-u$d`>@6*?WZVO1G)V~HEO79Ui{YBfFIH@p0%g z919%%P!fG+K*QXJxT zF+s(ivnIJVh;@(mCTaVki4~Z z7v!F`b%rq3v!?E2Bb-_39;(aWJK51;rE^I+?kE+Ks(oIg^v-#!#$Hut3=I#dQ|_-j z^(y*;dG#W+oC@pu_NRLa>s@}&m}^-J>crJo^JIR&9fpV)&ECLbJvnPE zp2aF2WJc~sL7OMHZV-1HMmRx4pVN6|l?*F`GjFPzWRu@foFKPFOgM09uN#}CUP(nV=0G{M zL|R-DJv3MnHdIv-J7hM-N;RK?GC}5!Gos>Wfx;WTEMHU|Mk0x7874nK8?+w*(eH95i%r z%haKDTM~!jx1_(aF6jYyQcGG!YJ8ZZsKk2Md+3zSrLWm(gT+unba9HJZsh}9m}TLe z#tHoxNO|(beF6CgKl8#r2TNK-ygv0h$FjgO;rb z(7byCDOIncZy3MQ^R?U0K}5qTRw;wBZAvWo9Rn_=?{%{N|0i7|3Qj3(%1CZ%aY;_5 z=v7K{L{2etX4yo2-r*|s20O-j18uW4PniNDi`VLNB6FoV3Atf8X}Phc1UO!mngU=a zLy{N#O&iN>s|0zQ6PcKrD@}||47;UmR`r9|=0g8#HXF>Oya?)Q5b>=%3?D8decV)N z7tkGez==Cm-R@Aor(Jc?Z7#M!=4z}t!rc-_{(C`>rRmZ&7HuGde=hTDkGdlH-#FjP#72D-H z+K(W|N4=f1aCkTVO4`ykxiL5-Umnu1>^LrSxPKHl3>o>DOBpnmY_G+wNU14+`Mi&6 z>5w@8CNKDXoUo~ui>Ya8c%`!7x!6YM@l%@{j)rX9c%=pL+G?2Y*OteyirJwf0+y7mIB6wFIs1n#Gy7UVh6V{Hg%BU z8e6rA$*^HAWYAoIYwDV+qjpT_KIhHD_7JyPWr$?WkHAp27Vdd=MzMn%$SR}aN=rYh zC}C`pc=+QfxHeVn(Sw^amTj!Kf^Io$N_3}l_{y<>9@+b949;k? z#QC)RoVwsz#PCkwBf{o9UeOi;a0gd2ws2W@&(0*aY6-lTh-Ip&Oh=Q%u5SJ^v>@rH z-EsC7#6E~?8@vH=x^_GzIjL?|$s6U2@Z+wUBV<5-I2^$R8{g0hS9XDH?(V;p=02tE{nsvT z+R>M|$%ntG{P=MB`G=jY#~Y3{4Sn^&W}xJQW#-M^;_K|-9{BJWy;CyyiPw?RcED=& zYBq#q@HlZZ_`HAYqRmGS@mh~GKcAL3{`7yK2t7>QB*g)*@Ww70^40?3U==;I-3Ns1 zKDG<^Ahb;2WDX46e@4h^Lda3p{E0WglQ=bDBr!4Jlf?9dZxeGl3$ViH`h`A)u@4GL6Y6IZ5I|yOl@r? zob6nw0=(14dVg0l=+_VJb22?a9XGrnb13kz{)TrbA6KZPj-N0Gu!p;yjCCh`QRwlL z)KTT-GOShNaRxaL{GLvMJZE8LW@b5GBwM|@JijQg;KV%b!pefR^FUc)ht)*LIkIfE=C6z%M*64L4ZW!4*tF!Hv~}THhyqix+cK zlkpQjIIhhszY5)h0;c!gUHog;0mpA?54L9|CB$RjD1h(9#8NIGYsRh_vI{a;0oBVq2Y|2Psh9xmr) zcNFwR4acju(cIp~)5M-}qzF-x7nert>QQdmHRZ5GdYB38ok67!iwDYKR@(Qb#I7tT zj2@e*Ui3KP1w-$+o11c4o>sIn-?%8ict+A_;>%2TSmwt8)9JlwLb@t#cYl^;5wXJ3 zquc{=q9U}giiV%dwd)=YNV#5PTR_=YNjFtbT3u1zDXq@ZY|up)FHYU9+J#}~%*H_S zSp#bS#rcwZR3BI32(|}kN}`RT|C;nXlpg$VrcS2aS*c0*BFLa!*i;}JMO;>sQ!?PB zQPG~Lgq`vK67mbayfj$r1zykAa8oKe5%x6P0ct&VhH~f&NBB^eBW`GY!c1*TQ$wQm zybazBPec}{z0W(Z5B@Li-wp9}3nTwWoHV_Z8gBM>W)U$#ee?UBJ436{t~-}fuyVAf z3@Rb(rm$6wUM{!vuQkV@=`iD@^6PuYlGNR9L_W3)-7hEXPRpwfN{lux4zMg1ov1l~ zLfz&y-stW(HxE{Ni;cm&jMpX}N8|BFrALYo4Q2DGYCQ3pop20scSnvA!Yt!HZ^4G|0A=#5ime3Q;N#++ z!`(f>*0=ukcAiMbuO|z?C#ZeD9UI_gP@#WbqTdiGY^HSm@5QhHv~Q6u-?QwzL({+c z8q7-E2w!(Z)IQ9W*cQ_?Excmk$tLXZjEbhjUc1k zqsaim-=~UjO{8RG7P36*nN{O5)(Ag6Nm-^(?znq0xX3^F_U$@0W-4sj($%^dHK3Ym zYzYDGPzDyKyDeSBtPz71mx;&bOSa~ds~jh5dumWYSFZZh~# zQXBg(P}a8jWU7F_QJAw68xX32?aXM*WS^pbe?Xt*Hw6#g82P@sZ~s-#ST%B*-}cW3 z>cbf5q*kQ6zN{8{s1L%wt5d$Iwps2LzNt3mZ$f^XCE0)E`1^gSx^JJ|bE(>Op;~ZK znMU?2uCSsyq_|M8Tr<@k+MY9Ky#h{I5DzH;;h>h6$RSu7%?zBfh90ceAdKE@@c3l~ zVUm&es{35;dd^n6-l!Jp#M*eU2AO_oOZ5FmbbV}OpXf6Z4}MQsvf_u+?R<5(-B=xG zH&xHHvEjRVZHxRD9xJYEaIcysO%F9X;f>c%xLB_sk`VC~t7k%Eg4T}$cO8Kl3QPH& zeJDKZG5b(N-lKNAw6>57AU#A#fdfR*pB3RLB6DPpvX=0`+%kC4Gm*wtj=b>9awMFg zgd8Lcb?)-e1i|C~$J(1fHFd6g-RL+dKPrL&W6CEgl*6^=y+WuuZwChH}DO%1{bfJ#_LiV z1{%I-xW=2pcwH{9%Qu^5Y>_i1Rl!x0s*`g!M?z*}o==X&>yZDYc7US=PYAg`VyT zGOb>-X%26iZZY~A283*nH-ngsW>INV=T4k9bk2<8%!wkeZUbXIHF6xq@`{@&JF6uYl4Yy9`Lh# zzs0e6(fgYQ=OYcAzZOFc$%Sd+e55ve3mRY$a#J&s_Z3HBRE6CO|UUXU@_$oOpzakEv8*`l?;bjc!L z!qAw9`ZSA^pU``!28{`3#4V33d1 zLc}k+X?`tlir`I=ylDcj`#s(*-HI5w&7|UWFQ6N;ti*H&p+82~l)$4)R`-Eo?AT*9%$H3rRq{sy;GV6$bfRyV!~0;_3V8-F!D zym~ibblKcV5lko(lYP>&GxSK~?o)C;De}kAMOKgHhuxP>s`;b|EAaio?jt+Z{T;R> z6(KSkcdNSP%Tk%5K#aJ>x9Z`~?pA$4EYzJD$>GIoUXU5+D*~^rT4%^1P}3lOA+IR% z>LFm)A9RMh&MbKTXs3%T!JqtPwH8BA3=XM0$pn-~ejRkgv3Brm4Z4{2t-;)Lylbq^ zTq`FN&cOlSYNYABCUOpjW>P2PE>Afh*(Wage(d~UH9>iy@)8u>Y_$G_*}~L2`9}c-H9b znUGFb`&Pd$j~w3qgN@IP&ZS*&4Hg(X`ksS6KJ`9gb*ik~r=)Kj;4Gwl=1mVAV4Enc z@l!nBxH@>hA=R#Lna!VBzy!CRaEH9GOI_Y}vQOSEI^H&+FRDA@c-y$X#O}D`ZL+=$ zcbw>WjDjd!Mipnm+Iei=>Rshv5>5(_4YnrIjW)C`7{@o;uLj^xzhN|3)l?T3MXn3y zuLpDn?NT^mlV3U1a@|cMYUU5kd%t%h8n67v=DlA?5lxlMsmLD6F;*ZUm~_AzF1{s{ z3$}L15o;+q5r(xzhk+4wdU(cC@ zc|9x4E1AqI-WDanyvUTIapMxBvb1cJ*ui?(LO3?imIT>^pfl*2Opo+wITi=Fd+sE7 zMk@vdr?7w)Obi4<@M=WHAZFt8Y~j9tN4J-}$LgK`UeD!{ZU?u9!oOkve&4Iex#4}K zzHSK5gdgW$t0P(*_@Ib!1MDk9O)Rxk#AcXK`ar#VzsT#Xm;MN_3(@f8TwIswQsdWm zNDwS7&77iBQf9_PYvNSJ5iuRQ#?Ed-<5SvXU1NkGNRCkyE%f&iA3Ie4DqN8qKfs@F z7g~+-K3`w=2^ll4kIs>UJy9>Zo)@#>-I?PwG3$Igu{l${4fXn5O6TPBVxH2uEO~9; z=w7{Nct^y)CCXkBmTe8&0Z#vQ*E>=5C+OZ>sve5-kAvj!Gtz~MHPJKC;PT})J%)EC ztCxhuR@9d&mW^&Jrkj*iI};6*=F#K^=L*+QA=)q5^Sc+q3nPU8vj z;M&mCrS*&o#j7^6{Go9yUjqZ8}UeR*Y_aG9P>UvM%w!& zlnZFBL4q0KXX8BliAP*1(ft7Kf$=foya+naMtpj>m6GFWla8c$aNZ3p8NAL!PAR+! zPnUo!B6qL-w118mNO|CHsCwx3MWH-Bj?g$`hq`ESC`*qcXu?RHd;fgzNS*WBI&K@8 z_}Dv3l!erSvQU2pOt%~1Nfc;6gt)UMFq`ReD~{P_FGs8pbG>4yYLn$^n-+xWT|%a=EM!8-8;>2zt{gvWe4>)Z!?-W_$g*%Xd^J%09j>*}0O)p0?jakEmg z{Md?$RcB?;qU%srFX7gZWN0N_AtEiZ4tOf{!(?tNsYOSwfA7Uca@B!V<7)V`6>7N&7s_pVsd;Cld+4Kr?+*U631U46nmS(S6Jt6pYAQJ zbIz{g`bk%0%ouAI{k=Ek$aU_wWT-XQ8o%SiWwvNZbGI}xdI!tWfpWy>*LAdwNFuC* zQYSxwUE3wp7iuF1hm(7hw9yuA3zw1ky%}tUnuji*+(CRs`^(9wV}iBfY|W~WZgIzJ zTo$RbPm!S{K=R2P4eS@w05GMD!m=c8onqRR_0#JzWU90fUX-yErlF5eZc&PAau7cy zh?f)Q1VL^l({-~cUKIIFRJdE5ji0^H292XspURDi3@^%*m1OgxX+7e^dWgoRQPx%6 zPZmF&Ov)uv-5ac{@lCIxx@)bZsoprMdpAEtj<3>K^p?nrr_}G=Z2ehPB0CE<&5+U+ z7v_`KwWNL{zgOKIVST%P@1*WH>qqr_mECF9uj==PxJ6;S_>tpwTKc|! zohai>LR)+|S*w>2ZTfl($qsN1k&#yxz;tIWIrQEhT%(B$Lx0IQREsk{YWN2r+4l zQrJY1HXT8Oi%Vmzq6QifN|pAw7S^7o6@|5EwSotVwl7EdFd3o-ZKe=SIpCTC^>C@t zcvH}GAV!@*&mDrJ5$ZYc=zeiD(gUUuJ*Wv*?YL{Dn{I6E`x8K{&b$ zxFpdkt_aN0K(}Ze>f3-V#0)@ydB2Q5GlY!)d|>>nlSWQiD3v+o}n9E!L_qmWEkhcGm%%x74ixcr-&A2oIi^fnS;O&sYueaBI`n@Q&BOaw)Fi|GWfUPQP>cFOfK+R$>UT_aN$F5N(j6d@}Gj= zWv3PwQ3rvh1(aE6%BVBE;Zty6KGe9pi0E7LP{2SM}t>^$_Q4DBt7Hxm`it?B~ex zK<^$RPGSSK$e*%7t!lmP%Y4r5{KA{@oO9N5+<|R4%r3`O%+=+%bjTjg%R*favBRq7 z^9Y)xDcz1C34{3^8O*Ce4y%O(lR^k7hoxKo@61~jPA-t;Af8!sZ)9T=^h8o-_ z*9&?i!^ z6n!FS`#&a!;;xNGXj3bV`TZcbD*H>UY=5Fv+jidZ9dQFZN@>DpJD!2MFNk9lu*#b4 zm(a889d!K(6d0juI~W>lJaMn?Q^1&v5h&!6%j&p;6zz>8 z>XdQ>-^*Ii2woH?AyBMlh}Wg@I>HkJyVx$*>N4=PWnhfoB*2FhM>*agFt^|%wXvF= z7s<{epkWN+3T0F#v5SsmqU?0>+Q<4&+m-zdcDBC&ajqQ=wfp2u)GJTClIapf+C{}{ zry@TB`EkgPBl&Rsso?&!or$r^FIe$-F^XL~YAw6U>p+_XzFW$%O;BUR4jgY;dS2d* zO(@)__+;;t^HJT(spV-YF-={jC(XBncZ~Q`qO&;c^!;XMcvY>XK_?1iokn;lo zc?Lp8%K^}$0MHWcX)PI`;BEPY-E1XG21(Kfdp!#ksF;l*T=m;UhcjB_hZ7G+xr9_hG_ts_I_{V_QTu|qAF6( zSUt?xd!c*kqzEPr`2zUK&^2(6=N)$nuNh~JXY|Z0Go4yy7MB@ow@7fYir20+h{B9> zrFPNE>->s_u%kco$L&Ta> z#j3D+Rrt!UdAQs#{X6{nSxo=#UsEeLD6SaZ2?F3m%|IUI6}eEsJ4TGHcZjsd6cw8Xhcm$C4rlJ{dZxAqH@*K(Y52PF_+bxUgXznQ*XH*hE{WXiCfc>V9zK?ThpQjFfoY;fY6I6$~fsB z?-=U+8#YX(_aADb*G#%%Juk!&ql`CxGSiVnEdP!_bxp0#KyX%F9Hldb27JC1y&y(l z?|wpDYcpBFlUHvK;j{b!teSF_d!qH4v2P+vrzV&};MO{JNiEA#MpFor)t&;wH`N`L zbtzG(S*TH#A1KW`d8 zkF0-(x2fSHNJth&T7!Y7iRzgZJX4TQELqb5dgm!){pVf$QwTHA{V;- zUH{_DT7xMZ=H9vjBotnQCxqU3$~UXly}!vjv(`DS7RlV7wvcP7jKyf1TOY&QV3R~1 zYMI?fcSwp$XYG@}+d8FB33IZx2m0V<<4~KbPunr;P}}%*avL4yl7tZ^_fxg|q`TmU zGD(&=(0j^Hd0IW|i_KyRPA4%;O&5>vY ziC!vQYlx!^rchuIg6yPyv$!$$zQ*bUusFRcC5G=mfu_BU|3gv`nUFp7lFNxb>VXeh zxNQb$_Eo^WEYbu%;t=oNf5>}_cV6MSMP%MR%48R-vPC`Q`;)+;4}0~w0_)si3fMeHC8VG zFVH_&FDjP=kdc7JzoFzu-p_bvKhMn|8w(mW3OvO8Btun5QCg}Va5RCsuaKnXu8n3~1Zgl&x5hzd1!@V2~2DC+b7g!fC z8B)MY8jMmqyz-GjzIxtU&mXPlovV57T~ZuqVR1Pgy0Xxqz<# zF_4M@w}l|Z=hY$qF}RO){!+VUXxlPDm9fvl$uN8O8Jts zQX4=U@MV)OQDBI{a+{0X@ z$x;!`E5gJ1f!rbsw^lxj_? z)KETW3hy#K7}BXV=(VmWmnp_&iglS-mn%wZAcusB(3vLSfBctzW~$bZg|8W@E+GqX zw@lOVyJ(#Vl#nswMxa*ECM5|(pIrmN|b@8G@J*#3zy+q&dG{2-8$^_E<(srNior)pR z@s|>YsvyOBNj=m6Db`DqhFXXe>!olvSSZ1Xs0^EZ)IRdO+L$4>e=0rizxsTj!6TM( zLeyDBV?7{&&|cIWv1<2^`5z{{a3g=9;6u!{&Q0bDy{r|&{~`S!@gMij#U?hcZSMx) z=S>848N27I0kQR(#-9I1;#^R4|LS+KNw8ZVEEypMlX%oB32gmcf6b7K)$oQHsEyCy zF_cYcKZbJxtr!h&O5hFi0$F2i6OERAoOd60^oJVfCXPG588^4z{KFAAZ4xk$-~Vpn|Kc_l|Ld)%E_6hRf<0FiXjZ0{B`D!?C z1$VTDLl{stE>UF~_EmFUGk3I#>xEX(Y>s-xY`<1KDcrY-bGvf9n>goOjypu=P}~yc zoWlX1h7213Eq)#t;5s(4V7-}r(7--a@`VofXp($RaNEqBS)6tXm9YC?wQQ(%HN;qR z#03LbI2FQXVx}))5jC*ki6>tY@ksm`;;8mKziLB}R>=;Fzvzj&NS~7Rtw)e#LPHdl z<0i&G?pM7tRP%6`^pb=Um^b7c#NGMzIe?`GV2bl|%PG3(8|dgZWpM$!d^AErMv^lz z8vElX!GR=xgU>;>>=DkrKMYaQoWUIT6q#<(Ft|iN6Fw^RMEn*Iz;Hd;G>b!kj=tc2 zL=dFniAFH!l*EW#ZJy(qqEo?La_f2UZ-hGFaqg+4jONkBcWi6YaD;#>=T2D82Q$H4 z!Jx$Kl^wQvZh3aX!yyTKl|6|Op0l3jM}nt^pzSXCu6-UfJH|Wg0^2^_X7ojH z-U#k!B~p5CnhRb7&`Q*^vV(;aPBHt&6~JK4@Q?~UrtvTK|7 zh67{b6+}*Da|Bs-@7~p*Zj6e*0;O}9A_#}&NP~x&L~?KkF(Ir09Hif;*PrPB6!dzF zoi#4Q9U}y}>bwYNf~&Q-6RGwa*iP;>OSe4!hX0kvnJ8C)icf+qVFYXmp3~#Jf#D9e3_%bB_(8;tC6}aT0XYuR88D>Y(&*axL_|^X%p=U$%MZtsZZm3DzjT_(jve2EwIy~<8;ZP3G#5; ztG5VEy?m6W9#r^&?%@3*>z6|wRn-{2^_nV8 zq3yfJL^HuDt+l&S%KJCi`fl&as#P76YuTj!{i#tFpu9F^a{8odV6=H(hWPT(%4%<} z1rkw!BmgA!fEoupGw7N!wug;$vkzkAgUJLg?e%l-Y$IA%NqD^FxKLW~%3>@5T?uZM z1pp&+Ai=%>72-`a*<9#kts1s|2%Rjj zY~z>QC7}xy=>nwSK;U`$X+)6Rp}pNBzitm4iYDJSmxIzK1tI37@#mn)*7+^P`Tuaf zx9t?&{-WP{tr&La;{nzF?j3K@zvg$xB_FrZu2sny!g#LvfwgC~|7Mt|iaK|qQW4a~ zqf)=##*g73;Ccyr0vmA0)wa(P?`ViEXBc)8M)iRWWQg05_OC~UVc0*MRbZSb4@MX1M0xx|3?4d9a6k5pi44`w5_U@=;D%?P&RIwK^!`;D(Mqt0r4@^ z@g-V^DL#rDZQ`XxTJGRB5G=Zg5iEgp$$-=t?R8P40}VNlR}< z+dm`N>i}WH0=EPraKn#B7Q(`~nv8noCEcndR?vP2%8Ie4p4~FwnQ5|^R`wIsIu_n12F2~hZSnD;H zMPycpuz{LyWPJWcAzfVg zH*)z0&j@U30Zj*95W8tx20b|~r)pa!twqSxG_7E{nIqlCh)Tp4R5`P^nc*t}8odPL z6&{hon-?U$%5Clg|KY9N=1kkhy;z0&SUiF8ZA7BSYu?ri!nOEC#%IQFulJd4ggW3> zZi8JAFP&FmmlvL!BV8xy{l;(B6HvlSpDB)4zfnRVNG0 z<2IC$4*HqbnThqUU$ovVE}3Ld#pM-6*fbH)I)EkLw1%Z`O3d#D5iL_`Dp+bu!cIOTO{~wPRTJ4Rsaf+-5u`n0)&2+9z+7z&<(s+9-TsU>X&b!F7&ICLgPDp+p7X|U zgU3?JAbpSNUJ9?g`P5>~w(5-`6|n9wNc$^hJ>XX9ReuvA|25Er$9ShpI`|{`)_A8E zfiDGPT75rOs^awz8N&UQzV7dm5@!8x1y*9~2skxD0fY4H&5eJ9jjsMIis7Rthk;kk zuoTAanHAI|-`2W>nY5_6wy|`wl{XR`ncp+RuxIwt#CE~?6Jf`_DRkY5jWXUC!bDUr z4i(+XeJ=kL|adJOzUD`n}o>pZr&PL0O z+@{JhsPwy*tXi}<$EAAcYHK*yBHBapYvoT^9afj+xt!(?$hpnoxdKsH#2ai{7Y<(k`h%#a>gzE(_|>M7lNPX^1~fyaIn+crM@zr+I`4 zUfI0WCfs7U#kp1UFf4vh?vji$;W{7u>pD?guAf>H#rTeIb+?n8Vaj^0fiTR0 z*J`Etf<%^=7HIY487@3me+=Hc{i)nmvp(M}Kqa$gM*neP<=fw*>rycDj;~Ki(Ff*- z_t=>Bj`6cIL`SvoXU&TtzJ2J)(#`6(jn?vgq$N@ZmVAIH^hY+ibGMekh~v7){!}q-g_fd;fKq} z_yztHU=%rIFZ-MLt*}%Hgzpgyr(`8^6cP>#FesFZ-Mp1oQj?*7M0PQ@a;u$gtinH5 zNhNfTi`|6ZI~rIyVE_Pv6K$(<@*6%wF=f;z%$8@ix(`h8KC{*N%vP?V5^yJ9>k>0M zai}FX+;Kq7y+$}HvbBFiOz3kX_f?m4!6e@m%#b242Z~JNSy)sH>2k)At9HR-LA$_@ z0qT1|4I_G2KI7=fape;_u1l0J!oR`yM?jvG-?68;gC&-e;e4>z^1Rv|ETv9{TcDyF zEVEdHj&!SY^0q>pd&1fw)+xoExt8sobM{+Day?(e1M_Eo$4SqTBiB2WZb20Z%@#R^ ziI0QPIc9EkAKK^5-0GaQm3x%TF*SXwA%arPB{+zweQ!?ER;>^#L>oyhO(Wb`z~#Yj z{hH_>sjN8Fha<(w8S&rxi|2iX0+Z90?!OR!*>C9#ccffz|HkjwPv#bq1>7k84cgV- z7GPqa6#?rg8uY)B{4y#c;CW|SpdXSq>Vt^vLF87q>yO^Ztn%9m z0fSpKYm35jVlj+KoCc4KXqA*IA}Bju-G9t?0S&D2p5FqroSGxkzfWKg@PD!w7}ziro@RmS@j~p!(KFQ{7wKag;V>yd^EXCuE!_O`ZN`QtB)JHPNli1J??h zlztMrdwKX`HmP}2teK4|%kUh8f2aji>ai{E2+Ft_VSKboeGeOZCapO_h+3eWacdP_ z_ZVfV@Guc&$7+w1m8)dqwe+)Qhrc314l@O^x5=6kD(B470Lw8IjIF zo)4`lDyL=(A4!?n$P7t;RPSCo|JobnbZ-lta@-R#f6tV3CNd@0W6AYY=N^ot>&{a- z>$h}78rM$pm2Gjiw|LiXK{Ittki-P0iC^#$4i+Z+U|FT-AXGyNp^6sgQa+rpMp^Ub zu8J_TA&!x`3|VFad57!@P4DUqFyY~B=e=*<}*QW9`8EYFKA z)w_A+LuFPkmLnx&RaPeIHy;ZE-6gOT$ylW5Z+=QTAzrY=`UI*O9vd{UvLW4R9kvv$ z1>6Ez536yr2}mmXtN*OR&1zhx1c6snbOt!RmQ6^h-)%`*;WBBoh8bo-@=?($aS4pA z)MGUnX^k74uhpRbV5VaIlr36izIh^5ofe=5K`$N0F(vUP67Gq#tmcPfNLpV}T?X&A zV~DT5j$DA$DV5m8(a|X%LW8}h{gr7h8M)S4nK-3Wt(8fsv~WinE-|^*NHMYhGHAZ* zIOsVTP1lwCrI*25C|XAMuJ@-lR31MT>Qi8ITD`CnpNc-T(PF^M@8z6qNdP4VlU>pofv^B1lhMG@+pZ zf0!u19LoXA%D>eBtm+`}F_PX7!8R63(ExA1dYwo;hSaNA{%~cQ4&V%rl8kxe8$3S< zX(%CCaFNf6$QSOfHSj6oIG{$e0D-PN;V}|8+UQ011R2GD)Bbfr98X*uf??|3_6Lf& zBgC#a!g3qT9R6>n!+k^QjLl`ofqV(NjtaF)C9dvt z9QK@BJFcw7^YtXU?ssHiJQW_Zut>k|3FG5l4y=#@D-;5HlB^>Zs3QXZ2NV9=^?7M* zeI_}YYg-Q-T|u_mKHDW|bL30rb((<;RD|n-#n}~V9gueUSG4hAds(M!3D!B~v<)+g)n#vxyr!WJ^jxc%b7`Xc4wGlSGn=FxI68aIu&Xrx`nWi zxl&Y6CNwEzHCb>Co@C$F?4@ zrXK2^`#;^1WKw?OcZ4bPt7E{3#|}b~Y`8^%VeBMzH^)12XnlAo26HW|G76Vh*ZG6ke>5H zfho4zBq!1x9Ld z_z`$gV#jSx)Hb@D<2IvZLR5SZ{J_;W$^Fy=IYvK>EadHq-BC_%bA0rO%aj;km)!`e z6SQXL1VaR61E^>T=R?Gn7Bvr0VGZA9#}|T@gK1L#LY&jQ*#OWOEzW!WKiVgZs9Nu; zZUr5dfmMWl+B5x9$fhndTgpA>J_&ZN+1ws6qFQ?!eIZwnQc+(dhz7<R7>~=pW=(m(h~GRiyC5sJ(HxCR)C`4IgOi(#*YAfRYl*hrt5&}=E5#YeB?E? z4ybN!_>o+-8>sHdpzQhTZi!){c;1pDOFRcBM8XIVVAYinuu;M&aK7hNbW8BA9-J5v7)3{fTY!@2c<|$UE7hATB{~&Vos0LOEZ1XJCgU## zP`B5QbCEyu*YK8G6d1*$`J&31_iymngI7Q@$%B_izHs9=-+%BbMV0Ble(|gloN3IH z+_T(Dkxp2Y{PbUUh0$@dNIUtWiE9 z`4cv+$&m+9WUX$PVO||>bB=3c4wAU*dhEnb0o;~8A z$!QoM-aX*DUq{gT#eQZA-oJl({TBEUr;gAH7pmQkTD0IiRn7I5qwfr5%&eT_)tO=~ ztb1M$PhC)L5M>t^O@PjcNi=QEiw^~0Y1_Tt&tbvdE$TSN6%fc^Ts~qFWfvaP6n|tA z!t2JFAQ|t=s+ETfsPXfI(~GZzbqmW zxMpD;%gProt1esdq-ic$l(I#Uyi&Y!Nwx90ae<|SL3ngu#Q9Z=U#%*s?UtNAS}5)j zP08Odurh2wlzmNq0VrniE{$Jnj4R zbE7mQ)mODs%1rJc%O?GZveNKHF%KKwUjB2p# z-l9z&xTNZ!VQ>OxT)ibwOXpP8_UIPEtQmafo>?iber|V^ga#!`(R`_j<<-@Ol! zQ;)-4NE;@I>tCc1zsxrSIhVYN)phgzlM7)}WDpJt!p=aUjg(&Gr}A&Ygg+kT?t1^F zx-Q3G`~u@+@$;THy1I7`c*T*7??LTtqx z!v`eP2f6AV6^lfD77|55A}u7wA`ziEb<%0K01vfPU$N#{y7xh9q3GQ|C-iL^hzlH zMOB@|@A-}AtSI|TttY!2%3J51o`v^+3%u9N=r zJ5Yr+?7coh?UR4cQm_0e4iliLGNFy>aL9F6e*2goj(YN8PdiJ@`N>X z?>i%@4OQR^Ok86~t*Gh~X_F&U9`Wq?S!{?-UPR!keps4XQ+4L;mY~liRldfmZgK+# zpAFIH3o<6yfbB?XO0|$Ou=trS3t?u$WkA!f*f;ggzBSCfahodJl~f| zRtD9ApBZ<2n|ix)C)^iLyTUxsC)%f&!}Ra(kE$!6=Roq?`vBBdQ&g&;Yq24^ z@mF+j2W4lMLmRcXmJS@pYZCfuuG$nqR8;G>(mEJPAy!f{Rnmk6eKnm=bYgL~hMaj1 z(sj?!B@sj3HQ0ow>5{l1AHLO<(j{rvV#ncYZ!rzMtf8N7;ZUrm8&BkaSnyfSKxNM= zqJe=$tE(J|k*-)1rqW1qvZ}g7J&{ySVpXNMx<7DVcnQJa0$WeUbyHmslry#J^VchV zk5qLFxYfVI2YjAt|GMDpb+xeBt6N0x6rED&7r`!X;y1K@#fU*vpcCci&7$>x7;%ZR z2g61dDlSAD;t+s+&nZRCy^b$0NhrN>1U6&^W*1};hR2CUs3AJ8Y>C<+Eb!vyN%XZqJjo)FnYHYC zp$sEh9cfstLPGm?#Lr{i4MB>!@JrX~Sl8+YU8`eUtJ!5=X;&v3M5$#<*v`^}_ zPv((k-i|sYGDJR9Ts$AYiuxs|6lX~Q+^xf|CkeMCW@`2U^12lT2Z5je%6Aabi3i^v z*3%=US*6LP(a7rUhVF!9*$d0IFDu7SK?kf|CFvz%O?ca>`z`**o~U%wRH-cCd%AZD zWKrXblhR|4R@yWVLUTA_(!WB=nf?X*bp^4ShZ=1)Q(c;IXbOVX6>q4WA(ewihgU!i zPcf{2D~O7g$-7w3*UC4UBvuu-i&aa5ss1;8Z&bSXKjMA8 zvbTR2{^%&k-B@+aw*gVAP%exei*5!z9cG&6uVFS-Tw6`YP1l)`HNa5@jonfGS3p)Mi|RQNGEYCLU(u|1@I1+0FH>FJ4C1y+^%KO83s7iZkiD zEz}zYbnm;ACW+R+Cbi=_t15u>3W-Kq=6f0ow%%J> ziJ!gOhNnu*Djbh}R9XnuL4Gnro~e^kX&CRRfpcKtbB^HL`J3h=^TFMzF;uhvg6-#8 z2JllKM8UVA(KQmgr~-O30Rtq~fzvWR7AnAW%ehjbfE&L(NctIK!2QxZ!;{)?!WSP+ z;ndd+jKo?h0KjnSC&46lgq(WQF~(GPM3_^_$mrVk!FrCI4goUVhd6_O9B%qp7$*(4 z&no&B86)AOOb_mbK#?rLYI4K!zM!SuBeBJ#CjnH_`qzZ6+^=*=+m{bFy%lH#3Qa2a zHKCE-w*!szOrRS3S6EHp!fKM*27J#}xSd~n z|5%~t?g{eSvHR5O)fZFLfGRGAR$mNL?WDSx_EUHDPhcH1(^Lj%D0h4vIE++sT+OVd zHd?=&YFztMUPa<~wm4~;ge(IchED#%!!gJrVunjZmKYO8lO!YK$sHlrc7ZVK?GyW+O;KE0+LX)`ELo^3=PV@b0SwLvVxQ+`cMU%dg{tW^J|&l@)R!Yc%HuZ{=I%AqQl;AJxx z%PLZT-qa#ld}C9Kn12!xXl##DHsMC5uNjB4XQo4URjAE@<>Sf!C^|ko z3ed)3?NmL_$9}g7qG*-&c~&*G-y|qc#D74g{0(A`dmCaXEP|85dNWFW>| z7koiH6tOP2|J9+m{%1?lRxGTA8>$s6#4BoduQ;*03xf5!vSG+|n@(?vL3k3%0WB&) zIv%Jm$Pc#w;Uav2%bVPe{oc!)oR>Foo-(W#e7k&&v;*ERH$lG`*0}IT363A)eWP~# z)jQDYL(sMAE_r*apx#A>Ep%&(t z8!|RWHkWKgVywDT4Q3K)`A>lkA;p1930E$;p{`hA{`G+zf{!878t%#+&*p})x#4WC zlFcP+Fd7&P=LpPKSP!cPU;~iSSc#qg!(C!o*!VIV5?O4L6lo;-yZ*s)F;T%1WYbWB zUWQeu_b%JyG;HFM$to;*hcrU&{vDW}n;iF4$>N>}@sE;=V&Y%hJ2bH*l4O2(6@B<@|{0tTAY4ZBD616ESm9}&kIq{ej2 zK<|p7yXT`Hsw_C388ajQjKZFVJ&h5 z-dhY>GJ0b+Imd6}z9B6Mx(H66jmLa{mv|OsUr&FH@m)rN zA@ATuDU>&MJ+UeqI#vN6M9~Z7Df4!NY*ihIUR2=8-hnVv<*Lh*d>1ylU6l9Jjd1#e z_WmGWCs(~S(RUuH^SvK#ln&rf@v&0eKT9T&yOyP`f=>aLV_r*YCIRzBf4~j2r>f>j zhZK$P`~HglL%e4;O5a93ZM39=JF9RABXEINC%DZz@9bFFd8#9-CH3~=h8#4(T_KBN z&FPW{fJ+S1y}t8h+@ZtktvUA8p~Z*(lG{aiRYmjfV(ASI3wiJak#ytgfQ$F$ds=0I z>hW)|@WwB{#_D2Ej2}k&IybuaCwg5Q^$rY&8erK|@*m;Fp=0G|pLNkKgyf4qcT@k%zBWw#W$%j{^}GFjO^2EDE4#T9U1T&X8=Cr7Hvff&@8HId&6*(NQmI)b zE`#!jQLGh&>_$zn4#IbqZ3S;Qe^;(YYhp9j>kRo?13}1D$7E!HPsmtSW4tEy)narJ z-fFU&(n>#^Ad+4CgPajBTUpSAM1&^WDTM~DYofTb-6b%>GH8+U82a9E6AV)*o9W0&kjpT*haFB8-O|jyuqP>GoQtn z%Y5&mjm}vcxp8DLI#$!4i*2ZrP|%~9kL)MB`5X1nS%YwJO&Wq>kb7uQK9v4?h%Xn} zzw_p7tow(*{|%oGzkctXvymwA8pMi}I?tsS!!2bb6b%gC<}PXpYdwzFU_qxK2`rj* z_YVq$JBYr0R@M;-#{U3x2QGR(`w-z_x+k=rY=8D{1ylm_DC%b#+^{cyQ2Bgro5b>@~wGE=B7DQlDyC7QX3_?mn z_~}@zNqf=l&JT%Q+~w51*m$0J_Q(q9h+L88;ieEUkM%Jq3mol`&XGfaAx4W&9K-nW zBR>1CAyT|Nt#GDR5M2C%MWw0XlCgt8TJD}XuqlNzu`RB-!iLNxkBK1R;6g|zIQ}V} zmOu{>A(3j5(e$j&3~?YMQ&uI;kQvi12Tm&r_3raOQVstfOrzdILLE=ITW2FW(qJnt zq!EXgK;plbyALS6e=m3bM>*I04EpN-$aev05#G;;EiUd=O04*jAsoANN&>)86m$2& zTEuSCIxGZDd@>IG1VAJ<94?ENc8B`TqJEb5OgRy~Q3F$0n2xExAfUfX9RCbr-Q7*h zQmZ3j<@7cR>b(C^4i#xOT8soQ5+3)SEGJP;rf7^>scSWS5wcItBfU&vfyb_9WvfD` zi7oLR+V#$$-3ag!`c%LS0@jC?}swGej?TeoM@<0 z*ZMPN{#pjk)eC#NXo_+0o^_@cXA(CNI*GW6(VS&;zw?Ft&J7?*c$?yYLQI2d)hO(n zPVTtymIdCqt>x~6tGrvwolDBO>0~?xHUUlpRCDEvW)UYakklEk%LeO+Gd-juK#hsj zl!^={%}V(*24&oeC2D(`K>(}JD{=)B(F{>`?1YXZk*WfZbwR(OGYBc@IezwSQ-t^r zinUArS-j6J5{3`iT7+X}?ehID)4%K#>rBuA6oxyv6~5tA-`&Ir>Tr0lmUD=o$;BAF z*So0PsVV11)(MN5z+&)klW1%0oBhTtQKFb#g*1C|Tp|6#>xJ|(aRH*h_3PLt$lmK5 zepd8Mo}fu5IR zB=97U;$QJ4{(+t-;>oLvhW8^Z0p`hCtU?x z25XgBIt)Qfyk%)u%Af>E<~$D$e)`vrdIln9%XVV6tbd4@Ew_Z(l@%=^cDABLieR%^ zM^&xr8xcJC2-e36V9?;=Hi-eBer>m07e|?sp@50ML1U)NRoeTO%hvVK`m3Csx&D9F zk0WEFZfjLyqQjZy>D-^O{?M^J3_5>(9^^K?L@&>n_LG)AYy9x4&PnME#ai8asD)4O z|ALJqBimI?EQsp{{tpY{i-NA>S(HR0{k2RUzUhC2LTjbSSnn4eavKh9uw+4j3(it@ zk&n@=9L z0N3dezwx_?(79qGg$nWi7;xdh74wv_~s4vOy`eRRVSs2^V*vM+X@j&hYs zY_=Ka8o)54Y{LDsu~EiSQPV*)_-s8Ik+TjNu0`$F_AiIJ zSGr7-n1vmxq1k=Wp7%W-&vl4mJ)p`36*^nA*mIgBGQmB|#kZqvzYVkfmXKdIp#RV_ zfoGo6k*zN^Pafw}ZEzoq@v1f;69xm>U#Y>;VV=58`YC!(F|^Y4TY-2JYG0$Lfph}_ z2d`Yu#*xAg^rC~YBOobCWh9W zu_@yafYK(s5ZJE}VebDI+z9Q(e>BuLd!NF^gkp^b80LdcwOb`_Su89I_b#CVi3Y|4 z41+^(c6ay66D_T;*w_cbt~i%O!7?9v8qC`d!^%a?TJ^K z!K*b;Em9of{uYxdVGhA~>(VH~tB_{?& zPYWl;Gt{@z@ruX3_}p5`9^4UZ?7ZC(d{|l<3}B}^*Z2Rh^hJLevavC{Iz2X(xV6)| z{t)boBK-fno?J0mN2uZ?d`I{CM|@k%?)G$VwOQ{R>5{g4?h@ay0u2qO0eKFp%_1N3^3@UYbpD{aA%$%H5LSyk8g$HpS zfz~8E$5`1Sv$x26wAk#7H*>>Jp)B5;kk0m3v2MhQEq-KV4oqhKZE=W;LI3i&3|=L^ zeF;Zo^gTA3y+-p<$9iXknfso!V_-F164mPn=mB^A@8w0vVDctFPP2p30yFq8x`}GC zE)~mVx(Q+?B6~wEGx^Bzl>Av;bdOkK=?~Y6#VP%2t(fRHd(zZBVwt5s2r2Q`AtS~3 zR8!<7k*bMutyDnjqy(vRe!LzWyqIV%n6wSG_W+6I(hDF@Pe7gl1Cfxkp_K^w(-P7? zss^-SQUcmAe;(4Z4^Hj`L47Wc+z{YKs9N;X2%cJqrA`sYq=SDSTaS(jOpLoXQagcA zL@5_Npoa$kdOS_?K@(I>eaWjy^AAb~0w}C9+;kA!g!g+ZvpiT#%I%-CuY( z7`;4jwL9vF+jDL&)j;@Mz$|tK+vSa=-IGY_WPgj|Fv0L(S&e<**&s9&|ACCVy&e)E zt9(a;qtA2n=K6Du)LFXoFnnb_aP=(RCGUmj7?kHGJ)O`U?)%4jxAPJ2Kh`_HUC-5! zp~Uyg0F9ujm)tpcee|qwm)G0nKTK-+tjr$VzpP2I-X7eR35u=9K^^^Ky~}YY5L-nE z{X*J~fBhc!ei_2I6mow2YrM=bD0K9b^+jY5Sc|5Q);EwD_6BTKV+YnV5m-%_K|ql8 zJbU!?dKi=z*M2{WYdhas&jfcX`oVt{szG~yUx-TXKPB&(O7l~xgtmY5OckZKeQW%7 zxIw|3LCfuX{x@&$9v4-e|BoNeoVhR@bY{R20c&PpxQUw#D5$gxBUdk*j5(lYF@rN) zk^+{}`sD7+Az@JZtd1Js>V9U%SdqkZDn-p*p+Yj;72Ew}ZSImqnq`?HsHx}se4o+k zv!BoJ_xb+y?Ll}rm-prMzP+x`*G*V^&=$Bjj{H%Y;;&sP?-A|Y=!$aakH4&<*^>z& zoA=cwiV~(3%;hS{k#5^^Q|-Ic%|QQ7g4OTUo$^X8a)EOIUA;)zjz|*#A&{Vg!FGmj z$q(~?SFPXE)Vr(JyQ|hYjSvyA^!}1z?_*a(34EWLd4-VY}J!1{=O(c0x}aJrS84Gk%5q->gWJ)&MUH0?934{$;2J z8!~i*^N`6}-N0n@v~KyVO_ec_-u_9OF5_%^``_9O85h&r{|rPGSS@6knw;Y-ofXrd z$*Pwi-aT?~_9A)zSA0Sbta+OG4U#VjJT`D2!W+Lpd&&IRNEkta4_8zB-|^wR0^eAL zKK`Y*s@7|(bzZIt^t&AQPWRdZ{Whw^V=qd;k;mPddd2c|4J)pbWEH65%0qf2od=z@ zWNogLvr;SU5^!u|1jn|iM3+%5_c64QA&y5L_*q7fd(NWTozm>bYi`I~Z#37sRy8|a z^=Fubi;p&McD-n1V)s}I4=kG4?EN~;+@#q2XidRv^E=9d!(c1Jvbv75jHj?63v$89 z2^eh2$Gk6ms>{*@Jw*&9u;NU+_M@UNvu_d|mF+y=rafD9G5baeFhtn`ACu9vL9Z?k z?qkB$+a#`9yKI$D8a}wZN7@;-J1S(brIYCi1BR5RzQGs%K>7AeKa{EAb9XWY ze{DQPc8wl}jkK>0A3WL<4s_kv!MOuz$AJY}zoikey6pbF4cLjHuUf}63N|70{IGRQ z%btS27Jig1slEAO-73oOxt~`>dP{wh9ty&Wuj##A)4!Rg4s5IG7QHa)wh%$PFR1nKmsbx9T!1fa(w7otzT?d9)#3r7rvIvIL8Ch^is#$an&4-``ByXwD7VeB)_j zVu(99%U<~iG@j&?+Ilj3q{bLasl#ut37;7t_V(!kO4|ncy^+3H)sB;=Xup>OUZ&;N z4*4nh)mYVK$uVZ=!qdLku;GamsPHZC25M)H0;rvNmw5A}zi0pBX)BXuhz+sZAA-`v z`Wk`GW7RXvTcBQ6Px{Coj`S%Tk2;RVblka_k+x$A3z5*~6E&`c9t;kgK-&ZE=~bSc zi+Rb>{l%mUho;gJAHN&fPJuwSkK{HY*iOI#On-_)7`_T?xc@L#ND~pdP0!-lvskly-a-u1>E@Ena>o0sj=#zyLhlg}( zt?Y&fo)wJ-YP?m`8POKjx_wG#LR(Dhc2#FaTWag}5T8up7Ae5o_3J71Z&-DCr~oR7 zoq>wqM)%L5O8!Q$;i%13HMO5r8mCa+yH&jnPwx(2Oq>Wu2@(;aF@?||P%3~kb&q86 z)LIdsrotev#Qyq=QpNH6~2y^uD1AG!qyK_tDRe}WX)c$Q};H8$X^bRy`I zozg9P&QiLk;g}5GmzA|vt)%pD!~P?hZdulz2Jn%9%ZIiGc@;HCc6%cd8#_VCoucF< z;Ru43R8qk8C40V|>QhbKk@><}IR3iBnAV=DoM6k409%1b%{Z>~XL%0{1)X<@jRvb1 z03+|+tQPIq4s{=kWQwzF=WbTZ)yr>l_pprh@>`r*Jmyjkh1B?WMfJ*Syg@b2=1Odt zKGjsH&7A{+G9h2E!{rBodfh|-bM}$jY=|#kFfHbb{P_}pK2c$t=!|q*5)gSi83J5B z9p^y3>9wG)rEKKlBMti(*SEZDl7zDJJ#ak}cqy1mNP+tT^)SSql~1Y=Kz+q1PCBB4 z@Dv?&*3vEM6JEC63LcE~K2_z*mk6&5^)lfu#%_BQh7w>Oce#E7ecZ#Gp>v}jJjHZN zAY>)fCIZ2JIz)rE{TWIRe4yt%i-hwouRw~pIdL!G4 zqrM+b@~D(xKX+`r3GBMtT>+aSndunB$}lpB1WjAOe%3D$k;smFV?eO46MS^ejxG|p z-gI-v{LAtmX>yU52+pJ}UjmaauHsJw6I%a!TJiTPBFIAmQRS1(fPG z(h~L6o15S%CQ7scfoxmi`ow1f<>52QSA5Fy>KPe|&C9A=!xSmYs-eR(>o6IKw8n#>QRgrBGfTvFYJbeZyQ?$E(z?}y| z280+l!J^S1fAS$wO39Hwm-APWm6QwqJQlfaz*OWk12%{wYis@XP*R z;B-NQ{$Ihi|Nn5hqWmx1NQ&W%WF)$U=u^);o#!`f@F57L$HUdh)FJ;w%$ua60lQkq zhMQBbM7@9Hb@u}D$#KEhMlhIgep+<~qlYru6-K)<+x8U4h>BJ{h3r?ZnVen4F^sx| z<@5|^591hF%UMn@bE|4vdk_~BXEq+$~ZwUJg`R#=eO+WW*E?$Q#gSE!`mZ^ZbaFmauzJL z&pL_m<>FKhXErdmbaATFoKk}bkA`f?5D)u-+8=Dt8PrP%y6>;J7*(81tnQR?Winug z#K|T!rw*358t`#*sw=g52^SL{Ckt<$H`s%l4cVvLl#b@(>IIn#)}C+EM|F(~^LK zQaO=SJ-~1=ie@brqijwYJlm#qUBi;vJhvRCjOG*svA>FTI)jOM%Kvue`$HRhv75eg z1I+I~B!-wtEvelkofRPaJ!@g%!}=3tQf)CWS7Jlu8^7eCjQvy7VX<>gW!@LOv!Oyz zW?)@Rb8{X?D>MkB)x?f;t=cUPy_U}XpIVACQ~Imn_6J+pyVZX0 z(K~bd$6x`(U+>q0A<6%Asmg47Ec% zbg-HP;JjJw?W}fcNkJWN@_R%&=&&w{lIevDIeCi4rO`${d5i|UG>Rmprt=Fkp-UF& zU*=DV59~%=&e=q>2RkZ5l4=Lycm)Cl>Rm^(5>_?C+JH!d!CA-*-;x)w{ey#q@CS>r ze)dg*R`>i}E7$<<)8!e;A$N7JyZV5;+RIftZ`o12Jxy#CiS4r{aUzN3rE0T_ayAM) zrJbsPF1F8G1FMu(7X)4fbvp-1ci0FnkKzRPHBNeo%Oi57KpI=sxW`q`!BNctFEucT z&v1DX?wy;2Ne~w3!31So&IEhfLk5x9@b+y;c4ILyKsGSs5o@eLDmDm=CQuFxc|?FW zNTr56VrejVKA*FO>yKv3o^1$rO93eb__!#S!BbZE8fVD++K~5c=90R+%a5fS@~*I9 zhP?0C)VjQHjCofLf)gW($b;)Y881_8x>_&p7CT=geOUw^o8dg`u!?tMp8pc_>L0y} zs=afnoqj?etdHG2>`(#j5BKI*OW+K4PJT?p4uUBe!r|xl{AR;;%>JgW$nm$~-9DCz zKT3~$z;EBuS4hS+%7tHmn+uE?IMwA#*maqoz^{SnI0cl{-#~{va+(Lz9TC;V<&sZe zwqZfRQ8#_5b*AK=eRsLr9sGIR#Sgj~qLxN=xeKn~Mf?zE5c`f%XYhMO06qvNy!lr{ zY$jo+I?ll+r%qB;L>fF-=FDQJXYTMRk)v7P&-eMVj){ClWYfftt(RvPWhVdR&dA&F zw+KA%B&)Jx;rJnEHhsLsAsygt=v(37b|AtgdfZS?2CdTI@ zeSB2s2Bo9Cb18)%{CVBP+KsN$+kn)7gC9rHngAlk!{@%u4rWZbZOsxIK>fTeU zJ84@E;iSL|@i(9_HhK7BLHR7W6SCVlMv^kEvT3Gbe}>YLdVDxlIVa%@5Uk@2YAu{v-UgC;zWke|NbO%G=)6t4G+t5OiF)VH62N zAYcm4BNigu*eog^TQ!A^pu)2#mv=u-w)W#Nx@~H6AU`WXCG%d(Hdk(F&uaH=+LrBJ zLMp}&@q^;Q1`E78@q+><4<1t(7tC>145vzF8JUpIU)~#+XhCpz4df|?D|IrpR+#MR z_eVx#Yenw7pN>q2npy`49A8C4Itx1^U z#R5$`w(?OO%a@Qjo{ME4DDRXc5Du@e1P!%6Ta8&P`EEyLZ!~6c#|>f;`rrmQ8iR)q zIExEY7&n{`tsb+6Kz5^4gn&3>b>3@9E^Tn7#^qyafV06#`##Oc-r}XS$|oySx;R5& zc4CqGYKV?z)b5ZS+jQb^wJ~TYdNt}i5WU(fT1}|;Z#K;8jBH()IQjMXRH7X%$W911 z&{SLu-3TWSQJv({jK%e1HhRrWtB)28D70Weq3;_|XkuK00Yx7&UQ(1Gj^DnJ{e%ti ze(_}T>rNxtI$hbwOd9|COmKzRf8a@7r)6}Lac6qM_D2DtyVQcdb{O*`?D#LO}8{vHUz)0Qm0GMfI2kNlIxQA-YW z#QWqy$*%&SGcTKppF7uXp!-v(G2>MAd6iv7_iLyZuCpWq6xAtJC(Y`N^vMZSpWR9$ zpIUTBvHPF)q<^0-XV>>fP?<|fSinpwer9qei4bT^q%w1h-N#C5p{Jl1Pul`H!c32a zEXUCir`kyQR(A_Mk6Qu3CaX4*kU&7gJo? zwxAnI=y4^_@&`>h8c(?S)+cPFuYhbJy1v^Oq0R&CK{u7;gHOkX-&FP*pFDZ=hH_8H zg4eJ<+k(bHw{kve=^bKn%OlDlyYV5PHpFcqMU0#qb89J#N2D|L$>j;~74``dl6J$c^W6zRlb zL*E@RO$Sp$LUe4{ON^$WL0xbPi=KTSV8n7_mFkupc(LMK$f*z;b3><_)MDtCz}D3* z8F`h@OG3$1oSv2>@U9}0OboRj;Gc9ft-d;dLOSD(rhA)8$EmSB?rw?Em{HhQ=r8mc zjcI7B36j}TC6wYd&uC1L%$6zT2;9#FZw!i?w@((t?vv_HC@87GuN2;6#QkD;#K$n2L_zna_PQYWnC*Qbr z1~3F~P2qyYV-->rSsd8#bA@;Trd@HyMgFFCOpUU6aSUx=t%q*o?|2yyxB1(^MxPIHl$r+ zL(UUkV5q$+a2LG5$FG7H=)=?E=6#JW%01F*L|lh8-KMPU?))oBWoD5GFYAXj^#mdxabse)aFDFv?=W*59&SY#BX zv9J*}Z)x7u{Ce}-+`KeyUPkjZu1vv|DY>$6t}KizQ#Cg<|EjsHd5Q79tnYk+kY3#- zdvb^c4*;W5BGM(n4Zk9iFz;q|5uBTpqCU^85v9P-5f-+SXiPh{kAaU6gP)ru5RE*z z&(LNe!N(~OjoibJ?V>=mjlD%lRiLGwvb7@cdBk+%z_#*kT3EaT<3@<>X%O2PDDN>P zRHR)x5d*Yyx+9#|&HLf_2l`M^VRm5(3U2JfM8diNbE-ZsHqc*5%St%kFN~@hP%b}1 zVg#G3ge|X(d2GYTmhp$>>LWn^G4y##Ams%DP@GH1l(ngNPgcG8ueTxV2{j@6d;G;{ zBy=ZTaDGcfL}I2kiWv3i_Z=ZT0y>G4#2K+V5?nL;s`Cr-3dnbgms}Sfm5~zFFWx3x z^k;nICq!SO?Wjl)(%sZyVAFXBfWX`=Y1%upU`IJ8zh2`vyU`M zSXIDQ1dJwD)yMLGT~)TxyZ@Dw@A&razpN_#)w^U(tr&Wz^4^--82j-qB#yud;V@CA0$1+=aL^ z;|3&SjA6jnCZF)y>^2}orF?74hq#lb%nFD*X#sJEEUDD&7wlO9aVLQEvnHbnZ;h4F z{T_ZsO7`q>Ld)OtCB^EQ7eaCii{mCClA3?vVCg(XNDeE>vNe=u)epX6czX=Fo3oHn z>+R1mg7^q}5JNm;jF$$Ale{DpSBxil8;DL<`?CsoQP6`1K~chC6CMB$cra0c+;Bpc z`UE2Dk-!D}lxu#Om}PwLj|Qyw2I2W&SKs@$j>9P9saJoDsf4#Xe!(|_2g2DAl?d3U zZhCB$47;8nx=|y?c*qEdEQ_5q@)zE;N|+_Y(ZN1f5qLTFs6Ld>6Kv>l3uwtd`SuDF zDmf?U!!aceLpv^<1=w^C3r;NP#}$LJXhmhxywf?#`MCwmTRH3>I>YN?DRX4dkh#+D z>FPCCdd-#2KUgulI@C7;hMkesQ^ib0t(6YkUV!ci%Hgmc6~ zv9GeMcV6X7?9PytA?HHgL-d2+B04V*x3|;kKg#z0dWUK)T@hK{8lrwfUYA7Yx6+LX zz-J7$Kd|beTz!|hp&d^b9g{t$h0t*_!r_X!krKk+OfkRq{p8P<#|eHX(z2qsZFyH_ zDwn5P5-LeUW@U)fWs;%9O22nqZ$hOvt`aSBK12FYp)5~-{haJM!afnB(~0zsQ__{P z#tS@>hk~B=oyjXh?7vHV;RalEs1`#4Ji>#vFFn0fiS3crEhRobF9jFs?`bZmm7$1$ z_=?{tzOqbd39j5eQ>Y&XWA)_QLm_Cuwq98!tUA~aW@`&m&L|^4F$_s6{jWUTE3WkN zWQd%PkcL6A75zSY=_ArGTgZ)vF{9#R$L!FN=w_>4B_ zRH$=@a7W|=oTwzomqQd&J_%iyLljeW5>Z93FGo?ALt0fQ!IPl69O58fCqZoD6kK%E z)5TVas4gecniGY;S@l_^H7AH|wC2!k-kBV-C4Bnlin9oFG38LE9FaALoXhy>ct8yF zk2kAbq^BS((!F#?AslG;{luXPK15S22`-3h#PhsQ+pK{W~SMlMHYH zByr4=8no^jjX*l}o7Znx{GQK`_}Q2R=VvQ%QcmoqD+R&e6P|!39-}`hLVeChiEeM5 z{A>~OwfH<&dL;Y16aZH`6uAe^EyqHk&4ecB7&XcciAN0BV=v9 z|LQ4G*S;Q0;zKuu!lKFe-zchkg3RnX&*#tA^-NTMf1T~h2$?-GBT9H_Wcv6isMfma zPd8f5XeA>wMsDP9<2Q=(U>y;7yFj}mzB5-WI8P4w-lY}I%Gsptw$ntHB5adn-yF8H z4S`b;hpx0@N_>UdtqW2I2c^qGDOb#YuBH5a(C#7PG=Xj;`agV=T0x|2?=)ESc6`aH zg5f&~o{BS(7B{7e?NcTnED0B4`bPYGRF1AM!oKy4P$OFqH=D5+hO!Bq@!rOS08{&v zk2-Y={2ilwKY>#qyy=xy$^%m>vh0r2c4g_44!0zHEKxb6ukic$-q;H7qzb2b5ii0h_!%?n$T_JEj|zSakQ;dbc}X>7|_>V zF-J}+5yAb(v0hQ-LXsZg1Tmisdr7_+CgOsyW5Mu{6hW#?A!Y0a7l+0`rc8NxvdrZ9 z^_mXl(0AqjT|>R!m3xQFoil`9l`D%rE`R-3v(T6Q{lP;%!7e z@HPMGIDJledZxo53O^W=dFB+`=lMKkxcuY4o$Mo8s!th9-F+j;$S{LiVP7Y6hPW@D z6TEj{5n_VC8+oP^1P3b*P2at)g;hnKb#r$ z{~Tw#MnvPDIY>s$)CfaVwG{ScIjb&=?1XM6WH#ASU=5D4chd=Svz4DMADaa>2zQZK zIZ+;%8(rg2dv)o9#?hPpPmp+|W6yXX2_Y5{oMk9@jrx5KpJ&1da|7{C=BgXSi&B^$ zL>6lU-G0{lhjOpG+|pq4*7iwTchsOgHL+j0|OeF&6wg=Naxim^EL~gpFR})DR*K9x9Dk$v9*lD zAI6sy1P?z1mODQu10@(F8pe0Xhvt;~JqLT|lzZotJ8OkUG`@Lz98@sNZ=)L5_;f^g zbkl299lstoKR^D$b3~ylNiI-vLQowina&A;t(@d%oN!ull7~3qw1lG+CqPqil1ZF! zVsa9-RWg~&QCWrXe5;gz8*)>{^rH)ZYMYc5`i<`%R-OX_M zv^7V@N~}3@Yfeaj{3CBl*#|F6&LHGIM-HE(Qxc!>sGB~p#BLDuI~}Je$$m0x3Ds=% z$38&%r#KH?}6enlo!-zI!_j@aQuiL%f z*`0}mLIo-|;}{b?m=L+qXD|lgcs5c7BV#a%4MvH!?7AzAMfPgI|2es`<7_ZVJ;Xv=7gnDR$ z@t$~zv6PGY=l3T@#Tu$xe{(3(lN0cyTyiF(8ZWb8DH6I$fXUr_ZmC0UCKUmS;S8D z<&w6Zk`nslicG!H&^{GSU~>w!%almcR7BP}>GeM7vTUVf-v3xfE}?L(+m7FG7Q}ft zmO9;lJX0pJ>7{J4_aU{%!XTe#mCh4%;3e{!e!`uAVHek%FcX}GdaRmV*j?}9iZIbiRVfp?v2?3>rv+hxwD?VF#) zzjz|Z6A#lYtJ9?}V*AQc2Tj6V*x+LxE}>i2o?;gGyG5uSE@VDWh;7fvYdb63DQgO&0c+cw#LXxB zr?bf39_f;0h|FnpQ&{-WVoc$%-bd`-0zwVv8ZxAa`Ld?o3o~rm!VVSUohiL}cH+{N zz$D7|5JnZe0qV_u7n?p`96-Cv0FQUC`nVjsAJ5x$767~89ZpO|Pic*ah%QTS`-?#y zY!7?S;GGcm|HBM6pICvV)1>HV(~qc;x;B*WiMdz+w;CI0E*w>D)tp)E@2%E zF{$d$#vuc38SfVP#pIUlQ=*6S_p;!p?}0%F3$3WSju&kIUeU z?2l~dW`rzRoV|Ee0W%m&0(Us(t72JXOC5NJjJELBwuz{aA-<}exiV9TNPUnGXJ;W5T`=C-!RW)xKacuM4F^v^a9 z?E?Miy40c#CAJ>u@(Q%b;xrCX81z@|*56*$CI}SS(DGNM(iKqSJ~4qpcDl$8UM(l=@)0TE1hGdyIF2#Q&-fGWm1i7|p2ddb zAM_i=N>+x56RTKJngcvf6=hdu<>4aCVGqi(YqI}TR`~{(lhyor^Ix0a@#kb>*nDCV zZ0Q!Wn-F&>o#xBls*iU z)31uZ2#Z#8;^1;vH}iljg=hUxpB$LJ3j2-oTQb<#@0=G`wY^dCXw#IqYEkE-JGzk6 z+gpZ5=B{ts9z_Lk`f|fH7-byc2cMN3=FR3iGs-laSOS<0w-~tTP^)Xq17BNL35Ub% z@MW>sLmiGZsM@(l$$^9)+mi8@G}QN)KwBzb0+@qzmTUk~bEolI^EBER+yISk)GZ>8 zzeD`jb2uj1>iG@n`X6~qLRp1Gt^PJ$J>D(p_zQN%yNv|ZhBEKE(s+=6e!W#jctE#| z-egCLsa05gAY#9tM+UGyKF)?HX=Upqy8k0SFm*cKybVbQh-HbfI-!G!k0!o>PUigz zhJUo?;afztCGU|oCWT$k~ruua>JgM4i5n$q$POw@eI%RU) zl<=XAtNgqEqj%#f@5WUq)wy>i8L6#P;p&&%9DkT@bW<;!oa;se@21jGUw=4MzI%$G z_a`h#$KcpydCPL0N65$S*G@V`cTWB?n-n8`9K~GBF85E+^dCPqp>uLlm-88NkCm5h z&Ss+qCVM{C>~CN4Y;y>76i43jM^RB-N6tkWg2~W(K?$W}6q;0x4ve@?Im3X9FkomobU|?b7OcF2Z@x|% z8gC_@B-(It$lAsX+Hf6`&s&2GlbLkC0ZjE0XZo@(M8D<`yBYs?p1lKV?gN+sz zc?t(yUOgUR|EsxDPaNA%F|OXlr|V0H>+6)!E%hy_;5!C`7xW?|cl9<4Y>tpW^xhu(zrFkC`vs#t98K*EdO!PE5c|l&T&u^j zaB?qWJ=y7l6y2pzZ&zi?+3wwKN{$Zlz4lK}r{b}e6Ol1dI`*YgG%Nq~mSw}wbTlFcGipz8RPus$l!6h2HL0b7eK8A>18(X5#N!&BHVR->3%@W-R&$a# z)v}@gDD!)6_Wr)i`};EITaRH@#u?0Z;{~e+D*xTHa$O-!v$9H}if7F&n3g|l7Q`?Z zw->uKI4833yGxTNrm}zaINnX0V)F0>A^9_vkj1jPG&rr*OQ?>IM}1{vYXxDmUtdYy z`wnH}y;)z9Vn4^rq{JK{D2*m;7x9@kh1C>VjPHJJdiPpZ?yjtPqia=#*+waqm6bO9 zs50(RI?qf&HDL9G<m66Nr<*xlp)4&OE!08- zV0`Cmgf&zaElb%`JGg2(VcgNMk|GFtfG#^G&a5(72;KCpW03RaGrmYMLfTumi`pbR zf`^LBNUCphnb%zAtR=Ma#|3rM&`&FEr^lifxKg@0$u5@?SUkTTYuVl{(Kn6h;JP)! zcdDUQ=tDNSKMP-m)%f4P?9w_s@06$yy&^(t$F&FMK89E-l;HdwX+Eb7^5qH|dO?iy z4UjFAbZ)Eg)PwW~L^1@zB9|-Yazh{;;;9hZq(3Bq-&`(n;=mj3n4b+;d_o2SffE}J zhN#%FZma}kKMr!Zv?bZgD?p-3Ej|D`Di#~TgT^?3E}0uMs|qc%iDcceehf^mR^rx5 z)p9w|)_k7y^f}6*@G`%5Q*T(AH>}J#jr1-fyj$j;7Zh+`#)q~eqws&tWPS4(ZXR)h zC1{QF$o|$DzOk!E#nPPMAcq^yMpD3K={ZT}t9{{2)+<0ChG~d&jTGdQWWE-_4V)Jc zi_uTvVK-yYDgtT@{g+fX)A97!y|rxFY_Y~sW_8feWvkyir}t~C_e-lYh*VSCf`F`J zQrlc=N77|^WzZcdG_J@H9N^Ng5MI=k4zc0Afo!xEu>Ta zk1?c9+Peqh-l{RQc-2@VLvaIyc|2G^_n!|O(;`^jgkw292*K-IEOrqmiJ{7T)hGD% zbTc56yMT5V5E?aG+Q~?b{1$XNCp{%`SzwkgAg2l@LR;HzO$6JN^@t(ytur zKOvm=+0+>!tbNA*dT@!huLHceGuv{;!vya2C5Vo{bG+lyeH$Pw>8z}2Nlx@cXS$`c zr)OZ`?AeRwWtp63>jrM8OxL&2Afv`bQ!?oE?co`!^xsX)(53H?XBg6V!V0gr5H%O3rMWr+5DymYg`}lH^HiOQZrzj4e zVlGo>sLWw%gN`=8J}Kp)6-J$iq&C22LMs4V#V)mawnj^Vk7$s61)k2n#86dW7+AQI z@iEjI`P2dUr0+(K1{Fe}cT616b;j)8A?wqLd@-Wk(G`ZbBcgIzw|wA|^&{`H>>CKH z8clut78$xBwbJqD^MJWna+j4!CQ>LL2x9SNasxUP$gq%rrxkaRG6hP6^r%T0v^f>2 z=7P*0+|JOM8*b}#BD3zc)?4bL3DHcluS%CH>`NaRKC3)^_PEKjb^f`<0}l7V!doS0 zETTG=N|#Ps8@%Rsacd*bPWiC)!Mb3@C#}OTC@-cw|7&=!wSK=g>1^VMtM-9G-@cUmO{600qp#Fej&2^rwDbJNg z2fGk#rhNfzQdeBPKVFhH;L4k?dRn7J#(f3-z>q{+2{Gq9Pl(yg_!+7-MBgJiv`sUh z>IplvW6FT8C+5%&)qtTV_0W!xK3d@yDGu$Rfru;+HGTX0ASwZsz#Qom89l>L1}AFS z^KtLQv%2ilPvFm@zdS)kczFnWz94LHv>;~ijiQ6g3sSM)vHC21LxGkJfk@l;&ce$f zi(p&66Oxz`Eh*6+(Yxub<;`?sI=F@5>1+w>uqoJ!as3J2BTuji9-G2@_=(->NPtgy zIuv!D+pKF%BWOnnMbXR zS))f2WUW6Bz0i&`7~1Zg6J83PJ~8TO-(W=C+@?kH%faVlcj(4r!oFXi^1-lxoT;#m z0!o*maYiHD)yDuUJP3CT7Q!EnJT~fCJu}W8N@U6ioO1y=6iHo@*A%A{TPj#YAHx8B z#Cd`6@RI9%9d51>Ztm8YRE+7}kDSBgQE}H_On3yBLcEX6L4PMVeJ2w<`$r)Vr;VAI zDeMG1b~6#1mTKHgBxKFS%Wx3|S#xo_rf70$`YxxaCY9?$(uEb{AeOdRD>?ssYYOg!>d zA@%P0+|0wZhexcrS?If;2?ne@^g1LbFC!o_mrG6-~k1G2Z_V`g?woIS~ zmHXeq#YBL&>>t#;XY+%91}r_Jxbk<@paO=^>7$x6P-LGA+W)X-_A`EF5}u!7!cTvX z+iL2Z^2#w>OeW9Ip((MRFEt;nx8^3GErY)<%3Qv<*r8r};rM`NaCK3}^5sj^>%VX; zt_QD$DI{s-4+KB4|FEJc_=)1EaO{a!_why2Cl)VLlrD8xJ=FO6;1Y{f{7sY{VolMz zPgrw_bZ@!+cxi=#m3{a9`5K1MnSJJv^67gm{;waAvc(dD13F{dfeO7e}Gw zs&?$NrR|EE=QTCYX$G4tDoa~!Ri*k_>4Dj$ofdrMR1j&#TqR*8DP2#rmARH|a%tLr zMSeBlm${AQe0XM_m;JN(9{lpZ{97+AW$LG;59(3g5SY!IZ>QADRHK5sVs46 zqAl^6#Pzz|*u*yz-%b2m;)qV@04nQW##dPKMtGlA0`HMN3j>r3!sh6=@;xa7*+99_ znor(gAKd(9>Gnp)YYiSpy}4v;`_cWsMYOxQ=lbv(P0eo`*2!9WHV>Cp)NX%y)1Mm5 z3r3H>4LV!?URrfdz3!T2_7jlY$F2fULw&szCiH*j)hF)~NNGy_1sJphtPg7$^<+Kj z9r?%g~>@q+{B;N2-2=%6yOHDTiOV$}bO!A_jlxhQ?g9q=P@yLnAJnO+4f2JMVe# z>TCR=J*G`39UM#9O9)27LDZzjnGRQ1N}!{z*?RtVn*ut z{-+3o@zTV+F@CMeFAa*?2tz0A$xVl8Nd-TK-QUh{u)C!qv}s5C{{2kLil`H82sE;8 zDeZpm?!iRyv=hX$>XD5GrM+2=rWIBl#$Y^(Z%;z zK%}JZ`dbD6Q20N=I*6sW+|E zXSh);v{5Z7*l?5%^S|^IA zY1h<=B5}xWYQ;qq4%tmOWNUq*sYGWi0$!ZPEqVawIMDXoq6Y&y<94S{q!pfPgy*{Z z&tvXA-|QCYQNB+UD|{A5o+AaBDBh78v1V~qe6u!cYd zG)aw^sySI%^+sWyV#1>7d2b>0C;0U>>2UFU3z%)-#V2;lj?qvT;jwwdps8YnIWf{qyR_*?LLf21WM_*du$YE~8Tb<<85U7kz|dRWl^nqe1+NONtU=2L z)+Jyw)v=kQZ2Pj0|KB||D)Rot+cIKZ0v?=H@77>p$zq9Jy`M+7elUKgCXcO~#asIS}9*JQ9p zJpU`{=h)S#1nDNXrk&K-KZyc-KK4PE!klmmz9AHK0xX1q+94WlQf_FFt}5@8MXlMi zT?2SE?wug}qpQ@DB>vuLUtdsj%6r0^9JuR(Z=hN(W>sp@jm}!Oe&qFQds1h_XiRS_ zd^)lkJN(ytR!Y~$Aee%6@;*9<4L-4b zlAESafa@6G=jTP`L}te(rlmP*O_b}P>wMmyc=bGfxLjFP)=qfi z{+s*((aIy83l~5UcxVGHImRDvSNaD|$6pHZc*6Yy@7a@R|G=Ij?JqGTu&-T7($Wx} zOE(k{Mhl_QNEr=%;0ukVU5eU)$Fa$fJYxl_Wzys|V4e3A87&g9*+YGg`+XOCdms1q zJ&uo@CyTNFnBF~`>|%p~eM0gV589>^tuYiL1%j%}R<`lk8pr4{S!NYyVemv>aedu= zeb;0`-z9C?GxQn?zR~;Y<52$kGLE28a&`Usw_dH*eI8!V6smpdBNoqa;vpz9eWh;C3S1XXL6vO zq>5+Lr;llH=6YTw`?vF>6=W~XNy1)Qikt(BM}0ZdaNqml<3b|vk*(JN(dx@d_UB9w z0JQpY9!fsx6QTt>v;8?g!^@S#Trm78zq^4AkN&A_)+`yYPB}c0SnO zfEKLLe_#LQ_h>S!^ycf;NMOQl95G&Rsp^)D6kZ20P4w2X)}2eHu3Hr9&Lum(TQtF)OLly>Xd;(ObGafem*H~796U>MQ8GCL z+#-cLmz)6rj&SFaGr%oUxpN6Bt6LQ2&Lzjdf-RSW`_$rgOEaN_Z8g+NuG&+wfNC+I zQ3OMaN3dC&JPmD@;;m9P+&GV%(izgh*E1$V6%ap|T96Lp%Bvpg%C{OFT(_s53chbc z*w5!7P78Yz=P6^u(|csz$j3dqe4gBFr=PGQSzYG`K|aME_5tz8s6s;}SNW8h#{xpl6gqDf<$AmA10w0% zV4a)I8K1!=1=d6k5~T}ppRyS)jR6v6s?yPbix8Y^j#P~~Rn9@ABrmYS3lr|YfSiEB z3o){QO@?C>ct7AAH6sHT1Rw;Tm?I=^2$jUUDqQfcQd5D{)etI$)YWDgV@OI~y6LRybFg+vYV*QFO!An((xKhJoO#KMw>kxCK!M zjz8vX6NoVXazOqkFMyu^Yh7b zAefGSjIOB~DqsR}9iST_Q-QcZubeix3okIUBop3OJ z!wtZ1wEjmzp)+W-GciCZ42}9@II={KB|HKWG;L3J$vJBp$3(OY^m$%9#spp;>4qQ6 z&;QkrWn#xKN4ficEb6w~#0lm)ae_ewjoRMnW`f6fp1P4p#}AcF+ib_ zE5uJlJqZw*1q}R7K%|QxQYQy}Z3zZOq%INYq#p#G-iI(p*1xuRh0*h)A4||m^`rOw zSUNmF;e^r;`@#=?ETQT)`o13v*?G+g@MD=`j|j)W-g8^&_z#|VfRi0ah|7U@)gp1@ zZQ{Z5hg;fv+%1GJ3oEw*$vYMWG8<2z**Hm#EG4g&*}ye zPV7{iH9(twVyEm3t>}{}PE3_YwQ~c>u(xA*5Em8FpFkOM=g|LU8NsBC8IJat7j6ng z2(~o(5-XXuba72A8&T8Puy_fQQl36U(r5VJkI1aDT^xN$UcQ~E0!kv?uek(weBZl~ z?p*4HV9YFQZjd{dvF3`A58IkcPJ6eAx__$SQQ%ag@1JU-`==UCJ|f2mCtu)H!^syo z)o?xqPBol-fm019U*J^3$)^&&3bE$W)?AbpILUDS1x_-Ye}R(>=U?C?n~0N)O?2l* z)a8;<>Z32+GlDormtv*1)z*fsa9LWJsYW>DJ04rd7P8r?OA9lN*e!A@qbrk*3rQnt zE@;k)aDL1BBE-!W-01k8$$X8Sa0c$8xkL^C4??{0T`;8)$*)_6gAV`NjJ(T&ELj7i zRdqfM}W_<$^HDSK?TB*psJ>{$j>nQF)*)ulYKtWaGTmp)0!PC>lK zwA2}nSV!TO8L8SiIj7$sqqFg7COJH8e;!>YH+b% zo=3aqiQMxT_dKzCp2RJf)tV+fz)rzP?)N*~^JK5?GR`Bz1k&KQa~~lKF(LI$7W+MO zz_g8g&G-a+TELc;lCdm(TM#S0>X}0hb3%es5)#2lnv=?VX4HdUIy_3;7O^j}5@+(V z_|GGvCE$l(ho}bjHD#qQaeWJkZ*p1o>4QH^Hi65~_o7FxTJ@!H_iIgN6_pGt zsSLNYK3W+IRcuCTDJ0aiz%&s2y&q;AXEifE(_kDh8i?s9rHp(4C*gZjF8gmKuG+wi z%Wnf?i7`3vp%R10m>{@K7!!RYj{)(J35Y#o=)DzW1`s(sV(`uEQr-&AkU?5F0$*hMQg zA6)T?4p{{S+-52x=8M!)P5|&>L)i!1@VL7fbLF?nTdrY5^KEp=b`-cucF5FqjDtIV z`eBXZ=cF?8S_UO=s;6eh{2?`HXK2Xa@#FR8OaMEgvs16YB=ph*>1Q-hiDz&OqA7Gj z1$ZX;g1?G~q0*<1Uf~!L)6yL*h>B!i!(KjYRVK~4lB!HfEpn|GM)cnL0@om-Z`+uj z@OGCg$|svbR0*;OqDqhvlYs}S1{pCKKxfdN(kGh=gms@R+B2x}$%wt+_(@z4d%BA-l;^7~}5!e?>hIkMNt;=xbB0?};2!XWUt$;);}g!%UI z&ZK3Ib^+D49S7v@=E+HoS6s>@fp+V;1To;T1LtyIFB{-sG>wiQ-|*p$q!}O!rdVfq zhjSG0HkU>|yav~NGVT!h`#f3H>oGW-M@*yU2HHSxYk32OeJGeRzd4<5AR;p<+Krtje4fy|Y#vn6mi+UWP%T9;*!K& ziK4`?#F)fXlOVqflO}N1I^`>nwO8i$h@Wi^^~+<`(-cuU-^pauy%T=>6uaWtjS+pp zu^tU(w7f4^Ke*5~#!J%SGvg(9NP$Ybr(L(jUEdk6VyHnQ9l6F0Kw)vCk zXM$txQ$x?7Ve8KBIq@+0MlO^M-iKxJ)$twJ8^q+>A^zEon9;HJ$WY9?!RI?WPs|aW zl9M_De8asuP7ve#tWT-LB9o^nL1m<=V(9#51m(|+w8zqtUx-YeM%?M|4(codDfKIb zgUjS`k(;}~JT(_@{k)_ox!yWST>i$#CVC3YZbmvHYpKRaM^ZT$I$T7-aR**Ih2A=P zDhzriI(qRMjfsAM0`>(!Fz5#zOM?J{vFtz{jTF0ht`VN=?mv&Y_q?}`)(g*Lh39ei zpT`HD*FIKKQ?GEYC|Nedikn(xCeb&hcY~lrtBqRbTv}qvCa|I<#g3&4r>Ud~`n!{S zNqU`!H;JWd;0xK$*U`wE_Z@U$=$+(kK6&eNmhv|gMmiCZc*b`U@@FyDzJyAPuQve& zja2Y2Z}`SU2Maxx2|bqI?{Ubz9)D+|L-E{7v!zQlR(b;5WEY!pF%fRE@C>wC6dX;0 zR7|vDu?v(Sa3GHLxCld+9KZ~=DBU!X!~Ask{=*tKt;W8zzg?rFC&P1YlTPD&u*C7A zV)FwfI*Y2cO?F1~&6!g{r)%o3Y*2Q&yuVz299wOd%TkxUuyA>0)w1UkH`L9KMeEgP z&qJXWmq1IJd0%fP?sOFM@Gx0ZRR**HTu^&rUfw=DOp0+FiNVIw+U&T9eV&J(oe<}8W`MD@}n2@paf_8>>I#(Suk zh^dE)ISkHrsay1oaA^8Hymw7W+nm1ag=n}tSb7M8emw8T?EAO(vQF2x?xY)Ic%M9( zh`h0s@9l-|*Zy?mgEOI9TSN6{s%U*C0f{7YrK?o~Fwi`1ncbq(v4i**i65&X{n-7?G( zO{`u6a`4u(>Wq0Gw1MF@s63zmlOjF=1X3Zz+2j>dD`FpSz~9lRl{~6hs!6CPzh1;I-P;SRX}3ih9dbUHI`r?% z_yo--f4eBT&^qO!`oi|`^KtZr9TU#Si7xDvotOL{zTO3_sVm(Z-`Tkk!dAH%5wHz` zKtP>xu@b0uAlw3ig@_TH_8f?UXxo`;ZM6=aKRY-Oke*Sr3RK%9N)1$}lD3N4&Jb)V zRh%(STW!bAv9@@tZ4s?^$@hDAu+#HB=lk>UBs*)r>%P{z-t}Gs8((J!REUkTrfu?!8FU@iL_mFGOX@Nx7s7~ptYPBJ8$sECGsbrUwBdVV7aMJp^i!pIkFv7)Vj98fis#V5P^j3`$&v zF~g%~iJu-WL11T)gOw^WUEgRHkL;h#LBgV;#&Swq?&g(aWjp+w3wx^uUpW28bJ7@n z)(Gn0BsKnfWVcK=H%H!*-RzihOL_CP;9Idbw@+~i?f-?3?|#Yn09f&VX8>$ zMd4>x1a;?Pla>sY2^+j1hnw1(t)cuK(P#66I%w;6P^QIO;0aT2V+WUQi%jf$w?2Tx zV9bZnt3JM7&0S(PL_=ynP|A!Lf||2Ey=7EQQM=@GEx0uIivolAoJ zqjc37DGkb~s^j;RorUpxO`W4!WX7h0Qam_$!p zkwS(g;?c~7W$G{Q#=Xlz{~KI&DBHIL+Z;g{DIUn8wjx_qd2eCG(!iB>7p}pA|HL~AeCP$~6I$^*)hO_xH>ko3(q{@t zpOG7Q5U)8;j{3|j8~ZuikdB9`D7=*o+gObwlrCTu%ke-Lu!?rTPs3Xm8@aDq{pernmv@>@y0 znQc)ownUuvJGEuv=_#k)@IUDnI5hY4qEjJ{M^vx+II^N*wK80~%7*KY^u-p#>9Xf4 zR=3PNU32f{6OBR7t?lFe%FaSyxt5csEz0-1J*7SFV5&tBw=>nzCteJySk`y8I%wtC zq7}=!sxg)_5uEN?1|!k=W#`%4I>-+H|Jv&V*)IYh}g z{aRY4(e1(1wIc6K4wiWjGFg_grkZ;m_ac|=U+%s|_IC;4@qaGH9>6(Mt@fD3KPqJ> z%(lOB3YU0G#o<6sx$n(-+rHJNxBgbQA9_=N>yMu7h*qxnrsBlva}&2H{~)7znoRQ) zcslOX_JEUd;!_<`OquePW2-(6tB%c7-aX13jvkpFBq&NIMC;8VoJ6mGl3O}z4(&Hj z=2{$PC4_nU3N+^IbhO=Kj%_u^<5!jWT5hD5d6tD$iRtd04<@UX8Uc+-;&CQ2J(8g9Qp27IeLlrMpQ*6&~nrQbB}#pqY&q0JH)? z!UKTm4*)Q|GX;Pd0>G~x06g*lAh;xYVR30-W%R;jlY^l+SE626oE>QVvuJTPCtbGQ z5BHr2Ad=Of&x`^!LEU7H+~CI3HMkPi1>jXGYk+r`>TOMomh)OCI8 zprpqaB}6-n#7@P(><{;bCO6!^f4XvLn(X)Y?1Kxdwu~_e(VxSXS}}H3ACy2Rh&^#p zf^hN_7(oF}o>gaz1|_$cX#K^6*UE$gy?gq5oF14ld8rg7^IK?PsD;A}3J6OT{k961 zdyZg&(7APN;6LyA?(k7l7bO$VUaDtffPouK%>HbO*HaxzYTdZ94&*WsDeC?i)eFw7 zoV1ABIn(dOdbz;`M`$i}f1=*TWNc9-af>WRV#>tIg;H(Eel^=r$jtQP-gIb~UgPf9 zW(=BpCm-0Z8C=z?Ik5eqK}+wW2ewb?XJcGas1{GmXY+&e)p|1)5nX9eXh5~ebgwl> zlP}H>(Pxq5;#f-K<~QJHw=~LY(ivNJ>dgD$5%y80++1!{_eTa~n^upJB6R9Pt=QDh zCEYQpVO+0{;F9%k|5cquL!FdJ@6Hj|dfG^A_U~cFBKyQ^aO|HY!9v>(4FitLr+ZJX zA492=kUF##WY>3NvcHmWLI0shZ^kf+;1AshIE`}*b{Yl?+~J9b|2AfDn0H>xn>`8M zV|=$L31Au+rXssfD0X147v)A|lcBc3aU&+cD1Z^rb#Fj6%-I9f@x*SIedrBHNi)+6 z(qV*`+BQzMPM@A!VS+X-qihzz)=C*Kx)Be)Qn|Q1g)|cZT{Zn$zl2GBM$@-3M%g57 z6VKsV$|L=qDF~WLAXV|#TGcaJ%IO(KC_?Ojl8ziDwxAZOl^Ck{nh{zzd9hdS^!0O1*l>J#KUP?Zf(`{s*k z-hy_4H^#3tasFKQi_L-U^7gQHZM&{jxcx%d0w^E9i+{-kanFm*v2A7BFAd6j*#q0d z2E%%T4{QgAFwn(frO93X-}ybw#(kH91A|j&I>+d~*1`I2_P;UV0^Z!Ll@llKX_M>C zTkaJm`(hJsdIB4%%}5d*&VSrKf@jKC?vRu$F|Cp^Bg=x;Rrgf~^-41HOe>bIm92SA z<(#@!xds8Q;^9zbO-GO;Uc4$+yrx4A)qjw$%cdmm^>5ESNDQFP^0Bte-jc29lk~Pf z?A{gRdBWt{eZW26WS?W=Q>ki)pv;gt&xF}MyFKVAk+Lo+gKy#<^mPZVj5mR*?cQA( zYwFl~dhwwD$2%T6y<%`G3A@$}#*?tCxj&wST@FP|t3Ra5Q4g{@j)r#cMk|I3#{^ad zJFtdn&8F?b`CHI6ZBVlsNGoBDT7nG_-F{%(E_UE4=IrXAf;eCwADbc80ycw=ZD?Y+ ztbcP5h~)qZk&u)CmgHTCYe%};x-wqQ(Rv-2$1ukwFM~x-Q#<9f-_YLEQ-+>B9XB-d zbn5owL@p%O!71%l&W`}N)9?2WC7xKeIbu!Sn&^=igI4TD-@A7mR9u{TDZDrSV1hNR zDZSr6u)l!N$Z7vgdlqcm5oq7Dz$^@4Q|0dVUs1MYn5z}p=HQj)Qo_PDlI5i}q05)n z#4KN3Q`s*d%;oFxqQT+a^zA}!@r%t7z2yg5Lwc9DeAnxLV27f2>Vem#F8{!fBi?TP zBofvYxH7tIZFfdHS`WD#{e`2I;z;?ZKhrpA%B_GikK9t++%a)9L3HzV`6$>5Z?FSj zc_Z5A9kwQcl5K4Nhi~)N(qjBPoE?b`T46>DId(<1&wMz3mRb;2sBQPqs%ax5be*xk zy>P`c%sL=DI#y)2`Tx5={^-wC^d}zuNn5_&j3p;@3YiC<#fGZdMSG7q6#e}P= z;7iXTO!?VkL5GG$hVbE#GG~W^M!pQ{-b-V=`}E?YTfgu>z2b|hr`LTEf4Uj#2zIw9 z(7tuy(W6}W7isb3jwfkSxyZfjCtY=~MV~zw)Nz<@O^59rhtD1k+PA+BuZK&=25P+O z!Fym4-%yjMWXs?fY!&NT>!HPNYCEHj^0Po=%r^37Dcf+wJ5yXJHI2e)8S-k4W>qv<(nzc^+&soz);tL)YmW@K48>W5(5+?D;xZ|m+r>;GvFeTgo%V^j;n%gDF1YkN5F}5{aJv*Y~mz+`p#k4Q>nD_S)25b(?nEYr(zA zZMto*fkcgNWdjiasd1`8(8sTuJhnC6FG{~~h&isK25Hn3>SZYT6^mC%!?aN>rTC%?h1&Z5?@Q&h_wN>WNTe6u6yH;S05Fd^ZMg+DP{vEE2*bJFDchw8*oRfVY!E7t)#i;(CAU zg19zO`GVvlk(~G`apt{JYiV3t0zX#TIvC^7GIiQu-kZ&Pf%eQaVZ3*P2!K)#+apvY7tp3BknOw%q z&2<|Bi&#~Apz9cZ*Uj9#?@av(3q~$=q&}$UOli6ma_JK^FZltPuM{O~mHE@bx5$8? z@Udh>t4jGKB6%LI^pB_d<8$~JiC17oa35|ogg(MPk-M0uBi%_oJ85W(9wcM7UQZHs zXRuyDEHJnvsmoSb6pUZZwCb>8i$Zk9@Z`l-1>4v@A=2N%P5_6~q9-Z6c~1nU7<`q`1p9p>WcS(2KuIT^jEzqVsQ~XTGHD!{_hNOmW}gI6gi))FBkvdykC9 zv2gz}3b$-Hdn;fNdy4MawiOVCOvL)`92_-;ORXW?GZ0G4%?7Tb2JsrG`S|B=6af~m zBuBgXYxJy#JH@3zo*ktwdy0EUseMN&&kO15N6?|fcT`XSgn)>gNsbL*P*JD-)l!f) z0lbO&5y{zGOW|)yCXtfD-gvI)Mv0 z*txnx`N!yo%N;t;?t9b*B|TFLFHq40s>xvXt-vLj?x!Vw^V8Mc)g#qGs@OWb(?^l= ze6of~g%~7?soHS9_9nLn4wPm5H0tB3Tm`phRc-))94xbGaVeOU4nYj-U|E;o)qq3j z1hLOUfxV)h&6`?OO2CcWh5xNHnHLXd|8;C6RFsa;&k|7*MruxCUN&SO1kN$4LhB~UI*n}l#ny7~t` zqR6+ElRfhe`W@}7RO`9Bz-2q=zO%qSvVcEEW$}^pYI}HWc!1{`Ub@}a77W}JocPv` z%Erdq)ch3OlU(hR7AeruJ?U`bH%~a`_}P@ZOX8HO6ByG;nlAn_6$>y>plm!DWWW{~ zx-M3hn^1f2SdUZgYqKz#vEf0U)2Q{n`_uya&;tHVU-w8iMhp1k69CWp;IGlEfCOlb zD^$+SHeqgQ>IwF^WJr80Nz0iR*z6}x*E!0ZrFF35!vm1_!Ns918oXze z4j(0#;|M?uif1E+L#XS81)ayo&or)J_{den#xiw?_$%|M%HIi9a^ddh7VwuS1w%B4 z3qS~nJycB>3o>Y(KtS@9l)(Q>$W}R?4Z8Sl^8)@$N`!uB(tj+VSYE@k&qJAm+PZiF z4&SPj^QHs_S^z)$ID)fkbuw?Fah|E*&lA@3yDX-&#{R?tXh(1X!}re3RhSNq8Ipi9 zz9RtJAyxlJbD)MWto?=ywncAtCIM4)&isZnMlkR2lfIWVT;nswOFbc!xs3b7{O8)uSc5`DyfBg{=D4I}UN<&Cw^5b|oSpF7hbdQR-X; z{9uJ7sO_S-kSM*K1!bBS5}~$ThvyCaxk4n+72_1cPmj)2mB9mrGiDjufd9s5F{cWjzv9o~IZ^n0#L{`j7ydBmzm5EV8 z>vk_2^@UNr_(iS^8#9|90uQTOQ%agWgLtl}?cxCY3ARYCcg(JRoyG$#Zk#7xZARlQM zTi5{+iL_97i{I-06Wpyh9f#Pu!HL?uM_stmExul z)G%-hzBff`n++ag0s`$SK2dnP-58!+IAIPpLsO7yXCL2gY)Yb!m3*7AiN}YfaU2IY42hw*pl2NaWpcQg1KzMpmU@|k4Yl|*$Nf0fb@;I7}U z1O3AC-wVItSQG*8^r9!h%wh5NXRn`vj$+b(8o69pKZQUPpV78Dqwa;0-xz(y1Ibdx ztQR2@T9z!u1FeH(DGNWP!UN$3 zReJx#wVA8*ij1`{BHBtTc8FkjA$WeWkf{THn700g13gMQivx3!GQ`A{u>a3~iBN4_dKYi8& zb5_u*tWa~-WMh_6pGD*Z{-=$c6jWI)S&~&k6OaaDUSTh(>Q=`N{%Qu>nCy=OIxH== zX6Ce!IqJBuNpsRTc3a!k>Z~84E|$QRGRIc${3hyh34EL3G30dAHznY1!fo{5@B~AQ z>a35VzA71@3nJk^)#{cbvHck{CH7oc2iV{qskU1RID>g*AnIO=4HaE4Z0?5)6{4qxnBaadLUWML=BewY>|Qp)zzUrl=x8zjKQk2J5khM zN_=sBEshu!5UZoE?(p-4-I_q)ZmiR+YLc4{3gcgc!rD0`qh@>o(lO$Iv%u#;HN@?n>8Od;XBbGR9SGd9+XNk>G zha&hm%AhQeI#&+gzlx3XLIHlmCC6MzdX-rQVRm{lyaAa7UN!aWJMY>MPMltfYmIef zjohr1E_>&#^ks{U1PnhV*L`d)fP!_LWG&H&`xXQxF6=wIFes^|q=!dBT0l~BiNnYJ zZYs%KUs5Ap8>-9=P418E+LYGAJ%ffij!0Zlv|V^FHR!b1)EvMS9)s`K@f~qnNKP8+ zUIik2O$j0;5-^-NrFcfkFl>#I^;d!8^rOgAd(Fuw>#yMn|HI!>NR$;6Ck&q}aBn4bA1j_J&)j$qC75yw%{aKZ?mU()k< zNte7Uz!K$e(us6p_)OaCN5yJKBDy=ZBQGmzl&07p`CpglV$51***nsn%!xi-MnANi7iUw%c&TyuE}a%wbJIq9>CmFkl6@G`$Ng*EC-&T_w!kP@e~EM`$h za#?6O;kSWKuM^ySr(*X(MLCHtFyG8merqSUta18L>gY?#<%EDh;rUuo6(RIKe8d{n zMJ43E>b2TO-wwQUi-H9i>%7q~eSPOAZqc0ofF85OCTX>aZ@$OMbR>d@=!OJ91|}fe zXcJ|;P+$8gv~0l4tQx(^W7EbZ&0kBW702=pilu2S9_ z$OUl$#^#0av{SIR_|Q9N`hkw5yV13cXuy@=f~LWhsc<<3PIOm7g5B!lDCWdr3{zTSGxISsSG?q zZczh5KuU5?cnkEnny2Rr8`mOmTTxN&F^tKa1ywxl04@YWLIZM@!}!oHz`v%&TYK#n zL!xg#PoVgQ~ z(fi?l``xPzpN~B&0r%&BZ8L*7CY3B#>-mPp*y4>k#I{N z%M8!FWwD7IOCQCvG3HTDQf#OP?l5IDiH7=?U3POZpm{SbF+kMbFfM&Gb8+!-Y4an08@Ik? zqtDLgy8FzwrMqWuM;nyqZ@c<2%<#^e9Jg26lT^(A;G^bn)(tuA zj}-I2q8@>|!;m0&kS6FBC&pvd)LY5sN0U^=TCtKHBMQ_IjJo-U2^u%q%LaVo$hb(~ zGbObDh4V8r6gy2TxnkrjsffuJ#aJaRYm4OCupO+)A#v>*@PrnFt7Q)@=66xnHrARJ zU~Nh(3%&yTdLgy~FB`AJGhWBvg*v3Tp$N{fU~9$f5Ig;KtTSDgl6pw8F<$kGL^rj_ z-?U^*2i{Q{*`o6O=Qrd9mf3w z7ol|$oqD_2^Uo(-HmCcaPuTzY1Yb=p(&?c^{{>RJ+@C!GRs=-I?|44P@3-8ZCtwE$ zN;t6d_87E%95%nsFGmF18atex?hc+3ABE;rvA(t)rM4m1*Mqjv9Y)y?`N6EznhCgW zC`6pXcO4n;fwFlF?z_=nPQiukP$ah1XE^I&{Q#wcEB>mc&1ZV;`=8j*6CY(1LcOJB z>MM!<8~)CBXTo(;;E7@kpyQu$9lw zTFh1TGlsa17-xufYFx)OXS6mxu0sjGXzF-zT*m}1*a5?2|GtfQl354UNFmZ67748j}iX8mv#yEdC;|=Iqbo zBg}KlIeVSZN0eLjuV1`twT~+4cgFSU-LwKR9Yt0|Ic5*QH5&zN|fQN ziQa$li}x8D!TenfC}nVffz9X+j6FoYinvf~>ne8E86B5kTNB6?z-gEb{)7zmFH3-H zhLomVh;KUYotG8c5~OFqQ=B$37_i~+(KR2Zu8QaeG5h%{yo_O)sFOL18&mt4+ywTVl0*yv(%zj+S2&ywj8YglpGa zch(d3*#yPA^ROtJ?05wAFjFyb7K2M}AK_}1?!4d2;31WZ+|aX^rO;DU$<<%pp`oym z8XT(ma?E0by&GrIlb9a=ntzV@7?mgkui!4eakD>$W!%!I3E0JJT@_(%T4mKMVZ}+S z7VTHgAu;!=m&@On9avWvS_dV!{=lJGdY0R>>sU|Kk+EvU zuXU^TvXp`H674Tg@dPe&A$<&%ozN{o-4)IW|2C<=N5P z5NxIgEQ(=DzxSR_yllOSo7xi68Ul95NDW(I#ip2umDMvp9^?u2tlN7gC2#2tBRebk z?YczhKnWEZZMSC<(jd%A)oQxoEZ}M`tmpq9eX2evt-AJLLHTg;_H#fg5%Y#ZGsEYh z%I&B!Ei=EQd?m`&?EK|k%b<<6Ct2A4^BlJ8+t&krlK}4vS1IHfe&gpnnOLK<^fozU zYRN)-QDoJh$FPXYRt>*BmRUc4Q8c2|TlI)Ji8U4mu7u`Q2>gJj(SEpuI3xD_e!j~# z>|QtDzHUB0nu|#ra(G@s+Ija2^RZLcs#B)~cwRul5AK!o!S=6mj;&I2n(nb=wFDMd zw9+s7<5ssWrOlPvB?r4qbCrf`QH@{H@_6=q&Q=NDEXK0BMnFqhjqp%9cPl3nnYNy`(U zRlK;opgbL~aRFwS&ezc>E+eHb*-YDZ_>D2$s50ax_*L+0isgbRN;GfDY8EJ;i0T}Y z@az@${Ca-XGo$!^e16q$@y*TXnKQq06{S2jzw>vvmkMh*BV)DF9H0x1O$qX(&UbZI zxl`xcXU^w$(WvRpor%U+#9f^1NyfWn?!@^r;+N^OsP($dSa+>z2HxDOK})Wua~H{) zn+WSPtM(w5onZ*XJKrjYLQYsl+h!P74dvrhQ(l4vX$CyV;dfeMQ+>-tPXuaM?Vd6p zMG#`+IP2&q=ROJkILx2y-jIq0fw{T`o~DT|tb#Xk!hwQZ6>cI9O;sL%Zp$R|hj;hKPKaHv;AGGS)Q3dp zEyY!iX5d?*;y9(@T6O3{Le$eMlwdMR5T^)kg#l6(eQjVO?P+D42+T92be4!YjX8f)wMFqS`8*hH9rc->gr zxwf>8-F?=i#)SV=R%0n>-X7&7)^oZx_z?mKCvQ5}6x_IFR--bcW;9>jsN{hB=J{st ztc+I$IJ=+Hy7MO%-dC&KgW&uCZ*5RTtJ@oiuRMSRku2m}oJns~_c0KLhQ-olg zEmb}CB2<|-3e^sA&l^Qm^JvMvUQ}fm6?mmPsDm;gCe2WK*W)$f|D{MBh^{`oVWF$kOaFtMQj9 zp;cL9#t-lB*Ra*0O95E>UU6BV?;zlEis8?xO;UF5%zK_p^k~#QuL$i#e0LO`Ta`pC$e?uBK4m>GDs+Ui=SjW{krShl^=&goYn z;W)~z7*>xIDTdbVm31D6sBhW`ub8)7u{_)%*S3{81jiliG1V({Wi{oq%GQ==ms!h8 zjq(^_nvFvA%4D%Fxs>p&Q7PctmK8H{D5F%X_Det>7I z@(It@-#RW8^dI3L?7w|@mJK_T!hwY=_|yrG4Vg$b0`y~C+yR^^_WV%jdh@vZexd!# zLf%Nr!=MI2xr5Zdxo;KXq$*otSdjNbxsY$DW0r`r>NEM*K6jC8P4g}CwBMgT2m7ebW2SO!jo;c_3DYq z+0HYJIq28<;yVQ+!osdRJBhcK+>(S(^>#YL*&G;l*7xivd>HLhDsb>s7*F^+(Do zvQ@sNZ@M<|6>-fuLv@X*0#0w084dLgHCsG;Gkn}oJHGh|N<+0DVmIZ%h9Vtpy$6$7 zE`H-0Re`nfgCLI!<8aTtw-D|xi~NZ;;lm4>*AE%^3Aw4diNwwXQM+YAa-?j3v>y%7 z8WpF64{eDi`zIUr=r>a9IcH5lcUO(m(4Fnn_J-#h4s4mM50jB8&2@bl@#0#tH*|Mt z(+sA8A55Cj8g=H@LcCk0G^}}7u2<&YSkKCidkv$?>!S}kicIKh1Kf#4fT_58e+-+u zlVV4aW=vLetb}cN!;6k4zkP4`Q|e-B2l*pYzWPbJ)YEjB=G7#&srMYT|F#hJA+D*01BX^uaaW^~+uSL4FRxN`Tz@~@b zt!rEBH?_fZ@fOC6cAS8SSZlPYCV*?UiV>-yMKR+tZir}T>|j;w>4#%`DfSCW9bPxu z742ko3Ca-4rFqsXqqEn=$~zZa?N>7nIBuK4?kUi5sY^oV?6fF!scjs#ctI`<9T%&S zrDt*>KKaQc3A3^~t?3&{?X`vp%&_d{&-s-FAW^Sbxw@3V8QR9pepG;t^7;vR*AS}{ z#~#Df?)0_Z*-DN1LQoK6tn$>F@3|UFR;VRw2Ga2_6JnHc>pD;V2vP1)33)l9vjoR? zLen~sUg{N0ojNeKKRov2lvr1&=ZAT&of7vC^XwnY0~kMxM%ZPOIX(;={wJAKDUTvl zAj}p4X1XuaEj9yQ{P-H0^rVw~p+vt}R`=;@|E1(2-3@5&yY@&mXILyWH~y zO3!ego@ak^9zTtW#j4STc?#tp z5X%4ZewvZW2gNO{Lo3@Bw*4TkH@$KMlZrhQpUwX4bf>OA|C^Y~A*&?Qdc5SHru z2VpJfU%{u6Q@e+jII3$8jQzwI`^DtygJEqKmE}^;I+QlxUNcW13&`j4Lsy~hFe140|$FmUpVTw6f(@0ML?S6_^5i`e#h z#KjqH)3?1IdT~zMW7}Sz;0g$A<=`%?kBiv2p?-UfWx}jQ7lSOeUy(-I z@guD>>3$JAm>PRJHn#V1REReJJT#il`?RRej+X={S&)PEsx^ZnHarSEsQzGCue!77 z#sGPT6Mkq4uVR@3AGWd1c;#Y$)Y9v}k1C0aJv}wHcP90!_2)W{V4CmC?^hFli4O7Rxz5Z2km?lryJg3%I@9wL}V7hgujpfoU{B&bvF3!@eVapb#@FVp@G#)W-VH(v#K{3-VfEwBdeFr;1mY!@b7=v zy+w^DwLV6yp&yeCYWt(vhU}_!_#wBveaANhrXx~XdCD&pZE`e0n2o1mPqVT(24xPu z|75E?vR7NZJaXu;P6z*jhM|;Xt#tc0y(CJiIzN&t!wfO4pPb~T6^S<%)emLwn_I8E zcE4Ayxi*3ZI$M4C5YQUyI5t#|mpN_dEtI(gWk&1D_J}tOo(v1@m3P+OAnM##Xe0_P zq(bM^EB}E)JDYC|z)dp)lHw;2uyn@$`@Epo0s`LcSVDGtqO7wW4lv*Fvl8hIxV&)C~rxi zn-Xrlyj|znTHxAkb#E=OmlvRG{0Tkwo7Fhv^t9qdlY3(UB#`l!@v3vNpuB>$@Qc~( zTyuW_ryqk^|0$OqQ2!unodF@ggAHs`E5qT)IngXF49_MO)ypYfo^u-+QfxE3{9QDYm`s0Gl#*WTWmuC#;xUGZI0eLDY? z6^a4Mqqp0VEpnZuoDLQO{np#kjHIw>MBX73pf2tb`2(kXgzj+FkhBb@C( z&1f}YXW&FURXugz!pi+>{G8+@N>O5+_c*-{kvA3)%fo^tN!)NI)@8UXXnVBpX)p{UT5b3)%lAG zanPY}s=C#!gMncEL@GGrw)6=I2fyjFe3(F6Tgm1HXCex9RqV$jfmP(X} zhboZ;pn|jO;Wo6+qGdp6Z0L!|Zi>PIoC(L2O(jj4O>m4kUP{$XZ${nfxL$U@?ieRl z;o>oix(*Tye8tY6ya-rB*aGe4WYD{~ce3TpI!zFQ#ub;XE;fRD#E;S~bS46%^CR@s z?O43HSoIT>MHU+$eAkXbeF%9_uq#;VP>c8%iD(62od8${@A-Z;6YKsM1akuv{9JWn zahVF{fD{Fe>TZ)|^j+V0;`+voKXrU%l_CgH-Nx%3U)9z9^rf}##81f8{L1+ESGaHd zBxv?goBj8)07mAo{JAGy{FACfv$3I0jfMY-=671;$#GITy@W@ z>|mVF^VcX#w^~ip!tzCD2?}N1-#mH499tw;k@|PiGwH4V)3-aU0xjgT3Ftf181N zc|kzkwMy9F!gxfzXV9`k*nAi~lU9T-bl&wkSGBBjK{;|iwN-1$C4`ImqBdm)u2ku5 zbXo}Js_|>^)cFVl`zM>dFEE^`N@V7WzEbQE&lK0*IyEbulWa(tDLJ)e@d+~Jh6UQ) zS&6eU`%;1ulllTfz!QH;^elI3d%?0+a!l-b-Qcply;JWT zzMX#cB}4O{4i@yx&audY4lV}eu;M`2)Pw6*q`*rYCrf{HdHu5!DOMG=MD{mt>oQUQ zGUntm@ufHk|vzjNh#bS~Q;JXHpFrJ>;qZ%=+k-yRim zAp^oi_Qx@2(j!v(hhpM3f8%)yt#5WOGBo@hG&zDdf8qxyzKo{iS;e3qw4O<3!hcB} zOCGq#Npf)+s-L$2Q+Fhc&m%a~dX}GSFlrfd4O8AgBNP+2<;$ptNtmXixzj?qI|$zz z<2P1uxwvUFo^isB?-fqTNmZtLFy~A^DH2WfrdJgi_C!+bd3+ou3nf=}(hO1CCAky}Ty1AT=EC5F^zUJ}!X6hp?Ckq4USZgzFnr~IQI6PguS*?v>3~0j zd&utTn$dXCNO#@tw<5_<@fD|5umHqzvER&_XKn5t{z1UG5mrpOkDZBfqi*N%H}l}z zvaUWV>RO(bP0&LB!_B-bieDD>Q3kr_+bK7ruH@CQFjuXJ>I)2JEbhRbi+RUod+Aca zFQ>-8qUbrF=l(Wt-%#J(8LF5}*d40`SiL(Cx+*DAO?d?S9|X&_K(R#P`Dflt3I8<- zaXCfpF>7AHk<^Zq6*byrd*#a)8RMjjz>Cx}Njo!I<76Ab_=$-^3HrE6_=F-LY_SSy z^nouHJPy6nA0 zXf4T^PCtCg`5%LmF6_C$O}(%ek~dEIu~Wp!DiH2>#KXF z?_hYO^b5r@4TWc39=!bHvQsq|n%Hvn@?@ZqrUS~f?;S@4bmGFg`B)oz;-*i2d!-cr;0xMe!}q+_Bxq3w!5voEX?{%}7v8*qE4#(zvjRF5By#-{iS}Lz4o1 z1?^;bU;wEQbvsL4#Uwt+{oMJG<&+m4hukRcye=OSYF?ekGRmAX)Hu@7sbsjmoGK1=RyZVwmmN5BuA~y>${+E zbV=M4a*)FC@SjobTCpx<9Cv{M#%rl9547>9oiUW46^LwVcT!AV?Oo84|9BjEGu3%& z33KHfucnq`dBe!)l(0}Aq69u7Z>FM4K6Kf~P2)eNJX9Al?G=;Xb=peQ5;wi!g2!oy zs0qLcb?P7jCA#UJ+7pmB=dL>-&mNG+dj;5R{!dgo~ zn>GvAd$gJNB6j1DmblPu@{KlWYKL^=rkuE`-&?f}!u=XBHS7nHipm_aqao=dC#MKr zY9?YKxY)fa$I-FkgY`DZu74BQ`0Dc&P+|R%z;-X-kmGxL+_pqIw3q~qvEjGW!HnOz zQEsr#5?JjF@|?|e+3vc}=GxEZ@_!dvZ^avv{C=Eya^sStiRltmlth)%$4yQw+bk%S zWb9kLSEjKt+~nfLi8xCTbm}QNS>+0AhZN)xalT0Lio$e9+Oz&~hmGSG6RYtRoFx)& z2v(|FXdGSvyGEtT9&tbmPSW#XE^hzOBV%?3^#tjC&z|1gcKP6h9o*M#kDuv+gCa$S zqaI}BP&y1w-PTjOZWBU#2r3f!2z<$&hp>sa7*YwZ$f-9%Vh{hH zV%8*?YqT@P3j$kml%_db)pM-8(!f|ZDXov~UNTL&OO&}aGb6Wd<<`u+0~3Go%nl4Q zdfQlDy_|~~l5*cdkEEJq2jC$6Tkfa4;3>7AMoQ`HL+*vV;K15hhd?+Y73=KT6zN3E1IJy?YK>dz5QK9idFz zWws#?4u(02=}zEYKi)v=(Ymq`emCYb){@3+ui zS5S9gAy}2$2bIRD%v%4Co1Z$nJILlt+8xXeJj@u9p2NIvSraRjKDRPw&8vSw6E=3K zzLNG<3SLGvL*BM1<+?jo|GJW#z0%&K;m@!#S0?0|)^TXd(eZk6sUDCWaF<{eN^H|O zr=C%`Y`Z1k0y-5dxTbzqccgEV{bKeGMJW5>LsnQ(r+SXx& zil56K*(S0F=C1WXOAqqGmprT7v%Z2i?!hGA@br6?1y`+pxnIKNp>r_>>Y*9<3%qXg zA{re-NnQdSZBO}im0&mr4$zxBbSuVqC9nhUcpGq^$)__U_lCFe8+Jg)L^ksbwNSZY zG_nQe9Ea(LmH!HMhfU$j)2*9oLYoqnFIH8ohRYDE-5ky|6*&GZvQ-B@SFNhO@LYAE z`63|J|G#iLZ;oi8t^!Z|#}BHG#fn?yFWI_rPaf)ILC!V){X3%9a36 zR5B-RjJc92{z>({1UA{@TEBl02u1LjxL;wiIkZ*|~(ZTz-9MeTuY>rnvujII2$+7<-hkuqp z2ZQ0WCPBJ;`yZ5PewO8=5yx+*7Y-Xl9=IGc*08z`@-x!LVsoTk7QGJ>HmASMo^xD* ziyMhoTFYp>tn#{z(z9Jbn^xv@x7XQoYA+&KY@L+{tTnL7f3IN4;WysAdiv(bL39&Y z;5U5j-JwuAZ|#-K&IrSE%ts>t%m4V`UST>X;;+v^ww{WduN3>fQ@Q^$2aV)MC=Ejj zr|c{kViF~+P%jH`Ccu3k;5Oypa$;YYgB!*(zP`;A4?xxgoNTePd(25sRzTsprTHy;=MUbu?8C!ea9p5#8yg)Tn=(5#B!JKKO)|vc4F5PiC$mz-lF-v4 zqe%yT;dSHb(^F(bi14$jeQ_qd2-Lm|kC`*U3lk?N4E=6BO297)&KX>LlnP!Duczji5+EhI;rj z1nfXy)i7);t-$)Bbhu(lS0|myK0!VPxv-?qvbAg?#QI{DZnK~`44BAUalL}6H~;tS z1PT#%!!Uw;8^058+#yM5kNPC*txNwgE;dPMOjPG9hep!~} z%GQec{q$q5;*|j9stIku7ujuxSy?)Bpj~?55Ic~{tTnf!I#)TC`8ij;q*(c8wo|{R zW0JsA<9E<3b5o$^jBmXDzPxUmFXjJhRyGa)Vg*WA>b2%jKpUbF6{G?w&iUkWC`|MIn4 zr`H;NN)XTl6H`YT=moA$cOK`$E~JQFk*#}a-CEq6GevVsM04_S%S3iuYFa+Fzm$Dk z*0VO7f7w?SzmC3T2NCyU@5B%Mb05&PnJ;Er>|%pNIZJ}={{G1_7QwFN#m)6~b*t~y zBsSOI3p1$k=E|%Y0ep~e?~AstC@*+LQWmUc1Irh48dYh%v4AeXUE*1zC)Hj8A|`}l5ggs{hU`tZ^i6teGLoB; zscXq*VNvG^9TM}o^!*BI6l_DPf|;rb4EU5AeRqPWjBJNpe44%T{e3p_x9+*wJ&$MG zAJ6_mmYmOEdovkRZ} zsIz<2*?b@kB_SD%5g(r27Tnm*IrYO=ykPE|B@gzXkDk{&?2S@p>)6EfK16;DPEBXg z&$`2Xs_A_^OQT?et@xyDZYtIu=f6+g*ChvM!XA*V7KBiID)nT%F0NT)I?2njIhNb7 zNt%tO375He|4rg-yIA<`Uwa$L?Fu_XKid(?ZId?(PhI}@G5T&(z_-2dhJMKHx3g^R zfx@SdO57Ku-azWlzkM`*(r6ZrbcZcSy@W{`$@*UG9?9w%p(5c9e5PXiouu};I`Q@_ zUjG;x{DH!KIqNIdemRS8Ba}uR;4frxO@P;;gH*WCcK#w!;Zf(ZR0%HI+es>QlFiY_ ze@ltOlfC>`SsS~9ggh!$sj8c@b;+H=d3%OnVEvPD=j%_i`fXm%r&&FpX7OEA9p)wJ zvn(zg+-4LZz@@?siYLouU+wl}**#hOQfg+>i7XDT8GNc7sqj&991t(M2eTSrLVGN$ zOPqAn_Yp6S!V|3~>Is#PRfI#ZQ|w!_SO*`Ws7*(*n*4EODmVz)_n0cPE6el~q+jWqen@YUvVynd+8gpDA6_DLri)He^78HetFZfHo-?wmXHj*qD8;K5XA%j#dKd+RL^C!`jRzsRZ47 zCM43##}gtMcOoGRgDcJ8Io0~}opQ$ghjd&6_x(oYS)a}~qyq}Brrj^4d+O4=z`&%* zPN(&{uQ|wO?E|Z|+e+#c8|?g}l&p=47i*LDS%Sb{#mfXM&d?^1%EG(bfMiyr6i?#6A&{gm^<`qyN0QpRC8zbcy7GRM zS|h%49z3#7=($V$fy{oHY&`f&LZ7DcL;5bcRb02czJe4??%JB_p*AG=5#(>BA&XNC zCsM7HnQqRFo+Enq5xxD0o=>MVBdVY5S8_IGvb#y}N?KvpmX$>m*A%QQk6ntcB8sAGTxETrvWN)e|2_96Ex7)Epa18R zPkZm3nRCvZIWu$S%$YOCxkFt39H$hu%9y0#aR1HD=xt6|^duS(>&%J8?+{@$Wf&Z{ z#d{isdM7v`ULeVoWR2>y8x~wadwJdnPzXGIla+U@i4hx5E`wz;E2u8dpV%+t%XT>XfRWI2C#l@kS~lR(NJA>*`?8!vY;iDqe8XiI*O%L!$JMWlXF@{{-C%ikp! z1@sM=fkS%F8+<36*+~=$8b)67F6ikcU+26k{W=ZLcd*qhV|QxDK0g+Ib$qtGMR2eY zip=WP$J#oCbjn@J+7fFYnP$S#om4$Az67EdQshl?*?nM#i51wY7D=VtM)`;%pe6c) zBku?uFNR%P{55pQ;NV(FTtQ=%gAwcQlKzLjcJR3{7D+BA=)E5~cx@zA{3N-qw|?%p zj%*wyd3p^73t=P4S}5k=)1T1rcRkQjVbXjNKJ`q-t_>z7Vz+J#bYz-SO@$k>%qCcC zC4rE;^%GPOyv%v|Ko?@CVRZ?a@i2}H_Hghf&?+3E8sydGm1$n78Y}u?BR)i5uG74- zkj`B5Lyse5sc@LSAyQgbXU5D>ZN8bzO7NIyE1}*ByMG;_!N@NEXN4Q-9j1&VzV46g zx6Tm$EOTqCW;e7;;c>Fm1LpqD3_f*cs6~cq#4;uc^(qM}HeM6Z$bZqpbpMTDJu6Yk zmT9(jNoT{A!tZ2wTW2KU89by9;LK$kMWj?3?~_^z)D|b;O8-Hn>=!A^zws+N+S%sl z+5BX*%@JyI2%p(Or+ofAb`NuKSAPJBtD`F%eb}!{w0*4XE?>4r@DmAeCWbqSkRI_CqUR1Iu8evwrAJuc2&DQJ zNy5buJJwtW;o6qQ-vR5^11qlCm$q`#gj0!4{?@J<4Oz7V*|lsSRMPDV21+C;4KfAkFx z15F9O7zU3bkrUoPQqGqMK5|O`X<(wf@GuO;c4e32anK;H2jw2q}XGlBL|5-IUBA=>;vkRXEPmfTn zy8F}WKWAr%IF+~SqYshko&FE1$tD&0sJi>3>ObRb%7=0BcX9pl?>~A6$;bQOsm3W( z2&N&#k(WF8BwJtWIfXcZu^y^+7BKZo6-XX^syE1V_me+{>{3Df1jl>DXX5UI)z@h{ zRrRd^L*plQhPwAv_aZRt!_+#YdjFjywQZpR=3qKk=jg6(RMtOmPTzYm_x>d;JA3^n z?&`^KPFsQ-zg|4*-c>!JjMym@!sP*fr9dj*Gvfi-DJ(S@t|n zd4yjQCij}^PL;m(``#d2LzvK$)s%9GQYa*%_)^^cC}o&Oo>;WE|#_kMEcbsFIrYOqsX8R=c(=XbU#(bZQ~_dK^Ex~e*~s9N~zM5M}PAcfWy z)eQ@%yz$dUp@4|m%}#EOt!qR?sa+0VH6jYpIzatWH+C_>iz(+qRnx)l?hqAcR6QRm*W3 zG6?Td>NeKQS?5(9IfhoZGvL+k<(TJv;zOh1>Bn?3}B0F}h z(U+~lSm=GbQCtz1dfW5BPrFTl{pFKHf0bDR5EmRHTp9Q4pi_ok%oRg`cyc`82{cVTtQjt;nle^ZrJ>pkS)FL zB9%y5SoO&`1Z}nCa!UB9Ze4GscObcR0OtcrlL36CZ-#uy~h0XhlNZpj}-=9@t zGFS0zrKTmjrKEO-d0ry&0@Xde+JL^+%jNav@i;d>-1uYsqm=67Y|pbyR9%h8sk?yA zd-p~3e-54NAN^c)H&-nzrtv!T@!QnFK-_Q$vj7y@|kWD{;G&+`vl<7c6Cz#W4(^I7@(t}(C-0;7#c5w|Rmk90*&MWl#m_jYtW48Z@(51HM^wfq%Jo%<;AKm? zD)iB02OQStuK@xl$LI?=zRGw)ah)dCT;8b!0k7GH}57vN3)@9cq>YcJAtwU^4#Fp?uV z(y;d`{MzA7W5+>;zW66U$AXZX;plMxC9NjJCXkdJ?1>Iv73!aMP3(%F$k8`R zITGKN-2rt&sYYtTyT0Lf6z?GalOq3>>37VZzjTL-E}_J= z7g=MQ!M&w-X0hr#W>IRX57El&glQ zQ43MRMB^3H1O5_!K0Y-Mm(ow-}(v z{XW^IRNPreZ7Tj&!tY_cVR`H;hA9`bxIBV}HJ6W|AE73+Ln&+B(mcG4J*0%If16Xd ze$dE3^xBBt0I51HG>v#S$<)>qP0^g0RhhmP;(Nwi<;O<9g9lE(sKL38pQZoZ0s39o zOe%V8KZ+Ku-FsUfNbt$0y_(`qgrlQu z$@3n<3*#}$B>34s>S|sq_76~T$=s-#n3dygIYBWbQQSXJJd-2<);;PkA;$Cdc=Q(x zGsF>+NQooHRWd=>N$rQPyV>5L8e3hwR=9YT&5@0EbUMgK0Y9OQ2&&$j2YYllnkxk8 zwg0=T5+sUm3{ZC|TbxDI#@=5`Z4AB~8ZQ%ZDPKgtOh!4M>iH-MumAn4z#tMKFv%&0 zI$I1fjM1OPQ)i^U6I+(R2@PGex1iBgv+L<^I3T{a%hICVif5G8@1I{;oD zqQrXuza0E%s>m=r%gwKV`_`qnXs~i8)t~1rL1O~f9O^YtzDBU#1rja?V{DY`nSnW7 ze9D3e9kM()qoY5ft~a5srw8hqF;G_`E4Bc%lr%kFV1RyT$`89aOr-pQ?wKK*L&fA4OYxakPu_RNNfer4V$muX&WwJWm=>~UJox_F? zZOtbA9JRqSw9Yf6?Lk8d2EPh??hR^T912ITz_YNG$nDR)sy7H{*IY=hxY`06pfs*l z&#x}bbDSB6e0BLr?PCNRn@;3Yn+RWz%e$9+Wst)}O>OSRy$~5@sYzzYGL5)mgFWSxJ zTK*lvgU}>V{PkqwFf2Xdr z8#w)v1&JCL(la1Cv0n|!&L#b2VnTM-Y#sMR3Z$nx?{t$qAf}<`$alfCbfY<8x&m$9 z%6L&p7J4;yDt|vftj!GFr@?DGf$l{1-@oSSyDr?a3->S_&wJ!-ef9<6#mVSq_g3VE z9ZJ8Ovk|{Aehsg4rvd0)?t?23fq{k^@j_mIWU|znR15LGf!1uA@A_C8w;^{+^Bhg% z@>VZR_HCZp!Tb$|jt$mYcdZ9+vGRC_)mK6j4lu8-$jg5kESF`ZfAwU8JDt};^lXyo zJtWLsa~HLac#kDmNFCkXC{^woe6yn^Sg|m{Cr87$pNuP)_c0uF_mzy1vF0zIEDbA{ zwFx>Lst>q?&O6w@F6qysC0rOk4gWQM4ij%kj-OG+dJPfjFCb8U4@tQ9O1VTa&0RR{ z%b!gsSJ1wYY<5td+b`j%JZDPP&B#D`=0FcIVCa(+5qt;?02YT!b&4_$ErLM}?+sE{k&hC1hFPtXXKwDcPWI0t zDEJ9~u0Zz^wQ^+~aDZZ|I`{a)!?48RwQ_AJ<5tR;sAGRVH7mX*6)a-amQ~(!AIj?h&r3gFC-K5XbP->P8`F&bMJ2|ymnHV4Zn0l2HLF3C>X=P+bXK}~ zoxw3ms_bA@?q)Bs@oIY&9mv*f$^qymhaa>X}gXB>DUg_SZl`8K2s} zV^UH!9jX2;!{myZu@zLA=)n~~+kCQ4BmP^eEB3!JV1qT{tJt);jrG39Y+0vq2Pf6n z@v*-%*qu>|d$G+DTcgs?P_oH+_JxN@{)K}5tx=FFs zOnobd$M#9a)yx;i@U&)<_#5VnDm?vWQtU~TSK#r9~8+b}zwB;*CE;wO({hOSd#}?vP-05cc8^V}m z+{M7EVO*(tUxT;Uiwt(ayxW;A?H?mrCjdal1PtRUMt|}`AcHSlseES}iww_q;{Y=! zwyJh3pAUI|F%*@2MT)0BL0~)+DsnC4gb60eI__dT86Q>^O__FPR#B18)jektuk{ra z_ymd#8f_#uP~mD*Y8s6RcgNR0eE!$sVdpVEW9SEZ1-=ufg@{94;q%78vPC%`>m*g3|{HLwDdMUIWeD+IYh2KL?4CTh!>)w=6lWCpZ0T6_(moE0roCf|-Wo@& z{h_MpPjAJ#qRq#-atp^-NL0gfkTd-Q87Sv9754tvrN~482e# zE=JA7R|j|uFUO)OSh#hIRYi{-H9mzAq5HWi3M<5PZ?1AtuoT$+um~YdtDPw_+RuzP zbU#B-M;H(EAL2sv?38R8;_Zq4KtQLB1klx0MUTIWZbIZSc*6l*{C}bf&ZvMZFpk+a zkc`UIN#=n%54EefD$zK+s?MXp2d`5#Gx~fe|Gui-toJ$`Xb5ENW}6N|VvMsemCeq^ z3D(&<*4Q04wh(9L5NB$X)3E?~MwUy*RS7)Fbsga`K2CdyvK+Kz;6rSZjAt(J#9Yil z?6JA%@+E)1!e`Itb9b|7iJ8Dyzfj@z6DFyfOG~;@;<^uuOlkVf=VOsLorI;#-X#p2 z=B2g~7x(C- z!HItQSbGdy0(5{iXG1X*VuT(rz@Vx_OEASmhw?#*TRGmzUFS^e1UQN-#me zAnnF`E~hC+mx=xmE@03;;tDcjG$-}~Z-ay$;v%W!1NLzLyvpb;m7!ZI1Xn6IHm<2>SGSZb8TfrP32eg&!~*vP#Kz8DYz5mYf<9y=!``9 z>3D07x~M#2gHFTS%IK6z^>=a1qGVthV!2Jzw(BUIdU3)_EoN9cmC3N(z$4fsT8}Gb zYS;FUsf>=V42`K2CM2+x1LC^qSP9#n{!+X>6)hud4CBQDMoaX17$L7xhVW|t6_wGV z%FvaSf-wPMG|K!XnxCLI2XC)MM0zK;02qM7zjIZcdCMG9A&BNCuy&pxu$6RmX2Z6`wTdS)FY{5qffOKU`ubK0e@aF z4A+M*<^6`h^{Q!M)+xWhvDqkKMR@?Y)NK zZ9V-bka#BgiJkl;PraD&k!E~vknK63=uaEpF3pv~hqPt>sHVfZ>DauRy5FvEXE33e{d>H=TV(pn{T8RLvmWTjN*aBB!RNajmNiFtf~{X|l8ne{c+i z+V~~A)Hb2?{y*EJefH2!yYMR2LcDQ6-h>wtc{2L{V2{3P5B_}iKYtycihVJP<{t_$9&_g`?Ts zC3b9sm1z#Cy3JT>WE*$HgNEU`L%NIX7z^+LXHc=a>MpeNqj4E%UdeELgD(mmjGx5e z$<1dq8EBOxS?d~#7?==@=RY7uVr}hsZ48nOl45E8hF0%nQNd4)#bbx!SVxL~k8fF< zg+q7*0y*%HwqrWT1xx(?1I)~Cf;w+dd2k_~{~pK5vu?(on|dUg*&DTNV_V!P;l-}k zxeL8fTpQVaW}SEYew?;840i?<#{INbiT$0pJGfRcek`{S`bqah z{@~2*!owtTTleR}AsejmJEft_keiww@THPgi(#F%ncJlSTOO{@#{C@g#bDD@2^*Gk<7`Pu2OGCa!LQ&dtY4$M3bwz@KrG6(DY@*0{!NC1t zC(fIZRjHk0nl>na2Z~N>OIN_}WSdM&4Ko!@dG|L3?l;V2{WED%iC^j)_|)ybyU zIWnCN3c69pYMktlI!CTkQV8o<-pLL%u*2#cS2!JdgJUG}L_GLobbel@31_4VkK4f2 z>+qN+`04RBJZgkr(DvYMm#XgTC*mLw+nKSAdx#oAm??Yi zOmHYXUzTJ4^q$xDF4#?MS*Av}3`gmR#S+hze9A-lFg{X=YbHKqg_)|?oo;s69GUn; zU)#!o;dn}K@E*yzz?)i11@lR@h1qW;8+$Dw6AJ5_<(U5gT+WLOumP?Ly_-)@z?20% zeo-Y`!rryYMn5k{@ca@y1lxhS{_+64zx;o|d-kXBE|&ZR-i`ry&;Kku2RrdH65qux z&7e`z`@>J+bq~N>|FiHe1LoiIQ~FN-6yDY(JjY|@U>>NKwy%j}lH04yx6KJSX2%)- za!fhG+Y?Gm(%G6IcBlO?8>jIN5BP^}+#J?0IU8~UVQJ8q{6!dJ4yQ9OHgM^Tp}-t6 za2aO7z-i5E3|ywclLOG9ZmI zhCYA_2LSl&`cK@%89cOa)%-1~>6jlC`PUPVuv8qB3B!NMM0kKlxE~6|jUNy42%)!N z&EA;gk+tgogXf_Ec(RNcj}O9=WK4W&0A5i!Kjc!84Zt<*vKHj$AZ#Cqde-yh5>?{vipb(w9~OFR4L7ne;urEjSAcPF(C=t@eaIpjow7n1euZ2Ul2{5~FWwr!l*g}ZXXy~AD62xTF5=r@*T(k$KzrPFNqe~O9Z&gwww+%jBxDZ1q@BIuPut_R0l3r4 zlF~B>Qf}EWLE^I{So!Yp39*4#8InR3`~6SgdgmnJx~-SXypt$S$b2n=t0o-L@KN?> zIj)o`_Ujm%PC@c%bEo^0SKN6w5F)2MLD61m%uR@>9Y%sLNQ3Y{IKULJ{=ek^mp{Xo z*xH}cf2~Y^h;b{*un!_zWzlDWp|%@;5G%-na~e3}l1)ul$C`Lp|8RLn-4p^vM*(j} z=rP5OQ}dv$Y#PCD(`}kpc438VmdcLUIwQAnxB5_u ze;Tu78WBN7|A*3$Kac(|(sVv{eujJ~(n=rdw1^H>XGp7mT#uNZ&IZQuCksm1@@ab% z6VqC@?`8sHocO`w_exPge&iBq;VoAqT|%ta?>e_k)i~lITrGpVu7AaMwnHtN_p-NK z(VM{+UHePlE3C`P_$;$K3eJz>TN|{)H{>Iy@FT_0N1(0z&VqI+a?bo`9dPrPJP3r- zl(-1D^mb+i3UE=thHKMSPt9vb48IMsjnAJk)L&23mHO&l9}Xwil}2i(J_J>oa^B3h zE=i*KXaLO=8O^=VIuL}@@1e0vI7X?D%6O)9Wa&r!nEMk%fyFH;Gap1=S1gXB4E1Nv z=4Ss@s=xsma%aW9eEr7n;Wd!cwdSc(kSSMTn8f^1fqa=@A`bgHsz+6eRIWEM9MPVF z6hPK&HE5Xk8xBPCcaGahR2kojAL4c*GEr%u{m!JzQgl{}$on@2ZAp;n1;+0Sx@U`BBVtIlUu+SHr&743Xv^r>7YzBC(| z+;DNnDN~`o=c0jAHy1FB>84F#LuM){6V_7wpbXFIDWvIEc#qyqOEg0l}NvD zC(YHun^N*RJ$ufOi4~jhSR#4t&UKV5af>cr)Sv#|q|}GMH)ZPUzDK@?C|@V1Z#{E} z-ARf|^LKGj)czmbUy9_#QgVTQ<7p%pA{mzykj((~Y7b_t&$?!1rFzqxqMZ{_soM2f z%G}QN9p9O>5rZ0MyYYWX+YI4;f)Q!Q(|yuYonCW6xR)OLzKJ6bi!ds*UdCD__jS8= z`uJQ#k9E%;H)C3jGN@#n9MgT%xVB9E!4B#tINB8ZUQ*3^bZX~;^Y9IF-!Kk4w9{Wq zaa=QY#?1P0>Rw%n^PrScBd4S~D#un|+f=_oc~-aM2DM}S*cmsR|I=p$JFZtdY-49! z|HbK=DLV?)?lEKM-SoxyBL&QvvMXRcICW~NwQ}5v6SxO34s&k8F8rm%g(#8yE%<1> zJ??rh-ftbpXGh15+sVZ&Wv+K<8OHPdW#e!Q8Q%>1EWRF)`S<<6r#HQ{_JyXU2W#fHJf_cL_~n6FJ4`8SE{@sQQQxAhU#@JARvy?+&Vp4f zi`zZq&?3|l+wVQKbpDB@H@>#C!?R5pSnQX!YL9TKJvxPz9k)RtABc!qnxB=bvOKmV z-WQ_B?jLbbNW5rq{Z6hF_6~6Gm5!@^dBMjz^%0%Qm{#UmFQ;+2FTXJLK12|F;ZF;q zUsY`5ycuP#)!3Heh@vu~m?+`z=?TITP$4`mzmYF!r7Ze3MVa%DuT?J?UKf0A_S4rm z9hIOT`J-jXPgQw>is+9i;Q1+itQ1=4OWUsQx3G&{W*k-4yfn__c8QP2T}$GVPghsu zO<()9O;Lec^=y)x8ld1NEpJYlYaxz#RfIXl_#cbwPNF}oW4vcAt~=O$>lgGbcDqG=8$Co{slbIooH*a2o=flG1MZX8sd{z981G(-YgQba{a0IDZYg_r z#ZFy>iygDLu9M#XAitlmxN775TPs%W*{LHsKC!r_Q97(^l4onB@LmZjM~xK38G_1a zxWdbnxhBVJI9^Pj8Yr0lB4WM8spD*_NOYV!PHDrsWqaOO1SK4IT{x)lZnHFxiHB1e zBgU{Yf{*7|UYV;T`D`e26(^sOr!e_kSmw%4JR6J3Tvx=aYMe^u@PZ6RU(HMn&3GA? zSR$5G`nGiSr-UF@T&5n8C?J-UskMn`Z(*5w7(F{VH6%eTSMFA0b^Tf)Of{68bSrP1 zmM1=MX;vcVAO|*5dT#+$zlT$MpRqKbzbH!+M26Dv6=}xJ7T1}JK#@#qqcpx0N#1~^ z`Rj}O3b2jEsbdQ*t}ia4ZT@L-oxI3&-#{{2X>tAQBH2){t1xDyNIDYsD=NrfS{oOv z^pLni2J=VWQf%M0hjI{jd#8K47(G&oE&pb2{8X2K=Gb4;SAYfuuu-A8d&&VWOgn- z08;bhY{vhXsdWBy{55g3p51mliKkgo0}B{O&;~e^%`+X^{bg7_B;Z&^13H0r9|$2| z?CU|G(xTQIA)rM2VuA^xzZwMj6T0^k#OHf@gJ(P4vMET=N-a$_0FDEp*yn@bC7QkA z0h;F~X?_O?NO$@fntKRCPj3!{G~irw2qB-sO)U-yn`A&0&X|)Nlkt80Q+&_J_#6!1 zzO;RmvF`tzsYuiQXuC0=@1#}$Obu56In#^#ygE1Cv} z)_Z1#=4d5rny{CES6XfVP}sPvSJv{X9^kk7v~Z&{JIwG!8=h_0)x#4Q<9E0x6K-j% zh&On*NeE%&F4o=TZ986PoC*#4u$VEg3)*D=J>}6w<-)yWfw@hipLZ^xZ7@x}%h6z( zR%z{YAKsi%)%Du;4CD-GckSpB{idlaD_Dg32H==T7voY`6Vf+cIo&_EoG*>eEf4Dy z!mR|b2g0ONgcm4~Sx{5U<8^0dL?^7K>V!kNew||Ft`tAVwAqVH`J+$OWCq6R8{@sf zQ+8d~=FW(wjf6TY-<0+ za*V;zi4rB1l5r^=m^;a`E__0;l63q}f)0aDQM{|pz%f3+w_f|& z!3-JEv>wwmg5aS-_RMg>G{HtZwr3g^OfzMM4UV>xlwL+3dCrt+Yaqg;J_x$rQuSv@ zbY)0%>3%}jtC!MMlb}oDj}iRwnXU|EI!%sEOM6YuO%}T@xVed{ZXyiAWXdk#k;f-Q zWJ?ZtH8kXHZ74F#HUu#dr}nFD!@KjO5snW#FCE~zX;g|-;NW!dRLN8*ZIU-5z`t^C zRg`~*@U&ThXKOZjdZpnVzrN4oh61Nvd(Kwi&~N`iD%bZ3V&qq#%qpRY3gEmT;zp2L z4|GV@x`4W14TqkD|4z>hMJDSR`zU>YMmuNz4fu=Bv5xL-#G}`9+*iZ)RWQEB5A$Ko zWtsYh3(aGh8tvVMP=0TvitA^b=d)V7S{!_%*~7D)ZaBJ?tgD0PLmE@^RE{AmX-~Ws zzRl6$a6b*glt}wL;%jkuLxZY__UQM9VuFopR9n^*TK%6h_Ur`oaQ5IGz zg_X1*?<~-lThW#LR#ctpPeotyYXSiZ;OM{w)P5bs|~W$s`vwLQoNTh?OWgVV9J-{I$!eg}0H8>bS?R-0ty<#kaL z9_etigSSaOImi)vwN#DEaiaxRel%QT?=y+7m-g+A_i`ycds3SYVmr^`=hSd&>vfa9 zfS+&$vHD0*(GxX+i_(rLEXPmY~;8Wh@zv)B(n~JpWf-g;hsWK@6uIY(qUkGIM zfVQNiOVnEXI^$8b6{oei*tXK<=i&p3U8Eqe#~PANFgQ7r(2Apu=bBcwr|@i_ zGKzjG{YK@$7%Qz!QzXuW;Lt}$t0kY8lK>rBni zqO2Qsn5IUw#^v!o9`37i?%2^dcc+$LuFhcim)2)3SXnug-?$~KV&$%1?9^^cbEPxk z;E*j@v$xo9AhFH58P)}aeWT%88|#WA7C=NRJ{+gR(G1{p8Sjf@TE^21ilvGF^JtBW z{|lSX(&yGbDRn=l%$?f4@95J>R0RLd!3i02D4*6J7|Ulrk@jU;PjL7Ht48(iJH5k_ z(b{|LY%kAzJB)eb_lleiul-?dPT=6lqRx!=zkbV?ARdx*@R(1OIer|}g5sNELn{0K70S5sNq|fafzp-P3*3S(?MRmopJgOO4Ew$~ z$I?`hcL_$ucP%DZ4#c!`?COp@bXe@eF%GD~Edau;E^%P)+R% zcO=5)=d@@Jj4pm>qF2KBv6|*OO4B9NMu0s0aPveWtyjmq7I5??H>Q0SJq;C3;sh`c z>`9M4<-69>&M8a%?NXY7QyFR$$YkKuh8oIk;8G0IE*zdoPJOSuF>`xqSQsf0Dczat z=Q5LY5DW3UgvK}7_SD;VbG_j?;a*(nM}tLsmZiOpkhEu&`?Jd0>o`P6kqZin0onGD zZ!GMDz2Qbwe^sc(%4hZeI0ikNx1%!~9AqcOPb`(!JCLg?V>ap7%jKXEawh?wcnzQR zTTOMxV|kIs5d5<~O^u~meMDuzeCSW%1I6}fKHIf0dM!}~w0aXR2o7tRRbBnNOQX9> zg(w*n;EGp(`3fSD2wW^tERx$b%>}!6^uYM(a z%9PP+KwRPePFy@3?JO0x62wlOzV!lZYSgM~2o|*`%kjI~4T>#U+Lcu)MIAi#ai%Du z#AMjIU(SI(-ZGQO)R?!I)~0DC(GVsM`OJ!3rlzVBD8YbJB%$&tR>S(lUX{m&5$$uJI) zQKYO4uG79JSr^=(pPK!ceNEX7Z_p4zG>n%c`{QAU_k!pJzlN^x|VTC$^k z%MJgm;D}Dq%ke!rVneK~tXZ<6)#(&RqN#OmvdezV4X-O;2l6CN$c`&hKM_X-c!IzU zu-`kmOuaH*r{gXu&QtMZ`y^rjILcg@=EzpHM?oBMmj&nL<=#VPxFVr|=$|XVE6B32 z4p}&+F3CpYU*qau#s|v9=1{rbpk6LGf(rU|N-DX0uHctSp*U(GsYge+ArJ4#k*4@x zl);P!%-%c7`sNX@rFjkeN9-70Nf)h!qohpRRs0V8tL%0K*NXdBQ0{AEO%$- zb<=mS%`+I^O|1HD=FA-neT8h_9_GwAi~iXHUnZ-53ULs*8g0>ILwNth9=4BB6jiWl zP7x{8FRvDk5}am?ZMZf*#Q3Hj@#~nT7nU{!9P$oY1IJ>`s$*?BuE#N~!JTe%lb0EO z&5tm?6|8F=!#7W#Fx7Vl>k2TwrR@zmMb94CqVxdNAf2B?=>};xu7S(J-FOn{)CLDF zR`3&_$JwFbJ&Iw?in6CXR5>XIkaK;4bJTK>v zS-d{3_Ci0tTzqU88YC>04ixMAI{uS%NxYyuBrB6dE5Fa31BC$3|taR8C09{AWxf)2ZmgGn;H;- zGnNg8pb^`w>Wdc*K~u4g+BC8Isw&o{h`)G0lG*(IMGQz2;LG?yS?*Roy)=YO0a@KA zi-K^BR=9^0VZ`6iGA{%iFTAi6##6r=2T~I%jrReXVgtkr$t-7__r5g7d2nB6Z9Wzd zwN@TZcDV7!DXrcdZ8^Kx-IA-bjonu=bJKt!)W*;tm+Qy|DgcZcZGtPp3kC}Ei!tZD=@Cp+7bR#u1Y_YBCF@ zQtfp5stdiD3ZQV6Gp53={%|I@wF;T8Fh{S1hntkCK!5UFZzd<3WGV?iw)yE$Z2`(P ze-by1(;qntoi#kaKf@e_V_c?GtOB7CiFM;B7mO07rCYV(%psfh1AK}(nqn3-Qoj52 z=T7%#4v}_|Wy{fhRN`-OQzn#Gz2Q6k*>5Ek_OKx%`hy9ZU2OmNCgDdi_+Wclr`LQV zDY4D(kkyIw;pV@9U62Jo^x2Ia+AUdQR#v4J*@qVeiik10wq%XkVow2MBBNX|kD2w$ zFACq&c0Ji(Bb6>JI3I$SJYamJGB3`LlUs!3C1~($H!ZenAv(S#Y@bDO#(ynb)0-l(+LF|d6m2C7B05rxFE_{WMzd!mg;bm_f{N5W7uc9gqDF}^ysIa_h2f$h^P z!qD^HEmvpKY~~E6PjAPKMT+8a1WK<+as4`;e^~bF*baIO1_t9zvt1Dz^*(PfxT$Hv+d2&J z*$E%cuISp_z29PRPrz6FVw=mGu`U47#z?tZx{KFPpl}A6x?bgPaaDT*Zr)Hn@*dx| zgjSx4Z+2TMJx)*d5_dHUKUjDLg(S=yz1PANQ3{n>uB6Ig292} z&qf>>s%Sc%VH?UEBbVimp0}JheEJ>T)KiB~PrPdQM-l0Dds)uZy4SN{jr~ZJKCJ!9 zK286o`p5|0cIe^@6~j^Tm03l*kMeJ-$>doyYR+#{UEju!PSZc3w2fvqP5DxDWVGUN z#cN|fd+fy6r3a@Rwm+s{dydz+-j4gqLZ97#ITc6VdU!;2XgOz zIeV(jlaCz2LXt7?V*lRVYFoZK9Msz!zd{0j-albi;1if;xd#41XGPBSsnwHPZfzx7~c3CScVsJkg=Vl@xO=uu9l!DF)FN z3=wmf&`tDZWtCygEDNsxA@g7nGx%)B{Z~Xto4L7y3C*OuDCfG7@gIE$IKsi9E34l3 zk7D(y>0xbZyH*``lldyFO$ob6&56`?M#Ir@`wTr=7MHs?@JZZ;H3|;s)rhArhFRta zWbF9I+ip4eW!OQERAIb#9ocs4v11*M-e}G4w19OREnU1FQmMH75Bb_+ug7OU$af^Z7SzS1(fYIh-UgWO=@LPq$3 z*3-=eFjLp*O+SReqy1-lvKZr|}-ur~7uT=})yB>QwS`-pY^ z9_>(K-Men8?1ls_u@e^~Js*QtUwymnmU9<7qaSa(6}1hsSsji;X_v6_&Dozi$^&9w|ho@yaz$N8hdpb zWEYo~tG~V|ryoTj&BuH6NA_g(MjHv}ugd%Wg&ppm0#1K72N2%RFJkR_B-#k)0hE2Z z+>kNe;4VTn{Nckq+q-R9cEI4#?%$U?PhN((E?hjGjv{jYwdF8-G5d5fZN`pr*I~d* z;mhPT+HcEU2dN7BT|Kc-x$CdAx1J+u`4-_R;=RP3o^7{ctlIUe7%p#q?c%^XZZ(OT zUFDQ*6x~?4`LOP|lHs4j%0pd@)fVeo%bdB%Ma#5#4D)P(eqkn-Z|b{gIi~(Kt?$yY zU$peh)S+$LBU9Rz1D^V7*VE` z&DEI0SFq|3!#{oJx(ICDtHAwC45PTL9@b!KjRIBJFRj-ATfLU?{fWg2Bv(Cs!UF#7 zJ2Qt)pHSEkOusWzRfI*-yQB{T_+8cpodWAJ6v40gH{cHcDHa=jzmZo_xahH`PgH>53tA?ck@CnZgjgA34 zeKV1tmPUO~(kcx3UZlkuG~c_d0NS?*WH>p+fhZ`fwK{c5XOcqE8&`M58+2;^p7}(Q zkvz~Z zbZUuJRH?=(4SKA>Nm)M-g?3JGA3+|hHRXk)%$EkNJ2~W|y_8z(rlmCtHjQi0X=*+4 zs{KHepNEv@KgM}5GO=LkBa66S+CK?LwbZU2P7)vz1<04*VWbDzX&}!z{JhUygfro8 zb@MG~D|JG4U>KkRk`NL415x}@&jM_eP0G!Wm&gsL@jHeh4}QXn#09@D)h{jd{JJ#1 zWSa2n;1fdr`1mz{3;|*W7=qPiL$Y}DE^t@@IvOO2Y#<{AaSFuUMWO)1oTP7u80+s! z4n%WjV3C8*0S;>%{6};^dC3ETHY8z+*GTJ~ZlufWomKB8bar7w3Evt>_3u+Y(25&g z+bVaCD$e0%2KcnHG|ECcqpJ@(GHrXYL}^>LTfHwcGF5!8Jg0(RH+}8>;v%m!v9-PWDGGzcF3B$>+a_s1#*@Sno6Hg{p$oiszsJ|KSPyhts$|suRP+T} zXX9u5SDemrN^KZbIMgM4spQ#gSN4BsjDAR6$L1M>zrqP4@Lr`^oK_M^(U<7K#mulQQ#W-1PcDOJ1XD)6-$K;{6$s37a%wHT(YLoI7Sr z2}?WX^Q)K6ycwX?DyD%&xP)&Edll7Fni{0Uyy~U;rMj`R@~WnmansvJ6+d--Bqh;i z51Zk-evsBp%~xZX*S8llC!Wg)ZfI&ZGn+cYX^KtrB9)u6d(v1aTw9(=+c&EF19PM{ z)>5A1<2S5-`foV~M23;exiYFZGBs1@9L$Ylkt~VH7qIM~-W@9^*%C(8$?3Ms3LE)A3weql`w)VI{SxaUtPd zH~r}+b8dDWievv++3rc92y4LtxmbG|`>wU!k%!Fq;Z*8TE6$?xb>_u9i{4PsN9d zu~cR9tIQaBq#kX&){N^Ho{JycD0lGd$%ceUpgud`5AlczAw9H28mL5 z{~Th>4dvL%br%z?u#tM7aXNq*!#KHnuqvW*{hK!69r@<^ql)TJ@@xf)v)PqZM>Jfo zhTXX_oSg|6#s%elr{h>m^v4QGrlX$}3jZoZ_1c!>+?B?zwJlTxkL6YG&4Z&uSej_W ztIFwahzTABf#C8}AXbdNRa;k*uJ?|X2h`lx#jDM;M_%>d_z}6{?DcG4J(K$){=4R5 z#KMXSTSSK0BOP_Yg4yf8)PIs5$&5XX)6ZFm^^IF$j*>A0`_+iT;eCp3v#y`P@b|k4 znTW2F+*Z8v%R6tvf7ciBx&np%eg!hd+T*urzSz$%bxxtKgC9JT8d+$nGktvEfxxgi zYW?F(yNaE@f%M&(zGgVm!1#J#drfwDe~Iu0;pFuZU4wLBq;nb|#Ngw`!y~%$<_H;5 zyo<{Ny2gS#vxbQWR_VuecXNkf;gG5_yYvBU}D2x=$8Q-Ut~*hFmAx1Oxi zDB5DVH#h2L>r?skec6#2MteE0?AsRS@0aTa46cpwZ7N)~CF=w|*rzQ`DSCJk$v;jQ zawj4gO2!DjZbq}HAdOcch2s|{WJ~%O**v9iGP1LM4mcK>$+4({ zaW|NDm~Nb-(!a>hc~Or`K89@L_7(K#h?(9IS7t~96_7G z!8&A=Cr%h^$wu@t&i@~4RJFO5?cjayujET7xAu=JjE*W4MicdmG+{4Oze~ZpWUVE; z;x6m1?K~-_;^MfAf{#JgC^&*(ql$$4ETYB?5!!!#nM$~tK6SpKKlkGtm7NP!nkvNx zFR7m1@5*qTA$DK9k9J`hepaOw()h@Cx#z>t3|n&M7DiL~1D*rj@bw^jkEg&ChF-ET zb66f?3pkp_pzNQ8n(;KcJFm63?6L2pTBPjki@bXcS+3Y73?$2C<7KOm@&>ayRGh zs&rr&a?A0o!QJeNU1Ym!#v*55HXNr;78`*~)%Q=CLlkMt^Uq?`f73}Cke*V=_5Y8_ zyGE)%Qb3sTtckB_2)@8`K$PukvF_TDyT6k5lLmIF)T^of&u^Ejzf5;Y?U!(AOD^r1 zXY;`VUPHAXA%0fo!j3lTb$48S4-w`5OEIdYpQmX6J!jJ70aEr{1Pe3@$5mT<{%-^g*sYfSpq zul?Cvz3J;!$Nbq$PGHGA689z9?DFHi*$TgOsBEV`BK3ic^5!16X~BXTWMX5X5GeIs zXO9-_)4^AWpVN$(jMCf&-FZcE?p}bglkO~aH3JJJjCHMKim@1nQ-hy%A?DhO;&BH3 z$68o@`>rF+VnFLe-;quMqGsZrW4X_wZ1XRe+&@ikKZ*rjt+hs1>!>NHbvrp8vnEP9 z?kkQc8@uZDRy2>)IJla=f?zQxd#y(^rm7LF5#^Hb8NQEU6 zrC=g()Fn$9kC+;D+tkJ}m{XT2mu;#4K8Js>Eqe(T_kX-K9K_|RjTJTyM_7pZgn%yb za19<}Sjlw<;l@0ZV4$udkzzb-YJM?p!xot}Ibuj+?ZQS8>;$yOj4lq(CZ~rx z;OHIf>I9)@PhmJZ7Ks>Eg;Dh700JrY#-&lPUMYCQASXc*=Dqyv;s{&Q z<;!%-{M=)T=#2SsgMm4p4ZaxrO#BkFb(LgO$};JsN||W^DqNri4C;+FSvZ&-D~PLC zz)yQ23e}QKioGTS$3Ww}j1+mB&&j3PI1Qp%$UV#{x9-$kePBB2 zl^T(%$eDx}2ou^gcCPr$yv%gpG9`8Z>EzAJp~xG;zGSM(q}P1ZfIj)$i3VSjlGl5&F4Leabwy%Eai{;_ z{%vH{5$>jRK#RUv(7&oEmQ$>sp_u<%p5T>vk;)gu^u_A8V1sqi@NgB)jA|@58OJg> zR5f$^XmsKExvLF^1}-PRvF(7>hEKX8DW@9Sdy$^FFPX8e_T zn&dGdz#Opz?F@$4V=C%!1-O+PZj8Kb{GeFhiUB6_wl`M1 zNF#Ace9EMM`aF*IW6_*@GRFW_Kftv({CY*Z9wthv#j0kwDw2E|zq^Qt?PjVl9gc-1 z97B${#-#uF4{#Mmpvt{veLFAWa<)viZ^uPcm#PZC;Kce{t&d|f3Edr_VnUhKR)kUn z;Ykcyf{wt}Qkv^K+5(sKpwUHmuPY=*)p<&x_&LZi$vvj1&P_Sp`9%@cRt+ZHK84Ih zd^A1|Q81nWBO6r*yP$`7SDGIAR-Mf-OG=cD&pl*C@D@kp*n>~sh0L*o#gA$pIUhN) zoAdsy_=`WIb7dQ7)cfO2yL!696u~7ZZY|=qo6hy?ih7>?G^#E7f0VrocvDr@KYVg> zZF*XIBQ0%#11xiSJPp_#G)E3AVr)1r<&JN@!!Q(j)xbbVe|(;B#KcdwItmeTJ zJNBm|@NizofjztZvYjyaB|K~AlKh51#WTo>pVCH1f7s>Zd03@pPUg5=^`&sVSNBZt58Pn5ucgbRWfF;tV|RZI*^Fm87`~+OIO7P z6igLC3!}8%g^{4o&+hIjag;oO1V2kfwVy>H3P2Y)*K@F*8u+1-H8O-VXNsw8D8Wg# zv;jcx>%b(UuFW#8^;dC8w)6oQ`>TLyN|d%)!DVP#x|mmRWq=P#so|Xf6bR6X6KHGl z0O-8Mv!vifg5LS1&1K6PU`6;PumZWEK^jzU<~4lV3wwf3fknZlbjdV!P6Rtd`}F@_s{+(ZPBM~p=O(~dQiUa`k$~x|4Yf|8_4Gyl<$lF zHMXeV7W#utSUxDVM(0rRvJ}BR@{)M*aZbuyMK}`I?WcEU=#R3^hEn_utk5Z&@*MA9*#lzcK46AMJL)q1vVi|E+a=# z4Wa!kBQPIeZpYdc35EMDw&<^Hp?sTQl;O~4q)6z6{t>pQLurR5a{(>{R@PU`kU@E0 z>Cdo5&9+dAO}J>KwovlE+CRh=%^k>Vxt5n1ly`f-+7`{Qg|1kIZwBS<>}PCIZXmDy zYF^=A)@%Lz`Tn!ksKyrh&MJJG$a|H(FRa(^g^yQ9C(8f~$LerFZ#A-ETuT>sg`z2YH451%qH_^xtibK4J~cvkKE?I(ke4 zbXZndasO!L16r)wV?Mt!A`;xh<@R450Ygh=W)+T-M))S9Wx916TRBS=k=*^utkGrG zP#I0~LNOuq&SwzA+R0O%@CNv~$fkStkC|<}rHa60n#2so^)h0S!E~(7b>h^McUj@$ z1*@o>3~ut13#{@Z&Mc)MGqrtRS3D)$S~w5@@!$S$lN>&x~ru* z2KbS+7V4l04(`UzK^yLX+B~+mP^Pv160Tg!jg3x26joL^q?CyAKzb+JyhhkRK!g2q z9L{MnEzTYeTOfF6&#fK-`p>T#iOOj{^e(ENT1#+;}}tn@r~ zvz9!o$TO0I1cT-#2kUU2VhO^MWyPtQ{d_^?N!%{ZypW@Zdmdj1-@A4`e6FCf<1&Kp z$Y)T+N#F8Gn{kwR4E-XNl1^II) zZRx_>iCWYZ0zT>!yHF6wr2{8UJ=Q4v#5XniCaf9ft1JGV@AJ?3fnT_><*_xJ+Dp{! zZdu%HcMAeB2WiT!0TTUEww!s$@>R zb04L~E*3yWmbrwt@SMVJZqrxlP$zw}KUMhoOZ>m8`RFVB&R6-+tGr!Tu+6pUD-J;# z^Ox`3$=9C_?Ig%>xUhIDzfIlu6<&saAO2Uo{s;1?#97^Qpf}WxKSc2}_}`^QLYT)Z zeBJ443|Urb#;`U!qn-d+J}V4A$9W zm^$9)4yHmUFfWT-qD3`3=a0Ok)--B;P3aQi*LJ}EkZ3#*zX|6~8V(U_;=(FE;9#0} zNe-3$a6#YX`U~No5shj4V)%Gv>HXHec7JAH4cb~mZOxr7%u+kX_j%gq3XI$d)WQ|g zTjSK%HLH`wo9;{4{N|dz`URImoG(BO8PtvYXi3?e%e2)YhkArhOU}C zkca@>LtyN`laGXkMDO53ck+Uo$n%~nzyz~SZ1dj+6-26>)?!*30LHz~q7tkC~Sv#q$ND#A@s{iHTLIV}Hw`rXSy!(u8ei`ck z&PheZ6ZugKp(dX>dBH5Ff_DV)64&1Z*4XC*`Uqhx30u$-V%BO1WZW57h3JBS%l)Z*G!^%Y@xrT=#u@lo2D76S zwGkJx;zG51p^BfCn%2Mg@7)_LKw`!JojW^@(j9elsIttWXS{D^yQp{eEHaDJiS)YyLj&a)^N z!z8bDW3f^^==T?2dvz4&iH*g|+6TuVc+|_w-~dAKhvN|7i}ijB&8Xb|p~IH&75PQs zU+9npu{hdW2fe>x z37;GM{;DPX)8O|=e)#O*_f89D*n#|LmkxzLto>Ai=UCycF=Q;Po3BO_Q2Ge+{8?@T z`=|f6ZLmJkuCb5*_jX;EfC+!}zr(Caz#yXJ|JsKhQDF3lqCU{xs1IU~AQ0RCMXM`4 zz$G_39F+#Y;@LH`*e!pWJs+Qx$3*9#K7Nlx>Uz+_siS{w74Y}!& z;6M8(TB0SEP>Dr&+l(Q6%d{DhGbxrv>sa6qCMDP*19hHbNSkI4q@kbN_Yt z{7baRvi4tbmqB}JEK3DL;o@h z^#uGs@F#Dq+;v4hBNS#1#&y(uNJCXPgBSu0ZRY;J15Y^mcXQ}7v#?CY(?&4`5Z6Gt z9c_l=TLnvrf`$0-Ht11P{r(=utq}c3fnr1SxHtg|j@3$KJvXQ<%S^L8c7+PF1Ghb6jjCdt8I0#;X3^rbIX{oYELrL@ z!%n9}Q=;bbpb@OP*^DK@oxyqvm`e{x1w*knxupq`$#X_$hN@jtb-j5a+~9u2L^9NW z{iOJMM8Y8AN{V)&%6K@Xrs2*=1*YEb1`j24-@?@WvSb7c3O z=9c}XzB{dfTiBjk)Lil?ohXNk@IxjH$mdnW{|vUZxT&#aJRP56Zbb-*rUs{5<$U{+ zyMmcLzs^~K+ZQbE3YD{hcn^w9dFPY&?AUQO;--Yk8-FfN86Z%zODF3o*B*xobCRxv zgq5{D19G<3+zvy$nC!lWej!{M*%M^CzcF|J)jX!-eZ$TxBZc!LN0AYCcxi#~%gAl? zNb_11#BIj?GBbNxTJgD&pc0{%b%-7BffPQgJOFpZN#u?=nPynGM(w*Zy;h@fYP2p5 zyAVDPXWbbp_q&(oWnsR4rvD!!qhE{+eKAs)M{QVoYGljoS1DSejoDa?^6U>5+=k11 zS~g`BjH1}Gn~cIoBll_B4c_14@Gx@! zGmPN6a|Q+HD1KvPJ8?RER{>_-IN=-qy{RaU+_z9WpvwR$D2d47KLWWd+7Iw;SG8`-?$_HoKm!%{GhqYPFX=y@rE=aubWIFAw+}JvgpDKH<<|I5 z)SQ>USXxG2+Ygf6G1@Wq{S{%|NXygL+6yxCt?`>!OJL+Sw*EBM7olaOvxd5`{rdv% zaL7u1lfCCsVND0GVHt=0lR~>GZvQUT`yDwq%5vVgfp9cp@X9{6p=pTlhmo|y2O60L zME4$|yBxbc&>>|o;d45&I&8w(u`c{;J)Yf1RL?Z^Q^V_nQ|rb;7w0;n@@O1f zmPr>c$>h-?G8r>``KGVw{W*S{7Quj&dRxjz7XL5;n-mw%co!8&OH6pKpmy>8rohiy zZXPKu;raPDizkfrKkyZ=;RAj&P6S4ba=56I8`cxe5+;CKJFg!pIpCki1>~c7zKTx$ z(Zyl$?kgaXbs&!pB0v&yHLes2C|@Dvx7y9YkOSS1qdLNvwYLb;Oh4NQhKSIjv#0-{`n z)?-_0dO>4)KqG~op%|u!04e;2KyNZ$D(VU1Dy*k=yz1)?`GgxNbzKO?pQr?Wr*sH= z_!QT?PhFwy*dmOl&(0-F@kJ&Vb+LRpf*bE(CEnz%221+b;osAuyR5*3RsEz&G&q_c zBA@PDCRT@AgD{_sHTEWA9|91YHhT;UG_<4o=4BEx7)No}LQI({o+QvSDDuJ7T{G$9BNfhu3 zgJp+~Om$AGT(c6Cz)~7cz7_0Rxbabe`&gyO(()0ovABluNW4VjvRbzPUCf+1v1Sxk zatluMWyvV?Ow$@?<^hCv@~uf9S5h~w#C-L}^-~&#*xjx(ojk{%R5{sc)mB73&XjUf zy$WAuwz-CvMk59?sGQ}kollVUpX1D7ZDm}9%*T%LV# zitasm4h$#hMR+rIY4tT}0V6Z-OJn_)E&jBGIGxF4*Q6tP>6giYmoE=aFO<_Cr1Xn} z(AxOUrk39(6x!}kvLb|{1sfV5CM2R4XpLqL91*qg7JubX_(RLJx0ir^Ui4M z&-nPXZ24^|-cI1HP=0$5Z(VqsNN*}V-X6l6@a1p_@D7Hb|7(hYM1M=^72VNMp8bBNqmaT)xy*~pDw z>^akYo9&~9VQ#<&`|YM)S;vXG3%iHI4rBh!3LMQH;D^k%*q`GN0l3=jv#0|sTnh-1 z#Y9usnsrFcWkzxd4vF^D*_;!%n=5(8?WjYt{aMUUDn3Y8+$-rq5anQ1uwSqTi@nEpdp%#xAorX8IuGcyZ zyJlosIjdCh22sRYoTVv}?Dy8ZpU;?D=+S=?!UxPE!@nI7`V@DuzmJE77D}R^Yd3wi6f%X*`rLNv)S@l_D#H`8b zJkuQj!SD{!nj342i`t^ns^NPd@=Py6LXAc&uxxj5rdvWDc@%mw2mJoD*Nw7VbqWOe zTrR2Bzr|?6fBOpErZ!%CotQhkn!k~M@vZmHu$J40n=xV*($!!*;*nVANj%YK&n|$? zc~58&+@#j$1Cv7ohZNov9!k;?|8f^J2Xg-uZbX}a`MlvZc@NUbqDCmp`^UJYWO#Ef zp9>yRe+ZIrZx^uHha5`v!Vjp32WUXdgX0#PD>pN93Ws~_j63wq!fJ$=)WufEA2s%M zG`shyp`mLcCFz_I!&|lPk5tmfP)*W=R~gYFzOv3Wiv%ky2_4(;U#KFgUDL_Esqd-# zwnnn4^LamvOW90#0o*0VR+o&yz{aa6Z$-j?H$jnzyF*;!^k4B;C;Y#~UD{D_m0=jl zGT(?pm+4~x0c1oH{>6Op;tTon)lR!*(^2=(sS~|9-1YFqb<>q=`S(`w^1W*SglrDW z#_&9yY4wl)b3SYxJRkPHtMJzH_k7Nf|7C<{RyF44wKuH`n(KNDclYfj9q--1h~Mz< zA2-6Z>=Nn7%`J8LXE=64Nv?1_KY63yfUqcry9+la^B6~R20X}l6#0qZ&l7yA@P0l) z^A&gDbK(L@1x8ucy&kli7FMpN8Xdp+@<%luUfTLz&E34@*icjHYqj#BxzBv8;X}V` zsF}eBPknKwln=h~#+e)W;KN(bT+avR7S>!h#gkoAlpmRK#?FamN7|+%`5EL;5u1RC zM~#Vx_WKdDkWCHOT*N`5v24l5dCw7znBk=>FKAv#(6b;8FG)yyO&zifS;{=eVw)wj z=9~V;@R&!B7u}Og%i(G%nVd417BJ2Z{6dcHs+~&{c95q@` z!IH{z8uUIk<|b+8AyclVUCW17a8n||-{G?Ih)Jr`>I4MEnZ^Y>_bZIp;WGfjM;7oF;&0ImqIJh<1rfix{h|YV@YgPDwkZN zi&QUpW9aNLw;rUaM|eFCT!7fkmlj-&dFQTaJ#~q^t8O_(vdn>VXA6EZZE; zo3Q|wQSEC@x$$>7iUsr4eBy zq?#3z+mRSsoXU-VB=m2&OV*Ngwk&&RgTFxttfHL>w)lX5C|;_~4RPZ4yf)J#A@GIftH>vCeNDnQ zM8Z0l^`hKZ<{iIj8!RTVuL9`2%P2)qUFVqP(;OnAXy1Bs7x|wmHGT3%5)5r>5k1#lt<7zkMiYHY8!?fyQsfdzOLDC*aGv@H`g`If~nP)}g zGX*vO>{RF9=&iu~Crbe2swnSou~pTM#j;RfV#}?}H*>Gb)0JfgPf+CyGWSUl?Wi3$ ztl3ApiP%}wrVF}ZkY0v!Hwlgul7$U&tB3RY>wn4f|1YwP_gq?P;Bt=XxF~8G6)WU|~RKJ*vX?plm>frFaF@ z#~;k&k{udMKoWnQS7V2))~173z>AhWdq|GwysQ3{vAeZpy)Tf&i2GH^e85G+7r*e0 zx_gX~17-(e1%#I6bx6XFT#y7K`kFk>=o5YXy9I7-feW{S%ExRxt^uvU#GY78y`Q8Y zTB%&Jt6RYc^8w;zsXGsy0gJTT5QWd9GpMS+Bss3z$2uz#fcCRCc?X9HC#;5!+2Gf> zPZ$H*?(JW~LR!6ZM&6DtpF+;21CsqZvZRQ8Z{srM@|;)8!#)Ej?APfKMY2SLx}YW{ zc^#XDN9CHZ!u6;Lb`0+p1hlA2VL+~kQ_afiy+lP~AEfl2iR1but^I=(IgBV|1i_LA z!x2o|hK6Coxe9p$Lib4I*PmAcB#fe&{Zta{xMj0psyBZ`C9 zjR^Rdn2T|&7fIKXUTL<8D`{?Xro)y-QLc@pSqzB58z<_izOM8{ZgtKGj6J!nH4(VP zo{vY+?s>m%u8AD1zfX#diB}-tl*?uj?ZqdcGJR3`*e^|F_eX`h5^QXOocv?ke>Y(MS<>5 zhuF+jAJQ$`BFf?*$`n2(aL@F@+UZ0^bzyoZTjkH~(s?$YUbY7*v1OR5t`7Ft9dL1# zmdxwa;FJ9kZqs5Bp*GYwJ|X)XbYIW36z4Pw<>4=GK5;9z&v0=IUW9Hcr8+xZ%92$I zzcDEf;e{rQK~C3hseSK?_Z4mMhBaf2ShAL8S1-+6>@;p!y1t^v_;m6Vq@5dI9y#!+ z6iPkZmkv$Pi-gh1K8?|#fm#uTxPt~K`~2+jl-ej$Y{r-4qE;q#f8hzTL0J4qf3bs!E9gpnb(qT^j)H&t8^_ z^pMSXBQw$SqSKIk?FUc@{KgSg-dhGkHZ&Q2sPED*o zo|wn}XDM!0?O`>sJycea_^$b|KmBV2A(4WHRZVGak)C92)2`jG=516C6Z2l%v7>J3 zYuq_|l57$co1&EC-Esw`AsoV5%$D-n1HEtf^($ml*2Lv`B^)S)-4FYSp^UG^fbtT=*i4qOQPO zGn>Wy)u+gwh+mw^+cD{}Jo`ko9O%p5$cF1#O5~5@5*V+E^`2L`j%hkI;qOv(Mkk0t~9wcw>Ix34j+;6yf*3iu#eXqF{sqMQfuU?2XGq~0b5 z*#_f(OX~L;j3=bv{+_5-WZC@Wb)R!L1vmS|QZluJ$QUTqi=~Nm+pD*5Q|{V%Fa#yc z0DwmMO8OaD%0w>V6cJaMd!8;94F3TA0HT_qz5=syR}MBlRW-zAzL1$ucyUMa=3_-+ z(U@DgpTpfx2eM`^^i$_JEaF|qusA7@=M-JE`!M> zM=y05hPp~gN^%*pMB_G>tTo_lGYtPJ8sD2?nC}YiA05q4p4CCs1epDT*{|cK6#1!E zF2gXFTy2*D@hGThmm%AAwN@_@1%I7oKO9#sXfKi5R9~2Bu^T=r`V(TKJ_L~fxx8^3 zq6FeLFAXFu98Sw|{f}kFS=LhKd9y&j_->pSq&`9R$q+mCFhJaQ;$!Gs9Ubjz{LK8dM#S^Ma?|kERvTxuB z0fa@I6~uS^gzGyz>&3C?GU@drFTY zwxTOEPCTxjzxb+ zCpPN)jJk93{4eauF`J*FCes9R=Cojfnm>mqrO8a5R?uETgkV|?_2(h=nEm7UVRN8# z;xa_p9X$aEIOtH5o#Sv?8j8<&O-%{_^Z2yNx$(U5W=kp7!b(@X^!c3RHHdIqp}{of z&YDx&k<;{;$Dpc(-QT#&?M-O@Wy?G|W~u%y#ABLF!Eh&+aCwK=J}<@_#mHs!-qA&b zqUo_C2Ie{L@U!c2>>wIcnR`c|YR6cQ-t^52Tqd;w%Ae)krFQGBXhPhda`l8t2ogeSh3b;|o{x=EfulC)^S*6^ zm#)cl2?WL7vjuX8KW=<5X|zld90I#`L&Y#aQOjV8KnZ?2?20;d;U3%lM!N0*KGFMs zA%|SFUvWu}w7I21-LZu~#=32P^WK{RTjNq!4yI=B=Qi=BxRf!$*OVr@Cjb#NX&#U0 zS&Vz6%pGYBZPxl<9I#FhkFbG?diq`>dXD3N?A5I1W%UfMn}_0(hL?(VbUe}JpFi$WW-(s8)cLYi)e zt}v60?fQ@ipgx|Q!^^zJb0{gtd)O8-0C5+^2Te;ZD0?owuVTp;L>kF2VX# z#jH%v=2G&a+#bGEHO^7W%S*{P^H1P{U(d^n$y7&a=vcP16s8)#$07kW$W-%BQ!9S& zEQJ#SkD%DBOIDgR7Q0K0o`Ik?_7z&3pa4w;_5Tt*U1+@p90h+m*-fmlB|D$%GKgDt zH|-I=H7R`=^n~_guiMGXD+aQ~UX|q+N`GBRN7y*m9G!b$6BUaP0B~Abvi&S3D&DX= z-{9jHD|N48s+zLhn~#}S)K%yf-qAeN>CFUM@7I^4qIAqBkONIdwbOR|+yfb6a3-Uk z>KpfD{rPeJaXz1BQy1iqp&7`&aGKMWiE!f(pwtY%gizp~8u@&{c}!FJpw@FtUH`GD zJ1%YhD|Vt7s(P`U`ge!CRoG3{t1UlPTULOyP1i$6oJ<&-*XOTB0&vzY$&_Td#eOL( z5*-qHG}{|aft_{e;q378I80$ps}+5}_Xr#Q48&(~Ss;JYLeB1z$*9nAH(=IuY3P#9 z+q7J+OD+r85fGU8Q(BRYH51#%zzH?P^@3cs7eZXp@f~K3iPy-CD=>K&x*Rn8O&o%g z3wq_FYH9OnsBT@ZW5C33{;2P3Z6o}(MtS*D;Ub>_!T`#$FrB`a~a6V%UJl$e=Q>U zn3YlV;&@gev+~Hr>Y{93HdZUqIFG9NGAa~5ET@cq`SV<+Q~n4{+;S-7j$zhvRuGJH z^M{is$m=YE=Rm5K%R##C1JbeE4^X!-PpwPzjNPg^7fjGKiYL^fVaJRdt{^Lw*<#(h zy1-_k6%4iR)X*V}x5TdnkgH-xf{yc;Jgajc48<0gz&ao|e0zy(fl-k2muklmEU>cg z2bw%qRbqFQg!!x%Aft9V5@Ze^qPv7JTEoASM=R1XPEVM?rrERWTJ^Fek@u}c7j7*! z73m++*M6i4eQ(-ltkv%~&0|7`O*{W-;&RTFk@aQv#62obzXIw9TtwWp@{EbgTk(Kz z#kw_nPXJ_^3^D_8iUvU1SDrF)xvT3|G_Bdxb)z)opCNX` zP-s=0y9+J?I;Na9SfEpQ$pj*yHSmu`M*^9F{ zXY+y3gQ&878+14(o<-k^{Wh@%VjkN%R9W%-I^b+97Va>SV8*&@NSW^abAr7ln~}@g zv3nf0!`J3fs;eY$v1(`F@@p_`F&=ON5NDHAi zOFPzBovV_Sx-N?vNzMW|t5kR^KIGrg-B(xY;{YQFZxX@?6pHDD>o~+Rc_s%Qc?1HF&@)u-M|{o= z^4cuCIq;6#;xV2%-9zlX#q-rm5w6du;zs44+n{%}dG9Soe9Y<0jZZ6q@i-lV8+$ZG zp6SH<`s1@7Ov~?WSzvx+={Rl@;PN+mdN1Mn^uTl#z6Y|h0x}>TT3Sm3)2U+acQsGG zH?-x!H2unzhH0hVD>y1je&&AThV5+kqO*C=paxui{V$_q7$iy+7WK_t)tu3q z)jI6t#vhWHlTYV;`om1B`=bB!En3zM-Qugq0Ll{vNDswcL{wv8X_OZ)a=sfcL) zSQBhHo80^T$La4Om)}x2)Z5I=Sh~P;pSE=xF#~1n)}V}gl`>ArW$3oaWk^&8Li{OZ%o_bJ zm!gz$7-eu&#%9LTd*u|$c&58$(b?s{posioOLyI(fADtG9!={6pv@n~)q^*vHMgvF z0!~g^wy%exPo_2B2yNf~32l8xI91!bc^i-1N<4n@*F!zM|8&2bagE2nVZK;;x9M4J z`x4VEEewN9U&5qKh0r}M!LvQR@lz+$-y3V7UKFq(1q9{6oVSj8<}XCG(kzEtK=syL z?Ak_|>W=g$?L&hvbO+_WLu60cy7cC~2V3j*Hs%k@H&X5eN=`0`=&bu6bb`phi}8P> z^LnP?3wEuUFu8z<^mMSov=1x4wiKH(Jy!;v3 z)cvmR=cOslTiPGvlIp+Nkjt)J%{T9+tq#3UJ+k`NfC z3dqRh*9HHMOt*+c##uLwF%GnBd#*ACv_I9JOJvEdN)4`-O_@ z26>2jj>}J3^>|wQQwKUu8#M>Qd3~ql2#wOa8TeZMP<;OKlXv!LnUf3iKJAe^7m{@k z#M^TZ?@HgjTS`{tbu8_;ZgfoPc^KBXfKQy(Plu+A5spLg=kyieU)#(g_cm-kQnp*U+dM435tnXc$?zKS>r1-7e-M4D0m z!k<|BCC;sE%}gf|5VGo5S)DrXC)WH+*qCU9noO((k!a2#^}&$+nRt8EKF!pQZrFd> zpUd1{6e`TBzvvxmvpBO#v3Rl!DU#IRxc$Yr7&%9=b&~^=VY&ByY(;T3RAz;ChRJB( zgT=8N3Kxb}Myz}HvzCjQ_ZG_suwla>s&w@i=OkqTai=!cZynPo6Xqhq*4YlJJ+fcN zI;d9bf8^x_EW8fKo&I9qnsJ^iW|2Q_TUNVe+ZMA-Hs@51u|S2rF|+x=K6U6^raj4K zVTpVc@PTz;ofb2aASZ3|2QrMCCMmi23?qLh@fJUTohwT_XSFmREy%Q5e#z`r(T1YB z?8hlAfcOD-E@)=?V2}h+KGdS5^0EeZEnQv%c>wzKsZ+BctJHUmn`VYez48vy;nKmS zD^XVX=ZjKNGWJMf@C$$g#?*x89Kc|MaTQGAw5#$}F!#!=a1tA@cBxUgW;^>ATh~4Eiz*^EKaKb8{xA;M_B(ho*;bsrA-wr?cMp8(2xHy znQPf*7Wy;LhR+!vPvUH@3Rvdi{C#xA%nZ1w0L_j5MhX8ANfkVr^ZQJ<9kJ2D22vu3 zL8EE1s=3Um&Oc{Oc5XR5`Fgkd#^&jY-OJ7mnWWJEn8VGW?w|_0>3!@>weAt!D*>>Kan3}cO=oR3t&KtkCi%6`jc z`#AY7QuJLM*e)oBh&<<(%zG_2aK z{E=RH8Q1nLQ@)V2U9*Y`3oX2~yr^0_a9daLAx*~%ly8L$sO>76=91A>Sa@w$!L($) zYy>{zhyLSIkC@7L^JOEI6llZIM`7PIG&2zN!QLVnJ25SWh36P6nkKZgrnQV-(@>*@ z7aWw;OKbG!tQxMu$D74tdeQJywIemM^=WA2Ulo2&gX? zbfH4)I;MANUVydlj3u0Jc2={O%bLoY%T>(0C9M9;zmzcve+V6u|8pmc{q9tA9j9q{ zgKkMF{bxpA^{2W+hHtg&UU^6(Yk$N4i2IA1syPP)Q@)I59@v3Eyl2HS-cx46JI~h7 z2ypdB%=R=+XD(lZ*5kJvE-Li!SsX7~Rj#s?fLhwB^{6e2=%mns*MjL6u)Qv}@UeJ<*YoplZcdxuMQcotsyCjEtwuE*IHl%D`ncBlDk4KzvIO zriBQ?FtPv#l?{w%vq-Lt4tRw!X1|%kZEaS*j3)So7ua4qzWbIs=drp5ffenJCvo zpC>WUG^rZ+;rwQ%5ZFr@UIG+bj{Ewg?!wkxoLl!FfZ5)SKzY8iT;QDJ1tovJNcl%m z{`UyKn`z*u@SESp^V-|-oW*aB;#pV5G)U~)=>Y47#>lhzUCzA};A27kYY9pSQ+YNR zTh_pj;kQf$A?2fxVL#>nEY5FX3K3NLV4Mpiie`}kmr+t&hzuWZEo^6d-;P_JrRN6e zZp%hFF^66ICbF!3I}X2tvUFZP7UtFV!qcXLp_#neT9A>#UC*m6vj>`34qyP2e^WVP z+Xs3PyL6yL&V>@`^0BKa`IMr=%>@aX#>h1N1D5R+paXy5gYSVoKIckQQvUwm*o`ai zvTTC8Sq9$umwiCkdmMS)I2jm7&hJ5L`C(j!iq54**AafB^qU_&s*xOqKC$*oi+5Z6Vav zlaA9GhCT8x>13bu@urV)UW|EAV%5G5RR;|F82ST?zI0dsDrNu#Kj+(Y=y#lUcv-Ne z7t%q1{XeX{`q9^U+#}DIk=96pb~UJusOdRu%iP|E459DSy^U5W#0Wz&=4%lIg3D=f ztP#D(o$C4q+&LVi<_MR=Y{Gk6LN2Ic%-waC{`7}f&i#HdKF1zSEK2)}O|uMv5Mw!z zPI>|sr!$Zd*bJd*YL*Kh={^qIqxX@@50oR>g!PXvQ`RoapF!^~CfUI(^ zMn3D4&!`woEvMNP-~5)#&L3UtTES&Q<9R5V%RTK{6Y&g>ct+H^$-&`>;TVybmI*U} zvBrX22|UEf5$;6|-rupsyDu4m&rKVz#1>wm+X7^nqbigx23MG8!)~??=U_P8aiOfN z2@Ox&2`bJ1OxszOUise|{v(tJ#vNggg^iisFM+-~cRc^XVRNC+!+yBPYxcN4MA>}S z1oNF{KB#ivLA5abi1No#`HMTY;@$q5tbXKeBi;x=PcytQXAdSxm^{JaO~<7|#^7>y z7NqYuXhuPHO(s^ET(2=xho~oLTg$3+>18;Fsr+mJT%9SOW=-N?YfLJdm_Cy;dXL=T zXX}rEJpsdhGlF(j?8hhklyw8TC2zX4xdys;^cpmc({aN4YO?t99|Jf+YfPM=L3b&7 z=82y9d}u{sBXxdAN6l;6H8>-~37O)fi?wj2JKcP^u14?qkc||K=u6HY-BU2UkINs! zxpx)6Z}~VKIm34+Iz?CUe#?n;Q->bQr(du13O=Z#ZqaF|oP=)ik=!j#6dKK9&{w0c z{qWyA#CWaTA$0PgrLLY2#tYk2TrR3=S)5KLGv&mO(`;(xn<^Zx!GAQ-9lp!(ejs;; ztuhmk%B9-pUy)aIG*1mR&wU*)c%MzC8_7+Lm*Ln@{`W-xunYsg#yQvyDHck`8KRUk zA@K5FKy_d~HELwmT9WXWo-01)1278k8E^nHF%2*t$_G zI)-n^Ibr`>-1~04SBcXTVir_+wj7=lPn)!|M7wOUry$L3J&jAljBI;s}4y>t;&4L(Z7PB?Vj8v;^xab5rgyu9&~3@@X!jw;j>~d}aJOqp2fV_&BZI zAe~f8#vRo~Ys(?b>MB{mMG()4(qsW!WOlh*Giu5%nugHC$CFtwx9L3ki9cIS#NZ^nLO8Gz6_W zic7gCOw1bsjnQs-_gg|H0ke z2UR^Ysn_5}m1t%ln~}0{jUC;I7RY9$IjN8?zARQQo<;J|nAKK) zJpB;6b9!2*-n;E`r#?1Py?qwU(mfSUKui0_Lkk|w7p^P+PDB&?p*4JMw{bmRbgAVY#S~R&;_PQIm>3%&XUEZ*t zBt?0B@nF4EKY^^CvL`@=C#VUrX}tAL&*D3YC{`ZPx#2)Y)#V{3BkqlghfWUhvQ{3t zavjrL?v}I3R@D~>n8mh@UQ7snc+{2fN3Rvtr+{Qhz!DEu7{SXF0vuE4Z-vhC)aV3Dg|DB-8ztYsEaec^| zYBW+73X>!zl7+$|5;iZ#%muz9Ec1iZ^8GpAAuW#mPiy`Qh3dyBCAu@3XSt^lp;Z2d zSg%pGa|urcoQ}g*g5;!G-W95Hid`0B#ND?G2v|XsPTQwD$Eo|5qRL%J=wbqi}IA^{ruf3b7Ti;~P4Mt+Y zlA`(EFD_Spb!De{NTBBw0*XLF+OQ{0&*7o!fRsNBg)WEG(u8PM471VWWy&=;xKPkM^b%Z}IMVj!h zRB*48%{zBUGrtN(49?a$r*+JU(go>q@cZy}87A0XVj4M+8r#QPzD?zE=KXeRcny!8 zuRN#OUn36iK`oSI&CBd>#=Se0K85*C*piBKN5}E%iWE}E?v3Mb_+@nV>YNL)(QzGx z=%hYY+Ljs!L8jr7!RitXx*4ZwsZA69Le#lRN&Dg2d<;|0tg?l3T^h!7lsyu)_e5=I z>)OhRomy9^9WeOCgv(skwv~MkN~RlvGf2bIsqI>MB-8@_0) z&RQmF|iWRmHwwN}@R+7@om^12O`tfuxT>)jFO^&ybW$0q&fwCC z&{9lh8pfOW;9_Vj%EvH#a0#g{#weQ*K6oGA*78WcpOWceSz+sG%db-r@f&(66q193xFEP2Ik!Xd-j|r~FzM1b%XO;7 zN$JAe)O`jh4Q1Bk98nG9tEgG*$r<*R_}Y)--e1LaC*q9#;mfiqG2@*Yr@KKI%dk}E zOStO=zM_$g)#D)1XFL*dli?JxY2y`KI9{BdN|K1$sXkVa$*%2FCgb+qV(8abeH#D>-v-xJ--e?q z7dxu*Rq~TZ`QaNg(GD*5x@y}w7yIjZOB~@pq0^Jw{cT1&J(An~fWy5;bj?oC{XzyD z?wv#Bn`dbK=MLC!xm@~L3Ra%LmMz!_`!z*=^6_O%0s&CNXopzZsRA=NjWDav+J}f3Rqw5KAAdEYWvuT%Mx-;xz^2W7al0F+l zK@3i@yp_`MRBiw*E)~NK0`hC1;)$#GGI&cb%X)-B#>DDhl0k%&^GI-;851K7-}D>$ zCcEDGvF{GfC@&h`@*CiRYoB_<+5x|d{>>@e=zL>TN)aL{=uMW7Qnul~RRb^8l!j7D zG(}eFh`j8*XOu#Y4#|%HJ>$Z?#vW-Jb|tKElyYJFyJdG#M?Qy+DSSXF;!%w&$hhXu z0WS~*7Jt1jSTLOG&r6GcOjR9m%9{^Fcv>s|D)6MTc_uKSmC+`7Q52x z(Twu`{tqb*cITcHiT~05oW;_ag1hFss36?;!U8*i5!{?tQ^2GUR}Asm}iaE=hra-yB3Fnk8a=UXDm_B2Q& z9F+7}sW^?Y3`+7%5M7kSYdQS2uNXj1Z}=%RRx$nzPR%2JlN|lvb^h+Jqo3@&7~&zw z7>Lzy817LGnYd|MM3u7lYr&V&YB;bgzrQuf*XWZ}soUA=yGK;#=AmZ< zDkxuT*QTUT+5IF#LFc7YfgzP`%KbA{O#kmv#31S9d!i}ajiKelC0si!mZm88RUlLN z1C}&5NwB(AOF^yu>j4=Um!h!e{6@>7lv6O_7C|U#f;C{yJt?#Rd>tZ=`O zMKuh<(5CE<)qY>lFS4$LG#}f|DRFfL5bjAFdouyxe=BWB;I53vHCel)D2}#C$y9kvx@9rA9Y8wxOuTj zn6cFEcU73QR&@B19}FO-;B=z7T7MdU*X~o=s){K+&)xDQw~(tr>U^4r78G;Z1?dYc z?x04wa%h!5wPSAH#^eq<1D4rz3j)D9S*HIVT<9O1bHGqI+{xaAYVhtJj$Ar68xzh; z+EF6VdfSXJi=GAI!~5g11=RdvB$sF=4rODX9fggOz?2@Rj$cAlOj=odlxtP{XI2{! z3W{l(B;jtD1rwooFJ$U}oHTRN0+ZXIxHuKR&2cy7C;QchC#MI;cOM=PCGX^tYaUN5 zW@}wQZpeV_>?D@afwi!YYd0WJK%k7u!_WTiaD?7~QDB(?Z@emnFQZ1}RjIt(+PoSU z&B{~T^_RCs43W3h@R`BIv4BzhX>c{K#eVc?ahS{V!$)!<){=ik}J?eM3y&s4y1$2Y(maxK+HHD;=r;=NjNl-9S=C$bYlPjaHn zf8dI3y+mUQcpl@h)L_Jm>E?kE??`HbMW3qqjL5QJctMTo*8gt%Rvg_`9oB_M0!7n$*SjbF@}dKi$3= zE+OOUxbqWBEX9ks!;y6Jp6B*KtOFF-q30d5fD+| z(NrUKY+sEA(ds*uI%*v|lf+g7rN2XCTanUEh(?gYRHMZDzb+ zrHY7%=6s(Wa60cf=bytT4}0%*eb)V1Ydx3oZ6OTP3cKIKCC~|#NBLa5-Rcn?Y|u2x zsKWe>fue*sLs96|wgDZ*5Sn5eWxm~kl!P<59S|ZRBsgFa=U^LUZOh90SAeU>{g1Hj zXpF10NgP*CWtQ;le)Vle8$mU|GrmC&Yez}Bd9(tXJBP4aXnn~|XqNc51@dkM#{9snWH`-&Ra_P-1{5F=(#xl2np$YG z;ul77e1?AWM3(bTrFGZOK6Hu_)JNprFVnSmLj}}YBiA)W{(&?5dmn~w#I(rW-!yLi z@Zkct#N|*lr+(IPX`-{KCHm`{(pf>Z&H7o;=1d9N);>Hg89vN43#dcPCb-z0JQrGX zKGd3{MF9MC%Y;=#!A&Q*82?5ZPbMv$bqcZux({e>SjaSr{5^dJ5rcZ;aZmrUgp=wX zLR(`_?VfCIIMsshZQ&x}$rGa@j3W2)=w>ubZdLm*h*v zk1|j0@BX-#GY{AjSomouH|&xu2?|?geG)qJOO0b6mGY7-vp)2=lpD5FoKyzf98Ki< zrjm=#-Wh67+kig0Q&K1HYxSgU=qpL$nrR+)R8pWiNm6+;>v)IW*Z1U0N^?qQXTKln zB4&N3Vt@NN2#b6`_hG(80x$XrGPrvXH_yoJM190sv11EG1@j5T*ohnP{U?q@*xL_6 z+IX$Fj^-%GA1MSyaY?vgMARwvV+-#n{dL6Hwc=LA{<>HSU-JJ9k9=MY28Z6bZzaXz zovE$T{dFl6yofyV1#vFP{$lY&cI-PWEC%Px(sTIMEJMzyM6kuKfhlmP65kw$qq#g$*6WM>b!ZjFPZ9@|iI{mo-neH~lApPUK=ClGGh8KDDi zxdUzpK+^%nxh7+k|NB1dzG^>C&^{A-0@}`82i-h#0vF${NBA_Rj4x;Ptpa~+_QX(P z*9F=_xxA8$&a#Mll0~cAURLjbF(`1WN-|t~2B<-&BqPz~%*jA@`1udr4+=8E*;9AL zJK!EnJ0%q9a<*cL^{m7s%XG>zrc?^Da-FY56u9bkAQuc+Xfv@pw3JbMnQLzW5s72t zqI93%Ps~Buppme6dvdNoZ3=9k2X#@Qj9!g4Jk&rNJsdGgn#7q-amFWcvpV01*zel6 z4Jns>25pCTNKuAYoY~AiF4i_~ISM9t@Z!uwo}Ww$Fn+pE`pW`mkM{~BHwJwA>s9wx z3V<#Sgld~~nr+#Rn@WuaMuO1QDzC1;TECTvG}>JbJ_PIqs>h2IMW=SjyrKlQzFqy< z)HbDRHfKAN8O^StGzRqHRh3{*{p13)$dHM4SB(dZKLaZrxDI(_jamq{F&2$xn&z>q zZkXp(e%=5@HN+@X@Ogh}>X8iz)wHj(^#r`8FM`g{1@h5DtjdqW`D**aK_=I7?4g(a z!uCtRFc4fYg+XV>-WEvxcVY9Wy9(hQ*0P<={)qePA>rBIQ3M-KXRdQ^ExkZwx)6AWIm z{W=Z*-vjCkgcIi)yDyb*O#mrZ40_EAT#g1vlwUZMZ}l+Kb_-f?{L?@-B=XbVa(ZN| zT^z!JGUkJ!P>eRn`w|`YvT`ELUwWd9_=R%(_rHCgvj%&7LxJw?{;F%(4_QR7_>=t~ z`>G=#_)rf<0`DP>?pT1wVhK(FEyWe2w`be3Ps7|x(r^guE}_l|(Lq7UkK5B+wfT)2 zr}z`6Abs{GyV`|I1@AEt9|GlJlng|Un>>n>bCorPN_^_%!iw<$tU{xbfN$m$a@G@7 zm$s4ul=b7M?iJa#MsQgi>(Orz6oI)`qTe70n6bvj4bx?vZdN8u_d=xEL^z$Cq~!A7 z025KoL}d^=N{wMj6CAY%cPr=~&d~9H^A*R4MEy&_-%|2brs@ z81A>;R*i380CJ3a%Dul{2#2x$rw9kC7OhY%g~5!0#V{xP#mNL^O#*NUK`i`i_e3Q6 zun*^k0zTP{HdKkpz>M1)Y@o%X%7>C;PQu$8I>v#Ji{MxLx1gw2>ywqAxyo$my32H76zFR3m$p@B)Ur59U{;OpiNVY zS=~#I@Df|h+BzQMMPAJMCXB{mlZkM^ufMIXLz*QL8@&%}Fsk9~qGl5gza2l21w1Z} zihlB9NX^9%R0Tg!bl<;30;%Pq7S0l5D_~0kX+ZOf?-rf0sV^|LW&Ldc&B3InV1$x1 z2MhBCEJvt&8C&t=09=AjP_#ws1~?Wpt1??dD#Z|fHib;U{>pDdNRm`<7qpyJiUq;w znXU{&$OM{3rcMAF?TYrr!bN&pcffWppdSBFeFfHb1Eg5$Tx;JXCJvcLGt8N6g|RC- z#K_bGqC$)nDu!u*WhC4|F>mAB{zV}0MN1$sAtuJCGBV7lCqs;Vm3@;s`qaj__CR3h z2*gt`%#q~WNs$br0I1?Pq%m#>rR009x5Qb4Q3m8U&v=Mg&{LYPzGkSo> zS0@62o{s>YK;Wx?1Of+u-#WOvq8Mf|!ZAjm))@%oH)@S9A$}g>dytnN-*$xCwR1dav*lT3pc&yWz~KGes-Kg1X_;Q!{;+(|O>zZJlagkfHLDaI(0F$xqr zpM`suE5^vgA`OIncrOqL#WM`yq5vTP1waM}1#p1Wzw}Kyh_=z=c^JA z>hNsGGrBy+7>@9BQO}V8DPRO(5+E8NM!QM@g?LvYoE$I&Fc=UCPyr$U(SU2HBR!s4 zKq_DuAPw*&;2hdw56Y1AMvSow`CbHc0Db~=0{<|DrVtT}~`w*6xcjR^WRA;$;BD zdJ4{>VSRnQ3GY(@GXZA6+H8%HMW1I-FWZ|?ZoCii1p@yU>MW4TFvr{5+h-#UGhikl ze^H3B^Z5{C@sbeZk@*-)=u@i!S5eH2-!shV8CF%?bcOM?V~jChfq4LUesM;`B$cR* zKmW`y8<3}5pF8ObJdXn6Q2xF6_5$8a&7Jh8gUB22>jBFF^8k0?J_*lsz>j#3$MYnf zp8?(ntOm>je24VL;(7T=hDpSe1^D46(xQ9-#Y(lY5;z4g-(21qVw`}w>jTUN%>xC8l_pCS(8odc}Ld&W7n(SxTEbJD@)&cI=WJp(ulw+_HL zyk7!b0sIRv2<6vYRU4NBM*R!8{ZnmB0<1FRPU?Vv7eGH6WgVM4Y0nsp8$7%4oC$CO zsADJLITp~~j&cCk3WOPjXC2zR0k8{@kMA5n7GV2bwNZs9!((1V*!BX2aRK_1J}Y<9 zp8@j#^YJ|$?mtac7(M7i-@&aAZf$t(1MIr5HtxjpHGmcH5<$JzSctW1&Z7I1)<1!M z`A}_4SLaUBjL)4U8J9b09Nwn_BJl0X3^4}amX9!Dcus)Z6L>y_X9}K~fH8mrnDOT$ ztxmju7iOAt0na0Vj{zRQH~AP(c&-I32TTO~1~3N@2uPV1@SKJ)sZZxlvLS7nzoPK| zGTwgyTm*ap_yfQLCxC*)5065mPtwZ;>8Zov0tJZ}L? z@NNT4;4s(XIhEc4BLGQ&P{3BeUninJ;Q1z=PQcfAUyElE;48HgZ#>4*|V(eH8Iw3mN_|x(b_3Wx$o0pJ{A zlmHHp2uK2i0UDk``hfX>Ge}!MCDzDcBo1xU8ddNwM%lL`ui3enHwb^Y#RB30;ebfM z=kPOr2D}0L@ILPU{FrqDPZncZ43GjOfI$E~(h%W!4*n0Y9>*Qf8ZRPVC%)TJN5kRI z07?J{2m^!z6o{LFG_K-loDyvN@9|y&SdOy11h|NN z3gO57PppyF?yulyUmk08;5i@9kMOJplmb=(zXb@Jj(+kko__{>0r+WUtkKTpO!^1j zW8kL@11?xARw4b#_`V2u4NwU<4hRKJpadjN&7H&p4t}9EM&p?VXh0sk1$4?VhOs}x zFwCo<+nxta*boTVKMMrb@4>tYIO0a0cn(LLBY^h-nlj*v=M#w5iMcPQ0cm^&x&v;X z1J*VnE^wNNI(fP2U%5TsFvf=JSmSF*hf74=eWNwT0f<1KgfM*`^lijDA!nEg_%;Hb z0o;JwGwAP67vxUL0n7&!;(G$(>febqPIF@2LA`dMtTXXl27kuRFkA5)hHxk78_#p_ zi@~!4-_^h&Eh0|i!BdZC8J_Fm=facugke(9PkzE2yc}+wsH5c{#~PnN9S+B{oYFvk z6?j$wP--HoT7!W@bq6J0NfnRiSR1~O&fgz)+(}!I&VK>khCl7cPP`dy{BL}(1`O=)XkSHpJlbQ?zK!-!QqaJA z5Qb$~re`7M5|k$buuY8iw_r_!AJOc0F?MEVV-TU=Ffn)-0UDx7F!$j7A?oE8AO&$W zm}iKFL~4u*_-Tl)gd5S54eR2J`d8zODnQTrIAc3tG0K1D4{^o=00yxx?o%5NfFAu5 z-Wkjpv}as}dbs*0hFOlVU7u);r1B(iBM?}HZ`x?5G7KwB}`*U^3uM@390 z(xQV&y3=^75NrNi0Pq}o4Cx^3dc-?7x^3RSHjl5L(|qIO0~;$>?~)C+b?nL4#=bbkH2equKM(ZWHf~?!cvZZ{GxElW+;KHs@3vN+yJGtBH}Cx^;Zebj zfBhfz2ZPqn9r?Fme|sVG#bV>$ukX(KV(cE|H50HFc`e5?|7)$WoB;0~fHMFIzV`r7 zV%0tD5s6kSd=B$6#yIWApTc_%fZCn<1JPd!q(^Oend0^D@Yls187e_0?!aYU383b4*K9gx=OfFnvki@{xP62XjVQ? z*C6~*#^j*`u(V(Fa$FNxSvqvk&F|sZ=h=+en}Y`wo}rr|ZD#R8#mB5O6fOT3{DVG> zw@EgNjxs_{nW6@-S^W3mI+OUTDblkh@#nEWoiZKLKp~yP|MsKjm6q{+g6f$Pd8&HJ z1Iu2Vx6!qlzwVK3PEYVSb%oMWpn%yI-SBcK&Ufq$T*i&P918T285gs9Qv?`<=atUe z><;-VaZZrS#Vr1$gmmod5X9_ho;Q*dD~E-Sbc#hKUx}PkBH)e-aTswu`B|Xm0O4*s z$`mEc=Y}D3-|LTLU!!9&%}U&>`5#%Ty1@~I?;vkyIPcl#c!#h^hfXyp?A3TRjyLK1 zB4mJYwl8s%(-$w^%TN9UNso}?-^RUx5wg6$;%o@#KADmL4)Sm`>s3tXNH?&b$1c(t zTEQJDhK9xsk1no5&SGCB=@$LVBj`Iq)}gvfk1XTCc0=b*j!h46hUL^#5^lu=O&VBu zsf8@hiK=-#ec7nHpteK*caQw-LEZ}JCo+;dqF#oAgLQ27?;qfZ6ud3am}99E>7MD2 zMLLmiy_#D4adacAqw_4oX{9$=@B3j0>;&Uf5!&x{XC8rx6Bp4w{}3F8+wIXQStsdU z`pOVlH=WTT7fr@c&CA)@^B<_UNfXy}dLz>77e4oZZn+?ZKdbP;acP#sG4}!L3i;6` z(#~z9sSpKln8|hL#{wp5^t=J=i-k11H|Pr~1olSqC;n^jFwT)f~#k{X%(UYr6;% zmZ9kTbypluQHHkR6dEG~bq8m!i4xaK)}Ilyc?$=z-wb(dYe{#8YQ;Ek><`QkT6Yow zaAGH%3)V$KGO{UBRFp5(bLxeQLl@F?C!rPU5{x4u8?q|Z-`>ek>O)wqe9CDGuu27N! z%%Hl=bL7BDrX)xgve5*nGW~g1(JV-9>jI*++XdW)0dPSm(SaT=(9P+9tLw z19~-29_sbh3~8;&2NNg;>u2O|@YoIJ!6;Qw$4jJe>F=`Ck3q{51>DqQ22>=Unm1USSU>X7zEm@uVsI@S=vyVvzX zU>ien|HqEslY`~L?Uk#0t*t5RFma*|L{6bHpwYU-lxh$v18BFk1p6~?#)_hHT0JTp zv3pz799BvK9V&B4FCAM8Rc(kIT=b*DfD1(76IzTiXZH#-p%VIBk(h1wkP1w8IJO6LDz6l`~Cmvj=-_qs$RTAs~7O33>~4U04BXqh1yC zplR7xdf#iIUe!O5`ds(9a<7HDAbL02x_$?Re{dfO5wi$Yv-Zw?x=m5Id3EAWuT{;l zu9aKIaPjuE&3xW=1gKu*6*F$J$eTxl0qyV3OEu(Cdl}j$Oiuz!hQQbKPfD~w!b_Oy zCa!ck$Eyc7ODcFxqnH=4MR>>6V8-6ISCh*5ym#Q#ENyt5d@hoYp)HQ%O^13WO1RhE zl20*paDIEmFHYmzu`TiU*C*zbFc%@>qd{w#f_DQ_Gnc~ipYy^lzI>jTZ} z8%8KxnI%VhUdr8IEYY;j&7Z~Hp3?NLcJF=7NR4421sNtLTxbggK}^~C$77+9Z5Gd9 z{j=|bWKyP9#e?2CADE%!BFisek~pT({WqBilGxg5>ZiFE%*EdY%8#M%&l~J4c-L9* z=U@@YyWjuYKzV}q*o0trB{y_Dok48rg>7Kn8Cd>mnCEY~7qrAzT@QKTxmQ$%L$7kK ziJhy#SS4oK&50w0*ql;eJ7LCXVf9eE;lB4TdoVjT(@dzR^_O4xTfXL{1U@K_^n0o% zKIYl9OkTP(Z5A*6Fm0u_=)NIlF!dYdIITfi=jHX|vJKMu5^2M@g-F5w0%!$wI_MbN zq9H4kwePTb;}}!IVBTX-eT~f<1GSABECpXe2G8*vrEjTM5DKzJY4F?7@)FjDrbCNc zJ>~U2$7~8C7--L}L-GdgbNn3Y)dt&4AeA)>4b11#w5-=^Fd(&sSqt?my|&+&<_tFE z*7La^mgG`jZ8Hbgu5zK|lBH`24IQB!R%oNR_gUEjps0|~+Pi3J83 z0+z~$ylgL@OY^=#wi8*S*99|%%SO_z2DQmP^N_YL=(WFXsh#!*Ec2+re47LP^9{8* z?q)G@j!>4bGZYYh!RzaRHrIyTuNjQN=}#Ntgw2p*8gc`E4%vNSPNNBB=@7W0KWIhw zX*h!8SWL*`{y&m09tFcB#S=j(YD4eyg|-Q|`NATkBP4}5{twV&SP(V1$;8|%^fi~c zNFT!~9XER_70xuHcd4;9j`{}D6lf_hZkg3lQWF>x_eijoclW@@%<1n<&1i}?|WFl5Ns)BGufZ_K-9%4$VeOX zM%_QL-UrL4zMMu=6< zgONOzi@GVDnY{Uuq*?YntD6=9s+%Ix`q!ucy$cB-=saG*Zrc2`V_lEiTl}IGCI~7U zjuLmizP@4VC7F|zKqWydE48GI# zO6wp5e}iRlEbeLYGyqF3q)x$Q?cZNh-DBu`tK7ImCTb4{d2xRi)$lm8riO zmbi7=XGP=AR*y`{y6!xpCtmHcv@A}6WU+U6Q%u|-LO&E}_EklrqP!5YC?MNM1!RPY zww7hGS$RF2#C@1jcS);UuB`GxQl5{hNz5r4&vwWHeO9I0g`rCvHg`gW4E)pq_L*2uryA)0O zCog{3Zo8dPcT&d)jf~PsyoeO-@1nl6rXGa zt1KkD7tuh&210O~s%~XC>4O^cqNzbw|GaygRIh};Zr(i*n>H>^A2e{J_dR-Igwnz* z3t?8q`mOY>&U>XBo!?5_#m~I;^F4R*q%@fo;$?X!_`F?6i?`jvf8E}2-R~aSdPUyk zM9d)m=VQFdq#~)h*PBedRqA!{p`9&w_JS|A_<(oYYr2(#`U7I4IvD=8GX`&R620U{ z0zpaA#-`TEt*pt*X6t&`x<&ArTd#$#g`a5wrV0A~6Xt?YhPpWfS5uNiO@$6gm4|N0+}sX@ox z|90eF^s?gG&=fB#S#v$SX&Zx-ewB<=em#`Z_Vvf$luhU5-ohg9v>rl*6^&h%&LzMh z_%&sj!V7k&fzP?i!no<)xT1rES1^cp4cyBA(@i2@76uaOKf+03mxT@g54Q;v>no*^ zOKKG|hZT>xH`tBC8RoO(cRypAY8V0UU^dbv*NJVOsZV|vtrb@U8PdnT>#us_pMkn} zu!+xo5go){rg1(;>OU~yELrxl*TWJo-hhiU{+Tt)iXgD`D@PF=<;$M)dK8Zx5#2Ua z>}17DiaCs5Rwlm!?=uv?66`p-9+kTO zQLBfogK34s+|x{Xd20?2tV^%>*2^(BK z=aE~)^}M}XFXCpKvWce0FHeNAPVYBr@NZ!4^6~$PTcDe8+fcqVh#SKgiZ}Fk>;D?0 zE*rqEgRrv|1G|mjTPNIp>Gsxi4B)oGUowE(hX22~EyNxrC6ZHLk#gpuVRMg*WgHI1 zm=9a{Y+`5Q#gG&f@!8zd$xcC>gNLa*F~smBg1k?7a9ZM4a8a0hk97-#o7`ZcbsIl_ zD(pmXBL%wQ68m8bl|ooIv|n^Xi<+Jtk2zp)d6nZ}H|ASV){6%7r=*a|wniehFej63 z$dt*@s+02ZFgRfDw3A_69G66-yTDaS|HO7)l3DBbC`|{o@5vH*XUL%PLg+ImU3i9&@DU2jhF(4-%?5~yv^0weST%}la+ zip6>FXo(=+tCRhka)PQiOB9oo+#a3n=~jOk$sf9fxC`sLp)N6X%s2eupBL`vhKuld zaO|k&-P^mlgrb;{T)MWV+X^ZLB><18us-mij5Rxy7nTTXsE7|`Vc>%l?e|wN>cY2D zrB2{DwRUB~1v@m9)Hs!TnH;Qv>krczT+})vuhQr=GiOTpX9r|1|0l4Vg3ckNlDWmJ2q~J z?>EqDRlN>Mw0%2O;3d7l)A^FrASeJtHvL`YKhwMMtMp*MBbXiz!YRFi$LTfxM|yOi z{=d^(<^N~5mASo?vQrV z9zarFf(CO72$#Ri$Ned2TaJ&T`lfD9xM%m?CH)XX8K05NwQ^3E#B@&XmF&=@tJG#x zJ)g4!!JX%%oP;w>&Bwcc=pa%`ve|u}#aX{8YaKTX8O*tCdf@rK81h= zeKbU148?RLKad}&)&BmSg0WAo+Vgh{vB~Y`TKfs*vPbP=p^yIys4+$AWalBwd0pC{ z@1kpOG8}Op{#n~`7cRo*r(;L$8t0CWnX+}HpfJ%86`7F{ZFv@2 zGi(v617$ok+Rfo(q6E#2nj)y4v(AYEdicpM1{nM6c0*w_wB+Nw-&7bA^sq&$EXoJy zLr`%>x+6)8hfsHp5AQy%=k@=t=T`^n`47J;x5FcZmGg=n0$s1IzMI9`($K!JD(~KY zqG~g=;d>QlCp4kr4_x7#cvvE3JhYsliUt)7ad=d$Q*jW-?`jw0dl(LS7Q`%RFxmid(1Q~~HifkLfA>I!%QB9Y z4bauI*4zaqh0-b;^fNi-XDx+HiTsrMUU$Znj;SkofaZBd+T{XOT@ zQRoGn(mM65^;@xwlIJwskQ5}hD6v5YD2EMCV- zp2C0Mp6;N+49kA0>7#E9vV)KiHI7sn@(#k6Tv&!a1(8;~qa&!Fh2cAiI$6pUc8^?V z*a4NAP{=v?TQV#!K_vWSxGUpQOY%nbe;yBb5w#u^iO4_x!JE)LwjDVk^~X6OVB3#4 zP}*@KW3=7mVUZr3np&lx+wh`$3wnc65;%Sbx*o<;F8K~vkP`ZlHvTSJ5vv$9HE>q9 z;%W6%5r1Sfy6okr%J<_0=x{Hr$m5WREbRKH4zi37a0VGHsbl`UcoZ(xTigydUS<@E$0$S|T`mQ8!T%dq{-a7i6I zzTWnW3_2a4K6AX!akUH0Xz&dk@AKc1>Dl9w46hwWz>X{A&YzM~jn|?g@C%NIb6vEK z$lZ$ChH-9%uV`GTQ?X-g@esOz`D*}Y7AC=Whi0qBoljGe5EI-E=;J*PZQq3F3HM8m zwyyR2X;dPm9UfAW_N%a{i_FivOtlr9lq+(H4Zi8HC}PaFJH;`p(D;^=M`t$-A=_ROFrYLTQQC&F7Gi5 z+3b(I%-c^OV!z34MTO{ot7?n=!pEaW8SlO<2KlD<&$IY|S8aN137~PWcoE zgUxbNau^8LW0pm(w@hfDU4F^GsP<#yGnZ{r?=vHF{f> zj?t7_`7(@xv2K6RR15kP&UN|%<;ph(?203upD(z=h!sikKHTO|(-$xF zPeFQ_L_(;3wX&`z59ZTVq;ErhQry)d=`x9{9byXqrn0)8dp6_kMdl74kJ37hjxV%y3%4}9RI_T?MM5Wf1nV5s?JM)*T$Z}AS_W1q|dIB+fQh6>@Zx`#2&PK zE#f7kigl4pPRVKYIR?W0&Kw#} z_zmtfNlw9@rio?LLm87tiP|aKfH7ibzcmR8tKIsji#D@~hO7E$pSOkfggA$zb(~?; z62b!)U%Pfidp%13HHeR$GMLU9Otj+Q2Pv7N7-;JI(#sy+zt5K%@Cu0*CCIsCc+2hv z5TC0@bd!(;+_K4wzowj)(G27SoOzc_yv^;e&hjWD{wgT};OzjHmHhZKq ze_nLO|0GyOT1CVl*O8Gi?TD1G|u{Tfgk4H z!O?AkX*-2HIp@yq)ps1LsSkM<4K812sV2j04tk$UUYdzG{5)m+%|FuEVJ9S`TC+m+lXy2u87 z9lg}46_;#3@zPqmTmH1=z7(U5T`Ko}H5#!UV}%|rg)%&TNi}7 zk-lIR$+~dLLdl)AGVAse%a%B0Ppi)Pz#4ME|n-99? z`O)H-lO2a|Cq2Z;`8ik`2|cbvb(V3Q*C#!A0G7jGi43$zt7k}Ks4g8Xj{cFo@3yyQ zx=T`DXVCxFzd*(*=6@vOjf6ST#%Cd8`^16u}ISm9)mky z6?2vcEzL5tmt!AA>PyEbtYtg)&{s(=g*J-@WsGipEa{AU1#Stqnie!fA43DfDuhGO zJji>(hTx9d*ne?~;n$#buqlBVo2VqhZq=}Q!q4u>vA>>8C+|)UHdUDfBa>ER=T(f- zsL{N|DKw>P7gLi+Q= zK(oJ-O_u;X7teqpaBGbV>S{ECI-E8VyI`O%0JS(SliQm)^LCaPH;UU&=fCPoZ8Idrqz(FTAB?Nj7J_l*HV~0?k!Hd;MvVH#N$?un>B9XbHA9iGOLzb@($4{ zgF8!F3OI!o@}?WZ%iPqZTu?_cg=j1*D|52)!px;7OMg(?xHq7*f`Ps0Qin5}jPx)Kk+fslJ-yZ@lt$W9bs>OaT+^y0k zsXF7}DlEY2&%iF3{M|6PXyq?vzwvtMtkzsLvh;30;nLRE?TZ0hTvyi#pwy(`=E z+J@3>__nElw&Fd0=}LS+uQ&rk;L;cQji&>yU+l=?(yYujfy$O#8OYE|?3UOx22bisw4%%#FgQ>j!6UG(A^Zb0eI&F?cO@xOQ7} zBk^W0j&Rl3i|i%2DtxV!+JdNQ1@l++Ekg#Nq`DRxMo!$F}SM)1(kt+eG#c zBjDHswwoiY=QBH012)P_gUa@xW~)-f!%J`oTHDnh!6TLnF& zw67!X2+X0GmR~?)gC;*Y{Fj#Dzc_|dPr$Wns5bQ%ua#QFp(iKk4a;KvSCWX;Y|&G~ z7ySG`BsotjxnzM!!dsmAm|IL28nAuc%@z3G73nG%o8*!2gC4)P$IlG#X=(@kLVILo z<`cg_!XZpTNvc>oK0}r8)q6$QyBZN>8wqmyG9)C>_=3C(2!E+6C zbnB3jH!o2vzdIB9R&x}srn-s?UILwVe=f;S#jpi@=<`p7)&@1x_p~ERf z7fY;zF~4h+05#TenPSagWuS-pQT?7=$VNdhKXWAGjACZG7P%uu<|t9coR^)m8S`ur z@R+-g^nj$Kup3VV%u%d0l3g(8WkZyhj}&W0zHFY&8fH@&@yk0Bm=PlTis&bBX88Aa zThr&Nqh;I(vqUk)_FLpE@wTWP2Po_1J@(gCCRsWMQ|(V6?xwfn&7LrIPgsdM+8q(P zW}Lzu!EG7K=8XjBu{m!Tf~e~h>QxHi3p;cn7F^o~GYmJ8Q$8iEBQb^WBz17ni9QKWz0V zje9hN4U4XHH!Bev=a;%40+zBzWV)2GymN1sy>tD&Vkw`u19R3YVXBK}$DB^kZHkHmA#O#bda0E62z(Y!F^;*r^>>^{RL~=*o!$w)2`7lA zd|FimmJrkUq|fazSjFk7@6N7vC$S|Gg(g+y zjAlxrq7PhIlQju?HKIkE#=^p(vo!#1++LvpZC4(;v@54|maVbMnPv40r*@VVS!GO# z66X?2HhsjI1RYGwntfksV^OM-NOO@NtniME&P`kNd9jS~FxjNHeM?FOh&QtYikle5 z`6bl@Y0Ol~i^nxfp<=I$_p%kZGp*Nf4PH|P3VQj&i2e28s)pv;ZKYblz^g++y~U-i z%ydqsp1QsXrE7{uSCDF>J5ysTxKp2OVK@FQVEV{z#7aFm9f7FMj`iVNX&_-}D+rPvv=BjsusAzA8GRKzZ0d3`b+AWf}sPOU_WYOlx}Z+6_f zwJ9M2pFU@IlSc-1VD0LS;0}cY2d~+s&kj%Jwq2w+fNbt7tCYe+wH%#EUaK z&fMBm#cq6p(XH!N7s$C6+nb!}bGhfZ-@5au5?rvmup{MKBDxkS(5#4Es=CCsqCom& z?=hk$kQ>;k*WdB->c^P-ZzYXTHY~$}-j#&z;}oYemC0vIMS?~~N);N)6R=X)@rs=v zZ4q>xNqM)4R~3sS78%{jZeWPzZsyD`uz_9(0a7on!>$!4oayGmXp?|kf9u+=N4vDu z>2A-%CPjM1XR7u;z}|%JxhN1hZ&W&uq_l6xT3?hPH3{l$KHR#cvZFGSDNR0GC*e3! zn@D&N`SX{6`cbl{7T zK2Dk@EVPU5a5vaSc#o)ko$h1??s8EFlr;HiXWSB2J%eIjc`}`fV=eUOC8^T`bS8UF z>1IFSJ<+N0KjIV^_bpD()7Zjrahj~nBgAba8-z4)Qj5eb`x$>PUU0BU7bKJc>V4tp zTaC~mSt+xgmv^|iq>SO4owW@>pscjrU?0Ar;YxKDuU-!Fm~VY#_Ar{l4Q9)7l#iG7 zw7Y{9sCx$n#Ql%L=m?&{{T`TIDTLFrOZ|JPeWSfe$LM1|RqWHH#py?Xs)wEr^R|O& zSx)r}e0-6nQq?3oX8BN3p&2?8*Tb5w+p^EEsGmQjo}VUaO&QUYG8}2yZicC=?(>!x z@Qz>Jj{&~+a(Y@JTefjuBYc^6HW6%5GXKZrG zhE-2flGuFoQ1ycAaqYr?oVoQ7o49uC&OozX?^Z3lPdYj*8ZRph94?V8=l?#j{7 zP1BU_hAL>rcPgUhUX{9Qj1@VWC0C_Ruic)bd9mKtP5WQxM?>s6D%=MB)O%YD<;Pc| zq^F`JN22zLr_!2jI~%4>zt6>)o~1EF*b-YmwUOiW&+Ea>=*3z7Ji1GB*Iur2z4hSd zeIZBUQFUpR750{tBId5rfJ7~^k`D z&DR?aYF1sm?LF4(8MfhKiDT!_dPT`8xi@zCf$Q9OEH4e?W{9y1_tqY64&j#9*KVa5 z&fz1ZDkCfx`nYr)`Y??1J2@Y>yeLx2D=w+sk7k5`ML<1nkmWQt5YrpP$5BO5xrE9H z@03fFRQb$|OUS0I=*c6rm>7o1B*8>U>uXG+n0^=2uiAUcZiCwHrlNxT9PZ<=8LWvL+Y=dz#HV9N73lz%7)Ef*%PWJF8$dbZ^R@ z>d8&Df{_FN8QglozPzk9u<@T*zawQqo(at1Q-8(~$r77R%bn57i`EXoXe}Fwt-+x< zT~&8#)u3q~>rO%wp&XidXVWOeFF2Pta7>ap?q^J{=OFfCz9e@`FO7}Ypz`Y*>Bw)Z z7IwLV$J%440X$MlqA}Cy9x=+0dkMig$b2=khB?dY8%?>#f>}65P!xl1 zm?cVDG&IY!t;Z0v8n=d~Z3m}p9)+VvmizuhqsG54K(gFLYN_Q;uli`OL6>ehBn^6V z3D8~Fz6$X&GKQ+R^^t3HSYsH-sAkBN5%CvInecL$uZ$+%#3ba+%UQD=>@!br*p&`8 zWe?$JDT62p=T)EwyD{E?wR6sLLc6}vntL&bws6qr2;4-Pbb#;7rOt*QBI1StV^UMm z#g+7hWOm#nZJTma)bfT=PTWsM+TEnP(i^p+-St+~&s9|w&JE>PwGlt_i^k9)I*}S6 zi#$^2v(y4jo+$j+4G*)-dxXi+Bsjw5F|Ur}%uQ$*#QB}v9dfBUgsOOXeH~nZS$hJM z8wq0@bHuTm7};q4;GJLGazi0a6?@Zocif89tx25nt7Kc&3H2IPg}?5ySoa{H8WyIAEEU#iAU8K(^5?p-v@kSwIo&m)XF(bnB0wQ8wb z2l3#ZU@wgbDKFq_4{P-H0X#i7v498#@`m)_&cAwtxAt-ouc>#{iT6eARMaJZ8kaTF zTg)1Y#r#y7&iZMpdRI-$O+%Dyr($PZ%@;SlOUIL4opA5AgC2++6!uS=pcpXwdxePU zE<>CQ9R{8Vh?MYa!<0{RD)?TtuimU=o#(MM_FQZg)bZiKuiizcex>f(hALN@g7?t* z4C$e?%nP{VmaFeS8UZd;YQ%ostf=uuao;J&vYP`Hzjx}$CS2op?BD139n~8ZTx-2a z+g!Oba{1nT2v#24-^6t|mXJ5cwsi+mA}?|spx>SsT&yUBK#Lo@IIAT`lKt#WFrAsu zEEv^OM-u~5l*k!ZWdBsfOOAP?SE$X{!S+~gi+1gTp0TFcG^1e=!+#=SjA2;A1Rh)1 z64lTOwre)d5}?r*<_51sKX2D`m5OeQB{;rs9Xg_ED6Of!6`0?>SqemItHdk2 z*ibcL=oEJtW=Me+KmgRy@KIADVaGJ+#HWnrXsG64vlCe~_AI`=17SfEZ^Uh7zB5Qj z$a+i`nwtCa`MhIz7R3(za5s*j)GwH4QJ*lY=bLBI)vHhp;1WIWb#xE~Qleg9$K6b>vg3j0-jK;p| zB~91LYaIed59rfXm2zCImVgU2c6m|3OmFOpu~h|z)M4t$lBU|j`#%+Ctl$*$&kp3* z)S}`NFw0~ofeUYz!a8?>byf&JcOm90)0D4G*@Mkf+8=M8`{%CU9HedU2&yrZd*fDY zsS4xbopH;ZNBV-QPy5H5_7DY%1QjTFKH6IdRxFK1xZuqXHfpFgy_I*Sh$k*2a zLKFerivL!h7h&r0D&~8SJ#^>)H`;@X=MHQ`e8@s5bLJ^zHa~SC zyvVm6G$itEl$h9eo5d-wJ;QAU(YYmB32O{Ri?eDgr9rs{t}>{G-+4;pR^$}LKk1GP zuidJLghzf3`}8{Q1rh`U4IY0fhKfk{y1&t)Mnu4s`j zc+JBN?7Nr3q0lxQg?y~*-(T>Ei`#_tRACU}3~;j`&RdlomSpCwEge{3A_q@dmcuEI zE4-02YD30zi4zrW_I>ZsKKIf4o~Jidys^Q)LGx9dmS;V0a^2>5$6TR)!Qf=Q?2Jg) zJ2rKYtpeyFB|?;FLdY*f4sI4tDb59r2NC20#{{|2_i7wwYC4GM2{)RK-2R3t?oe=3 zo$Q}+t>FIXxYI-HsV-g2PL6EI$w=kPQy?Gq# zk08XTKR>upsqmgxxT?z6a*De8O;v-?YF_^Kpr}AiG&SLTV~7p^V;R zlkwki;s%N=j2p+H8(e$^pCJrdKL2?`e*acUXqSbA&(sLyhB*s+>+DZ%xFp#fH_|e- zr*16O78G-mG|>o&(_{Cl<(tabyiCTcmbtW>K!T2B>SVRCtPD;vl`8^Hc~3G)^PAct z8tHt|ahY%^zfLZxB-BiwmUSWdTAW;caKmJgIrHe)Dxc-gK%VdwnL10^EKZv5ZHsWV zl+p!@V;e;=sO2k<-gpT-Y!*2jd3HYE+6RO)zr2w#TGed`onljH58Qz0A!gvYizEkyR~WmjZN?Oc;2jF6 ztq=7gk14{j^F~>YqvVE5QBaJSka}>n1hGslO(7iD_2ZcBy#ccJf8+Q;KaR1$@$G&b zQ-5T^PQdX%3JJj4T|Z5-N?UlN2?DI8E>>H9gSe_St(w)P+Ea1zPr~9(#mQ0z!-mu; zg{t;_Wg<4jt6B@GLYzm8_#fQ!fv%bIIE_F2JB@fD4HeS(|BQ?NncY`S7T(;7-14K9 zN_8p3X+baMB6T5yfqtx;gnk?-Uxz+CrI_WF?+bY^OuGRZ6uk*6V6m*^timZ@TeQ|h zq;<^;H)wTDrJCyK?H)R!``L8dQJM1=8S<=1+A4oVUId$45^ltaIU3lC!(kr|(1n{J zn-9}JjR{>-nA1aN2m^vjaKlI#(}x4FbcR=Yh5iirv1E)CB`%#28nZK|NZUj39@>Q! z4{;U-uEPzeI#ZZgh8r^r?YK-Z7pDOaUuGW(5W7~pQkr7qTS5mnNmXOti`^G9yTd8I$Gt1cZmx7TwI1f>bO*I_k0`^W1h2(O<}l*nFC zZ(`Ijk4j<&&t39;iEM4dk`mb~@+DfKl45SaO7`EcqmJ5phl?|CwUzfuu5njPbLV<}9Y1+~Fo@$5%FS`>x^ofTXi{4& zWNcxm;}De8(QqAvQA0W;<~Xv`norHiO}aVgl5%*%?km@K(rEL2D(q803UF!e{Qh(W zHf_oq=q2>23q(%kyD9l>QCujfAVJm$sv8o5IRZxqlUZ{ef@e$N;-cB5bma{PShiM| zhVO3;b+vL#;%BY-{o4TFyuPG(rxFXEs$*YLh+7aB=1NzWMwGRhTB6JLv~sdUSL-yY z0$vm?x5|?u`2m??*GjnR#i?;bFVN}EN5|2>7c!2O*M%vxvbf>X_uj%eVFVh1#P-mwr>0Ww+&oCu@YCp3PxA%nRiR(jFqtc_<2#7^ZrrI`>ZG5&mDtoT+R+-( z7?Pxb_UF)gSZ+jF3W$IgT)YGNptW$({^mOEB@}vVxwok$)a#*~kO?Kd8~+ILDBbqs z#Eub)Z~SOK!Sv4$#xC56_yZ5n{c(=oUJp_pcO*H2ZTnf{uDhgW&}-7Q4O^Q?0=ecT z^aRH^>HrtlIi;`2iz9J8;nFyBsbg|H{$W3i(G(o7J{vK_4)BGeT}^$Cq1Pu0inKum zt}RL%0t24aTdB8u^`Q{-cJM-XUx%;@IAZE|Mqx?`X*!gKkv$h!!Q);8cK_%n*t21N z*L6LBeMQHp>vmzfH_RjEFQkP3zBRBz#Te#Mnen4)r@jiRv3wL4Et3Fr`Fnn}8L!icpN9x^REZ;H?tHfOKR*H8E@hZ4P-T!dv^t)X0 z<3O^bXj}QBH=V62oGugD7{M6A@bt-e}XoMAnv@DlPs2F_^bXUgy&AT#I zS)OGo#&1yH>EI>@k$5P-Da9TjxB)=^$b5#<(t921EV$U0uXlZLi^5a4n)zAw-}@HqG2Rk8!HLRns46qV#m2-p7QT59DyND4?~ zbX1P(Tlr-Pvk}UEi;_W3J*(YuEj8{Re8S+`E93dIB2dAmJm8~OTg;48_OAM>9M>iZ zC+*i-9M`Cx?AL%Q1XK$wv!$G2Bg-Ias`W6AFW&wDeP`-;PG+J(&@8vkqjP|%1&Q@0 zDPt%|G!+cNH>I(f(r9Ma_i>S#ORv#c5F{)!{ihPzh>?$*_!vzvyfM6bhT9{Xaf<%gv$5C1E=KBYB{N>kih}f!3YnI|lL6<#Zgfi5O6}4N(ww({CbGpI2 ztcHE46ok+FJkTifp9~Psw{TC=$Uc{e1$Z1y6gDLmq|6*3aNx_ z(O2)XZFXp}H*TpqU%ur?3pWFtZ0uz@!;OUO+L1Kby+Bq(+iMInL0P+1;f@)cx|Gd( z8~QeeD^K#*TKH>@WU4XTX;>0Mxu~G*c!pDrk zLwZFCYH!S7`Sr_ScnncFo~2YQ=?~kk28zb>t?=oH5qw$&t{ulT@;@R{7xcs~cWk^K zV2b7q6+%S|p^nn3b;xV!Q$4Kcn?#Su@G<}#IMmEdfWE_SA@KnZTnjwuNd0N zw6sk&3*EuhQkZEfP;$|)j4v&CZr;*m=p6-#NSBiCyo&tS_ko7d{&SFkazU?GVoG&z^*2CQMo|L0aZ5n`ou3Q+ zH0F}>NDDmLhLPD_sV*)+x7AIj6)r88#Dy8+<>MkkvobDjI00ieq4O<={&DJ9?}-VU zEhGPt`OmBE(fH?zz-)aarhR%-=vsAX=iY*$Ug@7x_CJx7xT{{3l=um9TMd)XjnW_s zjXxCpGM2K7>QR4pd$KAvtJK$+luudNGHRIEYi!<&0nEHYQQ5rWfO@+>D`M;-cB3s| zkiKgXpI6Vla7m2L`G3>(F5pd7S>O1{IVYEP<8%kOV_|gCY z5oX#z!bKUiqJo3(B&n7Hbp}$EQc;sgv{XAv29b+>hXg1HWrT`CD=4=JqRv1?gi@OC zw@wP<`~QF6^Q7s?KKruvZSA$zUKjFbgtduuItTKcm$Tv1N#$c#Sk`hzw!C(W&sdI* z;iG>Ty28CMg+>OoQOwitO!ryypyN#&-~W0#Tvw6XF+RL49sa&TvH+WbJ4yeR>zmgG z68W2kQ^w8jHFF_W-66YdJ!M9ra4WEza|x{jD3u}q(f;uE5r{-}BlCWLxrQ_1sO49P zMJtfqlE{1Cy4=)A&3y{iwUIM+s>Gs|V$lL575?RNX%khdOR`<*)&CR;pX+JlB#N!H z$@yQ@2%UD8t&I1@%eb*`YSiDKG;Dk}m+_dPT~)aDvbW}Plh3$-=2yRmgQ*kFQ;~eC z$%s5oO~Qt(JzSFxDbb-jH?lQUSx9;ZMN!-RNfRJJgk`L5#AUaKmox$-8pOq}gh;_< z?4we{A11dopp!MpK&QZeJ`d}^bsgVf=wl`-unVR0_zgwHeV2jRfv8p}Tqjj7)r!n~ z)>HsnfM#~v%*(q!-bDDzIgq;5qPDEXW!Ww|+5FGlenDNY+nJ}C+fPV;Id=NmDms($ zwWlEFUG6%gviziq9fe1sd(3XO8iRT(){r{L?a|t|vl}K~UXR0QHf;ifYNhf5t9S@u zu;cR5E{_?&D#j!650en}{Kk5ia7i zXoj5>mBL4VHWuUVo83n=_|HU4w6i1*esW9w_(rUXoP&oh{VsqjICft6`fGf1y7T3&l60-*xX@B0;*! zr&^hHCDrHUT-oMC?=BUQKN--H8iUSRsi+?{j%Mt@g#$Zgu!NBJ`2;o?%2FqxL(>1)ZUk zIOoPot24%tI7a@O`%w3KUlo*4ExT{K4*lZrRatUxXD#T5+Zxh9`52b~ICpUH@!`vf zLLh3ioV9?0h;ND&43@b!$@3A;ti*GEcTc`zsvM-1ky|;vNNb#Um!mr+jUCv4w#6i+ zrznliM=nVWhAUgHx!DWb1$3~QV!%}}W#&r)pD)Mk=+<4z9ofto?X;KurrX2SF2xEv zC^{W;W3etXd%}%;b!OUhK@FzM)Q`!`A8jwWhB@Q(A;A>GFqtbB-B=-MalW=FEyrH} z#b$LVJx+KuytS8vqJSlQp18FVx$%U`$geEEh_bdFv8Zr+#HeQ|bqKH7e#dg26J8dh z=JrAIEdqEzk3shu`9Bq4$sp>Pb`N+J7MltRQLNS9C@A0r3h%!ZK!FM`-=iB9lHE=r zX!Wduf}%XlC3{h!(bEG}Gd8=RCfR0`7MkF#x!%;Ah*s6zaL%^BxI@j~qJl1q?Tc76dZ6Oc{jA*^Qf z9kYjeI{U@LMhPW0^ZMfJZQV7TB)eWYolNa$+Cbt0V4)w8d8%wSfAGmfd3&Pr*w?&t zOh7U(-DcB#0SQG-FCHOOrZ-*(vU}>>w>1bWPmIvk1j_)ine996o&a-RF9U`cJ3NLk z?>70Rmt%bCal4y@fu41B4$t!1?%20IyXroKUi4fBbWrM*6TXxg+irjRVUq*<$v#+) z#En<}LByEtz1xstpHjwd2S$Vg@lV>bhnW1vcnieG=YIl?C5yfBzPRz*vA_VJw`$e%6JBlcm57zv;#xVa=R1RTjU=8vtSj5|BXbtl0 zMGMmNl}4`c^bp#59+`1s1=<%#oZ#0B2A%Bv&y7h;-llKIB*QGlml9{V*M42Brt}gW zT`wW@Gtg>NqA))_Q^N{NSD7qkgr6|25uf*j*M8oV`Of#+`pC-+Ce&* zUXBQAiK4SPLCI9F!J3!r+atmN&C(u4HK>%gjGlzzsv`kU!G|N`Pjd(Z`QH%%YOG*) zkM+PBh7ocVpG1Tut1p(G9Z?juo!BWO1vj`jamldy)!2 ze4aSv;(wQa+b2q+dJ(7{#5v(>I`M}Nb3t`?#B!YFo}G0+%Fpmek%yv}l0O~DpMU!; z#ET_z*9khF?IjDb8aVH=Zy|qjj;6&xEFLd3Ks_EBMI}`Ls_n%<=-(ffRJHJ*ya+sD z_5f9=%|&#mSX|H{Byewc*LE7y2kGqJYJm&q(pd}$KuO_2zd~5g0PP6pQBIV~A+_%= zt|F1(nWL!uLRG0;p&0{h62LS0TX-HzAaE?{Dq+COYBJ1lEZ3x|%m;s&zO~9TeYs|q z5~%Nb_k8saOUoYqws`b1I)4{MG;T$6Cyod~=>^cE zuK%}L89L!n0A!opE2iL>{S3#f&%=oK*0vQ`6PWFlh)FWqu+RRtG>>L{n==_GcA39W zqo?AeyNx{|v_iiP^2o2k=o^HQzzsCmi!%VCe||&~IBsTz^I{1Vkw!4=f=nd(8@gzy zG&**+6@m#iH%`VF)Ch_RyxF68_NBO`m6b|npgp#zvWSF4&0N{uaJC%ySY)l@L|8T> zl&UC&Ri%Dq-JYgiESJQ#^X!WgMfIy~A?(Z2xA77mASRI~UIWs@B9b18$`zU7Lz%8Y zf~J-o@2XVJ*PN7RxcW|l@N}V->`9Srr7-kED4r=6C3XsiXnVs6o@x?HZ95f)qtqSE zoS=zPSZ{_go#S1QUm(EM-Rx>)2M29m%$g=J7T+!F#2BQ!Z(l42TO>k)dOibwDKu7@ zn5Zna#%qW3;F0Wh8Q_=t7hQer@w94iD*3y0I;3rX z?|wmD)_YNtn_MHujk7yug=Qt(?zZsW(P79sdoQAQmbr<6gOL2dK0x~IQ)UJZj(01w zT*_=;q53PYyD-)zd5=Mx(E+g=SVb0NH@yjT=-*2K<5}qSC&&CY9$xr z7%3Z9BP6*NCb^UzL(z29QK|IW(+1{)PGsGj)jl9zc}Z^I7AV2PbI}}q?-m$1tGlSI zvdC;Gn&B#%iL&%YmA^p4QP5eU%t40;e;?COmMKoQ8>c`{&4=HMnBt+Qssv&IK$QUK zxr8Tc9Eg;S@4FxYAe7c?A|x*n=E5{jXtIlYM1H#V?Yb7;|7HZQ4Z2i(XDhOjjNu7w z`Enr)CdMqWFm^ExQo`sc4-~*-G7v4>4GFf*-I{Sdpl1Red3a+lga@`PA?iH@XN^o& z_})cpFhQEXe100OM?*y_990YyW9`_4@Ec^J#MtL7CwryZ^&7i!rq;Vv(;f)m@1D@&Tx) zc6AFcti{7wC8M#(jQf7nT!-6(E1Ehcln4?Thv+YN3jcf&Ir@eHX8kj4!`m{d7uBT* zO*S^ts1$}}JXZ1k#idRD{jBMmNR5)#mZ0&zd9kUn&otadfXr6|#dZJe^&#DMn02wQ z#nw1%RgmhK+HsQnRwpa8U33LSAx5yF!M+P~=nep}H~3;}25y2|B}7igyXeXA5(cHL z!d%pXkF%Ka2}{L^ zlcNc?pL<(4;rTv1gKZ}SvKnIBgNZ|N1&UC8uSAywNxjI$!61J|8xWs#b^;-o@1Co+ zRDtv^q&-{66yASP;A#*xSCzf98G2p`V|Su__(pGLItf+u|LT=q=9kp&6JEH-Az)QY z3w;Z$L&C*=;^Fgy?4XLJ6~x`(EHg&;gpox3P5O-u@Sxe9luBFfo?WZrkZz zF?kRyad6m3^-6R!czpNGjOR|}JvT^QUd{{i4W792&+9__#|QRjN+da^uA1EMGQWi$ z#%C7smxkcm-Yy@xL} zZT*hs-}x$mAmm)mb3aVH!jj@8vzIKg^7BtWYvl?zX9^8S3?J$Z?VA|jj8O)yqWXgH z_|gUCJID(Bd{nX3LDihsaX%b}xIBLww!OWI-4UjppKp2N z$NC|f$v?W48&AjJU|GMu$o`1Rt;}8odHDwsEQ@jOhlv2_pgx8_>BSOJ;ByTYDo?ZTTS$RQl(j|e z$r9JvcUmZ3g?v1d#eIyCw+aoG6W@kE>V+naFh%hit(m@k>&&}=lNMKSHL48@FErF^ z+R4g56mx2gzC^{C^!s(oF2E1W`W!9p(0z%@jcU1+t`tKBS@l2m`3b3D#0nYiGYV)I zU-#)`EAu2C+4kq|Y0&-<=aQyoqmFugGxDSQbb5>WP#&%sijnoKf*Gy^G-YuY8s+w+ zSXU?8?n$UrE!6zNflhI$=ZW_z?Th=>>zpMQEIGhu7ohLorDJ>gFS0&xUSeoIXqgYejeMWgG4~JK@4aK+A>vr%kXH>2svVeRZxqy0Q6*J63wv{Y&Zv*7S7*@>%-~f>wE9d-Q$xc`DoeGlX54PqWouM5qzu{X7EGEAx?_ z?|8bG8l9Gro^e0$r^g@v3wU12q{Kt()I?GtXSK z5iiO`Vj4!)^(9)WpTI$PQbLT=m=mM89zHIQFwYuvT)}f;x@eyVU{EtPRI=0q}qw*xcD(C{Z@sMpYC%djGK{E zDYXyPqvz@dFR~gjubEZjk)?Qns?x(hDK%#P;OM;)AcN4bEw$J4yd)iXnA|SxO2)Oy z5Tq-t5lCQ~dB5vU>-9)Gc&wD^^W!rHolIe2Y(@bDz$4;5RM}1b&Euo)u_-NY+Ij3p zqsJlL-BJh=+ok~!i#&qzb4KJ&YLD*#P;I&Ee8v>)#8XIq!YuJY72^pjQ7#$?=2!<}GLp;2bJsMjWFn zfX(eSiJR+z@CI&5gkbKFxG`BlZpDX6-qo=HZ41fp7rZSpSHz#UxF3MXzz5Zxl=IV@ z95&%6OQ&4l^OL4hE@|A@e!hjkIZZ@37Y-8ShQj*{(g~KY0GV7;CnVvZ2Kg{M8I#{H z`0)8a5Rxju2hnAT0)tVqrFMI59a4kE=bKri4!WAHsDwcz-QZ>0ss@1cOzg&dtfrBL zX!^Mtwl$9-<&}K4`Zwgc9U|m4c@|!nDiF(bU_5GfUOR`bxKaiQYv{&A5*pOxA&?1) z!X?oYar>&8`r1RG1LFe+GNUj-=q4pM*4E!mMm05x%2TR#u-_Bd>Ls`}!EvZK58mZ7 zYQxeLM=bXn$J*n6m|v3helj#3z)uy^+2}iv4fm0W!+5x@EO;*d zNm1Jd15v2C86<@x5t6e&-Y_nkE+%kK0uhSk{C5(80stU5Q*6Pdnf~EkDFfAiS$LuP z+eowA_GYi8^iuWJ$g!iiv|@LM*(*bD>7XdxyP`(F zK1uPXh^XT-4Q%U*NXP^EmHPBTbZm^3tzHgD!>8_`Bdt$GaD$=-;J8EnBaLO|Ai7x2 z+k8%Vd|W;WNjm6^b6RQ6PU$RjyQZoul`B2(!awMD{-wRu719Ji0BQTW%QCLL+9ctD zyy@rA!RYpc293B_+FHl&WTy8c)597PSvT%Pq<87eb`q^jbk^QmSn}q5XWSl{72~s{ zsvHM!!SWZ>Z8qz^FUudPs-1-u{XZz>%s;nS1)+-Bo~-HaZI&;S7i_H?v82lLPW;wF z>{A)Hq-2pezmBI*JkO40VGM=IbCg33&R8p9J-9cTVhW|sd3jw-6hFyg-3z>qsc zxnbW|mXR`CkLArghn0ZqF$lkk5274U4XlFSr5Z*JHT@%E-ohwOVCV~GXe}u}qqk=C z_OigEoFgh`)Yx z?aEV6?bJ0^z_V40d_()$`WPwXNuItXEviLe_Qacui4`&Hcuk7joEn$)>J(Agq-j?` zbp+|*!FN7sFhY_s5LZ*Xy58@EW{IfI`N52lIA~RsC7zou#@j=wSW;qf6AFmR_be`A z+wts|r-;heGR3Kxm8@bV?JKdExEnm+7ExRzkvww~O_d-XlTV1sH^k5_ZNc&zLk^ie zywM}qPO35%zkvc#SZqB#CK%t)xKk~HAiQ@vs`V1~(~dEfN8k^Ng73T;G0i7gCWs5H zU2}yJ+4c3eUQmNx#G8uWf}<)}e}Ks$O@h@N%BzN}6!{<78IxdnV9tCA@aG z&S&T@bx(X?8lldNfd=JUkkwmez}Yf>`?=medHt;03S6rdENOZP|pS1{((8A8nn_!dx1UtBd`Q8DlAO@;d#l{H5*@EzY0O}p}~C1V!- zNGre!(bNs~`GeY)IPYK1!tU#XHDyuQZ&d&S=M1X2rYs8o%?isnRUl@i68^^Fp(Ue5 zUGPaAZhth7DXgu%E$Z@5sy-}VuBn!bAN)gmCLRkwn;qX?OoH6^tw+@vkLmt;*1Ps> z(+4YeiAyA;vQy?d2}6;n?F6z_e->#LKCO^OF8tG-7WQ&pbKIc{{iNH(+vBhp*c=y5 zO|UB8a)0oT^>A@2RgQwDjr7_+mR0;CqI>qN=P)q1#{0xs&)*y?Tf}A5Sa_SP_2Y=J zYvU_y>qodIX+;4{rn`bpX4_Xiur<{1{WZIkkN+g7#ZzI(0o={$M6Mv3pT9kDQFw9 zcQ0Q%jMgaD<1>-g_0$6_@f(K2;s@Vohs0A997r9Lc8IbGG2;F%tz&t{F5p-parM}E z-S5sassgQJ!>TTaI0BY7uo7{znhQ4p`Qty`gIyPY_Wun$Ja;e*oFD-o6fgO`sN4*0 zt66C*?mO1}2YYZl{c0ejp5i`j#0WmyxViFPZ-sssL39~soWOc2t9%|tf9j5A@JS+~ z4r;?a@zsw+46}*pLW)Fn*q-Z}rrvzT`O!D^2(rWn2H3)@e{u%C*{O03{9Wzhz>!st zZ3*w`>hj32Jw;FP8Scma)DeR>+UlwzB;mSXDk^dD{XpbW=O3YBQ(%>>Da(_DYkj1xhB2 z@+QDX!WgSuRBqImKaHXseK{ePY8@TZp50ngZA4f=g-3cvh+4&0q%-GS^-c83T{Vx) zra;T)kAV4*OQlgR&dM0zsN&rd-*Qd#p?(+Vb8}lZ=4(anZP&ytNU^wid=I*cJJE@> zkt72nSk}WB1XUP^3an(JvM)!JvLlCc;WyZ`&ZXaoNrOm)Gow#51P!70obG-4W|d%l z))g0k$okVrpo9o7*C81&E*|vOUUA~vc)-Ub=@)>8b^#fC4!MkUl!ZKt1L&yFfoEqa zH3VAfdpNv_@(&Ylp`NVt1W|nuge%z$dSnMLvyLH>AsF(IsZ!iM<0gM7rtdBg%Ua`O zeTj^1{4Gs73td}(%pLSl^EPxW9Ze&kC{f$(VuwM+%U~qyL42Ti!L{DT62=%;4E|=s zlgp!&i22|dD4a+)rz@i3yD_(LLlHAg4c}kms^)WsgI|uoE%hwzgczbp{G&mWfZ_zb zXtok_Vr%HpZ0|LA<>K4@6=c{V+gg9}(_EH*qY1359lrRv|KQt)q zvT#8c)OoK&G?QWs$}>@!*dd>s8mmD;m|+P%`A^NqtB1Uwf+e5Gwjk zcNc;vpAf@j?7R$}&P^zP{^8fI7BU9D>60W$?(KiO=l$owogQ4EDognW&Di%1po{Hr zephXGRMoU?)fs`3Y$bOvfVSrn6~2h3SRv?VSB=9Jmwk~oBMI`1jMV4qG~nc;V@X3! z8$2q9M7C5bFoP9@u+b7Z>BkCBS>vfU4)0K6eZCx7?9!0ls#37RvgC=S-wb=R+ zdoA)n0E2|2mz5&_hBd=imHW>=`Q&n!M>St9D4xsbrYQxD|Cydjxvz2(?d8mca^obT zRw^k*pUjvt=t*4HNqm|SVYqmsBqj9gyM);AKO@3Tqa1o!=`dnc8|81f_TP5kw%M_~ zZH00F&4M*mnw<=4aBle;{vS|@(Gw3&Fyx8%9mp|C5xUTjbJ5pWc7n3-(XShMSEnkV zTJhY#5k#dNulu^QX^q4l%%wavy5|~Fg;bYnrNhCu9qRKU;{Ox;>AaxQJS&&P<*>#~ zJHvso>5}^-{_(t=Y%zTv6}V1MW4vWIDek%CS@22WI&|CdUR6&+&$9uEPpbXpjN+(5 zT1xttV_;W)TJqECLeKha{XT{^^(3MY@iCDipDSfr@nYHLZ=-FOY@XA{Qt7yM4@2$Z zyis~)SC#O@Q;*V|=(fDmeTD;Y(Twna0r+@^ycYoXP#mHg2$duQcCq#Ef?qM)&L|I4 z$ec_58kZ{TAhy>oKc4uta}_0PUV_iTnO33%T+3lB+SUhim8d#__J+J;2n z$7I9Eub~FL5wCNY4I}9JVN%?M6u?(3_x`axzxhV(p;g&C0M^J@WAMB~Ga+XGh^ z`u>6mKKvdGKhtg6D;=So+7_W%ux;%YVnZ_7hwo|q-}YATqD_oTMj`C)GVMUVNDH_5 z??dw*tU;qtcZYvXql$?gIj|;r*NhApPuub?p$+y%2tD(8Ty-O43m3kV%1rDlgIS_7 z0qK7Fs9FGO$@|-x77|$4eh1zfU4uK(*W#)-MYc7b(OiI&zdqojldB)|Q>%o8FruC_ z{*4jSUnBaa+}4)~To3~&-yUQ~?9=)ad#Y=sHRwu&E3G{>Zmg2632qhBL~%E~U!3uH zu5TPy>iwJ^-re<-w_SSJ#8wXhhGWk?ekS07^04gqV`rQ%)54IJ=9g!3#_9H+p=J52 zMH&7D%ZBmplWG{S)Vo)D7(3egk7%8LbE{bAfivC%XQH8+(OVeBP~y%r-ktwR^zTVC zosCfX_A}n?|4BF9loGd{@oxK1qJn(=P~PS<-sb-#gXX|cVDE)Q4nmssn;q^?V~1{a z#mF2x6I?OOZix1-2Qp-VBe$^{j=y~dZha3KPu8>5Z!*W5P#~0pxE@a&AGwV;0X~RYcgY?Ya(^|Nta_rQG zHMbNZw&tUKkV3YyVUF~ie`JH@OhY}2+{oG6qSBwrX-#D|%($Cx0<&Q{J+B^{y5V8z zVOQaXY0)vieY>)tiRtdljOL@7Bh_Wq-_0%MTuIcj`k4lBcyElCvvO5lA8UW z9Fuf`>3^N=IhwcR{|lj}36L zV$9K_venyJ(>zAlj$bCZZ1t#0dkL%9&)k@kYtLp|8<-vWtm#e0jy3iwopt%w@P)9K zb!_W-IwZ&(@PWh7Lu&mJ>b7hv;-ar$O`VLr=D3mL9WN#rIc{wcykj);W{z!v5{LXK z7d~+fq7B#*gj;)Q95O}`EIPD4OE^J*T!lMMghgWPJ6T1lEMrJ9nm-$Xp(5&dux^>8 zztazDT*Ma0qRL#*{%Tf0b3?+2`aj2^0r;K|-`CZ8JOb@C4XUkho@7)9$x=I~ zbWBSKaC|$bC^+MAOi93A3224d zlO@3C=2!;$2Ybwt@_{QjtOY)><0+k|^dht5i!j8cVZ5MeSKUn0Wb_yaq~SCHt=afF z3_n|WKse0k5$SmX`2eYB6+R~8B3f;IE8^ogifhQR6xVROZCYGwL&WI$4P_q5tR6MV z=oyZT)vrdnIJM)y63%m~E-t1Z;&42iaP=y>#-HburT;=l&z`;4QFK1qSKI#Eiq!QvKE8<^wr_~|7*iJ8E0HS{U#4&h8D7l@ish1f)1HW1snZfg06sdkD z;{W`PVtIraPm`(mi6+x@hZ%nnzpC#r22TXJ6pu&37jITCMW33z*(a2u&h!V_=1A%m0YYn zHKV*$+k#1jD|igJt*w`$G&C#xL*f+w1$i6%%J_oG&epH6s|+bjdoY<)`%0=J*Z2#V8qU7;ouprZ7#G^ z`S8=X>7V}momL&?_8~V-Jx5cI$%7k-h-siyPcXR>yP^t<_Vtkk3$;*n#93|J9|5E6 zz6&I-uaDenR`yNfqc1lYxfJPTa^K4&da03KV!f^L(g4JEDUS4lACT#f-?X`J zYP#VkBYga3>w(_zf5(~jQy&b$E;YLipi&FqnECIxl9dW&d z^B;#RUtEC}_9%S4Oo-zjt#eFG5Eh590NTDU#1x_%Ej(FA7n$L!d{b0~5sMk41SJ(| zRE0iO6|SGLP%EYMmk@H?+9IRm`3plRCB&~SGH{88LgKIt0~upkY;-3W2g(csS>vxZ zgW|!6Ev-lKLNB9#?2hSAkfRE@{uOsxSI|>wHJsPm{C7;x(AXhi9LO)*pdQmx^xK6+ z`Zn2R=y6c!GqX)M^7{!wCh*0QUfZP{#p2$~{IRfiZ?*M?YkxK^q%w4tjAdY+(K?v1 z1C{82Jgx$Hw9f0by?ovDDCP0rxvqGmmpRYHI{t;VrapVo0rb`mwZdr$A!v?5)fC8m zDj|0tCl3MFw>hxBr6J_|b`z&BjcqON4RLXSeRAZ*W}qGDymqesd&C1?BgY@VhLhZUN9#X6t5X;{wNw}!oZ0D|Nli?h3J2R?b#5gx$2px+ zgt((|!*a7(gRu~4d8c9fs5{-+LK(sjr#g>!ZdJ7{#Si_@;HbTyb=r2Pp7$^azY*8M z4$JjVO?4hY7R~NE-ou^9X4{!6;0?VWmK!cj)g9>cSsBgY+ur@s>m8}WeL}x&2RcKZ zWF*eXWlZp<06Bb)rmfEH`bWt?wy)~jj;)aLJu`8d5_ z%~;Ll7f0hF3D|ttAxXNG5EhS#Gf940AqmWji~8rlr|={%^9ne);ae%Z2ldZ(IO6|Mw26b91)Z*J=2tP6Nw)>- zV@5oN)$iDTFna@xCZezV1*qP9YReXOZ;;-U=M&}NZ zm;N`Zus`~gY<5^7-?Lk<;>CbYg^byjf-*V|`xk19NKERC%D5rF3TQ2fvg7gS#l~QK zr&reLlu<82ACQ>nq$?c(uQ%A;;r*_|d4-BqeAN;7AX5I0R{!VJ7PjnUN25F(pL%-jQFdEb$GM+6 zu61>IuXgDFm4eVOY@=MClnTP|^_7S=W-bv`^Y+is_PxIdwwZSUE(1VK~UW-!Mc z!&ARz`DBCDNCzuE`Wq>IaJA4}9Re5!f~PyYhdP{x2n-i{pQc9U@-Qx`g!7}0MzU$p z-7G_J+*di_*x2i@CqlU zO7kA=e^W=mmmJ*N;oaKdY?Au_*4_R;LH&Q7`p-oBzq8}q-#e}aI=nkN^k3iYKS%w4 zBHI6C^k1`-wSAv*c7MWTL+Mof6EuhSV+3d{FarPS|F?JhAoafnV2lZRJG?a=&YJ&Q z|5x_)KaTnzzFU_1zY;|!2Vd#%uIzBG{Qvgi;9u|En5l{$J=g_jJd#$`0?JI`sd%+y9?5=>H$0{pX|e|JDC%{-eF0 zY@mt!@@^mc)^9NYc`<13@D_JCi~B}k^J1tAMdyD^U;leG=>HdY%ToVKQ1H>j=pt<*m2W44Bl0Ot%em3%^R2RV&kLn=TN};>M4|@_;YE$ zjz35KM<;f;Jn;7i+xB_S)+G8+sKLi3z&Bl@0%rvZ^wp2Xecn~|D%Yp;nl=fCpItjV zpo;%tN=9w7%K0a%T^QglB@Tz=@%ZOlMTu{yB?C>@p)_*)MEhCb8_h6{*rb6^b;SEX zdDi(DWgT?2CaJa_W_3JteRw253*SyJfQV4;_#aL|#tp=Ug&mxK$~m82VFRsBPnisj z*Ht}HFE)*48vVa$qW%q0&L_%o$LDuzM7qmM%}&qZ#dIbbX_dg7M)i>CEAHLOm<}NZ z*KRl$U=eU=7$QMz$`d9(yC!wLj9bqnZMbvls+L(VOJeZNau6-}(oiW|UCijZPNASX zO_nv_H$uR|%XR;zgse@hLeJ=ay!$+s(S0vH5BR-6qtpsT2*wu_{9pWH)RAK$=NPG9 zzB!Jj1)wKq?-qPBXp0M#_!@L|deh#yMSUsk_Ty(8nY}_MepIaI(H-F#!Sj$&`}mL%^9udKYcGKNt}L; z7=2Hs7qvGx994Io0F%Xr-)CBJ7`hO~QuTYyoSwdHkmgBy!^@N%JSiwMhLPNWG+nag z0_nWxY|CK9GKdOj{_t^bBTzDgfXB7YTWC9_YdR@PGK6g2&@Qt|q6NycIcCPwK0V}Iwvr-b2P z*Mn&j)Gl)>s(0NLSlBA09KvvC$tfuZd|LX)o3C^Q8VbeP(f;x6)Vwkf;aG5zsJq87~gOJ+#cnuCgtp7g56oc~%mu|MAdWyfXMy z3x^qNR0$=%!^57fdEA{Y%i6TisXGO#b9Le<=l%4Mm9KUVh^7=m=PoV!nC;X^5AN>~ zlw2&OyHtE2Z50PH;#^u?_?SqVFVs$Ha?U2Wsu6FbG1g!I3&id-&qdOR!CEA_bhJyzE#||vvxh>S3?La_Fy5I@O}IR) zOPbCQ{L~I~B`ASRF}Ao7EQ?un({b7x`ML@-uC)+)2=zxHug_K=oKGiDyPr&Y^6;HZBT^>ewKp2F3qijVB%qnOC zkZkLqz!yyr8%#z3xs_ z1|$&C$z9^dX|W#^@78(!$ccD`Pm_Q%3ErHA?j&HW^c4(GKm z(HKx-$a8b=;RUDiV4ugFm&b#}cFFsny)5zc@;JxK2_d=AF7M|6PhTquY~|{ZJa%oH zV;%9x0eQ??65skqXVXzbcli2ifED^*g6S^p4K6pl7QqzZ-7^ZaZ1ZRspUzd7B^Pt( zclfl_zvypxUxaYEMUwaY0CL~IAp-gzW7tgLi$A>Hw#E6>NgO|pb&jlhNbK(6xNY{6 zArBqs;jQX8mxlRwV)?b@()_#B37TwKboh?7Xkn|3c!r6<_|EAk z(F+#LLUc`p{|7picT8Q;b61}%ho-yF!@QexALee|+v5di9Sx~-%E=ba;GNT`8rS5U zOv^V)%LD#5$TRtX0XpMJ&=l{S&8=yS$sVv(l|yoB+aiumP2gZB^VB$+D;VNwJ#b}t zeR9Q;r%Gr=`*+BrFpJ(fA)P`y#DN>moU*ONb?aU7W$IIfnzj5i=og6T16nv3)w90+ z`G=meEo3LCElYbE%UXD67J<~vhZE>JAW5$IvO615W5ssfC*C)lv)!+8&ZBO$h9kZ# z#@DHEB{7-VY_)-LYEA-i1d`a*xUPk}%k<^tH?)O`C$&X;XK!I~H_~3g-^!z|u<~gH z%DA7`U1{l;F||3)IgP6PQJpar2DJM#z9WF0C6pHHZ}PS9H5IOzGzc|M`DPNvZ!8mM z4saFy7LSzk7s`1v?{cB$uU+*@cZb5AlV7{CB~C~Ot9QBZ?BBGu>-;k4++US?_%F&1 zSsq6{l*?NK5$BLE3HiN_ae0QWCtO1;0$-d4chumr&VV z{DpmgjT9)b@Db|*nh1c;V&w{kR`sy%WM*mtUj_tPG z<*Bu=J&hgy-*Oy+9!KWd&kFzg<=M6H>4)e-_59j3fwbfh``gNrJ|!&wFMMF%Lwolm zOxd%7_q}~__s31|>bv<+Vj9(`p9XQ$1U1F_ITu+Yt(@O+EnGGqU5x%4DbC$rU@B|! z$Z{|`p0=muhQoyZu)l9S{czqB|7o6EyT+&*{>dxG!w>B(N|>^p+S>(>KjB+E&OkMUD}=(!1_?3=oz>vr=Cm*K{gst5g9~+r4Zj>)68L?x@P)=b^9AHd(ws>@`VQ_x!j20!l5OE-7Bp5^FNHYX(Q(tS!JD^|RP zZ(AjhguqU3EG!>f<(J8|<;$n3cj^x1S*lf@1yz#Hm?t!?|JerU%sYlnF=bMII2%yhO7D0^@kcnk88~4xI6M6`F6GG$&YcF z%SHD%b-RzJ!*;|piU@7DK!%OC9n)QVm>i^_57@zWX$SYU3s))u-jXi!&7cn9a-}bb z4h#qoIshkMK#MZA$5@o!_4mh*@?wHA zkd!3OjS=9Dg4Q2C`c@1kbSXWnC7C3_|K#;28w>Rvz}-TkATKvpJ?UA#Ob#jm8{A(k zw;bSL7Sm%Z(AV`O-dOM(Y_jRpqGc|5rbO%WsZGuEyfs-}yF*Nlt+m<*_peN5+BSmt znnzP#t%g3GOq`Vhd<{OycOYJ1D<|a{CK;@=lA~}r{U@*pP~dO(XvOK*u|@o!0SRIw z=^v8Aia+fQg|@!Rv$(2!D|v3VEbUj&SY=W7i(P<~j)rbno&rWQVg3ogQbL&1?!qSr zt5}+6C^eu#k!P%PHDc)qdOjSVIdXjFj0Ks4%MHo0jH&Ck8|D&JhGf<-mu~7L^4a+U z0SKES{R<4Re^!GMcVG{rcaA|rfq-QZ1LqZMNXS^#Wv*Iibp79~OQ}o63UEld7jf4Il(Q)uU@P8eL7-<}0?v2B5 z%K)i=bl*UX!=+_-d~_f_SqgV5rLb~k?+%6P_=FR|-<^n#hR_s^w~lVR620&% zi1rf)FnCgsFXQO7ePlljQTAxVtW>L+I1DMT{xO`@mh?N4d7sn|^8Z5XEIOY7ta+MG zQI6H7DsWXzqs@uQ>`C*us(v_x`O5|6g84g*#%+1j^5#;(2$<0Xted#ue4`qV;SaD< z?yY0&smA37Db@$x+1}?Rx^VU83qH=VxxweT*z~q-d+(9s89%@|78ias7gDN;4rINz zQwhd`4@pln93Zj-%I^(6#6>SnYf)nhgZw|BYI|B3*1|oyCH#yOf&uz&oc~D`NNnus zMs_}H+_K90PR5jHb|xMYPZ=&7_0PyNRJz6!*=(t?-0CP8qII)*o0l9_1wuSFk96ER zFMN){gg$YDTnvrMdhImAMO6p*yn#NCc6raA#!rR&kyDffbQ@?X=U4O$3+WWPxYV8r z2Zb`ILZM7cKmS&FD|{JA@S>!~2t%K6FK_8oP)u;}Hba{^v^Nbg0DGM?X+3I6d%r)9 zpx_X+Im;*kq!fj<1i*37F}P1I%KA(0@;PorO8vi5g z`<%lG6r93KfuNTV6^mFubi_pGg3hdFC5Xy5=m_0JLuGUDf@+z1xT-!+NH5Q=Tfepr zMgp6C!sCzbAYt00G|`n42~`*rv4%6$fXuJ9icCwN+EH+s@zwf`D!;uWVKT%?dH-hNL#GX4zeda`K-2bW?!|CI}ohsr?hUcQElIX0B1H2 zLHI2YRhX5($ZeZ&f)M~CMwCa<3IM|N^{qG9aUdTIH^S$!vzEg!cZS?Es><>cUvcj9 zN^ePtV%@0c;lf^D`)(ySBx|GGmlSV338&`QIYg_2}OPyd74r-a&Wf=`Dwn!ByXxL;K| zvEdcmR3E+w^@kSzQD1uu%bZE*tZ9#7=!bn1O22SX@|TrPManaJ7qt7C8hasPslQ3Wb-`>OOn$5cY9zi%Q9=8dI)xG^pxGuKXc zXrS#F?%O91kYWlkIrxMP-8*tK zfZnHwQkBxgIET^#M4aQ{jD4w(EQ0+Na%g&&upp&}<{Ml^)VeQ;dyrJ1j?ZWh&S*C$ zlNj1*ZbwN78qzdPO4kSNu2O1*M9`%K9Uc%!##Kruv!HS(aT~MexDIr!&QX~UTr*2T z^Y(o)AjcqYfAGNEGgx7b?4!hnh5wbMN#~I)OgS>Ek&Wg>x|5MW9SVe50@mI+irSCf zNvy5&#l);!L>f57R$hLQkbyq8rtGroB*z zZB)b7beZ~-xq|xLS2Zr47t-x>pwW06$BwP`mQU8-FJ(wfu1rkP zd>%XIW43iT^Ug&Gk)TsCDJ#6~bM1(hj6%-OshX>=COF?{M^vaZNOk34 ztnj9`9^p005JHTOWV?Q7C{blD<6UJ6DEC#C^^dZW_NgTqoG&N_U=@9rx3oRT8+=c; zH`k|+3?wFXetuNZ$m+S=+QWtqo*&l~A~T+sEaPZB_1!U$ucz<}2LqvG)a3k#0BZeL zgscECV|#h{v5@u``nml$IzU$mbkl_j%tNRT=8D(NqSP4=m36U(%#vw0=IBTVcetd3 zJC4ard(h``f)hmhM4RpA6^I+|_PhwSj_M(JsH2Bbr1arROcvT)W#|wM13uNU48{}# zgJ(lxN;KV`W%ye2(|yK{~$kq%BfxI`r!GsYb`r}p-Q56 zE9m!1+aC`i{({8A=1pif+!cSr->o}Q<4a6ForAE`WxT_&&}B5BC_b&1B5rn+Fz~}o zBZM}$aTMV3NwDD^jAwTmGHTa(oeLyLeyBbj0qny2hB6+3I`39NI?sJL3#?sxPzZU_ zFe=8oUg-3fb86wC9M(^qtq~S|Snq8^=#XDLvNBm_*2rdW99WsmnUgfny_)#?j-&EQ z4g30*=l3{`)avHl#t&XHP8qV1g^M;JrUk40|nh*mZF^OvY zD^C=PXJXZuc6E5{WFH4 zjn|8!HBKhjiE#t>1)e{QG4n8V|6%Y{k7?KjxPy%D+A$0R^3|{#w$k=rbFF3{BGhbX zKEAQOa2WU#Uy$x1onIZplvFex7qUwyVfR|4wKo05y$~+mD9JG=B-V}|NONJ91``Ai z3i)?O@NLl1i35H0q=&;354z-FY8~|nfqn75U^Z@5fi9#i?~-#!cFEZ(v)0!*TxE$U zgpYF{HC&TavqE$8=8<54Gx(Ackpfeb=-LZ1g?o=pm-K0I7iN{Lv&D-3r`v=n(vjwO z(2*tS%;PM}sv$%KN!J=kWyn_Z*3XRf#!m zCUkopc!DEdROe6T;mcc0h=&eBGbc*phGg5j5waa1-rzcfUef*oFIcd=nJfQrIZOg? zELYo$`q^Js3$Z2{llkKH%tOEVdcCXd%ITY%zqD#(CtsUvd4M_ZdFi~g$B3~cc!LqJ z(e|9-Zq6XYx;|L7c8!oeJl6ebuOqi={d;vDm-gedc>DYPT->OSAxQt{&qoy>r*SA9 zhyA~pmpB%>PcEE!tnV@zgNKT1XoC9gk_%~E-wO&;c1$XDDP-mYJy;Z&-6=a<3f%rB z(P|-l>QYFnMZr>nGIURRH-^faIfH#PZgSoWiqQ^$$wnE-7sG#`w*G@SwWJo8e$cMJ z915y|Um!{SC}L@nn5^)gh@$VzD3re}FUyQVjSFb(bkwp~E-Z@f9c#r~!n0BKIf2@D z?+dSgwyq{`$B^-%{kSGeLBns_YyTciO|AY4DR0a=JlpOSS%PKeAjH@aF$L1);%`zOkHDXPb z14jRd7dF5x&)XbRZ>#;Z_H8!{Q!1HTDq}t{%Klux0PE1KgMT7aqQA`nqxff%Q(#mG zsez|dJ8tw++xg}OGne=NOZ5xhpKONxxX)phE7NNnvl6bHg1s9z0^&-zQHi>%qnnpJ z!@f~tUONm=0Uv&aL-IaU8(y7*vnF~@$S{>|QooVc?fndy4Z6Yjj@rcp zC1LWN*6g5=SsD7bV8lk&+V+CoU+Q{+E!SSpIWC6o#LmMW!x|L$HRp1!)tp=H&#)v5 zB9~{BHe+TY+qx*~$Ws5u2yVYbUA&8x5td?swuZVL1=rmb@og`{C&NHA4ZEc%!uoaFZ{cIkeALMuHP>=`qjy@xhtLjAi+O zvIme-?>*S?P{x3oAk;Xk?I1>^<<7EG#0I*Z5-Z|0%WsB)1)wl}!4hMch%)%tKI0&h z82BQxn2tt*g~txU?GMb@?t3icLlq4PK9+4D(%n}^_c2|p+!0A|vwZia^;fS8F`hT8 zy2^&*1-!q6D&j4ZyRN=jW%=%!-9E$3D#-$oRjd;|n;h=4ApjvDHT!%fj{QKe$QN9$ zoke)kX`#Mi7%{XML&erec2ahwrv1B6a9$sdgkPq&5!c4VnqGX5AEIBUwrS63+b0q!BaoJWDU}H-jvZ`xDw{JO z=ta9&HHgP(o}r0OW!9??XO9d>`7LG{v@?Bkjt~AUIE2=Xb1>Dob!6knfG%DGXEeS! zp(M>gL-M_M5>slM7f~Q)%TaiGb1L8$CI;yD_h9ziEbA^TLSA=>!)m}_O5?r&3^ zG~t&yOE;5!9D^I}TkA|Ti{XV+WrZgqCJcu2`snc?a)tt!!b|-`6DIhl?>j$?(b*Wn zDu%!+#E>~uQ{Jk@@E{i`d1)`{HBY;2Sl%=tg8y$@WJRrWtV^UPm{M`8vT5yoOh2S$Yb$XE%ct&9pd*k@%- zM5|pH8&a!XB~#Y5{qQ`rI3Vpu$4Vgk?l3iiBwLRE5T%?^$q-wmZL`w-s5P5bmYJEE z%J+SqXFzCcKl}Z?ey`WO;F)LcJ@?#u&pG$pbI&<G78&NW2|;~36|EI2%#Rs-6SRl-p!ckN#+2d0=}bD#T5zUPcd_Lx3! zMeAgXv;A>9pCGELkA{_1cq;?8Fb5U z?d$r8Y#-t_Al%n)uYll2dhfzrqf?-e2zm!N8oG=_7d5wCV{on6so))gdsQ?`4qC43 zsChRhfe^GR98$z8OE?` z)2qwU(>v8Ks=d3aQl76`H#X%d%^F>Ci;SPD0_-(OG2-G;Mg4JS)yN(kL%}GO4{uCl zeQ_k9{apg$f#4mmQ@B2s0SD;BA`;dE@=n#nJI$A5`nlg$e}f%n$V+^-27N+u(o zWw~{_u<}LFo_HsK;wmZFDmdB)I}e0sg%P%NV^(pj6V`?)mmf)(g4Q6u&yy9&VojWLLiW$gW;1#JA-S?p2TMwxiHs=KsS^E@H>yq0YQ0fwps8ixA$m>Ron=q_ zti`|>F94KRRLj|lI>J~}(= zFDkrq%_VhV=)3T`zOHWEv!D#W*VjdEP=j!C{ics}@qW01^5ObzU)Sq`UEs|1qihDa zgH1Yq?I<^rW|CE}Ns8yam0NV=i`inTA?fG;CT_qFvu8G|$Rxv>GfuMlU1V6ARTc|P zBSUSNzMy2o;|ffNL#LkGexk(s$X&%?u;>;Y7d{Hmp*Ts2t}Np}k&&Qo10~o~Tj!8D zJzKYAe2y;Lx?tgct1fD>HF=@a5oMi2M9a!@6xobz4z1zEFUjW-mBKWJ<0By zuEcH4&rX9QQM6lUuWwT~=<2Og8um9(_qm-^Zwt~s_n(}g{m*fC;&mlr8*m0bFRM)s z3xCn>qbMCwI7po`FO~5)wX7v-DO&ip8=3KuqD?i=czV9JbC-}KGI>wiU<1iD;w3)*rvS^nl&{KEXVnq5kt1-~gm}iav@0UVd7Z-N zQ?X;3)r&W(l?FRIuUY=9v_*1u-p2dquAlL?FACwX8`V+lcWDpjvu`!uW!t!j%}A`A z7Mqdi@v7H6Yh|N0#%1RI{B7_!uT$qIYI7&i^O`${@h8aB?@GaK?4D{yVw~`HI!VM` z*joI;|a zdIkgX`Km?B_z~(`B`u6er-nx@YFF1RGYPc;vFn4rXJiItS-P%$M$0l+957sB8nX<) zq8H6o$DH=%qQ9^Gkdc|!GlNT8bS53KVfA5%6%WH& zy>3>KI)dqXxzFnT(xRIS?akL$ubT^xX=J&0!laX~2{3st_EkD)Azv_OAq#kOVT1FY z?%LRwe0R>WTI(?#5w&1WC3*9{(&TWEcwo)=!-aalJg^Spx#*8ai$_a} z>W{L9wXnE4`i*G*ZSc}OxvJbNDGK#0O(U=cG(+TtF*iK9tFQykWsHAc-%}cW?G0O; z#F9`pS_ipib4aYhxiAV-LIBEB=peH3h2&+^VgjS2cs5^VgoAFl+!k)85#K zvHpf&%^7E@w%lm0dkIS{^5Z^&b#Im=Q<1ffpxA^<46Z$sEMyu3E57gE?hDRrSdU-03c|O3ecm*Q$EfXvf%GlurJyYYwK+}| zDAoD|w(%LY$sL|J)w=pzyhCncfsor|XNOD9zI_u>nW@97t zPz!qp&JyLJI8{rNs}-}*b*vAKcwS9`2im&lD%*yE)Yo-xc&#zzy$0b%cJJxt=fsB|7O(nd7rLd-~1fY^#-ndeLTwD?-OcfrR8&-OB z(#F=+=U;2s?{m;3`GzA4iboI~7)1R$pP@InFLGl$leZO-?CRoGpZmOwI6A&KwXY}@ zmE7Cb_)W2_z00Yx-mGWcoDX&l$FS@$4^0FsEy=KJL>c2y) z=~RjAmZ`}5Q0P;Wg!|$M2%C*IWWdHTBTMX=%|h^OrO`GoA?9A>Cp=Zx% zPHO135HZQr3j|7ep${t#{2i$LGV~VrIL*(FcW3d!fiwJ>`Pnp`tZc$?#;TH7r<1O( z|C<^baNv+!6g%PHAv-jj6^OO76WFokdTF^(t6VQB7hI%{HysH!9r5Xfk@Hdqx5Q;9 zWXJV<-5G(wtt521E+Dt>Fg6~0Eb`khO{a*BkXUU4RcqI8O1326ja4rl*Rv4nmGIh> zpvv2eL540vPL5A8+`|Ha;IgaBX-N}tb}VmGg%@HO?PSuDOm%vbQev7abj2lf531mstjvty4hITBn#6TvMJx~0Qz zNvH4qp4DU5S1!ZZ^8(!HE<~P$5`^xT3jIi^`w&1w2~wX)$~oy3_y9X8$b9rc0lZ0l z@XGZeg~^0FjuiUQ61@T%rfNcc5ww7lA91%MX8JNzfi)B3*p~IFJrJACdw#ZFPY)ZD z%xp`&Zqxae5t~{)BP5&Vu_y9#v`6J!KDA|mFOE&o31^>P`oPIN9#Rj zu`3ju0$7_+0`_Zt%T3m%zkE|~zG+HSP4LV%snyp_oPFVY45rxBH#FD7@-Q;yreZfs$C~DD-p`!3UaI1^e*I1vD!iY%@{C3&E z@^@BiVq1AB&Yfr0jn9@9f357-N#|}{fCa1f;AIE0S*nitt1cO1Pib(O0jNRNpyh=- z0K$v=_*W}xYhP4VK3BD_a{0=7P5G-St5z-jLzTYZ`%AB;T)T!ufSQZ`4QGwTH;(;!85}=ABS~r+y6ZJaZ2+4%>k9hBwEh7+fjq6*(-H~~)3iE)@!}e=o>TH1aHS(leCy&RCH zuq`3!XuVV0!XS}*OWsseG$pC>bxhtbB$OO>RIFjNCrN=9%4`YTrPHEDnY`YVF|jtU zH{U}E3QSEY^tCC4zTPRpl@(o9iOGMF%}%Rflt_W@^`=D$xzL-Yq(!NDuVT%IjB<>` zxcZ3Ay8t&$5KDJMD#vfJR-sH_Ev32+W3_ zB=tt?Q_n=Rrr`1;F!8>*N6T8d#YaH&l{Nb-$8LCr$&BvN7pJMOe~+@c4aHte zthl^~)!!FAF0X2`yl(ldN0D%sZ9lnrscAoZB4urrQVv{u)8d$}zx1&MKnRJQY0_p! z!Kj)M#g^p5aT7N`!-Fa~_sBERXgf1{T=hdk-U>L? zNPR@}1y4IjMgM(t&)$8SeT_YF{!2HFqmDQ>8*G1-A_n2*)hU+BStXS`T*FH01NsqC z>`Zw%-5KR$##OdbZb^8C;mic`tVwd*(G6=_b4#$On=2xk2{pGM7eLGrF&Dsn^vcjf zd!u;HPG541yW8a1On7A+e4MvDLC+wr@QOIrvPA}!5qrval>D>;Lj`|7DTVm>Epc1o z@RQXfd`m-3xo_b}p)mcNN-qMzc;CX?txXcvjw9sNUt0yI0A&9k;^3bYmOGkC07d579GA^t+*+Qn zHa+b3$Jt)`xP_V6F~61DMPrNSR@XOD`e!{b%k`}^f5XWZM&AmBUBZ3-7D@=YAmEmy zaQy-IC%51TDLgEWl_RuZRD$zBiQp~~X5-qFwuR(t8qU0)!D0ZE+=o{75*`WVe!pq}R3&3~`KP?_55yXyc zeg&+Zzn_FW)g1cgQ$7QSG?e6R z1PLGiawQl7Z9*EuNCT3EZ#Y`!Hqy9km2C=};?!lf5f6;QzFijWD!;I8|69A0qUxST zh9H;>7T+LWEv}487pM2(Wv2#*Z{j>ULJIP<{f5b!*IkaIktHbwGMti3Brh?XiO90{ zm26tkrVPl&ajOYHT`M~hMcmG`g7$>hDgYhHlEqq+VD#w>Bc4`?0Z2+|Q_jG5nSrH#{qOOO93W9j$9&*|FP% zJe>lT=o{{5Klv8=1_yVZZXZ#45`V4Fk(q~CSl{~pcxz*lg-twioX=(9&p4CM9frum z+!)c<%Pm9kK;o}KoUTu<570Hwz^qu8=(;B8+@%ssCnlBjfEiiD0+(?O5uANf^;6*# z_rCNgc)`Q%S!RA57pc|F$Gfj^Q#9Oj-SVyXTjlY%e21Ni5Q=H>h9|7|)8-qW@L&7t ztZgbdN(hoDGIZCa@cYSn_buxZIXl&Ak1!4*H;*EM5o7E3G5A6{P41uGvLN6_X)@(( zVnRV3c`ux1Bz1PHR0l6f0?H%JWKc&v3`YCB3XGvCH?sA>*lp@&R|kSRUvLEX&S8AV zL-_wlDWJexLpKKtey?fccNQ=CzUwpc<`CzOy#c#j((n$$5>xQzCJ0ddExll z;49l)A4+@Dsdf1Ln%|R}L(*cqY|2t?#v?)kS&i6oIhL)?b9OeHix z_y{9|zIHMe`HQMkvhp~|m}OV;DGglto7bU~oW()kz1p*kWa1ZNt=JalEVJSOtx9X9 zGdLkb)R<+TY-jTBzy-c6b2_~W9;wBQia&BKaVP9#gHduWdeaj9@zhSw2L_#KT0XuD8|;x6;bMTpY4JzOtvWh(^>sh5a|&fXzk=^5>-sNUd3?gk z#_kKqE#xkR$^CEwLRZ-&ZVCa-)Lft64;BY6)R>ZFhraPUt31DWc4A<(T7P7Co812l z1}f)iA@Iq3p|9)ju(%Dg&S$LMdTXi5>b=csPhjJ$^J$nPEkCJST!d&|0S*5jbz6#9 z*;6u4e8R>FL{#n~eS1`~DyogvMzbQ00tk!>molz-1DOm+7DmPCYgGZAlpW?tk~NYJ z>Mnh=UG-Z1e(0IFk$1PYV@D`S8c5df-Zbllj-yd6%NlauCn>{y@g_QPBC9^P=W*Vs zg1b%4GM`QgtBRoPZ@ppFNw1G$U$P2gB?g?Fq$=l(;@w3|E~ZCcgp0Ipj9ZW z*-saLbbZXzc$v2yRN3pr*{1YZX3Bz$D*n)?V3GIgbKcY4O}@I}bVi&DVbHkOXuS3O zdHwwJmZyuE^T|7ps&G|Ao80_p+7<$+{8OLx(7ECb*Y#!OKJBOSUC?Ts-YFvc~ z#^D`7k@$DO;wYSPp(wHh2?t1QB8sr8S!=2uQiE98;azu2&c-Wy*0Kqo+}@YsYbsYF3vkrBl_{%QJ!(Z| zgEpj=?|&;2yHP=NHQ8`>l!*CPnX>IvrcoREi6?)`qHf@Nb)DFu5FV}4i26@L6$mmu)ZJ3#~7opjIrgA>x@PIKf zWE|0JOgd{!_OF!cJJM1Y8UqIt&b-*gW(bSG@l9Ra>r|SwVj0WaSp?KsG5(*wb!hMDCD6P((yd}%E2 zt;c~tZE2f8XEoFiTi7(^O}D1JRA2tm$E)0IbA95T<27ID-;d@dzIiE1<5t(4IsM<- zYZP4Fa;CP{r_R*ZCi)WN14eE0UPk#V34B;~cQ9QKN}49W2~G+m#x*B1%6XC&i>Flc z-8LGic|?WJXzH7;f->XFwnx*Yz1?!mwXbxTFCOu7a-UJ3+z}|%CvOi3=L5cYX>zOY zej=Zi<31s&OxgD2{!#(suzxBRh-Xl#qcx<9YTlZ}zUvSw>DTB)abG~aeMr^yT3^fY z<`@2_Y$20pmYjZ78!*OPTvd5&rFQA>Dg!{`!_e^f-co(2kYo$JI8r`5erZK+2qPrC zYyYYudL_=dj1oMJ#S<3Ka+GWKmFibt^W{@L`o0^z5x?R3OJA_0U41z5gymfJ)dGR& z%}+|}o8Xkp$1}An%Y}|UMJ7K4i*~AUq$I5gHZ+ODcRQipqHNb6PCaq=xxDafsXItx zS^VkO^-GKA11$^VRenbT@W;DyVPw$;&K)HZ$AOFNW`lfI z-iC+dd5;p8U@OO%)oIm_3Tph_xe=ZLzg!AFd^YIp4KB)+cJ zFSx0dr(NUfyFj!0l^Tyqb9%A1vFuoxwne>UiAR~K|80y%AMevzH-i4|miY7u9&Hvq zkH-P{uR_6JLSR4Ot2qwL%vDh8J;5@=%q?6XxX35{)s|&G=`Sy7t!K4aTS|Sw1zU>R zqz&sE&Yb`1QmNn|5IlrYr-0`+2G-MaUjvh zF*781c(v5natL6o#yjwroS04il?N+S)o|0mqu zH6HS{Z3_9|8UTd>)!m3UAhV}HR~Bp$S^Nf<_Z=I0otLt?P3 zd2W=gNbfA75Z+BIHqG_;*7@3eNe$Susam&Cwck-SAKodDfYy@)>W2PmgikVS$I64OGypAZJR!LAJMG0 zAwyEB3O@jQXr@-LZo+e!zNU4pSytJ#&qozsl^Mocb4jpTed_{kFC>j;4ISHs#WnmN zSZ!Q)^%*CL^Ys!6(R_{eKX}mDMPpvQ6?29|@d=3^u(yMh6rE~JoBx;6JYmM5FE)`P zk<)}(!-NSFmo?@PYKmG#Htja7rLS0huO*FdeaTa*nkUH9c$$LxWmi&Dv3kn`UOARS zuMK0dL6S7l(*YrblrVGrLYy`elR=cR=e ziis<0w7k?_BW+1L7wpxhwG*Cx_f7V;r!?QK{}v7wzrbz}rZC}nj_aTfY*}BwO#i{{ zH&i8xiFaj>(!Zn4mg%dsI3+lXV*w6l4^J)WU{CtuRLyr<@*D3!xTgNC5%qEU??&JR zr-f@qn*K*5ySI?f?2ED+3Y^Ur%Wmj@Gwk?V2eAqDbqxz1KG?AAJAt^m4x+`$n)+o| zOZ7>K>q?d%MdBanx>-*;?976aT!$Ubh4@RGpArs7)a&Z;3$60AN^;wS9=ptGm)q)aSHy%2r?ZnQTHCzfb!p$i=-axg;bbYn+%M z+98wA>PdN^2YV>Mb4B;Lo7iFfBVBTwHB7tK*gvA~l$7 z*1c8ZW-Z4Y^(5&3C)yLI1mPq%kd`vjGnV%m@W56- z-*U=1WafXn1U=+SI)7?Mq7qmo&vr~pU=wCqWnEv1NduP0OcTx&2N~BrQL`p*B@~;)V}ocw&xJ1w3@dQ10ZZ5$-SyV zJj3SRCUi;^j(3#~b57kK;F+uPd70A+Tss9DbGTglkY-cs3m=4%WC7$bNs_oWe2*k2 z_+^Eb>!7;&W+lS3*A_1=t0eoo!mQ6$@CmVN?!1pr(B^07i#~hY(*nz>R4;14Kj2Bk ztSCl%-SC$;)QFyI+-3p??>zRw`mD|qZ))IF|KbV)d+21Kbp|Um^C5eaXm+WsOYNi;}Wd zCU29Zto93>dobZ&MZ8W8RaEZ~>KP29@L0V;VpvH3*GtMe4hTiZ^dUsf>UH3)vJQ)0 zFCMyT@NoNt#wM787RS!)RO9ky2dl~Y{y@F#^j+HdwC+vJ zamX^aKG&;_cf`fdooqa-jdR2$d~#Q!Cz#GocL+XC26Of(#|$YD=&52iA0|f%9N3r0 z^ol;>XI6oC@`VH>v^xQh2*$PxRhEv}8BpUw!DP@EXNcz^E{#apx^v8~_1>>_ZRX8In|;TBw0;69ejfwE7o)S2EP%x9XXF)?w1hsaoqW ziJfjuFg!fr&S5x;5M1Y}cQQ%t&I7i1$%GxB+Ju+3kPZiQ0WSp{p@1thRj)Zt&AD({AGSm$#OyRJG$_z&eG?%zZKm8@;qO zCHxlRgUYHy$}F615wQI?^L`fThxydays>?ctGi06Gq7b_O$qucsg>-}3FeVn{X{7i zYg2-2vKFq-PNG{{^za6kd6^N>90E~N<_@v0L_c22%8)I8gtqQexKK0U9Mp@X$8TY9 z)Me6g>!=R$aSL^LlWq0apQ{lE0Q?4>WiN^x| zRISfRTSVmF3C&`eYUIDkm84W&HeLwf#NJfgVBS2 zk#Z&~N5!_F*v4#yN0+o_&!>p~#xV=wR%f!D6=LamW|(TxFt@JG-I7>m=Mo4hIOI|> zDhF>gkC3+!6B-M8kZL)WiqP@Ll~{f4O(M5gmtOlIi$fTOlhcn%I(y5NWbF?*Uiuj4 z%S{hYyc4!TEGzKtTMM0)yBx2v`3rX0IObOqp9#F zYMVyHn;!VRO>m+XfC0BQCR4UG&YkqRB_};6sV1%l=_##AO6visb$-8|dw}{PjJGLH z?n#ty42-Bxta~dbssY7wXdA1%)R#jE9lNfPGgZqCOL`77hJK_F9>fQTV<@!sggYry zy*05u&MiCneoYdxBQ_+Ol9bUV(?EO8)E;HY>~S}w*AQ9bIIMx%K^A-(&&NUng?n@s zTjHyW<(G) zh#!fu0lR2U=su+Hq-=fgpBU*n5u4VS%$5y&|0?z&jeoIrG7j{^OSH`!z>jp!`nVQ} z3XzmY2|nf4(BvRj5N34=N>&RIB;a#2{vG@Q_f5>56r$@al@3b|GNg*9+rOtuEDLs> z2(`(Lyf;FA!IA!tW4Utr4P69&xtSp-a!#+(HX7D^Nq7M?tDZSXDo1yNlShL~i!e`U zgq_H=!MUhnPd6`*o=~r{{Z(p`tH@DAs8ubT!Do#i+R2vT-jD}@YtKaCRNKEmd&L&R ze<1a!mHK%SUad+?45Oc}hs1FzmB1B)yav998)hVNrcoJ!4gxNR^jxTY99{@F+mrwb zC?>V?Db3bP9=JEmNPnP%eXLDZlZENzatS|omQ}5?PNRj+s=AeJsOvo4dS9%q{#@XF zU&^@GmLqctkLWl`UoJ;TO5_~VXb8EP%60P0DEJ(XVRakTw`E3cEYVa}$uTf&PUV;? z;k@&>Aqca3Q*6qV<-w#Nmqd+cVmh);1l_V0b@*r6EB1^~Q>?(i@$_ppZU#VBpeb55 zQ4&8z;%-_m4P{4-bEgPYiJ@e;XeuXUz!G`!P!KLMv?y34K8wV}sQeFVH)&R%ljx>Y zy1DgV1zV!L?$}6ukuNZzpg}rdJwx4lh`A5>rh#u)P@IB%pi%7r0j^=)$h*XT6P z{I^~a@Z>(-kJceG{qMwXVMN&(?v3SprB1KZ=S*-GC~XBQt1TL13p!Ig;G21c5tj3Z%1-^ChDKA%LY6Lkb zDYM)W(5ijG3?$n$1v3J{?l{W;PXoD}|AU=K-IL3VpCN)Y7^6dD~9K>NW-^zw_o zKyXqUZqw$Tr+y-51LGZCCD?LJ!Pv6VTc9!!A2vx!3xn7`vx*tpFvR5iMN6gYxmX0c zRF9Mx^84Sq{v5ldiGE5YzVsP2t~70P{G2wqD_y%t1K%E;s^R?N_tabq)1TEXjHJ-D zD3gliAF_4nn<;^=c#0)mPUU=~B<*pBN1YgdZmR2iAH02def*+rkJKNfK(V_y$wQ2B z6k%t`6V^(-Ren^tHh@-KLMw{)gu~_&cb%IKCySnmSU10gyGS5pK!JyZ0x}W$*->)W zM}7M48@w(tzy5F3Z%*=zDuJGsGUqbZIaU%Z_bsxC-O z&>RsaPKMf;5;-@HFiRZ;};)X$v zSFp9?9g5p3=Sb%xVvg`qNf3J(Q~b_#BxV_?LCvCMf3v0#DK1E5VUUSs3~Z;OP+&X- zb)xzT$upBP+3%ztyrClxG5u@Qf@(7xo_lCSU+gj}PRpK}Q=I_>ta>DJXtMGUw zo&tK^OG?D;$Yd>C-4OnxndS#NlJ~Ol<^61p8;cmM04r(|18POxD}hAG?um*(qO^Ih zO7PUdZ-Pw3{TKE7SvS&CA^a7pnJXYO7ynL?Q3q+yz4Hd}g=RL@j0P!fWg!`0#n*g% zqDOu=Kb!Pku6}>d2+p^kpG{JLj~~I$rZM2-lWYgG`Po`L3tosLFA8m24_L${8fzk} zhC3nUU%Hh|>+8!NFPY{jpO!mz;JvHMWRl+In=Ua4O9f!kkdgjOX*#@8)PQ3coJ|aI zxE^pIxXAUenex>@|6OXHtf{*j`-o#VGKI)nVZ2h7!`Z2FIm=ver(L8YVdMS#k*cXx z$k#-!v+0)fF=ECh+}I0z*IBTd2y+FGVJw3)6+Lfmkx|1xM|NKT|LhfA@ooD&MN|Eiw7JN$~pr ztDhFd9J2nWum-^_0vDLlnEelFEJz}*Y$<1%@ZMOqy*WGgc-|XWR=xGX>2Gk;iDEJ} zTRYrJN|3B%^(__Qp4gCgUBHW|EH!s86>!>?S{*v8gCzVs-3;1hi*t#4);tW)EY)W- zzR+@4)pw{B^44SB8AtWFFWwNh7fPQ+W&R{KGPYPhF$u8lZwl49P&SU(ESdtOCz^Ps zpl(O9oA1A5VdO=9MPIaADX56xmmk)R9#XeLtXlyD1ss1+_a*Fk8S{!htXMRgOISlD zd~_rd?ufuRY^wc>Hs%zi@SIJak_YH*aV;Lrzqp|kWt<0^LX-mNA8XOJnrybU4qL6$ zX|y_~p~0SM{0uq%BYAn{a%1?76pJrqRPIHeHa-2cNt@!{&(9zOUPQFMgWqWS>c1YZ5F9JR-;m==x)CtgH8}+mL&4kGAoJ(+%2n z04hY4_s2PazbuZems*&u9qXTe!yTeLLVtQ=V|@zGJbT5G^!+yf)xNYwok{a-GP2)3 z3v}>tWq&{NVhiJ+azo5@Y*Z{=lQIsetGi!cfGZY*T67r2Jfm>@`?8q)#e+;;MG8ky z9TJig<5zCa>lm*#W-Ss8cdGnTNC@%97X-wh7bG&SeIb%zilUvbV;WhkOelf4B&Ug% zAZzKLR_dAZRQQ8Cn5+qUr2bOlK5?HDflvf}6G4X?kvo)|JKXetr)7 zaElciz~|^^5TQq>^9cEe{Kelv#Dw4NqXg9BYOCsv%}5JomZT<7cmWJ8QHQfm!!+V~ zof_{qEy9+aCh>0zm6=mLx_G#dc=~h1=x2Th7wzCE{lTk*&hM!`N{6RioyhljI1 z=*3a$x-BWERT9eYl{)8bVBK}F&&F804n)oaO3BX}OD>s=gpu?Y;AmODBnH`plZkRm zW8Pp@*~*9jYapRhyg`ix%j>W77kuYCRANR(ONIFp+~Mi}l>S_}x$PIP`^>T7(Xsr? zZB|$8#V52ASDs#pKc(Nlj{o(_Rllv>h_!g@dC$x18aLKQZJkGn@K*X%lJa+@H*ixL zoGMi+9O}To8rcT~b2OqA+{WbbWmT_Y!vic~_e_Uc2DW-G_HhmVZHV| zoI8SnISknh{1d2BSgiGlr;utl!=R6 zo={o)XS~#cA~jjObWDwrm!{Jp-q=ghjI+|rUg^(5(*M|Y>2+QR7UC`mBo~~?OX2&) zON~_CMCC_al8!zrHTOzWL(;TupY)gihd?rC1y=&nNgrp7{?|$G%P(QDWUQS-X7sBH zpIO2kr=svtOHv$F74C%R!!|vM10`YDuBHFUubgdZci;JK-OTi>RM zd_qiqeN4;1ORNczH63>KGX9U^{v0|*)$9D`FRaa*Syw$%Ii_-44q{LA;=NkFP%QTb z!KQn)h7Z11tCKN4`MMidW_*!u;mJ;9^f3C9HDns1oF?pJs7h#Wr`jZEQ6IZ~!8QbS z1?1~s#)ZG_EB=&xDZ|%jZ;G81O2Uxj(eljb4R{^eVC82VpF!JQDGBOu2c>v+%%GFZ;>W(n?dsUO z2{rwPK2v_wm+a0vLpmPllH$+)xr z8kT^JW+Wf_o>6H`jdP*}R%O=zJd~7{1ydW!o!zI8VqLADtV-fcf z>yslrvq!Ghzkg%ay5(t&nQe+ZIewP3ZpR=+?@ewM9gw`QE#I~FQ;b4SYp1fo2q@-{ zKdUz;U-rq>X^rDqjc*!Fblsaal~unScU0T*sfYL7mOO1&&1iJ4=Tqujr}8_h>-T?l z)tEeot-tTKHCPz_-bZHv@PiQAuh2c2r4nOJCv7%JPj-XCaCx{7sV?k3wKXOE3I6b% z(LA&akM{=Dku^DhDGU2AASW-K{`!nGIA(k#@>*2`6s`oas5AgFDwuHBkh?Rr{l1HL6n5S6sEihMIjpSD;m3XA%o>8%54XwDO;P|uqrU>_~V3>oReb`FW zWMS>MN$*4@?!T$^PMn3+8})XjVQc^xL_B7q zOVsyy$AaH6MZpL5aSsxhhcszP4`$r$L_exK87DfSblRhwc8%f6QKd<^2F%w@mLsl+ zio;7PE&h%L2N#B>)60Jtq^w~@T}=8^r(BXgJ=x@(MrU$3)%6M(Ja$!>PNDsKhqQms zK5o(v+JF9Ex1aU@q5X#kwSPN}UpE*aXxPV%Bw!Gk7{bwP0Y;5&;W3J8zA%bS#8C2u z8dD+l5FgiqA>+sj{m=mr^rT?aKCHD|R6jTn4Jf8Lc{1PuXnQ|U-m9_}l1`CX9<}9npYA8CN`<>CL zHCeTzZQ9gwt;L}w<2`p=Y!_r-bT0R*5l$6`BLk%Wp~)VNoGStYnC#TFr4)={c)?>I zM#(7b8ukH?J;u|mHQ8fX=UF@12UhSg9fza$4sd32L#M{F?2+RIfE2rSnK)AE_X zZ_E)$E_M-^43Q{cJjP^?GI>=dyT)cG(j)0L3epRjfVf}}mR=JC$|f3FG|)!bUha{f zZUY;$|F<^6_KTn?J|a;g1TG$*GEOk!Aci%G!Mpw)g> ziSUWb)Xygv&v=4$Ef}|#i@ODA6q`-l21&sf+`ubC?JJBKGnOxmY_`m|55Y$U7(Q=W zir`=vl8ZHTQk27P;yQhCn3?ZkTasfH*EL#lf&PR>ScCk>aT(N(KW0!nhtQ5V4+lE9gVc^FVkVGZF_#F8c>v1?6LU@Cjf0cJTVV0x&0~L)Qx~@8F({%#lWwA$QVuMvz^zI=G?;KL0GcGWdSF`FCZP>ocJhl3h78jvc}54leuF z2;Py=@YC}3lOba^W&p>u4$kt^I0pV-aWtP9z%iC^6!eCe4(_&FXo`A6#)*N6{-NFw zJ~;%}n|u0swCD@2@>>ojhuD!q`$NCcu2wmP_?MNLysr<#j1%?1K6cib`Yh81a+*RQq6CED{AlJ zI^VoUSe#9tkCh6LH%sR7T^Ra$Dgn<|R+4BlNpIAb>fWP!d(&S0A%JV>Eu z2@ev79h!xf)j92CWfwK1?ca*~iTPq5=I!C;-Ri^0$T}D4L7^HGjGFkEUmG-^g{W(& zCDdnt_?B}s2!f#dBJIm^%x*0%q!MO#@a{|;_Y;x%#qKP+Bh;?~LjPl|b}e)Qr#(T? z{&Y5boWmaPv?HE|7B_stN6!!B#5|r(`1i|T%O1{hs~2Mh84U7Aiy+XSmcYJ2ebN)W zYZ0D`-^0b11+=+8T5^&5L!Pr z(8k;C++QMXfO~~DqOkYwXQ&F#d}eRsztzIpL49a%#~5WK1$Vb|yCcxM6^5aE`}Y1u zpvn#G?PG3H4^U5Tzy^c;p2xZez4-t(7PRsI;jZ6bHKcD1)Hdd)zMZSTHF`taKHT5- zzh_tQKQ*Xt9L6p~n4kY@=PDyDfH#KD4>&@UNl1+|(7R!SEEkmDy;}zpjW|os$R>nWnMHyevT!$g1$edolCz3 zG@@sc@+GqVkFTY!g@brBkzn=95q&$SzXeXz7-E#KCVD1E^_cKt-t=S*Sos7dChaD1T-)7fACW_MgdwiexL>!)Q+c-Ek~e0z8QnD^}Fj#3N%q}%_iF*nZ~H0FB=R{xmq+0E^_ z1uin?hyV9659bXT^UVYJy}X@@BZLY~G7q`r-`hnB-ExTP8M};sF$EJH&MpF zt8@F4`sV=a`8T^rZbWpDuXj-!mv%)sO`MbFS_-V0 zLu@IL`PU6<`)_Dll&OE+#l73#YQGJISUb|QAD5}-m_e`(P(S*|Dk$`0|1F4-u__sW z`0tKYST(4P)&YE5c5z#7L67WD77alE34CS!u)w1mcM10YYr*Gt34>3&h?=a5Acl$a z^n(V6z98hH|Lp*i&a&j13S(!1tP8aZ=sA7?JttHO%*&!+Vx`Eu;NuZX1?Dx(a1`D) ztK><+-t{D3IK0yRBskJkXjq!^&C-e|`?(f|;TXa2rRNKiOob!M3(30>AJ?~62HOo5 z(O3&QM%gaz5kmGyXdjkn@Tr^jJ^vQ%o4>j;cz^W^8tZEjy1Z`}cVGXQG$)T2*YOhr z!(A|#90wDhh`s-_2==7E<_yf?gk4p^!#A zY8N+(AZEhiimRz%aKi|Mum{983aIE;XdWml`>~`BUxV>Ey)d5!LiYC zsIS-$^PG4#V*c<7*;+oVEgN+dW?)Fon2yoddcuw)oUOuLshc)!)#q_5CGcdilhcSh zReF0tI2Sv=6Z6tdXBwaEUnL6J{7Bb?OV(cq@bP^+AJV`Y&?G|$Nyko{MR9xRJzSiVrXo%s0r1S) zR&FP~bKWmC+@0*l!Jxx?)j3VgcFk&C_zbcOMXjzj-H-odC}_6Czz4=FtY?RWF|8ft zfK?POr4GU88D%1V{l{OV@#+X}+R1Gq_@V-Hhhc`eZ+{Ea`h$JDfB%qidWPzM06qw= z-O1J60uj+MAoyv3e$plq-g}E)kFOe-yNaFMZ*Rd8?MhJ9`eFUhuH@Q11gAv=r=K^= zc5-F6K#9C*07enC{uka1ZySW4V=&xVJGoi^1ozy(3)i)E5Zp-v{hqj!yXO|rh&@d` z0Q86b4mS_!cRIoOG&p7_H->##-E1(tgZl>ohY@MtDwavEh8rs^NRu2Far4D&j1GVJhA0T_ znj^Ikg`x?0?uOfl888z5^#TvUuO?1n5+so)PBL~p4)Qz&Qv7a;$7}M5^2EczTX-!* zMY{0{Qc2X64v7852_q8>?tq<$+fPVApGixaK&qV#+b@Uxe1CssOmc(RW0Op35<4rC+%sP6?mg5&C3eohf%jhK9a7#) ziBLf~yn}hr!rO?)Y*DM>sH72tEl|O~n$Q;Z+P??B276>rxOxX!{C-D>gK%M^JS-4y z#9Editk$64C|Gg_ECT7zq}JHc7kiwTb5k6jhlaE%721UTZwDv2H3LKT&%bF;Di{R6ZF|2= zeq}qim0A!<&cc?623njW{PgNObqMV>60DA3!*;IW79i374Owh(N0fm9`}dSva`*UJ zsw?PSHQTw`Th+xiY^Ja`JN#pMm;at2IQ(`1&dTjv#XrFjc1S-8$2?&OoJR)WxVCd; z{{*LEU~&23n(DU>hJ#%Xe^3T-El4*xq#HyV@4YUDgH?`CK|~lUTMQ3%(uwm&MF}+T z`Wa;0#6KV|V&dB5@ty)Yguo{ciGPVkrvNvfHzD}*?cC1^GsrtlzYUDt0uG-faKK?= z?v@CJ{>!r;SK446OPO`qGPTDLpfH&s7O0PYoxK%>WyOsArE?>*&>6EQ~ znM)+Z#YAW5Sv6g~A*@B-%i-NhxIpV`rAFlrR&HT@CRzB+VYthIhu0)SJTJs*hmQ>7 zH4=RZ!>6;GuGS}|&P&F4)h(`1^t|=mt}!tli*`Z-vNRd?wyDEwDHRO?>58nUxnFL# z{u!=+mo3QNtLAm~u@>l{Y2&lkIMt>m26^4_l{>#3X__nHYFBxA%^tdl!~ADu&owt< zOx30myErLWjBwk+mwm>Q+aqzwsEMFAbHx`u=`@B2k!e*v4jms|gQ{L)Bdt7$_{kQ6V z*YiZynSj;tJG`^%R^!{>@oly6?YH>$0lxiK__hk)-ov+5_=bEc{NXQo$E$d@nWbgZ z5<*^hF(wE(q5Qv0eV9rIN~B|24Ry>f&~9WbcNF5g9Jn) zitAN{*jwcH3NKgDf!np4yrytM{ds*pbs^-{APtv~Ym9WDxJr_>ZAcH=hV-CyNDnqg zdSD%ngcM&|g&rJL)P;{q4ZlNpgHyOLrYu2fcvQ@9^%ypHO5Ca@(9|WbWWnjnvyNRx z@(~2PVj2;+D0C!3bFU#0u*9`kMYK8*L8pj4My7##WRYITM(YbCye#$P30BQd9mfk- zM)ESI?gYR21y3Bav0cH>rd1WSLf!)3!C83b7EnjW9Y`^(ZIg!=N|j<T$dm*Hkk6)X}J`cSv~q|G|SvmV#R(?E8dAWt|i0L+wNcsPhW` zxqgXmMszr#59Wtdn5;LG;D?{=e-Ms@V%!Yo5bdIm<_89TH~68}5BYtH;C@$kma}Yk ztF0v`(EvVTUWBVYTTUMi`(+!<{X=s&jwYMneTv4Xou_rNEV37%9E!h9#-YcGQ$qFu^k%MEzCYeX^{R z+i>7?pR5|0E?Bwp%RcLT8VKy!lgNq5{4@9*3km0qI|CR<5};2&_US+U9s}vBpn>dJ z1cA6>Sl4%bG@zGwfKU9qQ!WA$!T87YA*c%1xl#Yy7&h6wOhI1viKg_lfcNE&4z{jM zK8AKGoS#r1=r`maAG%(-?y}(;JpY-E6K^+e2p|rtvUUIIR;{6@o-s9j-ns?CVB?^A zr4rN|V+7I6N?AT5tH9_yczwZZmu=oVcJI(ohJG}JX_6FG29D)v7d*QkQB}N|u0*%2 z)}OeshYUyIlrP$m)bIv7{K`F2Hmy@dBG#pN2KPWI%hK{K3RADb#8hM(Cpfk)n704) zXzgKzwdv|aYnysvPrFgLx-eX%LS`PVzV&K$V%h8w&aRBpW!fc+EU9D8p@ls1pEqe< zM#i9Q#RXORD7q}bWcpp;@M@otIn79L?W%;le~zjk>mN}dS|;f-nhG^tJv~j^J?*f< zj)we&XyfEWSfOTb0#M=7jPNm~vI})>Mj3L70ddn*wdoy1MBIZC_?W-N`dPf>%dW5c z;2(~$Di2*>I_vVTyL5)DtbT5L46;|sw!Hx1Z+%5fbG=0tQ2!U z`c+cldRduypUfna)Sb1&mDx0w1H}#@Pj{2jl$wt4@KGk_T*{qQnKIlKD9CUq!5ETo zfg)wfWs_H0_o?lm1p{ig7mUVrN+$U^A`Rlnl*@t8_1E@aHe5ydHzTZed0V~u*jnvt zZVExIts#mjxydG9nS|?&{ZolPmfS#AkH$vdm~=go)J6vuryCY~O8zf(?;hV&mGuvw zoZQ;$U_M`uVN5m82r3^0hlNe)^9bmqZ>O3TzS zJrF2`3PeQ&nTHmw2xUg`GG5SeU?N^e#L6hN&HG(DsWZ>>KEL^^>~jGg#vgB2s(A*`4eGe}J9v@HqX|$_iTBWM;tIZ_`=~ z2^i(VK~F_RX_3Xz=MN*am`T}eQ!}Kk`3VC$zC#bsN z0~~qWJ=?Uf7{W)8%OU7R9W6~7`;^}t0^M)XxOZ@Vk=NbH$cEp+yR6(*XMTxk$yFN< z54!8Ght?8?maRGj!Ayp&&O+H;mE2+RKEL-gl2@|i`wt1cFaUn{2P8w=wP?!jJ@iwQ zyU?=anrqR7{PZ-0=v3#01d1a~H zzjwg#xk!I>hTV~K!Xk+!VB~bTSLbx9V zKT1C?fCl(tI&7L;&a(O|YAI&k*=~|MIRV?EcD?4 z0LPuz=M#Fd0C)5<yl)vD z2+0TK<{!xAYbm$2E9m=BXZfP{%hXFJ+Z=WP)MHc~F=E=t<2#1OdR;be6n6SWOSH&9k(rr7B5!TP0Uli1S*- zdAr1UJB7!*^Y(e?MFm}8-u}S6-D34rZ#997djIIxAMqWhCknS-&?Gzm&?O-s-4|+n zuY75%qA}nX9~y62_lbeFtOZgA&_pvNi#|`#S#LfF*3x-S>(ul90|bqapG~+xLcp(FG3H{&q607n`(qhIwW!9Ye32aV4`pBL;k6XzcWr#vDEoV` zent4DP8p4ntn>pvtf<+9`CfT@N0NPrxWeJ z^lMcUweWu@>nDP-){&WTsPSgk=@lDmj{m3V0 zIAUi;CG%dUyuwgA$$xsO>slL+r|4Lnke<|$;3R#myIK{xOoMIz^1z$n1EGJ=v*KMq zO?^Snl5N4`pB~t;w*BIPH-iU4pVGI;#uLpK4n)F=5*ZX+Jw<*k0l(jY$W1chK@Yh$ zInq5FOt1M5k6(Ot`x6+DK{P+J{YjPZs%(z5fBfugjl2w{HFNW8+jxhv5G=wEhc2{N zy!Uvc_4PTgPZ?jf$T*$u6zqq40H4j>0z9k;*-G>Qf<#&Dz&N$@Ep6*gv5J;$V~BeC z0uA&mjP=eazWLt^dC@(E4WZ6g3HDRCc(f407%Tvs*L{~#wv5rg6bdGP(RaQ#3ti;! z0r^6|KY)o1r*+A;+z(-`y6{5~P|ye4!U?v8lh6!)j0yl39^86hoZj}9Ry2)unkIF< z;}nU-6}_a2f;>u*T8wbf76A>9(DrN)@(OoSa0OxRNT1YNx3TzcAdQec?XVVn_2k*z z%k;3}cvn04g*!*2iSuqlC9~)--f1F^GP+mr;uPglc|TBjbrt@S46h;Px0u9NDR>kx zG%8FoklieYJsKmZyOtmi7v1E}m$Nwa($bp?r*;(DF9_K!V^OQ`89|D0lNWA7a3CPD zWp_6)(!Ntbh?3tLUT&1(+AF=nKcq}XD+6zL)J{j4hFt&jLZ!5n@!rvgg>cz`x0T40Vtb*p?C~U_LMBO>dgsWN*;R?`xHTx5sj84z>oB zMeupTbt%q;R5^aSONsm^GHfz?#~AR*m5jOR;qZ#d!+^jir6e^Xq;x#EM#(TWcvu5cmgSf zG_QJ&R7v8L{eHn9RnEbaWS<|)-tW!cBl$!i?2AvC_T(C3%`=bEX&!|bmI>MI!T|)P zVP)|>4u9W2(zz+5KLDRA4QZA|ni$xV4AGLNkxVTT3#2WX_DFNo5c13*DtTXftYf`o zYL(__saey$q(cqKv|nQVrsmRFb10Oo0H46Y(|Ukqx_5u0G;m*j*fy}WuvGd)G7b$t z{@Jq#Mq!Jr-8ke1+s@Al!$Ip`pC#`jB~z%|*mp;s=$`xr*@XdUua^nta7f`JhErwlSvQ*ax|=wlpc5!qJV8pII&E3`lrzs( zYxch#JH1}aYZaL%3o&n>$ifhddHdVc9dj}|+AZhi2;!WSnE4Y8M%7Wfb8@)wT0o(J)Y~{7P;>Pdm;52bW8aS;H>dw^p1ro#PFgmFG zgnQtEYPIg?IA?9ESi8?#yB`&TOOy|M2}Y5e5-~2$*>M++k2K<}??b^QkV zwS)8GeYJ`D(>O|ej>hlGXw%pY--B+MzGv{mc?`aNigjTBNrYUhbpp*bQ`f&RJDe$= zz6)+Gk}aTa`;Fg+9;Lb$9_Qg6=;H+POBW0Ou^eSFfh$O?XF-c4p6Y!r1Hiva*AP(NSK0WlB*UW{V*@YKl4SyeSo6I{!xC;6s%iX+Nm>kpRf>ne}ibW;cD)66ocHK@OX-BhR9o zUjMhJ+G1u^+mf{TC9%&pY7g zYJ(Qud(de$=Q@~BY@apzHRT-as#npn~zyUOA-}9-v_VdmThQ2n$ z+)z6;+sB*SS)ZX!IzW##@2eCH5O2$zqumyEizQmja1XmDWVE)JOtZC+#biM?peB2uQ14+D5b9Lkfn>fvJ0f&0K zyYesW62_;fh;5GEkI7FY@yiXdPDe3-0Cb2x3&D;3HjQfz3Xcm^pPVKO)o)Fc^$5u` z*M$KlAsStV;uKSs@Y6+bPa+JY4CQ0)0HT4?UEPoaWY*nI0L3K5-Q>&J?$g#)BmjoG zA)GT}B-|RCIA=0;m@;GhjFy1?xQ0z>d@gS2d|s{V))N!?=YLhdPPi2O%nOm%_ z8w?jxCrO6nj98ISS46D=obdks6GC3uPY5~UimMuvUZAg>P4nd*}&xESW(08@pY-eOSW<a}ZuR{YG7BQ;$Yh3v^=HgrAY)Nqc7xjf65gnfKAV9zDj4RQ)ulj**CCdPrE>tY{Q zvhz1$WWWM5ult1E(ah4uvb3pn_F-QNr3!&k2A~wWa$lnJoxariT$Z5qd5+5YYP5%T z?N60E+vmvAV_`Bxxyd1tT;CDF5+Lwx=?1CNVQsNxRoBtSA#+D$EgO6?FS5nM1m$s+ zmYvTk04~<|kv@ls24z{IvR}~(58+U>pOrywdtJBdV4vNo?R>Tm=!IO-)hc)GJ9vms zX1L4f+MYg6v>5{ti)hyavTJ}RH*w|VC4q>Uo`=CXDgAdO2)<2y!0kyaZs;dkuCAev z3q182}zm!+HTjnJ`QcrkZu6&Sqr3sm|{)0 zYgJzgCw;4bLdfc(|ALSA5gG*|S>94T2nzKnioPTE#*H+NS$H1iAH~;!i2-HcJAcu~ zeByIj5M$TvKu_aw&A7Qq@YgNum|9<@#rAZ+mcvKw=ekL<`g?jcME zrmJoy!7Gp2l+ez71sn0$xr8g&zQ)YErY2i@L*vM@0eRhTr3bP&|1@4_Mi!j1JRn^`ji7N%c#Z5F`Ez6}TRIVFu*mk<*0; zSQ+pY;d(YT2TN$ZeAP>YI(`@PT4!Ibs?V#t)SH~sC8;^R*h^Od80Kz-LQk{*?1InmMmhg3Fd(k_eB?D5< zy3-VJoB9W5bFZ=X2o_cixp-ydv8KDOy_XBT+OrZqZLgM(9a;A4eaqBulp9x$IziVi zV;x27>n|dFllDjeYy{!f3%wlnwTD`1UyJo}r7h^amiFiay_k!fC4Xb{b$7zGub1Z5 zet^NB`w9NhUar7}6>$$%!F;ZK>}o$cJ%+pbP$3q+?hm~{m0k@fRF|m}5??S@Hk%&R z*KO~`yxp(>IDKpXekAu2uY;ZcPU_9SSRLPne+V1Kn*b_WB!FIg0sI!%y{&>9UQGCYe=iMO zt*Tp2b3Sfcmsz*0mu*^v8@^tVpDxT5CKP-%-n9PY$T68oOaw(@bjM!Crq}nM8h@TK zi8K9lz}*YSa20>T!OBxA{b{>t*M*Ui}+uFo@+*LsnTVto8AjFqqPMX zx_XnVsS-?2OW?Q=|EH>M3hGR55bF_d4IRfUE*_QY6Y8|DPvYlkHR3ok{2biv8jZQ` zp!srOzU<#{x{nWvSPk0=?nC`qqMG5E7O@D5-cqT|tF-(NLd*}5W{ zULDc*LiB+V4q#Nt$s)Gdbsp%g%VQ`MJ+E=wIadype7I!(tR!lE$i5qU55-$)^V4#! z8+udpKZ1JrIzum7M66yk4Tgnw|M*`tDQ4ZJ#zN626Oqe4l2YH%)b;j|{K0Kfz4=CK zENX6lqqX^s*3cb<3SB4P{1d)qwV!EaK^^9F?)8Fh&C3i{70Do-w#s{o?+HG&ZEJAV zl=xm8DyKcEcbZjKi&ekXS+u5?k3iXF%k-K`&&PXlBE9Fy`-U}28dY$aQPObB!`=uT zcoeg0xmR-Q<+;3kx)0|aOo41Vu<@mV3^_ti?nOuFx+Hk-w#C6!E?lE>Z`SV>hP7|m z+uYI`+Cu4jUAUhXT*Ioou+-OiYgr|co*l9>L<5e=o2NQ)I4BL&zgW6=W4=~;Cum8# zCgp*KEe|84RT;nEt1 zm2p+Lbz7=gV7`onR`9*|bkAZyVa%{8OIjCdNbR8N1l>AMbr!F;ywY=4&8Q0M0t1Iz zTX(nza#JYh%m5ljixaM-&W~i`*B_e^-Ym60*ox560-w?P;tskcK9|N7Ze8_8<4Byd zcQhd~Tw&>yt+tW*VO-#04p9zgMu`>K+r&*Y(z$6Yy!cwu&+|JzKUT5Ohk=p#Cf@!burKawR=-;eE$HP3H9xwrYq z-q2X;*S?*tyWVVU5r)CMsJ)>j)IjA%7|ueih$Qk`M#ZxEEys?&;A9KBq7~mlPyMTI zs&nVwSoD$h1ACiy?hRQPJZx3bCk>>Tw@xMUuQX+Q5rjdo&%ADZ@&TYM2a(J8NkiC%DJ!XLKZ~U5G(phGXi-$@~&GK&p=^@aE- z>;$2o(^zmS;1rwdxW@N{A+)If3&%krA|GvZenzXbO%uO4gQ|@W%IL7D(6laQA)%&a zhxWL^Ye5)BZ!N6=)P%qBO&G^ybZ;QK*Wns~8o)y&uvfcYPYBxTfKpr<%|`8B9Dqwo zqn3<4S-kEIM3bfpq9N!%U3I_uPn;BJ*Ni?22C&K};eO~J5VturKqz?Z?|1(mKbGix zj_A)M{yhKY?U>}X?KAc^-@Z3=oJNCXi#P-020=H;#`A8cN-3&}K4Os6Cmj*h#-n_p zqi|&5DnfC>mn62Jo)M_$$M%Z7%_H`P_E9}BD6`BTAcEiuz9TDxHCtQe&6r6SfDs&>hW^!=ef+NR8UAiTn-r~1EWN;dEq(d`r zS`Obih->ltyap$~X4=vFr~G*jRuFZV`ushu?`#UFpBaSo6C1FvWTI? z{}WE@p>%|f?WB%P9$g4(I;_gc^j{eb?Mu?o^*xZaDz>SCxhcR!?>4y3LdF5gWfQWT z{dR;d=)8%#G`Ia*DRNt|D%0{P#POjmRJmYwxJa}Lc$0vOn*SidpzPcEo$DxMNhMHV zGoYRIJuUv98nQ1i2YzjxzYM3yA=PzNb_H5!&4Il2HUC7f~gu_WndtM?L$1{mvz$9-L&N(+&Ic00;YYD4AVk1UjbHA3RfNnSiiF>}-EFq1#9^ek$Rv z>2*EI?#qc5E^dh_cek%>X*XtCGzAuJpiaZ$^yoFBx!L2}v% z8mkg}o;0({?s9HU~Z zv>YXHh6<>0ueXw2vd+W&Ac~#n>_bv=Pjw?&Q`c$auU{83QeKC*5{ZK@mz0lKyeb%Y zO}Fx)prmJ=3>(|jaOb*t4Rj-Z>SAO0*&=;rB?WJ$kNbN^M;0t$-y>DFPG0l~45N<(Mki~c4dyt{a5rtlYJT4Ny@ z$+V?(Jd2ki5ELfbmzey9#xkjJvXnJ#sS)dXxmVB!Txmj1z(uSRzW7V|y2Xg{x!mg? z$Lj)|AG-|#M(K0`7ZJxbf9EaX97ZVcX0HeSLIouB$K3=>pyzjAq|kG3!l6~W&02>R z_ih^CVYHBKrq|SnYUIW1RD9$R?^Q^cxyF+}Bg|g^k<)6wvCr%F!o(B7h5xd-%X$ zVZXlVQ%p!S(@?*I1R(gI=h?LTxDGkM?XP_ew-ZS3d@_-QF>3AHodC&oMpRA)^(1yg zJ=j;let9*5<*CmY3VAi@T~84fY4r8^xV%L=@=kUJalDHDMMNhWZ&bwu+$ILs8#~n8I-B-m_5;IKOc#P<%y#<^W$04eQdtpLK*SLS^D-dGo zY}xoi2`Dns9>?l+px!y{m3x{UdqM}PUdg8NFDn2W+>xepPgKSDgv|GC&o{)<)Rz0O zd-)y#mwh$^Zna5QXcqC9=w9KTSoHh$QG1#T_k{jH)d1y$jDYFcXkR)-RfL*U0XV2J z2}f3DG9(bXiO7Z#p*)shdo82frgfa`9=WnxDIV|R3@Z#`o@zlk-|6CnfzTg?)qxfl z>`y{fTe#k)Yb-=;H(V}e({(MBNwlFT1$Xt5Sc{B38=BvKSZ5*KHB+V!s7lXJ^wM<`5r{z z8IC;G4&(F@y;6%bwBzV!qvGe&JGY^=e!eKWJGOgQ`%AlzNtDscrGv{qzd^tqqkq~5BKhcc-yoK<(>+biwL zZpLGQmR%OrCDXFC&dL%LcJkl)v(msUr(R+3vsCa#G>~&Go}cNCg5V*S@B0K)8h1dx zw+1@Wt{e^mc*iGQF)tSlBQM~cia2mzLn*`>qS{MD1DeQp%Sh^!T%PUOEuefz(M zu0T&*H0QYIYs8&b#JM>rAncEwEKxdE<1sWRicZtP#y{>L>637%0CI``7LcXxI~-(r zuj#;o!-rw##2)z0_Y>0Y|5$M3If>PXY>4#-65(7$^=IJ^jF7NK2}aX*$My_uU%b0{ z`tHzc)EpM4l;*Xx;8?!81TmuNaBi0NyivArw?n*55`WU+f_jWdN>=#Q{m9ll)i(z9 z&1%16ck`Itq35W+uAOgA!?!!yrxVOU;(tgan@E{B zDOC<;UtWPV{F6oKl_wVzbh4$98-?FWkPB4 zTEC>?E`QAm|9CeLuzcBU*}0m6Xb^Y-wev?LXHarV^!7g(hdDZCCkZ{$;|?{h9H8#O zr)1{wkFL;sqgn(@1%#c12l%-z0d&#Xgl|bZq*+9_KZwTm{H47++WbK@w2%$-tvA2I zxA)q=i6#-eG(eSXM-7U)r0WZt=3Bj&?k)uzKA|1W<&Al33uMkPxp3>D^;aNtDlF7= z$?_>OMBF-T!^^x)v)aa{!=_ndW7A>NthKS}U;!^ZZqs!z=vAInM?X)TZ;|GjF=3dV zP0va52w|W-hrgr}#`!BG^rHL%@A^0a$1!iKB&U~hU`meYv5G7U@pt6@Bk-~-smr9Q zvy_-MlT_2@(TyWMx<7+10x$7P=%aH9%dlQLb%{wGbL6bq^?7?hpAt$*HhQ*9%sx>X6qbdW$ zJ0Gx1pN22oH5wtSQ_UnmTEiamFc{74UkKfVN?PDBhjYZ#^b~#h8t(Ro4KbhDi8o*K z6`I2~4fu^tSUhn!DdX}=VTF)RmIwgNP?hsQ@8s%Cf7TdK#>c-nzvI7G>wEDUQ^>FT zlB^A~|5byFY&$sNddWhSa15vZW7iO>2il(Co1l+ckh>AO!dlp0k|BahoRX5HgkIhW zyk^JfXt%0qbIa+bn$p^7JM8t}3s(j|IZzmmtC7>iz9+8?x-2|=Rt33N^hmF+2j`wG zb=N_INVGt0K&Q_!h0ZAW#oN@-vO8a4fAZ1@MEHsG>iP;HKU&X%09v2gDg3>Zx1BSH z{0q~v)0`^7=_D0RC&`UoNE*Hg;t+U-s_@$kQ2Alt^tE3S97>VkHVBkp(kds{`vPCv zii9q&U=oXNu)M1FYAO)Ly>m1tXpifxkL*GgYDg?&grhF?{bxFKC}AW>y}V3<%+Q@QKZM=3$PpM7Y6BTQu?Z(`ATuxZ7(l9%afojx{>z8VNkfd|B8!G zE}+e7%jTX`>>^s8neBzR6O8_@w^T&1_tID0roM??i02A^HN9NU^L@mVXal>LVFVQH{667O z>4ezeZGzw!l8wwRW@QF)qP72AjT0g;Yg{v0~Vi1VzHrqB!)IPfR*s)G3kIFtRhKhisHuKQwNr-qYDp<$S~Iz;G* zsApbRIwtxSV10)dx-K%Dc<|YsrFw_yiqrIA*GVTk5inf>Og2o0adh<^OveJhTh~)5 z)`eSYogsiTOI_;cC3+S(d#hPrCy7#_seL1`12Zaf=8$ zu<}UPKD|EPqKB3}CE88i9VV-cKdGue9X{O^CKV~TcJh^D z{uv!tY^C;x(&1#oVH4bQxn$s0rD%M-FRi{}++5eSgwnA-)_$Y!w_kyI8NB1K4%LlP z1V_5-BTF}cj3)O3?5n!tnmGkK@5!3H*j0FsSqlNa)12vu0E0>$KT|t@MgzvrE~Pub zt87z2qAF=BAW|8p1xEwL3CCMnXJrss5Mk1(PIo^#$Z|md3uSpC$H714-c~@8tV&+D zl7>t*bwf;=k7{s8F{>;KIaF7YI{?)<%oCcHKosjQGJ?ZEbLB_U(2eNQbj!MY_fr}# zm4Sq`zRIbqD9K6{c^RT!6d4A7h>ARKL#yXcLI6_<1svbk3AX`P625)v`pp#W*1i}< z@z)7@zesm~U`iDl&AX~OVK~&V&M0>472Q-0N6C~{Fi1X`v_u~U#z%t?Tv)!NSc<{) zFuWl^KV8mMSvGM>u3FB8seGD@{^LkugEAnL__JiNV*@9^_Cp?c+x7~+vw*W`^h&8Z zx;A~!wi`>eSg7{ZsM-E7VTKdJqesF#yu z)c*zP$HDK=Q#hTJFnl67jrc0mg+Q3@!_;TrN?QN!qnfbRfnM%Zff;k;^5xGP9k@19 zSNP3om}y5fjTEe=BXi{0poW4*v3bnP+KbgdE7uoz$CXSjm}KRUO9>S>U$)e9h{~i7~x+b;$rJ) zoGGL7@MzvY*MTLd*n|@k3tzwB9;(G0j>;+fl`@WOo?xa{{{-xyS{a+Rv?poL^*&D% z{Y%Ma>#3%dFe*J3F*_my6qCjN`q$-o^Za?0!rbwu;pfqJS2pJyss$;B@(~P1+cac1 zM5rF&9bOwUfDEH~2#;XCI-$BYT8up4o-hjcHNsx#MA=*U6pbwz`cDV{yRM74GJwQT z=@6p5-%^NTG+i*kuD@ofAsxa!yz8$C3=615EB;gh8y?XWhzW7?HFVUJNlLj)x&#W( z2bUWaUbVax>~?@xi@YXkRmGZr0$Nx-^r;9ZrdufVyffes1?VhH;p zao~j7h2kPQktmkw=dU4yT+IDj^6d*CiMDaU`6onXfh44hmYM}ew86(tz}Ex%D7%?U z9Oxp_-emt{Le$0l*#j49ByCz#u9U47v-t%_(#ih+#QsA2%Lz2$w_91R{Dm6v9j#Xz zY|?qNZx^#~TW~myISLS>FC}K!;2A+2sG|PSu>e2UyNRS76rMZD(Tg}x4Ic=sbE&fe zBC;xr`k&#&g5e4zaHJt31r;bIR2UU(oUOq~{ed8o=?{SEj4 zfmeo>#z(Sl+bW+zdq7K|x}yRV_kKV}7kjq0%cURC)~=kd2HyKXPK0-%Ki> z_Um-;II44M^}jU)m*PG}x14S&GO7g2x$Ujev z$}B13b$4^e`6(xx#bTJmKadppq51gm^is(4ABg9s-?L+Yt@%WY23R*^Xsi8wW^U`% zs-+K9WI&?jC;Nlgb)6>O`HIHLWR$r32(CguG%Kru=!nxZ7JXx1bnB>R0oYUwHm=Pp zSs(yyHqD{&j_(Q2nfRlipZ1ao^g^Bdc$I&|5T0W(47lpz>l~c7vj;87CVobv%o>ud zW4(;C*p7RUp@^MYg1eWu)K1i2Oy^l|bLoz$GwX$n#mzydhmN74Ei?hrD?QH0F6eW3 zCOJK~%hpK?#;@qms)P3%JGA_A5`xe0o%T!Caj$#s4JldBO#Gl9ObSnQ)zH_MRLWIn4AdWwN z1IY7q5dF|{>PhFmgujM&{Y>Sr{SY@HO7p_teMYJImb})OR+ATAehgQoa`RBHR-e}x zTn%vR*7?124x@FiHl2M)Tj!5?%J;nh5neTHckj*%i#5=(sLpHk&UwPyJTuQPx&Vl~ z@P9goBoq~!YxCwyX`F04fD1b4J1EwLl4pd}yeKa$dv2AR@5pPU&uGcxkUS$L&n=Q?xM-atd4@`!Qpr;ydF+y>Sn}8;PodxRDFa{?a#|kDYYa^1lsUBYjx<}o zI;fu?~naIM)B!i?RA;>kYDt;9CDj1>sQOxo8>us@upa9_3L6*YitfF#)#J9`d@jiMcz64@FrVJ>R$)y0qLyv z{x(XfjYX`D!ToIvt^Xj_T$_0;C|ZZ~H!{5bUAg%#2C`vEkj1RG)SnT7iSxbI5&gp$ zS^sOrdaE*ryo1H8j`|s*wM_IZ^jb&PyJYJq*|Vs=TCt8%JhdQzF>5)p*$?xUFJ2c7 zHPfkQWZ$lgHQPC!Ff-&~8vpP86U@^R2Uz&O$`Dh<<7q{luE< zUvWYXmo=GN(=4eQK!Ad43Iml5$X`;-cPf0nrLLKGVl`G_c^Wvl^QrP`)0S6>+Kk|Q zRc)1X$zWWl>R_`uAxYbPZK}F&`~KD1Vn!wXxEawB+Y)@(7}KV$JQl>#$9f0pj7E7& z?MtX1mF6J|dpEB3Cjcn0i?HwNsr$H(b1!|72Bdir1M+SB)``PH^G!-~F29$XDisQ2~Cwld2Vl^LghYJg6F(I;rE?s=8xPLk|q)E%)@rBD9tHB0T(8%p$o` zM>B%q&B*H#_QCUS4QymL0O zlnmA_!}9s!oXyF)?Av(D2fLF9qigI#gLz#}<0j#lW$D+#8GjaE_gq5w&=rGU6C$-U zL2C0_<>rMTwNi66qqTXBL~6syiQh7RonOd#X-W*M{@9|&L1Brq-USkfFbTl#W1z&| z=An$T%Al!@ptK;u=nSYHf<}wR1E8T^>q5mdQUP&ojd>g~5Z7a(XS4`XI$yFbO64SS zc#GFl?!^)YL8+BI6|!fd;u#+E+!OCkB#W4aj$G_RgC+nAuV@ryVv*> zD52~rQ9PwDeY@yQ&|lFQ1%U;1jalb-K~HsOb-lW;b)qNpBi*J$vd5x$a$}x6uV;eS zGamHZ>lx+slr4PR>$%nI83D@g^$hjW7BJZBv3os5UXPWCxMz^pQ{eUFdp!fao}7D| z?=8FcZ(fht>&fzZj9yPR9D9UA8(~Je8l)w=X`lj1n+>`Lz}0XuMruWCR{c8wI|@ov3VajL}@tI=KE#JpJx$Ie}SSK(TRm41tunCFQiDHWCYThSa zEc$c)y*ZY=Aq$BC|~zGZrFS-T(o2UQw<*v`)J2UaGdh%2T@DiYB0_IMSNY5 zySj+)^l|=sPf4IWVIl*Y{h+g6&uAh(b@-4*WObRO)ou1mptNDt<~px7L-LffR3VjW zpwt1W)ElvcSZZb}^#)2cveXrNMax4eM|{vb7Vz8} z@Z3WEoQZzQU=HCBPRq}jzXO*6-IB)?@Q}bxH#PBpPRk5<%mGhUz(X{yZX(K~^>F3=DX3e%<`*vS0s= z#y21#X*IG|N5cn`rPZ?W%i1*dp;*%DQy&cMLkYUiJ|qErY`y~e(Q)Cp-n9W}>aQhRtE;tq z=Th+LpGz6M4Y&fN5nc zRY;{8D3xIvQh{lsSZZb}^#)31n6^>LP{+=gB+r=NrYoKivS+mHamb#LAodun>=`P1 zhG3+wMd&B823yese#WuZH7g_Cdmn7{P@4EZr5$Q)Z)|R))#$20x|qSAP5&tU>-64q zZ-#o&-^2{M#o1s}g-02+PjgH_2eun+0SlCV-dMKbMuHrZ1s zdv20F1;A#YyX?t9D|M<~G&13sLdTU-?2xj@j?bOfdq7`^^>`QOK5eiIghuxUJI#t( z%?ZZt9M|F|ujw?{u6w|5J=zm%PCMG3B#Q<4G=OIS{l)JV!cvCp)zq-xs$16s{({xJ z1)Q8N$T+!xR^!!b<7vEmD5nebfOlEvN39@psJL@QPm*h?yRXODoL19bFsw7&>nyT$ zW$Etefdi{0OaP?e>X!6y=qj4RSrt9+&}tTU1wojj15|Z)^>F^tSzU*Pdc}JC=@&wO zp_?0Iitkp5Np3L0<;`czU|y?}ZEF}o=qzO;Ua%{xb4Jfk++eitdi6X=YB?OG>*n_O z=iS(09ebQOHT%2QU3d0y+__hJ-k9C(joiFotbb1I={Hsw-*}4rW_H-Qt^0$@(Djxt zG;7WN1$<{^PoVjSb&Wf^=xERO7@rk;Ojn+3QcnP`7O~_WY8iZ-4;VV!gY|FtPkiDx zF4Ugom;1oDwrRwY^`B@t-QTWrT{)d2dmK347Y%Uaq)$22G;LdMn?C;c>kfU#SKA6Z zAUw;$`<3gR?_B2`CsmLeDTDRL1;>JP3>ClVjy~qebzBaF&4(fX7}SG%A$|0YUf1i_ znGB~a_%tNY)zBw;AP&vpqv|fHMeS@pQPUcK^YZ%dlL^IXvkc4BO34Fpd)l5S@=Dbt zD^aI)eL$iTHSRlS6t)I^otFn)p1iBjJ~#~)0njC*Qs-k*5r=C-rSt*c*t9mC=vF6t z=KEV8yz@vFwdGVVsfTn+EXDF!57KoIUqUWdw(V&mes3;lYG2S4T1XQIu}p?_?$e5w zMi-h#pQ?Gs+i7z)JuS{9iCNiQO_(!0*niaTg{czL|MLByFXhWtH|-q_cbEo;_#H&9 z&dTS7N@rxHLp(1OAp(vA-nS~(q9A_0@AbGt^*$ib?Pc_vYfR3M{)~CrRs^Y}I%-ZE zVdz>{s%~+_N2et{Xy>HC$kMlo+4@u_NL^J#IJL6@k{8^Mg`T*rOrSe+` zJ?*eTR{Q|upuStv!n|YI1Js)z687s*5#`GB^r2iD@^~H|1eYTz9`Em)WV)fG+HrNE zP*Pef2*Wc<#$}_|Gk@HkYriXfd+xBApKovY8VSQ%#Q2}DyM9Qti1y|_98}<=>aPhP zNsAbr(dW8CqCLe1XPZ5cc)^#9Ep2KnlDXBEX{(-!2B|y2>+lLl^ON+096hbV84Ut+ z_fZI+LzjP#4w6lpWLC*}vp0_aLNa{jWXcro&w63c^(E?vzINTle+GAJMTO(wn6wiY z;;8R#-g>@?Je%PL1`dmR;n%gRm{fUyRdH3CWT3DimaqyvgP)S}h8q!#M+=c!=xu7# zQVR)jlnQl{VgTw(-rJx;`?UmEKu68*k|Ut$WcbzI8f^x6 zY(hpM?z4ALUU(qAAJ<5sr|AWE)28+CR4a-2Rby0Pt(1G->*OTS<#7HE=siTTd9!TZ z0`uYH|f@y-rw{l!*XJBYbs^XH2T$EFI5zm5y$ zSCF9;AL?F9h`CoN`ARZ5I$K3L zs^!mYKr9hdAe~di(kdjACAf8!e^{kds~H(wwWV}Mc*{1aMvzWw;LQd0X0{pwE}G?< z42jvFlnmo-5tXf0@2trbYmAOsqI4q+_=8!s&T2Zv+X}ubY%D|=4t%5MaA7b!1>XDd ziXUAw(A-n!-azNNu_XzEOUxO8lYPQ;A#LTR4UeP=1;bv%-N|=}m)9Y92FzR>HN^cM z9-JrESV(o0Mf~+o%kb9ZA|Rl*W*|~w{tY1j<_pjE%DxoMC=9M@(~LZ^sw6x}kTyC7 zlvHPzEHjmqLL~q>N?PvqsD^5G&Hd$7t?{(q?&9;O^#SIP^!t3SWWD{H#)R`9$Eqb8-kYo z1hoWPN9jWKzdu}ivb`HWRXxG(O$IfK1$C2!_nms$% zvkA{A(Gk($f#C6H(411qgkdwln`qeRCXytxEd>j+?I);1&C$KqE}hPm)rFRUyf6f( z-;^^WbH6hq^S_)K%?Qir+xr8A@yG}F%1q%|R;Q)h9;wrlMxPA`ctOJZhGc{!EgogF zUaqD~C0Tu=T&<_XN|{|dHdHcSNwiXAGb*4}C9BPHbp~acD>GBnhPf;g*@DUD47vIS zmMJG0SEFHxT%AcDigYX&od{*~0GWmQmDTxjwV9=&2Lu$kNYAnnP-HWDLkJ?PZWdj; zB!J82d{!}ar{Q7};0+hqCjz-_9+ZT+te%kUNyB$3fEV4!auLjBGeAKKVzT;nxtf8z zC^H4}qD+>J+|0>lxV<8|lMdT6;)O)fNV8KsiUpa!IIB%LmR z6*|?!mJGgh{vt)su@nR>4lIY@k;4DodSHm3To4Xg8?*-QI|hm%+=VAJ?|UX;IX(FQ z#Ue0s=qL5e%(0b0gq2oCLy>ekk5BWbq0t}@&8xckDgB9ejedIZ7>Y? zNeUyKzNsJg2jLYz*F6mPJ)HMIJjobtycmtbSz?BFWdmA0ARqPuzM?78j$A{0tlR1()f* z$B4m!dZt5inWfG=#m&nuqvFo6xoOp38fASWd;(`9+o`@`VVhffRtJ9-`lRg)(&H~< zbh4V;8d;jrYE!GOR_KS>hK_Q9{moaVwT|W*i=KMDZ$ay@Ve;AZwzT8wMk7oP3+JD} z=-w~;+=?nf>5Ui_RDCypW__=$4tKkgZgBlAMFU2@u?i4CW=jX(5z&(w3_MmgU31oC zVcSmbzr+q9P;!zZVtcOdIrNJ0SQ5XX4H^P;Jdm9I+=`XJDAY6WBIo!GzPl6qTbo`H z1`26gtL6r`1!L)4a7PfOV$*4h$f$BZ+DA<#_w%;?y1|1}$3{UF|Iu>G3WxJiWX3Q0 z#9x)6q&&UCK=y>&@Rox&N!hmN2=7&%@OFL$j&H$XDE5A&7MhNeLmK;h>cgvoSuyprqy&R|KJ7CsndO%y&QbuRi#q{e5uq8&Dcr>EKSBKMnA6f+&2=3~S?Qe0Rdg zcYke?jT9!%ybe}UFoVr^FnvVyIDYOM2>CF+_%l>7crL&Tpa*YNQVgGsLdj@D#`8k8 zu;k#lZHNK#GICCb(dWyjCo_fu4tp7g;V-@&id914o>U+#-n_RQN|PlTTx(un15h5Q>u(wb4Eq`gH?F^|V1qJG81%C>U;V zRuY+Bz4_KRs*S-aa^&$|M$If|@xx8KW>imp%lg6l7Y1M;#dMQ6v-y*%Lgy@+p8PQW zB;6Wj4Rjv(J(?GmCj0DUdlQm7-$}rxxqlp#AF90UJjZ{9X)n(&42xZ*E#9V9s1^K< zpbgVL=U2#xUuX+`z}PPT-WU!XZG?bkM?$<6of zXs|6?WLvgSaEx@E_@oGmK!_oCG>nM0{TGNXXrE(V3b%G!M>h&#n~k$|WUUV8C_LBo z1*zh5GSkaI`!Jd77%lL1(Dr71rZR&YrAS(Tp#dmVUjsiR+w(LmYjV!PX*QKgyxZ~~ zS5O~2nWl6s4A}_gU^`#VCCjLBM#-EliA&IkWX7>?DLtqMJNPwF4treRSbijPYgh?} zrbtfWO;}&Hj#5UJO>y*p&_TY1aZp=ph1`OA$>~P6WNUZ`=~4|^P8nkA68AB9gEJ^6 zOG4MSvyKdw WfZipmXVdkabfKobmcp5CqET?p^Il&mzWnJ$n5jaR$5`k&Sbk<*W ziNvgMFqo8ykGimF?fUoO%u_KNGd6?9ZG5T92Hm#G!v4PFusAncVzx>C86j9PCGD4x zTt_-e2p*Np*?B1;RhFcl|DI4paza`fh?(K5tGfJH%&{vGV`tp$O(2))=gNx-emBcHMF({E;9g*BE&mpkR2^u|V%Gr0rgEP8SN&6>$ z1WqbfcAz0C7qVZWct!|nrp8fP>G$T32?m*ney=0B!e<=Rz^DA@_Gx+K4KJF2?ws$6 z4u)x{$NF>wumoZQ03!Oe4mwoO{wE3K6;|{JCqeHwS8MA~L1YK<#6OUQnJ`cve%Fwc zWyC+Hh;K<*hVLI#upV)q2Iu|*1-{fl@RP(#tCVUh{^`H+qb=W;h-t!EI#h@RhX7R+ z$>!724+b{~Hh66HhI6G;KOQc98%jNwbhOW4{2m$|&aLr_edsq9C=UI1BU-XCKH;w| zHNq95zIp1waJmL#4vw>FW9}z3<)+K$BAj$GVavA68t`GeFu^uu06g~CrqFppFa@0( zCI=TcH#SI9QjV14hb~FlSb6Rd$JAI7{L#|h&My*v({2`|3NQ%GY5-uuY4zuXba~-- z$z0T?b?tUr|2xTek$1n1tXQJ&_0`w3oEG>lNPeKL&P1x#_|w_qc)qJc%qPG=0j$30OBSxKjW=F{I%CS0JM;7v|K<~+WzV=9$@Wfs zHrX#7j2e~GSMdp22YbeS8i8JMOS{saOx>n_I@QHpRZfQAUNvvInlbzb7%M`15Q>Hp ze1v3WICuYk!Sh<@Tv8Mlvf)9(Db6OJ5P!hC(=>B7NUuo8brIaNR&bh)?&s6je=p7@ z4)kt~6Rh&{10;3&VN^L1GND}s^@R0E4Dp2cMBeC47$TXN1sSW1mIFRUxAc_Y@@XUl ze#%^0ytYc6t&&nwBAJQsKT59xEt$HH0W2^7hbA}r$8tGMvyk2S7Evl@R%to90t_A{0*3FPv;3l-89HvR!9r@2I3LOQ2&IB1k!T1^h)W zqHHA>ZUOGnx9mh(==4(t+ z@buN2gmG#0l@9ZBCr&+b2bI&<9Ys+i3$|v9gyIb?9L>r>wRhxG*QeTa|FWcOYb-sDp&X#PkwCZd=M!1VQ z$>uQGY$d3?;W79R5fTSaBch*k+7D&(pXGEE;gm0kWRp6Wzs=^L6(EvjP?C$CSxWNc z$WX)wwK?#)*yfl_IsW|Hlw{NRUl4x~mb8#1o}uwRwHmeBY{cKqf6?$-#>{HyUaiFJ z16^L#w~)eE;f&yNt#YSE5#vA~!|XlzL7T7E%DymhR3D{-tx8{W{WtFD#9l|6`oH3(q#ta=gZ+l>_u3mJ}3-&8OL(SAq|19^>@TSvfoRsK-YuTaJHi} z4$UDu;_ukj*e21@1`?GEHX>tw$mMWYr5B9?0uYsnL{Ba88VsIML{ZZRGC zNCPH_ijDNjJ$gwsmR9c8(6zh>Yg(v0Q(XoupuL{{{33=bK} z{S1#DgzXk~sD#Omlo`y&ey5u7#cOaVI&?5ON56CCS{V069kb7=Xj%4MMhy}_1MYE= z2wh_8$k8;s$Q^z=M`_(j1I0rXHmQJTI6ubm48=c02|6kIRd0370HoS~(v(AAN6Jp3 zCu$H8%lW}q6O7Kq@U?f2`&ZeDXYE85ji}#c_i1K$M!H;!%-PJVV-0q8&A!=}$JmX` zjM+NTr)|~MB>|#y=GWT`!^XrT#$KmVncoq?n70tiHUjIi&t zC$tTtP9^s~0e{dA+-H#!C_PEOoQI@{?g!dij1h@PFP?@>ZXw?jQb&|q6l_Fp}NU`2F-s)qmx5Z92EG@qx zGa@nJU*5E59li`z7_!`9xZBtjp>W#jw&(k(0l0vgk-H4dNz<{AoA1?Gjbdf;#Olr^ z3!5_{gHA(yx}56F{ue~2`{IXj*@v}tNm%dVtcp9jdhy7)&pdfpDsY!g#ffL)_a(QiAhDYqm0=t2?HrRd3%;rO8F$t_h^wk)^?OFgC7rSB2Pm3^h8+c#a)?O&(Q?m0!^llqVh zr|dsfRv97`3CFyzHo$i)UmF}1xs@ba<*dy)S&>gm#8h)u%6Bj)C{hJf?;FxE0!t3}_f=$Em(2f>>(?~M)l+BW9d;3RyoSPc!EE#q)KtTiVt zD;ZZ=(U~CO|LO*1Na-S@uF1>LFgWuK4W$?<=A&1D|7Zh+ZlSUM5IddadoBTq{6@DU zk1&=6He4<&(Mva~sjX>Thgk!+3vwJ>Ii%hf~lt0^#z= zi_bCDPGTK1U1#fo3%5kZX6iltqH>>~nmlD}->`h6&BC-D+JK6v{X-1pi+@MHyYzF` zn?ivvyE`_>9UJ@|8-#SK)@JWR3jwXL+>raLZOT@<;aO$K2(M8NPETG1c17}&!o+KY z#|c5nw`IwB`h;E5qm%&2ZOMh|BO2wJWt+XgCiz+<$fGtpE~2#A0yf(n93sd%93vc# zREOgxha=75Pha4$Ir`fiDK^Id`;@-`I#qBt!Q-;w;BMc6cV*f+kAJVMQwE2ByfB+G zEO4|Mcn68Mfn%|6!XN2FE6Y1(A=&xqC7g3sG;DA<#w))QDk|4Il-r#v>X0}Gc`Pk@ z$x)ylhdQ_6`8M@A5X5t_`W$K2d-5d5WV`Ka)gyjNBa2YGR-eXd`_5|n9szr?H?TQ0 zHrsUDlzRb{Dwly1G%i|U7~wSRl+9*SzXTpt=57Tua{l>~PnfJ7mlszT0WKHJ2v96Yllzy&q^Cv->z^o2*j_{v8qXPMy^kE*woaTBCAr1xcqu zKdK7RF}Us0!6yV0y$OHZkT-0-=$v4k{j_y9aax3$&AYUIq_UH5$`qBoy#2nMVUK4g zRob+iV_3h;OY1#scHX;QQ^qDTbJ^_SB{s*yr{HXapZyA8j36nSrWMU^``|d$CuSnz zcIb1l${=(?rNya656yqfnoMVQ*2yu|gk>IhJVjqX2%WKevZTqZ5P zgc6O>^H_d@m}0gj|1^@0gcpfDxESJ?$^rjWGv&rx2gj+nQml%eES5h3UD7Hl=q5|I zDX~s(i#4Y92CMQZ^LLaatN>~pMFPai*{ZXsrS-RUEm;^eMio4H44 zOERfSJv?9~fPxhtZApEwFsKhoBB}X8Y`E*U+Y@nJF|SCy6?!aq$57))a;;+m^JttY zzTlB40x!ehzoYU&Ue6`wv+rh`T>So%yeVfe&)1lbTqa*T zR*CkI=9xCi039{cy!#f!OHpdI@}}}e$Sk`#ZLm5wp}zi!x<8e~XRR;JoQeVb?qJhM z6<9U_V}IdD4GPO6PqjJ!BD|Z;$1Vh3*B7=}lOAs#)za}%H2)Q|_BSpKc%RfV9q&c4 z&+-`1!JwA|mFO2ZW;~veZ!pi)+q7Zx%?UQ#d8ad!SLtjzwp^!^1{c$9Ik)PMcS4%O ztPD)~4Wh~R1@O!K78kU(>MVz&wGdRuKX|;p{4{p>;mVtjP|o&C=FOK8a-g#E;Padg zm&f-1>Soq_AjLcrGH%%XTMCy**=)bvZrqo{4>p;-m$JiV+aq5GEzlfawNOlEx*`>w?_LnYEso)^rBq#gsM z?9{Bo=b9&74$f>?95$W_Y0tctp0GK1vIWNYQqCQll{D4a} z`>W2@nKth}x!1HO)Om7In z*f{@wX?{h~*;-gX&%b}aLVuFri&u%4$-?xS2&02&!hq+!iSKB!na<8C2%~Gh!bTRjs&8cXcif)FYo*b zuqyKpV=;f>l6l_cj!q0Wq9?Ccy-zvqLs|&3%AI~xCP!cU9J0{(z%&wecrn&v^Jd*a zFJvCk7xkZQOyu#n(F_0GXh!x(WC&@oh2P;BiMTFMLMZlP{?{o#)MqHN?hCa@vv-ZW-eq^7_wK;d;~3V!O_`{R7;Di=Eac)5n# z!^QVE2y>`%1RrY&ApS;N%ZtKXCBb(kFhYMc)Bd7q{Gle(ygRn_!l^)y)u;3OXxZ9E zIIK?+)DFikE^RW@^zRdYMg`wTgJPSfF)&1ris+0)m=GfjzVnWOASic83eQLB$k-k_ z;yrL{jJ|w$K1lDheIND_-vxjXDgXt(7njx?eZtc(oWL}6L4#bnNJRr3;(bRW8nF#S z;DY#YPkLm2I$8X1!y~7n*gOFS?E7%-Op0!3&_pqsfhL11Yn*>hr%`$JJ+M_N2fY&( zcv#KZmGCm=DzK=z6uz5+H5noEa=%eSeCg`gKs&5_|A_T_uaEKC=Hioilm?teWP9P3 zt&$-suFjvL@aIM&BhRL-jjap)F;qljb!GNIZ1Y{CTvjCnl9f$2zk)rECd87>LZCiP ztp`Gh`7t0HzvOb@M;)gX*~c1S4T%JNv0TuZQ={!hDd}d*ZNFUAQ)3?x`I6=&pi%up-q*EA9&UEs6= zhG{x)PKdU~$39;2hKBSxnZOt*w%F$c52Ui3AVV|A^_z9&ZXGot#l{Vu-e6T6Dp&dQ ze(;6{69W>OsU@r0Fcc46Jif=O$wl-9%}ra9SG7q+xl++h$fNGz-nodVBVTr9XP@6< zO&7<8QggljPrO-;EPl7oRS`VN7?j9HnIC)oA9}|g`HDN|f6tqh{Hgz4ukt1PyxH+P z;mZ=+xYqt7v zgfDV~d7WmYH70vyIg+?oH0?M?f}&QkmFW7U?N?FIKGH>0 zhv6X_lVhNhf2y&ag#l$J)gnwMVskf~xPdMU1Dlvd;uZcPZ5O9Etnz2pdv~+Kq*#w= z10nPXj~;RG=#eDqk($^SLiS027j$ffdOyd~y6;oU~O zOvt7r|EP7@TIV11pf7i$~rS1Z4d<<0T(Rgdshi>y_T^HopqRZkMgMQ9o3MrN^BjO9f_80cn4fvo>qO06Y)i`eR9)N^C?Tk#7Y zbFGrNJ8ifF?cMJlVoRssZnQWJH{CVZ0u3;w7#~Y{1p<5B}%-U?9gGlvD z89O#Kx3L{hF_ljEGH5C-Be}#qW$6vl!Rec5gbB4u2X<@1FF)M*c9RLqYJ%`FA%Tcf zg}iAjVlMUK#@9YTS5Pu|;^U6*){J${NWFGKzKGxTLn&M|rA>GSSr zGNwJbiOl2>je`$g!Tup3V{;?oGaY|tT<(-m3eRa>HWSb3N~w06xh!My{)w9#8}0y( zch%aMtkFNKCM{lbU)ww9z3*I{ICbkp+xa;=d)v)rT*{1DF1u3g-8z5OT2YZIgr(G4 zF;i=9iF3U|f$T?)%dpN%#CC>z-`fdW(p1-IQ*~+DjHikgj>?#4w;=-l&De(7I#aCk zXu4TDZ=A#1%)b~oo}WZ5;(-_}gC}Xm&EzMs6D|AE7MInOk-aEmaK_pV`}uiXyV0vy zK1*gA@PQ8%zHzeJ)UH|lOm$Xr8ozM&<7i@N60>l}&!I`0g}aMFli2D>#5<;q!cQ$C zB&E$1mHP175y2qi-%7~ZX*%M=ddp&UY&AIDi~$$H*y9rRHoGh)dz>+c?oz#@h&T7O zhc9}H=48j&!xxmK5RHN9orl^J>~V2ooPm#vzoV?~(dszr4`DVD33me+KjS#bG?YtQ z&G}ZjTjS^4tZCeqZk{_m0KmS!BZJg^#4O3!TJUM4bQyK0d z!DSsE4BS>`F8rC-GrowH(dbX$U zvk>t@h_-8Zvz>N`!)@l7HhUJ}a7n`|Y-T%e8k)89*1I()hnR8#;neICogL(TRV-x zfGuSflA2aCE~mPbonhY(t1t}r8FLrSn3;jSw|y4J&m!)q#QmtnoxP>P;#fEBAT-fQ zIq!2Y5FNJ|Gum63<0ZZ>-$@4+~yD4 z^}psJx6_MG|0Pc{&$$R+Mt>CEUkadhP0sL8QkImI-JI4tasAqf=cRtSG{o4X&Q7Cu zs>&U0erXWz|7&wd$30kkYxIckZ_wet`=JX*e}M)-uB}5vq_}py5Fk8iC`{UTJ3pBk zm#9$3kjsaEFX`YF#S&gU zom_1$o6{eW`LC?ja0Bd^Ep*&iZJxQQtXc`-hw+P1yl0m*GzSd`tR1+mXl~K=eqO`& z@;gjVbu6sjzi`oh*OP-^9LpMRf|A*cF19I?18lc{u*1ji2dm1cXC;|`tP zL;(!KV=r-WoF1dNyv$yiV=uQ?7jLgthR+?e&LGf{H>|BT+a*)K=CQX`V;-Y<3zCRe zWnwdnESCAyZSzdy9|+kPANZ|JBiU$HnzNE|^k2LkkBXkNR*pW;7UK+iwdQ2AsU;Xr z?H@`t2aD7Nl_P}iHUd;jJlM-S`}e;YV=iB%VfqmlsqUw%R_WItZwRx5p>u7TT&B+b z-H2JzWQxs`kneAMK5R{h&6CJIu)b60$>x36CJEv4QaIHdO6~tzdT(V&hcHj}hUO77 zN~0l;{|#?oo(z=yf4#VeHH^lY{omGZgBvK#66ZX?t;Lxp)g&AzG@duo`oW;x<^4Yg zt#WfEIY(GVwD%NoaTqyXjGWietk!t3G6ytA6;#VZ(GdxTpQ24==1rgZSFaHQ1Pv^0 z!Mdv~P32)3;AtOlPhol7-2rBHm|eUVoX+0aPb}>R4+yX{m7z^Asw{0j)t$4|YA!1z z8Ng~btAd0lZ*1t#@ZKwBGN4-qKP%)*S=V4?>8)0l-mHunGxzheIJ?5nfMjv!mGQIf zDgz)`T>pRP#u$o;h}TQh!(S~7K-e@ur5F4ezNWo6_L!N%Up*`zU(z7)DFw}5J^ywI zBs$*rOAcw4a7s1c2X9J0-=_U*v)vtZBt){{mL%b^zk1@mDE7KHd(cL&K`q93eZMFg zsfN0yqZ_@t5%Dl9f^wp#TxR88vk|JfzkiFnLEa4CkSv#bKWQRhHR@U9TAs0X)P9Kh?FO-&v-TXZTW*77R65oQ z4cTN>g_AZLV4$^C=_rr-E6icvd7|!y`cP*O0YM}q)BK!14JMm7j%E#4lze`s;^=BF zL4sdb+F{Z>dkiNMAobv>u5HOtS4$t?p~hA&eBkW9Y~*PbK3$cm?6iVVv;1 z(e+$o!_(ryv#vev^1ZsT8=kJTnC&c#d#pNU?1n;~#Z@)L{fiSIZcn=QCBv?K8M~ps zon@^$cI<{5cvfrGX`zY6c~QnzH#j%S*)nN8w+>~-u4g++5DEKLsOJ$pQ1B7CV2#ZB z2D>wSi=c%ayX(oyNdsXo!x@_!_gh&_bK@QbI1p(AaEjWNj<~po{K5t*+;)0R*w;sr z(}i{PT6tS8aK^scT9nQgk-0n2;&obU(T%)vsE*4gJ_1c z@ZgesHa8{-#yw{kmUp*dwc&Qd2t$oQN@kjGCXo@9bv2z_ZmM_NQ*hrQOWvlzJYgNp zoYisLOSferldy(fTZomcj@zAiU%wj?X~E}G>}k3*lDn0oS%Y#{00Q7iJ|;3?AS^sM zU6+Nhgvd^|HW#Dj1D6Z~H(2CWRPmp4lh5CdlCo6eOX}Bj=p>| z^zsjiGihqI!|cF9O$rg{6S}Z33f0qsK*xpjxm|mHlhdD}L!6g2qNeuhd73q_ z2M~S9*F#?q)6CK3H{%wnffFa{%3sjJ5Od~0XjKTjIBB$P5}o%^Jx$lwv)Hn~r=AC> zo}tXOdfM5{uU6-?oG5CCt8)ztRmw1^#Z-hv0+h8mg@2DFtIxj!IH9X*xn4k+XCemh zRcCHHoA=)8d{~i;-Up-aF_kI!9bcKvUj_FtfkVvTN#g9AAChzL4C-OiElG=8UWjN};yTKh7dEX{?25fd*@jbGlC>(tPd$j1;1A`iLioRf ztc8g-MQc`bZv(#)U063>RK`l>gV|Sc8>Y}?G4x!|e7VI))a@F4SerYpRY$fYYk&`6 zWY(;1*K-y?nYe#ZHtS`F+l%5*N#%eXJ3GE|_7Kjv+PJ^Yyo2YGLT{>iTiz-e_s0~GvlpSQoEgpkDq{v*eQw<8zf<6NS>z2a7`-~3(f9Xl3vt+F0CJ91a!gv2c`actR3 ztMJ*Dc`JVN^^gpTt<+JGi@Ulvtm1}GH_97U2^$C%C}vJyPDcpe>D<~U|01lTw07;2 zFR``QY#i)!dmQ&my7me84fO$tM~NOu*=eOsmJVjzZd5<@sSiPT65o!7)Lqz{n!PfD zJ)k=0zXsy*;7EiD`DNg=V(YnLVS^_Ii8NRmDe@^}B*8JJ^7cnGVaCe0@FiNw)V`esE|Q?Zv`&NWI?m|xV~0LxuYC#+mm zU>ci0uR&K}A{<*ub`%N-FWV8;I(hL(PtnMcKU*g+!3oynXRMQJ)ajJZ0ic{hehPl%+*XBqSdXwF z?H%Ul(6)NWbY;b>cD&+}roM|u@e@B>$ztiIWiH+O->vz7u4jM8DJ2KhFf^S$5_4l79E zgx8XhQH(W3nWI?KDl}03j*~;O(W+o%4O^6@Co-U)`I0Uyy%v&ow`x1XdqRqQC1uEJh1JwdbnfN3FZsFq zu~iBi_4ThLwxoH&O1M-}YOm)X7$y1)Pk1;l%OvvZJWU&gT8Sn~2DpG%J>j__#4?+= zCh}>ULdr(?fl)7IQaZ}%|E(O3KbSEZP0`}|kla^Uj1g!V@az@+?Y?+>krB`M!|kdN zUnRM(@J||BR`7yeh1Rg#_mq5ddoTFaJR5yU-hMhH55aZzMYKu6U*K#sB0ZsqxVN&JEgr#K5O1lpu^mOs1$$Jv&3^@xF%*U_spK^hBgv7J(1JKGLBX0X~QLhv|t9 zO>TWG_;R*vM0`tWkDV^%pTA6BN!X3H;#VFrG%(zn$mbP{yC(g@@r-LB;OYs*&Q zO-ip;(*0S)k~><_5t45szO~agxW6rq8dj^c1DUu}!fTYS5(EX{8uu;6V=>Nal(7RF zk|WUI9Bjz9ti>Y8RryV;L>u)G{sPiZ<(scWK8|*fz)3u^rB30Iio{aa#(A!?y~x{r z!_sDONNz-Dm>8txUJU(bP!;4h=V^lGAs$Eq$b`V6U8q%J9|!Lfex#0+lqCeOKKO~Q zB8<7Y{vYbEViMW(Q+dm8&hDt;J6ft~e?@rv;{1_onF1SsLQpr$Kar#7d%XX|b>BBA z-w&(b19wL&3ys*Hkzl!R5WMUFPxZLWtS3JxvEVtY z|LuByQjA85R9<=| zav-V%(E-ll5!UO|gr(iU$y=h-5O#&a9Rf9I;bRoV{o`{-?|pX(CK8JvZz*kk*p6 z7j}AKg~xNo+<2t6kc5a2n?h4FkeiE7hu>Io{Z3v^#0Qt;B1e6tz$rN`z1Q^g5GtV! zz2%>S)XaT(In5PvQSKM7<))f5$rQ6H?!FXKwnU}^Q_vmDs+chMf+y}mRsMw%T+UMI zxdfTKMLOksBkcR^^eL`aXSm%6%XcKu8>ofv;qW7SLM@W>$7n6q^iaaxlJ7If>;*LH zm5e8h@JhkDslxwGd%=@%p(>5*b)n>@SRMDYNMYX(DtM^$R3JaJNY)Bs_QFsCb;9^{ zUdTU4^4}8z1*^$a;*;h^23~`_s7a@vK`sQ5<=0)T6W;Y?<&!WdW|9L=mEpb=qs6*wGf(yh z47e3&6k-cRg{t*pi{uTXt&f~}=|n<%Jjg3Kn%2GH5&5Q-uMgoozsaI)Z2B|mK3DB` z2{2CJsGA~A;4pyUs>0HI(MCFe&TuY`I?_yow`er2agRRYK}0x(ZgHnF5ePlgn#mJ# z75xNO`4&@=8%$+_vhayjydlxeqW*$|taCajS4VGP9jS9(N4sxPy@;=r4) z8>`OF-YOrF@g)UU{2I9d)$-7~M};U!Lmnb&-H$>=T?pJu>5EW2dn6tlQY%eiq$0?1 zp`siNRPPkcI~Cp{%aNjCVh;z3oQ=L+al9UyQK-f9z9oRROqvk++Od5nJL7lZBzeZq z8Q$)0k94u>EmV5Q*U-VJ^M=yZ$?!=TYTzNVec(UFOrK`)L3Ku&ClJOIgb@ zX}rC+GB)1CEaph&5NjrB>J%QxV7`Kf)&ITz)TtXV+)gQCG8fN1jSsv$ygpPvf(C?# zS3ZE5wkL4Cur|`@I!#3|x=u|a?;=Saj?rac#3EABi3W|sz=}nM>G6&t;>&xW5pS%A2 zzmBprwKrqq%<>b(==0N(92lS>t+YHy_=(1r^2}Qpja427rvYt1tAQ;k;!pU5>L6!? z$giX(l?NhztWC~6;`G^tOd9=FtW_dsF!bdMGZ#f7tJL;fpYICFs+tvlM<|&e2O!ecM{k zAsLIzPf>G@u5Gm^OoueibBHLjFQ?43(xVrT#*6WH4XrX+ET05hP8ykg_1qGkolt3; z!ZpyE*yVX<@BT6YyjcI zmopB!!(AEs_b=k*bS{C$B5p$%X6> zy)q{r%x_Id*FUl12Cx^>Rw*}?fd96Y5=8*V@_E#}=TaC1EB17TB{?1Y5Od3~)&sxb zoUq@>xo*2{0rk{a`9P(8<%f59?+7BRU2ipx8>tbJo zBa&61mTgzCbt6-V^;8;L=3Pw3$0Xm(pT7u1#1R;do+{1bGEc9BZk^{5QothAQ{FQR zw%;3OZ#jM$Qn0-_&SASHJ{@ogHadg@*2^lnqVt*`Nv8!;d5X@F2jN}~4B4-}7rNd>tYD8sJrf)HzD( zW*t$@IR#WxOg1Ymw|ooYRgO*)wX?XDPsSTX?d*k~KHNpuoJPA!%nq{nt?sL-?xAJG z%-}qeXjw!+vA6Rx9q`+#V1(yZ;usufVp29E9%H>J6=MtZBRB2$&aHs1D5joEsVE<; zvBtk?K7hlLN=HKaGiX7;1X`p&5Lk1iScwq;oxW!!x&|I!iNpPB?_{&W5UOyfc|P~x z@HRAxr&n{TzH8PrsUbBm;afBp{RSEdY4qvxf_;l@>@8=`b2t^T+ipQc_=|XdMw<`o z(uY@gR)Ug_nd5CUukXr;(lJ;2l9nLo#Bi1()T|82I>~3CtBC6I#4_mDh*j5>)l~>j zuBl@R^m?ttGf1xMOwi2c5>D=I7wEtFkgO}Ye+_G}B2fmK14Cfj;TV`Fu+zM~N z9)eGpA^J2I?ARPb`zPK;& z|BdE}|C4UHJ@^h^Aq#z1MuB5E3U6!Dbd-*A2B zQNJfD<%Y_}6@pPgp`I&I%VG3b4?Oa}4WRVo|Jjybm(%zeD*v)v_+>c_#rmG1sKB}P z|1X?>Emy{LI)=I&SuR8fmbqSsLCC8ETU&>I~E93`*m(PI~X&k4E0L zKz?Jn@J6hS2h^AeT>Nwhd%X^2D#v8?h1g3?Qs>L`>uDus67Zg#l5+ydeCUG~g?0nw zZOesi1a}1ddi7;nmvfCO^q}5)OzY6TZw>daG*7W@{V=rk)Sf-y_!C=PgzSG)p)=!u(O=|ItOVu@~Z`Ap;W|uOv=$hDg;Q|n^8pf zuq$VAX`?E2pW!=QBD{`$JN24_9eZbZ`aq=+%d{ z9-S0FT0BZCYuYBPs>sGw`Lf-L1mf(#rO3x~JUWPoY98FbtY$(!buFo2U?0W%ddI98 z&NW-do~$=zcCV=Cv)Szukb4G||D#G}m-!mmn;B9ifVb~LxRJc;2J zL=K$qNtePp%dXQnJyVXWDN;D}rYIMA8rD9}%jEL?i(0>+$xB=w_95;(PG<=IV8YH; zk%eF37dMcwv-$QS`ebLZ8zZfRJ#2x+l8vXF&WBH7aTMA7;~tTnAQmaBRzkTs#UK_@ zyvT-Bab6Q0<0+Fp;qPV-XsJpW`j_Sc*EjdSkG@vOcYSr%NzCpM->?>Bju2U>o zgpw5`9C%t;Pdw@}*W-#n_?fE4FhXG=c^QRLKct7v`Pi*#cqUimuSf;qa>7<7x2}>lxd?ylU`HK zrjx_)vw8Do&mIpX7CI+ngjd}me!XjNA1+%qt#~W#Wp3JQ_3>iD>>UW$m~siVT)1`2rL2&3E=LXXGprhzUWN@$(V0Yxe>9C=?>;@#@ z&$%?2LwMbESej(u?#=G%GTN2mPsmen7#Nl_+IwM3jbJ53WV68Q9_JNZ5S{~zmG$FC zJZ9^&l3B~gzz$0F)W zlsw>woOD>%u2oes2d|I`53)MHh$>2*q{vs%k?xEMy4&OFlos$SKqubEsH{`WS)V!F zo#E+|xpH|{(+#{&tEK}fsM`5snA7&k6dlK77s#_ShbDc-u`n#lN*TZ((~uVUzd3LE z1AHl|d8tiB2%M+Pz13{`uqEeK7WB@1d^yDICb*Ql>Ri?;%GJZ4C=bW3EJ)0JP|Z_c zmkrA}W!{Nk-c>_Wa)U`^|1T=ND||%%BZJ7Y?>3o)dzNqZVBdjpf@GSovGhBT?nzPi zt(kL{!wj%qc$1x{Fucl4An)dqDv?*89c3w@JbT#eet7*4h zO>4QDHtuR#peOArEh?ZEL=dF zzAKtCe|OWei{+LMGAYe!%KXJ$$Y&?P#07k~E$ZfO;(Dcz_g`^GKGbAha&KcftGP3Y zq|BpvcZ(;qnRkna394`xAts!5Z;Lmd?i2PMRnD!1xs-ZBdzghKRHrag$@3ZIX}Mu~ zmzw2I*Rn{yT%lCS^D*UFz~#pB6kp4e+lhd=R8==+DKz$EnQ$!&ELw$pCC@vQ=TcnQ z_oZ6b&DUodBK$$gBrEvnbEm6$hF_m2TNtY3c^!H7Ey!(9v+$I5m_Sp`yv1Z#b?E`M&Ai=$1FS z{TtnamvSxnt<|9TV_3Fn@*3SwX_vf*AZY!EFZp7-Bgk&g32ps);y7`}o#Mo4(qV1s zZ6|c*w>3h&!T}RjCu~d|vE--uFJ?G{nvw8`1Pfw><@E7xBaUYUksb>Rn@4GC^rh3D z*Oso_gb0b_fkuocDVzV;RF^r7My&Ht z&-$BrzdM^Pml*$F+=1uF_KIPaoQu&e(-Hf2m)q(4&u??wxQnSgSrhWz-aXqb-|64hD_x0Ec*M5k^k#ARjS7k1cuBm)cE1$?mm1v3Y4D1-XZ zFL@K)Fj6W{0_=OcZ*j}TZvQQAp&$lZYiZP!jdN$~E0czEY|$-lX$X_i;u3RkDG`In zEqpjdd|}5*@4tdNuy0{KRWVFA3>FutBj8o)5SX$o_d{&9{x~#=&v#qg@=b2P#Vuq| z9if+_5ZD3@noQo!^Gsz@()eMSL);$riMsd^@w?+2_TuIZj|4?BW8+$78q)$!7ZYlDQM@%-8#42+wIr6 zg(v|64p3`3mum!#+Y^tK1?T?n!*@GS8>7)F9|MEb86RZ8z57E5?Mlx9<|&`1C*AVF zb?HUlihv0gX<4SpJ0sc$GfUp9?ALF}7h71c`A*>!wH$h%(TyWV&Zlgy*eC?dvg2aD z9wXjAs{5EI|4a0LA_^Z6mKgDR%VJHHE!!>}BLKeQ{i07ZWsHW4-@)&9@%uqY=QEnG zlJwTyBj2Jh7!%i7^3KTQL2Fb1sw(CJAThf57^l{zo}{H#;<7P{KEqBJr9) z1p*leUtRl-j~Vt1=PepvX+}^VxK-1y9z(0v!)mdkU*+6z(Chs_N}6S~%y-ALV{%4F@@!@A>a z_wC5~U-Asmf4eAHW5A{%?Z4$|F<>Ql^T{Oy%=rV(K{Zm2ChTJ%`A#OhJ$dM;hWJ+f z)$sy9e--u^lsq7h6a8aEAx(k(O83o3ds7}mu$itmyYujRP#z^JolLgr-$WaXb5lp? zW8;VDj*~g)v}=rKI=NM#Ryx&MW87i{eLswDi}Mc=i6b$ZZT;KhKxFe!I!&;cHNpOY zLDZ>ImL`&+Y4+Z%6z`=Hy8*$oEk~l;z<;Q8cXV44E=i+}W*|vZoXA8tjS>QkM!z#d zgHs|Y2ad`rTRC1BOcwq`y$J4gIJ%7_Yaon$WV)u~RCJ7=xNdh;2>E8oQNe#f5I&*I zk&{uW!myYms{y(@pdCj|v?_+4Y^?hw+`T6OY4LFk||qMUsq{xAz=IWB{x zrNgP&K>-mKz>-RcE<=t6C+xc~D^Gucq;QFz%*z!QrTXXhFjw-Kfc`dfr7_tsceUp zX`5pT4VI& zr3C|9qOg7{LwmHripU$$;y0q^&+v#M8SLOU z+zp4i59?G@@BB7E%r?+|`K!=Xo&>%bb%lIaWRu{Jx`ZzYOxJ<#-;oxTIe~Z^@r^(e z7%#IjHNM>#WFu!{tE93n-pvBW_pXpXQHI3)y-Rpcfw8sw4AMCHvWpn`&hBsU)=U1? z1>UPHL4iiZSUwCXrd=C&7JFYVe!l32vgu5=PjnwYih9h>uQ2U{=0J$)+5_&XkDQPC z_&(R2{wVbmfBFZ2XUJc;{QqzXuTb@1o`EhhkAc*THH-2bM4qAYCoca%m(UW+W4SI* zE4AZ&WXhG_bNTnV1V3d890Cr?zFhg-2aT^&X5nuHezkFTQ7}y@EwoUA zr>G@34RtoRm6J+Hb%uyq#E#KqXR-vp~!VGHIv&Qo+8>=4O_#z88oWsU; zc5y&;!(O9+stBe8nt?@AUQI$%MQ}hM$TUAY287+lQ~~dxVX;%G+0q=tyCup6AxDYD zMAYiHH2B504j($7C}RmSr*bsFx? zcX7%R*4L%Br!Q61l(%u?V5kHP)R&QEFE{0t*ME_=(zS3AjIg_5dg}jB?&qrgWAyA> zrp3hVkG#lq9zkafv#7#fjgWQ{nOuFfFqtOSdJ1lR&` ziDR$sd9LQQ1dtbDHz;pJ&FgIb_q+%{r8J2-WLI`zlF}xpo7rB;)z43~^ zq9@OG1f9pe;rIbi#Y>d?fWk3+z#NjCn@EZa)S!OsS=hkCXb6~mckwK_<|4oqdXvF1)(w%o3r zCed_#3+fT`?#tLEau^I9Og>-Uc)7MGMwzk}*wL8Z++TPj7 zGEttr%s+dX(2KHQ|JcY>NKy|BwKO|Pryj%o)nVPQYzm|)z-Dx-l?Oa$#Julde!LQe`| zG>*H*i?Q^@*X)~DedB1i49Y}cPJxe=|UgdSWkQ9(#U+VwcQei&fT4Dvm z!ucT@t1U^ISb7Rq*Lm1dk3E|>f8f*T*whjEe7iAmRI9##2V#*@5;Bk@7$4}%G+a_2 zowLD|IJUHOm~I5^p01})6YAV6Kflz!ZmBTo-{^adx-G$=G4c`i)WOuN`*Th^a%RR@ zZ%(%d06OK>OZ~!9VH5%IVn|IgP2A*?hA|C`1Gh7T#2xWzqe_ydjQU)up5~Z?v>2Eo z7=gl?B`Aln*FgWPn!H z(6u;ic2&}SqrV$?HZTM=K4e@>G_XKyi$Ide#;zMo%6#c}tmZ@2xToM#i4gcwsVf`m zamn^~DN;!WionJ6ab`q6BJw&$=`1F`OYN>z3 zQsEy|2J7)iq%D$fqA`zs%uRTET+UgFErFuX_?W1>+PGz&M>{pOB&p80O*?kIW?K@M zlFz4&D&S*ByD|9vP&1Ah@~F3AT^&LvR&G3Ngh7U zQ-{FNF@V?BCkEv=%f_XCW~tzh!PFt`Iaz-d=F2@W(OE`MQbFqRlx=Je#BE72nA_+W z8Vvp#>~Cs9zKint8vi#nLVXPOk4XDP{-Fl=X0u(SjZ13R&1Gqjq((>RYgIpIm7X8h zg!~5is~Z2uHNs*lf89EK1m8IMWR3qwjqn(KBOV>2(xMKS|{G^maa;Bz|*$jvp=pOg30_?v5l5(VzRA(l+ecrZgVABZKyQzIDAD|WSUK*>wOFh!h$e7;)0p)0Msnqrp%BhaT9ON-(1RH%B^Qj7SO!1C+ zh_z`Grbu6%6iw}hl2K`V{p6s|G8vZtTa4L8D0*?qiv34FA`pkX@#gn0cYGI>4)pzh z_D68y${Nb5D48x-`iX+05Goyou*uq!}tnI>x2xC@EiAw)ubcR1^A)%<*_scUD zj7a;DF%yY)XGTdJrIdDyOm-PEGQ>V&yIYy=THEx$)-Bi6u=&2veFki6f4|pjUNCd- zx#ymH?!D*Ud+xdC6f#|2D&;cy&g%AY0@0eCZZEh2)?*8pTY%tj54_UuiIUB=zxA}(e6@qNH*OOZYgya?T=|OH*R&Sx^uOv%Slcb zAJdTh7Hu7Y6J&%Yam9_7PO9m5ya_*!{G0s&0vQSMu()r-Rc@%6vnc z*?SZ56cL@A$kz{qH-C>N!9W~;+b5$N&)=oFGeDantre?ZC>PNo`j4}{hW4}q$3IJ7 zoY_LM67quT&~WCyc-)KPus$9OBIC)+j3)|^+hJ}n%>+00P-|^QxpoPaGfm(uMuqln z4*L{5nFcqWp?vDc^G|5%r0Pq!!~RX7tZ>p2Jk_PKMRR`7<}U9i!9AOOdp3(E>S9Pa zAJRSz{&q9wJjYe@F|{V8pkP{jzgH#p5ES$p+SVUj;57M&#LGQpVPY0^HE4io65Xt{ zc1DYvhz2Fz|MkVS%Q?KlMV;+$VaFeZ^9SxPFcr3AF0*ky@;10r)+671xs4Y^YBJ^w zTq;2wR#&&;`r0=-2P=paX%3Fe<&~85v$=dfOa19wrY+BM%K6E>%~-j)LuOXL)ijlk z@qN!hP>A`|mc#dN77`uH6+-IadpC!cDSY>CHr=ccW(osCzuXl3ZUJqZ?PP&TaO=F=S$yVgbc6^5r2N3L-e?}eNVD}|YM zK0YUZrF9?NB@T_<6dbonQvQym(%7+PXw^!aPiAA(*m%xnrGW{1Q5&1Xa35#0l6<%E zW2+G|%Nh$jn@aZ2x3HMk%U3papN#Id5Ir1g+H)u6-FE23u5ASVP8sRR7J(|_!#_8| zHm))F^+xe)%7lf26vXg)E5>O3vgIkZt6x?bnPNS*gyuao6M2a^-2^BAks8xKi`cNoFo zMlr~0uGAmQcKHf`fZm}Pt%#~kj}VtzpJ9FSCj#nJhJHCxe;4W(27-q-iiatyEz#vG zjMT2$nu?O9ECOY;?u*okhY!K_jbb~iumnM2T)st-GVtpqHI!v`D$EPWwybag{Th-Vl)z;yk()~t7V6M3C`-lDN9lM1<nOVVOm|XdZ zf~v4s!n$=m)s{~PI+g7=jN;D%eqA6kQs!VxQO0d1tSH5(|jCLUnJ=hMQ@lm@LtGG~n`$kr*{X<~$iK8->mZ;C`7 z=3V;)V5d2tk;WAv502X?jw1*-4LrKZ<(nv>K6p&0nwyz|AsrcBV+iJ?Od4K2^6yzE zs~Bp9X>0`V_ZyhKejMSwvO&DEf$$=TQL4+Q`A?F^Nz>AtM?~WjilK%RZJ%!d@2ucm z@Y4B9P#iYsx3uh&Zm7! zW`;38)%e$_e0!Ut>0)J7(ZJKH{GUW7{W)JC&b?--m*mVw)}CHeA;&Od9Pqb_0OUr2PGnsbujcopqdW)nQ7=$nn&MmU4jcpNk;sZ z_@yR}w`~xgCCJ5UA>nAM@Fkv%1;pKy;_~IY?v|#9{}@Sg@dauSHVxN10D)Ct#UqW6 zt-v`?P2;X%gXksTYAb5i8-H;#x{Q%f!GwqLZa}Mq8Gu%uAzfOV#$JB*X9toh1HYpAnT# za*Lkq41HINzQ%1F?xlnOu8kNeT&zW9xb9As6HjLb*qcD{pOotH8Qlg1#wj4Sreqik z$l5<;$g_;g$}B9f6~tE;Otcq}Nym(G{AurJZ7Su4&edXVL$j_1->+pYqd|s>jnW){ zhmeB^97fK_b!n`DZ&R8(!{bXc+i1s{Ipng@QP>^y*bv59uvx~~En}-KBt^4q2nW=c zAZ+eY?PnXC0V<3W{~xK%=<}XhRBjC(trd?_PFuFiH%k&%Gg1q!Y!4H9H3HjJOEU7c z_~7AM@i0L{@KTHs-%U~pvcW2}`Um3on^3j*0;@`qbqjv9zZ}8glj`%e(}@# zejkB-dZfOcwc^en*O&fZ>)Y|;`VK{KJi&0VP7Q9U6}K=n(#GdDV8QT^V?85IW%~!> zmeVdq6d59=<6s0w4QNhN)4Zy#6(6BY%&QXi{FcqthbhVB%fPgd=G7pdRU-xN=>Q5g zw^mZS8IICg(H_AuIydi^FwFSr+%)YSDSsEr3jvIkU{S4TBk)_*2l2u>A}(&15Tqg~ zQK!s!7Yzq|OkOI^>Yq>bkIbE1jP8qK4waGS&ZfxRnJ1w!ZQCc!9%)Z<7h5Z%F>Nq; zY)fP8OVttlt)uv75`CWsQ)|W42yrEJ{)XI`F5%4Gwg<$aoP_gN45!TWG%(OOOp^L3 zp0;_DYsJY_2*a!G^KAhb_L&LVm4wOECWkazN&DJjjd=%bu^8(?c(~8{{LpZ`0aX-vPONd5%HMV zn(|LdaKZAcm^0?Hku;|;zo~0^F)oUMC)5Bu%boZ}?vPktoCiM4xxcR$|4wBwn6CDD zVR!d_el#5X0n zrn_v!b#_^9`oB`SQZCM?cieC$^e>G|6Gb+*RpTAMIu{u$`t3Es_)E(Z4DW34Sm@Tp z@Zx&98=)6z1$O+#hd`O%uA}S8``!s3(%htm*?Jg%!~oSz8E{M>?xP>4;m08e>nF7% zY$R9$qjz$=aS>8}0^6Kl>x$v)$gt&RVru&BE(!Zcamp7{M$5;JfYA73 zAX0hhW?{!Hm3RZ_R*qy!ItwwO)~JF@Y=&zhzDINssP}rgaVQu4pXH!KSUS>2xdj`b zU?3qh4aza<=sw?Gc)2dz(18fRY!uuk#2WH9z+BcuKRe`jkur_GL2DuJkTsow_7C{Q zDU@be2_>5L49p5xS|X)o5l2V*1=p{)z1fL}GXh@LG@Cb&GK_GI+;t?|6v_4kK$BZk zFCV&nWm>F|8d|!NDM0C}Ce^fbB{W0e57Mn8?Z~)c!!nt9qJS$We6`LlkePYz!WO)h zYkb_S;>}CwF_!KYn3pb1_ywx&&x_E5QSdS{7B7)|p@9gbGxZ}1XySseL@W*>o#Nmi4f3VO~ zuoz8DzPWv-@i0-2ZAt1C@r~N_TY7tEYpQ+Yw)wkN*}t^TH~a3XW^yMx z53cmh7CI}LeGg1-J!~FU_x2S&miJ?ik1)v28cB)b@EDaO2L4tBEOwowab2!bcgzT5Um;&r|Do zPv-Jo60*B_xa{0s+n)PD+ULSX1k>;>OLgN-pud3g7ex6BXrQC>7^xVarE6=A-b;O$ zTVA=%d%0VQFsQHAwcq*ygy^4T)xLYANWV0Hj2cjiV;nTKrZ2-nj9ZzCSJRu^9ww`j z@|-vSEorvx^(yBh0})1Gze}6g2YuqNiDt35_Cbhex5}@&)c)%a*qUsx*TMnLOgBF( z#;@WYb?=)&n!P?1_i~#&$p|TtwEKX&U$O^Z!y6XV3Ua9T;qAI(=`0ig_4igyx2 zXUWWn>3igdq&&Kt#5=^S!x>q%8xYg&V4~d*c zQ{49QxD^+-d{e4)ik7=A={KYG9X!vrPIO zy}OHg^E7W}Tv-byi3TFPrRaD@arR{RO3tglh=)o8#|{}a1IE;S zyNlk;K%sV>++9j#8nXHNXfTTZ(K7rSyjM&?_42 zBCGYVP}{XC2a~UL;gP&9IhXd)!e`x6C^Gcxh@tTJeCu5epfTbT_%9+M4@j#_3X8 zQN&MZ61j7aXS`cf9KZ$Fhhw5H;Dzn()@S$q@h*Q1e~Nyb-;F<)n=e32{H{wLbLtDt z=bzD9JgC3C)<2g2uCcJLQD2swR4zJ`qt~cCa<%p|PKf#NMtHHN-Qs7ZYt#p5?~=bG z{7nqkC69jjcVoZthPz^-zDwHuja>EelpRTkDOQtzK70xxl<`DYd3o)3jRQct@1SxyEy-SL*RJs3D)-^CZodENu=AzNuHYQ|{5V_)LOPjq z=Kum9N5Ti@s5#EreE*Yp6q`}E{Fn(%=!>K3PwuYWYW;?T|Kw`mM()*o@hr+lAR?GMiB z=HVG${B;fZWt7EEvX9ZpjZweKG3t%E^?L7~CBV*}m=TiWj4{8WxHPKc+%^JAszmG_6a&5t9w{%Sb+uY7(9p5upJ3g<7A z_QzfP*gmg}tn+%p+tJ(1&N^qkFbN`uEuJ+k%Fbv(IQ>EtMo;al%+Bya84NfoD_lx$ zZj1Js01tFIpZ1==y5++8n!&%Fao2smW$+=24OOH3mY#xzevju5(H<{%Y9oe=L)5N+ zSGB#Nw->ASSApm8J_x=#Xc%<_I(rmb4ZAbmE0rwAbu@@hswuM1yQQBNeVORT*q{P) z6YYNA^2pb_{k{_RRY;qgXieJf-1v00l0QW>A`18>=h|`WFE}+DqASZzRpaMrC9i$* zTOp=YvEHqG^izn~?Nv2z%)LGN1`5+xt0P&0=-YkXD8KhIOq6<$>I0p-Gv3T4zCRgm z$=F`o+gq#gh1R*%n>M(7_Z-h1sBNr;%9qIvK*8{o%h;Pg;P(WCJ8W%e#?CoPKj9cl!3#pg+ z`WtaRLv`(2!D3FbYLX7T`YJ-gbc0i{-4&mF1T8|(_x}YvsBO!0w(+puKfh7a zy6eJ5&88Mhp(<$~0`)2a9hO41xiGTb6`v(ev?whxsK-*sZQ5-tjA)FM{o(V4n%1XC z8oG@Ik<|L$@U8MY=Wf9m738{g9ZI8`1KIUU!wAi2HC})y*i;=Iy>!k) z)kjO3Yu9avseVUZJxQs3O(wjuy*948h!jQp4aCSN!fr!X@TN{xwPsTFvd94e!-X>zs%=G@o;>NDX8{6O92I)AiMTcSSoHsV-xM(@UA`W`hyyq)n11P-k3`^byV3es4}=?*IhN5IHNHQh6B0di5F%Aall9}`yUJq zy^u7!`VCq^l&8b_pTdCIbblBT3LtR6g~6xs`@V2KbEyG-l*ic_Gos7Krq9uv*>~W| zKNl9}r#tmhCK8nILAL!P9mmlT5bSWVZNh%e^x64{-J8g@Sa9*Q?eI3gtB4wevrxv? z+^t22wt~gII6Jhu&!g$?7(n=fyr{Yd*~@6ZMoc!o|@Ll1|`$N#Ms|F;@VJs5EL z;v|)rP(fa5;PJ5!ZXJ)*F;9&&1I?B4!V>&9{a;8+;P88=m>$E+Cw{1hkU@iRv|2n$ z$ePX=zN|5h-sf(X>8?69FcC|2>#nwMlnquM{-{QGHB^Jw+iB{dgVn)<)nX?VhAJbq z=x;UB1#Hu4-EAXxFb63&q7)0QmuMLJEmiIJGObu!wb({52z#FKzco8<~9}>p)2W8q#vY}eWVry`HwYZ)@=?1Ly0G!$N$n1pDXpOcowIO&a zu4Bj)j*3XT%B6OxNL%Nu7M+w$?P>#GWuxtKI3slr-TNc>l4`MJ1itw{;a85p-&rl` zqb>$-uNLnh=*6&^9nnWEqJ*L?HO9MTHgeGOJtS>D)SPBYXKp{ zC$ucWhhz!gtr2`v8NR7M#W#iFTUH~u|G)6v6~Q+i?e=^1Ku7mGmiSm)g z3k+F)P1>?i(m+w4jB_oxv2Oth>ZaifgPNHy`d_DAsi-9QPDT6T5#C-|%f{pg4=%06 zSzWxe7El;yWHzFfNBHnBN)*#-z*>d>jW{SwjZ0^I2G+$IKrKL zs*1)lbg-V+6Nb*N#i-uy#U()S{k0OS(7fFSX;i;M2p&_n7_C16X4@>=1|w#;EQV|qPiraU~h3mQFojX z^*kkspFIM)1P_Q|jEK-f#I*NK3)iWr{vVA<^{Qf6!zqU^KNa1Wk^cBQ!<$ zh ze!`QBj3?SBIEg6;nAoWrTC*1YwkE=t)e;fl%O?3r74=m)rHFeOTd3|4wovsyVT;5Q zFo)Q(LZZPmjnM#^e;4Xu`hV;$f<gV4G&2Cbg)@`aP{J78Suc~4N=ywS#J zZus>15>0>(_5Rm&WH*C5<0OJFSuZ5`U%$b%kjyVg>;|607cr6YEKA2rbYWMU6gW^D zyQJ9kz0q4&58cr$HLbvGeo3?z=W&eKP)-!?%2V-fG#`(ZD~t-=QQJv`l0qe0GghqY z-OctXKU4w#EG!}|hO?FaiQ^ZxYW#1E5cY4%tp756U`fNyKN`JHke_X7Ep@15+CTlQeoP4^CW_;3~=wovp&6R*Ch8?w8M0iD#%R zl!9l($yAo?un>V%x~7s$bKWHgWXZpOPW%gfhkh_>w4aX?8Ig6hze?;U09t>dANldR z>iB`wIaL2qs^1!XwMu-IKpEB7s((r~%fp+wt0VSZWUhLc3Pi@2pV!p|G%h}=E}(bu zH*jtZH1&S|#=1ZhQXECs{Jfq4Okn_q5ddQZ;EroB{ChTnkofxlkMA}DZ~jsJ9X5}5 zOJCH@+7fx%hAuww<;+`8ZPOfL`>Do2pEa>7sK-5vxkPPYVZ~`Y)l+#P21F;p&tDRf zTzn#ZrM)DJf-LdKZ^X8MGcCC0g2NeehmFcsv$8Y&dshrSSQT7dC9b9fm$z=ejXeag zyKLhK3khRl5%C(vgV5LM3n*e|@wBM)f-Qr`@K)uA;idpRT4|qfjX{F7?Ye92hHD2m zxnzlTZp772sLRvXWs_I9^)~gSJM;7lyT|m%0B4H5mXG)k9Bz0Vldmm?VR0z&+P?Ug zv3=EDTSGr5U)!hk!H!IK?LIZeiSC+9mH?C@h?m= zFVuO{*LgeE`4^HeGT-uQ^THb>7}MtjV_v8SfPdi>z?c`(EY39h7aH-ucn{~hy&7NI zKN;R{h8Jb(#eTwWx;BiCB%6`;kHb$Y@njFa$BJUA$ZBPg4}Aj|w*reH{9TGIUj0rHF9`jVm}p_)dIWuSOpr#>(kq-vjljtvl-8)x$?~5ThxzbM`*57%tQz4O%Lfh3D1ZDaGQtXK~ zwNb5d8jb9xjJ>8#)fc`0F!G`K!(SPeS9`-iOac z8;c0F;g1iWWP8FM0$Qvt{Q_C!X$so1S14(}{4q5IYjNWhL~|2TTv?xvb%5t;d?nX4k24^Z^r zB_^Uvhd!Yv156&0Upd!&Ciibc4hon)mfp`86h&TYZ2_&3meOYmEFCwu9l>|U!0_4Z z0?UE59XFdk8@^9X8II3~_wCdcJw*k~hG*~>zUFrD%Bh^`o9FQs{fptn>K?T~kznyk zQF}yLZpNFf0%f1SoCblokqAe;-5$B_Hdhf5?~+e+F^70AIn58hd=dnli}ArFr&;Qk zPeuwhdyL&KdAuuk3d-Rlt|n~cP#TvGc#74jFntI*m4Atx4F`>+Fz+yHE5q$Q!^P@w ziaDRIi-||ri{s6nn$C`p5U&mwCqiG=eg@=Y@P*zV-WUG?X7}HQrCIAyPr@m^VK&b9 zM3P5689(QC_hQ1nKP*WK;KWP--%VG;Fv&G~U2uU>4e(lxQ9W5-t6%tXY)(oprmm5> zpJl7b6pVwRjE93};-{EF&3O#AXE+AMV|K$J-#XFG9NPM-XuvuS4SNf)H^vO^QCKjC zb7&4*7T%CvfLTp5xs!&1m`sRzqAd#((sPhKIlTarc#>ry$zQ*W78HvtDJP(}$Zp{B zG~PVDUq%ZGQUK82J51sd?P;@h@}|IW@#heOrZ>S^NW%g2KU^z;)hCB<#q&`VNZEux z##GgXT+X7N;#bpp#E=_Ckkev>l+dx^HEO?%@-4C{{}se>Y85psA9U%f~-d zC7x4ZYV;+9s1ZDniJF|yGfolz4CV4i8}dEO#RZu-3-@0e}+By5?V43MtQ zr_x%@N&^H3ex=MY=aS4Z`>PUXA9>Meq-g=o4DQYHL$4U}5x_LkmoAwOArI&Zj|l;7 zIRfrZPNF-#Qym%?Be<@Slq8+9mb)6ao>O%t2p_7F`WTt;qeDcRcwj@LFvy_;0UKQN zBet}Tufz3p2bIe~y!Uw(fB?8R+*HEKkyqF`L9VF&A!G}*7!@e|6Q}`&|H2>BOVHKm z>$iZI#p=P9wXaldGUBJUT!py8@ml{>PT!{&VoeJs&QgEbih@0I$0uPVi)GY3V5qo? zz5tb(MSLOumv@@>Ki?Hh5%7YY|Y0#e|Fet#rym4~Od!$XuIv1+Eg997O{ZLg1562eUdMX*Mo z2QB9um)??Vw#Jjt_Ap1=l98T3koE;s&5H8e%#8GcTy(sB!Q`s)8vBBzsuk<(%+R~4 zd>urid4bma`i+(ald2aa+80E28;*TpNHoiWDG+6r1$uA6I{yN|5HmqQC5&V(H0mkd zP&CO6WAqe#KyQpTa7K;Sh(wyONRh$|gldLe1|BP6atdFc!418?rmkDB3k1)s5znk) ztfQZYfyps9_1UOb#=J)jZR{yZ{PwNJ-karlWasCgP-Ho!T`a!ye{P{ zV5(`^Fe2{xQ7WJ@M<=BR^ycUrxY-)->_{o3nC>H)jb@{TXoh7$0&Aq!vVgi7JzF;$ z8_}ek`FgXO%I2V~nrcK@0EEhh1y%pE?0&cCr8O9S7#SFU$g-QLckQL)@Yk^x(g)*8 z#ACEsu=jl@(fE#bie0I9&Y5ga9M|Zymk=1Px$Z!i zhoRfP?s?~Yy2xjX`|sNllCGlq5~JdJ@!gCr2lpb0x%)NIe|_3*m$ zd77l%)&dL=j|E}qQaa`Kyrk;8)#kg&T*b~OoO)WbVs|g@ZnwMZ> z?Y!=#WVPkkN3pZbEXRzq&ulY0`v554FUb+i)pcQPLV9GTT4^7~_9U1;pgweso{(br zv;7IjxztI143q#~ZRug9hP4knBENj(5O~M%EVW)IRN* zACg>k`Wo|V@$`(9%87SAOmR7wxjp^PxDA(7z$3HC6z|Vo`V{sHv<#e7Cgq9Y)xd#` z_=83uV0H^QEB|XX_Ry8V3#-Kol#P4P)r-~QMf#4uzZ5om;T1{X@uJ>v%fomGoT>?! z&*QG+mX4K!*`_JO`&X_o)}1$E$*jYq?y!T;j+?=h$l8ac=o`4V2v2W~yrVKqdl)f7 z0#2Yx)})#`>~IDc%Ems!Z&aG*Vej`&CtL##lbYZ$wfGj%F?bbsjFn3|96iyF+kra& zE4thG<*<^DiDn1##@dt?mmuG?}W_*)Ca>%c2K0LIQ$V>vqhYJPpI9N1ma4 zxRc+$qs}~o#tn>_+%|#FL1>Wpx@kM~bu|&Y`{oZH+P?i_#`h0l!<;GG1=l}?T=O|f zYj}lMPUD(Crte7aznyFT2TRYov-z))L_E7}{`2+k8DBqy;Rf440MihIA0oKCaOv$+S300n{a(H=3MjH2omLVuK7Jy3u-rT&2LKS?XY~1ImR0M z6S?LWSyDnt^C1S8WoUj&0^<8;a?OKME)TOLR%WTOe+<|BQUoGjKT^J%&!5UQAC5rx zp8_=K2@M;RJa&ZiVyu0-fnF73T%m4LyPib=rSI)W^tii(mP2KlMDCDK&XHgsACDYt zWT9v|tM4bTqO9C!ddc#EWrPg%*e$WIpBtF_at4!Y?Eh#4{w00?2jPro86R7cz`IZ! z`OSfui{mQxJMA6N@~{xEoPWH`l)%+TY*P)}9_rg$4$UQunX+gw;gO-Xl@sUE_n*8o zJX}xcbppCbyqWUN76E5{vtE)5rZN=e1Yx@2z z@Y8GbM(L-eBg8R4&Skd0xa$K&<#v@OuF!AX8(uEEaLaK}R~ zuN-?(W8bp%?lFE|-emRjid~6vW8W(FkP-96kpGZS=mLxvy6}6~ZxwJ~*_6#Jpj^jS z0U2QQD{2h$986bdvezC=Hywl3xkQ4hKH95?SRZ{Ztfq-UX>T+?xgGpKw;{(9SX zd_3AVl)1R(dYSC39(j^q{EnnFd&%glR@XS)R% z*~~$_mni(IXm92g*YOk~1|q?`JG~grceCV86NSX5FuDJWu%KcFe%OoBIC*`I%^#iPtr6ZR=P?dS zin|nC@iSx2+cc@`PSt8Q<-7ba?rMCzuK+I!V;Udt!hhd|#>b&wW(E>|-{*mSf#-J9 zZdN=(Rk{2^=U?#r<3inG0r)9@h+AUj}(PPJ|_9*hdb=;1K-2H zo;`Hp`+ZL>z`|%%nGSxh`}4k=`TiN4`Gv>LxpJU0kLS!q@bY7}kVYxRoDvB^qO~b3 z{wkbN6Z4Mzo<)MGPo!sMj)Cv-)JB}UrmpIuJ&~(@I@7KO1;4bs@IRJZ;++wXM6Q>i=4cgZ_<&M|BSN=JSvoBSMK*~RCd#$UVNK!X%b>%@WS`?=U`VmGp$j4BZ8yy5{-WG*mWH6G0x73wmzM`&u)G# z3WhfDr-R=0zaAyV(I6e%Cn+uf0W7*2p>%}4(QAScHub)hPKNG4r8hhlN3Ii?ZOpM=GcZ?V(HC2#EO^5IbfXY z`LiTjEPXm#9||5sM0q$_?vW+!6~CgQg8^0o(f?S9yroaE=L&RI)K}FQ&aH;v#q~)! zUudxOn`g=G{l&{OY&@rZLYd_6kqu5bd~P*y=?oz&&Q=s;JZf%|Z!;Gd4ql91C`{tw zbGTZcMaJdS>Z_SxF!RxHkj<+GUlrPzeX6*QswPJQ+Ly1zF5LVH%2d^gtV|qjuAVVY ze|lSr0q%vyznfFv>pK2jX>j!lw<`&Ov~tm&VGp#Z%vLjLZ;uS3>Toxs=_R7+(VJ5; zn)q!u$JPqtxk))N_LRt2Mh8qR=Fj8_3dFKUdyD+5F%^Yqv^du8R?LbPCc^A4HZRLy zK5l+8I_HTki&Zl+j56-%>7=O$Lu(-Ih1f=wG=1L5AAV-Fz>6*Pb9$@JD2wKlIePtJ zzYNX}a=hNdIe|EL23{<9Q+Fiof*sm3vo9@F-RV!q;$7T$72QO-CGl5yO9Y0~ohY!k zsH&63WVu1+>S6w3`5ZLsAkx{)BmG-q==tZ{HXaw{7CbWMY)+& z)1t#^*3o)gQk#|26ZlYr)Ml(u2GeRcKQl!rSnt;1e)VkOh>N%+KcPt`G~mw(D3K$6 z{;}RBtaf3~a-7GYp!K;UsS9EwkwBYDP8g@}_-tf9L0jx$_{ycdw&@C!okTi?jywkd1;m2(=JLBcp-hLm3YXt}pSaR@jCzXze;JxK+ zWgkC|rJ4R5ZfeB=4W3}z8<8^$*2pMt?n9K&(B&|8qU{fd2ccx_J7TXi6X-zaP&HK@xmT^K5UU7=?o|g61?ETgN-0!3 z!8;}RY0|s!BCe!Tm^H8^!3FQp2gx!A7rel5B4A+(bmH*}g6f2YLY#f!R3zZz zm^y;@&Wcf60GI$(h_@4PTXt^XLD&~rN;q=~EqwTx^o$WCBlQ;nHXiC2s;9eeJN3P@Mh30AG%r|yjo6BSIYsl ze^=AMNqLtkic*Ft1@>aGBXs=}a~xwq1gOsWz1f0U2*SxxYR za`6KyfIhpG;Hl3>tjR)hsn0Ne{`#Xj{#-8p`M=i@iW;e70Co8N&Iq&KC`WILZ%`o& zH?T|%0qG>8l-DRtobuoZ!{qjbq%Uf_yX_Y2=M&qKgjA`k9x5r1^1VW0V;(D@+E!#_1JUlWA!O2jKwkxqpW00 zKC8~;?~m{E+hINBr12{5A+Szm=wjrYvG!@;Jr_-{W-pdLRgM90QYr2rAeekr%GtYg z8lwNh(Eqa>mT0aeoOuZ$I~b3POeK1iMyps)5c_XIf66ctD8|#Ov{q zxw@g8UT19}D44h$w2DLJ5lalR{Zm@3(UNZ&!nKa!QaU~x!BzgFeskhM1m)A%I0iZO zBm2LPN8s;8JEgb5CFSBh1P!?~FxtMQlu{%S@XTH^?-{Y}5sO*X^7ao170Dd&U}f`x za;RE5RM5nbzU5Y~c^@S-WZl*5tBfdNGPvg7()Wg}>CN6qVtoqN{47g+g|CPHq>M@t zhAHd;Tk{SEm%!JXu_Bp1GSJH(s9gRhQoJ8JktS9=YfAGItZYI>^A@RUQsqK%bJ+mv z87lNUDgTD%XW18MQIfdk7WTcR8G633As;sZrqzb}^8}Bg4;lKgqouE=Ee7TL(6fZ_ z|2_J@&7gb-{~cc$aGi?(mki3cB~Zt^hJ4(Gb&Z#am9!rK@GFM?6OqiY0gpx~Zx!Wf z8~@eAgJ;e6SHk!fj|=aqY}|_HeaM2}cjB#KNoAk!BS|;%O&QYtl5XSzegBDWgwBkG zl`gLeE4#5z&d&1i0tS;7c9zFu3|b>T;IeWvz9^ePr@|DOOOuKJ#?lGG_`;&)r4?(n z??zcPN^MP)bJ|R2N{U6J@@ukl0=*V5=Y{f3UjuN96p9m(&1>N ze_!D#U*jpS@{~W~DPQj?-w0Ad2UtCjvjgH*0@e;(&HbigMk>UsM6Brr=;V~l#2fwT z_a=q{+|cGSCdq~1qh;cwRIKT0MhK-w4RwK+$vMN>3OC=8Al48NzNLuO^i5Eu@LR`k zHKK~hx?f(#?5WDi#4-ku&{k4(8W^Q*MqzfA6|j!yP*S?GA{lxQm1)$kKmgF-@-lHb z6>MuXyk221Q5qTj0-pts49iPUw%tE6--i}U)K}5+xTs8AMCI1tRt3^te7QoXaIvy3 zFNfHrjebNft$VHxH=4SCW2chIO7e@mtT<_qon9FG95x1{68NY2#vWjYd zCPFRInhsj$S%beQ6MsRlFsDm6SW?Nn~B8m$kGEsMD37(+jJKc5XGd2F{TzW~}vM00)e$X$=wR?wGIO2-yuibg5=E5?~ktMd*hduMLwq?2~E!IMt$B-Mhu0U@F3 z7NMZ-iIqk3u(OauSA|h$u9Sfb(#s8drE()#K{);or-V0b>d&JRmRFtPtAs^Jz`o?B ziWwyqMn@Jww?BHl?}$$=kR&eeu>Md@gUftr>o3mJ+h@bX3Opf0D9+90(>vm9C6zFONnt z=}=T!3m(_r{e!+B*9e|Wi!1hA%h_IYp+M7`XE_#k0V+F2V1->6hv#O->rgW#3!2Lf$Q@LcR=I0E-%c91pZ|#buX90o`E`N zt1zCur)Tm`>?+4yS^2L}r}X=I_B&_vcYyu2jQ)PE{2ZTts3xbk#;tOtSei0*RtzVp z?C;94UVZ2j@NE5_<0?UQO|^d8oX=ZY+wh2V@i={J@Ak!8z_Yotum2+@ zvgax)|F2~de^!Q4B4x16J158NNtbx_>!wU0mF1#e#k+r&mpzgv5m&URJlQs$NX%{O zAQIv5(<}d3eG>QCzA#emR+Q7Z@K!4&SDP7S`qkfX@8ni63?)co7;I?e&PcmU&MPAQ z_Y2SzAvU*Z8N!uBkb_=B3ijqTP&PR0d>%IzZ1#j|IP1&*bDkRDf6N$Vq7WNAjx{2cEc-WZeB`NBNcuN zjK2f~eP?Yk93IW5{us%p?<`+Xw=aG_!iSFWj;oi2gyXWn!IlYcWFuf8UQoODL#l6` zFv1&LK$6?m-9op;AB_7`EFhyMzW{BI%_N(wm@^j$k4ZkV#{ibXNoUR%Rx=|-SCf)mvD_TO! z_VACFVb|`^UG<4&j;gDMjr0>9Ny4j8$xrt1*uCK7Y3$3y0_|3%rZCs|BYpnhf99d6 zv;jmvL$;>9SLe=ccqIlJ?#~GG4HudpC`0G9#E`=hZTSySwMl1-;=r~35!-}f8heOq z?N+t6q`HOiSuvxn7@=QWOfYcpph|Tcz1^u14-bsJ?EJTY@>#B`J3{N`VMwr4)2R;! zD?!ie5FlQ|1k4_o+TkPP<764DDML+_$Q$e4a29h{Sd(3G?OgaMj6SUxGBk ze@Qw#c;3uB6wpI*`^)D+c&BJL{J;VvpbQyqfL1KM2<|i)!)AFfq0ARoCZ^J`C>>XZ zz!xhJk>`%9J$%uavJOS){FSqTll6GVf5#h_8Q)4d!(}JMwc(o$4pHyeoxv>090gam1;uZi zhp#$2RG}+ZaF=eqnqnB~9~#{Mbawfhg5NrQpEyO1sDuLdV<&}9Fnx7pdZIjZ>hh?) zM-RoU`UeX5uwV4O?-VZ*qr@{#e+uXL{E8N_D1s6_lE3430s2z#Z%*GSr!=xMPB}5B zuvcg%8Y)p~;a(d5Hky!~%yJnE>f z7tSAggVc4(caj^!HlIK5g=`JC8LNcB)_uq)k{0$e9x0E|~ z{M*lS$oBA2RC0XOYF_V->*rx?aXq?ufcAVKp2iMKtq?^<0w$OW~W6-(I$ zFZO`X@%SKu%KJ{1mCmeav?^U%I4GuQKs0(-VPobRI`y6x>LSi?c{VJikWAMw?Zr<#D zNhf5#>i6>Pw-26eq=bG-5UlNsQ9OmG%ieaWW?~7Av!ZxMr_8PJsGe$rd!wC4x^;rs zKy|xdfjk5DWiAU5N)YYZEP0prxg*`En!Pp`A0xnJ3Z2m9eW`bE-Jw6!i5n!k`~AoC zApH+w%?PgeoDp0=C-t}Z?^PtQchibJLXTg@VNYZFJClFZ$6v030Yg_%KuAYpE~!Vk z@i|DggR1WK+1!p8~GVElOolVsLNAphH&}G}`Wy<=(Zj z&%2s@v1JOR+0B#-OYL47&F0bv5j_ZB#9vAD%a;49b5nJbY^AaG+!SQgw(!aeQ4KGX znGiMWk<@22hyt0a0imX+fGlkDz&%qF{e+%4d%Y<*|?i5nSchF)erV`TJ*(<3g z!-M#nB8Ty2{W#uq=78`Al<$9yYq&+{bo2e6a?X}N+1`$_DO6h1O^8T}u*g^GWG?(0 zaQT~}gm!25Z*94>nBY_YR+O#`wAFtb)iC!y-7N(3R@BmNzWzj%ZUKJP4@T*hEKT6y zPD=RqJb|tNGe=8{F+`XSsYSn8wM=1OKx57B-B}5b&-f-rN!h}-PDTBDQPtiXP?K^$ z*D!abuD%SohdABSWx)L!_AI!_6;>w(#EW*I#O#9ItfS_PS*9$0BpJDhf%d--`b%dD z6S|(i=zqS>oSTjs%)Ucp1dvr4mHuJ5(iVGUo>H6CdRi4EE5wVaM@7%mf>v6#l_?kHazjs*q}yaR>JZsgA=C z7#(Vp?TYfLaK;_56yfYsxuwNQ*u^LuFTuBd+Jw0~zs6Rq{rN#52?h$by=q(0Wb_QG zMin*%Z)4SgBw;lseO#c9X!$+S(&gPtEqfL1Oq{J82wQxI{Lfb>=HcX4Jp|9g***?a1 z#1lj~fuA17qBF}su*sBPPQ+D9kb2P+J;=U>rbz$WCk!GZ6gsj01Km1?!P_Lw7EACD zv)fVr9YYHba-tS~&gUz_j=Hz{Wnqjk?atn$*&}t%raFPhacHnO@lP}{{6V8Qi&Cj; z@-P_SL57&I;;QoE4;*KIJ4$#$sz`#)M13~p1Y7Aun=;;3sBiX1R5mvE2 zZE6uSt6;FsV$F3-Tku%4xFTM+Zw`(V8x=z5oQo8ss)r*S+ zV)`di!M2sBy*feHbz(dc+h048sSuR#00pWEZ$aC)jEcI%Jl$hLTGxp})+?r91g;AC^U{Q#F%rg?2@?J|w*wNNd>MujI@9d6&7H`bs!2w4 zJ@3ZcI`n&Rb3=bzSlB6zh(50p@`dEKOnJShTT8(@=K?<8%w1Yi?3~Ce4V=@|U8Gy7 z+l;}3aH|u$rXtJ(al}7BmlWcYRK)Myt`oYa(%{%izcDtwd%LHi%eqcz%%$;W40Mvh z{nJ38^L1XC&N=_W*H7h=|G+E%8ZMHr)ZIqNyQkW$#2x>Dop7%wT)NxpW4WU5?SfV} zNXrTJn(g)Ror?0Ql1G6x3~CV1bQEHx^c_``bljdeJO6`l(U*2zQ-`8^s@+OGj4u3?i9tT|xn zJfRcd7H?5yz;W<|ax+C1)+tDC{AjhlfeM?a=9){1vHjK3o(a!K6gF%${~$?@I2$v+ z6BIb{EH5Pj#z}RaQw$v5<}()2ROGk z#8A!3V9iQj4Q-snDryFl6lQOX>BcMjUX1PXrVl-|GPrtW|0RlgXUe`p*6~nk{PN1a z9aDzhTtQ0V;PDmW@f9d}tNP2zp;appY4L%TWHpX0ieugtPom5fFKgJ%_n!$0ja;#enLXTWq!sAx#cTE8{6 z@uj|4uJK5c8{QG&z0A58e@dnk8*W~S6Q9LuwOJRLt+yeiVb?fA`buNT9DK)z@QY~# z)UfNHhLn|LS})ZHqZ{ZMnp$zFu)@+O;sP&14_1yAXruix=Nnol`(r-p;${0{<2*4T zBQM_$zjc%KTX#S=K6+0_J~QbIRZTn+71s+JySyI=n~xwKxww|{U|{B&PrFGW!N@C( z^Og8I;t61s5A9!qu0C%SY$Wby2rrawzJhai!55>Anj>6@pG}xNz2=23!8=aGuH~^z8ZIK zTo!Hj>4DSX5A3jZ4SktV{P{Ig-WBn5Db56_TXp_u7Q#9q$-JQKLoc`DlKvdjZuSM` zDA+T0+1llVf%(NsZ_pnevKN1PrJru~&prYc9O)MB?UZk26L2Oq$-8okyHt?*yy4N4m^OVi9t1D&$*FA z=CI^#6`Xsm z*_vXv&Y)koI5n89G-b_i&dE00qd8A>l%1L9+M{{Te0=ATY3FY@^NZ$cRc8Lq3+$R&FliZ#+H4qh@@@2B4&I>gW1%Tum)k*TMY1unDJ?8v31z>T1unKW!Lry*e3$Q zaW3rYySFQ7?DMMYI`m={wXS7tHsY!Z2k|hEU1Aye6eAm*C?J**L_O|yBYl8LKBH9X z0)z8`(}s8e!OWoay&`i4`E-|CUf)zDjZYqZ%)!p$7boi-@U)(P}| z3}+t`WoAt_kKyfw_%8L+Vl!`L{d5QV3Eco-$MEHC_KdC-LJUr$e*O;h#J>F+d%vcu z|DRp4+}tD{uer2)IAKrd>gD_(P0HR1O>6x##|Qd4h26Pt7HwS%G^Rb_mfSvrLR$hq zGiBOFpt{Y^c#S?GIKYGmMr-~4bl<(gK_t7^KG+fP`|T4u$FO{nr$$1Qs{IRTK3DT) zEx8BhTKIBp{N+|>rR!fUrNUStsZXWspi$x2JV^}MX? zRNYC-M5sA@_Kf)U{mj`&0Wm34Mb9i!Ia6OC$@%{ndmFeW>%D*c+I5XF#)ZLvi7;)u zU@+7=GAz*S+-?$2YQfa00~OFsw7O4{$I9%)by+xp?sQf@WHqKUBRbhG7_Rw7**` z?xumhy?^p7@`YRGueU5s#z{bJ|6wA(#9fqcF+!n#=|ZQ&DNW;kxCfJYBAO>-WXxz_ z@$k$fw&A@n&&^3_S5BY}+xuslIJ}pp&wdiKtGqtgBb~y9=20I$)G@x=TYM6QsP%CK zdFZ&zW+Xo<))#1wr3}iHs-q=;r?ilGeVKD$i6+m7N1hL5-X^v%pGt*xw{;kBSMaM| zYmuz9H28>rAgCoRONh;-%jOIm3;4H#-3id%^POyL z6X#R+?OZm8Vx}*`*hj{v7RcT0G5%ad3y6R6@9oCR^kt1D%J^dyyn*7coc_G=Vin8= zB6kdQwf`8l&7e;43BB`^^`ixtqaO81$5yrcdPDavN9i~meMrfVe2KTkEYUp`C5^bl zmdF(Ci;BeWI2Xgm+G6h8UBA3&-=yoYX$PcX>eC-4I1b%7x<8@o*#zH#uC4>+oG$*WD4*xT26y6aaPy;|M6O;VTa?qL13`Oth>=keD!Sl4<16oDht06s#QL*HM4 zL)qVi@An1`EhVuMv2NGB7t;VyG#g5a9kwltqzb%P(-vABxoP4COAgJ8L&dLfrvP?fE|X?$WO>IrHvs3YSw zI;$v#gqan3ZVZODrh3+yRc2+gO;&$oj=ek&3Nbs5cfT}Ge2He_ZjD%4wNtG-d%ctG z*>N20i<>BY{n!Q4UsRNK2tGezc&)eALYeC+)9<^HEu(_JT-lk6)IdMk#L|3DsItIR zKx3%^@g#5f|1`?CTIiV3IIhaWcKpY@*8ISwE3kEal3E&!G=aLVZ!zQezf}wAP4gjv zWt%O0YUoW_&}TGO@hK36+Z5;yAJf-i*BRNXh&(r_q1(rxip~z;6oEZPW75A?aD6qn zp5ic?x8i|@Fnj1zjIAP^&5Vu4Lz6;`LXp;d*I#6^75O;|YK>ceZJuPKB^LTs;!pFu zHFrog<7xaKg?ogYt$c8Y^4QM{y00#1xw=67lE!!H+JYbcF|Xswf|e@_Lf>EZ*W?K4 zRNF7Wkt5T6alx@O^Uy%(r^^vq7kwSO152dWOsCD$ojXs=rFQPtWNl%4K@BL0T)cyl z%D-4p93>P?CU6$90;dsX62lgbz=fHq@)us1sh7XR2{Xx~hLETfW~Sf^KB3tP0dXjO zA)mAXYz?h6^HxFj_$wqvTR&VdSpc0!BaJXd0>9z#RwYumzrq;{IQhfVafZ8N=7}*w zU=}Vy9N`SqHve>eq->W}uW^@lG_`Rt*O+t+~O}8W7roGj7N!tBN zLY;QR`ORJRYtkVpt$Xjr)y<%Ak8V!bo5l8;7@r#q<{Q38rKScb1g!KN_4Idb?yuk6 z1+=aH=k%k`N-I5&KU%+LTh)_MOBYvF8+}hmQ{A{{mU?zCPN?^!Kjem+a!Gb0e$L%SElf48>gw?JY(bblClGa-Mg3DM%`+A z=bCLkjWP2sR`ns_V5&r>t5BM}xqqy(YEl2m(u7j?QFlLFN7Qdl?`lg}*EYp(ABA%G z^y1O6aj``^QzakV#2acx-Ab+Y!l?UFq}9cHc6jB|#@P$}0@f(9Y^Eeywm>D;A+pbp zys3l(H!S!H%}1Wah{47Qsn-6kBr32nV(%e$&2=j3}hy3bnZJ@Y>9iTY7JO z(gMg!@mK!2Z+$|f;i&cT3wpl^R=Z5yEDbo$ghZ$ppbq9yH)<~IMW}(k|G|4?hur$uAi`4QryCi zsDIju_Y5I$toNXCTQ{7OOthqcj7*62SgeIe0&metk*o0$r9VY)NlEqPcEdnc*aR;ybc#lr|OZ!QOh2l&#Um`k;FuPc*n(x-McUCexqym;?-4q z4K+T-mn)TR>)ATSVpip4vi`%0wA>wVx0A(KYE|oUt=<&fy4-FQs$M=HmM06DLksQM8SPZN}txNMh>meH49&+o-Y02fN;1!E1HR zKa~C{B948Dl2tw6iEuFVApD{ldsYpN$B^ofaq@gKo2g|B*D}Vb^I`Doc-NRSVSX(q zAf|%WXj3sDDthbTYn?Bx)9D3W>O;b@I-TwzL8?*R9%2twVNGiG84a1+uq4%IE2|!t zs_qZ&%W03@{a-oVPgfo@R*HFqZnnMp$V9g69>W}N|K6I9Rr~jNGsjDrchs*nSf8kD zPFYvl<#&${y6>nl#Z(nY)!Fl_3jC9&TWd_}s)G8~J4&9$5KZ@8(f`R8=rR=a=x3F+ zEu37oeD*{|yRw+`)h~yEtzop(`jlaGSN2mnb+SHas9nfMwT`c{b)l|n>J>BBY6+F% z->ZAr!U>EG^b9Db62_)Y6|{OoK{xK;W5pHlNL*aevZO*RrkT489riJ5|NG+t zUe?0_Ka^6c>$HlM9!b`UiEXH_S}tihI8L=w>mIJ|xXL@c+OJi#ZLUjUAK9s{({hj8 z!8%s_q?;IH*K(6*b$iY1x>@y`g}G+CTH!Zyx{u|JHtCA4O_|TN<_4yPRqBYJ7uQ>L84-6cdaW|aQ0UV)Vf8p^swtpTRE6I8-q|kB* zyu4o(T9Pi)8zwT~*+{OIqW-f*;e3 zJY*y0cGqff9Gc-K)aaXM;W(k3E-^u^*ja6{j)+7x0KzY*xt+^! zFf|W2Sd`$f1hQG`3Lc2;(ki&lla8R=^KC)R&((k z2EUJ*4qcUlwE$;q2eKFg3=t|LuUcX=C*Ggw#5+fw<}97ZYx7bs8V@+LQg73Hv$mWu z*38Ri{hZdF%9`#AgI-{@jtJU3!N_YuKN)x}iP9m1m_1mKIyLmD3t(4caZHJ&FGa`<8O0I zY;PgMKb1B97MRU=6$q0CMG9WsfWU3f6?xg-QigwrS7+@>CMke^QIYoHtno?uq#~_S zKfcKOu}sTdV|uYyt(JM%I7Qlzt*f0y+9aEAc#-!{Jw77$c-PsmN=@T1&7%N~JZEMr z{9+Z&r^QaB6wTpj1D^t1z^KPYP{31#jV2u*n8B3~pQo=aj#}d#Uy(rzf(<*HDhHKH z{cYCdc|A(zbRwtIGrS%;iO(jPqabU?ehhqSAU=URc&=hQ&+@e^Ji|tBKqRBl&!q{$ z5_-#qroyiS3-1l#z3BZr*b{ZGXJ(_pv#fEBA2~2Q0C%lc9t-mBg6%1iq884KhtI z^%%%gjrG~eRmby{0v8V*Fg~Ro9tSxsB0r(9JC&B%G$JfyfGpKIypVkaI1DZXUzMq$ zvAV*)g^l%<5JdVpWnftnzSuZz-#ga&N}G~tEuw0tlZqmCjY@4MPL$ zE8$bC%V6U;FxZNzIzFa9VQ2&_^r3L6I^Ot}9|Kjj{;=_$O21F-1==Y!sR2Z_xkHH;elan)?e$}yR&;+_(eh~p zMkM;Ea!-;Xn8As$^xa&b6QcRC`q=UtbNJMAQO4_YPO##wl(ln8-`U`{J;(Ygy5FbD zg^-EwD}bix^*PA(6x5pEUJ*=Dy*=gxdoHSW3Ux0g$Zby9nb|7zeHPqy;MjjwbnmCi zs=tNv3qYqrcjFvYCw!rrId*Ce_$iJ29o;AAh$kt1x+bTkVkd{7N#uN-K>nPPg+%{y}P=*LEs^K?~LLVR{~aNz5Xv{2?ry^jDGy}@#JR;su?$-V6Ig^4z%g^-exVU@F;Nu3}2+3Rst=x zjaxLUK3!K3AGr?b+yQ8l$TW<@DCsb2&t{F!qtlvrS^AsX!WJ%I+%{HqyR1Ua@Lv~s ze>C1zQ4B9c@mZ(YUZ5Hr>&Q(FeUuDyc==st8}7mJ9cS|;7HMCy`E*6zgT~*;TUy@G z56}cQuN*kPOT(s5uNNjz=Q-IGdD?=U$LHi})Ag(Kyw4bo75S`%(}MmBFyX+5$IzJ_hX=zjXe31J4fAyr45BA`Vv>fbRisKrex527aRPs1rA_ z!_OGMpf5V_KlGzbPlS7)4X=7*9L5oOMu_zos5Brr9L^rZ_PxxmMnt^kn-9aJ-J8Hh z9JL!?b`o2nJW48834^F|=#xQu9=jJ(S=|Mt@onm=`;fExu(SLFr}YD;&ccF$)$y(~ z@NMD`?>H^h%sJJGC@i{i8cBIf-zUn5Z%4Ni#aw?+G+Z#C3~~y|#jJ6g)6C*3b^VYS zIGsq|z~u9UQ9>5)`iUIkucIx4GY0(!pmVqlLzf`}?wg2v^7Z7wGqs+Y5jfxu;yOZq zaP0PuR`9IBfCnK`U-USMKQE*HGLQKw`L`T4nSK*WeJ%Wj=GZ1@FtDzBqqC*aDVEb7 zHa_MY;N-IjP=+BK80E#~&Q+gnQp;~>{Lll6-iUT$v9b#HqpYfox$Jq6bi;qkTrR#H zYU2%K!PRmi;9o-)gY`69y6c@ScRL+IVsMA<*yGOb$DJ+rJH=e;80zM#3C!hMws$;Z zoauxzg^a$@ik=Va&c+#MIC1T$m4P#fbcRJU3R?_l)7!mA)f^rLkbC_FY} zEN~9>9r`A$bF#+qk-kG;M*4QtUKhtZVWX!z{tFh=v@=W*GcHV>TAZY;got z!9dqBtFybn+3;?-HP$uHPzdr39T=RL4Ttt;eq!LIFuA?}GC2{#S7fEib-V9$wp^Oq z=MV0fb}Yx)J>CgaI`r)I2ALmXOpwd;1%rW4kBxSAk9Cr3PyPW!f4FxxX7aUe{o^1P zG_*J9thL657T)MRL=fC<=^pqWs^O`6zj~NX6YhZ}Mlq#(t2w`t;CB6@a+e-I zqRQt+rytJ=vbW%w2|OdOvkhYDZgPWKl7oVwpHc9S^{llCRMaaXBBEG@PmRJ#)pLp)zrS>;I#S$mE=KSlx5bi<$T=*~@U9YZcM8 z@T*VCJ%t*udMgG_;3|>*vb% z#53&Hp6+MoLae@a#oC0!t-(~L(eF=Xe6JZ^eKC5Bhh(sDxT$U!lq)_xS4g3ipgTsI z3$`)CPOdj}$X6M)`^a4Jk-3{7=2^2jUd)(73TsT(h$taNVKCBdNA%?`Ij;3uc?wu; zFn+YaVvi|>!3`EV6S>=s3Tw0D2?Z{A3}X(_+V;h1ZeZq(3Vv7CBr{k8U62Z~s-((qR{Whs1G-Wlz!`ec-7coh-i>A%Rpx&`?BFS9}4VR>ra<+ zG_2{3rl-A8%+_!H9OI2rygEY1FTtda{&@7k{y3(GXWknLVpNePK>Y~H)8c*9i#Jih zYx!F5EJZ{oMc^3W9)jBb-l*FUZkC5jkhHd-tgn(bD|*Rq&HkHYpu#c_r&^Rpj*Gdl?{C{|r<`q0@e6R@oC- zyDWgSBytv+afs4^V_{VQx7UC_Qlu2N;9j!soNY!V)9>sUd=0BuoSNFMgyn&|N5cd; z=1o0|2+C<~X}Pg($Br93R|A|FTe%&^onWshEOvIN1Cb*b_1GlP#%AbywA(22yxuDo zf0;!?R>}hw!}LQQr>QqQ{0yslG8`$FAzq*?<5RP#pb2!x zHnTqG^xZnRjS*<#gH;s=$ASB`ja&V)ghc zA^!W*wNZQ@8GF8$A@<9aQ=0b501O2ejHF|piO>w2qp&!3nL~?dY}gi_GsPCgITrl| zKwZ9*Eu0D?m#E7PY~kaKz8T8DfJ*S)A|9Z&7lUk_5;pqhEbeDj)^O$yLW0ev8nB#u zS(Sl#P+?=0x;-DBez27rIKyc99wOUET@uQ_fw=yY{ng3{sJhUGO@8^A*_3dzg?Rq_YJS*+Q zp}dKG-wZFhZBM+8QH{jh%BRMZ7@b+lsz!v(Qzj)_qKjuI-dhE;) z;N8W-sz8XI3KmzxFc8H4_r{45!6rmcvtYcVdKH+jrLZ;S{DHx~;I>^0zn8~au zfPZ5l7U2-bBZ(Tm66TvL4*1_2FS@CfdJd z_}HKyShwQX-Lu3hDv21MV?lA#*1U^;w@$$n_xqV6Q6X(~kW*%s4m+Xgi7v(g42fY? z7Q^6&e#Lut>h&}7-qvJIx>av^4{X(Rgq3peafI0_U`I8H&C;KH&!Wrh`+I+1z41*4 zf0^fw-nse&7@!T8!-6j-OTR+!m1S-H8_ql!W!ua8-y0{)Cb26PO(@F67voNcneE}C z&?J7D>Ic>$LyR99V+KD_7`$#mo-od~hVoQiM9zxF9Axm$NWPGjnEfhRQT-UUL{H`W z^DO=67bft1#&r&yEHk@QsPTbu7zZ@G#x@}P6EDw1ThvG?s$1lKa9Z8?K|il<>`C+VPorHRYd+DN)xzYQB_3)q z2RsY^OFBGS_XM`EoVi?LagQLL;^l0%Fq<(h#yr?qX4iH+&e4lZ{c5&Htq20;k4((f zB$X1~yO*$qk204Z8|9wM_AX#@{vtQtftK-1g8|t>_VAw>J;k`!p0JiX<|xVi zuW)_rSi%76)Sw?~AWGOr1DCd!*^?F733b-k2*tG6)dmEho7mQ_e4sm9i%6~>iXv5${s>Q48wi{kj*U3Je`9^;D+JqI2 z!^x$=n=NUZ7sqN&?n`LO+5g67gb2L*Jmw*ydc8OVn^0&+DkIYn%2MGbYS>O<2?R+~ z9#6oMgw7|aeCYn_EStapG~FG4uK}*;6KIO<0HBHhSdvh)J-#N={hhWXSXvSrXz|yq zYJGSrY*+BZBv9+BXF!$k`r`?mQP6OriT-M^;lL@hiXB^b57<=&(U7R(5SpWF{Bmy{sPW#H5qqpBI+*NfahWspx%^kgz*NrhE)- z&wS!5K^vCkU={;&ewBl{oSUPY5#vsz{f~5a?l2G_Z1YMK6cY&ssz!8yU}9icTnM)T zNv-Z&RyC7xPdS3<-MW>(K?>vu-HP6Bg(c!i^=`0P)i%tX9KI?To#l^~vAz7T3XCu7$Bycc9giv(Z)6LPhxL5N z=Z=<-9O8u;0IT{V$Fe^=EV9ScN29BcI2I32hf`ahIp>jC5V#Wfr>R^{tD^=+x^7+< zQEAWVhVOdhs@@4RIh_t`r=ylD(y@hIxbF0P%i9iKDSkv1`Pk|M4x8M5^`9JXakZ+P zJ&wE=*xoF$_`cl7v($&~%y%|f=Mm`*yTa80N6rpMttwAPdpPIZjG827 zT%iHdW5^BjATQq*&e`Uu8B`RdJzTxnk+a!RlgUt>tzk8CnGOU5S!yv*&!!Z^!&M=<&70Z{)-VF>t zE72JGZTKZtAG@Myc=S?!^y;*ph@+P-!}7Gv>((vzwOqo02HO{JokgCdHcj)sf8%oY z2sl_E{CHSnuyGgk$o(4it1qe{q4p_mA~}f8(2ovfUix3;pdbs{Sz?UL9Hm>$_@2%2 zdAeRmfffRqkgRIoVT0t;@`%FuuZ+o%a zZORDmob-T4*|g7}!nr1nibNie$L{x~gl=3jemAqnmx3d0W~cf^hrH}yfzbYteWQeq z^~(MLKqsA=Nm!u|ete)|t89L>d!nOdq9gRoKv)@hjE$~eu8E(_Bu50^Vrpby;s9sP zv6-M<1s`ikXS|$J_bp>W_ycY8Qhy>?!KOP#(FEh1THm8`ypXS?QtvCh=}Py6Lf1Da zt2@h~uqBb-xNrh=x?wNGPYp~Q1v9_c!!2SK0l!blC-M(89e@aX0+Gp))DJq~`uXp; z->DB*&Zq{s1tEBIb`8Lk&!Mxe6Xd>z1y216S0E<>mzBXfy=`d;&oYe|1(dzx`m9!U znj3?@C&f)OJ?gihGjb=o4y29}e9StA5xq#I`M-5kKs!oBfetWETs8ck z%vzw4yI#8z4=Cs}UFOCc2m)`y;^V&Z)eP2aur~T%UyVX$JGYVhi2m zoPfp59j9zw`$30(wCp6*^l@0V0R63IRWCqfoi~1@dm&r+6_fceJ+7pw{6UNO0aa3c zfm_hd)^|3W<9W}FtRRJq-?2W>yXlfIGPiWvA<%D~dxFY+J z=3S!pu_fgVnUX&yvL#njDzEvV1C&>*GQZTZjcID@cwm;eNJcYRmF~jHK;o2Z0bG&%Es^});7iKKl1~(^1keO(^(rP(UZ%oUbjU zCGoG~#Wc#G0m}Mcy{iW|MKY!5vlDVGta5_Y!bVLf2V>X9Mo)l+VP2A=$?`$Rgk}6$ z>SqO7!+xRWqN&;#3m~76`|+H5Nh6p02@4~E_L3%t;Kb+C(H$|GZJ7ElZj=trYi z;ljZ=6E9IdFJPEB=J7^p#y+;`0E$F1Ff*yDIluRN{P zuK|6HvsH|BW-iZ3A>Mcue5ntIKNWl-o_ST|YI&4xSOhlu?Zgg8M(wvo*9;G|ft0$_ z*UiOl%cnvLpH=f0x^;Oye*m{x1CNvM_OOLjjLZRl(>QmA1j7PU30@Vy|?1f0( z-Y^ER7&5klavi)JA3!IW(ckqZ>TPD$+;uzTzVN^DETb3Dgld1-Xc}mu|D41)>T&pKw(!-#9SoI?EUkDd&rr$annS70pJt9=Rcqvu{ENMjD*S5=&xX(OCwTrl>WVRbH&EC1w@BT`nGo1WqloR7Z9eEeoG_wn8dVdJKO zTKfy>2l7P$b_#BhFgO_KuVb;%t4cGKb+y-fm9ys5fb{J)22sRi%^p z`#9TuwPvkf%LF!#knyD!#^P1l`r%o}o*_)Aws_g23lr>%(rrD(CubzsY7)**Nhn!A zS6tE(td7F_@18Oh&4t$A>g~yZg5H{<&7R@o|>DXxYAs_IPAo&0kh2WBiD z!`gfde|>Ui*NP?$gP=EGwk&Q}q!rYbr#&*+{qWQ_+Z=jH$9R?yegf^n#BEvs#-9F<=hJugcuU4;_QC8Zu;wcT2JegV1 za^+P;+N|oAX7JCwnW;de#p}zSoH6;qt`&%uj=o=Qd9#iBUcYo_-Daj{3$t`_>F=So zyf}+hO=k9$m)-wx)uM;(ak_ZD%^{)<^J~*8Z13Cvi4!zN1?>q)+?&C|=RLl->J2C$t{^nk#wNrT zz%PN#MnxP2XULfteZ^}YE@N>yI{J}YAvst;as^Sx~jUW>cEWJWlK+>8E7pr%(1yMPR>mD%(ZeB#;@8Z zE*VxEwSWHcme2mNga~0sWmZ4R!-S!JZhHNX($e2O ze!1#*+o~=aANpO?$`ubSGfsV^eyOxFTpvy!7nXM4nNXG6h1i!%bB~4-5S?sXxF0!J zWIL6)>G0&9*~of*_3LI$vD;M`v&F0W>%$$Fd zzIDcb+96RuF??LN7)G9l6VA*u#WYD6B$j)BBK=Yz_N^(d%|r>x^o;Sez2m}tegPuG zOA<6%Y81vV?Q01%ltB4aS4|s^$oGbo!5;mBJ9ZrC?tgTDVsH7xF8;0zJF{>5vA-hi z+3tQjC>488`0^c@mV@MkDfo^83jXb!Fi7HuUVqmvf4_|=J;>LTvQI(uL;fk>MJu)4 z@7i0s?cyA{<%7q1khY||i&|zFvCHmnSs~Pd@5dVV08Dt{un*9Tu7*oHwaqI#_Sw;L z;PFewc6-ZSyKFgUYI_%3k%i~P$e6?(_H!)!J@XxZw8K|s!H)wrmF2J44K<)Q$*E^? za#qs6@nf6bIQ8OveCn|+_lceNVXV_NS*fF8^9AS2DvMKruo>vBi7-oX3*|#~TiKfI zsziWm*Uw-ht-7GPA>YF^zUMHOceMX#W zQyvXqz|wP@ZvC$NgAThA+Kly2C)kyW##v=$d+g=3qwxv6dic~_T!Gaw56b(Tk~8O)FF0_wwBrvrw#0lnF9+Ic;?;a!~P_tt1^V;lT+cOzMZp{ z*_|_O2!11PSnECZVx`OvIH_dFxE>zMl}zt9vi)R{UFKsOH4W*?Fr9Cm!Z{ko|#!$IoLuuoO z%Eb(&We%k&htdo~Y2kYZ$Cfmdc6BK2p`o-N2h%Y4&?U7o3cXW&)PD}98`&Xv&JLzg z+0#)0C*!Kr(2l}6bj{W{&SsfrF^0hzO`XHw@>`DT<9w*bQS`&9^XD%mcx`9I-^FrjmCk(E#t&@ zD0$hW@}1GTRKq~>4%($+C*@RsT((oCTRCd5!gk7eQ|U zZph=?C19A2gKjEa%6-4VCyTB~@=L2i#Y+N1z%> zJv2qi!7ch2f6IBXfqs_%g85aNYAA(vT4)3|aN33;iV$9^s1-wu^0 zxlDt+9(>Ps41fwf^lKsgVex*s%ql8#HAX+s&f;H-(2~{2WtLHy{n1#kNIUa?ErfRF z%4L?w@I(!^GwatP{_VA5nOx=-jO*=*2-+KIW*Q|%mdW4pwOB+yb6&+FHD5*Wnn;-` zl!(jD)Dz|{s_S9!ykKx<%;>SqkvF$2J?oW&>hi!aHw6~o1mJgHU@PTL|uqn76^ z19IMKOy)NOc^u_2$a5{FyqrJZ+uyAPMN)wzi#&a3)8&bS!8xAQtSt)OkA#S8m}v0x zO{;gvZ(9pfeRTQ<>kV+Y)h7p>HLE(lC_~Zg4*U@hQg<(Dx<4*EoP`asS6~~m!F}Y_ zlkq^-FL!K;Y0dCSs~ssZW%#>KZG6AX!v<57{Jz5nfPm~BQ_Y(r=8~TAb@Jjh7fVU3 zV-v&IZXPeqr2DJCJEg~`xRAk}PGa}bCJX(-^R2sLu1N$ z83$nNS#sb@voEfuM3_ajKr18~CbY7cS2m=iX`=ht=q;1qyvL~IO|GdaZyx*;^K6-{ z)(lF)Aq*R5UhU|KlVC8^p9y`%T-d#{4mNI8te@k^aki{o&AQUp=TdTYMgSn zCqC%=NxFxo1wYq$;-!1&2;h5teUfw!&5p!Hc@N!ys6)C(Mv>v|^&X-RHXeYH)d${# zl(q3LcFi03dBm}Zvcx5X^Y{-V6#YS8`UZcL!s2^ZTttbnZE^w}CZ7~(oW=K^ zSaDMkrN#HYID04oC}a;XEWSU2N5Usod70lg+$5giIZQ$My=B+&GU)#>7Cy+JlSjNY zm-9HKO;Av3XH?_>o8}(3=9iHyY#%mQt5P)3{N^k94BM1Fla!N%hlLrW-G&cV0&}fj z8IaD%d$$_5iz$KGnS<%q>e^_cTq#UsYQbRVG+EDQPTo$NBUFZvL(bM9mel3 z9Eo4w*U4^D3-8zZW1iSLTJqI5X8U8FZ*G))n;NsdG3{S0;YWCFq(uq+AwNx#c!+wy zs0FIqVPKpF5&oMU#Y=YyZW?`srst{lmRkK z4QGC7;02*TjlhK3Y0XV77WtN;A+Dv7G(o;3$R2l$Tka!myg5U!gX<}IV^u$QpVznB zqpCSnyT!wo_*KcxTUzgY^|>g&Dt2RIY)x;<;!WT3g$<`*udh_|g<#FXIbBT>TQiex zD4vcbyi9{`K+q3BZOVb&jzUUR^mGra&)>jT!1&SveR?OIdwc>$nlhp@P#y~!Ne$gb zA=~Itcnd!@;tUhN zLs}Y3k34qS2E+B(nO-6>Z)$H8gLTz?7Uktw$?wx;Gg2bZ*g~8>|3Oxgc{^xH)X~Uz zHQ91VgS2+&-_KZ-G2^+@k>{lm4QyNw=S*hvLp_GlA&Ot+83{i0!8Dexlb8##$>&g9%66HN% zh3LYx`2lsAbZ;O#)RL%R~8Y3n%Ym*?n4_j5xn>IQCkcRYV@m~y5 zRe0nvJ#}$s4HBpcd9Bx7GVZ?@Qi$8sezgkTX8bAa#?(>%6!pf`6ycD;ug=^$+MlA` zn5vOdQr2zi0>N(HfZDfddPy}{p5L~6F~2xs@)Y|vLsgs3YJS$1D1VAFFEv`8=Wio% z6lgtOrt-h8NAprD%dXj=kqdq=KLjw{jIPj+A1cQ`STUHx@LpV-RuV{OwJIFsea1lnYLq?)m=y0^x+8)`;9+Br(w zyR}Pa)hLs7Dz+wr%X+~A)Kklv7My{LzzoLqS{PxgqC0t9tbB^?os^>I`yH(eD4w7X z8$T5BZ{;YwQKN+0$}h2xgGtJ@IRw_Z@DYT+b8PvgQ-cPx$G>kxYG5wf^+ZYp0%5eQ z^5h&cVvU|rk>$8NuhyCO+I_ogdbA#;?NDvmoO%i1nH3Vi+r;ClXL+Z#Y-YWUOWvAPoSXGrTo0$|`{jg+zYA~n7C5U*$$S13v7t(G+qp;S zD229$PrxrBMs*VL$Kl`$=gexMd6K87YF2%XkE>HA@7nn2_^gelPF0;Usd*zGjkmC_ zAPEih_h{>s8b=nKCjdGc>V^n-@1vjS$HuoSA632;aWn~$&G8%*+GnJ`BKr7PBw;CM z8BH}!&tcNh9%fxWGPKu%>BKV*d>-Dqlpo>YKuX@#&U%ZfXM9}mVrl6n3Y`oCBSLvh zd0-4(uJ|6=13kW|&Nv8>B5BrZ)A>R|5NFiixj`PHWFzb9UEg5H*bp?DWZgzZ9VUHa zA}*gt3Hw8JOd@n^066A;_H&<(JddlxWxn{J1}-S;SiR%#*E&_LHG!Oqorv3f4PdzH z&$vf_4aF?EeKgWQrbYx8#w@-|v7dm?(i%k8v6_*fuNzf&DEXnum!60!$tmV)k`%T> zH;OX#Qw!@0x_}0NeKoVczTg60NCSgwIY0dE2JxfmD~ly1)D|K4sBi0nQRbU% zkMU!UwU&0bmimp{TH1r+4(fBd#$)XJ3L&EF{97aw9gZgIGOlwtD zQl{>(O$|$$`sE2WHM^2nhn>_2Zm1^^7CPC?*|h9k1rcXhvYh0)P1YJW6C!V_2_I3x zNlSk^u>lHi#b$Ero+Rdrh59@;wiNzG#+J5BFBQj9!aU7Ri(@p-C4reuDRXHs@N(Oe zgek%1TH4ptCz>e-^skZr7hCLrd6u&P994S(&9&JAK<@`>Le-s}h3dH09`)UgUG(D0AE_12DtM`BuKSQ)4ep zvXmwx2z*V%+nJVtaZNcxx*ymZz)otwFU0?l3)DjMS(|1mZ|j4{V?NE~WXSp(dkgQF zC*tFG(zl3oBWZ_iOo>}FL68m|4EmnqW9r}9;D@H~nDoD%28w#i?%gxdiOE5%?nyrf zeJ^ZG`I~g8YwT+cmvAeZMzN}&3AgR|e42iX$sd9U@5%B{r|DlFTS;_YKO4pC_$>K! zxE}w6f08ng2;5vLCz@7%0*)aiKhPPqL=o{N^yp1#?aC!I&w)p7N_#9)&b8vEw07lV zRL=DKPfU6?RLr=(8D)KS8juz!)rrs3lol&(AE_*hGEpjW=jykFUJl7~0$gD0G=JcH zPs_`}mM&lfzTJ&$+cqC=^=p`|EB$JZJ5?(kSMV|ZVxPD86|^8Xvfs0D(`OCx{Vq2D z|EljT_WA$U`nJSe>Gikj3*tcsLw)dzMc(w0x)F*{0?V75x487IU)FtoM)|Kk!b5t{ z^&C8D;1S?mQ6K^b))W?r{~vV%9}m_M z830)GP8bfQCmlCDw4B#2&cElOR}Fz%*atNL z)r4fBgHRIV_>As1Xx9pT`)NFkq(SgnojHt|4*JwKTx;l(-V}UHu@O8@t`DXVF;qTd zFl{fw1wLJxrkH^{fadEP%n1X3LzdC*ti&v6L!^fMql}xTPS>=<1_kur(Z&Q|3Z))@ z%c?dC{oW`I*&zCR)UJ;{_X`?6))c$|DMT>PaiMaWOt&qg1(W9<{KBWE_V`-K*+!FJ zyq_}2E9bhYQcVWHp?SA5HEapSdeV__es#h`&-%4fotyJx8i}@>t&6hT=y4cJIO5`z z2@wMCcT?NhO;O%YRo?83`nB~???n+b4N`A$Vlqg*PNgRbKbo&(&2UkE@DT%_tN*sD*ijyga=fDh%zzUl0zNw_RRQ3zo zWF``*7=7~(pcVWV^QkzPCx!5Ewuf@&R}*OzKuNZRa5($F9?S!3(rSr<4IFJ z>Lw4dhXkWIZR#LR8fX3;+Fdbo6ZMn+!Xlj zCw$zIIK+pHbNv^ziUAYuTeh7KeK@FNEb>!>uVRDH1!E*AoMJ=HHt9rT`+MVsE#z#v7$mPto&yp{2`%%UhU2>>j~?FM@Zz{@u6fmei&a7#|(u4Fzr`(6}R}-8o=G}+Xq1J z#~J)sZqGj@(o!^5+$-x6ps&Du1@T8QKQ$aP_NlQ^RWmp6%GwK_3sQ<=O$JAYVR8fL za-le#WLci8^zX4q&7HvS6R^Fy$?`~=%pf-R8!D{Q9qgRq4j`#)fN zF_iPa!4`OC5VreGD~4bLohsa-Yo&V(E{H5RqVRu8XbL{?BD(2UBS1hcQ`jRn3pRhHe5&6jDo9V{XxgFC+JB>jfxOoGt_yAjTtr$a~AePIoL+T7-B9 zrwj_WI9`KiGfg1(!rhu(SC91zfLY?*XOfwLaDMBOQ)a3_%MLF6~V`E6LPdqqBb;6_gWrC5UL@lT!$ zyY|VQAL}UW?kE&HsGF^g`!4jPvEDSrmcE`owfKhIw+8#*FO1k#GU@XsKi;e!H5;1o zImL3s*$J}K`>tVl%@+aTF^JGn_=j^5v`5m(X32v{3i z9{59e>uR3u?}jV?c)k9$4qjuEPb|6`;JMPAM+e#aBGbMr4X+n&JKKFIfsbiJ_!|Gsuk1iC_u;^qx{eAny2TLGXp(j3bZNKMp;I%O)6kaPer04x` z;>qFHz&QYr@*SlBu^)I6$UVtWp3pc(lM0g*=9N!q_`)LDcXuFTlsLQOK@H^2PaIKt z)cP0UYr$Sh?^F5W63MAp^^@deZKZ09le0UCu5D+3s3|F-o=g)yai_+eK;58;z#l3=^99Kpqs3U z$Z-PSe(l(Mtvt7+U1^ST8AeGvCQTF?g$Pm99&M)n1CNIzh#Jr|yAlE)r)L0Lv&><5 z`?O|=K!gIqVP*eFVhpVri9$Ggl0vYi3f6q&31F_24-?7<@KDp&Uq`&rLGFaP(%Gq?=s0GZVNUzNX(S%x$6phlH8gBg!_V>=i^!o|;gJwP&^d}DB<44kU&r*SNBjLLCEaw1Vb0it8&M2BS0?I1`1rw{3 zrjCfNonOm=T?7wdlGSVoWr@*z5@_8PF)pQzbw;Ww<)#x~KjnfN_o^~bq;QA*@ z()>>i>)LL>Rg^37j08(Z&S&1B^IrEKKIhBdpyRFweIKgm8kJ!udFArZ7X$kwz{vXq zefcf{g9Um(n@33_=EOXL9IOzkw~0;LDRHEmyOWLZNM$#75u0uc6@;(#e6}(7rg#eA ze+*xgR?Mb71#Qw4N%loI@QWgMVazCzwMajZX1=)uZqI=t+@iNLI=O)|k46&tRvQQA zIOy5s^#v5B4oD5{kaz;b!nCLnLoLy`2~-IN|ldFX$nEW0Vi#?|2$l^kr}l9;<@;mCY8ZAuBtKV_3Kc>0Ce z5PXaO|FcgU_Ymf=5PoB^-d=&;$Kd-Q8)?zs8d&sw>A=7$a#0SS&?&rO z|94qznYSd4|CidR<@z%629vynrL%cr(1-BAjuKxkkXO-?sG8^*RF?)!3hT=SJ-+3B z*#m);!R$*%Yf|;C_$#ibD&E(_5dE`KLLRBrl;29oM z<{BrZ=(K7+x~BJfo!!C@E1mMpuzADk?74Ne2T;1scl{xE{F0oaH)ip-@Tm{pQonTd z6RIn^qH)W+&LFPCYGC!un1!)V1G}o@6nj0x@^f?-Z(Zp|UFe%JjQD&}nWtV-GmqrQ ziW>&LuX$5vTwmlAB$hE7?J@^&kpGuFnQ3hCYjfeE6e0}CPV?-ZMFtC(U4@x;%Jis>QLvB@8dY!KOtJsu%X8wVwBLBD3F}9aA&kXw1+yO(@K*`#;?Q#7YwuhP|@wl~j zTH8h3F+Pk3q`DJQP*x6^EyX+vyANsp zrTm{zzOFg3_-+Y7M3{L*e?gQJbtvg}QNI)Kg3hHa_0ohDj4CN z+^I6BUT=d$N8@%S;Oq7Ft@CC&x_E1T=1IE>X`*G>&GyDYlv$2@1YqMNoY5^jl_PjT|BJYI5TWcHzTIs1 z*x?uy3@#~SuoLtSKRR93-+6TjUJp8L(zNBZftYls3A3LA3qHRgx5~s-yfoP99ej00 zWD_J@6T{NT#9oo zE<*5ER;CL4(7jM`8wRjG7f}gkFSMU&GDA!Wuw0>eb~hs&GGJFamdm~?kS-T%s+g)J zbSU7B217{m^!wp(|H;`3X72qJ0=uM$1Uy3n= zN?`7FVvRLIgkbLbvm)}S2JOZ@|W8&&F^=ALh8PP85mVj+i zt1e)yVsmt~@hR~wQm;YI&fI0)ZP5zq_tw|fy;61f2Y09sTA=f5i?LZiDQ#b9Ti zS)eDdXt!PFe~FNyR^X9*X9Z1ClOnswyB>a(gTDp`UYKatknd&Y;u_u8LVrfS}r<^+Zkx1OWkX6uoZrS zVj(By0R)-Zb}=@6W&A?_csxQNaPpxa+5&@tfnP|hNWG%g3=)$0J|g%A_QTgcz~vvn zfHMgUIH(Dlp1g|IWM(m{cKfD=Vwd|H3VT^!{hB!@7css7T`67kT#HBHZ>%G}J>9Z4 z%?Ycoyuv~#014ds`-|33OL;KYdS4({W-)>&Q+1N;*xHKUhTTaU&NEakgyS%4c2k*B2qdnNE|JX&eO)BU8D`-@F9U zup)ffa`-Y#VBzHU$&;bH!5Cz>o~syPa2HWPFQ;DPRD1qP@v=N0q}*s!IeZO=m#Djx zHKysC`DstXdFcvxIrv)~#w)(n)k|_8fY*kP;*b%d2FJjYZYG-&hj70c@%|(o^rO=P zG+~`!KjU(PJmK4~>B(2$ksnkDx~I=}7j=9bceAFEp$2t_LW2W7lxyqsE!$(qCI3hq z3Lq7x??I$08f#tt_e!amK5KRP&(GGxk(lEf5;~t|0fi zmOT!%(+}HieEQg8$RR^JgD3c`%wWPVx9$s`&`Qd(V8TFqrmyZp>E#^!mrv+q{1l zKcX0-POEf77v5f-7+miofoDOw|NH3?<(Eyyw^{7a5CqR#_LIHms9}0^I4iI=3wLVh zDEO+Ko!3NzI4o!LhV?lhv@TYa&@P!e3>V*MXxRKw6xR-vx24OFF^R7M#vmqMiH%$N zGBjM)yr z0KE{LztG#8He=F&-Y6@g=Ju9-fE+a(mr?K+>k1f7dnY|ZWb6v~>^mLDZER(+qUCC? z>w7!-gsi+tL5PSTfO4FV*EORW+4Qo^REVt@FY=2?G%#C}!4R<>f~Af44xy%vP89e* z!g&ANbnzUezjHl3ROgd@D36kBMu@K>t+J;-4N|d>u&w%IGWWM7s13nNL>z$Gk4RoB z^05t@NZfHpVzUxH0_97<=I5G(UK|K7Y}s;jjVpnhHaj2o@zdVaE)2}Pe+cyJ$`|;G z&9YG_!ZX?69o2Dr@(oDq3e>)gI0^nm)35}YVw)aOWX>k= zJB!|(umA&yk!)fSmeY!j<{W>Diow`K=~|rV%CcMDO>~Fe0!L&%{Ny<~cc=>w`n&PaIe#eMF$!!GlMfvd5;*Dt zB9YJ^BYL-X-rc#fFaV$3!a!u9?}O-%s3sQ4f|(^I^(Q7%;$Ss#jw}peiI)Dvp_G`S zCN7qRVJtDNKha8wscPc#qjLa!<)Jv_vj+6hKEg+xNhh|f6ZU5CVmTJL{v{ReAmDB= zZ$WWmP)NjoX3xQD@;j#c<_*3ZVE*rY0GR)K9{}e6-iPJ?e|_)+))K@}aSO(bA$-m8 z_^WgEU0D1R+qngTYY0*HGvpzfwX5aD0~Ykmf5Wh(XIe$uKW8L2!QUIo`VZcIeMJtx zP^IOp_b=N}v@Dd;Ju9fycn91L+#hK=z(~+@ zz8Pk>UX$%DgRbyJIeoyQQo6-Wn{l7Q|FAi2xI5{IQI+f6{FTic*MeUQIvGNhkK%Wl zO6WQflpeK={$7!8wRBw)%R(y#SFA8sc^(q?xIGWg2Y!1mUM2l{{vHY`w6G%3QwtYu zZ^zxz!;19K{6fCt7$qavT+LDVfNIq@Z>KKRQJ1QuhgMdXl^`psqxJWf_!!Y6J$kfa zrW6b^Wh>kB0`wp1hI$=L`=gd6w!iAer|LgI( zsfi8I1W2ZDwUnL%eW({Adc!w*%~?I)tJgJrvTsgMuaD@p4PUSE?|b&G zz*G4`{6r&n+PwE!-vQ13)1U70ePyoyWXo6B;(O=pf1z`E+mW`ej@jL9d%yO5WIp*} ztL}39g$If*T)02r_b^P3?&#M;%~*O!OstX~4y|aLJ->(m1W~s zHES`Rz?Ut&l=Q?MMjs@v2*y?UH>?I3-u_Yr@90}1sXW|Q@7(K)rfRV8p}acv#{45r zMXM0r8HZ9Ut4Dzjc|N87iw=1ayxq-khxpmWgDv-KT%lpAa{(aQE2`Z63A9H?RkhNq z@sFnRExcPA9;=H(b)dUddqzigM}X6f3umaV%ysoWcdtg)-M@8#xC6S!vg-l{O*QZH z52NyKUFFt|kw%12-{f|Ejl^H=*dJ+DXsXSW?z)c{$}WlIe3dovoOkTvK{1ixJQ@$c z3+=+4#e#kR^H? zJ0N}8Im6Nbe|RMU4{HKSBb3eNK`j@1TrFq(H{~2F)N+P@DW^zYR@(rum|_C~g$e`O zaa61Mhx}`Pm4;mOp$pTYZFGk?5x%G=BkqF^b3i|1e|U4VjuLG_LqOa?)q!FfSU!&aAMH&obKaDc817= z4iB+s(XCV{-(}DwqSLU7&|j$d{F;6b(R$DbuH0}zPD6+K&>?r4#{H%M{sQ{6*3H-j zZuE>P%DY+5h}pQHNVU|!bBn>vrVuSTp20|Uz)q8`o28CR=RxH|3k|g1M_B2&A;$XS z*V8JW8Y5pDH-PcniR3q`SBjSj_SLdB|?R$WlBHv2~5I{!ebhsJJ|p02Moi zdZEVAgk{7@N}}MGtUq1`fHC~>we=V_;tc@?G|5`mVmsg5wxg%NZQAc-Jf?Mg^zX{) ze^xGhtiK%V9}J$Tf8y|#0kChD7)3l5K0ri(?{&O??FMZe8=}(2jFx72-q&RJzeez% z7C_;PzrvLYLo>af*W@@t%`iL+YC-Z=ybDihz%Tc2T>|8Zd0^Fx&h-o^!&~>y~=}E$BLo8#Qr{C2d47R*ZVA}wIl-6iUpjb zlfGB}^%@f-U=AQp2b5S1a&f+pl9S|T39EfsS`IsqeWcuB)crDS8{4cr^brK95}tQ$^= zOT8K(UNKST!|6{ahKyjd75q#3^#1gN1QLV2 zSL4>cSg}#RU6RGVhJ38PE6mPsF*h}(NpP{zgTlEhM2DCE!c@RHOTZi1)=DHI4evdF zo9R><13rB1+G&k=6-In?dV|OQ56TY}7}~>_4@|E*9|u#wVIY2BY_B!@flo{R_!`BRY`@R!ry^NcBDb2@vl@Vjw041>TrC2bE}Z)N=qH# z^A%ZfU?4mL(#k&q#_p9sM#v5=96loQ5!c9V|BdL$I8#{ju^EBorI!i@sl~+}{z8}*W{_>hz^5RH)m;!&dn>^BR>?;4u z)U>SKCbN*paQXqQMgjWUEpS%B$wg+sh@ZcgwJcTQkZ~5jf-iMlA|Vz3|LgBRfM!_3 z@!kn%s1GCygty+*!7v3AZR^5@KDV|}+<;q=Gh_l@b{7+Zb7>XJb4j+f-UTD)okC1+L_nDUPmdZ24S> z_v>b1X<4!~&_n{himhRZ{uiiE{ri(vfTO|sjA_oY+mUyPZVk}@vBW-HT>|M9AL!m* zXb#P5TRV?z73R@Rq(T|OwHjjoI4j1sO(+$=Ln`hlw(S6hc0Z#bDjThyG;W<2RviBO zr~172;X&@WjPtfWeNApaTW35q56!^Nt=rz*gj>bleoN47DjY~} z5VC+xju3 zO3YOru&V1hdTm|Ljjao2_>e~gRNkr&uROnX-bJS4z@cD|aAEWK503Z??i)5Aij0~|?u93tFnH)>c zSM0w6pKzAs%k=u-dCS`GDJu}xJ}gqBcy-ZkJ60T2ISAK+2G=5}6r@`f@7i-_tg5KC zd*H00MCalWk$q}1co!Xyax?RW*rwCtB+h%7FPXt*ypbXnmt=BxB*U4`uLR<7jN-iS ze(p-;MFFgWQfDy_x0A)R%_N@w);NG>6`r$I`_B_mcdyCP%(=Q&+v=w+S+%Id-qSQi zRaD+K#lLL|G8|kgTGp-hEELwR^@N^;nE6hln@MIK7%~*Vxfo$*E$!Y|UJAkv1f9DS z4E8n%aB$IZ(K6UBRIL1VEK#i3DE|v&cKiKOF=Y|m_*0Vjule%O1L_84C`iISb`}%S zo0%l>8mU+>R!P@a2~2r8&dm$hUC+-0t%>Gn7(RN=T}+^eIyi`j@y+vj?qaRGSm!R* zyNeC(Vxzk_!Ch=}7bljx)zLyeXECV}h=PX~9vCrj+N?I!A1S`+mAFSISo1t=O~V4! z!xnUtj;(EKXo;?To@W*fczFZmfMJp>`G&I)@c!4@4dt^)rux;|HR+yToH^S@ z-a!+1UzS-(5VD%FnY))NvuMQbSwj{w2%R@-s!?=NrFxFLu*2NdeA#-Y+1wnL25H?< z;lCZX_Ld7$NSM~t7Ama<-xJ0w$}B;3c8FrbFIcK{nd2>zu6%(6e>;ODHuss0M01ffy6OzB6- z8kcxPJEMccO88Arw6q@+C?-9k%kiw5=3X`1YptH<)st2hD$|CD^#94(My=R#Qbvn`wc#og@7rvyG6`Ft;&l;6 zaK(y@d$x!Mxr~;5#wgdduBqdMZo}jPQ9py z!8o__btO@|W)9>{i;?1gh(77LbPNrsbi6ww%WaaaPUZ;mtvXR6iQiq*=SB<6`{6tLFX9k0%q( zUD0Vs?B4w($^JS=b=#uzg>|2b;x}xl9#3vwQ8iRk#jq*8JZ@NqUCQvO`idz;VpJ=$U~hlABLg4Hs67u~Y#EuTXo#)-Uo>oY}|6cCD~> zR~fjfUoss06~5!5!SzqxJ)5z#)UA}UaOI_?sTo;_lC!&z*O$j@)3U}QmJbSa%!IjCf)w!0Q<x^~_yeE4 z07=l+e25r1H9ubC2+{iMsJ#BIYcx(zQDi#YW#EC|HN=uUMBxR?=Nd%frI9Q}z+s6O zVD>4o1L?Xxs+^?nE)dJ0!yAw+O?^SAR!^tKBRuDQJ^_0g&w9-1)Zrft^ZqJv&#+&3 z_w9}twGTB#7=tBf)CJi7329xo{)=EC7RTZ`#rnG3mFwWNnBr7iLt`5Ah%n z(ROptC^RF&(?yDs@L^mwYH#q45PYlGs6}jw;e5%5aYT84esJ)uZ`bcw1&r3cGI;bd z9xYuL#SbIXH9-b~Y}CmN1T;|74cZP7Dr&moyYJ?qR{`(mtwLeL=I8m2H{-HNQ+~h~ zFh@-s*KO_!L{0pZ=B~gR5$lUa z!QY)s3aNT_^61r*r+ja4sDAVFdjUbs-#ElD7r1Q=e90nibKw)VEP5P=$I-5kIb$EM zAB`YxT8RyU6ukx=1i19<7{fth67qS1`s28*T+wUyV3bD#1i}cGH@>^jY_>LUL#&N= zq#e%Q&2jYO%6@}lyY8B>7#eB)Tar>yE zipWJ~)75b>6RDJ!9Ee{k;5%x6-i6)8I>2xF=3BY*nxxlBY#olm_&*hw59y>3 zXP;f|60|cXAP8$bt0bb;+ox5Rm0G1pF#!n#xrUuY4Qd}MKEK*=FwUVVgsySvwTXcX zcbQ#mD&}Lpmc(tk@(nZpq;s=R_jp}`FcVQv?~mK3UA#~Xkt|m>3tq~ZJ_?i1k~$?d zgrELm91BA~pSqxq5cS9=PTBfNu!g|Geq|QKEQkoqcU`ZyuPkWhQ?t%cuR{RmI=a;_S+qCmwAxu z`i}1?g{PC6nQ>7nDIqt?rR;v?cTN!#U_gZ^YYXyGznn?xbXYQszXLsq3zL54e|OXr zWEi~*fBb)+gpAOotQ{;`)1@gdn6d&Q@5|m`hwt4b3DefCsxT%rrG)T5V4RJ=nZ|U> zlmOqGn%{P8u-`HTXG*Q@Zt>sv;MLyn!As-R`;!k|E%U(}UTxU=IsEUYWb*C$DG|@G zDmMY|_7L#l4F)lB&lU}nj6xA&XSN+*Nf#o;5bg`vtR>`uA2@IMzDf4=7olCZeK3$8 z@?;wPUl#%>JdR#&OR5F^pT~(-|5x-e$lOBLHkich^mBz0^I{BBcIF`{Y=P(U_J0-< z=PAq^;qtisABE(x*`YTAi|zWj5TBxrTBHu3ROV?pcyn6S*K*~1EOix5%4gKnFK_r-4!=Wbxzz>dddSssi(d5(h&sbx8|s{J zaDg!)n!I#5{uGd(lT+FA?a3HI_faosMZ%Y~2rQB=^Dc(y%N96qJJPziT@-fDu2IPFxiu-TtR zsU>DE{r3g1)AX1JjM|hJ4GoU8+i+P|dU>VG>FG84EtJiZVXUhtjEHIA*Jf&^UaiDu z)VUfL7RLVg7X7{QG4+M1@JNUhnw;Y34NVor#6qPc7N>_6JwjhG{3pq=Vvk#aiR?zf24mI0K9Dzhr&3vd4_+E|Ja)A@H%4)Nitc_h1s z{OV0Y3;qcE3ifF%(y7cFh)>uD00R%PU7b&Uugsf^$EwQzQ&l-T_~z7>ggb2NX7~dY ze8IFss1mrXd&ISOh*d*|w+f*Z_Lc;-4XXY{$_33)$nc;p;nZypg?%~2_JUm3jP1@D zyFK%Wq^FGQDI=r}o8AVy%k+&?x7*2d(ow`&MjF5P=~cgKtpadL-3I>?69dMKByENS z2hmeSMUk4D{J*DaN}$CITYJUb@gvEU{J)-P6I=Mb@C4)b9q{=dqdfil*1zONnv>EV zy*X|1jWidfJ#bT63omBJZtWav+PWpun6rPs_%QqyLoD(iltC`K{I*V! zho|ebTOy5<_V34dz*&glwoSn2LEZLZqgmBg8Y|Y{W?oBbx zUo9qHP8%Lnxb*=@1CMFtg*3HdYR=vb>I^zopaiQ2V+Jo$PqA03SFI!5ciaM%&Y$YI zsRpJ9`}%{1s+S&vKLGLq7sH z;9de{Hk@$~qtxy*`iD*Qt@2eoZjcZE`0V!+)eQ7Kd7^K%ui~;!?zr^qH#dDBFws|o z{95^s;@YQ!e>7b$G4Wub|GNp(HVm#EmhIcnHda_aa+UA7w)OcNq=kQQE+m0z?M9x& zRtrP)Y%zHjHsS%l;TN3B0_XKNb)8~P!v8pqJ&y;6_ia%xYdH^FM_+s=CP|Et*}7CR z4O1T_ll8_b)AQV=QpmZfYF0b9)#Nb^^UNS!I*-ZfnXwxWn;=}{g1e&stN4eD>eLI-R$)i_C9$dXA zl~{e(_ZRN2%oop3PFcP@=>lpW6lV2uU-Lu08o1u-eAL zIT7X($Oz^(pCPBCy+g@L!nB?-aW>D6LeaDJqV%pt=6_*x&tEdcc3@}TZ`#*RjD)W2 zeEmL=S5hFl`51NhxjFwifdZ7QYeZoH7a$1N5DnmeggSljxr0?Q51A!#FTPkJ1|m_7 z(k{0DsQ`++&N({R%-O`8&Q;Ot-sAk0R1CJvXS6if&U9iru!D*ZKM=wqWNQ$82p>6K zx5aXZle5afiCS8YY*6FNDx;S&ypX?mme=v-agZlzCdqW9e~6Pw&Q3X=gA|cgIVG*1cX?#0ergdB~^#cEL*c` z>!(1+i(awE3f}Tg=R0O`m*x)2NS;*%y9^_u<>E>@{DSuo-BP{p@HGg|{rXo*=<+cE zLg>&dKEH#yUzK7EYLlxfo~?Rc6P!5`;L2J8T2HnyO6UY4jcA)+@u#t&YD^XDB8La# z-9qm{ZQ4(zQbf68Ju7aNXFBjem5k-MXYVP1#qly2990ljvxG0r>C0cBbH8U?@R;Sj z@7A@q!bP2UQk4rL1GLp@dg9!&=X@ZmmTmG?9nmPWI+2hVs0duEI&4NLmsW%LaPuqp z=D(N^IArZ$aWvMyLFur|C42B))*k^bl}nD`nX-LO*;@3KCy$d2GWzwYO)P%{{rCqZ z1hpxw9~sE{xVFk$R;53(>^FAVGQ5h_uv|M~S(9C1@Mp{-9>(%d^N|;3%1Wb=sH4LM z8qgl9tSW_ zR9rfIO|(2CxDKD0HgT1`W>rq6{Z64S(xMAz9Up#Stdaa0j@6TA2?mFHjyM{Q!*_|Z ztO*d}w_Z&H9^TB>H7}W(Zs2AtOvk3uFPB!L+sj3gPoID(`^fMqea`00EV94Vv+6btCj-MMpq zo&PxP_}G6P7sY!`Z<*gpKaw^=GHuF`hF5){Rnq1v^DB^kBpI=s%IRL`Sn%FFIuX{y#wsFG|vkO(=mM z^jZ4%BY<)WT&(7}O3}$7y=9@+n^!2O-MRR8`HQgL7T$>ho)GuIb9ZJWmpKoSLlC&V z&v|3Rm3DTZR(=t8Y6f|e#~stR>h%ULBiSS_$ry1|je%A%@~X#l1WKEjNP~Ab+Jm*m zGp3I3<9Mw6_%kUqL=Fj~wt%!!!4v78*gtMXgj^g?5yF6~iKSWVHf>^BBe8r_-62Wa z)LjKMEAbAgxJd+ONh+oeW~OYFy$*|**nOX*t*?tlLePG}cM8A$)VnxVnqQ8sf(lAM zep^A+KVv$W_NREHnIh8Sy7UjE}6vj~me=2zCF%kLwg zzF6)7u{Y1|Ncg_Q~JvZ0N607IZuDZ8|uoR2sh$9bDN(VBnGlxGi1Z%Mfp7^56va z$K~_y%M(q+Qc+qR{_yFREJbXfQ6IyF`jpVwwpx={@!x;Z0 ztb5)y2D2>IeUYV>h5|8*2!fz-d#J%q)7a!(Fjs_D>2^=)Zos5+x56}%f!yvP@H^xz zB@+JB=Bm;T{P$XbXWJM}LCCt&yC0~kc-QZitS+-x>!7SsSBH6X4ecU~-D}v_0 zTqeT4Q!fdExMcKVNzg(Dkm!vj!hK@2gy#4e-Qo`>di31E3eO>Pq&7b#`M1#ytusPRoOdyIk`jy2}_CYnJPdW?Lb z7sR2{sPnyUb{e(&Y0M@s59Pe^{m=p!&r_G=nbbi#1Gmx2^xsEaL*NEO_;6<*)T6F0 zjf8gY-vcc{|GktX-rAe4x1Y6xCf15#?4R+#@;*KMQSryLdl$C|Ye*7MIp7oQk;oBy zi}r^(ROv6NhO^s(8UwG!|ul zyG~4;*DG???%o;H*?UbDo01NuDp7M31GOLVW5r$!Mz?id?;VsLZ7+03hl&sVcHO{U z69koUrAwoxv?L$|R{PjBiyMea3V(p^1s2yYM`#yCGuEpQ>aa)J$F&&fYxB{qUNOnuoCDT>T^Hgs3b7CWPXEHK z?+~t(bnssLhA(J7Z4gCC2hG4O5|{}=oj?)>9nT~TicaSP%TlKWpR#=%Chx4~2BdGt zzvQFs<5~^%%UguLgkH^9rhXl}bSALaQt&+%42r})>KytHl2TA73-Q76*G`zINTI2t zEGbHe3-8u|b(I*4bXSGqC1fy_{x>K5Xj{dyOkV2cU9SH^XYgYZ2GDP~jat3|ZNSAM z8mJ{DDhN&V{81J6Njz5(;VO4(yoEaK$JkC-(=nVV#2m*_@Lto_!b?>{cRTrx9L}4> zmt=EZ@ceHFbBRVo-1I<@FUjJ(3g3~zd8(*z+8> zSVjpXd-RW2Sk9Mx$#BME4w%0MbRROt%*P)g{}=+@6au+oc6li!YI~}k?TWEvyCcb@olIGo!pWWW*pEnqP4;;Q_wnki?vJrqi++qH}tn zkB>Q-^cBxerk>KDbH??YEGAfg&KX29;O7`^y3JI#kbIHGei3gm_}$b#oJY_(wtS(p zg;$TU0PPJ`^byt`KeZ70lQ|>o_~v262N;!>B8T!K2%k|)&f@k^JK>aNLtm@l41HSI z3^v{~IQT0iv}Gy0igOSC54HXRYO12}N-Md?n-qsLM_Nr-tBq?W#NIruu0en81hGNn z!TM&%5iRzAmnYz~ZbJZIr@hH2o1R{~AMO^mY;l&SkY9w6cR%4Of70{d&?kP7%brFl zR*>qho)9nvjjQ3f#+c$;T_m#`>rJ10`7#sb)SKjl)#c1{^O``x8Xex&HpmH2su+Z& z%AF}^AU2?6J(7>!$ZV)eSWP+zBdcbuzNzipc@qkRg5)dHx4NuS?wkptw?J?U`rEXk zcIHMshLlzbETQX89MfB0hrRKIT#S%q`ES^EzyTu*Mxh)qb(59izYY)cxGzb zV9uG`mdOW_u4EP#ObWuoIb&|+Hu$5hX$m00I+p)V$@?@rcDHZE5r{Womw zQXIPUY#P~2zA5QSnfEt|-A{{G!2&r-RfvYgBPQHt$ka;^m*?rm8fe0>sdq?q-(g=K z)+ldk{D&xKg$dfpxO8j%t?YG1-%~s^CUUB;6xW<5eplt$`0iB(Da7WS+i{OXIAWDoSa%z z2-gyUg&~Uk?03zDg>@T2*Fb@b%`G0$Niby@ZRSbRIA4o@(=MKEHF^n z)2wJHk=pqHoh(SV%>540R&}46!Aa3*&Ip_ycTVETdvk4Hh>7PKF;XZH(9sS8xwH#^ z{Bzj^FMzSBR5ZX@L`>F8(xal=@|@1r3(Q;_(MjyEJen>VBaEp~BXIR8YY`$H=H)>b z;UTNEC-dACQW5HTAs>Oq8n@C_GM055!mdJd(Z+o7Nw_=LDqTkZBx(ULGDKu1E{~i~KA1GQ+3!#rT9MgtR!Hq#25n)8P>QNl?`3bi;Hy3dL&=C-is3?<& z25E6J;4U^J#!zUA(oU1$w^DQRn?H&VidDYR8>FH^;*_eQ!A_`Sa4K5HAfT-D>6Cp)7x~Rf zZ_~)Ef~;n%u&&vEGDjV9S2{Jtgl(matbFoWaD z+*LZRY_7Ffb%|6v^2_~nCxSgIO&PoU9Ls@^)5P+hud!TY^Y5pMAWAGkpW$ek?qZju z5tysHv=2R(?H4`2l|>M3)<9x|!p=3|7O9AYO4;q=t3Ag2Mk8BKy8iW~xoJJU)Ze)P zwM6TQcT9ef&Wd*K*`}N^2SM_*n{l~CY9IlQx3CBLm;cxJ#@p@ro`T z_0k+{H;W6!B~CWAzYQcqDaFBsj`|QsGb(DLs*ZWPSx)58yPmwpp1d30U&7xX^A>7F zXUX5<--Nge=k3crupiTdB{|5kKE5OuYsOQA(2X>a(7(`^bC&0lqC9zO!dOCKU}8 ztDHp^RD>TGQyI|id^NsqhO^x~R>VAeU;>_JE%vZ`sm-ah6MIho9_kxgpe>hF2n)0~ z0Cc8koMnvG(F)KCRqG{Y8Y-@N8*a3JTQ{)q{wh6JxYU}by0Va>gORPK6TX?_ek;N2 z)M*Q)lEVW@n{Ga1~JPK ziHl?U3}1qw)hfWH7$Te?uQ=$-L6ldVB4)*w$CrI?U-VCSju59(k;-@eB}=)O75+8u z0~(33gryMf6h_-UJ-6pI-kv8FC9qf;*gF!#=Tgx?U_5oqVm-(11vVZmKAE1I2h6|& zGrT(<{h95s&pACFnOx~a?KvF~#v5bW7sX1lfnxi+k@Jtp6B}$}XgA#wFk%O(beVeP zj#4#!hM|wk9R^3dl#WSDJWuP?m}u^q|#CMH%eD z=q$2JMWgWSO)8oC8!1Hx=f$kVXqJvHWw8f?RFq8*DJVLIWuU93l&Tx``amhgC>4!k zAE|4R&|qgMDcXJuQl;oy_SZM`eCurd)`_IbHa0E;#esc#-0h}m13$~8i$!c z(JiQ<6&<}5g?iqjq8%V!fH#T%Kie#+tloY2qONLFX|O){(Y#P{6ndp`4cxnvLDT_(#j}xIi}_ z{G>k0_fT{f(gEyHk83D^QoqRa% z4#5MCZ{r5|n+YEJVSWSOaSJ!Uo-Y{=Pj3WaBT@Bzx-V%A$1u` z18e#$t`6^jyX9C7*9;w>gP05V8OUolu8H9zama8;IPh2;oIzYlw!}g8wwqN* zk125?67cX;9K%y%JHOe#tne@yF7qoF&k%dK`E zL%8|vf)XO^;7_5?IBpXbKkNjr8Qt2hZxSj#)xv>dg{*DmqtHl4zC_B`q;G|`f!|2a z2ofbA&977IJ*Lgni<_8!My-dEfu?1PN+nDURNnx z88&ZsE=`WO?vgs~7bJ7mXfZM3PLw+}Qi${Uw9?X{@~leKb_1Tp+zY~Ox;gnyQQxE! zhg6wLM-3g|G0n1j+kjPImjG2g{uzG#(;IT!tDZ8>50Gx~D;azTwpd5X88opl$9HkT zgsKkvn%tg0k8A()ILmwb3oFbko5k#J(h>__YcT(iPF>qaU1`-lWxAYxY>>Z|-i`^E z(_6JaZd22s01%AwTeJk_o&D)&|a)Tvzx#!Y0!;kdjF|Lgl zbLmc3Ix5wRF&$NZkC?i)K}xs_m&yyBpd?k=x5>0+OIO$0wb1h#El8t>j@C)GY^j2a zJUBG+tL#W=Y2?A=NGU-no9?#;p7oDkU$3kW7MUB;efQxrv&>tbV>QjVUK7>v?BU!1 zG-r#OuitAKt$x#|8~0j7TrFPLe^o7|du{Pgw_E{l)wR~91k-zlyq9~hjM{J%L2x|#@N?%zKU+f9w%If zo30zzu*EuvT%C*tSL4k)7wac4Uy^jmk=)y!0#XFd;jc7Ot=~`uH@+$DgIs#9O0PkX z2U#;{Mg1oknW>iwCU{d%Na^~DVxu=H0V)9L|CyV~PsR<%Z29p@`jdE(q%@1`3Ic?t z>rgB1OEsT?d?;AtEq&36TpNB^{+rwagL8z<^7qRTcwJ#uqfR|vk*z!1p48iJgDP31 zJ%!=97;a#OKCL9#K3#74=DSv**PIa53|7*0R4@1^-lWy({}+wcd=PJ+^OPT#gBY?O0Fz% zXN~4wgM}ZXCsE z@SW=&#aerUt^>G7hmRaqX*(s0ZUK%UEjQg_hQpWB%yK(~XRT}K<+dW!y zssOzR$J8#ofFm7Uh(Sx;!GSa-LKm+3a!)5nrP|4vvkHQxgFU5Yz)cv=AmBUdH5HdrmcuG-)xYzhTmx0cxv`?Nl8qL;PmZO?j1eyWFrA#fkC_^y|*_PA%)kXsfztq={dX$&lzcdIoqDbcKxuUyYTS^Vo}mw ziz)q$$RV9&rDkxWJ=TH|*N9DZ4gSiUfN^x{WFz@R222D3JM({)Q@|@DhQh+%e=pr0 zM59yU@%*_xp(HklhQBgwTbtav;TsB zmRf2JzlJCG;QzbUJ4F4W1(HQ+n}?`nPWdwjpcEIkBq*hJJFUM9X-5Tw2kQv#g&97&(2zf z>OR<_5z~}ePvS9nLXb~rWn*V=!n@rkpsWIybNCz^eG08PHXOO`2V+{O+U~2yMTftX zWf+xe440i!k(FcisSXn4qwVzM9EdnJA_CpZw`JvlueZaK{kpX{Dj2b&A)5u5|~&4Uhng$p`YVp4ys!#RA8=jBFBJBo-8U>&<(z75f-7cKG0I&Q}TS!bMC zpL)#DDrATKmx;3L-Xbv$I)EO2;njH$Y1DZ-0WaUjB>8=?x*ZBFrpfb>U zCwMChPx=2bo<=&03tu|NbcG;mIpt3OWPBzf^chIjz_$RBpzB+<#^Oxu$pG89$t<&e#5uQ!v=cQql60y}`;~vs{Cv#+_=$QGxZy8@|>F zr#|R+FS*EygY}_=w2ns7#ljkYqJR92Z>#T*jmLr!v-&6HZIox+=1UUsg~ORgXya67 z9Vub*|3+^4gX6`A>4uzzVg&}jht`Cf#zk-mZ(Aa!x?)vw<`Lcvcf>8GI5+~Mk02VA zBy=KTi)5Fs_bCj{Mq1d~En!M{KD}bR8&jgwOw|RTY^&`xPTe{-b~mt53Kr36Ed)6u zr+MwCwXP87TCA&57C;XHm(sKCS+j~n+w7eeXQhjWXPL#9pU7o~;jyb9jWwOhdNPJV zf}gb;Ly6c1;5b}}Lw1%ilB{RL38$2h0F4bm=z8tiG-owGft~j-xG&|6{&X4y8kScZ{kPCFQ0}7cr%XFcp3vThr_s&1Kl*O)02)t<58F2$xY+WWu0Vh1ynZ+N|!tcDmsD2T)#1;bju$QFN^Y_5J(B z`teKjmf(P@_k}7$Tle=^PfEyOaa@8f7UP#!Bx`y!<0GN6c5ZwlH{L&b3@TcFX**V}t8ZN8i|4i*y1VWu@3}Ir{mMABS@UgN8AX^j_QpBO7OvuHJ=AWZ z7>iH78y5}nk&qsTXV16e{NK_=gaGsZgI!Kct)?bJ_{DQ|L)_l4J?{%{eW#()BvQvf zs>D8u53K~xcIT`1%8vM`NL<@LC_oHz5kR#W&daVRAt zU-~}e!?}d@DhoTerKWjPb@06ehn-Ggr*{No#~R2vBGUQFgK>7epiIx+abmVu*1l() ze=qfsd}aH$jSCp1rJR!aEqWF!0R~j@c;h&Liz*c9TakB^pSunE#siy7VbkBnB7CZU zBUR9!w?{#}N}~^|PVJ#_{zgj5{Tr_DTR)FB`cy6Nwe(RndB{XV)Ygf2Y3)&8-pyt< z4?fECGnM@H&+=cS4}G|+S}gQbK;Xvzy2nDFd#;A&aN~!g$pNb_M?rHiQKGw@gxiv z3Y(Sd?)hnIXusRx73Iw#J(JM`cy(wm80ShB{gbIl#Ms(m>~AsHm4>RtC4e23$;l?U zjJU#hV6u#%>^V_p5Xs4j?4#QHUZFGj#E4JxE>CYDIAWVl%1N5FQO%%mfJ@xV*4MeGsBp&kqwbT`^f)vx6`Wy@W(#TYIDR;y3-oF&tv1!K&)G$qIdq5dv zUvyCnj@n?z&XAaSyqNI7XtR{2$?|$`9*8ZYoIJNB)7o%DwhaYGmHt+ejK>6TndP2H z<%Ex=kiTw=(sfPb<X^c#rZX zC!b>UkL~f=K4v>n0yAH+ zzBXAa?ycPr69;tY02F7#m-0yk>9&H}xWSWwyk6qG#V6fXoba`l8GRlrKYush@e9sU zGst$wx&tj5zm}FXlg4PnJK{CNVP*`GUIFKQnfTb=)h~3wgUQpV95JzGP8ecy(BnwX zRyjXqdBz*$roZOD!2);VGxEDby_9al!z~DxQ}aQbbQg}qYYbTGR?e;H0LY#{@%mm$ zh`5Pd#ILeGZYlgWbh7^fUHNGo%GQW^8c_j1@HHe$t#K@xUMnzqZPcog$A{k`pa?uEm>ssmcrL=_?t7u1c0ed zU2bHI4VPKmn~_syTyl9a8KU^>iS`0*5LG8xMMlwI zF)BiqM|_!)5xMXQf3PDT-?Pv@*m2u@!&@L@RpgDHYubi5R3e!W{}GlIV)#dt!G?Og z4D@b}CJHYv;a~oUv(&Q{i4~cPDg>5osux&gT78%Rga7LT3UY7fmRXHNnA$RpJ7l5# zL*H2fbGm?FD9ecYIL-_@*iU<`FDBA<5B^71P-Sc1(*%nuJJhfHZpS>A*d+z7ki2PL zUXqj`fE8>yC(C|xNobbXjo7g+b_zxb&(p>ff7UrvEf7Y%Vt4|;p{qd5FTP##cw3;s zOF<^2u3Ip>C#_z@i0Y&>b-T>`H71=?HP*)yanZ?kiF(0=o_Y0qO?|i`M{BK+9BGuy%}GuDZVVxm=|^2=s4j%Mq(bBZleGfOUGfjvl2mlyR<*XkZv4 zVs0LJcb4+zb|F}PIN?M})2Fa&+I>t;b~9?`g_qpHa`%eyimczw@U;~}wAQZCQn{CxMbIszc&wD<>&m}s_q zS%5~gk4A#Ei*SnOIviH$p=3=?G%gF_mxbXAeSDohLMR$DA@OM6jC9tcdQbn3#FaSO8p+LzaLF!ISy$ZJ#k1jZ+>^?1U%-k83~$f zj!K&Myvx6fV6D+JohyEY_dM3Q;${4I_GIAK`aISDnRL&^tO<$kp7dxKX_sf=k9d1? z%M5fXOviML|8}Z^e ze=datkZWQ!vO*n?CDZz(NDKYcQH?D6BfB#$yvZOaH`jhG$OT+@S6`QFQg6%%m%+j*Dsu>8_gzZ_F)*RZ2ai#M}HO-1#xty6R~Tvq_)qgNCu{2Xs!%MF}Q1EY4bTDw+LM9W%j3#r)~eyb_U#~Zg+qYTm*3@BvyIo=a`G-Vo& zRp(Y1WsKTTp>a!mx6Fa51(joP%o)z+zE3yQ=KZ*f#q|j{o6fN`PpNNHY!ht%?%3uH zRR_n6CN$bE*n%7B2CEfV)iibl?23);O{JDNF!OnDQ^e}N+8c!K;U^!wwZqutG#z6NYTxw&?6 zxBoy5dujar7~eR8e&)ycI%{g|{<~_c?fzA@bD^YB$^*S|zI?E)u~hc8AC=WKYier9 zdxJ()1jbx9Ui6>oB-Z=#kIHiYt=P~Lcb!_U_pdr7)jNhV(oaaaj>C`G12-QI5d1%~a0wGnsUn-YdyFL434950<Yb zK7z0}_1$p5qj_18)WAKq4>r-e2`mQ#Y|EN>`flq6W&^B#X84~&gYNcUgN-IK+qlPS zPC|0)<_ce5@>x{F;J^;cqL(-}7qO(pes#LNj!cnnb}k+=1jj5*aO6}VLT+0Q{D~Bz zp@v;1|6PawX7aB({5;oT@~^w8b2?5zrrlK2R_=ewY9>5pDPU*yL}-B1v9s-^HkWq8 z1ANmi-RGm@99$U3%t>fGdEsPm<4MGiumODM34P$MraFCKRZ}+Cp%1LlxVNz=b8 zdgMgRi-ES3f=>TKS=F0WI~BIgHG(r?hEPIFyen}8A^9@o2$V>%XmGZA`?zI5hH0E3 z1obL51A+8tjn}IrnW^1+F(99QGLt;J!WY;MpR|7-(L0V8F3XrxD9v2ZExJ)d8W)vb zvi%_3|(3!D#^Z_Zb0>1 z91$GH@exEQT~M$Kqh?SWB1Wu#B0!!$jo7lHN?{4KfySZY z4CcvZqG_TPRMn_A-A-J_**8e<>`t>SqanB~=3spF{vT$|1h%H!?zbzkgmbQ+5^DFW zT0doi#v!qXFIhiDw*FbgxXTa>ucQR0<0V^3TT4>HUd5qir=zK@1s85He@r}dw7&W1 zKw@h^%gIMtH;dX|<{%05GGfjp!rF|&vwbGj^nRb|sZ`IYOPd&A>b+6>kZ6gPw=8|X zA@+hM*ua;TVB{EbopD)?)*wwBuS)t_b?d7R*-pAcze3z%j|p@p-ZMO4Mz~jODJ}E% zI>VQ!lh($+#Ad2*Uu;Ztx}zY-!RfuHK5^VV(*dH?6(uy#lD>-8VW%lKiQa_wI}=N- z_96yuV|^kNXJ2G>%3z5oLVlVGeUQ~Pp>?zCY41j5>t?M~VoPz@)E`wfKbMIA>YVPR zm96k%3fHk`==P)cj92&2_1x3w1Cg&aC2)I@328-xM(pQ=Wq~}91am92OiWh%&`y!1 z6JrbsL;(%dXW%P22870NO!9MLIQA*HDXPa69gh0W4kx0q^~v9)D^=~QBTh}c$9v;x z<%wWbpA1Y~b{L1ci@!{~a5B4P#yp6S5s&3UMV z7{U3)lEg!sg&4)r#fh!{EhpLD8H{antA9iAEisgg%X5Q!r9K!Rs-QzexDuO$dA7M%pVAElvZTjmT|Qrxz7^zPb$Ny4MFA9oH!S|3Wh^{7O6l<@sV z@*z>e8Y=cvF#0J=yVm=nvNfxL(#_WyIQAg8H>WfwCgORts=K22Hhfv%O>KMCDRxM~ z>$j1$7p$e5`&VMqy;9A&?~8YdZ0a8{eC|f=Pr;^7s1s5QrVAEuCx`(i%_Aml5t-C} zQ&o1;$E3Nh(%NwGn*jY3erB`=IdbrHpg1a`t`D047NjYAVXB9s1 zgAH!pvq&ej83f?<$*SK(^yu0e>wA>I9 zJIgpt;W&ud^WuD9wXKXGeauogsa@)ZIDnnt`5N_9-SR?GgX3i-B!&Iu!r8kO_Bz$- zZ*f@rOp+_gTe2XQ53k+scBfOJv2j~4ft?f`uww~KpioH%`-|@LK>|O?&Hn+5*O&T`jFh6P;2rj-?(pFJ)-z9G0Emi)lD z!ve62_KZk2?N-|zFYU{zSoqvuU|5Dvu2Y{(9W~`l1cIWGvg@@^gt(aUb>XTAi9Jr; zJR08;FmBEO^n^GKE>inw6HofR+83EBgsZ2$ht;Tqdz7i%q+!QPxL9?-7|4zDa_!Wv zNkU?HMOP)X@%w)XT`4@)KEefhJ_O-L8laEpixq*jm=1a7-{F>wj>J&icv^Y02rWJe z3$Txr17yy^x+cPtg!w2?#?+@|k_CiTq5gC`6x}Tq9c~kzt;>l$Hnpg=HH%-lv0^Fg&wr0(Yaj*QJb#tsUdLJ-hmTl5Osfn??6)BE zLOM%vzv07|qFsi$V>Mp2)pig2lQ0*oqYf%Mu zC@1)EHNOoCauFmnr}~n&`dXoFBnm#NyosA4*NZS9?e7~81$R2D# zwe=lJrk&()L-%7i-KUdlH-+@YR3WqW5C#fA#*`G-^g2i->-i)eAsmMkO#gQ9of7KW zzZK6Q$PwGr%SCr_;QWp-+AJN{Xk*=B5~oNC1&+1#eL|R|(YC)ge)pRyoF=Vp1l{dm zMFFm7K!V`O&LpL0*9~W%M40^Zmh=ycb!xr*r%hWpjZ>?J`?K1?Sqem8-ea?eNe*b{ zajZFOq}A0W!})mU4e0sjy_J!(=q)r$n>7N3BM$gI%b4V|4nL$SCnqxtR^l7}atFON zrm}S=1(T+Nziu45;WrOIVW=ikqjorh9#)`x;j2aU|r0BFf8(pw-jMs##;>LK{X4RSR%@2)q$y-gX zXKo-UQ_*)qq$FLaNbR0004dL$5oj2)6EKNtPfPNIl-=9M10~+&QF?{i&z|%gZFS&o1%j zHR?=+GEP<3Uga^#KHDzEgbEZyZiv5*kTYudU2-6ba;iGK^dzR2QLiIaO}+R7|7p#r z{cxv7xq{2HJJ<>#=l~QYF`jJ<N+!-T}LvjqtG zW(PB_9uUa-68wV{=OpvuyaF)2kga5atSp9yB_anN?!?OrEL_^cPq+X(Ux-XiYulw* zO=~L2mB9Ea>MHz1ZwlXWU5`~ZHAv5otCHaTEp@228RO~WPR1E$hVu4bgIgEl-gAs8R>-GJ z^)on&yZtcc#isW#snb;|p^8@E*Ylqe?o&+Qe-q{3U_QU$f4KV$$mdK7*FGa5uPOI< z6eTXT6~7lIcxqy(va-^wS%Y@DYF3 z%{ug57p}9M?kwv@df`@(R;1pfb-E3dV=X085)JNRdWn|#UK6Zq=+(C_INcG}LV88i zVAskUhfMg7;+_>Z4mt53m_atUSDKO>2kkpfX?N`6s?woNB#08f*LO;mDu-4C8&)Ey znL&);vb^!VjtNW@dDAF(MUm;aJyaIlX2FKG%`#*O#%90q`NmkcH3{=*CQmoM0fG|H-{tT5B~%$vf+0g-H)`tUb( zbg5sUrJ(l?wwj_Yi4YP{;Lp<5_1)8g;~CWmBfR`yE$Mj<+n~eNBb>b>h__-~EAFiJ z&(%2^1`i~p+Ko#9YyZ#a^>3?_?Z%~e<-V~d>QHQV;=c$+5-N(-0o-%BBv=r{GDyP) zh07DfB6zF9bi~;2<xz4n(t-L$EOU5-l)ojur#9<6RT0f);uo}JZ zZI_u$YJ5CuG>Ko{p)Y($KBgw#N4_vU%kd)0wWoJ{g8DP>%~srFeNH_abo4W=o+pkZ z$fv11B6!fq^8W-}0BdDDTTh7TZkj7oo{!~UR&eW0&7*}n$dpZmxWr+xq3ED| z{o6IJmy%L5w7B*=y@NlqV}0Ev4v`l?29$?;qyV+(&HRAEwRKW@zke+${g5 zhQR8fgy0$tPMbA!1g7n@5c6a#Boi9!`Pgw?P4$tjF*F^|TUyKr8p;Wp;68plhUwpL`WP@Ckt4i}i@`*%OD9+=SR>VmK2OmlZb%wUOx zNVkQWPSLJE2(I0pv~m?WkHW?$d}{H5#)zW z;nP|!@qpC-z)l^mZm}bXUn{pa<0et(*f)e}i$5fT@`XYoZUYIV=JljpK{sxLD86#4G;9iBqqM?a$V0;#AoT7mBOiR;SBzT_3U}t@H1s|G+S( zV)g7y)z$B^ey&Y-r_JtlYLw=y*Y6m*IH?a37fn^Za~IVBRlp@Z2?Co6u#kC%A}$yU zYK_xN&Ras;c1SpGDcPH8-?~ig(;%!$(L9Y|o3F{*i0js= z+KL)yMP=5|iQt-(qbGxpv~|zugno0o%yaUp=uyFXMq@vH0n%vSWjkNWsAk_i4_jtL zVOufV2g&siqwt+8tZ!pjD!6 z*t1`*t&W0}U`F*X8(ye>1;AW;fhqbKce_izh7EdpRLn~n;oJpmv}j}{u(fs}WH!X# zTmVeqX-z@i`}g}rw1v`+h-;0QZYFi={x(QSkH&%N;ZcGq*{4Z9t>zv26AH6U@~CoQ zl;qRVLvSEE~p!j10v?VsS@~aRC&I_M%*c5d;m;3(QYHULqVQxu=6i7 z2}(xDrKuLCZEhH3ix;JMHLquKFTf6G!3|swH<<>cU2?4jH>w@1T=l{~+GXamSD_vQ zJsInh)VyA7_lX|r+rZZKsTU&!2-jxg&HUPB)k`?yKr>-tyUZ0O^1F|A+8bWgc8c)G zozzA?knXy6Fa5kL!k1n`uqniw!q@N6?SVTKCA7-ssha$qeI`Cwff!1htmAZ?5ITF< zv0pe#T^Id*Osb}pt*Ke$?_NIJ-G5;SQ3U$<!EdqTcaNY zy)`vHowN}f4Sl= z<4fP3$Qq)-NYR6tQ-f{(8R>~6pQCYsJLe@(=GfD0O&~JD4^;@W=O~PTgqL3s?zPop z7sn82W|z`IQE)b@s-Xgi0IlTvR4~rLkylvE3X9c(=pc*pcZSRs9-+wvf3D{)Lp_84 zH68`_F-w95kuaOiA}(fAJ(mvSNB%K<@%fl@AcNoqoLoKOaxE&G*?ZGkHTa0*o)U8dh)LjAs#8ca^aueMlv#(5a zx=nhh2g?}qGnbw2QqQN}UJetTvr%uHgSsH*;piINwfVBsNd3^?DC+j-&Oui&;{)q& zUb=6+haUW`k%AgpkU%ZKMT%}Yi#R+#ZiJ`mG9NNemBV4jA2QoD4Ex%Ska-Z}FdmKNJ zd*Hak0*Y?;-dP*03ysskGP;7ylmGRq;y1{9eBm)RcZZidlXjf#eb=klL^YyWFqw9( zxytj8>BUnpm;(slwm`S#*LNzT51&RaRs9ORG~VP8>TUC5mva$d&QvQ_`?g~2A~>j|;69MQ&}R32H^ zaVB>v_Q+O0N+*F))ilsA6kPBW(9Y9-E}ot_pYxhDdY)hx zRgMzg~h|GI3JeaxQ8jG36oTz zC4tQ?Mr4hE!(U^jsY<5#B9F~=V(MWPTQHw|u1gJm9qw)4Wyr?UUQ-PpjIs>)=(*g!Ex?Z52CbS|kY&G0j%ts1`I3IP3 zoKB(^ZYpx%Kh1ksRi)rb&%;+ymRpVwE*GOW&ctWR(E+w|J$#kR#s?0YKPv8yoP)f0 zFn>N))kf7~-)Gp01a9j6Z?2nTD4BaT*9qo4$o3{Nz$HCM2Wr3QMayqoL8s8a zb6@WcMf5qZUPibBcvC1BI_TI0%_b2pKT@zS81n7xZtlB(*+KojzF4# zHB4Ii3`^<(LP`p1YQqNr4sZ9fyQ&#qiuTr+;wh>h{dCz&C`=ahiP@^(P@7QL96F%* zBjP}bSRIa4ja-I5Kz4$*md;n-LVVTE3fa_d{CO^pA!^zAuQKp?p!DjyEF&rQCA&Yk(i%muhvgED$6;eSw zUjRICHt)r*0~f$~c)^e;wjraQSHvi{XZX8Y7x&Q9Hvz+Z+;)RZO9oxIz%MHh)m!9!fMSB?mAoIq_ zr`Rg)4}hal#;EF8Y!q~*q1a8LyN6}LgEFN%%+E{;h?rq$67_6h6m*!R9VaRe@~V=? z1m$YK(vNoBAP=mD)#LpVe3hKP+=rokY>YG^a2A0G6L7>M*;Wtdy;-Enh6tcb>Fn{d zz83?UbjhD;hRM(1goBFblP4QH7Q)SaS>jlb*^NO6gq8OM6mVZ^8 zhpc^+4%`6E^{N-2Ra=;+dH@T43Q?^~E^f$^zBegXbEWJ3`^ui;d+3|jH zY0%&qRMS4eltT@9>L`A!uMx~EN-kQEaP3n2+1rSV1v_eNR4e9Jp4yV)iP5hlZLpH7 zG5W~?#g#$0=vf~T`0>XvL#aVSc&^LGMIATcsUBc}eA=!t1?Cxy9hu(2RaB`zelJF! zlPic-Vs|1Z#&$VrU6y&i9afz4GCPhXgScV_eCz!LOrC2wsGcw7a#0dVgm$!Ewz@b~ zt-qHIw*vF!t1!Y(&=e$QL(bffP&M^~Y`h;#vH(<~FX zL_rcrGI%jzJrWi@n7~xUzTe7l)%VkiOJpX|+}0#hs&tG=7HG=iOb*7BHG%HDM4t(& zW3rPMIRt(H4yeWaH146o_0n=(>~yzel3pI|Ua%bLZ-)jI_b1~7elH`!JfDPHV3Z=; z_U*)#5!iTWR03nqt3V^DeHIMhE&Y#h(csgkfwj0k1CPVm*3~iG6q`Rj z`*Qd189-r_(LOasV9-wOdeq>zN(xUH$8SSli& ze76>!{xRHXg70ekXxb^9$PN1B`hY<+!lfxU$?o|6vq`(FLxspC99)sEtr*=p>=+e_ zNLs^9q2^wZ3G&rkG_mNtj@K@vu_M=>9mWtCKmUlhW?s0RKeV-YbgQKhA|O}Jy}mQj z`Dm+dCMFzs=58W2)^{l&BFDe!5GM}O<`e3rmS`r=-l+eIUrq&6{6<1`UlnXV8 z_fFtRYN^PLJ|ANWdyseJ?Fg%{gXjUv?9BGjKC{*r%YZKbe)WXasl!9D}k zvKm*c55P3%_~>{1pJ95A`d}WuB*IJ(VQQiw1OW^mrofYipAR?OUZ5Xbuil3v#!NA{ zkAa!E^R6}bcn`z@?|EJs!@U6asrHe3=|*-VNTkv-MhBw0TwJ4eI-l)X124{Mj5`Rh zMkso8@=7%qiXT|;aUab8M@QdeSoCq(Fe5XHHg}LN0U=M#Fzy<2B5;gYK^sQ=xjOIR zg?c(1Ebl-(rf2gPS6<}Rk775wwI@q$<;SbK``@ZEI=1`|b!m70x4JyX?$rhH59%_C zbrnBSc`;s%2+E?&vq!78##43R1%r%QW}%khhpa23zea5)wDC@6Y28wVX@LsOL@UHo zvuDRJm)#|IE}-_Uyw|?N_v-v7Ix0mvD%IA&|B;Ss=KK$BGe7>{+NOQ^$Mw|8Ijz(2 z3@*FjPQxymDA1jEr@wIaJ3)Nq0uF>uvda{;4agK|^Cb=)40fO^qmHapBNeWi5kz^X z+wlyH<&2KM?{if;MH4$`m}ImlxMlvoA)hgi=D~Tb#xTh|gx{lf*M4Ic-TWabYCOpa zt&A{<@vH=w`@T$_g>=ckhi=r(8-|NkI7QdNU9y{XzR9hVi_Z zN+~F=e8_C`UoIh#EOtW}=NDgtHZ}_eBE~s39b->4E2O(9>(S}xRaKij+8-ThcUT2S zWoC6HtUse+>>7y;o?w__5`!wGJ?oe9?(}r29`TnQ49p~Ode$4Fxr0W-G?)wuhN(uw zbitr5H^lfXBt?W_OeN0u7oVLDoh%;;_UYC-s`hZ>c&!HoM{{y@9UU5`aIsJyA@fro z5DY#v%5(po@uKhpoQmmI>yO~96&xl1D;)D*?~UJ!n|`1P2-350x=BvXW33xSf@Jtd z`*U+a61U?jm(bz(IP+B9rs}#5Lj)H#dLlUUq#A>u!!V^Q;0U%g2C{O6fs9w+KS%1?)uk2PCFv{Q(1jJ>FBsChM z9_Sj^AE^T3k6GjJduC3z&Jw{!%6wo2NALg)gd@0g@BtcWT|T|uAMr8~a_$JlkFp1_ zqYcpD#vC1qJVnIkBKDrM-(N)L(COHLTEnQ0Q=Q|zUne;B1NEh_$cjMmp~_$m zv7FV=AOFZj43P@h#1jvo?r{TpG_ec5p^P5xe?=x0r}tP9hZ zMd$Dy9+=h5zrf^#{nw+c2HHd&oyRdDCdRy; zF=H^0xuBL^xF{PG)fgZiuMoyPeHXxUMWDn1uXQ#-6j#pI0C?_G@NHe5P2wH=DIUc< zrgyAOn-;He{5}4+mo;a{pe{N8So|@z;Dhhrd2`Az#}_n4!626@7zoGxvtGXO@RzEo z-xmD+?v5{u*CrPi%L*R4t3NviBFsOYcHAGrwu-fN1$VyYGCY%q3oeB#(AlcbzJt{d zgO~yv4;xhve^oH)s~@UTBHrPxy3vZQ1+D+!GF&0UP;P?EOSSiV=so$$3>JL%#A94Ik4{$Bif(7f}**))bs zfs*2NF&k2#mRP(=R-R3Aukt{4(-&EO*SN*!?SayL4Z)4x(b3yGzS-1}ylU42F8XV)`)2S2&|JdhhlxNp*8f+Hcvax4hSmv5F=ycPsw4tl~BA%v3;ye4acf{6`-=)l*1~$o)RwT>pkrI6lZIp%s8OX_ol4W|)8#K5IAyM5qL@!k$<9D6T zh1QX&7<`!5gh0uyb7K`3vp^%i(seWTyg2E=i&r`v#cwpRxlc21&nvU^v%RIv8u_Xw zw)Zv0a_X0sDW!hDGDEhGi(q{Y>G9EX3ZCfhh~((jAR0f^pY!%~ z1hV#X-|ssa+<65ai1szxf{s2>`pQ{vp)F)ik`oYR!^wYs*V|oe z)m{Vy$v;)uA$GvqQ#Oj7K^#JK&kwstA~xSB^HGV?m*bhFZDQXb&qVQAnolGpbyK51 zGWdulAE%hVA7Ud5{)!^ovQ1O-ap+$$Zo6*%2{lJ>NU&{()jq@qa9~`BJ6q6Ua7^*A zSC_~t)`_jLXW7M807v1~u?pf40&--TEdL}i*s3VDYBl;~44W5p5jv!IrPv{pf9Md` zKgJXZq_e{*_p&cyO6+hvg`+YSb@*ycJ1Lo^R41x2Hy3CExNp|aU3Mqu=eV=??_#ZT z0-`^?bFOl)(%u&|H&WlXLthpZot>Bz|Ljjjb;0_xKi{t5#Qr5Y>rG)Pem`?h>>dPkZ zWz=VMtfjRTu%?Q6G|kMoy=BPUOaGil8-+YgNe|=^0ZlTNQCHuCg_{c1u>8B72^u)8 zdgmrLWoe*eQDx8FXgFk38D$@^O?!o@ECsVxGs0A9MQxU@l&y+q24}JT?Fk_e040P~ zVHp%Z-psQ6G`^zZc$3nSFj1H)>$72JaVG&*PzDQ2c&PQhwG%DW9YnZ0vI8j+5(uFWzTLSWAxp%1z zUwQN5`g71C+<1?FOqYotG3QFPpAExJS1)8Jmh^t#XG{9&E*V5$=1+%JHQ$N~o9LTX zL{3URa=QtE(^yMhh!9EDSV{w|EyOhByrPw2o}nMDOv$F`TcU6G!5)8(G~jIr)**Tq zt=>$Y2WSztHb&pSMR)zlOEKSQp%7wdwj&q*5h|CV0eiV|Nz!Gns`GoOIo-h$N4(<1 zeY9Q;TlJ&1=mDtAdxpHVWl=(fdTZ}p%0lu_U9LP?Uy-Iq*btz+|JLlTdh;u`MsODaqrR3y%D6{ajm-exOrl9j%3I%ifyrmajrps<2%P=kwbc|Cc8PBI3^(xTcQ7f?^R9zDF-ZG>0 zvGBXig&GH=S^hq1 z$DdY5r8RL(e;XI-G?mSw{REt?Xvk-vIpZ4fP5d?V62q8dDJyynofCh}ri`yoOqbyj z04Stg%aiHD-VaO_;>z?Z2s9TOU*CbLVO<$sdg(UQqq#;ZHq_Ty!Oky#ALAjk zoO%r+#r`?7-Xj0J!Z#xpCG4d`N$)jpQ8q7Q zd>RA@Xycnd#jNLT5NwNln!ih(oPRsz&rvwprAt8|v9HaOz*@E#NWj|te4QV9?O|m- zlH#YZy}1lpdVV{^EKw28aM`NHX>=J=9piIx8t)C{-RRSI6e)spsQ-bWGY$%ZGSMks znE*Y^R0&e?ctpH?QB7DJ#BJGatp7bzqpZ`Z>WxZx5NyK?az$xa5Z&Nx-uv`~h0jeZ z{+qh^N;j;gMES4zBk$A7c7@eTF$!nF1BzYLZ5AeruDX`eetzB+ya@}5vc*q#Katcm zLzHd#WabwozPdL;OO)yHMgj*PEQ*t@rp>K2m5{lj{7eoHhl|@4TJo$1Z{}C2M)8b# zag>VDvHqaC=krLt&%@T|^c{l~78sEmm7L%F)#)i|2clrK^?o-Xk^agBXo&&R1rc{x zc-wP{XJ$M!<4n6W>WPjpX49tI{F%rGn)a+Aght!JsE3j>x&u@7xzx0c%6j_N3%f6( z;~&XMPV>HvEXVfri%sb#&>$+chL5&u3~X{j)@Mp?FZ93+P>#?TV}RA+ z0CpyD^&sO7v<9^+@T2YZwYO!wy{P9n)pJn25hfS6dpaVm$LQ0eaGrHIa`c_xy~;~* z(T(xXMtmmExPq3#!-uEG2jh7k45uiEu!k}G>a*;5)DS$+$g%t6oHo4Q-&LZ(9h_p6Pagem2k)azO?Y@sOs=4<~@L-`U7sbXXY6|%|q%ROK&~sme5b|?Dlpw8y_|C^Dv03qTF(MKJ1gDqfQBi<31#21vODYYrAJphUs zP^hL-8>m!9V{tY7uacCdB0WpLAOf<0O;2{?YF1b@zD{|)P_n0R-pUokwO_X0VFc%mTmz$v+AhRK71@Nf zQMSj3{58e4CTUEuJUp4&4+s3s~HO3pEum2lc^&iZ> z16lot1_!>xN#sI(rD`>fBo!52b<}^NWbPAiB4XLo+`75O-jcvptzr;VsOCVF&AEv7 zP6YdFY(^IWhH9=%V3~^gV1b2E8+u5WNB7_N>Z98H7Hd#K@wPY0JHt6Ty7eDAnVzaYS`e7DpDjHB@ zbv$9y1rSburg3*vgENmxHVUnqTM|DNRlyandv$p+x)ZB)P$pV{OSExxXJ`<^?%rJ9 zd-#8^XaBV+)iBs&d!1g~*!8QcH@jESmV{dNTT%zmP9Iiv`t6rS3gJ>{FI3oK?d~8a z0z)>kPF7No!E#Bke;33;z7}a%X^loBA~1{2b&6UqXZWW)D9W@!7vITB+iV(Ou8}19 z+MG-KMo1jmc1N|@#WuGI^_veQeF{jqJ@|&}&2|>FoAI3X6W_hpY5My$-k+ z@2$dq97hwUw?@+oy_Sb%dD4QN-Y2PLy+vLoUDsdvBpu?aR(Z$2Dd2!g-n(2}>tOcu zD0^f}mTtYc(Cz7oI%xgF6!3g$%q(SD+4|Ynqf_(VvxV(G_E+KT%>h4sT-1!$?5D%d zAFK}J{O#+as-@MTfNuRY6|%(@)XV0^t?xLFjWc%8JWFv{GqbZO$05pL2|JLGV$s+s z&d;C{u`eoS1rI7EGuo0Myt#eiJ$R0T3-Z2iAs*Q)%Zoru=92gm1A)eB38Px>$4h10 z;))f)yj1?n)S?{B+Qtx-VP*64Q&uHK6uNIB>?wP3<&>V4Q>?3~%0uq{OEe7vjQM9D zD{=t{1-hgIGDB*syQs~YNx6_zw8Chl+0ZCuR0}3WE4Z*#uLp3CAf@;3-lbAiETamW zbn$0XxEVb^ozk2&#riWUh>OR&-*E3iM#7m*eUowTNFYLfPA(nA$<_G(HMyDz)?Ve& zk}36p_9>$@REiSey5Z0hqd;pRjX+q%&e#vHm)z*H;TyY}?x$ERBDq(8xONe*cv6IG)Z>qb^s z5Qu>>TfD7q%(F*Qvn*@>e7+~D&H514#fPZU-GluSd#LdY$TdD9TFE3o$<6g5>o zHC?xcGxVE3^cG}{9sQRnxi6w4u?DN^qW`CUjC-&juSWD-jj(zmP}c+f=+S(vSn2CW z8XDvM_(#h1KtJ;6M_FhzA{B6tES&R}F=Q!hHsB3C7w(*9TpWn#8Hi~96LFVyfJ)L0 z@_0usz$*E_cjN<0q!6-HI2(j3kQzbo_w!wjJeU?C6@2$3KjgDTh|4FPcOS@Ui@=2* zp)(W#^ZF^HVjfzkoPBD%3OUp9{Ld_KnNU|L{J{d)=)pIuwU$!!V1m?)jQr*Im;g(C zPQ<1y-CdA#jq?Bm)&PhNTNWCPk-Vdf5KPM&10PIdy7BT1;8WszitHRyTwjAw7EGx;_h~9e8m3vhz{0ogLUpQ6BHj=W>MDa6rNQY zS-IPfDSGnFl8h4@Vhm-&Y``Ep(WF3_dZyfu*>p1b$m_`&+mD<|?hpx?F}DNRw;kzE zE-Iq${mF(W4S7a6lYcTf-;&JBn9P&OcNg9L8q@!!jQc6ZNerGlL_(a{ZxS0(YDJ#T z49qWO=_4CZB}Q8@BD*4J?Cj(d){)YY5j{`c)tP}W$vMf$0#ocu8!mm|d*a2;;3qPf zsmYlulL2=E0q7)H_+M)EA*dH)XqC-HMV;x$=N3B^Z&aqaGsDQ!>7%fu$Z#U2beU1c zl;w#a&=ypOsxz~bGZ!S6F5^W`DKm7IQZuPARkU)v!j;LTF-D$Ppsc8~lqiyuoS&L} zqQr-+533vz3^7O9A_4+z^L+mcvrzwLJx`quoMc3e(v-5i6GtCFW*n0gUS!b+FxmWL zOpGFL79K5X>nt=WsTrV$52eo#6~%z$bg``Vm94X&gke~Rrj~(O7e%pM8iF!Xx=$59Fyp+ z)6qlTVC;8C#1K&I8cg*g`1U@bJG08iI3tAAY zy7Bp%s?OJk;bmet*@@wUr8$sMzmYZiRPgqvF1!)k`NpUwSUn>dviq)y$v3-)hPIA; zQa+Jc+z;j@Q$z8HUOrK>sV&(l9?{DuvbcG)FQrjgK2f^KmMko#jow#?{|N1AO3sCT zX!L)i{r-2BH(u#{tQk(Q6APMO<>&)wbQ*$Fh%H1D!pm4-V`R7LIqQZ zU<&3tb_ENk`O-k7X1v<&mjG{Q{uztcF>QLe(dxkr0Bx+rUdaf zJ_X98CY|`JO^L&EocJ4?5{qXIetA<6Y}!+x2W?7DiNWu`h`&EcQR8`*_&YOYI-X~U zzey?6@SF(zeCNj)N%`r_E*T`W)+y9zlRLAv4>D|pRYk9q$#|M1B!2KFx|$A^+VhB0 z;qD27L3~fL*2v%yp$et#oNEc5lds4+dV<io=*29_1jF1y>3&_*kuUpl6Xawj_XLeq zwj^HlG_59L^mo2wVU|Uu+r?%*qY|3ckv8Y6g>9{%C>NMVnXLZQ614YpruA`pM4Xkh0(h+ajXKVBj8M@9Z!f}r)|O^k6M34?y1LMZkOVU z#N89&Ie;q`^?>w>yi2J)!0i8=j!pWQh4@VffO&#qE@N&#(CX)?kky`WRD?mSu;bGs zZ9#|py8PPx2IS*T?y?9)yW?`PGp6_m?ja)^+77`CnTg6|Y|SJXvK%2rDOwcp2d$B) zwnKgeZQm|#u_>c$)ylDvt`H5XG9oStpglhj1;WJix^w%7w3kIRv^Vm`(| zi(YX>*r+X-LCB@dqnVjumawVB(JU2gr-JBBDN3UA|KwGm4|TKI+}8=ZFV9Q9JRkxL z+Gu`w$SRqMg$Ebw5^Ftu9FS%-BY@L$zGn)flWDcn%My-Wimm@aFBu)}60TNT#SF0A zUIJb0fdDrqBBNP2`+Y}GG2i15O6YuJPD7TAqugF(afM=_6a%34AtvVC$*5;KrhEj#8H^=%R@>fPWdgnzAkx@U}1Cv_b#brUHr1+lQI3V zg>vItIo3BRXHzH5UFdK$%=$Y@5%Jg=w(LJ9=K>F!L|JPaeRw~^hertp7SbG)HncLh zXl>C>ZsLX*E_~xea$%TOPmDBml*ahpi62P0$gcxOUlb}DDt6Chi(gicUU51cTQ6N| z<@WkDHnz-VhyFv|z%4#`$+oz^KIM&u{v!M0)an3H*j9xLb>MDW`+>CP3Kx;Jb8?;x z1NB3;UV7kRR&c;TuKr--6}%rj@G$K3>qFt^x1WnR7g8U3V7`R&uiw(x&rLZO(z>Mu zuK}&c+WOChoQUl_(Rh-Js6Qs=sX6(k1{MdgyXPSXH_f(|5^QUC&tr#CL8Prxe6OU> zO4~v4CAFq{#MWkOJ;+UInFsAv1_C@i7g?WrARU>w>8KV7^;_t55;v{BPJFF9kWL`$ zkBM*Djg5C3MjEak<07w7skVj&o}1R1-GYFE6S?WFm6Xt0Nw1Sy4~j3#+kSVqjhpuM z!LKOKNZTPJH~sqZYZ=IKy>0|w4jBvUR^fHx-Os;1hOE;M8PkuY(f5&`Wq?e>4oTX> zgu@8Pz)ih2pB;2C&=<-$d5MS+oi+~}5~hzD6Z$rgk|tMdtpOSkRPRQWQfwwOP-|M} zWNsr^gIw;RudQlggFinaqIO*R3DaagnRD3J(^2f16C$cD&ntj@@^qdt2!H-~S}j(A}8BMG_{;%!S>L zDi?)tk=sJHKl2r(? z)uQ(d{Q(%fA*@O zq5C)8T-cL(XY3@$`tG+y65yzn!%c1>yy@YMhwyO3g6cQuGoS1(&3->Ec3)06H+dm_ z*#3Ba=GJnPY#YD*-=E~`zudQ~do^ErTC9pckVYL@zqxorH#g;4nmCXw^{2V;13jT+~Y5kcQMu+cdq zn8gUkrN+E>42u>Sx4rWOx>v!4;{atLUiRDmcYRTRAEseJixCm&-=2l+^~`hTV3AzW!tXm^7=0uOHC%f79Vd;rujy0 z`;xk4H&MSRr?9ff!cE>#o?e+o35EsrN4d!d=#h9kxNJ^qGg`Pkr*v5{{MMDff1Bef zuVAZkHl>}7%AvvilQ0bKf@jB0q+m^Ct?~5w{3YgW3N5!th@k{5INPs$2nNp!U5JTT z`6!){bF;nMw?3&sVywusVj>L8x32^@hHXoI0*YR%Vfl@$y{o)sPdv$UVTIYN-e7yT zjHhn)Huj?@C+96+c#7?<@p5v?Yx80@G$HTWRd2FYzxCy#T9pY)=N~8Z#((k zy~j1yL3-Tq@zAu*RYD-~6Uh~DQY!>LQO@;ZCgSkKez^U4t45n~Mq z{uZTReWlZq)as_UZ6Etx`$b1jI-PB-zZX-ae(OK7_pGs{)I3QCn+RKpU#Xdnt#8oh zE3)T{0(BM0=q5NiQxQV07D)PL%>;J7uuN*n83mSXaOyzjhLoSPzOd z`2{^8u_-E^P(Mk6u-+jrO1wy4gqU!@>j;#*MntQglIU=OgmJhBDCq>?uIa26;rh1+ zR0k8}z4XNf2O~i?Nxk1bo4T5WJiYxQS`pCf3$#{J7CM5Z17OufY*p|dpp&(_r4+TD5;M4Fe5Tfp_yXUIt1mmE|!qYLV8Kf|L z{29FA?_N2lTkA@Ht2Wa0#rZB4flH4J?-SvPC8g$9>6PG%?=ti6e)P_n+kf;v$$a=n z?-R_g+qhadvM%9y1-K} z;m`B@9YHctmk_8+H*s9_9$iGr)KP1G2x-tzbRT~wdTo%k_ubtG#o#=#yKIP32ec^l((~sALQy_x?DlEA+80TyF5xGxq^bO`f zRVlz}(}&68_&$#C`Ud&yp3r|iWJ^vY>W5cz5>T_jRAoYDYR6Ig6AO7K8+5(x(&ea+x#TDk(T;`V2`Sccw3q6bfhh zQYcJvr73+G6!;llZ7a{_UoXL71XJ{Q(+tXBCT?s|R4{+Qmr)a7-sF|(qlYEq9@!bg z0?t%ue*$Iu*Sxl{{Uz|pAO4TLRyRo2>vrj?ovN9E;%4o68BHW>;!eMkHl#JoLB)7%tB z$ylYJa4C+F19x#j=eeqtFra)TXFd;ed!ij%Hul8PS<^U9iICLBK)aqLWZYfB=w6SS!x#(jQu>g8_r3he{RW-0D``G+Cghov#AR`Urs zXK<`Cyz$+{#>&LHtmW>k6%dX)cx=l@{6e_dQyCsGg798(4totti7iHw6l@{G7`h>t z6OyMezy{LX^S2SF$>&cyk>iZFOK1WD@k9db!j(l}u_*TL6Y3SbnxArZYsAvhxV4Y= zZ#^9GW6NQ_e19u1RnRBY%dvGh-bFnx$OLbuNg{xABx6jl8%eCe(f7ob3Mmokc>PVk zQ%}6*R>%q$wibFE%N4`zia?_nc9KODODf4rB8IVe`NMuT(~+u$t{8cBdl`|wZ|>X7!_ zHoM}XiNU?>43O9dGj;hc7neS2>n>_MBt!;`N7&Ipmhq%FQ`~I`&!0am=Oce@*Rds(G5BuPfq93ShHGu)E4 z6a?HjV+wY0xkkL|(^r>zVqxb_vuQB)x((E^#i0qVJKu2VCQ$#9#7?)OUMY$RLaF1A zRE4#nSYJRA*GN@9)=5tNkv%rhVJlz?Kck7cG3$OS^gv z=UXvo{<$i+jrP@piDktfxOYECMOrF!#GCPDVD!ZkM-ZqAmg_xy3X+*Dkc>uH@(rJE?UG zBniwZy|V2PdGNo|iS!7e^?&ok{Ix2|1UR~j%XH`gbq-g<$ zFJaYD{F@2xl+C$r%9=3LitTK4}&-^EL{7ha+VZwxzj=eTNmh05|u2`qPb-03KTr9z>}LSSEZgQ z4 zC*NA+ z;jASWC{b3GHK~6{0v3^AD3W3A>M)uad5+W&VC~8ZH8mP$Q2eEl(hQRw_xv=z?&G^5 zia!NHt{M`MHPX}TbvW@#%##qMTFj!)F9yRwjjs)lb*X=B<3k&Qt2Vas)i~`hu^_!o z)J_-WwYR_*l+C9mhJhoKnKn~dhfrEpWgNuw6pI?T;vmZ*1LP#$Lq1=Ovwn^Xx}GUt zXTm}p?$IpValRiZ_(i+8dU@T)1~G^% z?%#r7@EB`A2j0dW+&N6|*;6kcHjEw{G+@H$RzFy5Il?dcM=f+WCEYMO@ZuYU3ay{s z!<@mx$5dQC$|bBbOgYO(mi#)dR6|CAzA2a}>}+jW8R!pHWd_pX*S;(2li&4R>oN64 z%{NuN5BN>`*Kj-{_gl_jIg9)MwqU2oi1Ndj007H3{ei2jrJi9y%a?%=C_I4zf#4?f z_God_KI%J>nLq7^p-H^te=1EEjeQFL#3K|n2y#J{m%0oq4c@cxv(8h73iu6QlUi&b z3(lzfojH{1PWdxVGach{a_G&*OC~ddila^PnL%^<@dK$ti*XLjtLEH*98eTcr9f-a zQHNT3YqhZHWoj#thj($j`h>5{?FnC68ddg2Gj3+6ckJ2cz)_&)sg%8XvtaL9Ff+f_ zkKUh=;@})i7D}Z^R7yO`WwcdajuW<9T(8Ok{PM1)E*=}_rMh$qO?UhnyInG9#TO*E z6dNg86u&#s>Munrj30PZcC3NsUEsiw+Z(UKZ~r4+?QitOOZRj?y`E}{_D|0uju5-J zn1Z1~j*D)keLqf*jPi+eAvp>=zmAxh*JrEh>p+|fFsJal{8ZK2+CuXt3o%^OA*ta< z)kkOXUkc@+KKJb-{VE!NqL0Mghp*aaQB$(25%9JB3mP3rc_Jmd9|b);Akaa-3N(ZK zL3SuJI4D=r+^30p4LLkkTtw zisHcLCPke`pztU5g@5Hg!`~7JALXsDi;Or#P4LS4p+o7EuW(C)C=5bdcDOw%>Vi$8 zVQyf|sQpp~*(9u!WK-z+24%IyRVQE3G9Hru5ptATS*oF{O1_~&b|*it{Qt<$z3-Y( znfx&n6Lr1f|4n{w4~6(=Z9ra*ALTUnr|1_WABXhi;{h;1KE?~p2UgDVLL;6e7t{)k zB+HBHnzX*=KR9LmotArGKsG)m8%{Y2Ym}6$LvfEl6P*Zv4BL&pGHgHdA9=c}q%RH4 z?-Q>`MR?|-`Xi8r`^Z}iZ{_Q}Qk6ivDk!+!5<}|Jh`xN&U&=QqOH-TbJc>YBD%ACc zTlo2J(oTWAV|cEwECu#g7%YK4z6^IjTz^=Xvo&;niZJ^+Ldv2UT}#1$UowSsU5kQ` z7Fw@2z7*k@e*O5SP{>xvE1EWj{t!V-Z6cDUr=6|lBLzAh!xgwVF8ELuFF2g(cu z-(b)Dkr0z?R$Y_P*EDU}w_N5pCO$(pYwe-FCZqT?sj-{_wMjOHEZob)C&&`j5ipSRB zB~D#*<=N6JZe4$;PU|iRcNS1umV8PTB+6XDpiu0l#L9t7f&`_7csaEH@SZxT!x&2>1 zxfB+)8hvJybR-F8xb`V^?WP-MjvPhvw7wI#c^Z6)w|MZCfafoH^=7xOG?C_=m>6@XSx}YV2nBnbJ7k2s4@>L*IowFgD27x}$YJ@J7xUS?>H= zmaxd@VXa&saCf&3SAuaaPJ90L*Ql_x^bI}QK;4fu?}Vg8JmRqDy3n{}UVmf4=y@;S z#TyF##XFO*`&@&8a^a7cT`HSeGn=l7qZK^-FeTPsI`)ltNIdYdYa=!K=1Z8M8=6?L zQFn-6)s2}0Bj@Ju0v#TEB!?|o_}6~nGNlXpif{04j|>|x5{BW7H@>)V=L*r%lovJI zwRrRO5_ZKHXP0f{RgU>p$u*go#%g4g&3Hh9*VbZ$c>|EvqU z(~31^CDuHu#;n@l6WWktGZVpBb!KihwJ%jEJ>pCJj?7~9dFpoJ=7#A;^VGBa$YzhM z?)3=0Sz$F(jYC#rdNRNDLs)1_3z&HskIdQ|RjGbV!E2XMp~xW{g+QWW;K|3Ntbo1i zW84!`p5cx1YLj*tgc!575*JQ7ExoZc^!#GPyE@)K^J7g2sPMqA@xo*E^9x75oH9S) z%Xhjtd|`+`KB~pH1o)2<)?I6ygr|VL2S03@3mi> z&cjLjSLb0rA^5lnB?0eEUvEm`#ZlyLYktlIe#$UwJ~QR3^!Y)(?#~3=qt7EtmO`3< z%y)bckK);+=X>`x4k8a;q?;f0`P7xr4e#Y(|D*=_hzaXzN_8+5lgJt`cj-)7w0^Kl zZA`Ibjd=L*{4ZCW*Jn{HiC^L82+<@JMd*;@k>8I8^~MrmHz|2Bh&<9}%X&kL_)UC| z_r>@4&mlO^?9n0v5U*V!$WX|1Vs{AK?#~vLJU`!=PlI8J<)x(|Wp(K6mhHpHe=6z+ zOLjkNK5m?gv`O!>ftRX}@A!Q)Bp`L-rz<4jr#4QOaw7yRnfioZby#u`gFF_E{20mD zNwZoQ3mOV+iqZ%&&~QKrC;(QY5&i%g2}A+q2YS*XK#f38MNb-^pOMy)*pt@bj}a6> zu|hhF6%t{_N5HKS7|httBIxI3q~#se31_av3c>gm0*r&bexUc>qY?D7p6JkKaL0yk#q`3yf3bXg=gy}#YPz)@d94mMVGSW8P6)WtS87uga z|BLU96|N(WgGXwFMW$FmxSKJ*-=D_71O5`#k7cBR3Y*}!IzCn~8e;|M8`X$g3ecJo zD{O0qj2?x2O>h8v(ZDu@Qw%fLm{-I8|2pXLkD{M`Q75-;%Mp}7dtZ*29OpAyW@`l6;n?O$j^&`Ox(lr7+#{uE# zYGE$o-w*0YU@-U)Y#C|MP|JX0dvt;vR1Jg!VSo(zMLCQyZYX0%z;g`jtAUf%8X*MV zmB78w-)M!jpxzJv-vl0k*+I~`pt3~9_Ph%mAk30t& z3CaK&zyWeV0VsiR;LHe(unG1mz(aXutgsNz6P<*A4F0|e^YwEw(!!xGpNcdBj|VGa zg;jTH1Qpx{0UBWEE3pEFe;s!3g550Wd!UZ~TdZ*ARiyiCu|hxC3j>0I5I~N6b2sds zL^_5eyil0&zF6V5A2b9R>8+kLb{AvmpwoaXpv3^5!RN&ut&qMGXPe&zpQ}Ot$k^O! zlqvAO{~tQx+rOo!Jw7)hZ6>f7xUFXF7H|e?4t5wI1N<;M2ebDcvAk|9%t-qqkP29U zaX`J_|6KZ~I$;{rdB889!mR)}kSm`<=GHQ%`^fJ)>L?BoG+ z5$=AV3V0Jh<%ma}8T%!fu`T)e=O|X0384t z4fF>#!H^qq8$U~{fOXG@> zjw{mB_M@)42=o5)Q7%Dm16q6=0we=zK=~g~AHhu))H!4po}Tsy^fLy;2_ul-g~&Jo z4c%yaO}?9|FgKQ-J4gjqn}l z72qbofxl277SI6>$k7Ojiknpf`;k`N1eh%WH7`{H4M?>p0RD zc}jt@@e=fZi z1&sY|H~{rWgBW|-<@f)9Fn26uEC*$`Fqg4q0~vco$JpNY{r+{?s9(SF`?tUD_s>Il z-tiLDNB#bXCNQ?~F~&Yb#j>d4d#vmAITX0K85}w5N1bz2*^WU?feRj zaBhlPh=CuIVRmu3MwkY5g(Xf{O8U$=fokv(u6SPYJ`K2YlH#Nw_MIh3rVr0g)Twc0X&kZ5g78VvOi-B zpg#b2FM#@h7U1Fzjc^$>4{j4a(+QJ6gPuVd0zCt}gP^_)ng+TA@B+p2G{PsKufjZe zDZ&80ziCbrK|R1Hz;z&D8F=rC5E5@j2+P6$V8}ZYX0>oP9rQV%23XwobJ|hR*yWHD zu>SEl;Uo|e_kVK;GYP7_vFS2$EL>#J)q&% zIAL~9oY3(=oN#7loWKKfXT%9RABqze<;4k$VXlVWb$^^7Oapx|PDll2K>sE59dMrv ze`Z4+3;!npPXI3TQylq`g7sPCMTB`6acc#g)*T_l!Ymp5vL3X`JzQfgSrOrLVW<#2l_SW-$6rHWu$Efod{YD`e)F6z?)G23-ko&HPDlwlUJjy z0xbaj4%7*H5%g8itDvn&Ti0JQ(q2ZmEin5W7zXvRdzerQidJ7}%~qk0+ksw0$8)Q| z=dHWa)4=y~WSK-T?{FXupr1Vf{*dffgU=wS{qm0IV&)@_r1<`UQJ#bS<+JUO8QQXB zmcIaY7sBqnl3gs}Ay2;qGarTZ4Dtce z=2hq`5JqbtZo&cR)kv#}uyYmaW+dAX2gQ*&et^0dYKSA;@4xL&K%M4+{!gHvf);`P z3<~$N)vP0|4doyPyuXC{cAS`zwi$E|s1MW)x(l=k^e|`#D0=CL3oUVnhYxn5%z%e; zG{yj}2ag7r-3Eftr|SS60NMsR6!bID@t_}o-Vgc)=wqO-fySdwMX3i8*(~Tc05$kV z^}}KKJpyG>08)WfvpdtWKo=j47gXp=DuC3z7(ccBlJ-d@@)|JVlXxL)3;Oe~pnO-L zKeZZTEYNP4EdgxcAPOaLAMW&qL8XoOVY z5#R~jPKvWeDSe( z$?Xu>n=oD@gx{qW*2C^rpaLidT!3eWT6pA|TJTI$3)kb+LM!x%!5IGlF2{Amg@r#4 zIsyLt{2JN@&?&$+U=MHxX7!+BUd1;+eLF%p$07xzEK=yvL<Ye9jE}NK))7<{TuQt{<6^aq>hUePKr#JyQL?slK2E~u3FS{g?eEt?3Mp3UdRKI zfpT1(xE!Ec)3)`lu1#hFA$>7H- zxWg!nq3|%-)#*$DGdaKj4p0Ir(&HOP-vK4yN57_HL!^-GjuZwXj1KV71MGoWILwM$ zdeXX&VtxUAo7tcAq*Vj0FUr_UF6h;AiRVUqcO)XAL3hIbL0~J?=K($JcL3c0`xN88 zib!FRJVEH$8Y!p|p9Gi>g?TF6goDNa;l!e02ZGc;Q0{*(zVP_x%i>-^2{ zUsQ#@F{ooJ@T%Xh_zL5laS4Kv==cQT5zs`?^`Oxc5`=Q79pn~v9iIZ907n4yDII%& zTECy>p=j=iy@7cX@Hzo-)cO5e|AD?C)M`KgM&u+&^GpnG9I$(=2J;gD&3kP{e76BR zf&FU|gfnmA8?Xx432Xu?@NM}r@Cda4TzmuL6;L(Mvm!xgfqo}24JZc|0fYaNAS8fZ ztV5p#*bkHgTc1H00XbEKb&Hk0(A7f3%H?bAN!bI`VeIzUTF zk1)B!4zJ_GrH^q^@6Ko?`I3Cf;ApN90H z?~vY(`47^Ah8=|dY2*`72WUR&mmplygML7I%x4%rfFAS-P=@)Woumi-iS*0B&mrhR z^FSHK%l|`q(6>mx0(_Gmbj*j)uf#kOr~|Z?^cYXyAU$a6Vdz&ewgS`vx}Wr`kS^VWLkWzGM!1ob-Rj9M{LtgH8fcHH>6w-sPAw9Kun2e&s0FSA zcYT3z15g6A08w9J90wEv>w&j{Gl1+XjFo}qz~6w6fDT~bDa=a&OMopvBk(#4cvVO^I3oks0F?N6klW94$J~*-NFTm944*VP+Lj;1@*r%rvC=xJkaNX z8NguR96;+aY&Y7;fBOB@J~GUSItZAfVLyQa>@w&@zyBmrART_q0u}%wPyx^!BdtFy zZpBe*bQKdkc6MU@&u_-@@JuwD0VM-~ZY%m>u`~w}3KG z5B#CHY{6VJ`@rwN2X$*IKHAh04gH9Z0)_?e{(bz;2BlM4HWWi|;*BZOkp#?^udA_Thg-5E zVR`I0auGx>uuUZh`&SjD#&USj9sYjqrnn@4J%rNK)s0n3>rrrM?gh*+1<~R0F zb&IF_?0@rn`#pX3j|J?9_cD5v7!^N}T#e%jPINy!j_=>cXs|U~ZOZQ5u~5}bUf>~# zXZ*Mi`y+Cp`bFB4b^P7m`&lpf`Htl0kGKt_pn-USrw@;_WaD+QU;Qk+CizM6sQFDi zs=LJP;2hmAW?RFo3w3JX(!A zxX-6(^LrPx#jV}AP*r@TTkm1chnQ)y2KTbJO%AtC4slPWtuI5g1BdjF^L-eNYj}L~ zX@?JDx| z65mm-*4|z9Gkic;DSz&+kf&!bHba&FIZX@aq6A* zA2{~yZRY8g!@XN4##bJnC}sNKrU~8RL<(x>O5K#+l+u48b91w>^6#cB-mK13hZ=L%~?Ji~e_I)_(Eek7(Qq%Q23B#(ke3x=xcb?p&d~--thIWvmbCf1z z6dt)7cb^^C;6B8`Yd!a3QDlN?_pRjgaFd4<25r<&rfqn2A13Ugy$xDh6^o)nSt5-(w*1`e-GsZF zdPr~kOt$J~b&5N4(e(98;!AO5kUcZsvpkUxwr9?AXFd-9@hkkS)uqVK+c9UX(yE$e zHPg-xt4wdrEQTWIRF`$mG+t?y;%is$v8rqHm*srcmAhHv+dVE}M1|5B^Cx#K&hp(Y zi3(SB=Fm=_Aq8RVsIFD2?)EKEx;a z%wLgv1M|gcd^rnzyZyGDS-zZwFnnl!6u-ciGYd-ZrY@WLeX>|^@Amoq++Jpjn6(~{ zK}uhJo;RC4OK__lUX+kF(=4VW!)1ARcx3l|F5QWy{9?7!^Hy1tB-b`>B%;@oRk--OYK1NC zfuJHaKasXS7Y2vf1~a?%fdTVI2Yo*PDTs?Vkcc+bYqODp{pG&?T-8fR!JO_iN%q{9PW zqR?gE7LCLX>@=sZYy3MVftIxR121Q^x7@7TJ?(@?=G1XVAu*KK<%)gvz9K{05JSOe zDodFk;{|s-vW&MZusJ54Le*#0;)5jls>3&r%1v-LN;j|zg3uW`UvU!3e9h~6Jyr22 zld9-Dd(cwCx|%)p*xV==^^|0*Zo1^|tO$2jygSR_&iaEps}61|^p&aZNR>V^$es6q zJ159dIY^)PCw%y8Df4QHsj7RwyHLvq8|6k50-(0MfF(CBN%^@GAB|K!4^7cs@5HXd zMM^%FSKhC2XT1f})|Vq(+!j~0dS@Kk4Y&Hqt(9)|(`Tj(Z>p7bS+btS2IU+j?BQ3n znHBYqf+CALJo-UwNOXqS*$Jlk{&cRbTHP#pxiwg7W}enQ&uXtw@PQu-YFx3*C$!+oFEJXfI3ow6obWXq^{MEQ45W3%Ruvgjgbpeeo29q&v{5 zJt;S2T*~7t2E&=_?X}2mzCy!M#k$%&PWMUYF0RdBfb~M%MRcd8d0<9N>kJWd*?hbk>mRx zR^WBivhoV`{&##|$(+IYMPH7p3x0Cv>5)n&zk6+bl5TOQ5pQ2SiD0lX5eMdc-mID( zMk~%CO*bUg#Yp)e=Ch(G*}#s8N;*@ExQLJ89HU#kGbuK{XsDKtZKa11u(P+i*_(Cb zFdv^VtWb}B0k1hkdt9;a(%Q+ZT1Q7zD8`LVm21}ofqAF$@p&;%;)Dg$3b^gir`ZYF zZ+9u(nq8aK4>`SAj#1cz9JWi|K6IZ`7N$*A6f11n2i6v;an~S1Fx>SW&*Pklyl~jQ zq_|L@*H}BVv-x$Ll`4GfJG~Npgj9uo5>?>6&$IE`l7IV)v|V^x3%yRH3GQ6*W@TH@ zg`fwrs|M{WAI3)x?64xRnf@F@r%UNm?-b3H@=hb8g%uin@y*9u- zKJR5N^KO=N>Be$pYi>mTL-wGZdCGYYEkvWInZ9BT9(mq8;4%B>GI!9E+J}|=aGV%B z{@IPD&u)k(Z$K8>I0arvdm}NRLvv$LRn2d$F07i_y5Z{^6&iOezx|!Nd_l9sYh=B; zuzhCh>fnZ8C`wv)1&JS%X^|HB2`O?~%1>^t1}V^58iAVz6dS(3QC8WpCL&c+Hj1vT zu+%_|PB}}eplj+=T5puCF&Qaaw#ozb2=e3Z8#n+^7s>XfCWv2=dT;#zoC*8#M%lZq z??#B9-`H30qJ5r}zRuH^VZrTDuN@nPBBuMt4WFJ>bxCJ&PzVb@@S_AC<=l~+JL`WC z47|nv_Dp(5f%5*r8?VY;>hm!tjNJN<6443&dz|dd=U=IJaTRK9H0znU`Bgcun4(Us zX-po`xPzL)fgN=*!L2ooAv5b9CeP|(Lh2rtK{2&*hZ;mhhlK0mSZiftU0yI*h?CXj zQQOhLuMP>B*&GwxJc}GoefMa{)tHd050T@)$0}NHHnx1e<<&}cNcvO~6LL6vHB7pa zM=Gb4|2MA}+yCEr#q$eb_IGUJncUwpNxZ?Gu4e(yb!tO0NguG2&Ol4&hX=R1b*p zH}J3sHaMemp{`U9jTvjS9tdZzy^`%p7&YnngR=r=;TFzz%cxjVY=8V2fl1 zlS4QCMb9hE{0-brV-BHj=`f|MRiu0+$1AiA@=K};wQFqo`DRT_qlb3RWCdGGTaq(;!^IV7E%^m)FfD|DbgES<^s zd5)A&edzOi5_p#YJn+Or)d&A84+uKI!{|O9?(O4YR38tf|D6Z0aOfADxBnVPf~D}$ z+<_h`q38H0d^!$GK92%SKt{T)@(V{z#jL zVvML^8x$3|aIdV?MQI3rOmf*nQDGQ8Hz-{AFfKJ!F4era+gbNG9Tss>2gq44nQnVg zKq)?d9oJeJN0hs!qJtXngly<03= z8#%pxM8MB-C;Zw%esLtJUcYdHQ7Kyc{6asY2uB!b){IwWDeMOoPQ}jI>v63Z+8SIU zh^O+Te&u82z?IUH?G92W#U{oV**}cQq#VQFr_H>DDFiy2q+%+RCO!j`GaV%n3tY!= zY9qZkeMfqd;fv1ug0=VEdX!2Nid@otUltW!;b-DSRJ!jvB~FqFg@mZ!RVt@hN?Wre zl)Uol@Y+P5hf*9|+=)u6d<>#;_nq{IKkDE5Bc=qL50#ZyG{|tB!T;($?2dc1Q-iKw zQYCtpB=1>*b44ySq~bK*Q|`i8Aawdy8v_{)c~cjEy_(Y>(K&;4Ez9wIT2* zPl#N>_tzTmD)AD&4#C-zh+TWZl2Q_=Tr0c{(^6=gcNoGsiAb{bIWNE}#Xc#_0q zp@1-HN0yt(G9RO#d`s`S+cud_H$HXh+EQm;>VSD0r%ly4Eo7uSe$B|4^dtDXoui5l z2ip#PguwaD^TufP-o$Xdqwb&Q_S89i9+Cq%mpYra0Po5%+Ay((LXoc8n7T}L5rYlL z)x6;vhC{nhE5T77xwIBg;b>27qs(V`vXM?9SH04fQ+Lg!L{ZvVOgCgJz__@F{L@Ra zom!i4%BVycNg5J41rjrbflZuw_LMgC~g>`T^9Ma zl~YY(Z=1N1MXV^2%e1miJsq)h%cqk#pK^Y#@X2%Blhy7lx=ze3pW&NK`QH~c)IFJ( zOfZ$P7K+>zQT%q_Hle1zfiabMY#(s?&7E<%y`aZdbuW-i=aTZqa$jS!htJs zeqSg?h5m#Tilr|UOJ69qYj#U-DD6KtCB@A$c@yJC85Ky!eQ)d{Y0`Kd>&8WPE^|KX zbVe3gxy%i$$i^LdjPZ4JV-!nr4(2yac6ZbrP|*bx4^X(cJ)%vnS@+qq2Nu483I1$} zmq?hNkgIpeo8>`ua+R1#reM_~~eS>l_TCy;ieBrC`@6g+*r{2nZ%O7xWq|bV}`jt1}!)dQQN^bHh@I+^_&SCN} z`yFpMvS+f8H{?l!Kgq&n?)Q^utxCP;E=X4|2^JFeY1S6g}hIp-Vl~oe2 zRUTxO#0#!#gRfcdi1%C*k}&fEab0%bHz^<^vJK-Vm>m)slbsDMM)6aHbUUJ5Oeaf3N)D|L=T1c*l3lN=mUu z!*T@qMK4u79B%$^zt*bSfB^N#s2(12@KibM7Rt*I1 zB(fQI=nH?zv;GD-zY0vgKt3SgQ>{TvwX}CW1ogtYt5dxQAyr|1<7z$C3#Nj}rqc?W ze2QtCFz(%?ztY==#KLa!AXQ=YDomdtqh~pz2HDO0^rswwe4@3etdT6YUFr68)inn< zM=DNx*SE|emqp~#DrF!2peTKTMK7POmtH%Rgs|0w@_@1sKFYD@4ae-iQ-o0<%yX|2 zH&U*p3nHEomqK3=mIql8Y!Kr8_S2ig%z!PE%w#dsh<=47WoavD;ws?nRH-WYXU(rpuDs@!Ktw`K)kd+vF zRcZw+x~Z^{svZ-q6o--rsE3=lDQ0uT)uFnvG^J)#q>LxI>I?p4l&^TosejCOxW8Nf z=)*bl3pVe&%cp;2Ygt)M!XxWwvQg~50zX`Gz40-9bANsDWA$=iWdfQ%; zj;0zZot5Ix^u4!Fdi?kmnh}d@I(9`oPUd*_cAt~O#Sd7Mb7#}ws>sM4N@Sg>F*~c1 zVjk6dgY*wlFjA^irMAPPq|{YKS?%?ar(YLukss0_W+xY2ABhD`%sxuqoTdSzc!Rz> zxftgp8mj0cL-Y?)82Hg+xD0;Oh!+EPg8S@HsgZhf)b)~@xORwZNeufbgkI`6je39hg6>xO6 zY26jEoUCtM;Pk0r+v!s~^W}PJb`WmbjlFJgIi1xbLsN_iN1DOD&#N7$F@&CVdLkYT zUK=@dNIh4ADfc?O6pW?PGQU1fzHnb6rjzb0xf$Ncq;Uqrabi=PeAQJ!pPZ}@U$`%@ zD5v*O+zf->8KT&awK482O)ls>SFF4Jc;ZX1$NjJhi=Gokg^$(eZoG**1|n6-(j{>| ztExAC#&-^V<4+hoIr31#y^|xkk~4nY|6D;PKcUFeC*PL{7i0CSzQrwauwQZoyg(M_ zwO1bHzEtSHR+u#}i-V+@U*11UnL!Y^JyA4@ID2W<`(Xph%wRXcDi`%}!O9>M^N_BlgsUTdhF|Vq|dgXNh#S8+U!gL0@%&=4|6#rUNmV z=V^?YQ+y>=X_4==$#>08Z-ij?Z!7rom131$#ckb=x`7qnMD^ma8&}Is2mQ&V z8y(BS%h&S3w4~5{98+KNdZjaD=h{(x%RD{~riD$%5eP;~c!dw0f5*oTH_sQv=5%a~ z@bPg)aap-RoR1IPT2rUuisJj@>GFumly|5)t7ZLNS9z>5qFRYdWHq5l zLzPLwpLM95VxfcG=sy(92bt|pG>Li02`3vjraE;m3uho25 z&hRUTmDb&|HeR;&kN0&{M3hx-*;=QOJrO26+qn3NHLF#qNLz~X-`(@X8f}u&reS0L zI?bZttihVeZz%(7ua*OsA=l2q(~In5%a7=TLq;eBEV@XARqu%$vN2j0bOpJK;{SCk zlFnzL+<_lWfJ^;fRja?q7Owrd2d*u0Tt=2OS9`=sGBPCyh1(_nMsOKzYMGpwcZg;tw5knKD+w=jJX)R#}_Ce@ynpkH}W- z#g28}!e`Es2T$Q&U>JIUK1pFB+`(wkJ#coZ0yUSvkYPO8#3=rMby63S(9i}6_KoQ|fs9prc}Sx!|p z4|=R_&?CONlgP{#Ff$E$%rrM$x;x$Q?{g`>jxmvXy?0fePlI(zOsgl>INHyj^Le-G z4Xmy?4!4)RL=KHg^xm)%VWAaK{4$&U@Ygrz5vb84fUHv1bl`eM=ODJ>#SUN0-pyM= zkVq)ZKK0!8`Dg1qFQm$SQG2D^dZc=!y|%S>4d!^5;iGd{gsnM#Z%5O;9pZfy+SWKe z6;&%H8v3f@!q3j}8nGBj@6P%pz=D*XXIa719VSo5(5G~xJF=)=Gje#`4^&?erT4T> zH*I`Wo|4~Tl-F^WcTR0?68I3~l8be^VI(M%j+zDJ5iFiRDuYrSOTi;on>c&n(DUkJi5As^9ojt`$qK2~{7ye_Y*x7QwfvDX2r#kemC1&kQrFjCQT*XSB(1lTGsq z*wtCn?CIb`c1SIIBH3Im=PRq9(*CFrGe|o!xI*Pwyu_!G@s-Q=jcwbur1^u};yoR8 zO(RY;4R37HRjYrjaTic3S9zK+(AR&^Qzsja=cD%M8!K|Q`&4|XQDx_3@k8|K{Dr|o zYu)M8RjYr>Z5BYc#vcu;mO^j)3Beg_SL%n>>OZ)>Sl@`^XiZ`^B_8FFX-69{5-bUq zIXx_|*1m1Y@Ir8~f$wmdhr<_V^KFNyJF2eMtgM+|Yik<*wW>4+=7pP^c#SIu-LKMu zq+#>ER<&(&@avjx|Fm@749xRyaiKt6-L|TjFDv?aseJ$|8ZzD<%DM}>_KyFtsJk}) zIh&TPsI~oxQVf<#esnFbwZ*XbwRrWtwALndUu~gyAj>8_GZYD%PW3@BlyxUm3;8<)y>-+E0lbYJ(Gg8 zH{V|DTvB`Dr_zGTl-89IHOpF;MYL^ORS~kX^2btV3@gf-b5+I87kvMI@sUcGGQPV) za}&2#lUrBFO4kurg)$y6>pm@23uh(@dRa8n;)Yh%|3o1({dW z4uAOJTC0ayrR1_U-=02W$?>f}SqoG-ul!W3Y|V=(n@NvB6&)$EYgy6W`)sn|)dkx} zb0u!(^Moy38&e#bUsO}{V^Mu=NKO1NHWj;BYm+X10|(X*WC4%kT}7^4{8AV-N-RoI z4(I|b+NKbTR*%AFrfR2P-A~I^_Mm>+hZLPA?$B!1)+8*i)i>XYUkhucwY)JP3s-IY z@)foG0DBgTe0Z3c2Yw23jJZDt*>_*Jn^Wz(yYSowA_8}I^Vn6}?dEZ- zzOb9e^JDDhiTpgf`H%c&yEzTcmLFfa!e^$vL%t>f{NowUEGnS^HvdBc+XE8F@0Ebc zt_&qH{D%ahNdm=pBrpOJfMEYq0wb~l5_s%CBoJL+h~UM4U+$Ga^nXd9yxCYAZ%2Xz z*`?7MmIn1ntd65pF>p;u*%^9|%wyUp)p(KrKz)ZN$K)k%-R6rjm;3oSnIh&Y=J1Bh z=b+*5D_IRvvYyQF1~Wc?f`7Qqhw%?ePjAv3r1{Y0U9u;r823$-4Y%Tz7Gm@gG3w(q zo)`Ki8@Ya%X~ZXIWN00yc5}hb9H}3~#p=0%K64P}cg)dsW|iBFxoWE8rD0gr%Z($0 z%NNi#C7RR9`PbzNpNFD|;L7W)GEI3QCf6;*1AbQBWc720G2uiaWWx0@unpxw{d^-sqTVOzPwk z^pT-~=;WyTq7#WPf#|q?AD!0`9j77h|7Uzw-iZ(T`0Fq8G5^pvd%7FARE6(=&N-=9 z2;!f~8tu$cdpBQpPNM02{0d)cu2z^%VFLE?qCrZ`F1P>t!{fqb8Z-@VO1mryC5VUsXUG)k*`d`@DNgS`M z(GORE6a4}KI&mi1s(SIZG@kYy=qKJw2H-952(mP+HB3F1S&XfL%SW;P0?YL-dx6U| z(If53%T21w-Wiug6*=1RpmtnHs^Y1f%N2u`#d4XL+8i}|ZTQyWRp$%tzii8)P6`Gk zD@K8;g z>yGmY)eoAsu_|>Jz03I2*vr*HVi57Li*qTK2i4~_jlOJOm|$8s5N_MGU8{pr6}kER z2xawy;BRN;+#zVV`tE!-0rK+pb4wKXEDO!wc>IqzD>9< zJ7@xiCL(`%iwg~`Q;InpNCN^p?B8Sq1Xkj8R3@W!ca6f8W~HM<+2xhX(R~QWiEO{= zH~(@8=`;Cd^wk!%Y{VNt@wkGS;$eQ{68@(?g?}`)A(hqx#2d|zvy`tcWyvikv0e7@ zTm{$Mba!3TUD$AQ@h6MyuB5?Xd=lT^BDThlMLJ;BeTZwN&RW!&YGP_VaxOMTIE372|O!i&m_k9podK>EOu3) zc;ZsoOuICWSRSc0gkrObRrP4@%RB~hl(&k#ZoPbS33q51gYekPUT@Q-n#x^4&9T@h z@KFl9Dy(ljoT444-q3hy{rc;h6S$J8*l}F@-lg`p8*|4+R#;|NCRSQj-JD&STx?oj z6h7YsN2&qL8l0G$(W$jEJ(rkUcLR}X2o_%s#D?dDgNZPy-Em2u9R&OM8P+x?#i@&i z1$ke&WVpY1AUe{&sS+~}Q5Sc^W{HQbrRXKtJa^CQ&t)F<`vx)NIBjGocF-J&D;!-9 zcS;N(T7t=WI()8{Ck^H@lVIzMtDI^Wvuwk&zB#3ruw#z;y5dY?$|$!r$2F+(los2g zyuxaG1RIJhw#WErO9l-@EZ(iz7PL)d-$wR(;+&CtpIUTjS&%4Uw zbF>@J8Rfpny;XPnRY&pODduWV`0?baPdWFhhqZaQ6CMm${0%BYW$U4Xm~1|U7Zptw z>MbA+_+Pcxf9O5`@!(6+WKfglk{C?Bj||r4U$*#yEP;w8yV;8ef20wXIGDcI%Q4}2 zLRL&8J)4dCZsJ%n$IRUYU)>{kC3tkId+j5Xv8b=g#j8Pg`M+8J-}mSEUIHr#5faXf5xTbCS+-@l~<0WNWv4k1GzA| zeqwNLTu&ArKCM&4wKu%iz&#p_C&c81C9SkfR`o+Gra~ZzUCIVdJWo7XKZw!h|4b7q z*E4YiKlT`MId5M~oW10!Z!W@TBYCecm}(5NN(*|=Sev4yiDXQs;EVVk`B9X~W&V+M z<|ZX26}&x~%QRyD>$se4v_z?uG_QeVKX9#o7!H~eJ$K|HicGt`Aof5USnKj0)pgIs)<{K3M*oA2#hNi9wH z!YXkKnelkHI$A%K=4umyjX`%7DKfFv?8~6G0YB{i0{^rlYX`Z(f>hz2_wZ^odGtz^ z=psXSgQ@g@N7yv3Uuf?0?a+^qlP`lhKKQ9_V2J{!Gd7bWV-RM=hau2IX9K1i?wF2) zsr2A9f<@rsI{IRWzwOzV$W!Z$a2Jq~K7)9NHwzGG;hjKBP|j#Q2qCSKtSMlJ|5-0Z z$rwG<(8pco0a%pm*~y;GJ4Ej_?vgKP8dhuA_!DLez3*v{DEee}f3IIQZ}fs3EvL{o z-;X{+2K9{aEBu#VuTbbS=&oL45H0D_0KdfLhj0?gV2I^g)eHV#<$4j@ef1d;0oM?D zU>#L|QOYtf&7%as%I(ygU6irJdnkCUH7Lc&l1h$}?E63^YDj1D4j9*D!m5RO9Ih*O zX54}ctjytmRmo4|L`xQNDUQAv*g8?sp!9htpTH%GQq>W^)q{2Gc#mNX3CCD z&p;%3-d7fViFyyi3j9&!kp2q84L@y{K|N7;c5lkv7q!{UW!0+D)iKJw$rmk_-U*Yc z&EN7NI7%Q#nqopjg)_0N!yS=W>F97qBx3dx?f4c%7_0Xj8%9(3RUdpiuw$f}kCraS$DT_r=fnkR**ld) zW-6GJ^2-IRJRFEawuOP%c>&QG8Jru8cl<;-#f_dX@pNrZ9q*I+@{lRL%@~P@lKo?3 zUoZ8Gq%L69Oj@)z>1dFNcl@F(;t{f8^Qsr5U@)McL?a3Ouz$Js#svh5si?xZM$-{L zrc&P?)Qp-vM{P1k`Xn!55oJ`8q3-wvlb-no$*Q)#@0%lYadVw7>kVQ_pGh zXur18HiD+mjM$zoJ8rwsWV>)@NmVS6m@4Z*gz1V;%7_%;Yv0m(0r9i(Li68oAs#k3 zip$AvZywXVc){s8R*k7^L;bhTZ8Jz!wf9@t#cMSo;uB<*4?P;Hd;LN~Xf-GL?zlb6 zavr>ZVKIW~P5dYXEeLygqjv?4y1&F zGc>4_s&h@Kr4+eCgVa)gE{&vM)wxUhO~q#$*g_h;=Emc8|FiVr+HySX ze_d+fEmCToSvXGqUxyL8=5zF8CJsv?F*l|BRcAv9L=+r{L{}m=Wjwd>sDF|O@IZPN`!`$ z{}JSgb29gRI5h{u3Ez0eF3EiCtj=D*B88oew-<2IOM<L%2F(-xLh9qhOU}{;_os7g2gc+6KPXXztxEy@z>~ zp_T!fgY3w_=M+}PoNW<9oO$GjXImc7?e&`{e0Ya0@YIgSbgrj&%+(2hIfGt*!C2_t z%2aJkgc9Qm8xnlJWw?+_bWo$+z8DhtplG*YB&BIgoHrCDxX(xwO%+ZZ7fiho$&lW4 z979JfRG<0ZW!^~{X<@MYV(uh0%q3=R7-`?i-04Z2nv-FbqOu=5gM(_E>V=cjgUMr2 z6w;fy53Rl!dUSe9Qug9ASWynDikHFDynQCE-%{L&=_#YKACTj&;2zZ^ib&F!mYkWG zoW>=a?mZ(Naf+;dYU5NiFvwC0*NY)&s;fX1xfDrs4}2P|8V5TPBN(zA>=7T{ZqTW+ zXQ5*`<($Qps;1?eZvz{k5oS_vUa4_w4ENSeBc;n6ncp36&7+YB*%*yX^Rew~Sa3P` z0wZt!^Hu5JH3uU)ZJM(qbq&r@1W;mbpBPFJMpK!v9OM$VCo9edxlvYj^52u$@4|X3 zYblt(uB1MJH^DulAdNp9A(tAs0G zqaA47zHTQwvIna@vIGubJj%zRKg5RdwE)+d-bHdRJan=T)Eit^Q9N?EuCx4YY(t@TG!c*ehp2sxTY7ZWO(o>I_@pM5GEKd1oc_( zA9!Cs=l!?0SBW8=aD+lVsta~~R^EX;ePIE19~h6b47%Fn%*pCMf`fZoU*9?>$N-}%uxqf;tQdIRVG#qi}sBdWPoP~EB*-cEoQSeY913sp|FQfmjG;ZGy=XXn2;Z2A^wO^tc&^xX8 zdaZ~|9->mvV8w4>X;}E<*Aip8Ei1Vm3Nv$ByppP~tdgsxo{@P{S&#KGs%el0h1vMG zf<%?>!8}60thHhT_wH_N!}rbc8xmN-PKm?p$T`P)Iqv=1M?u6Q;Y3Ll;5QH~Fv3Dg z&_OEIv?hq`NNxwG^;NHG)~*c(wo#J7aIY`H?PCyA)sWF?UmJ|JQzY^Po};>PXD>T4 z5*|hTMObUz0Vntfi?E4aTw&-_9zeb$8K`}&2-4_UhAeWqzq-EMNO;`YFpBh^Aa~_?I@QN*i6%j+dz1hZIiM=qzv{%5bY{Y30t7{SWCY$Q-%r z>Sq=Dnl|epEG?xm0r$pdktP>bFgmPM! zqu@~_EO9JUI@nZ4!2|R$e&IAu?JT%`;Y`O&S}WH&mtH3v# zrhL6`mEZbxqX*wjGbKKmF<<;aw9z_i^)YK(xKax{1N?%8CWF*2uZ`ATJQ`^|%l_%~ z+F*mSz&TqdOI3tR1PV9VHu`Iiy+G9!JRJ(2_A_5stKRHW5ivVH+Ty& zP`HdL^SfXdkcQ?~RQq9V8;^8OY{Vpiqa<&LwhZ!E*?&3h_Ado$u#5jn)ir;kIyUiGQ34mo8+1VAaIJr z&%TS==TFCU^)*zPUOOFn?KHoX)G%HB1NqWD0H#Mzd)S5&@LIQ0{hZdqR@1zpNdp`G zxJf21?!~yJrtDiz+YQuT7Ui?=Ouad=toC%pG|n(}%_@ZPWrwRUgcqK6@XYdc+B>FQXhnN;d-r~LDnO5LON zZ+aBy#zyxYIXn@7X3=4EW3Z@Axk!-L*?+!8P_ zL%gR7Z-WAdc);iVQsIq%)bQ|+E7+IKryC}EroReJ-aDCdTC~LN8|RI?{e=zenp>E( z4KKa4%scCLWSU1`LdknT0Y`do69s~)uP~`x3B^MN@7~dDH60qG@-CGy!nyEK> z3JcugluBPKT9P+sh1*n{Hmz<B>)H5d1&>R8`o= zIL3foGQR{&XqsXkleqOFqy)iK)tj5N{+~_-C$VpCVhx6i?n8eww0>_`{e8l6E|rcC z8vLHwD8%Q<*!7Oy8A`35-L@@ln()o3l`F(C(s2FD5vZ`xDTTrEU4nE$rgUskT+&aV z?2Z+%B{w&@IGy=Otbt_z(R;6zy><$5R?}hp;xv@@sZTIM(ykW9P0@~r(j5<`1;RkEFK6ErmQVoXk9lg; z*c^wS=&J+yEs$X@$;U^>ff)1Fvd164xNV~Di8oHI%)=ZsY-X&76dc&}Jfvt?z)@D= zb{Sazf1g@7AK!sa8Mj@NPlYC*5~fh>9lCpQYt%+S4D@maS@;eduWhtQf_4e$!PC75 zC_~`0D-xS^cC&B?eK#u|5}X9s=b%NPf7y;x*!PJO=Ha%bG)jZ5+{jZ?3PU4L6)1&K z6f))RcA%dT7ta&N&m&Md3ME2B`R%{tPZ-R9?d0u+p=&3RKXwu+Z~y1~S15EazsY(E zbVszzGwfl6pDBV!o!dzj$+XVKm?oX_u#{vYV|EYxi+B^_VWYhiA|0OwMR-`ZHe+9E z^x+R0SR85a>|?cd8qlv_MVreQVf3j%VU+g4u7f8-2TvAnU}a4XJZolWogTof7e!mIVA*=J9-v;6BRQ|@k1W;F^eR2u5#bPzh&PM#F~ zOFgQ_h7#vOEqEgfRlaecMCCoCpab^V5;JyM<#8M8Bm;Sg8{2r2n~b>@+Hexdg$-09 z*s-1ptfRJ(qQtG7^&`ssx7eB!ph*R)sko4f*NPKLg_kMyS~2wV$(El_n(z2P=6uM4 zMb=>-Vs)VKNbBj&lW0es*8Qa_m>T!yrZJpRESSpa#1fht;_E4mTL|KBWS+c?iQe>q zspX`hO>O?w2bo4I8aWW_`rXOU?*K7)AK`aYI}m9wV&TQhb<1zrfOM9O&W639)FH#Y zEy~OTX~3>VpJRk!Ky;Oy43(TLPE`zbT6ES2)L$JZyd#5oJMrEt4yz+glIaKgnF*~2cjSB9DBjE@}wlMhNwDNF(a!n zw1)b9c%NZfa8lwe+JqY=D5MDoO);b~@1>5x*^=$Xli0w4LBYlx;b6)gEUBN6B|><_ zLa7atD7T%}W=_y&-h6jv9vu^52lT@+O+4WK4i_Yw#vVF*&JJ4A#J;K3`#mVdGU18oBCujfq9(lZMM0C(D%^GMB2I znx<`;lY?yXx%;pWRYu2byYq9Bcmw2gqj}8LHKb=C+;I|nJFTuZ)o|%5ES1>gAd4DT8>4z&%6o;k@8*jEUZORlc;@rasBVcdF*xzcjm7Q^_?I zYZ4DETDJUFR`aNIjPt4KOOnS3SEDGk({x0?uTf-EgK7g7><$N$){7H7I`O9?pACA+ z!Hn=7rLEISDPakYXeTl+J(KbHqKg-b^@|o%Ema+W5?e7B&l#L|;if|| zG}?O?DN|jzSHD53aezu$x%xnfeyOUoyiV`Ur#VT+1^Gs|be$+ZT{GJ2FLRl0oqCBj zwOMKY!?t>z6(7okbR~H?vff3RaJgI?#A1>lIoZ@YeP$*ZZaLM>(1yILS%w5R{9SlXf8fn3 zROH)NB|>#QYb17o686ns?>wU4lHGmyK(D?;)qTh@!r-tGGvM&0y5TuY+w|r(cFi3C z$gOUwU7Fx=OSR$(wDL)uTiq-NQB6g)QMm6RUlF#k`1Ho*8LD9zE`Chndtnu|s%ND; z?k;f_t>U$vVCNeHcnf3?L@Tag)9g_Hwdobt^lk0Bb6E{4hwngXqpU;!>j5YoH>iXy z(N>eY;?`1{xzUUPha%nZiUI>a$fgE*c7m!Xn>kmYk4vD*poI*G#_STR*gR*O)KQ|; zxrUi1Y0Orj81&N8Y(st&-|5{sDxOV6ca}pR^bfK0jcZi+;l za5`wKYv6-5S1=|(`^`5&>V|*B+=e%aewJA4Z{akRVSVQV(j9vp{^9#4?7fB`+Q}e3q6ChI47GJyy zX-acks3aQQyQ|#TR5UhPpw7M7Vx2S-xac@Z^13iPB^XXzD@GYvCNjXQh^U3N5jF)f zlfbj*iQZvE5M+RoSE6Ru z#}tEg$jxiqWmw_Ie8(CF*wJztsgi0*;JJUh$64D7?T7^5j&;Zgd`f*0Oj1KM?b;*( zhIS4R98%o`O7yMI2tb4f!&=d&iuV2WB^h2f$a<6VNB^sLNdI!1UmR`=DvrJ&!4E#M^@K-hWwlM~IAe~z)!KFLMCjZJ>(UaMGO0T( zj@ocSBbUl4eL3rzm8gW^LNv@{z>44~Uf$}D-eGYX_-mB3e4+LF(j~lfTDj+B97bP3D-l-4Sb4Rz zOkrh5S)u&Ejy!FTup`1aCy`K%a-!mnJ9M=*76)hSu~HuMyJ#SA=k_VkJWOX=TOh0f z?v6Oa;Y1m69TMWGFVOWo8@Ruf=T)^L`V=C;b(rNp~L%eLdfO>S(^7t2vLkFbuA>diCJ!{O_eAU;1{S)bKZ7QA8**B0Db$>aoT>w8fJBJTP3;{cmGLk)uo6cw&d zr-@4L(rA7+D+0NctahW+fl>GM>6ET-hstYKm~*zf73!v(A05ZuKYktT=8JzTH;xpZ zIc~9gwEWUv0b^q?V0@RvxUn2}+QDU^jX(tTgH+!%D#y^O=mhO~L8~wEegXOL8kKWVnBb74t%%7ozQ9{XaiyM1ge(6-X2)7JE zLZ`QR1j^_@{n)ep_BhQA3*%pV+`H6@l;(PLAIFV2uiHPOeMIw!=o+l_(wH;lAIDxi zb-OU{_zOnXoY4onDGN&@33gLv8Zt0Ka15TR59SeO92b)m9<5kH;ZUhBUQ1)h^`|RH z;Q!6>K;4xNVj*ZuLx}=T3D%gIOU`&hk~)*Gph7a8kCs>d5KPuE@9V!yR$q8OLrhjN zje2jgmf4_pC+irGo=@f&UT;rU;-od49JlM!j7W0)fg>3M$qD@f8Q&?5(Oa&-ONGsF z+@r#d(XM3nrSM7xU$7Xk;L${5V2gi z1fDo1t+^S#i{=%bz!BBw8z3o$SQ+}ufZ&s>+gTA7E5Y#yAJDgua-1(#x{Dcme!MlG z#2WRZ#g4?V=xkSSxs~dAWw7{1P&{+1No{*=Kx|&m7tt{SFFp>hAU?4Q?_j2_HVt0r zy=)VHqj$H^yNTWlRI{MJB~n?`eR98seJrixthxT^0}%77jx8JDrc7DO8M~ew5H3*K zxw@t^Q!tb!Hws?*c8q4$zTU1ZJ3ZjIN9nwW;q&Ow1&Uf z-AnP@_YFw?qL$%8T-bz!N(O|56bB8~jcTe3ry9a?3NgH=D(XUqK}hDHI`Bl- zA1p4#8LZtw>_I`c-9A`M2+cppuA;_9T;uz^P$X>R|);!>3)g>(CMFPg zur5>NP!;6=XSjSDXs^cg;8(>ua5);+b6>gKU-@z~nv4x#E7BSR&mF9<2qrVohGorp zM{7$PobAf!OJ6~2RwCrL+SElq9&?LTa6a4&hrXz%Kn?I38yvf-CHAtv;8$R&KKs@x zP#Xvx5YqEs;n$biN(UNL+yqK+`4}az6P(`g{Z1eBGOFD1aEh=mr)RX?w>qud`|0BH z{IiJHn9w&Za|f`=^p?>?2>j>AbtZ8(G2RgK_2=s=^7>!bH|F)@NWBv0SJF|4_|c;D zyW7=`V%?M8C3MCwd_Yx_)|xl&fv)$Ch2A^n9TJ8J?@}D7Lzc!gZGe|Vk9^z%!*1IH z)?)?PmM5FS^=7MBB{tU?r%8ox7Pd(3keX;0tAfqzjd^YF%KR706g3}1#a0ucgj5Di zLOUfF;~p@-^0D|)2}V!5284UNREV!?%}IG}Lmw%%(ff}YO6kS*$j6{HpamO`iAtIQ z78+x`H0uMUM{m;Y)OmDGozfVAD<5GqmF8BCT>H*_e%Z$rk_$gkDE#^ud46zwSmp5{ z`C@pLVu!|G6+t~b{U>yZ)UfwwYO8}1YSF8&}qJ7;n|EEF~BBatBVxo1s|iWhDKF{ zO`06SVHxyN9{Jdi%W_lj3gz0s<45aD=Y)8@qU8_AFber0*EN9zfB3|J zBo)Niya6L(HnI}>h7&~D|Z=)*^A zH||%qtD|ZO-@uXYas~=PnK-cR$~hKjINCv6bGr`f^0%>$A7Vrwf9j9;m;?JW2pl3h zAdmK~tL+lmqsGgK2)uZ-K9}RNa)vQ>{b+s8(g7;UhISCAeFQ=Gc>Ih`4@rw4NHJ3jElI&%pr>j}f;E zN2wenbWJ>J$hu}l&AYFnX7|?BiFq__I*2`)u)CeR(T_BiKsMD^W6(7irp}G8KKbOAt9V(B;i@R)-2RZ|E66Koy zas3_))X~R4fX`jm49wG;gk~y%NWQ^-&AN3pYPL$Kw~CJsS`$k15&K(c8w`#Ebf-a7 zxRW`c3XEDLIRR|hcgj%%$s@wa%D~I=e1qL>xh zypq~KXx*`?#OhHSv_$#`S4&|v!RAn_CkHqA9g^}bTqMoOc1Vj8atcSJ1Y2owEVWo2 z65tNM0`~Kg{xy=w{qGneOrzDp6Ee!E{-V-;H=2ocXG3EH5*HA;Sj42u~jcqD;cDCVrtvzgYhKnnG3b%?eG$=)- z+Px>{RmHuq(CGe1L0Zu5+6Sn;(c+_sgtSr}P5u~f2{m4o_JxJo-Z;2Kf7iU==%&0S z>v!0d8p8y&b91NNf4b0K!E=U6)s2RUY~=*y@^$IKkg8c#^h|$c3ges^=O|)j$4V$Y za5`rH$TD&L0o%_smaQhjEI$ECUn2z_HIHPYkH+8~b8xI#S*CpaZK%Z>E-AD-d`dXH zG^8rP8v?nkUVo52hM;_c7z{}qC^^Num_#j@7R0<0#J|2?*Fl{ zptQuJnpkH5N%`nP%e;PTo*u>E0gaCC=mU)RuJ0ufC@<_=4IUgstcC=^^)tNkWRzRt zB-S_Z72t&V^N@k<;Qs5Dey{&WPRHHm(Qfo`pTgsIr*>k!RxHp53ldR@yVHVSX${Wa zL3r>e8|)Nbwuu-ql2045;@pK9?!rW_01k@~fX8(?)?hd9?iKAOeDxT)^j5o=B*mN_ z3=Fa+!_O)Z5o4ZIqU%BoQ@ZV4H*1=*(QTup4J@8pV*fo>Y!MLv98s+k@Ji9cOrFH! z1PFzY8ra9l(eM*0?Nj6qh;m1F>Hvc4&mV!;uW)Z&SyNO0qsKA5j^n`ZS)DZgq7TGC z;-!@UvP;Hg9qQXU2aG)JwX?nK*zz4JuU1<-+pX1>=ft5CT%_d()~k?^QEZ6;$&!W; zzOc!reko%N4=FIGB4KSf%)+{0h|4!$`iM*M*zE;0Iqj)Q`xd7!vzH{%hea9GY7Hk8 z#hc>n+6=?HERLGkproGEa)3I*ysN=@G zG}jCINx^lbTbZ&wRU4F4pM$=a5pCsF;6uJkP68_e-UOv#?L@0?whxUL=t|#ujIre$ z<)~+JR3$VDtYyhL4(DB3r-XASYpOlja7!(nDwx0S<}@Ythi@sd*P9y_)Y8fz@KO&U z*y&O`*s-wR)Z7Fu*Jie56Sas2bZsB`q}k(lBr(ENDfxH`u&qBThB7DfFe9-S>5!I+ zvrs(6ilJQFi$|?RN%kV*w<*puFb5fe8O_QzA2)z%_d(hw1iZ_0T`reT1Bf2Oswhes} zB}40_g?Ql;cyoQ$2j?#7`#?k$!s~=-N3wdqf}89pBK8@R82%F-L%N31$3J>NSAT|P zeFDw;8Ps)waWv_1r4UIlk{I*%*AO^t(5x2zNTo_NUSNt=48tHT!Ltbl^Cy5o&8gDw zb}F^O-HB`cvlULMN@udhDZ$}Pj+?D_O0*0agi<$1)6FuDBcOE6tX(2R zuF(Y3qK-kBqF?_4lf;WxTnCeF{xD3x;3eALXJ}LtULblD9-!o5W&B(3%<%&s;UdL_ zefnXn2-63_xsAYikWh5_p9rIi`v)9F`+tE)+C$|J!vkLF*M03u%q%o?h+)EO^xZx~ zX`DM*E!&{GljAVO-9<$B!pT~RhI zD61+!Mq=CA>mWhFdgB5~M&ePCj3fY9-LinBjSA(odtVMJSastx`Kw)lWeCss1&#Y+*kK^SFy>JvDQ)+7}^Xj@KR_%!L zX=U6y;WXu@_Z#TwQTU8<)~;Ae%_RB8PVKorcn4qY4W@trB&6qQ@AdSSyPUZH{h zF%%^uxqneCB91Hrz~*O2_(R%duR;K>Xm0F1gXdeP7c53KGYlC ze~s8HV%dR)fY+LuJB zq0LsFn&{?LP~ECsfqk-j4q0-SPnsknF3<(e8c9aGeTf{`@@Owik0n+Zi2_U?wVx@U zfx9crU&U}%%#_c@yX$nU0~^!wg}V{{w^+yDNKU_Yb2P6H0^vO>w=S+J)veRlcM9`* zMGJiOo`x}vI!N7!*JYIR*!Q%| z?hX8i?Evjr_xB9$P=B5;AqYRbJdnTaK{s(zAl3)bv(X60NX=iWPUqTa}|>3S^ki29Eb~%6&%c z*5$3bA$SF&2>lG-(5$3nn~%FC%%^(Skf(SWIDp&qmmbl#UY>%eXISX56+4B-*AXH# zO7%cGXzZJ-bA8!sRl>NKTET7JspBT2I?+Z$6zaK?Dj!;orI8=dwbjxpBgl%gs*zM zMJetfZq>Z2_c2}19!~ReY0pj6B)jB9FDD)zuJa2RVJX4j){Wt?k)0swQo(FhHDGM%7wR`IfNB}Wc+G-&rB%T(3R;CP z?>79P5I<%EHGPJa@ZVA?`IilYHw$F6tfRh*?&*a(utE7v+PmDNVrZP8rS`+PmM>uo=t-F8Xj9mQGjqBWpSZj)Ma&U6MTd>%=U~u>g|4C(S zdUtOioT3!I`wAac`G~=~fO@Rf4QC3CQ~_y-+*+nC`r#|5_>!?4-5P2BBO*%F!R9}7 ze-RF4yuFPCi3oC(ZAR6O6yil)V?H`pQT}B7kV)d%-KG;?A>3-(j9;wjq=g8(@b9T= zQ86xXu2(Em8rrVl1RM#>vEJ8U_V;r$yMYLF;QQWQ-DA3|syfp^D06>27zl`)#vley z^hk{E)-2xhQ#h2_9^a7d%IPy?{djI$SOE__87SNw-{-5yFtq($7WhB@Nd~XDvE|o2 z!(xB)yS+SG$48p~)E(ImFW`&b$Z(yFZ1_f< z`gN}%E9TT`%MGI^SM1kFtdY6u=-`{{*`xCgk?2+8>|M8ABTJ!M{Y=rHzrwK^cT;yr za;s7x+jP!uAv|b5f?+6#7x?$+mEO6!omp7IU#Il zT1NH^s}#E4AU5ne+4i3(+2B~oz97||NyI0c)Fdyi}&I?Njq9A9LiEYzIB%U83b9`BS_1)lS zJI5nMG`1T=$fN4HJh<43K00qlX}=JjBHuWbYco9Tsgw<`IUz8 z^?O{0_mvxWw~mK|UCFuj^%htB+)9<0&&1%KgkHXlk(uQ%-L(zEKSXg+pz9+bm`iXg zIZ-*nJ+x8;W^NbdSojQuDtDH~fW;qoo~DjQ8VuDbI@f}u zL$86NqcWM9QMOPhzemfD#vuhAeFQ^^Pzox?o4h8<<0_8U2xb_z5QAgjhqG}aECZNP z7VX9*AQhba7IkpXDb6ND zNc>`SE5Y8T@l+U=YRbpJh(!Y1Fgh+e=_nVycm0iYtZaU}tG*P6zV56Ajv_job?DsH zA%`ssukf!9QfewO@wNyKUv-_CIfd;PF6dXs`ch~V>BlJ%jIrYG%wl{Ks?w7W5H zOK|X!9^Jp&x;tamy7Q`Pg+E#vKb^w^k}I;y3CSxhM!%&oU{-gRWbX_xtxK2M9m_!IAY zNn>O@PriMZ{_O?&LOXZE+JHBYCOuWqC|1+Z7G_aqxFh?jJNn{oF)u@uKrqnF*KqWk z+a1cK_6fO^47v}dNcZ3&uL_=~hvc>Qz;P09%SJ-WleOMp2zC>Ar_R1j?rai*5s!U? zFoz17vw+NdGUka@LOy+KI)~QG575peXgVADWot5chA|}D3Wd%v<)UxZM=<$L(d`n z3=3+~@gYp0Sn^?>LEhY9YFg2+W{A0zXuF@WX}c@8uEx$$>X`x+HvPypyQR`LxN-`$ zRKi>`cUqH8=YOo=p^(QYL}OvzUa#NijU*@To!_n=P>v5Pc`-giT9C~L!;7je_UaBa zfCbyt-w5tTRnyog8lH=%^K!{nN9g$yWgS?fU*y@<@6jL0u5nlTjWCmgyXTTxaTdH2 zrmyrk3vk7tQ-a8AVx7wIPHBVejL(P^#XD_8VbkvhgDr;WyjJ*x%CssW8>KFL8;StD zrIPwEkz0uX^r30bmw2(7NMnKcjO28on=+;EYadZ5m4^u7a|)s>03=*N*40kA3e=Es z;D7cL5Omn`yLonuWTb2E3BT>u*F4W_GkB^0cum(?3x*L5h8K(krLdf0v+^vD0?P#2ch}1FC7w^E0c6@oAp`ubWW3{TZne4cRSP>vcM1roAU0eVOnL8 z0w-pOucd(|WDQksa5GYOkGa0DHMAbyF4vAT5rHW)e<}H_k{pT8e!{ku>Ia=GP?bI} z;?{N6;HIh|B&5lXC;EAK=SJMLu@5vHJ8p>sp?Wi^&{A~OP`wFqy#-Go7MFFWj26aG z5`ODyekc>vGlXTYuVtzkt$YMm_>e9S|WilsJyPie~ zaeuI0$FDp}q&CNnpzfjZefkJR;&6%P>Wn9{E5Ed}V{&NF26lzteqLX*iciv6F{g?Y zL#L*e6;^4?8blB@(MM`q*W*>1LnnvpfL`~^u#y9(m#mDQko_rupWbssT6BkJv$X8o zLs)^)Y~hGaT}U1d>DIPH@7`@F%D6FaFW0XGIWi>0@yW`{WUzD6Mh%LM@C%$c z$Xrl2MYf(}Qry1^foHqI34p-`?A z)Xq{4w1_6?_c6i?6l!}>LN+y(R<1PRH7RYO>&Lw)q*o<3$JH5zA(7NSWmvLCMvZ+? z8Zp$U*3KNj{T8Fba8jv?C`XC9^r&UG+qb$tH==}^|5ff=0T&Jr zLuzyo&a0!=-G(el?EI_Ub9J>wJ5GBQD%U6~y3te7v=sWhINu-akw9%9=-?wQ=~))1 z-KLR6Y1hFeFe0nnWOpU>k(Vh*e_`q4knr>%D z$72^nvA^EEZ>1zLlIGE3!#grDAqGU=SjclrlEGLA3JJe9Mi7s1@nPSt=J;0ap1m8C z8&q8N)77~iuBvKr(~%=nCcZXF@}SH6cEJx%)`pFnHmDNnhWzG(ud7*Gt(5KIwtbM?$=GcL_cdL$fV)tSlTw~Zg2-soD{*MTGa`FC!ce^cf|g_%z}$6i2a zWuJ7HG?U(FeyR`m9D*H2rboi~ex^@SpC9^;;+x#m4Sl>ex!lr{gZMVGa9Sxg#-c~LN$Z?mWs9=hTfvQ z#~Rc{`K`@xiJBE-&s*Y}cjV zEr!yCHxA?5ZEzHKCUEfOOytGMYIruzX&dAdMLmHojHQfX5pfl~|4t(x{GT52e>&mr zIoK#t{8LnrbgR=^6XM$5nF#i-R zbX4v^=v92&&;eo`xN=(l_&BB0hId*iM3Xci9IuFF#Hw`c#h?M)L7xxpF)l!hwlxOU z>_MmnK5ndt*?K<&u9fg>?Za7UJ@ViIVY1~N#>@5hQr$y17@SY0zaEBumw%B5Ha}0h zZ*1Gr*nr(bkv;P4)VAZS>UCgdcFC%HU%+R}(Ve2ya;gP=G8?O_tP7fypSb&6~PxMp?$=i>1J^Cc7LnjIb5f0+)+5k4h5xqM%X7mHZg_OOk=|S z9d>_P#Q(#Ky28TlFZXQOv-iuQa9Ld1W$auYeY!TW@T<0Oy1yJ4$wWplhyScid;f?& ztv6DpIPyeT#{fm!>lJC`dmCGe-rTh3i2jY6*fl0*-n1$>H4+{<3}R5H&7Dy=+w0%4 zaa}MT4xG{az_0qeKA16iA9~EYm1!wI?493(U_8QN>dWQMTQ0p|&A#vO5nKOUeVwv! zcFyxn$vLK;gBR}57nBuFv+hp30C&MN#ALR1qxoE{w$Nj$F09T@TadYc?Fhvz*%FdP z|GSW*`?gd?+hQj(*)?CrTJjIeu%Z5jgxuW1Mi~YffEHWldYYKtUGb z7WuMiT$16*G>$FFI|={Qk1!6^$c0bf%D?hkSdE+6b{CufDDxQ0C6RaQ-!YuJLFt&! zI%aB+8BYLK^YNnZieo0NEG5c$=)kIFz6FUJ#=rVX!i5IC@AWE2Db=(=nUj~WZa_6^ zL*Audv6_4)s2XXQtUr}Z_j1m;m_7RN3V2Z4uf*YIS`zc8!%Oeu~Q;ad`5N7h?L$7bBbdW+=FHQNS}JbJ5YMAfQ{g^=}3K@?1ZjSJe|%TaYc;a)P;T_*98N;nL$S|_NAH!H-C zIO~w1L-e)S43$;7-R9ZvXXF{4X7;{LjjE4jPp7W5o2KCx;`r$)_X+u5V60^>DA=~Z z#3g0AdN@tT%b1Rw70u=}{7}yUBREXveHsKi;f-i0Jo@T+hYt*|&%6$VMY9U#x6U;e z;3zo%ge=#At%)lf<5-B#Ahw=pOv^MIGjGYn-OLSzu9x6Pxgj%}{`O6}hWzMD$kC7m z|IdvC(@i>DXWfuRGDqP}3h03C(m&FONy7RsuA>n(Zp+k(sVQI@CZ>)|@bp{sHGDs> z=ffaU;A#8{+uskt6SlNY4(c~d1|kBNV=ygQsadKsWNM&|yghb@F3vf|qeEX*XS;oH zUDVdvnU#J9Y5O%yT;(mCAwy6v@=RT-M3VH&58G(dPb1oi#N{|bfDw3jJnNnbE-3}U zlu^x0bgCL=2HYfAvYM!3`QY>9A+(Lwd%vRWvtjt8t(Cn@g6{&scUe`SGrSJF5?3=8 z9KaObde2&))4^fSYVCfMSDDsUw=tfcx$2YZ;$DA{k19>x(W6@WpPLweeQfQpDJ!$ ziZG}cv3P_ZsJftP)TPO+rkI)YQ8Qa~=FnC44)!?~tKbp!1FSop zF)U3^$myqB$FZhv%o*@?)Vz4cGoWR1?|IQfxn4IwYqAw4n#fFF(NTp284jx)a97tf+`QkS1Ao=>_P>J%w zbda^G<&a;n3AsaHSbe*4b8>H~S<@&Ub=UFTccrI4i{ZPO^EN+NC3L|YDOM*x1KE6zJqBOZS$!&6qdbn4FI=*}rw z7A0S%x2WvEAr$GuCc-cV=9clM5hNhAny7nl?O5`C_!rU%v&Db>Chc;^&KMzI4_9@z z0=_Jf_rb1=IshI=>>3T9PlKX-v6e@y6z)I`3s7a-d!0|Dw;>YS5wf1TLjwanntNrW zooXW~8+qNF<@ zm6OBE%2BpQ57p1lOvXV=&XYT5o^9b)cG^+g8u&S3a$prpB>au!aZ`QE@Io4tvx7a2 zl(_cEuUfc@PCI}cdx6wc?+V_bGvr?LsJ#A%b3M@Zg||Djm*=-Au$(k)qz?650P|XH1%67@ViDoD_{=5zn#=ddpLmDEk~GicX>g-UvK>z8PJ(x} zD&I1zM7y~0Gs<#!QSyheBYTH!dvb1OayhKo4F_5KcxHB4c}hw+l(@I0fwp<(@nAz_ z+bN5^Hi$EgP|B2CM4(%VX|s36?yS1#^^JRB#{0sAL(mN_^w|9s_<@A``ODTJw$yxk zFdzMsoqkC4*F5_Z_c~T9-{z{Yk!gDLlhmrT_a`?diI#hpl+inCr^#N{zU3vq)cLzf^ay4N-jQ}O2 zXETTF;Y5f|=KYXyUcEvYPKv`xcf&;K)ZF|!uH*ATJ_!Tt731rYt;vja$=Do?cS-uf zhj2Aa<7N~i%%fq_9_PtkE4pXWwkpD>g)V)L7xOz8iW`5Dz!CE(22V#X`LrzvMpM4U z^*=S-ImyWSK`O)Tha64C<*W_Sc@TWILs7aYepr{*JpS9B+-4<>pW_#x*F{WUM+$}* z)AH5lVLw!e0ylkY*mKnm-xqnRNC=7qwl6*p`qUuP_8}vOsNq|~#-C9`n(eQj!*p@T z*}H4%w{vw@$dsnkoIt6?kjF2IjzB1g{sc6Btb$igFCy3BUBEPVP%9bxq*(`v#*9 z{U-3#X;@FL!qvu2gl>>QUE;YX~yzxfVEjZVmbIC}Z4E1S?~!vptUb zoV}s7Ee$jj;A*zEv^BfIWVX=KMD#1Cl1q(*(%n)YdX%m9YFju-2ivP;w!m3kw1c)R zfidUd2}eq?w`GdXqUs!v&_S|`GOT=@+ou>RqT1%MHq5Lpaw|DIuW?J>ijdrV_}a5S zR+qUIV|&2iq#m(%I#34zl{s8GuY~Wbbc9*pCj?a)ud4|BISd%n;Ic+cWnC)Se~iFX zvYeA=i)~u>&+o8%WM0)4q$DIBh6?v6;L>{o|FPvG}2+2TowsaIItfoQQ zpvI_Pbm7i9%jNX9=%C;HL?PxofnGw#swKE=7VmSqRi z+sse&BJ-ZE*2qoDP-{fkA(e1B`*#OtXTe!73c%x9HdIE}|3pX&-j@R*N~kF!G*fbL z-A!l8oCjwVI$@VtO8kFQO1o;x?cyGQk1ydPN@l-{7%iD-{3jJ?FHAuI9`YA~cDyQ= zt);SGi3oq9Ot=R;doEf-_hrb51CLN%O1~EEPS+tdc737hh)_crns5SCWIM<`>>yZ3 z0`zosLd`qj1g54f%@dxZwU-iug2%iB1yMQATvzY%h_GU)-t2#<*SvVB-p8&>|42l5 zbSQo1Kc+7mN?&$e`u~Usi-yvt{bTwEhte;Q(-V%Nx)5?ig!z=kw=!dAt}yDLwJ_c- zA!By#!osHfcFmM@LNuXW(9*zi&bqldj=z`Mjwet;2DDa>phYv#vdp* z+Tlxa_5oyUu+(m({Npchx$0Opy)BPtRjSZn=5hO9+*Xv<18c{7@ za1jA`0If96O@|{`rgiH@FfCxau zvx<9@5+EJZiws<_n0Sl`lB@X9Cp7P;pS;>vtqYkFJD z+DPDN541XQnWXigK4&~u6D|p76K#Q;dkwiU&;)C*|M3WFhs7OXG%e86Lnjk59=L=n ztnhfGP8*ERyt3B)WujXPYUuhwEK_q8{t_}v+3~h(xd>)B>K2`0;+b;)l zwbE4(Okh-8^z#^ukdYiP33CZw4O+KR18dXisS{wAmi8K3wP_uM#kCuzdUjP!UX@X` zY+nIyWTt!jO>-k_;4S5DqMD6eE4xA~yM+HDq#6pZfNT!m%40V7u7UQkT*u8+2MwcC z&Gb56qJi43N4i3fbP11AUJ%_Gkzu0iG7ZjUOyQtUfs>c$v*%i@5xkh6AXbakWz&rj zH_wQvOmUWq`?vF>BB^oiBl`4xZmp`t5^sa1R+1%JZs>$yP+Z^C{1df}WYt zql~1&3+1>LZm`0@y;6nTY31H)lm8~fM}i~M{c(fU%|5pe*BXgQ8rOFc)8PNPtDQCf zH3rc-)qS>$>ek?VHF_^KvTJ;ogeYCe)Fq6UFnor|{#(~DDUXiq1%M*Y;(B`Xv2Q?P zo?>8}4cufO>GCLFey~eSO@t5Z4in=)-R0er*ihJd!xlxuq`Db9^jl0DvJFnH=vR4D zN50y&#H*c9e1irmJz2nvInw6VYi_T8)sx`ex(l~fdN=QSwNB?zO0%EXc61BmO3KOm z@E+KM`Ou(@?8%ti`0Zc2j(ye@)@uT*+ql#hHja29NoP^E?Clbh63vI;;GT>37El4G ziO%R4WM~qazi7*Ty{rCRs6JPCluy@;+}OGC-7v11 zOMpmUleWRG&Fr~{gGqUg(ms<%AyjU#O_PSfXHQL>xPE}>qh7<8Jck%wA7@vL;!FM; z?>JB5^@{Qdv#>9{!0Wvw&mwSebnZS7+I@g8`7eav5yA&(h;LMwHgw736mpRyjl4u6 z-h8Qt28dh&zGZ*FpnK)~Z%xb4k)y&GOUaD;{zSyOIlesA>{TWR?yf5fxwOgq>a-21 z8x(aGPtF#7dfNt*yor6UhfCNG(^iHXA2{BIE0XMk&6DctN%Y?E@Gk7AJ<`D@#!z-? z7f=VyS~r?qmo?aumk)$qJ|K9h0rl`nYpUq7CIfOz)xkB+b%uba{DoaS{6Qxrnm#)) zaif}Jsh+@VZRqxwCS|;8{04J^uBrevSRwBD39p8_s}|+6-&-BjEIg2NP&qjme|9Zj zely!~6LTqVd}hkLZ4+|Kt!(~mW}BV7K$Y{Eyids&3^u4k&6MB6uE}98-9uKZ<%`)h zxlH*oR&%GkpcPlfL?7dd!~mbwr_hW7c}$vw+Y$_oicITm<&Gm1eSo6vLr8+jl=-t5 z=pn`dT=s%`xc(~V{{@j9r(&SfxII9bFVW9(J9$6ObiBOgSS-`}%q2UQiR-cYVjQ0@ z-IaxJII)6%4m-y%)^>R#-E!nDyUoht1Ptmph^(Z4-Moju*2@=CdKX zowB_Lcn|Rt&)k#pevdklO7Zmo`>{ZsI@#KL()Q6wVUYppvF9pW-$Nuh zp4KR$aW4o}Otr$4|B_^a*o>WQf6`zSD9VhAkqE!y_<{F#77G2T*kZ}fqTIy-jEOd<9p9iutX%wwMOtX#EP2IlSu+R zfiZpZ4g;1>68mki_VFI?%cS41UOn7HP)1oN-+sxv=XjlzC*6b904-cyx3~wZQ1b|!<&;W*}**$gSfX)0eAXdkS?F=u!2U_Bgbv>YS ze6KFMNzhFxb>!TQR4|PdPX)T-no3icKUqNQCHGiV^VuwY9)*KPD4K26=h6DNl(<}u zq$v?Sp(~f{Bfm zTiIzu*OC-SlLD`w3>AoP=_Qy)xCvn&8Ft**$Q#jlK$LF&_qdZ(N4H)+xi4vQ{gCPV z{Lbs`g1^}eYM0}b?4+;@mYuZ82^i#B!VCp==96OJoQb1qa|wvxx2K9pW6>84bfv*2 zA!$Qv$7489J~+k>sS+4>_K%5UD!4?tw(lhJu;EiBGsGy&J$Y-+n3>bknA+(=aSY|w zZ5S!f+;-6tBOhwLXqicSAHU$8dO;Vsm|sr~`7g#LZmgko#?XEQGbw)%Y&GQ#Co92J zhUDjI`dpEN7N0xD(M+X5{kvOWf6dMd57E+p1=U+`f{4he>?^^Ch7R-R2c zt0f&C{8*SLY^V3zk6%?(7Q^kfn+bInnG0LCp5((s>H-m(60$f3jrC2UNknYs9oaY8 zDozSpOw!-BjVHO=l6TT%QihE`sh5k?nIdH63MrNg<-RJ=OE6UgoCNN%pY-7gQHcV1 z&W^y{Nj=>jOIZxxdVfa@IH_yoAw#@z_2qXFBJbUaG3YTTU&yb&;eGC6SFUdLMfLTc zu^GJ*gaWg9B@BbX)D?qEMR66nl8d_UgXSF<^J}i^-nkgZO^l(-F9zG80P0 z{B00t%@n2cTvXTpYv^r^ayTr&=P#mkZ(U57Sx1cQ$JHRMlxSyp{|fU>|Mb3du^h%4 z1w1?F^VX6)W;dXccptpreHHhrPYTB?Xda#r{@ETr2?j9=hb|7G-9iNEw;2fk&rqRU zJ*W>j0_rrhhERfV-zn_0ZQcnCkzkz)YlC*mNe@TOsW<;{I*qQ2_ul-Z3!X^o;`Pv^ zUrKp@7W&zI>yyV6?~M5|k2{$rv8cXg!$}gIYl&UD0x!d-THMxMSk z&J;sIl0}Gt?zM{vG1*SK1d_FXFhc{ugBA7^$BwQV=MU`3eM}v_D|Y#gd(MXqwnhu5 zG!Rr=D|9KZ3HY^&aw@NC)iXsY;*)92jnAk8L@4JG`>`p9}$V5}&% z)H9autY3cv<}(_*k~`~Tn>`C?-vWXlc%TPBQFXLwM^|xu(|0F^oBi0;;=owIyKhej z6g`A<8C1rXCm>WbhIm6N?~4;yXR-2}`d4@Bzq)PLx&cATg%em&)b%&J;p7^{+r|>O z^3I=Vq2t&B$rHIGERuw=v57JJ#a(=N_?&tKdizdu;6L5ByzFU@iDWeog4HSy`E1Cb zw8u`c@vK5`!ps-QmT8KA2xGafrs-cAiK$8)2(Ek?@t=_V$T{W3=t96INSpACFRx8NDNAvohD^Weq*j??`d1e17xATfzw z{XgQb-Oiix%n4SJ!&u;_a`}k@rcP&+P--uv;GaNqhukrvbSFNEv+vj^O=Rl0>}x?! z6wOZNqeK<;o9j=l?rvS(Z7U&dz=UX_9Z{k{6kXG`xy!bS1adKSiy|p${SD~3YBbYs zZ?Eb&0)OWxq)1)ICwmroTA-;kr{25&bbj%*M5bG@{uWOEnjSj=TQS~uPiGU~Z#Ft_ zc{jLWtP))77!<(ksKQ51kdMMyA=$b~IATSJEuEksXkUwXXC6i}q)|a4atT=Ms6Z__ zx;S2I7LKh(oCQjz!w7_FWI)hw8L20Xho9~Gamw*iQ%|(sd!qK<6Sj5|ZJ#jF89^L9 z2Eid17^e$9N>t$>gX8X<1sl>Bul2 z81s_!vRf07CsL|(>f>7fZa<|+?{RPOr&@h-s_LwU4NgBqXU9`ibNr^1uky}j0DkXG z%AOKy-zl3@>dg2uZ{fCPJ`h(Dh~89aUyag2MFnJu|52K3q_l_U|FWo|`%o0MFP@Zh zdNZ|8dZ5$&uK$=6N7k{W*ayzBTrJ#rf9YR$gnwr|qRIcu6;uy&aEzj?S<3X;8hzW< z*z@J5gZ~*2;yZ-4hgz+1GKP2&nyrtgO-Ba)FWaq~{6E`0p(GIZf6;Dp!v8_L*N(J1 z{r_LPGbpFn=WYnNx7)nk=VniZERV9pNIY_CZ_M~`SFGJ7-o!Y?+mCtZ$L&mh(k;Xs ztr@~$t${EHEa9(V>%g|HJDV)5-~)IqyXs$>B?D{b^{l~d-%X;COMqUNOqiWye)BZ; zSJn*~;Lci@Et|S4HVF>#KsS(|o}Zrv9~g65!3WjJ@LDa?)8TU0fz(Q}ui226Aq-qzHm=NW64pBVZ>+MyIuFa(IakQD$V+j%|B zCa5Op>ABWa9-5IeBrIc~=W8w9>G2zo2VLRaCCe5Te_0c`=*cSGQou0<7B;> zlZ6-2Gb_YNw6JVn3cjkyuUD)S+w!`9nnm2Kz)n;=HS}j$2|cg!4DU8OXhjK~2d5_O zAOvo63C%j_-;~ZMEurVaMH|$1ewz5q97jW#D+OhHm&#sJ)QN3b-OiNKne(CW&Y0zt zgC1@Bb@vWeW`GWJ&@#WP)kDv9yLgC>_DOBiySF_s$zR_JQwTdA(ClN_i1X5J$(&|L zuLyKqorz2tH;G9UuPX7EETg89F+^K2F0W$av}b~L%cO2%WOg>0SoTD*#?EUKx|8he zMv{J8oK&Hq6-%DXpbaTp8^vDb1CPVOMfh)wG(wAO(V}gy7hE z%cFO1-*+GtoKCVnIeFR|MA_)>sn1FqY4v#Z9=lP;3-2Ey0au7?761JU#V zb3W`;+I}Ko(MTi<$y9AW-cCe1W28T7sh7kCnuW6f>7s?RR~zWL;aTZLTb-*{Y+1E} zZ_HK}d2%i6E6y$C_%N$>I7{hVJ-fDXw$eWML{o0QvuWFO*`~ozVfl86z4y_|E&Zqm z-CE~sQB>61&U6vlyxNjD?$Jtn@0Q+?$bb;pBSiM{9gTo^FfhesyUCoFE__p+YjM`b zme!=^EOVuYDUB8eG!Oh?%1N+ zEbGhb?bdvmGUvOi8Iyzd!tzT3Z^hHF&enpX`12A6%*NZ5mf7r<#;!Y4liKoL*X=tJ zj;)XKTiF`B!?UN#&U?0|JGMr;U4GAwJwQUw)(0y#Ikv{t@9e2j*1O#Ml?PlsE__wE zJX@3btr~ZoAGSK`_pREjY_$9Rc4fW2##y_qi{CoMZRcz3TdKRPoBY;4Ynxu{YP8R< zeXYxF&kT)I@7CW8-&FPo8-q%ItEm6taEG#@tFcRYc`H*<=|8C)?(#R@P+srqztOw( zF@LwR2mjA0`@4F#j;iPqG|bWY{dTuq*=Y}K&FpPBJ@AdP^Sj~i@N%C}UcWJ@8a*7T z`unJL!;y?NQWa2T93HjK8p-r-RrZ96`$l=G%ikrG`EW&L&$r5+6aGd7e&hd6*?-}B z_n=DUk5rvn-t}?BI=@iJpz0z1?FIPTtGerB`MRD+1_=gLsehNR8-!cor@CGdQudI* z6nxJk)oDL_0s!-i`uMHC8nE-79Y5rwgQgDK`F{K0)_8Q#@OM1=h@DD}NvF=&cAh|2 z^$((_{Kx$KQ)f6kTPk;Kr_ga8zwJve*)>`fHgGLyNSu!xN#94&qn)|1O$p1O_ z$Nukg|9_qOLtg~{bLyK92g%fr{P)y{aR`C$(>q`ar>OAAaifF5wvfZUV#Dhce>f48 z2Wnj6^cUv)|E1gn!(7)2i}IFFAQHH{h70!}=U=DrHoZ>amh%HnEI);Njt5|NX`Ql2 zTJw(M*p1G1?DA?}FFWlM&bgt1n$1xrmB{p4($^;FhCdPdU^b_ko+O_*{obQI;9K|( zxo2VX9KTw4ohyl^tjpuKym{Q=5|mg!q_(|7m-kYRV+p8pwd?qjLhXP>xn#+bb+Ve$ zlA~8y*V;{^i#OsVvEv5*?wn$-~XcL6zvh zp25W=(x;+*0(id8B*Yxp)#2Cq!9ZAxE(5qLui;oCB2$a@n=w%3X4N% zheIX9g$svJ9SY4p7ToguaZ|epMuAq@tq!L=;M8EMI%+LdUHq2f#kMDl%22)ip$51TKBme__xW+epI5U)R7_%BsJhi$--G`|rU1vkqr`l?#OpIwe(PeQ-D@ z9Ge+%ifgvJ1vt+xLN&ck*5Qn+d9(Mec^LP>=rNrx4212gPAmr2NM;j}Q4GP~z?}I>)iA!225e+RgVA?{LB+IGF~nS;bDw zN$?9DKwZg^C)Lijb%k%VMXU^d#6!NS#|Lx+o%N8^#@U@hn6};B}YkD=56TIXte{J zvOrSyf@Y$h3;ez0=oPkl?H|V$=}V3dbAjO%rA4L{%ZrRF78V&+%wi?l7dk^8IXVhs zyN(s2YPb@_&>h$r=v;`gcBn+19S(uK1XOe&)T++>VK^r&0+AUBP>DyH*|}gCei;i) zD#`73OGnz>`S?hT>~@TNq$4`#kHm!Cj!}&COs7$Z@pR^yRN;i4)!k0Pc4&hD>uTxGF> z7?)WF*5b7~wUe*b)X7S!lUJ?t+wSYMmh#1=rfShZxw5#=RQ;P56-ZZnw4_?uIO3&o zRk^?4-dp`}<4R>e@!Ht4*56qgsMZcVtL(J+Pb)81|Ek|I@V)Z-cm4~?{_lW+ev7~H zJ7q=r@OS>pV^hjrwu02{Ot})V&NTKOOrTYfs%7}z{c2$B=)=-=t3s^Z*bICl_QmTZ z)%3toWmy-7r>v`_dhP%L1S8U0{cE_51c!IQkN2jS&@bM_EBWfEo^?v=M*qLxrT)RO zT<1|xuv0gVg-Gs_NEJW!UhsTNK*6f@?w3S8rT&3ZCEmDAK^k?pyHZ5B7dzo$tafGZ z*ofjHl5KYOMc)_3d`mXv|;z}TtyMijrRE-*IrPVqw2U7=iq)#Bk>%1ht(+*0z@ zqpsfq4+a3SybV^5DK0|451jWmo=05f^>6RQ^;S@Rf#uIfkoOE=9Nu2gn* z^i(PXE0=VIki=h7J*BY={Cm$vWf@_~%j}m=ORC2Ps^|0&4j=5{rriEN zyU!@g&SM=aJ6}@$K<9IAGU^pKd%DmNU0GN0H~u25-+l{TCDoJhYc2O*??dHfc0Yj+ zFCg(HAnSdrHi}jWaqBN{&)j!ygSzha8r?>E<#6Mf$B$qVC&Hu zAj8P3qLi;z4^~T89B3p!AaO6zK!kzw0B#&G!o5}r5`Z@0 zU2(p%)b`-9;gtkQfn&X6C%!W34hBvNVPK$oI&hYU=`jbv8v)zPTXRGn5_#MjnYEqvKpQ+47%zOs0MdjVd4 zvvOX(zwCtwok=ewB^ZxfF|}V=YoF|#j->z#g7L_(seRb>g0sZ6*16necA8uk=Ry~h>RtKH zS*}N%23IzggzOh?ZC+r!%^H@kxrM!x_Hu^-zI49m$QR3574b{$FFbN|$!U#VxUrwo zcC=d%XS5x~zTv!7`;U%phMl~VepG=1Z6A`*hZKc<9f|Z#={ddc?MF@xbhHk1)DCoz z_(wVr-*w>Bg%01_*{%H@kc;CIvmhO_og#T3Wr=v$c7l9Qk|2r=$GL__@JVCqAfehr zu#ZR9QamH_mfGVT>%Yx0xL@JjSw8EZGlsK7MSANinjB-U1^h{l$;suqsagkxzG#9K$Zrsuwk7-#C3h+lrs9 z&Hi=0i0^Sl+AptjfR6N(Mpl*j?NNy(N%kIlB<8MFtJPTi?ui5_&95>5lxCu)3edrN z#A!`}-@Sr&yL?NYCuJ{Lp($QBZyP^vp%1&B;RT|qzh+cbYtoDO)fFA-c3;h7s~+b8 z>Z&Y~VM&q3_Q#Im60~RD(;4#~*H~xq)>2>kZ%8HSvox#!(6NN`uQKtgI3IZA)$2QO z0f6K)X;w|;SDp7Q`or*f5ny_e$$eQfRWmQ>Pyf#UqN;d3=;({_Nxuhs^4M^G~-w#g`AR2v|;X2=NB0mh<^1sT^Bx#bGhj;P=2ypoZ>^^jbdp9YRL?&w7 zJ2jem|ADEKn8p@={S@~u|0LDU`2DE@NH|;YIcU8nXQtk`)9HAp2=_+C!w)Dm3;Z>X z8HKYmo>;ASFa;UYbt4R9(dwFVy#p3F=yHw<1SSLuC24sT8(8KsW>d=Ex9D~~_Hej* z=8z`a{VWsy_LIzBFP)uAB^UVL8B3S{it0-99KQ7`e1^o%{5EWcHct8yyLT7eo=QCw z#){c9vGwc}>(eRL1^&|usJ(9!cg?KW`f!Rh)qi?E34nH3T1IRtF3!7V5JExRbW`Ap zDa)K`J*mo!u^oY(&fL__7mM;L-eIMC6KGr^3v7!T&Q_i~n47!)Z$?4f5^I@Uiri4W z@*`7N2ZZIh^NrP1ZtlF_0@AaX6tEjylrlUYq$M^LG4rzKx3}YlX*=w!b)*cNmBr7p z-(ZXFw)n%>mOd!9sHKxrV;5w%;VuC&K$4R(3=!9~{li-TC}Z{iI?Jb~+{piu>${uWFYE}yQ7U0@V$rH9*NvnG?F%icp^ zdmOL5zwwPt9Mq-;J2HG6NLmc7T|p!^>w z^L8Cw)NIL>^?aagtvlM;{NyO%)FNAkY>*#zW*c6kzIlB82eEd8u(dE$Q7B#joo^>lpi?GA@AtAUwHb`-EaP1`++{Uo-TO?YWk)o)U& zvizqfP&=l?vXY1B$0Y2(*yt8X)$=J;V3`xB9TR>_X!hl3%5d@)E?LaFPkZ^K=(51e zJB|e{cO}JkfmO@Vo|jcjtKb1g_NAbHE46p)=LzEn9LH{%?y&t=f_>WhO03Hj4^{Bz zBgj!F1xXHNZI3@XF)Y>+YFD_+GBzSMi!@ySB)KPxYnS!Yi2Vuulk)7d$O9S$p+B^a z)V-89<8x1EknBh}gbC-z+J}#Nyu&z{V#9H-;GM+!x}-!~LOT{B2dr-ut+mTSvd6DE z6h5*ZH87gwHQJP;ummdPNlH9d!MkBolZD0pu1r0xn5AOA=0@}dhMxJ1loN*ojB~1U zlOXlp;Tnb0nOQCwG<7H{fB&toIVp^K3$WT^k3z4{Dd*pLFlkZ+$3vBf{;6nmPomPw z`Ju4Ozmr(OB~21w*UVd^9eor{!|6CcPfFC8KZDB)af8GQQwOLM)yQ|ah@gG?c-7b3 zDalcv`}0=u(OSt-+al6NGzk6EKx=QdkFSY!MfTICZt%S4*{CZ?C=DZhMU6 z;5}~0$Q=gK*LZY-TRD#*j5iPl;op5^`>NgXPNE$?fB-kx9NVRKE5{4Hj&>GO23i6A zcwGN8xG95CV(_>P!m5w^pdLCbe;UoXPiW%(DA4=FXPV3nhTJ@S<8GBZ2ERkug0DVZXWyFcA-_0+Df7i_z1^2q6-37@NLZt^tlPm>!`l?BAgv^drtDwh?b%;T+7 zj>EFnRI%Z{BI^2*UL&$WK4A)MC&u3cW-arVsH2nY|2dswL^>~BXtf&C6x|q+^ z#UT^@Qltaa93AFldh|+7s=p#NS1{@^gHu7@ij;h(G0(J4Y34IX7CgG(VD^{fjL=8J zdO1<+BRv@_!iV{h&jPJ%T(db<=(kXhX|3((u|~VqEdb)AD@ebYm89R$HJ|FP4??FY zR30IYh0L~CY3v(SRpM9|ban~|pNJZ|nn?u@f3`2he01=x;gPae{BLD@!#}UALD65E zuMCz0$A&fxO6tpEpIqmGW8 z^A_TYulJ)MPzxFbD;2vs$yuz|AM^-5VOP&;KX*A%#zj$Fz6iI0@@YV88EfL)G(6$p z8xJl+jxk^wAqD<%V>0=PNKF!MQsOoAtIyt4G{AM%dY@G8((X?|nC|AFQ`<8MXNUfM zDF?V*V$j2`OiJ_^NH#pUCeFEuvmJaxYs}*wkB^}WvLEVLPEv}O64r&>pYoXt0=KlA-9ja+38iN=QeUvCpJpF^0 zQ*IndW7JD!_9#w1n!;fZSKBL(w4N9Ba|U@hm8A^GS!gNLTu+A)>Tyh}jkqcoFR-6;TiQ=)fVMA?(iA z?;Mnq8_2?WeS=8%r`^0r#@27Q6a6{cnIosp9H~8XM9|dI{ro{f43xM-C_&~g*DK=b z;%BenCP#A6JgUt(;CrUl zc8K68-z##+7dZrTj}G}_UcRgclb3U35LS|%#L*EBq1@W4$pi^+LurZ9IV_f zm7*+B(1wAkCSbI!Jxp}F=T2NP8EMNLQ4Nkffy4Kx}tQ3a-B^5!ri<(V&iM0`PwSSSgCc=QWTWUP!!w8(i>ls@GwLYJ*XZR z>v22lJ*RRGvypmo+^+w8+=9n`&Y$FmApg`Q6!sJ!ZNSGLIAZ&~rj_6O4b;a8NK zQq(U*3cj1$$gL6ELnJ3lJT8Gxo;6dSkTu8h3f(@9GC^1B{)oc0M-o$#EZ|4Byl|xE zb@(p{t=T`#pxYlL{hU36V!v1pzXNwuaq8u-b(ka~lTba0`z~0gWMj>b(&{pCgUn_o zFdXc}*D~^@op{*8QBH+=KP9useP>0!a7#k$XlKlJm+Xsirn4fG)M8ObIPl@7OtUSf z*=tZ}z`bVkTl;hb_6P#I^b?$Cqd(sAEY)_?LWJ}x7Gfa`jX-d|`bQ*h|5p&4R3>RP zp6sJYV-)_eiwb8Pv8PlBt(<=3P8+wW$8MPxYV@8-vMs4csw~#7wH`Mi)#lZo04U2E z5j5*FUqe9284;+DNw(OoHO*)EOot(JYpAB7LuV_GgzVY-w4yrg&~JW(c``}<#?J}6 zN9O3DTSVgh#A7swr}@H&ZrdQ79Q-1D=-fzn#<(NwSU##F*N%P2BO8ppqI6j6lPnz| zW{5qKB|F}p;R~CV-z@WmP2c#&3xTlveUgQHw?AumgdmjNc&1)ed_NXkUP_8+t`kB%Z*ulBkYA))JIEuWKp9 zM66_`#22q6AiP090Iz&3&JM|U`XJy@G#k2){8DZ4bdq+P=&iag@Q zNNUV7A)8UW#FSNt5A^~GD2aE=|C5!B7FftwrD_XPcKZcy*PCD_Rk^l6(89VQOkye&VL3)f}P z9-q*jfj0pDtF%vOPLiuZvTX#`Zpo#=UN`R5ihi)R0a(BSczN*>V^$$63Bi4^=s#ff z4hpaa09~A_SAKs$yzuCo3IPaD&NLJ-$BtJ!%$871Z-n6a;Ky>oP9)$tmE9%`C~ifs zY0YZ0Jwmz?i_~={uj+7D6keeXX5O4O=oNb8Zj|Mn`lI@~X#0=bd*O5|QNl0UiNFRi zN4vSl8GPa~zjhWK$jZwJhfBtBvuEfa2_pJ`c@MPVmIa0t387Mj_l(te4IMbEcjNwr z+>8(7PET!Oy+@z*9AbF!V!d&fKC4)7d{3WMsn06ZXZ;!0Mi7O^yyL7vT(avm56xD_ zn2QF8))?V_j@OdNy9q=g1D`N#JHeJr8VJe`i&O`E`V7KN;<05DdT_i}_Z*GAj{qn1 z)g#(K_1Rn>^RhF{m$Mw{ddJUopO4)2SbY;0)xZ{W0=?$qwUe}*Dl24mCvgVS2}=mN z>#1)?#ckJZ91v7mNI!7BB1}ymy?o$;Cg4u-&`;_9I51M5k5S^1%zXqBBx6S*)s*cd z#mWJnyAsA0Tf=N|LM*-b4cK1|Ei>A`2NLN-{q0IohwrUn%tUkQkAR-zMD9*aqR}VM z_sAEAz#?N%*dHiyi_i(kmqVx$G>>{=hi0)cFU(k*v&h&YDY?@*LDFX)@l)RN0grJ9 z5{J5WF^y_`stn)pD~*j;O0o)k#yUje@lO8nAw@}4U1iLUy`qO?#4X*9xar<0?ZTJ& zckSI0UMwu2yhk1pm+0QOwL#9xeBvT+{Mool+)WC^*$xL#Yf08KC@!LrA+}t|7Kq#)O?f4d#^~b- zo?&&?i^3|mvMhS0$r%`WiL4$1_HhX?lRnB;MH*#MwX;ln$fXI!%TT*E*ANGPBQTCz zMB*J_Uc%N`-D0&u1V$CNo_JyXLRq*3Eqn^1Xnj0jTR^g_7u`f@ z;?N)O;(Rs@mEAF#rDkH;OQyX!10wPgMd zzzXn^`Cm(A{5tRw;VcrxhBIVjCN;59MsYDG%x_NoJ7XaYW7}9axGa)0j%LReX*CIv zlTujPo?B%zS+lXY5ndGlhY!5YyX5v4U&%Bp!z*$ter>g{R!cC2zo~geIM#$ zqj-@qV=N*Fr4stTK*|f?7u?5XjNhcx3!_7FN+`Qheff(i5>8w^kMu05Dv?xy3KC0r zp;aUyjT?^~8wH0K@3!i*p6BvN`FM1OAKNzvF%0_MZFfci;q8uKqQVyyA>9+SYafl$ zBt||Ovm=U@9>AT1>_Y;dRVXUtTfuFH94ZL()le8O5ZI;17Yso8-Dvf3k`gf)SlctL zXeQr^Yx+wsx4twekzhyE8eI^@7g7Z}pD1R8-bv8trNX){@B>Scb>n@LSZ4hZy}-8s zr{~?q>2b?r*l^Gw(u|Iv6#D=wbl>M`SdqGcP`x%DZ`iVj4Sk{hku^ww@j3M$BTQ~M zI$duPb~5TCqfAFmsx6}u{wOyhJc}&XMz<*7CKrmDmcSS&+3?^Qy7x!S>V@V=)9#B) z7DO7eiV4?3@F#AP5z`kZTgJk)R=d(J37$D7#en75(L z9!F*?5d(3|Yn-s9BGWdM0SzZG53+otQwyz@~z}JeT=~u1ZgGYefmQThLx0&NVf(JkK zM;L;z$`_gvTd{tc>2?A8S>zG0pR`B4R0>~pYIr1nozaU|t5X@mLe)N{7nV&nRxm_8 zbonBd4Nf{V?ju;oz}vY}-g%b{Y$e`A5WT=Fd$b`(ErNFa{yZ`Ctq5f@hKxr~enrb+-i0qEEM)ng3X* zLAIw+HZLg?aJfBJo#?F3{Q+ilqtA+~U$&P?6wgGnyEebyAmJY|0|o-dIuib_ci;Q~ z6K#8e{4p{y#w-$TjCyaM(YQDjpS;+Nsl3pcsb|KkKf=JRI`}(`-obdi__^(wtjgCK z1#Tvf3@{$unV_^UNZ7CQ7t@Sf)O*}~QV1U6I}QBKb86KUAQ&5N{y4}oP1{KahZtw1 z8M<%;S#^CErAKe`wV2~RaY248+|%wbiSvif9q|b0Qb%@0<{x^WRD4rbXBxWFOZ+F} zL-&y#H*I+FGkXeB>r841_DV?T6@OF?n*?c5#6(!y29G!&+|NVAV?auaVpCFR?c8!1 z%*UYkPrdFXJ*PGB3>DRpLclqDF|?|n971@^-}L@8lLd-m7dv#Vm)If0^sqffIuOUj ziR2e|SqV-|^0SL`q{cCGH<}gfBL?wq!{K21-?okrlei>ZbzhDY!9Puqc-&U=AC3sE zeL}q$uGWaVfky>mD}I6UK%5FTMjd3gk!Ji+9>!%aCd#<5{>N!=1h))N2~ zi)`F9>)TsNH?4>Nixx(g8cdX89wa5|M|f+{sLG-SnwYF<4u&}Kp|Z<7C+b#&2$j76 zjR8T^{i5bShh$Iu2nb-bgsR++Y-k{7Pv#ed%FI(jmCa1lw`11c=II>rC-OH@4mV5* z5FoLE!dv%6ANms4TE4-khj>4B2C+6kk_h9cBi?Cm(>h*U`QWiCXQcX?%qV^}K}X|W zELM10S9E!$BCqREeudaW_G8|jJ`hzbh(xHyWrP!UXw<){!ia1QYv!E=Gf`qPe1JM{ zlajlJbMEZ6KQOpOhT9S!?~_46_@WoD#2JdXShjRl%6o?}RhgZ;KGM5`M)9-LtNr=o zMF6DrJAb{WsqK*NKp(lY`KZ7m3tSRvD*pnLIqNhCKXE}FpVh!DXF=$pv zvM=1>hduIVVQqX{jm9Bg*)`iCFP5zs`(UR-Ub$n_XraNaAN!kj9`e2qiiBER8b=OU zvhhga$l?A%LhlIu`rAd&yU^ZfWYxVM#2(k%-N!M-{Oz`njTCcwP6>l>lwP&2(j3Oip0ocjoO z4~k`b_E44G>Pw`|J3;+{EKMFi(BXs2*op!lYzq&;dDHL$3=Iz6xm}uJI5msvz*)dkFKO>197|Z{ZI5yO(ixjsA3yt(N6^`X z*zZ}F#-_pW>?K~{G5D}W5Y-}_4_h3XG`0z7i9HQLD38VMlBPnx`JKz8&3xEMf7E+y ziHB+Dd*6m` z2E15$9}fhPKNlC~lNaaLFxxh_S2b&JV>^d%*>R~O;&DDlEYPyuaTDCrHVB&v^CLjy zrwC^ z?f5W90y@8ELXn;+PVS1#zae=H#!Av818bCJsp}Z^QL+9EroOQ9HSs=&z zA9`Q84CCGs2lG7G%Z=j`Fwpg2NQ6C*T?xH|l6 z{FoFzQv|$`J0P70vSvQVXA1ixm)P>6j#YgM)`Kv^?4^{KNinJT#=H69pMCO#l)zPvP8 z@#$?J5aF?Q+g38O1pKcR@y30q2ajOe(?(^y1;k$aZXOXgl#HP;5lv%6hB0)>0?M!e zTF)a=6I=F&1l^b@3$&FVp(2d2HuWp(EbOf@Vt%Zq5~Ov<#oZ3*_00?{s<_F+i^RWfew z#^qx@?sViFVvekn`eeH;v105S@9Oil$$=BP;b4hM9yh7PSdTQfSIZJ6q9ki20!nIg z%1XLrz_=0d1QtxTjfWB7+ix}(lqZ-XqRKiBr7M0U2<9aAz6JPHw8>X|NKE8h|5p9jE+DT7~JAe zAA}N@zaKR1-hhU-8qn`pK%3MbhT4pH^W462KPgGCQkdTQQg7@)pqBX%3IL`;vB}Mt z1P6SELg^E$Yj3nnR4Lq=E35)Sh1zQ^u+q~aJC%HhlymERe$th8C!y;EC7DWNAZ~h* zVv0B&lA}zrV69IxFqPJC1SSQJVg7ophf+6z&Ekz0uB*{ovd+p+q~Nti+!1TtQ2d& z0iUOph=FW-2ucM&pK*}M2^+OB2*ySYv>GA{c7ag*?6gof`T}vG#i=bQ{U~^UE0tH=f>dCo?!(XQA4(Vp?vR>P)A^`Z zXKka6bObsZYc0F0-c!Q7T#~gM$u|G4MYgFBAGY7L0N9XBnNfJM@(~u|*CE4DG|g-A zWUWC^UAU)n)qX;!bSdz<^(?QI`m{22uE<)hv0B%dqF!Ado$h%r2-(~6=;_#C1zHn< z2Tc#R=rfY_?n(NL6y(KYo_aas*96{>i&r?9*h+@q_80*Jcx0G{IFopx$#6eDSamOB z?=_HyJ$%^1dHHr|c9^o3;D|13DKC(MqA0E{ z3R?)U+y=%`bpK^$^)B?R~^-Gg0YDKDTPkAjD3q2YCuuAqYq2v1Z}Wh68eex z1erX0Kf2b)gs)58`x*_ABV_cC3e>SzWKqZROxU@C+oZ^zQ|ZJ$5lG=4gQoQ|iU1Sl z6E7#5x8V!6>jy(SVO?AwvgKbD6Y~rL%JEEOrSs7+w6IEOp&;fl3dciy)O#C?!9w~_OG5H>5als3a!U>XQJ@a&f7%m-B+7DKw z_A%a*7w#IyA{RnXV>oThBshr2R(Ft~CLM8O4o{C-=%jt*!m#aof+;Oxo-y;8MDTT7 z(DUJYIY~e+!CHwR@5dLUmoQ_(vE%@Jz_i)p9ZUEWhkT9fs~8WKc@N~@5PsXd2X8Zj z9dh%JfaTx&pcU9Q?TtPoyiyn+OJQH)-oNu>S>q`EB+9>meQF{)!*waNkB z_n3noHQhB1rvTYvj5W38J`%sJdNd*v#(xI$bF^(KL76n8N%^o|mAV9F=RJ($Lll{k zbP%d%)2pMgR_d8$(6XJWPs^;_&?1Y=CEzhwmzILG^BpYov#h*TFJ9K$8ZD$d;1lqT z9cs9MDvYEGm^TlM(S3g=LvoP7F34562{`PTU>i$dH-V3kE(KN@4vR3VhHTR9cyzK` z7C9w=F=*U8%6As1Hbp-p7`4Eqrb?uA*+P*XJq?xly5(*qTYYgAlFft{ zwEalB8onNOk;2fQr>dF->u!H;wpEdAFt_{lK~A`GhUDh@+jSZ^NxEjuPu!E}6s@D# z$Wa3mlp38ikybmz0yDKnR+PT}D}l2ii=sekZT+OWgSq>-U5nZ1z>Xe{Sp(-JoW^rx z6_-hpX-^$An6;dl=-LkLMs3(!&AKIMZIHQbJ5CCK&Yyu{are!6S&^rfHiM^( zD{eJ48-zlT*H##6G<-k!YS+d+d%$OVnuOqx>OwmbtrKk zvo}mM@y)TlVbsyPMh_%G<5f7{iA+jF|HRh6JK|kWppzb21o_JJm{l-a0daf!nv{9X zKTVhfcm|;XOdgq zH8qZ~sLHPdZ!vsFWJNuMYPx?yAKj99iew|_*ci6(SBM%V5A4AiVTU|FRc5NqDehXy z*w!3`7uTO_H)ViKZpyRW(+oj@d{ZG$gJGDU&w%HGyFx&iFTu`lFn^}lAsRif3Fc*o zNr{der70)UkP~IhQF#g!o`P_XU@g&dUu^6Qhry>eydTP54lC6SVi+H-tZ*nqQ^N${ z;-szf4+^3tGDa(D?ezlyF^4va-;bvq}yhbkcl;MYz#Z; z_etcCZ$kd(6u&!IWlt8kPeQ?jZezz2GEd6pqvnn)ig&1(pJv|$=ppt2_*TveFC+_# z!UJ#)%|v@>rT2Ma$S{=N;Z|U{wmIX3TnBDI0jnpT zvDJ}$q)+kR7>|vSf_I0(9+%NTnX*V{V9T&k9mDdQ+kDJ;4-?I05)mjK?^-ddC>Mi^ zlY=V#NG48KzsEqZa;gF^Qs{%x8>?w(_y1P9yqcKcjf=7T?X$W}qe5&n5cY>x&{n6C zS1?dzwqAi;7`wHE`J>oWy-*HPK-UvyFNJ>=T@u^28EPw}_LL0=h^+1&Uwl}=K;*d4 zTEg4*JZX;<48P^RG`4Ld?eCCQA3tgP(lpif_{|=YnxQ;GHhhWbzULOi2jLgaUF;1duMr)s~NgDT_x+e?Ki={X3CIB1Ykrmte(MC?$?)!L)<- zR|(ewD6+pW9$>=|nj>!Gc!Gq~5gQXGQn1JB53sp;%8%CP%pdQPOrElRK1 zP?f%>YmKSn#**9(>S<$$Ki-a82KP;q`(-3q4m*htQ*60O7#>s9+~tM}8ltS+TVfi01;*kw}C#je6XHe(EY3Nc%;+!aN|q*M0V17t+< z*M$891HPS}P^oQl$ZA4p0Iv+Z9FYM6)cjf+iwj> z$(q2nv(EJL4Ufsm1W&N9W?w;jHh#dd2LSIKXa!iJd;(~wF+^!t572*e+rKBkG%;qD zL8O~FCaEsvT+;DYxP{@E7%n3LdGHL?f7X{$c|ITt5A_*QQTGtEPx}EcPDf#@)}Bn+ z2KNJJ^Yd>xnDOjpk4lk~>c|-55md08nVzV*jh&Iaa4i|V)N92xnX_#n zjZFiP{EZ__4lc8aIjXrdBbP-}4S1%2OQ+wW5>vWMm7SUwdS+mRX+C7qAwu3^2HT7Pw(Jvo`k7D$j@vB>h#__Q!Rvp4_!o5;(C3&*(T zGi~ieZLc8AAlajS{1({#3VofV^15uMNrUE@EYzLdxclLy}x6 z($`5HohnWuTWkN?7e-BtrOT&N0~6uB9h^u~QlLu|Fhn64|FMXZFG}d8%TsVBvP<)l zrX+J0!q4#RIw>dH9m{dEcH_VLZ($|wAjkMh9dvsZl-UcD;T=fijON6H_hc6^& z#kLnoTkU!I{nGGKPv%@t=5M$h!mlJsi|FNJq=``zUz4&i!s*b!EM?gQ0!+L|fCQ;@ z&jfePBB#+EmD(2Zm$$BKd^-30ZHcjte(py^P_AHE`XJ#qJ3N@p%i$q@hg4T zB|Q!x8-!*wgu-C~hN3*ot}}}84yljbUHL$Gv+vQ}>u*>qld-*nKMRl0Vh_{cCIU2) zO+5hzZaMXDH{~916f(y$5M-N4nuhM;<%^st0j=25cei?os@k3$kVyTmNXH|j*9pG9 zjo+cMXV|DZDJ$VSqu8vqulO8tYTGzEdlEJ9h;mUDj4>GwN2b?Xhn@}^RQX-YJnp*s zx6I3fo&?H(!#0I)R&}HyX0B|RqSws?+&B${o|n4h2Ok5WtODn(fz#xS(>2U7yVW#Y zyk#8SHxRFMBv6`3)&lyVuH+LDCtGCcP2y$G@5oO#kPih=u0lJ3cR>ZdZvLU!L~XQ zi0nCJ_me2N5PO>hjqn~#TlNv{)GOz0_I)8ijyHH(h%2PD8}=pAJpG=mD1oPcoiC?7 zfqAWm_BDOFf9U(uzCfC%RblHSG}Nwtw<%764^Xi@T<+WAbN( zkF(I_Q>h%4dJJ5cvtxReDS!WV>?_4fd+L>Z_QPmgizMU@&`YX;1TOp62;^0BWknGz z?y~ku9~KU4hGqvzxuuwrgzqegqAlYV3@lSFS!%7rdAbpbqQdU$HBwBSw3{~ei<(UP zN**ENcsxVj!l94uyC8N*iBgE3I0z-%R+Sip9g=;&VX2l|N_I%z^XNx*9MQ+8Ai+VK zE}R#nvbAuJfu7Qiq(#KOVsSSs3 z5Nft-8KHlY`nPRs2zckpd{MOHW1Pb`h<&sFj9QzX+E40+f5I`Ai66FKATnyrsw>*a zeXQg$NfA`qxIA){Gf$_%y&72^Su)LUeMPSD;E2!m7lInQ%9^70v20y}xAv>bVm1+b zK#1>~!Vu<3pv`U)7##{^-vHiiA(_;dt~Z763$)&ifDRJisHJ)3=#BfgIck}0&d5jY zp&anY0K19Ofgtb6vGS0)UV+v3261R}{s)o~Tl3DF#u)K(^J(5wK<-ghW`^$80#<^W zgx+h(#|cCTx%n-;hAy7w-9g;)+!#fdPodNjDW{qXnT+i3 z5}9eqxMfeG`^mEBwGP2|VUpPRi6|g>8dxAWzV21Xuw9Q2lD(-1S2E$Pq&}6KPb6H# zU&(w0H=o5fo^}xg2%Jza{sB)UP=}!?fN7vts^7lF!k0jf!9Y;%z~5LpB;&GuPr8T8 z3j=G$R&W_gs8wbVR7*_7i^xLYgGF#3Pqum+3HM<&|w zhIsvT&+KPm;(Hbi?G%M$7Fmx%b>#1qA##=|RG0AxEDR|U9w9tvejC-ae;=+RkXm(1 zhq2=~ipEc`R&T}$MvR`02(^RM=O*>}TF0|BiPO+icMUsajAh1FA>lDX8f{LJq9Y}c zH8+s;8wB7f$9;_kneOLXw)DMqav+97;oCT#23zXDD)JQ#|C{VXgtoxb9@+aK#YPtm z)(?QQF;&&#s+n7Hv?26u^4@pzAkoNSQeNHXfCm|sNUx&x3&`obUcA$>0Ctvm;iQs{ zPIhjsf*>nZrb*k7|B;m6?YHug@YSbDetesADRCm4M)MNbk>X9WPdJwo zIu4ZXZI$gMEt2g;i*`=1PuOL5y!9mx*G{e4*TU3l_qsCJ8IC-HiktGDAZ(EN&}Ut_ zTo#!IcVeKt3?7|`xQv{?q|Yin1nwQ8&Rf6onA+kO7O&xcRAckaxYGiPSboS8W~4ShknMEXY7NOFk9@B8DME(rq zRJ~*@j*;^=knmB?2f!w4XCqVfb9BF|EIp5f4cENJO)V2Mgs6Ej|GN9eVsk(!`?xue zh-bzIDoDH_hI?WufBYneY7`_@5^n_0wNbmEy>saDnCcXhUM#jiL?^Q*pv=;Qke#} zGWA;I^-Q3g3d)(5oHr9uo{M6mi}oNY z><__LZ9_g`UXN&9Jyt9#ZaTnYZIlm7u7E$ERbnA3m;IUzCu!ATt-NV5C6&t-L)wb{ zfXUX2%#u!MJDF#80voerUrS)n200(lv2{8`?VJunHKee8_*5=?wQL&GKMB%iXTf@j z%Mxn+%K@a@et(&dibmY3m=`}UUm9(FO-Ov=6dx6%t`M;SwslC3vDQ*@%#2g$MN6|` zxbhSqEyu?F+K>)8g67 z`4aoqxAikg-a&NUr--a6%oJ_;0dPaQxH(Eidaae@-%lD5^RU_L6=Jk#kHK({us1T$s@S`uq* zqe;?#9Lx{2Mo_;>vPF58VEDBiwz!gS9vIN|NG2WLWkptwr}<=(>~b1Uhd?_nUf?5C zRyvEuN{sAQ@)rlpp>l-6DWrPp_2v~MybX6FY>BQ}G2DF1Z%)H*Id0X~9=zAW;f<$C ze|Bq&lR}XJc6_{k)UZRSg7D+sKY)n}A_Pg#bR~7L>z)M{?JJ-R0n#QP6&6xaa&7(S-)+3h8(X5+T*pI;_5g%cIkh$itI{ z+SuXCz^XL%7M+z^#3}lbyWrB+Tkxd=8Ib$y0j#MAM5dTDFnr~G(pZ28PB^s>MCDZH zjstp&sL!L=>oiI9xm27FC6;g7H4Iu);Kl3v8m)gm;IQjwT}L|MP;hFmm0f9)OftP# zJ=UcZ=@p`!T?za#G47x2lD*DJ4(<`c9?`}^rTV96n?c1aw{WO^1N&;*mp8MaVMOP1 z+7}O)Efl?xF&D~pD-giuVRoXfP=!cK=Ftd@r5nXDs#~NM67%8cJ!?$pEwqcbh=$Jy zF8B$S%OZhzK74xAC%^XB2N0WeA|e~CNXdOT<;OsW*NWK)&;`MrY!}||l>mk57#~7Z zM>~_EjQO%_lEZoT0QWtO+L)kQZOD>RIMSBkXK&pr{nh)__c3E{*@kXbeJ`x{bjB)$ zyQDzFwoQl;cr1U)XpWzmcagskd04qSWgUW`Z zERM%&*9}xVz1=vtYTUGS7B*1BFM)`q)xvP2vHMX;H#^zIV@dQDb#wpf2Ch?-1DAw2 zE#+ckNPyYu+x&XO7v4Tz#6=uHofzbZp%-Hv9>{Zr1Qa}T2NzS%QaQQb#t(B&QJu^M zAHeul#D2Mvop{`7&Lvrv%`;D6{g%b%31b9enMWrI$_wKOdjrAr7&@*F&ev`7hunfz z{k{eqQF-%tOzxb-B0wp=|NQzYU1{Ck;Hp$VI zCGoW2pO-@><4*6tk8a1P&e?1@u0Xv<_j6BD@wv)3DpG{IF{0ljVM}ME4`@x6jv$A_ zoa~RIts%hZ5GmI;0+{-CKfx9H!?mAFqQca-LVx^j1k_CGkH|dG@P(g%l5idO;mDQZ zvu-pn6*?U7xuR}pA59#CjgfBA7{I|F4F!ScEb2Bfy3@h+F8GyCAKz$V&+v-aosDCl z@t}w^9=%~m*aUG>IRE2**^LP!@WDa^k^#fvh5L5v?QRFHur>w@DCVK_+iuM2lO7hV zv@~YvTrjjf;gRvl?Bv9(UMb61uXJ-)s9kZ5@=4KlEzZ-0a@H@qQ^0>M3e3!u(c=jJ z=>EQ9ONve+itS51?%nHge%uZ9%7>Q{+=m6YsZft+tY^EqvwpZxJa>i2CPkGVBPJP< zIHZeuAkt2S+hl#!iZwu zd^F!P4$;eZMO8PdUUajhw=(_(_QtO$%GeEv3GR&{h4% zSD<8^J>B!ZK@_%7n3qFL2J=!a-QoD2RYXiT3PLq7ElHbIFv!F~r%tfZu!wV1i>=d9gh6j}lZ7HRY#w~LOrp^?`RL|tPe#yFf$C0n zFz(ve#LcRB>(9V&!KgKqe_(o~QvS7XMm$@ySv6)x+GOQsm3&6-=50IXC=m-NLMIp0 zktT1C(B*71T0{LsL#Sv$;pcim-hKGpWbhbhRt;>0&SIUpa!KN2&yEBZP*!F z9G4!Zz7P;=EY&IE)YoJrH^ta|*%f;LyUjl(zXXUGKB1cqwR{qOYVIxg>tL?r*v z2bE!U`d#al{SLcMa36u3rH9||Cxs>OoZ`6s##m84BqdprdJ()2#1_m_m}Qj(p9kok zBtY{&+0V;F=g#K$U1TTDYu&U&Ij~CC_l;)Jrme5xv+X~AmH=@8>Lw>WV+W-%bBE*Q zDZo}zs9r0wdiFc`(*5tFIl5S=iUwz%*l&GfKQ1Ob|J<)%N=t8yjT$Hya32{Q(5mvz z=)!)PS9l)p;+~*^g+O14w{&?T-C2fQ&gk=LYT}e;6$hyikKALFOMtWD{ zHZL%`SPqd*^UFA-RMCDPWB2neqmBZJ>*B|#Pl_X4W*yf6#Vv-1Y32k1ha*HtHL(P9 zWGt69`7%H3GDkxXDz>0rgf%o~kuZk+@uk__MU-)EC7d2+5MK_;4F6 z5*d$P!dCD``~|jxWUxawO;Q#iAcOUzk<4v3eEnbebb)aNDR>~!GL7G9^s3LfZW_uF3b5$}y~R0&~p zDX(HbTM4#yiN@)`r9X`3mFyp`_^-UaE+Ox~f0FlhSImb0%6p@WJqNh&`SX4_3ioPP z>F@t5@8vF%1-N(odGFzSvCCHeUwJ?A9_Z+4B0tp=(IbL&TA%iM*&G}9Mh zZbf2jmZtgpljhb(qU31Th%A&Vu{yiZnfhWCez{ku(3iKj==2bR-pbH>H2I!rXKU9r z&qEhHktaRjeVz%kaQ2X2EHIp^lDW!H7e6G(LV7JhK&;(q+nK5;5%;hQpdxg*q=HKn z=-Es@YGy>68`4Og(m8i@^?4={ui;8|T>9?ZVyC%lNY)1hN@mzl!pd;CmpKXG_9XI_ zEJMCFaGuUUi=p*dLY8}m(7dcH$h+wZfq#k@#&(u&o1{A#65K04@!X~%86U#-i6i%{ zV=j0m4L|Oy`T&g={40Fw{6Pj>PoPqY>C~FbA%I&_b}z<@QAyfgFd`*0}q<3L*# zKjXfK10@MK%;N^{$KirUdeRf*oZa=f2kwxDUm!#h2kt{8LYU5>gh+@Vk#<6)G~5TL zeUOjoD1z2e>*M~hs-R2-iOMa+4a)kM>{!w9kG6Q7Q_(|Gs$w~+_%xBU6z&tiZ@akL z)WLC$DN_bIqi}@Q#3ATcCdg zzmF>xqmYioY&fE#wy^%TyiX|Ili{N#znr6@K;zy5CmBL>tkkp6$rTVepHSvB&i2b_ za`Gy<=C+HKw@IAexwvowGBBO{#x+ZUAbkPy9-({wPRVMeETU}7`mz__T@ezIwMsX+ zznl>*-#IZtcg-Vpe(Ad4VNZG#5+HA^p4!0r2#li*{APeoBP1EsReF+p8@e*ktW?;luDROFj)}`cL>G zr%szXD|5h=EA7$dYzxZV<0_aWa|x;ufM(ca0JzL^PJOh<@Up?48>@^wu{b2t<64}R zFO?m9bgW(~&3RnmC++apcXN~Tbd%r8XGA$+3@#WWa9n>qLI;1MIHMlb!oc_;{=MHN z@Z<`COh54NZLZ;me#+yl4u9U?{UmRVD<<-%dA*lA$;T2e@_gCJUG4;lEQmp?WVpRf zob;F!o_g2mLfe#*K_!S7Uixd2b-ti%BeIUx>eRu*=gANw!)pKJDu@?pUv+`Qa4|%F zp;RKS!G-n8dvdfcZzp$BsB5}rx5Hy}4Kb*!G>&SKL{`Ksq9~g}2B92hLgYJ~5Soau@rzcXbMO~)8#S;KjHB?BTu5BX}c|hwtQ?1l031~w`{b(N;|nS0ie)d@gpr_h5lkM#r&N5OUU5w=fcr)Pj_;KKa`8` zmm602%iXq3r*c9Df4RKTal_uXy^Tu`3 zu7di?6Vu7X`ms@;74PnI{>RB(q0!AYQh!J0#XLea3t1k#;`!V;B%#rKySQpZ2i808 zzVQ><$*D$2qCO<{{M#vv9ox6Xk&D^gy^_)dqKS~h-)EZ%L$nJ}5bPhOe(f9iCddJ8d|GI;_-T}-lLO;IcuY34E#lpOE*tAr) zkU^+B)6tn?mBC&>7dkes>vw(_-j6ywA9ZjS2n;+k*2tV)PFBY469`gX(i~}$u6hkO z#yIH;IGxK*h!{Gtc@yZ7xYpxv!c+T@qAkF7v3OEn#KK5@+-ni+NnC;FkX$2J{+CW9 z9Ns19@FvJ&qvMyuwVOM^mrV?qfb}t_!=56Xj1g;o_dS2AUPv7kkxwEOGPC{kmuD-# z79Lwq6QlU{Zse?Z1{|fv_+qsrT`}8)?c{x%W$3&ma$FbH-zK3`Ev$3e6`k>nt}h-( z1^YH7|G}w$lT>qzQ6gkI*9ZgB|J*(2Xr;?%*uU7}VZvI_XPDV z-%v(WZ|ZK7S8OOR6{NQ3DREE&lqe6r5^7vAr3wcNxvuF`(`nU=>Abu9((o6);eX$) zl8Fiyic3HCSs&V^G&AFM1?%=Uql7 zuxta99WT0JiY-ec7Z5jc+1LqX2jUkEzv;^!2W?#FU_K-|u;K-q$A{w_5l&BncGfdh z(W1@iVbBrBbN@r4&9ATGb&?pDuPQ(!V$UE^9wpk@!(=}!VlTwiGub*3dkz1qbij;f z*qFC`a=5eXNkP2zzx%Rp`|K(Fu_P?uJ^IqW`m%5MY;XJeNt6+l_WP=YTMb0F-{b55 z52f{_!2YJxUW?&8BPVryK{#E%rDy~2OZv2`UvdvnryQ@FUX6gp zgUVHhr}LbL_|@^ciqWJBJ|dNSgAyaw_g^MQzYO;}y{eVpA#`*zcR={2gE$2~0@?f1 z_8)Mj3jH{zhd|82n~iL)wg6l5&&Ake7+Xt}LokzadDzlOTv`svgm1P88lrx8iBj?n z^+`MG9O3mwCa8@$52LgC&PLNnC|%k^lPI#C&>1<4yv78oqeWMK1&gO~dHND&OqqHv zs~A-DD%uoPfg;DUlXB6C+I6C#s1Npu2Ll~T&Dm7zfduBnVZ)>b(z9O|;rMp?`zg#E z_nT|`^mFhvURGnA5>!py0fiJsUiPa(aKPgAovdP21Hm3reA_#Cb{Q`hi7vtK+q%yH z8|S0ArZcQl|6F`xrGY*b<1w?()!uDjje9DB>1vCe%o^VnO6h;ig_)`XE8Jj+%j&r2UYirvxrx&o+?ejc|Tg!UW<_ zzNjCk^DK0%nXxa)W3FRQ0p078{uxV@t916{inT8=>$l0zHBz6#E&}6^I2NZBhEr-p zS^u~G!S;}UdfSMoAUJw zkcvM}M%XM-p39rfbK=f&{hVs1TtCnMak%Q{6q(Q*^p#lx&7!u=4Ue;mOr}GhPxxkj ziwDw?%DmBG)TlJt~@Z&5E1|gj_)Je^Hx~;1F5MPP2 z!>ObHE3a3Y$!)$0iAD*bneFdKw1Eli>l+u*1#!RDQM_mjLonlrRI{)hMTXkaOfbxhGEY&7)?F2n%ln;|zZHB@Qi!mv)oV(MS(Vk0S=dpT;uX3h|?7{^p$r%8vxkE(2_=02cy9 z2KeB6PKedsQ012!aL4%j4zr3iGL5Z2KaV$r6!xCLo5{KoIj15gh6~D-;BCgea!Zjj%MTOf7U6A<|IOOnh9Ej? z+czhUvp&;Nx4OM0KB(?@?X~p=Lv@qkZ(4s03ZqKKtAgsD>Zq;v*1o27=67@+@^*G> z54~PDucI?qRV!dy_sfo2hu6Yu9d@HC%upZYoZYcsu>tm0jV7Rocm|!qFPrzdsY4AKg z^1(4+P4BQA_FmZwb3HD-gI7K3e2nliIJ^kzXH-27&9Y<18y)67?>bXDK-|tAqK%`~ zsCu%~r9F1oa5SoJN(XRv3-L!0#;hKg%)of%ooQrZaxZ6Uw=#H}v!&a~1 zW$hu;>O&!i9F`VsW23dK%^3~asjO^=Qw!QDt(ta+-B8nH_=lEFB=Zc16)u3DZF32i z+}4ThJL6THsKcsm-<+VdhP69dYa5$tJGAUY%51X2*Qq~diAru%DV+fwov(X44`{9O z4vXDuv1uL0t;K9!>o!0G2V&duC^1Ewo-)6Lk-7zEJFNhDofqxFgY)^ z^QuIY1$i3}*IjG}46I6K)nhdd6c@spSt$2tkwYfu`Swl$)4pxf9j#Z0&b35m1gkvM zpm`(2eb|kza2)1U*$AU$I2KiNM#yAA7gX1I+c99=CO5_fCPSYp57Wc2FY3_iLg4MQ zrwu}`ciK@O;&9aNCQ4YvZM8eJXHAD1oPTelp0Tw%54BOx9BRAQGkK#uGtw>B_i?Va zotOfR?OaD&OF|HS4b_I)>Mn{v{SM`Bur`{FBQbFU46jFV`-oVmidO}4j&?(h*YFCu zp>qquNdoIb6!H!2x3wd=6SJa43j*>W;CPxkE-eUXAp$}Hxlc6_u{he_bvwLuyW2Y* zh|Gbu@TxfU@Sz4zeLJQI4EP!c>UNBf+_f#C#&Mpiy0Q!N3bZ_An%4kQ;i=PvNMJ&b zH(-`+L5h{I~s=P~E1A?d5Rkee#;49qA?HKtrUf%X0jek?0DhH@wXgL4a zUQ^Tg1||;B&ZVH9%9_{iECThE)?c^z$2BIws!>wc z?b-RcCAr0!TRfVjP@(o z6g60%YljnAyrJtMwFRrpsx)qK`^$k8T->P2O)hLt5++97OZyh5agVo6Lyb}GTw2@C zC?z+ot!7hFT2m7Gb`#Y&)0(G)-LQW(@~`K`qKm1gRXtDHC52Ikp6p!czOp}L!_11m zuKpkQ;`J+*t{Ti6=zPO%T3hsjyJmW0DrQXPjP}}XZbOax(CefqziMHFw$Hz#dz>T@ z1Y$}BJ9DPCA9~lF>OO?Sz+?pSIFX!^PeKiX9yM-*k%XnyZAw1WVECtO-almg*$jjP zuPH-t@0zWve<53Z*x&(2W-8WpI<-Z=kgZyJGGDZMjkc&*iwNIIv=7saS*Wj zfZIBuoeQVe^NT}PAJl;9aBAVz5i&2&Z4GVjm2;s&!ln=?DIX2NoIYksN^?)23MJW$ zneLQ#Gv+nAlYXI1$(Plnqp4`8{yhXC55|{_UukRqqQyrDI_CU-*;ye)e@Eql4vy&wv7h4R>~bcJW9SHDxh#Z9o-*m4*? z7ec8yoRvOJf$<$+KEa%0yhqz$58*k|WV&LgFJ9NKTS8#@dJvSyI zms9|MazQ5$8eeSBkW6D)m*KuXEe#u}Hg{tP#Y?JJ?4F3X=_YIr;Rw+pc6V(%A1H`K zki#|k8ttFj;4{zVL7bK6RjOlPJj3lgP~Z01XCy%M8L z1jb~S);PFd5uWT;r1Ub+)1o4zuDmaG*S*xGluDBkGzYT7TL5%)ZlVq8$(o{d&|A}4 zLe%eLw|(GcMh8cfVWNVDkc^C}#xQ2f2IJA&uw3E8#1+4P-eFuwBkUD^p;(VW_Od=# z9JyVeE7e;H&AISS36)hEV+a76Ij=2OS~FEId2}mIm*G_KQKZ}7gt9E&@W@3GX8NUU ztd8lAMYJxFK1`g0&>~UDKzEIN7?a^xtLGJY4)2(~6zqiE>(^6fspMQG`(V9ReTik2 ztJ}7zSFtCB8eB(i4+buJlMfJ8E(iAf%&Dl050m7Fi4X{3OX1=L<^^Ko0)`hN9kj_# z3fpV$wgVvBE;EQmPL<=IZyV92<0 zgbW*sdEz0T8Y#sA8G>hxvQ!m(*AngCqa4__5C8VegI9n;BukwFwGiHuRGmpVhAD@e z4>4sz85kJqGf4qOuMlU<%+zPn{*InAqV<_6c+UJ}UwO31(Ndydc;%Rar$hm(nEpSB z$FCYw7Nwk_Y*GJa`E-@~#ifE(0=J)F%VFCDHh@=PK=p4Tr|lv~8*nKT6SZ+%y;kmkVGVg^!XP>OhlI!pPCsrnjMg zu8@gfsgYH#2&l-K<#m^bob)6O;@l;(eqXM%B1<1F2DFmQRFuHqc`1cLgtC;B-O?s2 z-RDE)?2#>5d3i4=%dbgccpleRd$W8Fl{&an#%EGPBC_y< z+e2Oa)eeu^ zVZG@vX8jTXFBDTha^narzbsU(4D6M$TPZ1&l3ZX%hYxl0(V<%$ePLp53?*WiT+qsl z(V-U>#9k<*jX32GqEGqJq4OTq=%Yi8;~4Weaia+ne~#4UiRV3&mq_%Pli4hN<`iV# zq9=UT>jTE>Gk@lXU^5QI<}v+7A9;Q}ZS7ezyw4|(hTT&blfNv~xPZukKXNB25*lNU z4ppBS1d4kPBbtUW49fR6$l`Ayp~O#QJfZviMo%?0oA)U#18(*geS#6x76&!T(TWzG znSYC>Cig)rum??}Lr>2y`^8#z%o7TJg4h)%#*WEyoeeUNi!~QATN)bc`9g8SM=k-I zlgmP3UGJak&(E6mk^b0i{rrbqvuLpELmq-vWk#-6KZ`gUrW{`NvuK%blbxAQb^e3u zJUzc)@bVIg{7E0?GAl7pU>dihCVV$f5I1J&3rEN2RbNV;f^A933oI8JfgDw(B3`L1 zmrh-e0hKGdz{84#<;RQ5i-THz&d4)Ftk1mY$6BEs-kq)NB+t&)>dc1X&qrGR z8euV{Y;~G4>x(a9T&cqqgJbpMCD#@c7OwF$0uGMI0pmp%7K`Cb2p{-kcy$+VO8n4 zTW-0tejJl6q0_K_&)p4g^?4?{JTYy|MrZn4DOmy|11ebo=-}F4F#Rp$lKAeylXrc+-l&w9oo3`szB%L9*H2}4mJ6px zh#E)q$0OR@q=vT(Uvk`IO#jxq%cmy{?7_%A@I3g{-GZ)N>|q%HE*3ari=Qu!thN0+?+VLFRR>&-U^!v3 zpT8@pR+8+}CdEpq$yiqqF7{5}>uT0|U}ZghFIP`^>n!jmMIB4cTkO+W#9NOI;Q$v( zgKg3nks$H_2IP7_kaJ3J0$}8NlJ;5?_Hx2#u@z7`&;tdba@;1heSdo7Jp2h};F>pf z?~La?v3sqtd$~Udb%x6I{2$}?D`)KT>h^jb-dlCk=l$4D7oyue7wp`}b|5xIsfMFX z5?_JYmOQ`I3V9W8W{DUZOq?7-LS+?ZNV0+qYg9>$egXE_gY~M~`b={k$({8ob6zC= z!_o8B?|Y)Q9&RI|af4LJtI8A=;u{{Z1 z8K&A_jkXi?!R6LZ@(?X#!(WW%;VwD^ovL~TMD4hVF@zf)OXDVzkd4QkFUL)MfF*I< zq%drL#gMQK*TepOg!U|1CO}mb%d|l=HD?8*(G;C9hG^p5#^yOSx=~!qLc_EtC~G|P zS;<4To4(yOtYV4+l8%)r$oFZF(l--hFl7}K!d_EOsy1{78B~5CF2w6~xU7>sCmhxj z4laaxYG9A|pGceHIqs0(_8rI?;~l{3Bc3A;TunjArQ0Exe{Bf(Y&kQ0)wiaT!1n~4 zUmMcdlcl~rhTBUC2viyy%Je@XLJO@9N1s(xYgl(A5N$7lRZy*=sLtxZHrioA-ughw z8jCFo{GY1ljH$IO_+TXGf?7+_`Nk0UX}5Kk!_(-94VB^7+UTfoT;SiR{foQSn`u{` zHyJJM#thv_wWdCEQ@)|vy&<5&#E!4dPLQXoXT_@jKtsOt5*&LhDu_*G zvZF=GuL35Myw#Cjh97#|;z)mS3Qh6{uhi~*1#u|lC(vy4S)bKLI=yc^E`-D!9`)?Jz_|wC09TldE zjp*@LjE1e5)&8t;$O?@emPsf}c#(?HJssv@flBOMg)S)cJnyhBcW^BV4Tu5@05F=N1ZV!#;x zz_A96$#}wK)XsI(G?>p!)FilS|CXFN+o74PMO@I&rbcTf8BM8%8e`@JM;@-BzDb)o z-DF7%=`*i4Mt_*6}zksIr%(P=c_m}b`KFwQU@=chYNGPNm?9Wywl zZknTaOkw>B`-TnnK$FSnm!BS`mYb4e!$Vvam-lB5&(9pzBnP*YlDBTA`(tcP&j*OM zzCzD1qCHPHf64KV%DY3-UdArr5=hS3UBkuGe`l0qNO_039K?ouv<@zs(kj2xPH@;6 zPDd}X;Xy9TTiytVC(O}LI=$!*t4JG+4CiXN@swpq=?rnO;g^FTm-z*;2d`9q=a;{L zrhu_knsg??jdb*suKs>;C zuGMl@)A@zQ^GPck&i#whD!_W~=9)t=YX8(|m|p9sb?3K_+>%AW8}1o4GF#d;fo2~L8pXHDS=$3vk6{bwwK><-0A&T#Bv|{SmP45F~ec^JIRK>B^w&trxHY`o~QW6y1wX|>hn4} z&1`IRb#x{s8jp6G-}(L^?(aQ5J5%G}SJKvx>_8$Kz{0XW_nD6;kyc9M#e_HhbpCWm z&Ctzc_fUv=u=Df-jYBoN%2MctxKo>Ht!cIBc#SUe1Rny2JaE~gndD|8G?weDk8k4_(RRzddfmV@ z%O5sv{Qy=7LSG;;dzVjSFkTzjz*{zOn}|GcGtOHT#t+2U>sne2x?H+N!=J5ns#^I8 zx192T!o}!h%z^;VZ(6yflol^9*HZ`MPhRB{twDxBHhe=s(t7vm)@_#6>&l|1>>QtH zUZJ91?;WF^-D)Rlb8|-f{0a2=CU17DC%-j2gV^8Gt@VM^8j`>K1oj0emY>k0QG0oua^XgrRh2EMS3iA=dz`*zKGr&Iwhch-l6`b!cXw)Ioxg1!bfMyTV#kvgD>q@;vgdCIbJ$Ok9Pv=(RHw)2){ zY0?!6+aTrR!tB%2KcGB~ zd+-VGT)qE6ZJ(a9JdD0h__nrc>iVh zT(?`#*g2LulzZ1cgxl|4Nv_ncNZ(H|PZFruaMoq@c?a#D&+WvswpQ7-gK!%lJ1++h zwkK2kav69qJ4SoNUU_$L4Eqe~IZE~HUd0`u|IR);I*T|kDtn7kSS5Fw{^L9cblGob z!wN#>^SkV6QuR{-XK~Zo9&)nyPS-<)1 zY5vkswiNyL^`b5u>E&Al2Kfl#mcR6Yd`oSK<>=z4RxK^Ji0m?g5J#Uj%4RQoddKB_ z%hB?gG#gp@;?zjli?2vlN@l0due4Wwm;7h@pu}Hd8`U`oi~ZzEJBaaTdQ~%6Op}+{ zX^JAP)K8%KE`GVU$nN>0y&s1!=p4I@GH^@$pT~F?*t1a;piLT?X1c zOHahpcVTmy$xQCP;~!cV*SwcaIm&(n7KpZ&UWQ!zTR-abxn!L1&( zgWo@H$81fb6k)x6%wK1SH_7g@rF!Put%-JjgKQuAu(D<9?69qHMT^cI9|{@_%6!;v zmvUNvgL_@JOmC#!lV$I}>Wi21x^P675l@Jh+WWR5_Rx89(Hh@a=t!$rQNwv`sFH>D z&7h)M+N;PM13=Zu)MaA`8VM(?%l5QaVfQ52NrKB%*x&eU>)JsD`%If0X0uz%;T7hY zHW|Qz@>2h-;3R}U<^)6kop)MB=EOL=UpUyh7KNVwq5ShdF8@6DHBD1>;(xen^x*tb z0N@F+_jjWUAw%vC<#qG7=5cj|K6I=8O#cOWrdXs8P0LA*<31Kj$}k=8NN7UpLeo5q zT~{m&)gk&=c}>oW^tuSa`-@$o*M;XaM(Y#R`jT+?xsarUrl-8=OUW13ClKUCs$&Yg zq|R0Bjy6WCH#dG`OjH|}5%ZCg4Ip-{P{J@x0$+eZPe} zL-^>T=K1$c#k9YrEdOkA?b+b@XNz^9g*!o6)Y}>RIQEyvz2rz-(wfZchycKz5eF7BH^q#PI(-mo$PXlum`d&J@{0HF^zHO8q5bdeJ8PINLYA zQzu2ke|S!lQ8a6$Vc@QJgf?*u7i2@FD`*E@Qk+vTQ|z)iynk%*RJB*Xy&A-%)B6@8Oe$!;r#t9PQt!5NBCtoQ;ufkj5 z(s{yOI~z)10VU#b<;z5|YNo`(VDstnM3xAL$oyLZf4xX0XVD|nXh&!Rw_4ySQ>mxs zGPp~E#ll1M;>_^RrnxQn96>42fjowN8oX3UxI9YWOXmA!)=;6qRDS_|3mjO2y#Mme zcJ=Az+oiT%>LE%vrTTt&*$@5m1?_)G$No#g>m_9bT&u;tJeLjI`rf<+!3D2LH%nzk zi^Q-{W8_5#moa#t6f5+4G{$DpW+|oELx(@`nM2bvPdDc@Jmlirys<5w*cPk0g$pOj z&eybLU-m6g$Vqe5h)G|MC9vK5P>bim7Bba@QtN8mb8n7j3>nvXO!NIATsXDIQllxj z#Bd+dd~@E}L%hioO2jx#DW!$av8r_CZ(7i8py%)j-;@AQln+f~gDh{kNrTW1*?VLQ zw}l#LO4jGoxx29>!gZvWrK1q;6v3LSJQvP+gnB;q*K=zRxIy``qViSa*#N+7X&HNd zbBI|NQBz&7C`gyiQVhu;nMjSgaBvo5XnKUn&VV5qN7>NuZ>6UanN}Kbwz<#s2AGl! zhN5bJ2#J_ZU$z(W{Cd)$wKKg^Tem*`v4*Ba+vM~kf0fjRHmlRyOL zUZl^c#3*p)q%;F4BJGiYBgFhp;0U&ZzEe@Rho5*ZNmG z^tW-w6_fg$j^;ct#jYEg?yxxh5x%WI;Op>lkNz0n1%&T{5qy94|HOC6Pw{>BC-~YH z+>h_#pWw@n;v4^e;9Cs(##nsZSU+~opY8c!S)DS1o#GyL!g`0^-sSK4U=R=Ym0K*hrOlLWy2?TOf9mF(dH2v~m9yr-KJ zG16;CK-yjgF;PXW@6`LEnDPF_3q1(r5pQWeMKHd-c0ki4j<71b>3a>ZDLQ( zPi-So53|QFX2Amo?TwI|+H=9?vi;Tbz0G>T#(mm^0w569=r_~Q1eS?w6vro{F63tw zh?zUOdpd(kRL6=8r-^0$T<9xFJ7A>mL_Cr^K7vyMmwpQl_iWrQQAOK-viJ2iA{bSki3Gx zmIzV0&B3(YmKjW!#%ijt>D zP{NO0N{ndQxMf@n0lPQQW_wl;4{^ngFMR;R?NpxFc56uzNeKS-mHVL44V~)P@yKPn z=;N0K_}jDkUVGF+d%kUAB|>|uaHk`*2eO?`3`1%?kljDlKN^My;Cqv#MLkCPrVvAx zp@&9lsTwoz)MD}Q)g>ACXp0M}D#1X481C>>K7_CGkCT(u1MCd=+1i2=UW~;uUrK1& z(_N2Ym@fBmll;U$(j6K2TAmGjBG2aEd&JPU%C-K;Uc-=&qBJnu0Vc167*Y*`QWu<> z0htH={ItY(D)r9r#U)9!l7NZ``igl+-1^r)p1=S2@A>Oz&X~iY0<7UBzEfRyVm?_i z%A2#l9)T6}%#UCVANqg5Qu_J9B7#-=@1MXbjIwW87;j+>D085lbD-;@2otFwHQEEt>8cK$UgETOFf0;Dqji*?JT~f_#4p-?^X`4f-BZey_*!GVTD6hiqZ$IJI zCLu@Gx5y@LEPWBqS-?wS8e@ycr5-H7)uv>!dwHdq#(;T38atsjew)UBFI5cTxFA&Q z<(pm5F|syW|EHPTL~tsv^@`i131U``nq#7U%NrRvqUsLx%4b`-F_c3mX4$ADoo2Sx zAEsPzjc5zQR%v;7A~%zebC&wawv|YoK`D0ej@xnwk;%o)aM*p-mpws5^$b4HO2XE2$@%tw@&aBelFe}C4$kUD3e#2u-B5SBG_YWk>uGZLc# zMc|kKLp>Jf`rT)DH zumG{NSh72j`<`Z<^C3U1In9W1A!27k9pfnyqdWI%@XN`lEWb2DedBAq%AG#kRm{(7 zehI$3D!)r`#>-x}e$Q(&oBbhu@+o(k>`RDv+&p@2l@;VcGxC}@z1frAYz-7Lp=R-oJ_-<3YT%96|SF2sp_*nG?IrlE54=J_Rn{b%S^fI1=X6~Pq#tqW% zWyTW=^hs0ABIe$qB%M`ax9*r8MO%bDI6umMMTEO)F+@S=oal;)v)X)j&sA`}e$dW; zHGyS^HTPrPVRc|tT2*tJUS}00=`Za5gzKVQ&i9)}4=_Aqnz;^tJq#q?qvOw=;~XQ9 zjyC}dy5EpBb9*RFPIsH=YeMcDN_bUS5YBLarAMb5Foh!#tL$2w*zdxcf>>f9={$1~Veb=DVe#jQtTtT8~5&PcdTvd)@k6FcO%sHGnH+wBj9!rz;nI`Vnl%)^Nhv&64?kfx4 zl6N(+umnt>pWN7#UYy*}l)i?3IQprhA8T@bQ@WFWJoMwGpR36`n^KB{h2N0m9e55E zepSh@;dvZ>^~KVZ;;`iHcvUBF!|!#HQ(w+9k&wJq)*jK)O1L(vs=4?$M(X01i(*)Pi!FW@EG3N&ubMAxD`vZ)l<#U;&8OB~o zJdP*1ppo)j*3;JbCa6jG}#*8WN8ZaBs95An$6+S zNiTQvEh39OxUU($!HzVlY8~5?rf;7%T`4j}6_Lq+@p+O}2nB*q=RFZrr-^acTfwF8 z`$oqZ@oa$!l7obcrV)%3)9HZ~_Hs@$`g##JeY%NUB)!vV6ks0Z!NU-HDw)zMZ&s6x zKU!b?Qz<3k1+&CnAMf$;P9JX-(dLKSMtMz32khQEyyq70{GRW>>C0^zX!d@`d%oeF zxB33-zS`{h1;M@rwg}teedx8i}wuj&LO^kz=t8reM()- zmq-ef-$R~3nbI$Om3qWr!q!a~$gSlCXKy1NUKA`D(E|%|Kh7|W1Iqu)dk*u?K^`~N zyIvjy-Z&cp^pkawNC7H z^B%-Ib_;p!J{)Z!3sh}(@7I?^8k_Fwqe60e)ZW*5kA-*kP_FF1fq!M{czE!jS|8L$ zg{G~|>6+k$hx(no69MdzX9plr)Hc|uLh4L6vIBhIjC3=L6PI*eFp1|5{Ehm500%66 zNn97b@O`=T&UMm@pRZtSn2ewbgy7AoP@lN&-Nk!$^VUD|oJ#2b6lC2)`VKd|J9*D* zJoK|h^tnuZP=YelZa=puX=mo{KyNMYsRdE2*3~>GrLv;bsG8Iy!*;qOHneUEt`S?m zv|11eK24L}H-(fYg|S&!&NBIL-^`UfJ$3TD=Dr{YXP^$7l!ygL6YZX->w}>22TB4{ z(kwJuvfT5aX8*^4X%rarGPHUT3OuMFYQYqxGRGOC(ZD zr1g?1vYk5~?@`r9HSXGZFlqH9z+ZZBTEglCcYP`zI}f@CnM1GJJ&EhN93qouq1)t1 zG*x>51Sh0ZWcAXWJ09*CS07CP)CZ@HS>52)Bv8Tnso7V2t6@Z@TWZoGhGp{RN1v!) zTzl}s_s{HnG_}@v!C-dZ48I&W2&V_9J#eHzT=4t@A_N!|7bFHif2(nQ;zBzVnOdo~ zsuRBWnz+Z%DT}?2@t((dYdFuf6HXTw_sWAFIluEl?Gd*r8THrbDs<;BTsVKh9bcjO zYH8zF@eceuJvBajrSzR~pGQ+YjK3R8y)nEeo<~#EiC_6IBlwPe{dB1Fm`60Lj)u#O z+?gA#v#zdmqMWVWms^*Sw|y3zD{V;42@hSt<*3KZtJ%KdTG6WQ%MnpypJ>I^HWKc+ zuV{gt-MDjFnXzw0^%`i6vvZA}8FvCMN(LD=$iC)evDhdq@bH8On+*F^PC@-@*^^XP zX03Guo4D4iZ`g~r3kt!5JFoyVg!eu=5svHOm_VD=&@S z@rW9tiW)-lW@U7{O?5?wlMIK03!cBBDTs=doiS=B6wTXiShy5>Y{ulAeY3)6vR;(f z*DS*6GmWC*4}ArB-}NeW+6nXe+$QT{JNMaNf!C_$Y|=}{8aL0d9V(p2U35dk!l5K> z38^3k#63F@?!!zTKvv<6Iw_2LJ zw|sQsJ$T>oY_ak}NdYw*Hp$1nvqX2N@XR!GP<(O%-TC*EONbO+Jk9(!i)DK&CDE-K z+W3*k7&4>!BV)+VtFIdCGOC?MZKR>*dbQWU5HTJFiJ_6SpnTStw^tEo@jna0Sc zh}gMz6#fq8`&OI@*(k2&0M^zIng-efxIa^F%fckHCpUAOHDjU1#N|r##i6rv;gW8y zVo?CEeb5wOs7Z2ZBRfs-$7)6Nr-HOwN4*7e0(t^En{DbMdo}R%C(3jrDo!WjUS4^h$18Tj!%}W_5Bk zKvs)47FToTVq#tBdJ|V)w?p||LB&`00E=V$>8l@1XQ~ePdOkXMh^gA|6Z8Z7tXT20 z@x609qR-&woH9DkI*J@2JqZ}Zu0WCNLy7yaxbu+a=tN$tBiy-$I@EA}jHtfuc!P;6 zICee4l#R`e$uk%TYe}unsMUg~*#p?`D61$O0iA6CPL*Rw$cS;GXxppK5HY?Pn;s_EY;%N%A2{;o}gJ#xOPs3K7X-_owKE@^7j0jmJ+QhH;k2)6h~Ix z&=)@_#D9-@P+}^ctEl(z#p4^UE^;p7+T_M!fs-8;XfunrRw3tDSgs3S#N~UyVHSx` zufNG%z_Fi}W@l+Vd_I_p_a*8(_T@at$p4PW4*HpNlZ`(dNr>2Svp&Kjl+>Uyp&if8 z>6KL%pP_wWX_y4{`js^LsXB1M*1A@isrdAoQ?~>3Eux}j-5F)UdYdR`#{=k=+|%5 zZSdAJhQ#f9l`=!OR3})qo-#%2R7%72?Ufhfx|pgz;glS>Rc#g7>jZe*MnbJb7k>K1 z72GO^sko(=f#MTy6TKu`Q3p<40z4an+3XhBam9M70;zEt;9HjjZPy z9gCLcYad+UG+kY^w(^_&;_*wQt*IqXDUCBp7yMP}T;PO<>{orDH3Gcj+_t1&EHtF_ zE@LVtf(Q89HIpD;!~keH@Hjg$pRk4y*~1;W!3GK4Tw%9XBZwm*v{696ehp#@=6CFS z8g?03ba^4rzq|#v?-S-N>t6k0aKX3I70!8!w=aJb=cz=8VAjUx7e6$+0D~>Rn2af4*hs@@N5zMLRnVxID_bI+t3U`nk-1s4bLaGW zr>HDy)yCDe*Vm|^Wf$DwtP8c&uGg%8EolDFE%UN8fPq-jvC=K5J)>g#)61J&gvc}|lo98x%{md5vC5}nFr?YG%_;h>WFndR*fdfc z(6Qy{ESo!|B8qYhDNai|M3C6>h-EBpo3dWLv!^Eb%}7E$YoJqTmZ5>U-cTg0uMd)PDl$HJ!aobZepeb~P`J?zsraBF4jyL(!swFUg} z%l?BTva`(^94vWc4|{@q{wM`~-NO#mBZ;N#UiU>V0v0EnBBc^jp%s2>qL12JGo(4Hm)2a|31vpr z6}Dw+BwMp5^RoO$y7)3tOS1RyP1o>8?loCeJ`AV7#a=VkNf4?~%53hL%tXh%O{eJ^ z=$=3Nw@5H_SM51di6+ZClX12722fO2k-W{6<7GU#z74hWh*z->)4%+>&cU>t|TvD(~W2*&&y`` zUlYFYc%a6rQ-*x&7enUf5^^9*ram)ue`jW5pkoME%;~WsU$4(}o#Koq9?>sa+3OH_ zl;SG`a+tJ;?loIbYe3Ha-*7bs%bY>n`-FV}i=6tLPRzPVf0|vOQ_6c*w(#(=kyuo8 zZE)t6y1DHk7osoz@A+f#$7aQ?x!f6dnapQg%D~eTj{p60D?qX$!T}eo7uS6f-)U0@ zUWD&GaT+H5v`rQ6!WP~`-ptPwC!alqJs6$e^tJ!B^Hg7FbLZjal~=y$bWhvUUeFZX zgd>egMc;-Xqk1;flj(Q$D*JG)jwp@L`mhl0VNYathS z?ddkx)2va=3c}T?vv3kttgrErr(O6O{ph3bsESy5F0KpaF zD=%-QF(2a0tEkLw1!SAwVEnb<3qsz6mW@@Zi&SX%hze6UxHr*oID=mVR+fNMini$c zC6X4uH~iM0$x?+M3kh$VCOtMYq|I^i%m;6}KX}tw@+OGDP9fN}zp}BJksNq$U7O>> zGo5d`|Mn(~A*j}|oogC{4D;JUyZLP&+2Fqr1Of zC4{`7{A67xIq9V_7%AGL4mZD40c(BdcWLjroqoKEO*6HU;NJAs3cINgZ!S2_RZeh(4II;SOHzo`~fI0QELqeDZz{}{d|J}n{B z;#$lsuzQo|-&@{sFf&QE#u1nEKV=vm6 z{BgqrGdz8jDR|MsR})j0_Q6ELh%=lS<@Vs@geQycZXnijLMPA*2sNC8(6L-3^2Z!2 zx+11HYiLHQ21;Z3J^H(Nnkbg{j7RcFOs@AjOPWjV?3h|MPkQ*%~UKyEL& zCM>!=f_VT`CIK&iGR~0sksm4GYwz*CfN!qFmPJKNbTD2AS&uW(-6?Z{Eo6oCHwTdm`pxcWcEMtk%^oNAqFz z0E*1w&q%!ka%$yGr0%r^HY-t`)#tr61;eo|ey4HgW`cS-j&OTTmO0p2(^@_M*bmb| z%EGl87!O@zJAM^0>iq;X^9cM-hMS=*%cvW!Cj-G_8a6a zU*d5mw7C^6lI%5LQ!!kjZSwFf#|~tkm-o5D*v8$6#PAJPcE7y4|7Y)Krzlu4>V6xs zZq1qjEHA_CP~oC66|b&)1b1Km$vYxEExBN20+7SV8&w)gxX>Y9-?3frTGEF@Rm1Jp z77;1E%nP$DHvHqA>>VtmCDSHLG&DJzlUnaVyRdtAZ<+iX{4G>5#rSmY-ctQVpK3zr ze~-Z5?X)CCfa`&A&O{#}crh0mJ`5|ywYJc|4HGm*V|!I(hNk`tT#4={@$)a}T{zm3 z^dW^&ffdEx=+Fwd>_vy2uZ=KAPg-%=qLE(x({7JT+xn;7&ewN0Jont{ML6&?z;0U= zw*7TOLCVGU~X_sz!{kST6Qf#d%I$UE@)b`a1nP78ts4aT(a%>=0 zP{nEkSxI|TLsMaTYOhn#9N4pQ%(O$PqQfHW0V><7$*NUhK$k4rn4`lz>VOKh^pof0 z+b{POzrND!pj^>YI>f!JCc&E#g(D^V6yb%-^l1^a#AkP_FLTT5=#o<$kB6C0)irX9O>V0Y8DTHC3m#ci7o7q1kYOjMt`|8dHwTkUDCc_I`b!Zd4{u!-NipCA~x4-*zztd!LhbsBcf8d%^h(X zhf3IZ{!<`E%aEO{+l~^akLx-L?857CXCNdQg%qLeTg1D3Z~A> z3tpVKA?S^oc>Zk~Ixs|So67IxK37yQ+fj>VfDAGjadnKzY+NZfWuZ34l|iU-cCJ@b zV7OTy^QERsuTsQxktY5SJc#ZNEqjS9t4q%x(|Ywxz3~v&tMqe!SKs<^z4N>J{+Z7i zvxwFqd7JR;Rmy0cV2olWe-(1(t9tiW^{rpkJ1grE&&Ci&m_DG*?K<}LoYgB#XIHGX zsUp`U#7=%?o~bK&AS|L<0eobPa(HhVfHNg_{ zh_Op=w91B)-v5oUYwpdigbPOkeuAE{x82EW1^o-TdYPunP+LFN65Vc4w%v)=>R;kT zo92FL+H5}y)beiFtW29b(KlB1zt34#47VxeB;jhW&)8G<_SIFsCX>5M>RYqwov+n5 zOnJ_CeGt|GOm3vMY!(}p@?3YymwC5LUDh?ICaOeAT5Gzc&*_9^J!d7*?uAaE#PCd} zu7kI(eVOO$dJQYN(EK1`4a3m<3H*?NkGh8o{cbqvG-p!+LzD3&2U{v3dp=$05Va{~+wUousU$NDs`Ao;S{AAL zmvZ)k8rBm2UHjD+cHt6+ZnS!#RR9ef$+0aKiGjp5GRF32dU4-((l)N>tCTOlC0KVK z;7n)p6I0HbZsG4O(;56d12Pc1Qm1KiX}OQzlI9Uqo)8F3UDMYFCJ%^-V!bjjZE`*C z0#E5;WbIv(@6!_WsfX&Zf?ztEe&j#|**pE*(;qoe412W(UCq8X<0><$^i0MLJDnb6 zvj&^3A$C=|&S(uZTSJR(+pLq!S(F`_mnY0I^R0`f74v3!^*l7G*mmgPmb!@6Pj_8C zyX(T2?t8nOKke$j{j9Hn-{L}#^Zk*T`ktGdzuX|AsxErT7wJ3Mf9I-(M$+kN;(B5N z3kF&+{iH5^DdQ|7(|j4TS93P4e^<;AO;@TaFzw8)R3dixK8+i!i0sYn^7~qT=8IkK zFLt$lvCFx67dwTBu*r9r^?;Cj2xbarahU&WCpc^LN{Yzoj+~Rfx`d@Dp6q1vBu^>PczWxblV9T7L z^I@2Nk4A7?v2<+>~OQ~8&f@VwTneS-AX z^OMLn%+P0pV6e3e$UTnYaID_?*yz0X(G^AKUXvxiPIu3yW8&QQKJlnNbs)8K-wXAjz%c@TXGG;P zwQfyJA)0g2Ke=`F8pK=@wH=suCTW*DX_xa_9s3%=GGH`y2gyRFtk|>?SY7Ep*{auz z(j!lbKU|qU$;caaGhRXxGE5eIl^j0VD5$Q-B)0gpF#J8DM7%*kd$lzGY!rs}>@(x^ znP6EmulU*=#bs8L(5wnS8J{948o00^D0_x!Fpotif4UVz0mm@tSOTc!cp(BonH)Y)Zu;DobVNe=JQ+ z+LSbnGQC{#J%{VaI%F>QQucf`Drok^b%@DVFBzYWp1B<&^7T*hW%HOir1&bm3efB+ z5>#=JLO`K%()M+Mh1N+VoFm~)H!L!V$Gvp4<+Eo456h`5?%Q>}?xmUUDB$TFgl2jF zcOC&w3EU);#Ch0EVwyvF3Eis9@$xUHkSh6GR zIZ{PSotJbB+|im(^3}N8_6drH?5$g-oLTR`W^=>xn)o#vcjEM^bu|GnBF)^26?ZD> zF1O{_K!CkaB*A%92*{cK_4<7Q>o)AedkJydJ67{4@*wBBgr10Br~BLbeG%&jhyiYE z5)i?{>>R#Tx)ldkR`ieP~Yyf9RFAsN}EF;S|0y# zq2v+E-Qg0*71GzwtkDmow3>t&SIKA~&ol+wTk~!dXJ%%&jaGTO8+T6?FYMeOO-oYX zwo6AOf;-bIQ=-0}M0XcZ5zCm+%w-C!@>upoV03RG3#HFXFjNB*R!(qSBC|C6V@zmA zn^)C^k?gNi5`AiF`SRlnJ^OR7K2>)is`aTlXJK8#c8n-3bh>-6_1cXKS5KbFAR~A~ zD)qdm;#8!=vSWMF4*kMFoLdNv`YPD&&TVz%?#OdP&~&C1XE`X_Ao|%yoFh@ zLGOx7)uoSz=0L?5%v%Of>PsWwpHp(8N#i8Cr^p6oXt7XRFR4BIy;mdaE(Etm)H!F> zA#wkfXBknOJKbo7voh|txAK#iOJwM=Y>d7tuk#!btxoQZ60}aNb0*dGZ+^BU7K1ey z^LQG=u=DDQaHaEy;?lI@lBiOH-Ce4+x0Wi|gu212*Uq%x$gqAmx|*LIOnS(75}U)D ztocm^771efTqiHVHs2N#6pAHe@*=7Dh{K_}huiybL~Xj*VPCmCf$py3^af>zFdc*L zqJ^-xj)?4TAL;n1Q2$)?m-@2RiOF?=Ml8s!HJ-R+Rw|ayq@jxtp_t-EMY~_;7?I>H zj>_HG4b>gqXr`lUj%Zf(wtX5%NUK)6#I43I4kn7IVT1BI^X_7-Z zQsxO%)(|r<3;M+*_o8nLyTZ^-P7$hII-Vt*eAzGSGf8KTphN7wTZ^HgTcPeHDVx7$ zus6l!UcYlJR7$zM_>4Mtwd%W&tBgt#Z z2c4F45jxLYqbDxclir(mQ`46b91{gBOWuSnx{F_H5fC93y6CKaS)66z*IB0`GneiN zUDhk9;;60fxZHa7DN>7`jV58rG*hrKM`)Bta-yfSbcb<%4>%aL4Sx^rRlICa7meWduv`z^Vn!t8&)4=TmAy)ZduMIyv$f8hwY7Zb zTmEc~$5~P9s139`YdxjCwycNrWjnXL6J$I$j3v9Y$l6p3vCowVVDjF}ZK?X!Xnok| zDAu-k3Jnp-f z6A91b+E6eOdQoWdz^7+KWQ`v~^G~&{+FECRZ5}~Wz2sRow>H;PjDg>iwU^82&FFg} zL<%pIw1Jw`r3#~i^h=|43XfAJMh*-tf@c5?RS3lwne>=Rj!dB$O@hRR%g!YmHVxg-=CW_-va;L0afjq9pX>qlIjy;FOA7 zm*t7CconG4t@r6bPkFHg=oDORm?_11J22>3o}f`%taw*pC@v1{DMnH%bj^#BXCsKH&Gh^Hq%wiiJWB6B1vRF(Opm@EN4DE3o!nZZU z2PdNo1;Le%@_YG`u}ez4B##nwEEk89Urw!v3O2h0uBd>{Wdi0gTyKqiw6MI`<&H*0 zYO}%|6;hj4qek)NeKq)-KB>t7G^`l~ga)Z_)jSxh?5u&uK`AMw`wK4p2vgQvj(L;T z>;k@|Y@FeuJcl%ayoWu}#eJSr*xX}N$(G0}JeqCkjnXYU!kYY5Q8;v^#|3K(a&XC9oeMj+E;6?5AD=hDfhcIts83k zRPtU`pz|1^bN|E7dOZ3z_ZswPh1W7PoZum5jxdCjH`Q#9547JbF58J(&-Q4asEM;H zntGf1nhHowkvrQ62fBMnU*nn(COERk<&I-l5X5wbWW+MTI%}}YZ6f&o7a{Dnp?0vf z;_%^2>b)rS>Jiv9JZ@8)JC*QfnAZ}1TPH}iJR?I7$GA@d1HGTs`FMNw4olQ6-68L+ zI*q%mrZu_d#=@FDWpJ-D$hoB^JLp-DJGIRnhdd3JV9UMEuion13b&*N+Y^L*1^ai5 zRDJi;pb&ZN!N_}l5B*J8!Z&;9^I^JjU5)#d8u++7U#Y<|xg0pFCp=3?p#fO7pawN| z&Tb{a@tlM>#PRcuR8nQ{PSj2E0ouS#^*X4J+~^oUWHw<)b&$8JObCA`BFE|&kB4+J z%wPSzKZG042_Y#mS1I5J<=C%ivW`+7@jMqb%ot_nC!AQvdX1jkzl5O|pUqksvUTN0 z?hdSK#hi_~rCJ$mUdf=S>;UxB&+3GjAJoafs>Z!sa?PVfePAh=%%EqcMb}=%Sd}Byie`oKb~Wr+O>B!_MnP$LiZg={ zvf*JEYv02e7EvK~^_H0%(#6K<;h~ienO6q4h}ydJio~PnfTUv4Bg=QvNweX{UGgcR ze04URw3t#vH%tS9xOf`fQYAl-J=xTi_E|Nmc;;gDCn{e>lL&ri-l^{E(tOgZz)S&j zaNDZYFO8tupW$xGV~DqR`Cao*@0#4dFd`AIZ`XIq^|i%UO63)50dkbpw)pj;h|6-D zKkfw8cP4%yVv_k;>r#Q>fhoA3c#Xwrg0~#*%uY;PN^m&UNr)i$p0bf zFWl;zlGnJ^ZQZYOtBoZa!K(rRnxD+&14n#@@BmwMc!$iR34oQI%_Tfd1{o1TYwY%R z91V^W!c?m!sa9cse`p17s8??V%UO>5+1!EU8>^Xld~ea$8Y-g08#mOH)> z3zV+vis;A~cP*=Q;%#conc8yYp6c?HYIqikVy@OYOK*^d9s#%?aNMTLV8JI`_y_`c z>%WhPOLLl(Owd;JE(FGq&eeYo)oT&;dxv=+YKSl|Z!<#Od~!6K9>G*$BW~U%!b#5r zvpQ0*=SA3z;&P`01Us8F02KH-iOZv4A17ayp^2Eb;_&QD@^z_9`)KuS!C>FD-U}Z0 ztJSTVYUitjxayBqK+nOM|M6L#x$7s*zB${Ipw?x{b(oE8N@z=s@6%;XVuXcRfx4_v zUDjlCR@h^tGGy;;xGqW>r!~yN6g`Q8$AtCS>NR&29$aoo#`QdwDT!DHHx9Y=v#QGy zZAkT1Gf;>rK<dlI{aJ9arPZfFoZ$UTus@!qa zt$kI_I6@k-`MEbM^1=-gKb6E^ta8Uzw_dDr#`5tnmiJ~&^?2fdGT0DV)N@C0IYQ{h zuOS@21?9gf^mKraxIX!o*~m;T^0_A=hLH1c5M}UC2lmrG|ws~nD=@Uu-_m#94q(u zgyxc?9>8Wm*d#`VF{|fCQ?#o3;E3h;h{ui5HVk!E7jhD;->+^avu2`)kvg)^(<$Wy z<|g>=pf7AxIXc5to#@LDzSDQ$BncPvfGdb*>5s4CuU5C~<_K|3I9+^?t8JZvLDBoAL-5!{^1JXcIuEV>c^aIR8KeeAJ z?MLytH*nB`KHaD! zeU6&IpNcUWxPPcbk!T?GgpsPcd%(tqnPE?xdwq-8H+3!@u?s9icfo4y>&x@2sso5m zBKS?5{lCMAS#if@lDPOIvP&C6*M1MglU#&3LI;GV58z~}-+XkPbY^C}yueuHIh2ca zAMgb;HRS`t$Cdhc#cZbz>=J*f>-dqTPn-JTqrvlMqt}vuU8jtk-B9!;Io0lCjtreD z8tW%Gl8GeAJ`1^NY5reci2}CSEI7u}d=cK7JQ1^#IY}EwVZ4W5T?+%lN_`d0NGS{Ili2(G08$Vwb?n_fm^$ly- zsqmvj-??_R@rBu<>>OT`f`08%$uKmqL4@f;asD$?8`i)0g%Y&h{*ROJ>`wTh~ouT-)DB$scv>0dz1;`~_TOMj1OOGrOh=^mAqgsdcD&5hf4MqNsrp#o)44)F|rn8;jhZLGMeXK zmG1t^*8WOoS|$7SzvaoE@nD{_qj`EO-4`ocFIGAeE7{NgJHfH~_2WusLM7Wnvea}<{x;xDai#mC%GRDrECsA?uG%L~KWjfSc>|qle`(9x&yWdP zf4bK)M`Y`od*KLHMSdg-9$6Q$`6j$YBR}NZzf3t>x;Nzr`(CA~i-_1Rv?O>Z^#jcC z2$R0-WoSk70#bX5N^ZYG=G_i{`L^LDZ&kk6em1%NBSuO@HQY~;*=8Vq#UyK_SAz8# z*d`IG<2|nWXK+6Z>D=pk4`rELke9q=00wZO(cuVBym$_mG(rqpMu;~3kXbGu+H~av zU)fdp-0GpEVXjfmCKD1Y0V7^At0Iyg|Dx^CdRQiiJrcvc8K9OOKMFt%gCmykVU#h0 zft>(;E9{MOWHh@|vjo4lgi37=hc&&@b7)Ptotb*-WJa3V9Y*YBc?N>TYOiI{piTIQ zr4e^o6k|J)TmV%80v1#Xf6uz6vW3nhmWHsjft{)83X?ob_z3J0+Qdr3-JNhrFuKFA zCI=1u@f~m%w^_rD)(D+75?cTW^c-&q7UNH&b0wge=8uFn-@#=h6pR}fk^0MrF`L4a zl~e^H=hO!n6`83>>l+%;`CWNLcsE$R>B0<`<@k@}m^T9VzlTGI1|VfIw&A=V!b6V} z9;%m}Sy<^_SlPO;(s^Jf`y?S?ihS#W%d*98O!fJ^4NqZQmpC>b&C%qH$%v=ywo;|N zqEzc~OMNB*6w*I)WO&FFm2$)skCn^l(dmoJhg;L$6pYJACGmrdIP>;S2$N4P;zmr8 z-_7m>FEq3be|B+*wCd_pyc;c0k^{_r@XYK^E=B@#~Bx(|QYC8Ws+hf_qkdMGB4?7EQTfufHta+~cp_4miJ5~RT3$27C42-%tnII%dQ& zXV{16Wi0jKO#M$i!Gv)AZw)_Mw%mTe985IdFrhS0kxWE27b{rEeO;6vc5SJeT5!`11Q)T-*Svg=3!Yam8h1Pb53YAz-#Y zlQQo*`G=1L>GmB8?JW{sD`m*hz%fE!4hWf;n~BaoW}(02#1Y@ z3dO+G>vP{3o-f_Jkc1<&*O`N+#%1^J`5+dj)KFAda zXIvV)j`)K^ctTz0xN|56WoSn@D3`NrkEIQB#7q1t$r9Hb=!4?Q=I`|xgB;t*gew+p z!njJTK{y>I@b3JX_$A;MN9y_kkGImpEy0n!RAbZ?8Me2xLnMDdv%|6WPV77-Ph2~F zH&@5rAarh&ve(HIXYe<70%crvt|6PPY>rh2+8-hjbfmPnlvJveZW(P2jYvbz0|gS- zP%i3$x|RQnV~4qIy+!vm{*6*in=hWKh@o)rbVUq9_I%K%aUce>qTeGY_%lIwN#1fV zv@?Q&O})W_!S==p1-PU;rvGtzn&84m%c{n zYm8$3^*VvR2v0kHB7{R0X@BBWQPh52AbW>U0r!W0&#?pK)z@IkYg~+MjKh>)b1~uL zA765+e4729q*Y$!nrQZ0^6GJ{R{o1K>_fmn9u5BQV=@ya-w%h@h#EH{4epM%7vch@3aJ>^Jyn>9G#Uej z`4{@^v>|uh*b3&b2rgN;)nQ`_6F*5bffJk`;G%m#NRs6Q#w+}zGnX(3( z&#C?K0j-a4&bv4vh(Ji7_s2iv9^hJUbI#iwTSvkgzTpmkFFf2KQX#of>b%aeJ4rYb zu6={k2vw>a@QHE~XQyqN2?!@o`RFqg&$a`@%p$wcruiKoXumcZH)-@4j3+FhLS58y zcvos@4ejH*z!Sssi@+x#c!r^01im2E&wQOC{aX8HzTg$4;Ja{xf~z5op0Y%yi^4g@ z&*HU3lt3rM1KvCuJpw!Cq&ZVw^mXUS`C|4*z5?bXKPo_l6S~3sKHli@C?DoDv`VGE zq?3p#DlLq3EW7w_?q}UFJ;Nu6rZhqvAA%y3pK~gj>d|2kSvB5>8sS*CqLjT@illN@ z$eg=Z#Y)nz<2ZQ=SsJm=yW{`$iC(MU%j4aaeJ z@f*R<8z{dGx!lQxA^d5iq0s-r@XN&eCy+;*L9e~Sh4T|ZubD)aSSjUqUPf3n+#xX0 zX;(R8^rS}d6%k046aKATz*NHHGifEY~y zI&qNWpcl#fR%K)#3e^5QmMD}YdW$psTtV7MsJ90iJQaEqk#kTC_l>rRFK#q+tgmT5 z_kvXj@I4%Rl>l#%;OIDAln^k{Eu6bJUDRWE$E-v9Pd;sw)LF%`pOLf)w6hZNafshG zr0phXBDNf-Dv(&#Md~y;|6u~>4WygpOZWb0x>AlkLDKbKCnXt5kb-eVQ%J-_C7lJ2 z0X_pxCdH#)(7u9vZv>R#NiUAyCL_c1GIk3o3v_&)JRSQ3Cx1sL=_qX>#}@KKg0Q$Y zkWKK8O8;Mv#5F=TpChsH|3~a9J~sAOvDa~zHj!85f8f|Z5bz29#qoib1sq%E#h`N` zz@~`=8n(B%ax;nkWjGk4JG+2{&z2Sq`a-n7Bj2Utcxhi6ZSxe4eU&HX??}b45%7gF zy8CyOHj%SFMY7n1nf5@d(3_b{nmcbC03T(Y$&uKRk$;b6<2Y*^$*$8-nZP`rvp(z1 znnq=P7LYY9^ooSadJBi^kpwl;%seuZ%bQZY{fmfGfH=tL_PMbp+0%Ez6!ES8g0Bx?f)8wbPCMHcbFYai57Lqpa5V z9!>@ybUA37iuxtlSe8-Pbq&+x>o<(+ed|}`zmSzLo}B$e zL}KwOIqb{xuBX%MAJ2b*@ymOBj6-uLElNVK+5W2{TK1IJDxxJXt~Cb}_t8=M`C(Nj@V ze2E_TN_^mJ^DkeGbm;LAqV7#4LP0p2mi!(%73SxK;EAHXCQ<0AU}h_`f|O2JMULRt zWXiUY7wINko-l@#M%XCQ*hrS%4I(lZp;!xHu|nCy@2`to%*3u27EXT>dud;ju}^bN z(jQ{Sa-tz{Tm*=hfCGqiQ9&DsblN}{xd4R}IGIi40fkenk-YTD=sv56{V!5)hf9P_ zX?}*;+=!@YoIuwMt&elgCpcj9m~2|O5x9wY+;9Wdcw3urt<_v4|M@)3{oaNKCO|{G|9M}N zHQHV1SJ zj~NFfr2Hi^Rz#kTeY^@donmhcm){u1nB54gKwx?M{q1!`Q>q;wvH7U-?}kZi+y4>! zB_G>NVq32cJFgOW4?w61fLoa5Lo)WaOI>eqj=%B>#CRd>KYUq=?)mtL?e%@LpAQ3B zcugmlkxPWxe-0Z?l9(E)zBbVC#(jMXK{jO^4j*Os+c1gULSmgA!{vV?IUY!3l5I~6 zw45O5G)gPp;kGjLNIO~plfuW1rRC$wKm4Du=&|tfy8q$RRs2ea`vr)N*WrHE<+ctJFQ+B9%@j)$Iu}@zU;hb>3LmB=!T)x3qr6OXgOYt8sxe~)XLQ2O&*ur6rj--+L z*qrngTuT(NV|%Rw+vc7g+P=w9J!cBDb^G?{?Yla07+)hZcx^-t zQ&%19Usr+q=2J-6qjsitON@V+jq&%{JmTUV_v3Ns+S7xx5~jp$GQ`D2m#K7J0-Q@n z1?#BMTIiF&crKDFfbxGI-a~Au(97j<+T+zy9{4* zjwZv3W_@#@!F=B&YEtb_481%mq&z~pO(=AJ!Lb%XccYMAzDk^ZN-CkL$*aWV2;xqu zQ7C*`7&kL;8@5vFjAWILREgKcWcTf~OA~_<>lZOoR4R)7fK#brD@>#wJneBHAX205 z9du72*=EF?>fc7h3$evxqm{=Y4Qy2~7gYvIXCNjc^;X12fG%XN550^zh~_!vWET$9oCF*2|c}ik+7^ z45P_GJv=fk0(Lqn2;0L1*%!ILDzVbDuS{D(QxSHZklMZ@u!3*+2vtC$WvMp_Cwif- z?B9nv1QAYRzEKivgb_9UMy)?D(QbklD$gOzgCj{s-$6xy#Icn`nLh<_oNNE0S$i+ zXjtQ?KH{g|@0UFyY3TCnU-D3YDAVAbpnl{b_0JRglc?;xK(#cmfu_o9hS*PrU<$Qq z;8qmiicwa?s9d>G6}i#k_03~#598B)@MN6xYcj;(%2nBe;9Nq? znx3q1+-(!mwvPt4*90=s?PZ%F0eaR~d~{`d!V z;(UN~Cbyd`ljVeo7*mp%%F&3D$eKn@f*8G&yqJX0-h#%kLYK>l5<=My>JV*pkN((m60 zU_u{I6y77U9k5c%47QWl6^JV!^_>I5>9&K##l-{5+aD{x!{IVAf0sk@N?G{U+P)75 z`yQs2zd7L(`(b<7WpRu6Qdo%y(u1!j1*`sLu}vc&eFEwjCMW=yQ0 zWua3<+sk^3OWhzXb?mtRX&HO8jClm+;)AaquJdf)Y6H$BuJil8E88}Cdc0TmZ0hVB zI6s#TZStN^nAnXbV4KRe%n{poWX9UT9>k~=nwMgNLFbuSQhn~RaQ*shss8;{KH1TJ zuY8D?9ka%Al;7nla*g9(xAFDV_}5K*Eg(#Wy0f!}K#a-xehtTbV~_e-ehA^?;zr}L zzxTy8WcuQs%fssGKYV3RA5FvFCyffZ!>>9`y}tR6z;86o!~aK`gZWbZ+-@J7NhFQW zD`Rp#_Wk(m12~7CMkDZ$efS2DbmOiPlk>3+zTqy)#Y4|ymn+rJ7%i9bl`Hk(1{U`L z<+c2S;I9GvmTty+5!Ry0-T-eo$_&c;Ty?lsb<+KVPIa&t%ZUftBCzHM?-Lt%%r2`4 z!d1vS4@`OJBNg9Mv4{qQd=rO#fOo>k=|IY~!DrVH_V|8*X3oo4`x&uISYu*bK| z_AlS$tqz-9vKaS`-bIi>dvxn8Slpkax|6_LwqTKNA3Y0xP75d#4;6W zst6Wssf~8gIKFEFvz0wLNHXe5AgFpSve?PEbrcj5>wrM8QTuluUoG=!O8_qDqbL`R zAw;gD1wBWY#oA-O+Cb)_&N(}RN%&cuwH~f*9ghK*9rSUTeg`iT*uUKad>rT-@rJ)b zk6X|O^jmkt;b;hZV9$E2sczjAsoHh{1}jKFKBl~p_SFv{{lT@N&j2a`6A)|L zJK}QO$9=_-K?i2amEUkia_2fxtqBuFs-|9#J|3=be=l5LgdgF7u0brF6Mf*haUK{1 z4=f)4x`VH$r(R#m-k)Cs9hlmJbsg&d{7g@{-XHuS!7l*63HU+RGu*+=juwwu*)o_w zyP}pVbPCWP*E{aB6sBpgHuVfXv1q#OA|uu;H7_8t(9-++sn>B^E&oAykJ5>jP|rkt zz05BnUYEE8NnX|Y@W~1ivsHuUAW@4rD~;qGLo-*JHEmg`0d}OxeEPgYF$*-H`Hm#dTEECaQYu%c!7R=IpDOQLxwz9x=wmRKrxG~0fW7c>)59& zad&gMITBoPUCD%I8Od@b-1{$?XNxUBo>U#ctOtIOPZRmUu1R{P*GNxmwg&RGwFq!|GD zzsd;U%aECUn14Z0<{!(z9WD zYLT$>2GgZxwFM*<6KdxBrH3D^tdP-{{Ba_az%Fg^vuXYao+BphUO5Fq`nC8Wts`}< zq#sR)@_HU;#2AK{g$3{2?R7qdO$Orie(p8g`WHZcTadU=POWQ4`GyWjLCak}GS?TG zWhCCO5*Og49YEg2>EiV44q1!DoynmL4;}Dm53{Jd5%J&%QZF;8!B;BF@$>R`{E27l zA&v~jXi?H$S<}+dSfN9b-0=4$HdG@Wrw9sI;UIkYd71E^bpcysuC3os21|-bDtH}u z9D^T~1a+9t6;79+5-vGa7$iP$Oy28k?+_Oh-9=o2uL_ou+jILRYbfiwyB)G#=Lw!^ zwBRYAA;EnX+WxxYgB}>XbL2*@G#H#sF6HX*k6ydC4U3QjlNV_MLHa4f;(4n9fnG3KGsy={^`%XcSgC z@si1pFIGjFKk%Z%LFG|s*5)r$Ef7>Jq_)=>Di;1)FZT$A#XWMBknZ#-7K5t?m{=n7 zv*D*rd<$p*Y4+%1=%!7 zC1MhD67v<2FDigUg-h%vGR#WX`<31rE46U?@6m;mNx6pPZ>B*SYng-o4wHfb}o9pY#II`dizoK?3n8PAznTSO?pW5W-XyP5B7Z{{|rm zuk$|Uh50nJonmA0@^nrZt=`7R4ZD5g^5r|D^YoR-afPCY#~ZA&R6WLEe~iI${E9Df zT&58nC-5PPdi#Wk(%+sx1HV=HAt}7cB=C~E$1&ua8YDIh#;7t76@rZ?3WH82RDQ>? zapXNVo9zRI`mXlU&@PLmZQyyO}Wjlbh@v}x$pkI_b?4be<9u(KNXXL;U0fu{w}wkr4B ziIfpD`tPscCbc=~0>cN~qJ?Q6aLGsIcuk@~306pOGKHrI81Z8Fv#pV_Ch(s*k@)m6 zA*3`cGpkg;H}cg*Aw8#XRoS*ecxxGrB+(c`MkS?e<=CGG0Zy;-5DGMK?Dynz(LyRw zZj%Yq9NZlZ%2|;JJ)P8XDKokXr`*dK_L9}}45DLY{IVXghYu9-G3*5b40Kff566B= z-eVI1xB`SNlp)! zWv{=FgC)7v`f{sibbl)#P zT@L`YJP6bZpv1r(vzeLcBepV~P{pjG^b1KHj9C<0K3ZJQQlpC^#u)aE(U6=FA(RJ- zEgk!gmKqk7CJ9J4F!HwO6x!$v^tFUCnLtjV#~M{5%rIxrW@9Wu+4Tg14&?tW$G%M7 zc~%FV46y{`C1Q3B3H7o1i+qAHR#!gA>T;gd9~)mBorGp8pa3YMEPkud=9I+zjAR2q@3Bb>aCwi*M@oQU!)+ra1;TU zdPWiG@ix-ziEW_8Y|KxhA=3(9T{u5r?!x)pM2If@iH7U~eJ=%Bqi=hhYjY*7o!(pv z-2b3QT?+O%U$#Dc8-eeUK&<9VD9cQNH5^G_LFhYhpAkEMAi>r)uU&E}%;Q|g2Hmzx zTMv2d>CQuB9gv*skSmFcdpkw4HK|3E5z0CULeQULo*3gNV4pBe`M;bZKCn2R&}#Oy z2c!P0L=mNMp2IPYJc-9+m7fqQ{^HAt4->65m&DEFp`g-4s;~ChCakwdWxjUm^>Y}X z55LHVJ4d(~Ps7u4BSDLq!!9TIWBE-(+-L~^$A`W#BW*1I{HfRHftEYBFPxu(C+KHg zbeoA_PQfGq^LV<%tbP=_(etuPGWO$v=Y9aZ0S@%w{UWf3NTgc$>)DG&qEbBy5!y8A z(ngOXYqae;VVG_Gn$wt_-w+|L=l7Jj)B^Syf+sfq`~jwUGUga!Z=>9FQR5_x{m;un z=ZNj14nYeh?jcABBl_^7(*Zbfe-f?D8=lk5E+F|k#5w`oICKliCgL$#Cx~=sF{%b) zR3-IRItF?j+u@U$1<7IJVH%@DFlGQ|&#BXJ#>OreweRjpWhK(?A!*(35_Cy^&?Wo1 ziDb|6Mp`Sl4a;deHdESMGARnsjttm^jnFA(klN71QZZw+T;zk@r9XqzFY}a-_BRGb z+s+1i-_HB zxGTzuBGJbvyQs~%hFCeAODm!r$KP#kvT0@_Znun2>(a#68bH$;Lyv4*9+O~8+77Uu zt|A}3Y{I!YVZR6TgN-(4bJ?aE(FoJ$uz6hDzWWkooa$i1Bnt4}PalPM(_#CO@wn=TZjHj*_8`2!bGTZ~ zb&9MhBthKyK=(RqD0t`=Kwmsd0B-|e$KGNjg8#f9+BoVc2(1%;Q-7AhZXaFJwqFs8 zM87lI4wQE1z>G(IZDagZ+b9MMdpJe9LBG&}C8k`Fp=_W~GIw~vrRgnVo`n*+keWa` z)s6XSRMuxGB=z44IjwLhc$k;g**FXtp1G9 zwnCs=K{h9iwMdp^LDnLoLW~9Ein69X2U(^|UWQPg6WqM(S<&zi6zQfBk4(@4wfYEe zWXBJA@8RnJUbhln1S6)Ub5~xF=PzWWpbfmd&k0@r0b4Mwc$_ky6WCISQDUsX3UNin zLb8AJmw@UmQvxc^(JqI;l@j->7?)^nxpu&EN4YZO#s>Yvr(c_RY0TnTE&PzjZ@vm?c*Hr^x#RKVW;&R&q zq+%xwjIAg!VfDckU6;3gXcMJb2E_)+fJu}TO<5L*nc%{6v@V%!>eQVZ?FbdZYAttb z+w2O_@9MuT^c$+jL5Usc{jP>cm@0k5EKK|zvLuDVMW@Y?uZuGFNXbTDU!?IIZ4(XE zr(>gk^o?>MvCW=x}v4uQ=;84X0K z#W-PH@E5%Bz8%^Rp+&4kaV<1ZeEU|q(EO=5{R1SzqT!^9Ce4fmkD%hEJ@by=P8*4rPq-S-Q|8GMd$!0hjOIXT=F; zedNu6T;1i9t%m(L*-JlgV-LApX~s|K<_0wPP1oF^+e~CdNYr{s z;dxP;cy3>aqBrD`Cauer*xb;hbh(Up$X%`^JTN5r$}gNggPb0Y&ik6oES_sqifYnu zrn4&~s=Dr>3Q^jYTB*yyRfH(3k1w!@MX;l_g(#05os#y)Tj}EcYN_))$G&t66+?`9 zsS@=XgKUzZy-g?3KB$&N7j=`bRL&%^EinzrbdFK)Spx4!aO7mITk7iLM81(TDj9TCyHQ^s0_fWJy{1|vy zP+;*wMqbI5=g(puH9^p#Gic}ELc3_*LqRqXMh}f`vN9)3#b|8HNj1irhm8YY@7JJT zLb+lS2wo72q(S>8t9mCZJ(C}9n;hkH(|S$TQ-}PC3y>eu)-Hr?4(wplJVtU6HqdsXL!F2=8Z_`Kl84$Q*OC56aQDnW=E}ti@5nTGl=r5?>$%LGyjVZ+1+d;b;6r{c; z9LucZ8w?EZ@6BI{b{p%HqcmN5nqMOU8-gD#@nV+pDolpr%?@<_3$#soe|Qi|8>ysh z%KIh=NFn?6O>BUdI(0+7Q2=8%zf4I+1KwxSaQUW5WQ=~!Cl*l-+4ss~0i0-j&_CF3 zMv7GqEYe?~Rnj!*A1?=u;7quF2Es|6lQ*%9iBgG4 z|LuwkB3EAUSc{gE#kvp2zkbG7@A%h`_&PrR^&P$rkAGdm*JtBj{rLKUs8-Z4u`e00 z>|hw-N-(ecL?@rKxly{Ujy-Ub$V8%5&6(L4ysb{V_vV;#6`_Kn$TEafIvH++_DxO0EEv2J#+K6pIIe(hr2s(JC z2~HajX4;@q5YI^>*osymD&VCvZPbDS^M{I3xo9bZAm9{4KrYSqTYEPpotbl<@A<|F z-FxkIdDmL+TI;>9&vY+ehES;&&OOP)G~4G```3lKq2AD}B`$ZacUPkXn`(Rhat{lC z7*q4**9sF|H?ANxltzX2rv(+s;0|1Wyo{9Cd@gj|BQftyo8?$}#at1O*>?SnITAYJB8fCw4-Z)WCX;p9vQD)y`C#g#K#8h zvM#q0931fVt1wqFTwwR%WaA_Fk$I>gBhV*-;>BAxVi(*()GjIf*yXx!PGda7_A}i? zNLy8fK*P%xbfYm~*`h<`TeAAiN@3V-SHiPSmd?=pOkV3G=TkQ1--t zPutJJrdOSup2H&5VPhTDGKY<@DXtnaZl3N6iS>}XEc*O)>&BbQKztM6Ba`b*q8w#n zZ<*9l7EP3x43}@Ms*u>fWCH1Wp1{YVCKQree>ZC1wzchidg;xXr z(vyQQ%_$E4IU}BCvfw2wG)F3w+SBjmxfBGs@N{>G>JGVWe+T4fC6FVD8mv*`$}F1% z7V{>B!!$Mu{yI=kW^9lwqiwiiu*J;Dm7wAdQ9q|Nm=dBg7D^m8!gV-&4U6k|Ig%mO z=&;G%HbNU=%hQv>DE4eM!xl6C8n4E8$|!PG&6N@Cy%vCkZ!yL9B#ez zdW?EoMyKQe-d($hF>mW7Ym9nXI@G7qjrCqzoZZG6rjNqeM9Moa8fUzT1PCu5-!#%G zAhvg2^q}*ZlDzYxhl0-(Jz}P1mu`t$CEl-@Ko-IKR}}3M+`AFXz8m4#FZIU)xNWbu zJ%iAKG;n+v`JDv!g=gTq<==4t{u6v>6@UP^Ng%aR-cd*oI0iQ=H!8ir@ffcOSN`R0 zTGb))jzV>Sm1PF8j0p`SQ3L@9phzqTCX&0+a7;OU4bM0^9;4Bc0EAwGWr4}X$`BGb z&KR&U9U`YqE-VpD@aE5T1()D@v$zDF8Q7R}kVXv2bEG{F5S(xw99pbzr}u3$DC0)+ zGr%yzDC{q+H;lr5gHmo7h5bNa!zk=Gh!PB=u-~AJHAG=Qh*;QM8d4tsmKV~Tfd2yr zq(I?rIpkBt=wzIg};zIh0Jh4dLw zd=WleYIza2*OCp}_oc9}4-N|Z`Yr6_IryN&9*+IK`uretVYwBi4zY(Z{c;m*sas!S zl>mV?pRHrsipFZZnN#S-hjDK}e9v^)j=jDiS(fwlhU8}~Cdy526=-OX1hztr>7H&H z-WVt!~#h?3(*$6)j{+{%v}_uVkZCvVitoP`UC$p z2eokA9`apA>Cy*Lr(BN~N;po2485^Uatxg?s+Kju-h10>@Vin%DF9w9k_0&NE6BPxK- zoE1I7wFQ?xVuuaHBLu3R2Vi>m1RgA(iXOquTD0X`QBOQ&mWpzMnJ*}YM>dU2+^)a% zZoyqNdMBLX$oEj@3##GonL#N${>cREXz7(QOC^r4+-_oRrcol{l@@ILJvw zT!;`tI}J3GED*q_m#b(7momZ)j}*~LxKTyyDDvsYqzIRg@g?2J(mha8MrDNXaVxLU zA#0)(0Aau2x_QtnBAS4$F=XOM8xkR3q+nzvl7*#*{1PQs*Q2bbp6jDI`r_JvUKW%W zbKDmUg5#sh+#vID*es=tM!45UcM0|HNuYbqklL-N$(%-Nl28HPZL^d%e=^{yZ+otU zecvgiBEhb0f~4ake%*F{!!FiG{kGPpPUeNk}l3?b2+_8{u;)bC$I+P=tN zYingR>)7LLtT`>$@43o1f)-j$=2FV+Ybc#%u7u`qG?(P5w+z{MrhM^9TfPxY}3Zu9ksEA5Iv91iX3bF^HXF@cWr$5J`fwj}AZr zw^&N}$aY*1MmWe>SHV1brF4bKTT0p>a-|oEGRad9(b8z%(Je0-EnNbA%Nr}(c|lyH zo1~A2!L&^xknlaVE#?UOf><3yhC>q`+_FSOIj{@{GS#$Y@&64z@rwmW#Z3()sd)UV zsT|W8S!2aLFmkDxqU18c3XAy-tvIkZ4f&vq1{S}MC(9hZO^u4Q`SAZuo3LWQ<|ySj z4e1NPX`a!%u{Mx1Q7>yZaU2Q1K~7cVQMQxg1Rv1cJ4|fYiRHp&;!auvX$lt)4zIM) z3kITjtQazd*uZ0ltJ3gQkrgCznn_T4EG1!ho%Gqw8^}71;inc8OI{R?jNvnoqi?JY z>LKF6sS@OCi9jdxz*6wf_XbWX$_SFnm;vhWD(*Q7N7)F_(d%?L?=9+1UNQ<;U3(h$ zqYOIEUPi|)S4fVW$&ot#=Z^Dx1z@gCiF2R>uhmJ~O^%Ep&U8;bSQzsSn8jI%uo1CB zg>m5Iip?C~HGOZSo7~=>H-}(j9SfQzy3OKYt2wh&gx#y>um1@5JB|MZxPgyskl;p- zkRy6(g!%xdHM$o7Ipc|Ya}1d;S90>=a@9SY|A%aSA!JjA)OajA$e-y#nWx^6>Iun< z0jHQ^-o|8#Ia*R~nCR#eahCO*<%LN1B1?$Jb&eai+r&IQgpppWpa}DvMa!Nh;m2 z0pX!>K5UY9%OwLdSbbhRDir13}=! z%6CKY?_BIl_W#CVbB?DFaMQKwCXe!<8IW0%jcmqxS3 z6?F?nj-rYrt7O5*sZ~*d!)HMy03d?2z}8qootEN->}!}{!jcnOW$i^mxbj3M{Cz=V zZgq9vbsMw@nHCV4=o0Ap`fC?Q=y_SS^p~o~d3v5ieA4V~D~!{$HccV%L)Ay&Z9B6k zn<{>+AX(g_rwC20c^*`Chcxf>MZI`5aSg(pZ^jJ4Yr@meR6%wNW#@PdCTUrq$K8^W z(WP`>T&&R-A^dZN%${Bnm@bRLM=JyI2|n>6w7_(G)F*uaZ4ui|J*|1Z1Dm+eHtcXY z(9+N?{F(2g6+BCw)V2S5!*f1IM#&wgYpZ;<61$Y9$D?eU9Itt)b_(6&pww%UYLe;3 zJgTRPD$c0IIsO}joahicz7nsH1{u3E(~M%!p@|(d37g^IxeI7agb8=3M2>l>fHE@w z4i)W~_p4C}Vh1l!zmr4an8!us;K2Uyvh+v}kJ2jD%W(*UbHJ1a%+bT3TXk_*z8Jro z+#D;cS`0_2B@2`7l$2Ee?qYeOB4>6WAtCbz+^a~8zI{GPU^L`#?Ffv5942jnQIH2z z;=m}#VTl{yAs^X2{vL9xl+#oH1K`*!da#qP&q`yJ218QV!$2)>fZL^nhf z^{a*tc{>%Gm7mu-%&R+{GL>C7S_txjbOH7rkZL|{yI&50Vp|#AlSA1h#Tf{vkVe^Q zT76ntGwwgUuT4YG+$wR~`w(nU?D)1q5gXH72DhPQ<&R5kXTlIxHr@X)w|B^q_Fs_3 z*CMJmAwK@I+=9EB0$XK{94h1!IWlGed$@)Fg#%y)Q7*v@PtWohfDIUabih8Hd|+^> zRPGN0h zEo)BKzDGAgcX>l@I~}eqqZ=nuJqRS|3G5|h=WkL}k+R@!@IN>&ZYV=)?amp+_D^qESSqKccHDxT#@cc7G>x?{ zX2KwVDn>>Y>-jyC{nJCNx=~CO*VNw67QZxq=e_n%KW5A4@624=3uj8g%lWj+c%;iK zyih3a{wQ2HcgLS^`adMTXe3?tZWtFU^ZH9{qPq94<$@o`@O6kWNH+h4K00gUu+d{3 zmV8YDEIg{{Q)VQ`t1DT%FkAEAA%TPtgO}n?h&Xyfb;|{HFvfd=cE(&N&x{EiSeWw$ zSt78;+^FNLn51ac^(ps%u6YB&x1f33#>1m$IwYMk`>YH0SwGrm-L^kWXsyW3!ExKX z)ij#Np&+t7bAcSTP^N*AxwDZ(^0w-@n2T#e!pR*%nMrUGwn95+PWu?U4ty;cb{{Gv zTP_CS@e3^OFU5NYp{{xP#YrN+XsN%JyTa65i}A425d2H5jO*7I?4yJ*#15KA2CUTt z&5QGK)-(b&b=Y}(eogf(r>Kn26*&nr!JN;fm}QisTbmNpz?|B(WEGIOS7PKO#kLt2 zGAGbIGf1>qkRk|&e8_Y`KSo%2gqTY^E4_2<_rk1O1>K!8q>^;))nd1!wkf?TF|`p_ zRmVlfpjRcMPAHu!YUwtu^ROtWqPM@V#nt8wC$yK-wE7>C>fw>CoOI($hU0UK|Tz;9XQWDpvlVR6BvCZ`kY0Js$t|F322TeO>L`!=ewAdqZ%pj5s zhoI(xx~}28W0V$*I293ln^v83)>Y&rw&IjC=E_G$oHSjNSjb*1KJHAX{F5&`Gjq}Z zpwG=d`N6xmDaqv}F!1oSx&B0+TNa(~kk!Qq6#^U#ly2eq81*MI%WS-3|&@GYDW=-VEaN5NX-NlzJD?9 zB~Bt6%y41`64jfAiXVV4)+Y;ja#DhQPrdlI{gWpP>DjSJ>Hv+&Cz6=L9+Gj{os36s z%zgmyNU@W$@w{a_A8E9M#wi_`PJ(JOGHhpm{^9TF=GSgOHfy{wytf(G-JG@%F#&NN z=lZT75~;7wlvi*yce2kbm0QKIdMFs5dJr0YUqc?Q1Hi4$tNkmlH7qCgMZ3k@m&Y|U zY4I2ph)sQd1>)zFV9ayZYYje4TfRK6=XTp%8ZHAlvkf%xT>|RGFlythm!Gd0_d5eE zKmNtby$8fAWF0UHfdLM^Tjk80gt|CduDyRfj^~VciRJ?2nVy)J?J)h)$6*3Bg>Adf z1p*7%H#?=XE$PObRUEP4d)AI#%m9zDh<8{+s-hhGE({em6vll(tWGc$i?ArmXxPxDC!>2 z7Xn?QJM*(~g-M$Ux~97KhYC8vKWg^s{`x~(p~B_9-BuxCAoqY3FEJw2PXs#DWLG1m z&OAIltavloHs*3Lo~ryX1Sj%jN#(W>uLtYudcif|LjNof-rFoc0OPs`U>YRdvF{iE zXSYF!;H;Nb(8ToTG~U!}@DfOn@V;X`$rNk^=c%nsr;L5r!x%r|SLx4}P@kT5#>1Hs zEBz5?C1v1EHZTs{mpH>WeiY)qgxvJ(M`q)@IFn+y3@S8kykT5&?*1;0n}vLxP=YA* z3{r*nM$kEW8qW2@m`V1`-Jlo2zvM2xVp{vdQrNfL4^6;S^~$xx3}6C1UY?jPF62D3{#WCPeuVyT>)2P9{8OUAY;cWt73KA_qj$RnbCJ#}@> zT{vkiaU%7USs9C;WHcg5<7q;kKT=H}(3T{T=Hs?}x^aT2ah#}l9||`vMB$X;61eL? zLsmSO{G~+2V)Azv#jqln{nX;6@etLPFDw43AbEKYBQp5@oupmG$NvuxmOk8ICITI9 z@cq8v#W({ku6b2aC}?%lEHPBxiF3Vem4)KM-$Du$$(GE1VW-6fFRF$!W(H}@8#Vyu zDwTH#1s*2_Aa5`KB}j`HM115Ij$xJ&7>9<2PfD6Dfb9DmQpTH69iGon-mhsPvpME; z!3(hlTEh8KGuP9N-%=eiJ%WyQW4Oxn9&bp6)pW!zLUq zg<}n=r2sG|-%Cph#?N36AiXXOWv? zEF2c49&<4)pY>AzD?DomJQBf0zNeqElJl$i98fRgYRUJ}{+pK7U zoQ%6LqIbrc%t+3!fpa)8-@&s5o=*Q8`~^TDF&8?=YlG;Xd=TG4BTU}^S}u#gn(z%wpvmlEG@jP*aF_uud^a&g)N2_A66qt=?qh zd=P>4(q_rokFIoxOjFK*;61D`r`?Nb&B5CC2SY|!T`eNGwLhC3zS(Z+e-(Z;>_VPAiRCS0Tbioi9x18Y;>x6&GR&2t@cj@UIw zxame12D%KSm34{^v5h@Ph~W~*ogjP*d6cbCtqv>PpMyiNwr4R#%~nB`2?5<~15}xf zHI(x(jT71{JFUBU_Q-gm3iZm)hGYZf=f)$uhb}(f!MOF%qZ?u0ET`PEffNtS#N0Cn zu(*X?bLwELXv1#0#|nZr{fF?{WXr>#e~nJrSu1qde_FeI_E>fjtFeeEc0%#k17oUQ z)1tpT?Z?ZPHAD&wz|91wD~Wy_dU5Dy32Z^x>43zjJA4**sW%!Tu+36Ix!X#2FvaJ+ zSp+sW4z?J|0pMz?s+KuM0q0RR?IaOMI>e9nVmx9lvtnk~n*kHNsVuqOxvjytT) zWWrV}h2YyBaNx;n5jQR)W6BH|ik;%lc8B*c_lUqW1$_(A0bHYv zK9Gs!(!oG*9A_YXN+)MG=v=*>5uyye#W3h)ZwwLhps$(>WR&?a8PUapwzWz-#5(RQ z)&M+MXT9dg$)VkgPY>Ukj?O!MKro_{auX~yOz;nA;tkX5V{o4uB;ULLhV)5_(|cpgP?6iIC>$}1X|tI|0xPLW9*!r6U|nXj zcvL2d*&NNhAV*DFJZ__nr$S;nZ}Z=Bw>7wa`+M{mw!t9hiCHVp_qix!K_4Lh%3J@p zDO0?NZPjARvz)D-|5KI2w?e!kGs_ggS3TpcmVyc{-utY$6*kUFax4G?@8#7@OdpOc zTjAMuSU8n*NMIcuOBFxRYTE@O<=;Ty7}#CQ@%R?iRuCKb9D1v^;G@hwiqdRAGV=nJ z(?tG4WO#(AcR!(+UsKd0=TX|yiPDM1Pu1d4PZhsZn_N+B$1?2skg_NsEvUlMWL~3) z1;s0Pt;TEPHp=oYf?;;X@O+YO2|XNTMF2SnBn)WwoI(uZ6s7 z`5ILx