From a331ed2374b5c5e6ab1171e50cd06412a5e81963 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sun, 1 Oct 2023 15:09:09 -0700 Subject: [PATCH] [sysid] Add SysId (#5672) The source is copied from this commit: https://github.com/wpilibsuite/sysid/commit/625ff04784e5240991275b9fa52e7836d1dbb058. --- CMakeLists.txt | 1 + settings.gradle | 1 + sysid/.styleguide | 35 + sysid/CMakeLists.txt | 41 + sysid/Info.plist | 32 + sysid/build.gradle | 172 ++++ sysid/docs/arm-ols-with-angle-offset.md | 66 ++ sysid/docs/data-collection.md | 210 +++++ sysid/publish.gradle | 125 +++ sysid/scripts/time_plots.py | 89 ++ sysid/src/main/generate/WPILibVersion.cpp.in | 7 + sysid/src/main/native/cpp/App.cpp | 219 +++++ sysid/src/main/native/cpp/Main.cpp | 29 + sysid/src/main/native/cpp/Util.cpp | 80 ++ .../native/cpp/analysis/AnalysisManager.cpp | 568 ++++++++++++ .../main/native/cpp/analysis/AnalysisType.cpp | 23 + sysid/src/main/native/cpp/analysis/ArmSim.cpp | 64 ++ .../main/native/cpp/analysis/ElevatorSim.cpp | 50 + .../native/cpp/analysis/FeedbackAnalysis.cpp | 78 ++ .../cpp/analysis/FeedforwardAnalysis.cpp | 120 +++ .../native/cpp/analysis/FilteringUtils.cpp | 417 +++++++++ .../native/cpp/analysis/JSONConverter.cpp | 165 ++++ sysid/src/main/native/cpp/analysis/OLS.cpp | 48 + .../native/cpp/analysis/SimpleMotorSim.cpp | 47 + .../cpp/analysis/TrackWidthAnalysis.cpp | 12 + .../native/cpp/telemetry/TelemetryManager.cpp | 275 ++++++ sysid/src/main/native/cpp/view/Analyzer.cpp | 851 ++++++++++++++++++ .../src/main/native/cpp/view/AnalyzerPlot.cpp | 531 +++++++++++ .../main/native/cpp/view/JSONConverter.cpp | 64 ++ sysid/src/main/native/cpp/view/Logger.cpp | 222 +++++ sysid/src/main/native/include/sysid/Util.h | 89 ++ .../include/sysid/analysis/AnalysisManager.h | 358 ++++++++ .../include/sysid/analysis/AnalysisType.h | 63 ++ .../native/include/sysid/analysis/ArmSim.h | 79 ++ .../include/sysid/analysis/ElevatorSim.h | 76 ++ .../include/sysid/analysis/FeedbackAnalysis.h | 80 ++ .../sysid/analysis/FeedbackControllerPreset.h | 164 ++++ .../sysid/analysis/FeedforwardAnalysis.h | 25 + .../include/sysid/analysis/FilteringUtils.h | 209 +++++ .../include/sysid/analysis/JSONConverter.h | 24 + .../main/native/include/sysid/analysis/OLS.h | 26 + .../include/sysid/analysis/SimpleMotorSim.h | 74 ++ .../native/include/sysid/analysis/Storage.h | 95 ++ .../sysid/analysis/TrackWidthAnalysis.h | 19 + .../sysid/telemetry/TelemetryManager.h | 237 +++++ .../main/native/include/sysid/view/Analyzer.h | 261 ++++++ .../native/include/sysid/view/AnalyzerPlot.h | 203 +++++ .../native/include/sysid/view/JSONConverter.h | 57 ++ .../main/native/include/sysid/view/Logger.h | 82 ++ .../main/native/include/sysid/view/UILayout.h | 95 ++ sysid/src/main/native/mac/sysid.icns | Bin 0 -> 378189 bytes sysid/src/main/native/resources/sysid-128.png | Bin 0 -> 8688 bytes sysid/src/main/native/resources/sysid-16.png | Bin 0 -> 857 bytes sysid/src/main/native/resources/sysid-256.png | Bin 0 -> 16534 bytes sysid/src/main/native/resources/sysid-32.png | Bin 0 -> 2011 bytes sysid/src/main/native/resources/sysid-48.png | Bin 0 -> 3468 bytes sysid/src/main/native/resources/sysid-512.png | Bin 0 -> 31092 bytes sysid/src/main/native/resources/sysid-64.png | Bin 0 -> 4502 bytes sysid/src/main/native/win/sysid.ico | Bin 0 -> 54309 bytes sysid/src/main/native/win/sysid.rc | 1 + sysid/src/test/native/cpp/Main.cpp | 11 + .../native/cpp/analysis/AnalysisTypeTest.cpp | 18 + .../cpp/analysis/FeedbackAnalysisTest.cpp | 105 +++ .../cpp/analysis/FeedforwardAnalysisTest.cpp | 251 ++++++ .../test/native/cpp/analysis/FilterTest.cpp | 170 ++++ .../src/test/native/cpp/analysis/OLSTest.cpp | 42 + .../cpp/analysis/TrackWidthAnalysisTest.cpp | 12 + 67 files changed, 7568 insertions(+) create mode 100644 sysid/.styleguide create mode 100644 sysid/CMakeLists.txt create mode 100644 sysid/Info.plist create mode 100644 sysid/build.gradle create mode 100644 sysid/docs/arm-ols-with-angle-offset.md create mode 100644 sysid/docs/data-collection.md create mode 100644 sysid/publish.gradle create mode 100755 sysid/scripts/time_plots.py create mode 100644 sysid/src/main/generate/WPILibVersion.cpp.in create mode 100644 sysid/src/main/native/cpp/App.cpp create mode 100644 sysid/src/main/native/cpp/Main.cpp create mode 100644 sysid/src/main/native/cpp/Util.cpp create mode 100644 sysid/src/main/native/cpp/analysis/AnalysisManager.cpp create mode 100644 sysid/src/main/native/cpp/analysis/AnalysisType.cpp create mode 100644 sysid/src/main/native/cpp/analysis/ArmSim.cpp create mode 100644 sysid/src/main/native/cpp/analysis/ElevatorSim.cpp create mode 100644 sysid/src/main/native/cpp/analysis/FeedbackAnalysis.cpp create mode 100644 sysid/src/main/native/cpp/analysis/FeedforwardAnalysis.cpp create mode 100644 sysid/src/main/native/cpp/analysis/FilteringUtils.cpp create mode 100644 sysid/src/main/native/cpp/analysis/JSONConverter.cpp create mode 100644 sysid/src/main/native/cpp/analysis/OLS.cpp create mode 100644 sysid/src/main/native/cpp/analysis/SimpleMotorSim.cpp create mode 100644 sysid/src/main/native/cpp/analysis/TrackWidthAnalysis.cpp create mode 100644 sysid/src/main/native/cpp/telemetry/TelemetryManager.cpp create mode 100644 sysid/src/main/native/cpp/view/Analyzer.cpp create mode 100644 sysid/src/main/native/cpp/view/AnalyzerPlot.cpp create mode 100644 sysid/src/main/native/cpp/view/JSONConverter.cpp create mode 100644 sysid/src/main/native/cpp/view/Logger.cpp create mode 100644 sysid/src/main/native/include/sysid/Util.h create mode 100644 sysid/src/main/native/include/sysid/analysis/AnalysisManager.h create mode 100644 sysid/src/main/native/include/sysid/analysis/AnalysisType.h create mode 100644 sysid/src/main/native/include/sysid/analysis/ArmSim.h create mode 100644 sysid/src/main/native/include/sysid/analysis/ElevatorSim.h create mode 100644 sysid/src/main/native/include/sysid/analysis/FeedbackAnalysis.h create mode 100644 sysid/src/main/native/include/sysid/analysis/FeedbackControllerPreset.h create mode 100644 sysid/src/main/native/include/sysid/analysis/FeedforwardAnalysis.h create mode 100644 sysid/src/main/native/include/sysid/analysis/FilteringUtils.h create mode 100644 sysid/src/main/native/include/sysid/analysis/JSONConverter.h create mode 100644 sysid/src/main/native/include/sysid/analysis/OLS.h create mode 100644 sysid/src/main/native/include/sysid/analysis/SimpleMotorSim.h create mode 100644 sysid/src/main/native/include/sysid/analysis/Storage.h create mode 100644 sysid/src/main/native/include/sysid/analysis/TrackWidthAnalysis.h create mode 100644 sysid/src/main/native/include/sysid/telemetry/TelemetryManager.h create mode 100644 sysid/src/main/native/include/sysid/view/Analyzer.h create mode 100644 sysid/src/main/native/include/sysid/view/AnalyzerPlot.h create mode 100644 sysid/src/main/native/include/sysid/view/JSONConverter.h create mode 100644 sysid/src/main/native/include/sysid/view/Logger.h create mode 100644 sysid/src/main/native/include/sysid/view/UILayout.h create mode 100644 sysid/src/main/native/mac/sysid.icns create mode 100644 sysid/src/main/native/resources/sysid-128.png create mode 100644 sysid/src/main/native/resources/sysid-16.png create mode 100644 sysid/src/main/native/resources/sysid-256.png create mode 100644 sysid/src/main/native/resources/sysid-32.png create mode 100644 sysid/src/main/native/resources/sysid-48.png create mode 100644 sysid/src/main/native/resources/sysid-512.png create mode 100644 sysid/src/main/native/resources/sysid-64.png create mode 100644 sysid/src/main/native/win/sysid.ico create mode 100644 sysid/src/main/native/win/sysid.rc create mode 100644 sysid/src/test/native/cpp/Main.cpp create mode 100644 sysid/src/test/native/cpp/analysis/AnalysisTypeTest.cpp create mode 100644 sysid/src/test/native/cpp/analysis/FeedbackAnalysisTest.cpp create mode 100644 sysid/src/test/native/cpp/analysis/FeedforwardAnalysisTest.cpp create mode 100644 sysid/src/test/native/cpp/analysis/FilterTest.cpp create mode 100644 sysid/src/test/native/cpp/analysis/OLSTest.cpp create mode 100644 sysid/src/test/native/cpp/analysis/TrackWidthAnalysisTest.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 47e23668005..e617a756a55 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -293,6 +293,7 @@ if (WITH_GUI) add_subdirectory(wpigui) add_subdirectory(glass) add_subdirectory(outlineviewer) + add_subdirectory(sysid) if (LIBSSH_FOUND) add_subdirectory(roborioteamnumbersetter) add_subdirectory(datalogtool) diff --git a/settings.gradle b/settings.gradle index 38617022ae8..3e41f162093 100644 --- a/settings.gradle +++ b/settings.gradle @@ -40,6 +40,7 @@ include 'glass' include 'outlineviewer' include 'roborioteamnumbersetter' include 'datalogtool' +include 'sysid' include 'simulation:halsim_ds_socket' include 'simulation:halsim_gui' include 'simulation:halsim_ws_core' diff --git a/sysid/.styleguide b/sysid/.styleguide new file mode 100644 index 00000000000..8506bf193ea --- /dev/null +++ b/sysid/.styleguide @@ -0,0 +1,35 @@ +cppHeaderFileInclude { + \.h$ + \.inc$ + \.inl$ +} + +cppSrcFileInclude { + \.cpp$ +} + +generatedFileExclude { + src/main/native/resources/ + src/main/native/win/sysid.ico + src/main/native/mac/sysid.icns +} + +repoRootNameOverride { + sysid +} + +includeOtherLibs { + ^GLFW + ^fmt/ + ^frc/ + ^glass/ + ^gtest/ + ^imgui + ^implot\.h$ + ^networktables/ + ^portable-file-dialogs\.h$ + ^ntcore + ^units/ + ^wpi/ + ^wpigui +} diff --git a/sysid/CMakeLists.txt b/sysid/CMakeLists.txt new file mode 100644 index 00000000000..31fbe08d0da --- /dev/null +++ b/sysid/CMakeLists.txt @@ -0,0 +1,41 @@ +project(sysid) + +include(CompileWarnings) +include(GenResources) +include(LinkMacOSGUI) +include(AddTest) + +configure_file(src/main/generate/WPILibVersion.cpp.in WPILibVersion.cpp) +generate_resources(src/main/native/resources generated/main/cpp SYSID sysid sysid_resources_src) + +file(GLOB_RECURSE sysid_src src/main/native/cpp/*.cpp ${CMAKE_CURRENT_BINARY_DIR}/WPILibVersion.cpp) + +if (WIN32) + set(sysid_rc src/main/native/win/sysid.rc) +elseif(APPLE) + set(MACOSX_BUNDLE_ICON_FILE sysid.icns) + set(APP_ICON_MACOSX src/main/native/mac/sysid.icns) + set_source_files_properties(${APP_ICON_MACOSX} PROPERTIES MACOSX_PACKAGE_LOCATION "Resources") +endif() + +add_executable(sysid ${sysid_src} ${sysid_resources_src} ${sysid_rc} ${APP_ICON_MACOSX}) +wpilib_link_macos_gui(sysid) +wpilib_target_warnings(sysid) +target_include_directories(sysid PRIVATE src/main/native/include) +target_link_libraries(sysid wpimath libglassnt libglass) + +if (WIN32) + set_target_properties(sysid PROPERTIES WIN32_EXECUTABLE YES) +elseif(APPLE) + set_target_properties(sysid PROPERTIES MACOSX_BUNDLE YES OUTPUT_NAME "SysId") +endif() + +if (WITH_TESTS) + wpilib_add_test(sysid src/test/native/cpp) + wpilib_link_macos_gui(sysid_test) + target_sources(sysid_test PRIVATE ${sysid_src}) + target_compile_definitions(sysid_test PRIVATE RUNNING_SYSID_TESTS) + target_include_directories(sysid_test PRIVATE src/main/native/cpp + src/main/native/include) + target_link_libraries(sysid_test wpimath libglassnt libglass gtest) +endif() diff --git a/sysid/Info.plist b/sysid/Info.plist new file mode 100644 index 00000000000..37bb798b4f0 --- /dev/null +++ b/sysid/Info.plist @@ -0,0 +1,32 @@ + + + + + CFBundleName + SysId + CFBundleExecutable + sysid + CFBundleDisplayName + SysId + CFBundleIdentifier + edu.wpi.first.tools.SysId + CFBundleIconFile + sysid.icns + CFBundlePackageType + APPL + CFBundleSupportedPlatforms + + MacOSX + + CFBundleInfoDictionaryVersion + 6.0 + CFBundleShortVersionString + 2021 + CFBundleVersion + 2021 + LSMinimumSystemVersion + 10.14 + NSHighResolutionCapable + + + diff --git a/sysid/build.gradle b/sysid/build.gradle new file mode 100644 index 00000000000..e6709fc8285 --- /dev/null +++ b/sysid/build.gradle @@ -0,0 +1,172 @@ +import org.gradle.internal.os.OperatingSystem + +if (project.hasProperty('onlylinuxathena')) { + return; +} + +description = 'System identification for robot mechanisms' + +apply plugin: 'cpp' +apply plugin: 'google-test-test-suite' +apply plugin: 'visual-studio' +apply plugin: 'edu.wpi.first.NativeUtils' + +if (OperatingSystem.current().isWindows()) { + apply plugin: 'windows-resources' +} + +ext { + nativeName = 'sysid' +} + +apply from: "${rootDir}/shared/resources.gradle" +apply from: "${rootDir}/shared/config.gradle" + +def wpilibVersionFileInput = file("src/main/generate/WPILibVersion.cpp.in") +def wpilibVersionFileOutput = file("$buildDir/generated/main/cpp/WPILibVersion.cpp") + +apply from: "${rootDir}/shared/imgui.gradle" + +task generateCppVersion() { + description = 'Generates the wpilib version class' + group = 'WPILib' + + outputs.file wpilibVersionFileOutput + inputs.file wpilibVersionFileInput + + if (wpilibVersioning.releaseMode) { + outputs.upToDateWhen { false } + } + + // We follow a simple set of checks to determine whether we should generate a new version file: + // 1. If the release type is not development, we generate a new version file + // 2. If there is no generated version number, we generate a new version file + // 3. If there is a generated build number, and the release type is development, then we will + // only generate if the publish task is run. + doLast { + def version = wpilibVersioning.version.get() + println "Writing version ${version} to $wpilibVersionFileOutput" + + if (wpilibVersionFileOutput.exists()) { + wpilibVersionFileOutput.delete() + } + def read = wpilibVersionFileInput.text.replace('${wpilib_version}', version) + wpilibVersionFileOutput.write(read) + } +} + +gradle.taskGraph.addTaskExecutionGraphListener { graph -> + def willPublish = graph.hasTask(publish) + if (willPublish) { + generateCppVersion.outputs.upToDateWhen { false } + } +} + +def generateTask = createGenerateResourcesTask('main', 'SYSID', 'sysid', project) + +project(':').libraryBuild.dependsOn build +tasks.withType(CppCompile) { + dependsOn generateTask + dependsOn generateCppVersion +} + +model { + components { + // By default, a development executable will be generated. This is to help the case of + // testing specific functionality of the library. + "${nativeName}"(NativeExecutableSpec) { + baseName = 'sysid' + sources { + cpp { + source { + srcDirs 'src/main/native/cpp', "$buildDir/generated/main/cpp" + include '**/*.cpp' + } + exportedHeaders { + srcDirs 'src/main/native/include' + } + } + if (OperatingSystem.current().isWindows()) { + rc.source { + srcDirs 'src/main/native/win' + include '*.rc' + } + } + } + binaries.all { + if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) { + it.buildable = false + return + } + lib project: ':glass', library: 'glassnt', linkage: 'static' + lib project: ':glass', library: 'glass', linkage: 'static' + project(':ntcore').addNtcoreDependency(it, 'static') + lib project: ':wpinet', library: 'wpinet', linkage: 'static' + lib project: ':wpiutil', library: 'wpiutil', linkage: 'static' + lib project: ':wpimath', library: 'wpimath', linkage: 'static' + lib project: ':wpigui', library: 'wpigui', linkage: 'static' + nativeUtils.useRequiredLibrary(it, 'imgui') + if (it.targetPlatform.operatingSystem.isWindows()) { + it.linker.args << 'Gdi32.lib' << 'Shell32.lib' << 'd3d11.lib' << 'd3dcompiler.lib' + it.linker.args << '/DELAYLOAD:MF.dll' << '/DELAYLOAD:MFReadWrite.dll' << '/DELAYLOAD:MFPlat.dll' << '/delay:nobind' + } else if (it.targetPlatform.operatingSystem.isMacOsX()) { + it.linker.args << '-framework' << 'Metal' << '-framework' << 'MetalKit' << '-framework' << 'Cocoa' << '-framework' << 'IOKit' << '-framework' << 'CoreFoundation' << '-framework' << 'CoreVideo' << '-framework' << 'QuartzCore' + if (it.buildType.getName() == "release") { + it.linker.args << '-s' + } + } else { + it.linker.args << '-lX11' + if (it.targetPlatform.name.startsWith('linuxarm')) { + it.linker.args << '-lGL' + } + } + } + } + } + testSuites { + "${nativeName}Test"(GoogleTestTestSuiteSpec) { + for (NativeComponentSpec c : $.components) { + if (c.name == nativeName) { + testing c + break + } + } + sources.cpp.source { + srcDirs "src/test/native/cpp" + include "**/*.cpp" + } + binaries.all { + if (it.targetPlatform.name == nativeUtils.wpi.platforms.roborio) { + it.buildable = false + return + } + lib project: ':glass', library: 'glassnt', linkage: 'static' + lib project: ':glass', library: 'glass', linkage: 'static' + project(':ntcore').addNtcoreDependency(it, 'static') + lib project: ':wpinet', library: 'wpinet', linkage: 'static' + lib project: ':wpiutil', library: 'wpiutil', linkage: 'static' + lib project: ':wpimath', library: 'wpimath', linkage: 'static' + lib project: ':wpigui', library: 'wpigui', linkage: 'static' + nativeUtils.useRequiredLibrary(it, 'imgui') + if (it.targetPlatform.operatingSystem.isWindows()) { + it.linker.args << 'Gdi32.lib' << 'Shell32.lib' << 'd3d11.lib' << 'd3dcompiler.lib' + it.linker.args << '/DELAYLOAD:MF.dll' << '/DELAYLOAD:MFReadWrite.dll' << '/DELAYLOAD:MFPlat.dll' << '/delay:nobind' + } else if (it.targetPlatform.operatingSystem.isMacOsX()) { + it.linker.args << '-framework' << 'Metal' << '-framework' << 'MetalKit' << '-framework' << 'Cocoa' << '-framework' << 'IOKit' << '-framework' << 'CoreFoundation' << '-framework' << 'CoreVideo' << '-framework' << 'QuartzCore' + if (it.buildType.getName() == "release") { + it.linker.args << '-s' + } + } else { + it.linker.args << '-lX11' + if (it.targetPlatform.name.startsWith('linuxarm')) { + it.linker.args << '-lGL' + } + } + nativeUtils.useRequiredLibrary(it, "googletest_static") + it.cppCompiler.define("RUNNING_SYSID_TESTS") + } + } + } +} + +apply from: 'publish.gradle' diff --git a/sysid/docs/arm-ols-with-angle-offset.md b/sysid/docs/arm-ols-with-angle-offset.md new file mode 100644 index 00000000000..ecb5c439820 --- /dev/null +++ b/sysid/docs/arm-ols-with-angle-offset.md @@ -0,0 +1,66 @@ +# Arm OLS with angle offset + +If the arm encoder doesn't read zero degrees when the arm is horizontal, the fit +for `Kg` will be wrong. An angle offset should be added to the model like so. +``` +dx/dt = -Kv/Ka x + 1/Ka u - Ks/Ka sgn(x) - Kg/Ka cos(angle + offset) +``` +Use a trig identity to split the cosine into two terms. +``` +dx/dt = -Kv/Ka x + 1/Ka u - Ks/Ka sgn(x) - Kg/Ka (cos(angle) cos(offset) - sin(angle) sin(offset)) +dx/dt = -Kv/Ka x + 1/Ka u - Ks/Ka sgn(x) - Kg/Ka cos(angle) cos(offset) + Kg/Ka sin(angle) sin(offset) +``` +Reorder multiplicands so the offset trig is absorbed by the OLS terms. +``` +dx/dt = -Kv/Ka x + 1/Ka u - Ks/Ka sgn(x) - Kg/Ka cos(offset) cos(angle) + Kg/Ka sin(offset) sin(angle) +``` + +## OLS + +Let `α = -Kv/Ka`, `β = 1/Ka`, `γ = -Ks/Ka`, `δ = -Kg/Ka cos(offset)`, and `ε = Kg/Ka sin(offset)`. +``` +dx/dt = αx + βu + γ sgn(x) + δ cos(angle) + ε sin(angle) +``` + +### Ks, Kv, Ka + +Divide the OLS terms by each other to obtain `Ks`, `Kv`, and `Ka`. +``` +Ks = -γ/β +Kv = -α/β +Ka = 1/β +``` + +### Kg + +Take the sum of squares of the OLS terms containing the angle offset. The angle +offset trig functions will form a trig identity that cancels out. Then, just +solve for `Kg`. +``` +δ²+ε² = (-Kg/Ka cos(offset))² + (Kg/Ka sin(offset))² +δ²+ε² = (-Kg/Ka)² cos²(offset) + (Kg/Ka)² sin²(offset) +δ²+ε² = (Kg/Ka)² cos²(offset) + (Kg/Ka)² sin²(offset) +δ²+ε² = (Kg/Ka)² (cos²(offset) + sin²(offset)) +δ²+ε² = (Kg/Ka)² (1) +δ²+ε² = (Kg/Ka)² +√(δ²+ε²) = Kg/Ka +√(δ²+ε²) = Kg β +Kg = √(δ²+ε²)/β +``` + +As a sanity check, when the offset is zero, ε is zero and the equation for +`Kg` simplifies to -δ/β, the equation previously used by SysId. + +### Angle offset + +Divide ε by δ, combine the trig functions into `tan(offset)`, then use `atan2()` +to preserve the angle quadrant. Maintaining the proper negative signs in the +numerator and denominator are important for obtaining the correct result. +``` +δ = -Kg/Ka cos(offset) +ε = Kg/Ka sin(offset) +sin(offset)/-cos(offset) = ε/δ +sin(offset)/cos(offset) = ε/-δ +tan(offset) = ε/-δ +offset = atan2(ε, -δ) +``` diff --git a/sysid/docs/data-collection.md b/sysid/docs/data-collection.md new file mode 100644 index 00000000000..9d28a151a0d --- /dev/null +++ b/sysid/docs/data-collection.md @@ -0,0 +1,210 @@ +# Data Collection + +This document details how data must be sent over NetworkTables for accurate data collection. Note that the data format has changed from what the old [frc-characterization](https://github.com/wpilibsuite/frc-characterization) tool used to generate. + +## NetworkTables Data Entries + +Here is a list of the NT entries that are used to send and collect data between sysid and the robot program: + +| NT Entry | Type | Description | +| --------------------------------------| -------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | +| `/SmartDashboard/SysIdTelemetry` | `string` | Used to send telemetry from the robot program. This data is sent after the test completes once the robot enters the disabled state. | +| `/SmartDashboard/SysIdVoltageCommand` | `double` | Used to either send the ramp rate (V/s) for the quasistatic test or the voltage (V) for the dynamic test. | +| `/SmartDashboard/SysIdTestType` | `string` | Used to send the test type ("Quasistatic" or "Dynamic") which helps determine how the `VoltageCommand` entry will be used. | +| `/SmartDashboard/SysIdRotate` | `bool` | Used to receive the rotation bool from the Logger. If this is set to true, the drivetrain will rotate. It is only applicable for drivetrain tests. | + +## Telemetry Format + +There are two formats used to send telemetry from the robot program. One format is for non-drivetrain mechanisms, whereas the other is for all drivetrain tests (linear and angular). + +### Non-Drivetrain Mechanisms + +`timestamp, voltage, position, velocity` + +Example JSON: + +```json +{ +"fast-backward": [ +[ +timestamp 1, +voltage 1, +position 1, +velocity 1 +], +[ +timestamp 2, +voltage 2, +position 2, +velocity 2 +] +], +"fast-forward": [ +[ +timestamp 1, +voltage 1, +position 1, +velocity 1 +], +[ +timestamp 2, +voltage 2, +position 2, +velocity 2 +] +], +"slow-backward": [ +[ +timestamp 1, +voltage 1, +position 1, +velocity 1 +], +[ +timestamp 2, +voltage 2, +position 2, +velocity 2 +] +], +"slow-forward": [ +[ +timestamp 1, +voltage 1, +position 1, +velocity 1 +], +[ +timestamp 2, +voltage 2, +position 2, +velocity 2 +] +], +"sysid": true, +"test": "Simple", +"units": "Rotations", +"unitsPerRotation": 1.0 +} +``` + +Supported test types for the "test" field in this data format include "Arm", +"Elevator", and "Simple". Supported unit types include "Meters", "Feet", +"Inches", "Radians", "Rotations", and "Degrees". + +### Drivetrain + +`timestamp, l voltage, r voltage, l position, r position, l velocity, r velocity, angle, angular rate` + +Note that all positions and velocities should be in rotations of the output and rotations/sec of the output respectively. If there is a gearing between the encoder and the output, that should be taken into account. + +Example JSON: + +```json +{ +"fast-backward": [ +[ +timestamp 1, +l voltage 1, +r voltage 1, +l position 1, +r position 1, +l velocity 1, +r velocity 1, +angle 1, +angular rate 1 +], +[ +timestamp 2, +l voltage 2, +r voltage 2, +l position 2, +r position 2, +l velocity 2, +r velocity 2, +angle 2, +angular rate 2 +] +], +"fast-forward": [ +[ +timestamp 1, +l voltage 1, +r voltage 1, +l position 1, +r position 1, +l velocity 1, +r velocity 1, +angle 1, +angular rate 1 +], +[ +timestamp 2, +l voltage 2, +r voltage 2, +l position 2, +r position 2, +l velocity 2, +r velocity 2, +angle 2, +angular rate 2 +] +], +"slow-backward": [ +[ +timestamp 1, +l voltage 1, +r voltage 1, +l position 1, +r position 1, +l velocity 1, +r velocity 1, +angle 1, +angular rate 1 +], +[ +timestamp 2, +l voltage 2, +r voltage 2, +l position 2, +r position 2, +l velocity 2, +r velocity 2, +angle 2, +angular rate 2 +] +], +"slow-forward": [ +[ +timestamp 1, +l voltage 1, +r voltage 1, +l position 1, +r position 1, +l velocity 1, +r velocity 1, +angle 1, +angular rate 1 +], +[ +timestamp 2, +l voltage 2, +r voltage 2, +l position 2, +r position 2, +l velocity 2, +r velocity 2, +angle 2, +angular rate 2 +] +], +"sysid": true, +"test": "Drivetrain", +"units": "Rotations", +"unitsPerRotation": 1.0 +} +``` + +Supported test types for the "test" field in this data format include +"Drivetrain" and "Drivetrain (Angular)". Supported unit types include "Meters", +"Feet", "Inches", "Radians", "Rotations", and "Degrees". diff --git a/sysid/publish.gradle b/sysid/publish.gradle new file mode 100644 index 00000000000..13569464413 --- /dev/null +++ b/sysid/publish.gradle @@ -0,0 +1,125 @@ +apply plugin: 'maven-publish' + +def baseArtifactId = 'SysId' +def artifactGroupId = 'edu.wpi.first.tools' +def zipBaseName = '_GROUP_edu_wpi_first_tools_ID_SysId_CLS' + +def outputsFolder = file("$project.buildDir/outputs") + +model { + tasks { + // Create the run task. + $.components.sysid.binaries.each { bin -> + if (bin.buildable && bin.name.toLowerCase().contains("debug") && nativeUtils.isNativeDesktopPlatform(bin.targetPlatform)) { + Task run = project.tasks.create("run", Exec) { + commandLine bin.tasks.install.runScriptFile.get().asFile.toString() + } + run.dependsOn bin.tasks.install + } + } + } + publishing { + def sysIdTaskList = [] + $.components.each { component -> + component.binaries.each { binary -> + if (binary in NativeExecutableBinarySpec && binary.component.name.contains("sysid")) { + if (binary.buildable && (binary.name.contains('Release') || binary.name.contains('release'))) { + // We are now in the binary that we want. + // This is the default application path for the ZIP task. + def applicationPath = binary.executable.file + def icon = file("$project.projectDir/src/main/native/mac/ov.icns") + + // Create the macOS bundle. + def bundleTask = project.tasks.create("bundleSysIdOsxApp" + binary.targetPlatform.architecture.name, Copy) { + description("Creates a macOS application bundle for SysId") + from(file("$project.projectDir/Info.plist")) + into(file("$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name/SysId.app/Contents")) + into("MacOS") { + with copySpec { + from binary.executable.file + } + } + into("Resources") { + with copySpec { + from icon + } + } + + inputs.property "HasDeveloperId", project.hasProperty("developerID") + + doLast { + if (project.hasProperty("developerID")) { + // Get path to binary. + exec { + workingDir rootDir + def args = [ + "sh", + "-c", + "codesign --force --strict --deep " + + "--timestamp --options=runtime " + + "--verbose -s ${project.findProperty("developerID")} " + + "$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name/SysId.app/" + ] + commandLine args + } + } + } + } + + // Reset the application path if we are creating a bundle. + if (binary.targetPlatform.operatingSystem.isMacOsX()) { + applicationPath = file("$project.buildDir/outputs/bundles/$binary.targetPlatform.architecture.name") + project.build.dependsOn bundleTask + } + + // Create the ZIP. + def task = project.tasks.create("copySysIdExecutable" + binary.targetPlatform.architecture.name, Zip) { + description("Copies the SysId executable to the outputs directory.") + destinationDirectory = outputsFolder + + archiveBaseName = '_M_' + zipBaseName + duplicatesStrategy = 'exclude' + archiveClassifier = nativeUtils.getPublishClassifier(binary) + + from(licenseFile) { + into '/' + } + + from(applicationPath) + + if (binary.targetPlatform.operatingSystem.isWindows()) { + def exePath = binary.executable.file.absolutePath + exePath = exePath.substring(0, exePath.length() - 4) + def pdbPath = new File(exePath + '.pdb') + from(pdbPath) + } + + into(nativeUtils.getPlatformPath(binary)) + } + + if (binary.targetPlatform.operatingSystem.isMacOsX()) { + bundleTask.dependsOn binary.tasks.link + task.dependsOn(bundleTask) + } + + task.dependsOn binary.tasks.link + sysIdTaskList.add(task) + project.build.dependsOn task + project.artifacts { task } + addTaskToCopyAllOutputs(task) + } + } + } + } + + publications { + sysId(MavenPublication) { + sysIdTaskList.each { artifact it } + + artifactId = baseArtifactId + groupId = artifactGroupId + version wpilibVersioning.version.get() + } + } + } +} diff --git a/sysid/scripts/time_plots.py b/sysid/scripts/time_plots.py new file mode 100755 index 00000000000..6878126af2c --- /dev/null +++ b/sysid/scripts/time_plots.py @@ -0,0 +1,89 @@ +#!/usr/bin/env python3 + +import json +import pathlib + +import matplotlib.pyplot as plt +import pandas as pd +import sys + +# Load data +filename = pathlib.Path(sys.argv[1]) + +UNIT_TO_ABBREVIATION = { + "Meters": "m", + "Feet": "ft", + "Inches": "in", + "Degrees": "deg", + "Rotations": "rot", + "Radians": "rad", +} + +# Make DataFrame to facilitate plotting +if filename.suffix == ".json": + raw_data = json.loads(filename.read_text()) + unit = raw_data["units"] + + # Get Unit + try: + abbreviation = UNIT_TO_ABBREVIATION[unit] + except KeyError: + raise ValueError("Invalid Unit") + + # Make Columns + columns = ["Timestamp (s)", "Test"] + if "Drive" in raw_data["test"]: + columns.extend( + [ + "Left Volts (V)", + "Right Volts (V)", + f"Left Position ({abbreviation})", + f"Right Position ({abbreviation})", + f"Left Velocity ({abbreviation}/s)", + f"Right Velocity ({abbreviation}/s)", + "Gyro Position (deg)", + "Gyro Rate (deg/s)", + ] + ) + unit_columns = columns[4:8] + else: + columns.extend( + ["Volts (V)", f"Position ({abbreviation})", f"Velocity ({abbreviation}/s)"] + ) + unit_columns = columns[3:] + + prepared_data = pd.DataFrame(columns=columns) + for test in raw_data.keys(): + if "-" not in test: + continue + formatted_entry = [[pt[0], test, *pt[1:]] for pt in raw_data[test]] + prepared_data = pd.concat( + [prepared_data, pd.DataFrame(formatted_entry, columns=columns)] + ) + + units_per_rot = raw_data["unitsPerRotation"] + + for column in unit_columns: + prepared_data[column] *= units_per_rot +else: + prepared_data = pd.read_csv(filename) + +# First 2 columns are Timestamp and Test +for column in prepared_data.columns[2:]: + # Configure Plot Labels + plt.figure() + plt.xlabel("Timestamp (s)") + plt.ylabel(column) + + # Configure title without units + print(column) + end = column.find("(") + plt.title(f"{column[:end].strip()} vs Time") + + # Plot data for each test + for test in pd.unique(prepared_data["Test"]): + test_data = prepared_data[prepared_data["Test"] == test] + plt.plot(test_data["Timestamp (s)"], test_data[column], label=test) + plt.legend() + +plt.show() diff --git a/sysid/src/main/generate/WPILibVersion.cpp.in b/sysid/src/main/generate/WPILibVersion.cpp.in new file mode 100644 index 00000000000..b0a44905207 --- /dev/null +++ b/sysid/src/main/generate/WPILibVersion.cpp.in @@ -0,0 +1,7 @@ +/* + * Autogenerated file! Do not manually edit this file. This version is regenerated + * any time the publish task is run, or when this file is deleted. + */ +const char* GetWPILibVersion() { + return "${wpilib_version}"; +} diff --git a/sysid/src/main/native/cpp/App.cpp b/sysid/src/main/native/cpp/App.cpp new file mode 100644 index 00000000000..947ea434a65 --- /dev/null +++ b/sysid/src/main/native/cpp/App.cpp @@ -0,0 +1,219 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include + +#ifndef RUNNING_SYSID_TESTS + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "sysid/view/Analyzer.h" +#include "sysid/view/JSONConverter.h" +#include "sysid/view/Logger.h" +#include "sysid/view/UILayout.h" + +namespace gui = wpi::gui; + +static std::unique_ptr gWindowManager; + +glass::Window* gLoggerWindow; +glass::Window* gAnalyzerWindow; +glass::Window* gProgramLogWindow; +static glass::MainMenuBar gMainMenu; + +std::unique_ptr gJSONConverter; + +glass::LogData gLog; +wpi::Logger gLogger; + +const char* GetWPILibVersion(); + +namespace sysid { +std::string_view GetResource_sysid_16_png(); +std::string_view GetResource_sysid_32_png(); +std::string_view GetResource_sysid_48_png(); +std::string_view GetResource_sysid_64_png(); +std::string_view GetResource_sysid_128_png(); +std::string_view GetResource_sysid_256_png(); +std::string_view GetResource_sysid_512_png(); +} // namespace sysid + +void Application(std::string_view saveDir) { + // Create the wpigui (along with Dear ImGui) and Glass contexts. + gui::CreateContext(); + glass::CreateContext(); + + // Add icons + gui::AddIcon(sysid::GetResource_sysid_16_png()); + gui::AddIcon(sysid::GetResource_sysid_32_png()); + gui::AddIcon(sysid::GetResource_sysid_48_png()); + gui::AddIcon(sysid::GetResource_sysid_64_png()); + gui::AddIcon(sysid::GetResource_sysid_128_png()); + gui::AddIcon(sysid::GetResource_sysid_256_png()); + gui::AddIcon(sysid::GetResource_sysid_512_png()); + + glass::SetStorageName("sysid"); + glass::SetStorageDir(saveDir.empty() ? gui::GetPlatformSaveFileDir() + : saveDir); + + // Add messages from the global sysid logger into the Log window. + gLogger.SetLogger([](unsigned int level, const char* file, unsigned int line, + const char* msg) { + const char* lvl = ""; + if (level >= wpi::WPI_LOG_CRITICAL) { + lvl = "CRITICAL: "; + } else if (level >= wpi::WPI_LOG_ERROR) { + lvl = "ERROR: "; + } else if (level >= wpi::WPI_LOG_WARNING) { + lvl = "WARNING: "; + } else if (level >= wpi::WPI_LOG_INFO) { + lvl = "INFO: "; + } else if (level >= wpi::WPI_LOG_DEBUG) { + lvl = "DEBUG: "; + } + std::string filename = std::filesystem::path{file}.filename().string(); + gLog.Append(fmt::format("{}{} ({}:{})\n", lvl, msg, filename, line)); +#ifndef NDEBUG + fmt::print(stderr, "{}{} ({}:{})\n", lvl, msg, filename, line); +#endif + }); + + gLogger.set_min_level(wpi::WPI_LOG_DEBUG); + // Set the number of workers for the libuv threadpool. + uv_os_setenv("UV_THREADPOOL_SIZE", "6"); + + // Initialize window manager and add views. + auto& storage = glass::GetStorageRoot().GetChild("SysId"); + gWindowManager = std::make_unique(storage); + gWindowManager->GlobalInit(); + + gLoggerWindow = gWindowManager->AddWindow( + "Logger", std::make_unique(storage, gLogger)); + + gAnalyzerWindow = gWindowManager->AddWindow( + "Analyzer", std::make_unique(storage, gLogger)); + + gProgramLogWindow = gWindowManager->AddWindow( + "Program Log", std::make_unique(&gLog)); + + // Set default positions and sizes for windows. + + // Logger window position/size + gLoggerWindow->SetDefaultPos(sysid::kLoggerWindowPos.x, + sysid::kLoggerWindowPos.y); + gLoggerWindow->SetDefaultSize(sysid::kLoggerWindowSize.x, + sysid::kLoggerWindowSize.y); + + // Analyzer window position/size + gAnalyzerWindow->SetDefaultPos(sysid::kAnalyzerWindowPos.x, + sysid::kAnalyzerWindowPos.y); + gAnalyzerWindow->SetDefaultSize(sysid::kAnalyzerWindowSize.x, + sysid::kAnalyzerWindowSize.y); + + // Program log window position/size + gProgramLogWindow->SetDefaultPos(sysid::kProgramLogWindowPos.x, + sysid::kProgramLogWindowPos.y); + gProgramLogWindow->SetDefaultSize(sysid::kProgramLogWindowSize.x, + sysid::kProgramLogWindowSize.y); + gProgramLogWindow->DisableRenamePopup(); + + gJSONConverter = std::make_unique(gLogger); + + // Configure save file. + gui::ConfigurePlatformSaveFile("sysid.ini"); + + // Add menu bar. + gui::AddLateExecute([] { + ImGui::BeginMainMenuBar(); + gMainMenu.WorkspaceMenu(); + gui::EmitViewMenu(); + + if (ImGui::BeginMenu("Widgets")) { + gWindowManager->DisplayMenu(); + ImGui::EndMenu(); + } + + bool about = false; + if (ImGui::BeginMenu("Info")) { + if (ImGui::MenuItem("About")) { + about = true; + } + ImGui::EndMenu(); + } + + bool toCSV = false; + if (ImGui::BeginMenu("JSON Converters")) { + if (ImGui::MenuItem("JSON to CSV Converter")) { + toCSV = true; + } + + ImGui::EndMenu(); + } + + if (ImGui::BeginMenu("Docs")) { + if (ImGui::MenuItem("Online documentation")) { + wpi::gui::OpenURL( + "https://docs.wpilib.org/en/stable/docs/software/pathplanning/" + "system-identification/"); + } + + ImGui::EndMenu(); + } + + ImGui::EndMainMenuBar(); + + if (toCSV) { + ImGui::OpenPopup("SysId JSON to CSV Converter"); + toCSV = false; + } + + if (ImGui::BeginPopupModal("SysId JSON to CSV Converter")) { + gJSONConverter->DisplayCSVConvert(); + if (ImGui::Button("Close")) { + ImGui::CloseCurrentPopup(); + } + ImGui::EndPopup(); + } + + if (about) { + ImGui::OpenPopup("About"); + about = false; + } + if (ImGui::BeginPopupModal("About")) { + ImGui::Text("SysId: System Identification for Robot Mechanisms"); + ImGui::Separator(); + ImGui::Text("v%s", GetWPILibVersion()); + ImGui::Separator(); + ImGui::Text("Save location: %s", glass::GetStorageDir().c_str()); + if (ImGui::Button("Close")) { + ImGui::CloseCurrentPopup(); + } + ImGui::EndPopup(); + } + }); + + gui::Initialize("System Identification", sysid::kAppWindowSize.x, + sysid::kAppWindowSize.y); + gui::Main(); + + glass::DestroyContext(); + gui::DestroyContext(); +} + +#endif diff --git a/sysid/src/main/native/cpp/Main.cpp b/sysid/src/main/native/cpp/Main.cpp new file mode 100644 index 00000000000..6fba8480da3 --- /dev/null +++ b/sysid/src/main/native/cpp/Main.cpp @@ -0,0 +1,29 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include + +#ifndef RUNNING_SYSID_TESTS + +void Application(std::string_view saveDir); + +#ifdef _WIN32 +int __stdcall WinMain(void* hInstance, void* hPrevInstance, char* pCmdLine, + int nCmdShow) { + int argc = __argc; + char** argv = __argv; +#else +int main(int argc, char** argv) { +#endif + std::string_view saveDir; + if (argc == 2) { + saveDir = argv[1]; + } + + Application(saveDir); + + return 0; +} + +#endif diff --git a/sysid/src/main/native/cpp/Util.cpp b/sysid/src/main/native/cpp/Util.cpp new file mode 100644 index 00000000000..a9acc537a7a --- /dev/null +++ b/sysid/src/main/native/cpp/Util.cpp @@ -0,0 +1,80 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/Util.h" + +#include +#include + +#include +#include + +void sysid::CreateTooltip(const char* text) { + ImGui::SameLine(); + ImGui::TextDisabled(" (?)"); + + if (ImGui::IsItemHovered()) { + ImGui::BeginTooltip(); + ImGui::PushTextWrapPos(ImGui::GetFontSize() * 35.0f); + ImGui::TextUnformatted(text); + ImGui::PopTextWrapPos(); + ImGui::EndTooltip(); + } +} + +void sysid::CreateErrorPopup(bool& isError, std::string_view errorMessage) { + if (isError) { + ImGui::OpenPopup("Exception Caught!"); + } + + // Handle exceptions. + ImGui::SetNextWindowSize(ImVec2(480.f, 0.0f)); + if (ImGui::BeginPopupModal("Exception Caught!")) { + ImGui::PushTextWrapPos(0.0f); + ImGui::TextColored(ImVec4(1.0f, 0.4f, 0.4f, 1.0f), "%s", + errorMessage.data()); + ImGui::PopTextWrapPos(); + if (ImGui::Button("Close")) { + ImGui::CloseCurrentPopup(); + isError = false; + } + ImGui::EndPopup(); + } +} + +std::string_view sysid::GetAbbreviation(std::string_view unit) { + if (unit == "Meters") { + return "m"; + } else if (unit == "Feet") { + return "ft"; + } else if (unit == "Inches") { + return "in"; + } else if (unit == "Radians") { + return "rad"; + } else if (unit == "Degrees") { + return "deg"; + } else if (unit == "Rotations") { + return "rot"; + } else { + throw std::runtime_error("Invalid Unit"); + } +} + +void sysid::SaveFile(std::string_view contents, + const std::filesystem::path& path) { + // Create the path if it doesn't already exist. + std::filesystem::create_directories(path.root_directory()); + + // Open a fd_ostream to write to file. + std::error_code ec; + wpi::raw_fd_ostream ostream{path.string(), ec}; + + // Check error code. + if (ec) { + throw std::runtime_error("Cannot write to file: " + ec.message()); + } + + // Write contents. + ostream << contents; +} diff --git a/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp b/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp new file mode 100644 index 00000000000..1d7565b37bd --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp @@ -0,0 +1,568 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/AnalysisManager.h" + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include "sysid/Util.h" +#include "sysid/analysis/FilteringUtils.h" +#include "sysid/analysis/JSONConverter.h" +#include "sysid/analysis/TrackWidthAnalysis.h" + +using namespace sysid; + +/** + * Converts a raw data vector into a PreparedData vector with only the + * timestamp, voltage, position, and velocity fields filled out. + * + * @tparam S The size of the arrays in the raw data vector + * @tparam Timestamp The index of the Timestamp data in the raw data vector + * arrays + * @tparam Voltage The index of the Voltage data in the raw data vector arrays + * @tparam Position The index of the Position data in the raw data vector arrays + * @tparam Velocity The index of the Velocity data in the raw data vector arrays + * + * @param data A raw data vector + * + * @return A PreparedData vector + */ +template +static std::vector ConvertToPrepared( + const std::vector>& data) { + std::vector prepared; + for (int i = 0; i < static_cast(data.size()) - 1; ++i) { + const auto& pt1 = data[i]; + const auto& pt2 = data[i + 1]; + prepared.emplace_back(PreparedData{ + units::second_t{pt1[Timestamp]}, pt1[Voltage], pt1[Position], + pt1[Velocity], units::second_t{pt2[Timestamp] - pt1[Timestamp]}}); + } + return prepared; +} + +/** + * To preserve a raw copy of the data, this method saves a raw version + * in the dataset StringMap where the key of the raw data starts with "raw-" + * before the name of the original data. + * + * @tparam S The size of the array data that's being used + * + * @param dataset A reference to the dataset being used + */ +template +static void CopyRawData( + wpi::StringMap>>* dataset) { + auto& data = *dataset; + // Loads the Raw Data + for (auto& it : data) { + auto key = it.first(); + auto& dataset = it.getValue(); + + if (!wpi::contains(key, "raw")) { + data[fmt::format("raw-{}", key)] = dataset; + data[fmt::format("original-raw-{}", key)] = dataset; + } + } +} + +/** + * Assigns the combines the various datasets into a single one for analysis. + * + * @param slowForward The slow forward dataset + * @param slowBackward The slow backward dataset + * @param fastForward The fast forward dataset + * @param fastBackward The fast backward dataset + */ +static Storage CombineDatasets(const std::vector& slowForward, + const std::vector& slowBackward, + const std::vector& fastForward, + const std::vector& fastBackward) { + return Storage{slowForward, slowBackward, fastForward, fastBackward}; +} + +void AnalysisManager::PrepareGeneralData() { + using Data = std::array; + wpi::StringMap> data; + wpi::StringMap> preparedData; + + // Store the raw data columns. + static constexpr size_t kTimeCol = 0; + static constexpr size_t kVoltageCol = 1; + static constexpr size_t kPosCol = 2; + static constexpr size_t kVelCol = 3; + + WPI_INFO(m_logger, "{}", "Reading JSON data."); + // Get the major components from the JSON and store them inside a StringMap. + for (auto&& key : AnalysisManager::kJsonDataKeys) { + data[key] = m_json.at(key).get>(); + } + + WPI_INFO(m_logger, "{}", "Preprocessing raw data."); + // Ensure that voltage and velocity have the same sign. Also multiply + // positions and velocities by the factor. + for (auto it = data.begin(); it != data.end(); ++it) { + for (auto&& pt : it->second) { + pt[kVoltageCol] = std::copysign(pt[kVoltageCol], pt[kVelCol]); + pt[kPosCol] *= m_factor; + pt[kVelCol] *= m_factor; + } + } + + WPI_INFO(m_logger, "{}", "Copying raw data."); + CopyRawData(&data); + + WPI_INFO(m_logger, "{}", "Converting raw data to PreparedData struct."); + // Convert data to PreparedData structs + for (auto& it : data) { + auto key = it.first(); + preparedData[key] = + ConvertToPrepared<4, kTimeCol, kVoltageCol, kPosCol, kVelCol>( + data[key]); + } + + // Store the original datasets + m_originalDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kCombined)] = + CombineDatasets(preparedData["original-raw-slow-forward"], + preparedData["original-raw-slow-backward"], + preparedData["original-raw-fast-forward"], + preparedData["original-raw-fast-backward"]); + + WPI_INFO(m_logger, "{}", "Initial trimming and filtering."); + sysid::InitialTrimAndFilter(&preparedData, &m_settings, m_positionDelays, + m_velocityDelays, m_minStepTime, m_maxStepTime, + m_unit); + + WPI_INFO(m_logger, "{}", "Acceleration filtering."); + sysid::AccelFilter(&preparedData); + + WPI_INFO(m_logger, "{}", "Storing datasets."); + // Store the raw datasets + m_rawDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kCombined)] = + CombineDatasets( + preparedData["raw-slow-forward"], preparedData["raw-slow-backward"], + preparedData["raw-fast-forward"], preparedData["raw-fast-backward"]); + + // Store the filtered datasets + m_filteredDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kCombined)] = + CombineDatasets( + preparedData["slow-forward"], preparedData["slow-backward"], + preparedData["fast-forward"], preparedData["fast-backward"]); + + m_startTimes = {preparedData["raw-slow-forward"][0].timestamp, + preparedData["raw-slow-backward"][0].timestamp, + preparedData["raw-fast-forward"][0].timestamp, + preparedData["raw-fast-backward"][0].timestamp}; +} + +void AnalysisManager::PrepareAngularDrivetrainData() { + using Data = std::array; + wpi::StringMap> data; + wpi::StringMap> preparedData; + + // Store the relevant raw data columns. + static constexpr size_t kTimeCol = 0; + static constexpr size_t kLVoltageCol = 1; + static constexpr size_t kRVoltageCol = 2; + static constexpr size_t kLPosCol = 3; + static constexpr size_t kRPosCol = 4; + static constexpr size_t kLVelCol = 5; + static constexpr size_t kRVelCol = 6; + static constexpr size_t kAngleCol = 7; + static constexpr size_t kAngularRateCol = 8; + + WPI_INFO(m_logger, "{}", "Reading JSON data."); + // Get the major components from the JSON and store them inside a StringMap. + for (auto&& key : AnalysisManager::kJsonDataKeys) { + data[key] = m_json.at(key).get>(); + } + + WPI_INFO(m_logger, "{}", "Preprocessing raw data."); + // Ensure that voltage and velocity have the same sign. Also multiply + // positions and velocities by the factor. + for (auto it = data.begin(); it != data.end(); ++it) { + for (auto&& pt : it->second) { + pt[kLPosCol] *= m_factor; + pt[kRPosCol] *= m_factor; + pt[kLVelCol] *= m_factor; + pt[kRVelCol] *= m_factor; + + // Stores the average voltages in the left voltage column. + // This aggregates the left and right voltages into a single voltage + // column for the ConvertToPrepared() method. std::copysign() ensures the + // polarity of the voltage matches the direction the robot turns. + pt[kLVoltageCol] = std::copysign( + (std::abs(pt[kLVoltageCol]) + std::abs(pt[kRVoltageCol])) / 2, + pt[kAngularRateCol]); + + // ω = (v_r - v_l) / trackwidth + // v = ωr => v = ω * trackwidth / 2 + // (v_r - v_l) / trackwidth * (trackwidth / 2) = (v_r - v_l) / 2 + // However, since we know this is an angular test, the left and right + // wheel velocities will have opposite signs, allowing us to add their + // absolute values and get the same result (in terms of magnitude). + // std::copysign() is used to make sure the direction of the wheel + // velocities matches the direction the robot turns. + pt[kAngularRateCol] = + std::copysign((std::abs(pt[kRVelCol]) + std::abs(pt[kLVelCol])) / 2, + pt[kAngularRateCol]); + } + } + + WPI_INFO(m_logger, "{}", "Calculating trackwidth"); + // Aggregating all the deltas from all the tests + double leftDelta = 0.0; + double rightDelta = 0.0; + double angleDelta = 0.0; + for (const auto& it : data) { + auto key = it.first(); + auto& trackWidthData = data[key]; + leftDelta += std::abs(trackWidthData.back()[kLPosCol] - + trackWidthData.front()[kLPosCol]); + rightDelta += std::abs(trackWidthData.back()[kRPosCol] - + trackWidthData.front()[kRPosCol]); + angleDelta += std::abs(trackWidthData.back()[kAngleCol] - + trackWidthData.front()[kAngleCol]); + } + m_trackWidth = sysid::CalculateTrackWidth(leftDelta, rightDelta, + units::radian_t{angleDelta}); + + WPI_INFO(m_logger, "{}", "Copying raw data."); + CopyRawData(&data); + + WPI_INFO(m_logger, "{}", "Converting to PreparedData struct."); + // Convert raw data to prepared data + for (const auto& it : data) { + auto key = it.first(); + preparedData[key] = ConvertToPrepared<9, kTimeCol, kLVoltageCol, kAngleCol, + kAngularRateCol>(data[key]); + } + + // Create the distinct datasets and store them + m_originalDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kCombined)] = + CombineDatasets(preparedData["original-raw-slow-forward"], + preparedData["original-raw-slow-backward"], + preparedData["original-raw-fast-forward"], + preparedData["original-raw-fast-backward"]); + + WPI_INFO(m_logger, "{}", "Applying trimming and filtering."); + sysid::InitialTrimAndFilter(&preparedData, &m_settings, m_positionDelays, + m_velocityDelays, m_minStepTime, m_maxStepTime); + + WPI_INFO(m_logger, "{}", "Acceleration filtering."); + sysid::AccelFilter(&preparedData); + + WPI_INFO(m_logger, "{}", "Storing datasets."); + // Create the distinct datasets and store them + m_rawDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kCombined)] = + CombineDatasets( + preparedData["raw-slow-forward"], preparedData["raw-slow-backward"], + preparedData["raw-fast-forward"], preparedData["raw-fast-backward"]); + m_filteredDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kCombined)] = + CombineDatasets( + preparedData["slow-forward"], preparedData["slow-backward"], + preparedData["fast-forward"], preparedData["fast-backward"]); + + m_startTimes = {preparedData["slow-forward"][0].timestamp, + preparedData["slow-backward"][0].timestamp, + preparedData["fast-forward"][0].timestamp, + preparedData["fast-backward"][0].timestamp}; +} + +void AnalysisManager::PrepareLinearDrivetrainData() { + using Data = std::array; + wpi::StringMap> data; + wpi::StringMap> preparedData; + + // Store the relevant raw data columns. + static constexpr size_t kTimeCol = 0; + static constexpr size_t kLVoltageCol = 1; + static constexpr size_t kRVoltageCol = 2; + static constexpr size_t kLPosCol = 3; + static constexpr size_t kRPosCol = 4; + static constexpr size_t kLVelCol = 5; + static constexpr size_t kRVelCol = 6; + + // Get the major components from the JSON and store them inside a StringMap. + WPI_INFO(m_logger, "{}", "Reading JSON data."); + for (auto&& key : AnalysisManager::kJsonDataKeys) { + data[key] = m_json.at(key).get>(); + } + + // Ensure that voltage and velocity have the same sign. Also multiply + // positions and velocities by the factor. + WPI_INFO(m_logger, "{}", "Preprocessing raw data."); + for (auto it = data.begin(); it != data.end(); ++it) { + for (auto&& pt : it->second) { + pt[kLVoltageCol] = std::copysign(pt[kLVoltageCol], pt[kLVelCol]); + pt[kRVoltageCol] = std::copysign(pt[kRVoltageCol], pt[kRVelCol]); + pt[kLPosCol] *= m_factor; + pt[kRPosCol] *= m_factor; + pt[kLVelCol] *= m_factor; + pt[kRVelCol] *= m_factor; + } + } + + WPI_INFO(m_logger, "{}", "Copying raw data."); + CopyRawData(&data); + + // Convert data to PreparedData + WPI_INFO(m_logger, "{}", "Converting to PreparedData struct."); + for (auto& it : data) { + auto key = it.first(); + + preparedData[fmt::format("left-{}", key)] = + ConvertToPrepared<9, kTimeCol, kLVoltageCol, kLPosCol, kLVelCol>( + data[key]); + preparedData[fmt::format("right-{}", key)] = + ConvertToPrepared<9, kTimeCol, kRVoltageCol, kRPosCol, kRVelCol>( + data[key]); + } + + // Create the distinct raw datasets and store them + auto originalSlowForward = AnalysisManager::DataConcat( + preparedData["left-original-raw-slow-forward"], + preparedData["right-original-raw-slow-forward"]); + auto originalSlowBackward = AnalysisManager::DataConcat( + preparedData["left-original-raw-slow-backward"], + preparedData["right-original-raw-slow-backward"]); + auto originalFastForward = AnalysisManager::DataConcat( + preparedData["left-original-raw-fast-forward"], + preparedData["right-original-raw-fast-forward"]); + auto originalFastBackward = AnalysisManager::DataConcat( + preparedData["left-original-raw-fast-backward"], + preparedData["right-original-raw-fast-backward"]); + m_originalDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kCombined)] = + CombineDatasets(originalSlowForward, originalSlowBackward, + originalFastForward, originalFastBackward); + m_originalDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kLeft)] = + CombineDatasets(preparedData["left-original-raw-slow-forward"], + preparedData["left-original-raw-slow-backward"], + preparedData["left-original-raw-fast-forward"], + preparedData["left-original-raw-fast-backward"]); + m_originalDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kRight)] = + CombineDatasets(preparedData["right-original-raw-slow-forward"], + preparedData["right-original-raw-slow-backward"], + preparedData["right-original-raw-fast-forward"], + preparedData["right-original-raw-fast-backward"]); + + WPI_INFO(m_logger, "{}", "Applying trimming and filtering."); + sysid::InitialTrimAndFilter(&preparedData, &m_settings, m_positionDelays, + m_velocityDelays, m_minStepTime, m_maxStepTime); + + auto slowForward = AnalysisManager::DataConcat( + preparedData["left-slow-forward"], preparedData["right-slow-forward"]); + auto slowBackward = AnalysisManager::DataConcat( + preparedData["left-slow-backward"], preparedData["right-slow-backward"]); + auto fastForward = AnalysisManager::DataConcat( + preparedData["left-fast-forward"], preparedData["right-fast-forward"]); + auto fastBackward = AnalysisManager::DataConcat( + preparedData["left-fast-backward"], preparedData["right-fast-backward"]); + + WPI_INFO(m_logger, "{}", "Acceleration filtering."); + sysid::AccelFilter(&preparedData); + + WPI_INFO(m_logger, "{}", "Storing datasets."); + + // Create the distinct raw datasets and store them + auto rawSlowForward = + AnalysisManager::DataConcat(preparedData["left-raw-slow-forward"], + preparedData["right-raw-slow-forward"]); + auto rawSlowBackward = + AnalysisManager::DataConcat(preparedData["left-raw-slow-backward"], + preparedData["right-raw-slow-backward"]); + auto rawFastForward = + AnalysisManager::DataConcat(preparedData["left-raw-fast-forward"], + preparedData["right-raw-fast-forward"]); + auto rawFastBackward = + AnalysisManager::DataConcat(preparedData["left-raw-fast-backward"], + preparedData["right-raw-fast-backward"]); + + m_rawDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kCombined)] = + CombineDatasets(rawSlowForward, rawSlowBackward, rawFastForward, + rawFastBackward); + m_rawDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kLeft)] = + CombineDatasets(preparedData["left-raw-slow-forward"], + preparedData["left-raw-slow-backward"], + preparedData["left-raw-fast-forward"], + preparedData["left-raw-fast-backward"]); + m_rawDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kRight)] = + CombineDatasets(preparedData["right-raw-slow-forward"], + preparedData["right-raw-slow-backward"], + preparedData["right-raw-fast-forward"], + preparedData["right-raw-fast-backward"]); + + // Create the distinct filtered datasets and store them + m_filteredDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kCombined)] = + CombineDatasets(slowForward, slowBackward, fastForward, fastBackward); + m_filteredDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kLeft)] = + CombineDatasets(preparedData["left-slow-forward"], + preparedData["left-slow-backward"], + preparedData["left-fast-forward"], + preparedData["left-fast-backward"]); + m_filteredDataset[static_cast( + AnalysisManager::Settings::DrivetrainDataset::kRight)] = + CombineDatasets(preparedData["right-slow-forward"], + preparedData["right-slow-backward"], + preparedData["right-fast-forward"], + preparedData["right-fast-backward"]); + + m_startTimes = { + rawSlowForward.front().timestamp, rawSlowBackward.front().timestamp, + rawFastForward.front().timestamp, rawFastBackward.front().timestamp}; +} + +AnalysisManager::AnalysisManager(Settings& settings, wpi::Logger& logger) + : m_logger{logger}, + m_settings{settings}, + m_type{analysis::kSimple}, + m_unit{"Meters"}, + m_factor{1} {} + +AnalysisManager::AnalysisManager(std::string_view path, Settings& settings, + wpi::Logger& logger) + : m_logger{logger}, m_settings{settings} { + { + // Read JSON from the specified path + std::error_code ec; + wpi::raw_fd_istream is{path, ec}; + + if (ec) { + throw FileReadingError(path); + } + + is >> m_json; + + WPI_INFO(m_logger, "Read {}", path); + } + + // Check that we have a sysid JSON + if (m_json.find("sysid") == m_json.end()) { + // If it's not a sysid JSON, try converting it from frc-char format + std::string newPath = sysid::ConvertJSON(path, logger); + + // Read JSON from the specified path + std::error_code ec; + wpi::raw_fd_istream is{newPath, ec}; + + if (ec) { + throw FileReadingError(newPath); + } + + is >> m_json; + + WPI_INFO(m_logger, "Read {}", newPath); + } + + WPI_INFO(m_logger, "Parsing initial data of {}", path); + // Get the analysis type from the JSON. + m_type = sysid::analysis::FromName(m_json.at("test").get()); + + // Get the rotation -> output units factor from the JSON. + m_unit = m_json.at("units").get(); + m_factor = m_json.at("unitsPerRotation").get(); + WPI_DEBUG(m_logger, "Parsing units per rotation as {} {} per rotation", + m_factor, m_unit); + + // Reset settings for Dynamic Test Limits + m_settings.stepTestDuration = units::second_t{0.0}; + m_settings.motionThreshold = std::numeric_limits::infinity(); +} + +void AnalysisManager::PrepareData() { + WPI_INFO(m_logger, "Preparing {} data", m_type.name); + if (m_type == analysis::kDrivetrain) { + PrepareLinearDrivetrainData(); + } else if (m_type == analysis::kDrivetrainAngular) { + PrepareAngularDrivetrainData(); + } else { + PrepareGeneralData(); + } + WPI_INFO(m_logger, "{}", "Finished Preparing Data"); +} + +AnalysisManager::FeedforwardGains AnalysisManager::CalculateFeedforward() { + if (m_filteredDataset.empty()) { + throw sysid::InvalidDataError( + "There is no data to perform gain calculation on."); + } + + WPI_INFO(m_logger, "{}", "Calculating Gains"); + // Calculate feedforward gains from the data. + const auto& ff = sysid::CalculateFeedforwardGains(GetFilteredData(), m_type); + FeedforwardGains ffGains = {ff, m_trackWidth}; + + const auto& Ks = std::get<0>(ff)[0]; + const auto& Kv = std::get<0>(ff)[1]; + const auto& Ka = std::get<0>(ff)[2]; + + if (Ka <= 0 || Kv < 0) { + throw InvalidDataError( + fmt::format("The calculated feedforward gains of kS: {}, Kv: {}, Ka: " + "{} are erroneous. Your Ka should be > 0 while your Kv and " + "Ks constants should both >= 0. Try adjusting the " + "filtering and trimming settings or collect better data.", + Ks, Kv, Ka)); + } + + return ffGains; +} + +sysid::FeedbackGains AnalysisManager::CalculateFeedback( + std::vector ff) { + const auto& Kv = ff[1]; + const auto& Ka = ff[2]; + FeedbackGains fb; + if (m_settings.type == FeedbackControllerLoopType::kPosition) { + fb = sysid::CalculatePositionFeedbackGains( + m_settings.preset, m_settings.lqr, Kv, Ka, + m_settings.convertGainsToEncTicks + ? m_settings.gearing * m_settings.cpr * m_factor + : 1); + } else { + fb = sysid::CalculateVelocityFeedbackGains( + m_settings.preset, m_settings.lqr, Kv, Ka, + m_settings.convertGainsToEncTicks + ? m_settings.gearing * m_settings.cpr * m_factor + : 1); + } + + return fb; +} + +void AnalysisManager::OverrideUnits(std::string_view unit, + double unitsPerRotation) { + m_unit = unit; + m_factor = unitsPerRotation; +} + +void AnalysisManager::ResetUnitsFromJSON() { + m_unit = m_json.at("units").get(); + m_factor = m_json.at("unitsPerRotation").get(); +} diff --git a/sysid/src/main/native/cpp/analysis/AnalysisType.cpp b/sysid/src/main/native/cpp/analysis/AnalysisType.cpp new file mode 100644 index 00000000000..18b461fe6d8 --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/AnalysisType.cpp @@ -0,0 +1,23 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/AnalysisType.h" + +using namespace sysid; + +AnalysisType sysid::analysis::FromName(std::string_view name) { + if (name == "Drivetrain") { + return sysid::analysis::kDrivetrain; + } + if (name == "Drivetrain (Angular)") { + return sysid::analysis::kDrivetrainAngular; + } + if (name == "Elevator") { + return sysid::analysis::kElevator; + } + if (name == "Arm") { + return sysid::analysis::kArm; + } + return sysid::analysis::kSimple; +} diff --git a/sysid/src/main/native/cpp/analysis/ArmSim.cpp b/sysid/src/main/native/cpp/analysis/ArmSim.cpp new file mode 100644 index 00000000000..a72f50569d1 --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/ArmSim.cpp @@ -0,0 +1,64 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/ArmSim.h" + +#include + +#include +#include +#include + +using namespace sysid; + +ArmSim::ArmSim(double Ks, double Kv, double Ka, double Kg, double offset, + double initialPosition, double initialVelocity) + // u = Ks sgn(x) + Kv x + Ka a + Kg cos(theta) + // Ka a = u - Ks sgn(x) - Kv x - Kg cos(theta) + // a = 1/Ka u - Ks/Ka sgn(x) - Kv/Ka x - Kg/Ka cos(theta) + // a = -Kv/Ka x + 1/Ka u - Ks/Ka sgn(x) - Kg/Ka cos(theta) + // a = Ax + Bu + c sgn(x) + d cos(theta) + : m_A{-Kv / Ka}, + m_B{1.0 / Ka}, + m_c{-Ks / Ka}, + m_d{-Kg / Ka}, + m_offset{offset} { + Reset(initialPosition, initialVelocity); +} + +void ArmSim::Update(units::volt_t voltage, units::second_t dt) { + // Returns arm acceleration under gravity + auto f = [=, this]( + const Eigen::Vector& x, + const Eigen::Vector& u) -> Eigen::Vector { + return Eigen::Vector{ + x(1), (m_A * x.block<1, 1>(1, 0) + m_B * u + m_c * wpi::sgn(x(1)) + + m_d * std::cos(x(0) + m_offset))(0)}; + }; + + // Max error is large because an accurate sim isn't as important as the sim + // finishing in a timely manner. Otherwise, the timestep can become absurdly + // small for ill-conditioned data (e.g., high velocities with sharp spikes in + // acceleration). + Eigen::Vector u{voltage.value()}; + m_x = frc::RKDP(f, m_x, u, dt, 0.25); +} + +double ArmSim::GetPosition() const { + return m_x(0); +} + +double ArmSim::GetVelocity() const { + return m_x(1); +} + +double ArmSim::GetAcceleration(units::volt_t voltage) const { + Eigen::Vector u{voltage.value()}; + return (m_A * m_x.block<1, 1>(1, 0) + m_B * u + + m_c * wpi::sgn(GetVelocity()) + m_d * std::cos(m_x(0) + m_offset))(0); +} + +void ArmSim::Reset(double position, double velocity) { + m_x = Eigen::Vector{position, velocity}; +} diff --git a/sysid/src/main/native/cpp/analysis/ElevatorSim.cpp b/sysid/src/main/native/cpp/analysis/ElevatorSim.cpp new file mode 100644 index 00000000000..5cfcabed763 --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/ElevatorSim.cpp @@ -0,0 +1,50 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/ElevatorSim.h" + +#include +#include +#include + +using namespace sysid; + +ElevatorSim::ElevatorSim(double Ks, double Kv, double Ka, double Kg, + double initialPosition, double initialVelocity) + // dx/dt = Ax + Bu + c sgn(x) + d + : m_A{{0.0, 1.0}, {0.0, -Kv / Ka}}, + m_B{0.0, 1.0 / Ka}, + m_c{0.0, -Ks / Ka}, + m_d{0.0, -Kg / Ka} { + Reset(initialPosition, initialVelocity); +} + +void ElevatorSim::Update(units::volt_t voltage, units::second_t dt) { + Eigen::Vector u{voltage.value()}; + + // Given dx/dt = Ax + Bu + c sgn(x) + d, + // x_k+1 = e^(AT) x_k + A^-1 (e^(AT) - 1) (Bu + c sgn(x) + d) + Eigen::Matrix Ad; + Eigen::Matrix Bd; + frc::DiscretizeAB<2, 1>(m_A, m_B, dt, &Ad, &Bd); + m_x = Ad * m_x + Bd * u + + Bd * m_B.householderQr().solve(m_c * wpi::sgn(GetVelocity()) + m_d); +} + +double ElevatorSim::GetPosition() const { + return m_x(0); +} + +double ElevatorSim::GetVelocity() const { + return m_x(1); +} + +double ElevatorSim::GetAcceleration(units::volt_t voltage) const { + Eigen::Vector u{voltage.value()}; + return (m_A * m_x + m_B * u + m_c * wpi::sgn(GetVelocity()) + m_d)(1); +} + +void ElevatorSim::Reset(double position, double velocity) { + m_x = Eigen::Vector{position, velocity}; +} diff --git a/sysid/src/main/native/cpp/analysis/FeedbackAnalysis.cpp b/sysid/src/main/native/cpp/analysis/FeedbackAnalysis.cpp new file mode 100644 index 00000000000..0691aaf6ebb --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/FeedbackAnalysis.cpp @@ -0,0 +1,78 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/FeedbackAnalysis.h" + +#include +#include +#include +#include +#include +#include + +#include "sysid/analysis/FeedbackControllerPreset.h" + +using namespace sysid; + +using Kv_t = decltype(1_V / 1_mps); +using Ka_t = decltype(1_V / 1_mps_sq); + +FeedbackGains sysid::CalculatePositionFeedbackGains( + const FeedbackControllerPreset& preset, const LQRParameters& params, + double Kv, double Ka, double encFactor) { + // If acceleration requires no effort, velocity becomes an input for position + // control. We choose an appropriate model in this case to avoid numerical + // instabilities in the LQR. + if (Ka > 1E-7) { + // Create a position system from our feedforward gains. + auto system = frc::LinearSystemId::IdentifyPositionSystem( + Kv_t(Kv), Ka_t(Ka)); + // Create an LQR with 2 states to control -- position and velocity. + frc::LinearQuadraticRegulator<2, 1> controller{ + system, {params.qp, params.qv}, {params.r}, preset.period}; + // Compensate for any latency from sensor measurements, filtering, etc. + controller.LatencyCompensate(system, preset.period, 0.0_s); + + return {controller.K(0, 0) * preset.outputConversionFactor / encFactor, + controller.K(0, 1) * preset.outputConversionFactor / + (encFactor * (preset.normalized ? 1 : preset.period.value()))}; + } + + // This is our special model to avoid instabilities in the LQR. + auto system = frc::LinearSystem<1, 1, 1>( + Eigen::Matrix{0.0}, Eigen::Matrix{1.0}, + Eigen::Matrix{1.0}, Eigen::Matrix{0.0}); + // Create an LQR with one state -- position. + frc::LinearQuadraticRegulator<1, 1> controller{ + system, {params.qp}, {params.r}, preset.period}; + // Compensate for any latency from sensor measurements, filtering, etc. + controller.LatencyCompensate(system, preset.period, 0.0_s); + + return {Kv * controller.K(0, 0) * preset.outputConversionFactor / encFactor, + 0.0}; +} + +FeedbackGains sysid::CalculateVelocityFeedbackGains( + const FeedbackControllerPreset& preset, const LQRParameters& params, + double Kv, double Ka, double encFactor) { + // If acceleration for velocity control requires no effort, the feedback + // control gains approach zero. We special-case it here because numerical + // instabilities arise in LQR otherwise. + if (Ka < 1E-7) { + return {0.0, 0.0}; + } + + // Create a velocity system from our feedforward gains. + auto system = frc::LinearSystemId::IdentifyVelocitySystem( + Kv_t(Kv), Ka_t(Ka)); + // Create an LQR controller with 1 state -- velocity. + frc::LinearQuadraticRegulator<1, 1> controller{ + system, {params.qv}, {params.r}, preset.period}; + // Compensate for any latency from sensor measurements, filtering, etc. + controller.LatencyCompensate(system, preset.period, preset.measurementDelay); + + return {controller.K(0, 0) * preset.outputConversionFactor / + (preset.outputVelocityTimeFactor * encFactor), + 0.0}; +} diff --git a/sysid/src/main/native/cpp/analysis/FeedforwardAnalysis.cpp b/sysid/src/main/native/cpp/analysis/FeedforwardAnalysis.cpp new file mode 100644 index 00000000000..b7a9fce79b7 --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/FeedforwardAnalysis.cpp @@ -0,0 +1,120 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/FeedforwardAnalysis.h" + +#include + +#include +#include + +#include "sysid/analysis/AnalysisManager.h" +#include "sysid/analysis/FilteringUtils.h" +#include "sysid/analysis/OLS.h" + +using namespace sysid; + +/** + * Populates OLS data for (xₖ₊₁ − xₖ)/τ = αxₖ + βuₖ + γ sgn(xₖ). + * + * @param d List of characterization data. + * @param type Type of system being identified. + * @param X Vector representation of X in y = Xβ. + * @param y Vector representation of y in y = Xβ. + */ +static void PopulateOLSData(const std::vector& d, + const AnalysisType& type, + Eigen::Block X, + Eigen::VectorBlock y) { + for (size_t sample = 0; sample < d.size(); ++sample) { + const auto& pt = d[sample]; + + // Add the velocity term (for α) + X(sample, 0) = pt.velocity; + + // Add the voltage term (for β) + X(sample, 1) = pt.voltage; + + // Add the intercept term (for γ) + X(sample, 2) = std::copysign(1, pt.velocity); + + // Add test-specific variables + if (type == analysis::kElevator) { + // Add the gravity term (for Kg) + X(sample, 3) = 1.0; + } else if (type == analysis::kArm) { + // Add the cosine and sine terms (for Kg) + X(sample, 3) = pt.cos; + X(sample, 4) = pt.sin; + } + + // Add the dependent variable (acceleration) + y(sample) = pt.acceleration; + } +} + +std::tuple, double, double> +sysid::CalculateFeedforwardGains(const Storage& data, + const AnalysisType& type) { + // Iterate through the data and add it to our raw vector. + const auto& [slowForward, slowBackward, fastForward, fastBackward] = data; + + const auto size = slowForward.size() + slowBackward.size() + + fastForward.size() + fastBackward.size(); + + // Create a raw vector of doubles with our data in it. + Eigen::MatrixXd X{size, type.independentVariables}; + Eigen::VectorXd y{size}; + + int rowOffset = 0; + PopulateOLSData(slowForward, type, + X.block(rowOffset, 0, slowForward.size(), X.cols()), + y.segment(rowOffset, slowForward.size())); + + rowOffset += slowForward.size(); + PopulateOLSData(slowBackward, type, + X.block(rowOffset, 0, slowBackward.size(), X.cols()), + y.segment(rowOffset, slowBackward.size())); + + rowOffset += slowBackward.size(); + PopulateOLSData(fastForward, type, + X.block(rowOffset, 0, fastForward.size(), X.cols()), + y.segment(rowOffset, fastForward.size())); + + rowOffset += fastForward.size(); + PopulateOLSData(fastBackward, type, + X.block(rowOffset, 0, fastBackward.size(), X.cols()), + y.segment(rowOffset, fastBackward.size())); + + // Perform OLS with accel = alpha*vel + beta*voltage + gamma*signum(vel) + // OLS performs best with the noisiest variable as the dependent var, + // so we regress accel in terms of the other variables. + auto ols = sysid::OLS(X, y); + double alpha = std::get<0>(ols)[0]; // -Kv/Ka + double beta = std::get<0>(ols)[1]; // 1/Ka + double gamma = std::get<0>(ols)[2]; // -Ks/Ka + + // Initialize gains list with Ks, Kv, and Ka + std::vector gains{-gamma / beta, -alpha / beta, 1 / beta}; + + if (type == analysis::kElevator) { + // Add Kg to gains list + double delta = std::get<0>(ols)[3]; // -Kg/Ka + gains.emplace_back(-delta / beta); + } + + if (type == analysis::kArm) { + double delta = std::get<0>(ols)[3]; // -Kg/Ka cos(offset) + double epsilon = std::get<0>(ols)[4]; // Kg/Ka sin(offset) + + // Add Kg to gains list + gains.emplace_back(std::hypot(delta, epsilon) / beta); + + // Add offset to gains list + gains.emplace_back(std::atan2(epsilon, -delta)); + } + + // Gains are Ks, Kv, Ka, Kg (elevator/arm only), offset (arm only) + return std::tuple{gains, std::get<1>(ols), std::get<2>(ols)}; +} diff --git a/sysid/src/main/native/cpp/analysis/FilteringUtils.cpp b/sysid/src/main/native/cpp/analysis/FilteringUtils.cpp new file mode 100644 index 00000000000..6c66ef8b424 --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/FilteringUtils.cpp @@ -0,0 +1,417 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/FilteringUtils.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +using namespace sysid; + +/** + * Helper function that throws if it detects that the data vector is too small + * for an operation of a certain window size. + * + * @param data The data that is being used. + * @param window The window size for the operation. + * @param operation The operation we're checking the size for (for error + * throwing purposes). + */ +static void CheckSize(const std::vector& data, size_t window, + std::string_view operation) { + if (data.size() < window) { + throw sysid::InvalidDataError( + fmt::format("Not enough data to run {} which has a window size of {}.", + operation, window)); + } +} + +/** + * Helper function that determines if a certain key is storing raw data. + * + * @param key The key of the dataset + * + * @return True, if the key corresponds to a raw dataset. + */ +static bool IsRaw(std::string_view key) { + return wpi::contains(key, "raw") && !wpi::contains(key, "original"); +} + +/** + * Helper function that determines if a certain key is storing filtered data. + * + * @param key The key of the dataset + * + * @return True, if the key corresponds to a filtered dataset. + */ +static bool IsFiltered(std::string_view key) { + return !wpi::contains(key, "raw") && !wpi::contains(key, "original"); +} + +/** + * Fills in the rest of the PreparedData Structs for a PreparedData Vector. + * + * @param data A reference to a vector of the raw data. + * @param unit The units that the data is in (rotations, radians, or degrees) + * for arm mechanisms. + */ +static void PrepareMechData(std::vector* data, + std::string_view unit = "") { + constexpr size_t kWindow = 3; + + CheckSize(*data, kWindow, "Acceleration Calculation"); + + // Calculates the cosine of the position data for single jointed arm analysis + for (size_t i = 0; i < data->size(); ++i) { + auto& pt = data->at(i); + + double cos = 0.0; + double sin = 0.0; + if (unit == "Radians") { + cos = std::cos(pt.position); + sin = std::sin(pt.position); + } else if (unit == "Degrees") { + cos = std::cos(pt.position * std::numbers::pi / 180.0); + sin = std::sin(pt.position * std::numbers::pi / 180.0); + } else if (unit == "Rotations") { + cos = std::cos(pt.position * 2 * std::numbers::pi); + sin = std::sin(pt.position * 2 * std::numbers::pi); + } + pt.cos = cos; + pt.sin = sin; + } + + auto derivative = + CentralFiniteDifference<1, kWindow>(GetMeanTimeDelta(*data)); + + // Load the derivative filter with the first value for accurate initial + // behavior + for (size_t i = 0; i < kWindow; ++i) { + derivative.Calculate(data->at(0).velocity); + } + + for (size_t i = (kWindow - 1) / 2; i < data->size(); ++i) { + data->at(i - (kWindow - 1) / 2).acceleration = + derivative.Calculate(data->at(i).velocity); + } + + // Fill in accelerations past end of derivative filter + for (size_t i = data->size() - (kWindow - 1) / 2; i < data->size(); ++i) { + data->at(i).acceleration = 0.0; + } +} + +std::tuple +sysid::TrimStepVoltageData(std::vector* data, + AnalysisManager::Settings* settings, + units::second_t minStepTime, + units::second_t maxStepTime) { + auto voltageBegins = + std::find_if(data->begin(), data->end(), + [](auto& datum) { return std::abs(datum.voltage) > 0; }); + + units::second_t firstTimestamp = voltageBegins->timestamp; + double firstPosition = voltageBegins->position; + + auto motionBegins = std::find_if( + data->begin(), data->end(), [settings, firstPosition](auto& datum) { + return std::abs(datum.position - firstPosition) > + (settings->motionThreshold * datum.dt.value()); + }); + + units::second_t positionDelay; + if (motionBegins != data->end()) { + positionDelay = motionBegins->timestamp - firstTimestamp; + } else { + positionDelay = 0_s; + } + + auto maxAccel = std::max_element( + data->begin(), data->end(), [](const auto& a, const auto& b) { + return std::abs(a.acceleration) < std::abs(b.acceleration); + }); + + units::second_t velocityDelay; + if (maxAccel != data->end()) { + velocityDelay = maxAccel->timestamp - firstTimestamp; + + // Trim data before max acceleration + data->erase(data->begin(), maxAccel); + } else { + velocityDelay = 0_s; + } + + minStepTime = std::min(data->at(0).timestamp - firstTimestamp, minStepTime); + + // If step duration hasn't been set yet, calculate a default (find the entry + // before the acceleration first hits zero) + if (settings->stepTestDuration <= minStepTime) { + // Get noise floor + const double accelNoiseFloor = GetNoiseFloor( + *data, kNoiseMeanWindow, [](auto&& pt) { return pt.acceleration; }); + // Find latest element with nonzero acceleration + auto endIt = std::find_if( + data->rbegin(), data->rend(), [&](const PreparedData& entry) { + return std::abs(entry.acceleration) > accelNoiseFloor; + }); + + if (endIt != data->rend()) { + // Calculate default duration + settings->stepTestDuration = std::min( + endIt->timestamp - data->front().timestamp + minStepTime + 1_s, + maxStepTime); + } else { + settings->stepTestDuration = maxStepTime; + } + } + + // Find first entry greater than the step test duration + auto maxIt = + std::find_if(data->begin(), data->end(), [&](PreparedData entry) { + return entry.timestamp - data->front().timestamp + minStepTime > + settings->stepTestDuration; + }); + + // Trim data beyond desired step test duration + if (maxIt != data->end()) { + data->erase(maxIt, data->end()); + } + return std::make_tuple(minStepTime, positionDelay, velocityDelay); +} + +double sysid::GetNoiseFloor( + const std::vector& data, int window, + std::function accessorFunction) { + double sum = 0.0; + size_t step = window / 2; + auto averageFilter = frc::LinearFilter::MovingAverage(window); + for (size_t i = 0; i < data.size(); i++) { + double mean = averageFilter.Calculate(accessorFunction(data[i])); + if (i >= step) { + sum += std::pow(accessorFunction(data[i - step]) - mean, 2); + } + } + return std::sqrt(sum / (data.size() - step)); +} + +units::second_t sysid::GetMeanTimeDelta(const std::vector& data) { + std::vector dts; + + for (const auto& pt : data) { + if (pt.dt > 0_s && pt.dt < 500_ms) { + dts.emplace_back(pt.dt); + } + } + + return std::accumulate(dts.begin(), dts.end(), 0_s) / dts.size(); +} + +units::second_t sysid::GetMeanTimeDelta(const Storage& data) { + std::vector dts; + + for (const auto& pt : data.slowForward) { + if (pt.dt > 0_s && pt.dt < 500_ms) { + dts.emplace_back(pt.dt); + } + } + + for (const auto& pt : data.slowBackward) { + if (pt.dt > 0_s && pt.dt < 500_ms) { + dts.emplace_back(pt.dt); + } + } + + for (const auto& pt : data.fastForward) { + if (pt.dt > 0_s && pt.dt < 500_ms) { + dts.emplace_back(pt.dt); + } + } + + for (const auto& pt : data.fastBackward) { + if (pt.dt > 0_s && pt.dt < 500_ms) { + dts.emplace_back(pt.dt); + } + } + + return std::accumulate(dts.begin(), dts.end(), 0_s) / dts.size(); +} + +void sysid::ApplyMedianFilter(std::vector* data, int window) { + CheckSize(*data, window, "Median Filter"); + + frc::MedianFilter medianFilter(window); + + // Load the median filter with the first value for accurate initial behavior + for (int i = 0; i < window; i++) { + medianFilter.Calculate(data->at(0).velocity); + } + + for (size_t i = (window - 1) / 2; i < data->size(); i++) { + data->at(i - (window - 1) / 2).velocity = + medianFilter.Calculate(data->at(i).velocity); + } + + // Run the median filter for the last half window of datapoints by loading the + // median filter with the last recorded velocity value + for (size_t i = data->size() - (window - 1) / 2; i < data->size(); i++) { + data->at(i).velocity = + medianFilter.Calculate(data->at(data->size() - 1).velocity); + } +} + +/** + * Removes a substring from a string reference + * + * @param str The std::string_view that needs modification + * @param removeStr The substring that needs to be removed + * + * @return an std::string without the specified substring + */ +static std::string RemoveStr(std::string_view str, std::string_view removeStr) { + size_t idx = str.find(removeStr); + if (idx == std::string_view::npos) { + return std::string{str}; + } else { + return fmt::format("{}{}", str.substr(0, idx), + str.substr(idx + removeStr.size())); + } +} + +/** + * Figures out the max duration of the Dynamic tests + * + * @param data The raw data String Map + * + * @return The maximum duration of the Dynamic Tests + */ +static units::second_t GetMaxStepTime( + wpi::StringMap>& data) { + auto maxStepTime = 0_s; + for (auto& it : data) { + auto key = it.first(); + auto& dataset = it.getValue(); + + if (IsRaw(key) && wpi::contains(key, "fast")) { + auto duration = dataset.back().timestamp - dataset.front().timestamp; + if (duration > maxStepTime) { + maxStepTime = duration; + } + } + } + return maxStepTime; +} + +void sysid::InitialTrimAndFilter( + wpi::StringMap>* data, + AnalysisManager::Settings* settings, + std::vector& positionDelays, + std::vector& velocityDelays, units::second_t& minStepTime, + units::second_t& maxStepTime, std::string_view unit) { + auto& preparedData = *data; + + // Find the maximum Step Test Duration of the dynamic tests + maxStepTime = GetMaxStepTime(preparedData); + + // Calculate Velocity Threshold if it hasn't been set yet + if (settings->motionThreshold == std::numeric_limits::infinity()) { + for (auto& it : preparedData) { + auto key = it.first(); + auto& dataset = it.getValue(); + if (wpi::contains(key, "slow")) { + settings->motionThreshold = + std::min(settings->motionThreshold, + GetNoiseFloor(dataset, kNoiseMeanWindow, + [](auto&& pt) { return pt.velocity; })); + } + } + } + + for (auto& it : preparedData) { + auto key = it.first(); + auto& dataset = it.getValue(); + + // Trim quasistatic test data to remove all points where voltage is zero or + // velocity < motion threshold. + if (wpi::contains(key, "slow")) { + dataset.erase(std::remove_if(dataset.begin(), dataset.end(), + [&](const auto& pt) { + return std::abs(pt.voltage) <= 0 || + std::abs(pt.velocity) < + settings->motionThreshold; + }), + dataset.end()); + + // Confirm there's still data + if (dataset.empty()) { + throw sysid::NoQuasistaticDataError(); + } + } + + // Apply Median filter + if (IsFiltered(key) && settings->medianWindow > 1) { + ApplyMedianFilter(&dataset, settings->medianWindow); + } + + // Recalculate Accel and Cosine + PrepareMechData(&dataset, unit); + + // Trims filtered Dynamic Test Data + if (IsFiltered(key) && wpi::contains(key, "fast")) { + // Get the filtered dataset name + auto filteredKey = RemoveStr(key, "raw-"); + + // Trim Filtered Data + auto [tempMinStepTime, positionDelay, velocityDelay] = + TrimStepVoltageData(&preparedData[filteredKey], settings, minStepTime, + maxStepTime); + + positionDelays.emplace_back(positionDelay); + velocityDelays.emplace_back(velocityDelay); + + // Set the Raw Data to start at the same time as the Filtered Data + auto startTime = preparedData[filteredKey].front().timestamp; + auto rawStart = + std::find_if(preparedData[key].begin(), preparedData[key].end(), + [&](auto&& pt) { return pt.timestamp == startTime; }); + preparedData[key].erase(preparedData[key].begin(), rawStart); + + // Confirm there's still data + if (preparedData[key].empty()) { + throw sysid::NoDynamicDataError(); + } + } + } +} + +void sysid::AccelFilter(wpi::StringMap>* data) { + auto& preparedData = *data; + + // Remove points with acceleration = 0 + for (auto& it : preparedData) { + auto& dataset = it.getValue(); + + for (size_t i = 0; i < dataset.size(); i++) { + if (dataset.at(i).acceleration == 0.0) { + dataset.erase(dataset.begin() + i); + i--; + } + } + } + + // Confirm there's still data + if (std::any_of(preparedData.begin(), preparedData.end(), + [](const auto& it) { return it.getValue().empty(); })) { + throw sysid::InvalidDataError( + "Acceleration filtering has removed all data."); + } +} diff --git a/sysid/src/main/native/cpp/analysis/JSONConverter.cpp b/sysid/src/main/native/cpp/analysis/JSONConverter.cpp new file mode 100644 index 00000000000..54390349ddb --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/JSONConverter.cpp @@ -0,0 +1,165 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/JSONConverter.h" + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "sysid/Util.h" +#include "sysid/analysis/AnalysisManager.h" +#include "sysid/analysis/AnalysisType.h" + +// Sizes of the arrays for new sysid data. +static constexpr size_t kDrivetrainSize = 9; +static constexpr size_t kGeneralSize = 4; + +// Indices for the old data. +static constexpr size_t kTimestampCol = 0; +static constexpr size_t kLVoltsCol = 3; +static constexpr size_t kRVoltsCol = 4; +static constexpr size_t kLPosCol = 5; +static constexpr size_t kRPosCol = 6; +static constexpr size_t kLVelCol = 7; +static constexpr size_t kRVelCol = 8; + +static wpi::json GetJSON(std::string_view path, wpi::Logger& logger) { + std::error_code ec; + wpi::raw_fd_istream input{path, ec}; + + if (ec) { + throw std::runtime_error(fmt::format("Unable to read: {}", path)); + } + + wpi::json json; + input >> json; + WPI_INFO(logger, "Read frc-characterization JSON from {}", path); + return json; +} + +std::string sysid::ConvertJSON(std::string_view path, wpi::Logger& logger) { + wpi::json ojson = GetJSON(path, logger); + + auto type = sysid::analysis::FromName(ojson.at("test").get()); + auto factor = ojson.at("unitsPerRotation").get(); + auto unit = ojson.at("units").get(); + + wpi::json json; + for (auto&& key : AnalysisManager::kJsonDataKeys) { + if (type == analysis::kDrivetrain) { + // Get the old data; create a vector for the new data; reserve the + // appropriate size for the new data. + auto odata = ojson.at(key).get>>(); + std::vector> data; + data.reserve(odata.size()); + + // Transfer the data. + for (auto&& pt : odata) { + data.push_back(std::array{ + pt[kTimestampCol], pt[kLVoltsCol], pt[kRVoltsCol], pt[kLPosCol], + pt[kRPosCol], pt[kLVelCol], pt[kRVelCol], 0.0, 0.0}); + } + json[key] = data; + } else { + // Get the old data; create a vector for the new data; reserve the + // appropriate size for the new data. + auto odata = ojson.at(key).get>>(); + std::vector> data; + data.reserve(odata.size()); + + // Transfer the data. + for (auto&& pt : odata) { + data.push_back(std::array{ + pt[kTimestampCol], pt[kLVoltsCol], pt[kLPosCol], pt[kLVelCol]}); + } + json[key] = data; + } + } + json["units"] = unit; + json["unitsPerRotation"] = factor; + json["test"] = type.name; + json["sysid"] = true; + + // Write the new file with "_new" appended to it. + path.remove_suffix(std::string_view{".json"}.size()); + std::string loc = fmt::format("{}_new.json", path); + + sysid::SaveFile(json.dump(2), std::filesystem::path{loc}); + + WPI_INFO(logger, "Wrote new JSON to: {}", loc); + return loc; +} + +std::string sysid::ToCSV(std::string_view path, wpi::Logger& logger) { + wpi::json json = GetJSON(path, logger); + + auto type = sysid::analysis::FromName(json.at("test").get()); + auto factor = json.at("unitsPerRotation").get(); + auto unit = json.at("units").get(); + std::string_view abbreviation = GetAbbreviation(unit); + + std::error_code ec; + // Naming: {sysid-json-name}(Test, Units).csv + path.remove_suffix(std::string_view{".json"}.size()); + std::string loc = fmt::format("{} ({}, {}).csv", path, type.name, unit); + wpi::raw_fd_ostream outputFile{loc, ec}; + + if (ec) { + throw std::runtime_error("Unable to write to: " + loc); + } + + fmt::print(outputFile, "Timestamp (s),Test,"); + if (type == analysis::kDrivetrain || type == analysis::kDrivetrainAngular) { + fmt::print( + outputFile, + "Left Volts (V),Right Volts (V),Left Position ({0}),Right " + "Position ({0}),Left Velocity ({0}/s),Right Velocity ({0}/s),Gyro " + "Position (deg),Gyro Rate (deg/s)\n", + abbreviation); + } else { + fmt::print(outputFile, "Volts (V),Position({0}),Velocity ({0}/s)\n", + abbreviation); + } + outputFile << "\n"; + + for (auto&& key : AnalysisManager::kJsonDataKeys) { + if (type == analysis::kDrivetrain || type == analysis::kDrivetrainAngular) { + auto tempData = + json.at(key).get>>(); + for (auto&& pt : tempData) { + fmt::print(outputFile, "{},{},{},{},{},{},{},{},{},{}\n", + pt[0], // Timestamp + key, // Test + pt[1], pt[2], // Left and Right Voltages + pt[3] * factor, pt[4] * factor, // Left and Right Positions + pt[5] * factor, pt[6] * factor, // Left and Right Velocity + pt[7], pt[8] // Gyro Position and Velocity + ); + } + } else { + auto tempData = + json.at(key).get>>(); + for (auto&& pt : tempData) { + fmt::print(outputFile, "{},{},{},{},{}\n", + pt[0], // Timestamp, + key, // Test + pt[1], // Voltage + pt[2] * factor, // Position + pt[3] * factor // Velocity + ); + } + } + } + outputFile.flush(); + WPI_INFO(logger, "Wrote CSV to: {}", loc); + return loc; +} diff --git a/sysid/src/main/native/cpp/analysis/OLS.cpp b/sysid/src/main/native/cpp/analysis/OLS.cpp new file mode 100644 index 00000000000..d095a485d50 --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/OLS.cpp @@ -0,0 +1,48 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/OLS.h" + +#include +#include + +#include +#include + +using namespace sysid; + +std::tuple, double, double> sysid::OLS( + const Eigen::MatrixXd& X, const Eigen::VectorXd& y) { + assert(X.rows() == y.rows()); + + // The linear model can be written as follows: + // y = Xβ + u, where y is the dependent observed variable, X is the matrix + // of independent variables, β is a vector of coefficients, and u is a + // vector of residuals. + + // We want to minimize u² = uᵀu = (y - Xβ)ᵀ(y - Xβ). + // β = (XᵀX)⁻¹Xᵀy + + // Calculate β that minimizes uᵀu. + Eigen::MatrixXd beta = (X.transpose() * X).llt().solve(X.transpose() * y); + + // We will now calculate R² or the coefficient of determination, which + // tells us how much of the total variation (variation in y) can be + // explained by the regression model. + + // We will first calculate the sum of the squares of the error, or the + // variation in error (SSE). + double SSE = (y - X * beta).squaredNorm(); + + int n = X.cols(); + + // Now we will calculate the total variation in y, known as SSTO. + double SSTO = ((y.transpose() * y) - (1.0 / n) * (y.transpose() * y)).value(); + + double rSquared = (SSTO - SSE) / SSTO; + double adjRSquared = 1.0 - (1.0 - rSquared) * ((n - 1.0) / (n - 3.0)); + double RMSE = std::sqrt(SSE / n); + + return {{beta.data(), beta.data() + beta.rows()}, adjRSquared, RMSE}; +} diff --git a/sysid/src/main/native/cpp/analysis/SimpleMotorSim.cpp b/sysid/src/main/native/cpp/analysis/SimpleMotorSim.cpp new file mode 100644 index 00000000000..58a8b309d0b --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/SimpleMotorSim.cpp @@ -0,0 +1,47 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/SimpleMotorSim.h" + +#include +#include +#include + +using namespace sysid; + +SimpleMotorSim::SimpleMotorSim(double Ks, double Kv, double Ka, + double initialPosition, double initialVelocity) + // dx/dt = Ax + Bu + c sgn(x) + : m_A{{0.0, 1.0}, {0.0, -Kv / Ka}}, m_B{0.0, 1.0 / Ka}, m_c{0.0, -Ks / Ka} { + Reset(initialPosition, initialVelocity); +} + +void SimpleMotorSim::Update(units::volt_t voltage, units::second_t dt) { + Eigen::Vector u{voltage.value()}; + + // Given dx/dt = Ax + Bu + c sgn(x), + // x_k+1 = e^(AT) x_k + A^-1 (e^(AT) - 1) (Bu + c sgn(x)) + Eigen::Matrix Ad; + Eigen::Matrix Bd; + frc::DiscretizeAB<2, 1>(m_A, m_B, dt, &Ad, &Bd); + m_x = Ad * m_x + Bd * u + + Bd * m_B.householderQr().solve(m_c * wpi::sgn(GetVelocity())); +} + +double SimpleMotorSim::GetPosition() const { + return m_x(0); +} + +double SimpleMotorSim::GetVelocity() const { + return m_x(1); +} + +double SimpleMotorSim::GetAcceleration(units::volt_t voltage) const { + Eigen::Vector u{voltage.value()}; + return (m_A * m_x + m_B * u + m_c * wpi::sgn(GetVelocity()))(1); +} + +void SimpleMotorSim::Reset(double position, double velocity) { + m_x = Eigen::Vector{position, velocity}; +} diff --git a/sysid/src/main/native/cpp/analysis/TrackWidthAnalysis.cpp b/sysid/src/main/native/cpp/analysis/TrackWidthAnalysis.cpp new file mode 100644 index 00000000000..eebfe8c6762 --- /dev/null +++ b/sysid/src/main/native/cpp/analysis/TrackWidthAnalysis.cpp @@ -0,0 +1,12 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/TrackWidthAnalysis.h" + +#include + +double sysid::CalculateTrackWidth(double l, double r, units::radian_t accum) { + // The below comes from solving ω = (vr − vl) / 2r for 2r. + return (std::abs(r) + std::abs(l)) / std::abs(accum.value()); +} diff --git a/sysid/src/main/native/cpp/telemetry/TelemetryManager.cpp b/sysid/src/main/native/cpp/telemetry/TelemetryManager.cpp new file mode 100644 index 00000000000..ac97cdbca4d --- /dev/null +++ b/sysid/src/main/native/cpp/telemetry/TelemetryManager.cpp @@ -0,0 +1,275 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/telemetry/TelemetryManager.h" + +#include +#include // for ::tolower +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "sysid/Util.h" +#include "sysid/analysis/AnalysisType.h" + +using namespace sysid; + +TelemetryManager::TelemetryManager(const Settings& settings, + wpi::Logger& logger, + nt::NetworkTableInstance instance) + : m_settings(settings), m_logger(logger), m_inst(instance) {} + +void TelemetryManager::BeginTest(std::string_view name) { + // Create a new test params instance for this test. + m_params = + TestParameters{name.starts_with("fast"), name.ends_with("forward"), + m_settings.mechanism == analysis::kDrivetrainAngular, + State::WaitingForEnable}; + + // Add this test to the list of running tests and set the running flag. + m_tests.push_back(std::string{name}); + m_isRunningTest = true; + + // Set the Voltage Command Entry + m_voltageCommand.Set((m_params.fast ? m_settings.stepVoltage + : m_settings.quasistaticRampRate) * + (m_params.forward ? 1 : -1)); + + // Set the test type + m_testType.Set(m_params.fast ? "Dynamic" : "Quasistatic"); + + // Set the rotate entry + m_rotate.Set(m_params.rotate); + + // Set the current mechanism in NT. + m_mechanism.Set(m_settings.mechanism.name); + // Set Overflow to False + m_overflowPub.Set(false); + // Set Mechanism Error to False + m_mechErrorPub.Set(false); + m_inst.Flush(); + + // Display the warning message. + for (auto&& func : m_callbacks) { + func( + "Please enable the robot in autonomous mode, and then " + "disable it " + "before it runs out of space. \n Note: The robot will " + "continue " + "to move until you disable it - It is your " + "responsibility to " + "ensure it does not hit anything!"); + } + + WPI_INFO(m_logger, "Started {} test.", m_tests.back()); +} + +void TelemetryManager::EndTest() { + // If there is no test running, this is a no-op + if (!m_isRunningTest) { + return; + } + + // Disable the running flag and store the data in the JSON. + m_isRunningTest = false; + m_data[m_tests.back()] = m_params.data; + + // Call the cancellation callbacks. + for (auto&& func : m_callbacks) { + std::string msg; + if (m_params.mechError) { + msg += + "\nERROR: The robot indicated that you are using the wrong project " + "for characterizing your mechanism. \nThis most likely means you " + "are trying to characterize a mechanism like a Drivetrain with a " + "deployed config for a General Mechanism (e.g. Arm, Flywheel, and " + "Elevator) or vice versa. Please double check your settings and " + "try again."; + } else if (!m_params.data.empty()) { + std::string units = m_settings.units; + std::transform(m_settings.units.begin(), m_settings.units.end(), + units.begin(), ::tolower); + + if (std::string_view{m_settings.mechanism.name}.starts_with( + "Drivetrain")) { + double p = (m_params.data.back()[3] - m_params.data.front()[3]) * + m_settings.unitsPerRotation; + double s = (m_params.data.back()[4] - m_params.data.front()[4]) * + m_settings.unitsPerRotation; + double g = m_params.data.back()[7] - m_params.data.front()[7]; + + msg = fmt::format( + "The left and right encoders traveled {} {} and {} {} " + "respectively.\nThe gyro angle delta was {} degrees.", + p, units, s, units, g * 180.0 / std::numbers::pi); + } else { + double p = (m_params.data.back()[2] - m_params.data.front()[2]) * + m_settings.unitsPerRotation; + msg = fmt::format("The encoder reported traveling {} {}.", p, units); + } + + if (m_params.overflow) { + msg += + "\nNOTE: the robot stopped recording data early because the entry " + "storage was exceeded."; + } + } else { + msg = "No data was detected."; + } + func(msg); + } + + // Remove previously run test from list of tests if no data was detected. + if (m_params.data.empty()) { + m_tests.pop_back(); + } + + // Send a zero command over NT. + m_voltageCommand.Set(0.0); + m_inst.Flush(); +} + +void TelemetryManager::Update() { + // If there is no test running, these is nothing to update. + if (!m_isRunningTest) { + return; + } + + // Update the NT entries that we're reading. + + int currAckNumber = m_ackNumberSub.Get(); + std::string telemetryValue; + + // Get the FMS Control Word. + for (auto tsValue : m_fmsControlData.ReadQueue()) { + uint32_t ctrl = tsValue.value; + m_params.enabled = ctrl & 0x01; + } + + // Get the string in the data field. + for (auto tsValue : m_telemetry.ReadQueue()) { + telemetryValue = tsValue.value; + } + + // Get the overflow flag + for (auto tsValue : m_overflowSub.ReadQueue()) { + m_params.overflow = tsValue.value; + } + + // Get the mechanism error flag + for (auto tsValue : m_mechErrorSub.ReadQueue()) { + m_params.mechError = tsValue.value; + } + + // Go through our state machine. + if (m_params.state == State::WaitingForEnable) { + if (m_params.enabled) { + m_params.enableStart = wpi::Now() * 1E-6; + m_params.state = State::RunningTest; + m_ackNumber = currAckNumber; + WPI_INFO(m_logger, "{}", "Transitioned to running test state."); + } + } + + if (m_params.state == State::RunningTest) { + // If for some reason we've disconnected, end the test. + if (!m_inst.IsConnected()) { + WPI_WARNING(m_logger, "{}", + "NT connection was dropped when executing the test. The test " + "has been canceled."); + EndTest(); + } + + // If the robot has disabled, then we can move on to the next step. + if (!m_params.enabled) { + m_params.disableStart = wpi::Now() * 1E-6; + m_params.state = State::WaitingForData; + WPI_INFO(m_logger, "{}", "Transitioned to waiting for data."); + } + } + + if (m_params.state == State::WaitingForData) { + double now = wpi::Now() * 1E-6; + m_voltageCommand.Set(0.0); + m_inst.Flush(); + + // Process valid data + if (!telemetryValue.empty() && m_ackNumber < currAckNumber) { + m_params.raw = std::move(telemetryValue); + m_ackNumber = currAckNumber; + } + + // We have the data that we need, so we can parse it and end the test. + if (!m_params.raw.empty() && + wpi::starts_with(m_params.raw, m_tests.back())) { + // Remove test type from start of string + m_params.raw.erase(0, m_params.raw.find(';') + 1); + + // Clean up the string -- remove spaces if there are any. + m_params.raw.erase( + std::remove_if(m_params.raw.begin(), m_params.raw.end(), ::isspace), + m_params.raw.end()); + + // Split the string into individual components. + wpi::SmallVector res; + wpi::split(m_params.raw, res, ','); + + // Convert each string to double. + std::vector values; + values.reserve(res.size()); + for (auto&& str : res) { + values.push_back(wpi::parse_float(str).value()); + } + + // Add the values to our result vector. + for (size_t i = 0; i < values.size() - m_settings.mechanism.rawDataSize; + i += m_settings.mechanism.rawDataSize) { + std::vector d(m_settings.mechanism.rawDataSize); + + std::copy_n(std::make_move_iterator(values.begin() + i), + m_settings.mechanism.rawDataSize, d.begin()); + m_params.data.push_back(std::move(d)); + } + + WPI_INFO(m_logger, + "Received data with size: {} for the {} test in {} seconds.", + m_params.data.size(), m_tests.back(), + m_params.data.back()[0] - m_params.data.front()[0]); + m_ackNumberPub.Set(++m_ackNumber); + EndTest(); + } + + // If we timed out, end the test and let the user know. + if (now - m_params.disableStart > 5.0) { + WPI_WARNING(m_logger, "{}", + "TelemetryManager did not receieve data 5 seconds after " + "completing the test..."); + EndTest(); + } + } +} + +std::string TelemetryManager::SaveJSON(std::string_view location) { + m_data["test"] = m_settings.mechanism.name; + m_data["units"] = m_settings.units; + m_data["unitsPerRotation"] = m_settings.unitsPerRotation; + m_data["sysid"] = true; + + std::string loc = fmt::format("{}/sysid_data{:%Y%m%d-%H%M%S}.json", location, + std::chrono::system_clock::now()); + + sysid::SaveFile(m_data.dump(2), std::filesystem::path{loc}); + WPI_INFO(m_logger, "Wrote JSON to: {}", loc); + + return loc; +} diff --git a/sysid/src/main/native/cpp/view/Analyzer.cpp b/sysid/src/main/native/cpp/view/Analyzer.cpp new file mode 100644 index 00000000000..32709188ca6 --- /dev/null +++ b/sysid/src/main/native/cpp/view/Analyzer.cpp @@ -0,0 +1,851 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/view/Analyzer.h" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "sysid/Util.h" +#include "sysid/analysis/AnalysisManager.h" +#include "sysid/analysis/AnalysisType.h" +#include "sysid/analysis/FeedbackControllerPreset.h" +#include "sysid/analysis/FilteringUtils.h" +#include "sysid/view/UILayout.h" + +using namespace sysid; + +Analyzer::Analyzer(glass::Storage& storage, wpi::Logger& logger) + : m_location(""), m_logger(logger) { + // Fill the StringMap with preset values. + m_presets["Default"] = presets::kDefault; + m_presets["WPILib (2020-)"] = presets::kWPILibNew; + m_presets["WPILib (Pre-2020)"] = presets::kWPILibOld; + m_presets["CANCoder"] = presets::kCTRECANCoder; + m_presets["CTRE"] = presets::kCTREDefault; + m_presets["CTRE (Pro)"] = presets::kCTREProDefault; + m_presets["REV Brushless Encoder Port"] = presets::kREVNEOBuiltIn; + m_presets["REV Brushed Encoder Port"] = presets::kREVNonNEO; + m_presets["REV Data Port"] = presets::kREVNonNEO; + m_presets["Venom"] = presets::kVenom; + + ResetData(); + UpdateFeedbackGains(); +} + +void Analyzer::UpdateFeedforwardGains() { + WPI_INFO(m_logger, "{}", "Gain calc"); + try { + const auto& [ff, trackWidth] = m_manager->CalculateFeedforward(); + m_ff = std::get<0>(ff); + m_accelRSquared = std::get<1>(ff); + m_accelRMSE = std::get<2>(ff); + m_trackWidth = trackWidth; + m_settings.preset.measurementDelay = + m_settings.type == FeedbackControllerLoopType::kPosition + ? m_manager->GetPositionDelay() + : m_manager->GetVelocityDelay(); + m_conversionFactor = m_manager->GetFactor(); + PrepareGraphs(); + } catch (const sysid::InvalidDataError& e) { + m_state = AnalyzerState::kGeneralDataError; + HandleError(e.what()); + } catch (const sysid::NoQuasistaticDataError& e) { + m_state = AnalyzerState::kMotionThresholdError; + HandleError(e.what()); + } catch (const sysid::NoDynamicDataError& e) { + m_state = AnalyzerState::kTestDurationError; + HandleError(e.what()); + } catch (const AnalysisManager::FileReadingError& e) { + m_state = AnalyzerState::kFileError; + HandleError(e.what()); + } catch (const wpi::json::exception& e) { + m_state = AnalyzerState::kFileError; + HandleError(e.what()); + } catch (const std::exception& e) { + m_state = AnalyzerState::kFileError; + HandleError(e.what()); + } +} + +void Analyzer::UpdateFeedbackGains() { + if (m_ff[1] > 0 && m_ff[2] > 0) { + const auto& fb = m_manager->CalculateFeedback(m_ff); + m_timescale = units::second_t{m_ff[2] / m_ff[1]}; + m_Kp = fb.Kp; + m_Kd = fb.Kd; + } +} + +bool Analyzer::DisplayGain(const char* text, double* data, + bool readOnly = true) { + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 5); + if (readOnly) { + return ImGui::InputDouble(text, data, 0.0, 0.0, "%.5G", + ImGuiInputTextFlags_ReadOnly); + } else { + return ImGui::InputDouble(text, data, 0.0, 0.0, "%.5G"); + } +} + +static void SetPosition(double beginX, double beginY, double xShift, + double yShift) { + ImGui::SetCursorPos(ImVec2(beginX + xShift * 10 * ImGui::GetFontSize(), + beginY + yShift * 1.75 * ImGui::GetFontSize())); +} + +bool Analyzer::IsErrorState() { + return m_state == AnalyzerState::kMotionThresholdError || + m_state == AnalyzerState::kTestDurationError || + m_state == AnalyzerState::kGeneralDataError || + m_state == AnalyzerState::kFileError; +} + +bool Analyzer::IsDataErrorState() { + return m_state == AnalyzerState::kMotionThresholdError || + m_state == AnalyzerState::kTestDurationError || + m_state == AnalyzerState::kGeneralDataError; +} + +void Analyzer::DisplayFileSelector() { + // Get the current width of the window. This will be used to scale + // our UI elements. + float width = ImGui::GetContentRegionAvail().x; + + // Show the file location along with an option to choose. + if (ImGui::Button("Select")) { + m_selector = std::make_unique( + "Select Data", "", + std::vector{"JSON File", SYSID_PFD_JSON_EXT}); + } + ImGui::SameLine(); + ImGui::SetNextItemWidth(width - ImGui::CalcTextSize("Select").x - + ImGui::GetFontSize() * 5); + ImGui::InputText("##location", &m_location, ImGuiInputTextFlags_ReadOnly); +} + +void Analyzer::ResetData() { + m_plot.ResetData(); + m_manager = std::make_unique(m_settings, m_logger); + m_location = ""; + m_ff = std::vector{1, 1, 1}; + UpdateFeedbackGains(); +} + +bool Analyzer::DisplayResetAndUnitOverride() { + auto type = m_manager->GetAnalysisType(); + auto unit = m_manager->GetUnit(); + + float width = ImGui::GetContentRegionAvail().x; + ImGui::SameLine(width - ImGui::CalcTextSize("Reset").x); + if (ImGui::Button("Reset")) { + ResetData(); + m_state = AnalyzerState::kWaitingForJSON; + return true; + } + + if (type == analysis::kDrivetrain) { + ImGui::SetNextItemWidth(ImGui::GetFontSize() * kTextBoxWidthMultiple); + if (ImGui::Combo("Dataset", &m_dataset, kDatasets, 3)) { + m_settings.dataset = + static_cast(m_dataset); + PrepareData(); + } + ImGui::SameLine(); + } else { + m_settings.dataset = + AnalysisManager::Settings::DrivetrainDataset::kCombined; + } + + ImGui::Spacing(); + ImGui::Text( + "Units: %s\n" + "Units Per Rotation: %.4f\n" + "Type: %s", + std::string(unit).c_str(), m_conversionFactor, type.name); + + if (type == analysis::kDrivetrainAngular) { + ImGui::SameLine(); + sysid::CreateTooltip( + "Here, the units and units per rotation represent what the wheel " + "positions and velocities were captured in. The track width value " + "will reflect the unit selected here. However, the Kv and Ka will " + "always be in Vs/rad and Vs^2 / rad respectively."); + } + + if (ImGui::Button("Override Units")) { + ImGui::OpenPopup("Override Units"); + } + + auto size = ImGui::GetIO().DisplaySize; + ImGui::SetNextWindowSize(ImVec2(size.x / 4, size.y * 0.2)); + if (ImGui::BeginPopupModal("Override Units")) { + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 7); + ImGui::Combo("Units", &m_selectedOverrideUnit, kUnits, + IM_ARRAYSIZE(kUnits)); + unit = kUnits[m_selectedOverrideUnit]; + + if (unit == "Degrees") { + m_conversionFactor = 360.0; + } else if (unit == "Radians") { + m_conversionFactor = 2 * std::numbers::pi; + } else if (unit == "Rotations") { + m_conversionFactor = 1.0; + } + + bool isRotational = m_selectedOverrideUnit > 2; + + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 7); + ImGui::InputDouble( + "Units Per Rotation", &m_conversionFactor, 0.0, 0.0, "%.4f", + isRotational ? ImGuiInputTextFlags_ReadOnly : ImGuiInputTextFlags_None); + + if (ImGui::Button("Close")) { + ImGui::CloseCurrentPopup(); + m_manager->OverrideUnits(unit, m_conversionFactor); + PrepareData(); + } + + ImGui::EndPopup(); + } + + ImGui::SameLine(); + if (ImGui::Button("Reset Units from JSON")) { + m_manager->ResetUnitsFromJSON(); + PrepareData(); + } + + return false; +} + +void Analyzer::ConfigParamsOnFileSelect() { + WPI_INFO(m_logger, "{}", "Configuring Params"); + m_stepTestDuration = m_settings.stepTestDuration.to(); + + // Estimate qp as 1/8 * units-per-rot + m_settings.lqr.qp = 0.125 * m_manager->GetFactor(); + // Estimate qv as 1/4 * max velocity = 1/4 * (12V - kS) / kV + m_settings.lqr.qv = 0.25 * (12.0 - m_ff[0]) / m_ff[1]; +} + +void Analyzer::Display() { + DisplayFileSelector(); + DisplayGraphs(); + + switch (m_state) { + case AnalyzerState::kWaitingForJSON: { + ImGui::Text( + "SysId is currently in theoretical analysis mode.\n" + "To analyze recorded test data, select a " + "data JSON."); + sysid::CreateTooltip( + "Theoretical feedback gains can be calculated from a " + "physical model of the mechanism being controlled. " + "Theoretical gains for several common mechanisms can " + "be obtained from ReCalc (https://reca.lc)."); + ImGui::Spacing(); + ImGui::Spacing(); + + ImGui::SetNextItemOpen(true, ImGuiCond_Once); + if (ImGui::CollapsingHeader("Feedforward Gains (Theoretical)")) { + float beginX = ImGui::GetCursorPosX(); + float beginY = ImGui::GetCursorPosY(); + CollectFeedforwardGains(beginX, beginY); + } + ImGui::SetNextItemOpen(true, ImGuiCond_Once); + if (ImGui::CollapsingHeader("Feedback Analysis")) { + DisplayFeedbackGains(); + } + break; + } + case AnalyzerState::kNominalDisplay: { // Allow the user to select which + // data set they want analyzed and + // add a + // reset button. Also show the units and the units per rotation. + if (DisplayResetAndUnitOverride()) { + return; + } + ImGui::Spacing(); + ImGui::Spacing(); + + ImGui::SetNextItemOpen(true, ImGuiCond_Once); + if (ImGui::CollapsingHeader("Feedforward Analysis")) { + float beginX = ImGui::GetCursorPosX(); + float beginY = ImGui::GetCursorPosY(); + DisplayFeedforwardGains(beginX, beginY); + } + ImGui::SetNextItemOpen(true, ImGuiCond_Once); + if (ImGui::CollapsingHeader("Feedback Analysis")) { + DisplayFeedbackGains(); + } + break; + } + case AnalyzerState::kFileError: { + CreateErrorPopup(m_errorPopup, m_exception); + if (!m_errorPopup) { + m_state = AnalyzerState::kWaitingForJSON; + return; + } + break; + } + case AnalyzerState::kGeneralDataError: + case AnalyzerState::kTestDurationError: + case AnalyzerState::kMotionThresholdError: { + CreateErrorPopup(m_errorPopup, m_exception); + if (DisplayResetAndUnitOverride()) { + return; + } + float beginX = ImGui::GetCursorPosX(); + float beginY = ImGui::GetCursorPosY(); + DisplayFeedforwardParameters(beginX, beginY); + break; + } + } + + // Periodic functions + try { + SelectFile(); + } catch (const AnalysisManager::FileReadingError& e) { + m_state = AnalyzerState::kFileError; + HandleError(e.what()); + } catch (const wpi::json::exception& e) { + m_state = AnalyzerState::kFileError; + HandleError(e.what()); + } +} + +void Analyzer::PrepareData() { + try { + m_manager->PrepareData(); + UpdateFeedforwardGains(); + UpdateFeedbackGains(); + } catch (const sysid::InvalidDataError& e) { + m_state = AnalyzerState::kGeneralDataError; + HandleError(e.what()); + } catch (const sysid::NoQuasistaticDataError& e) { + m_state = AnalyzerState::kMotionThresholdError; + HandleError(e.what()); + } catch (const sysid::NoDynamicDataError& e) { + m_state = AnalyzerState::kTestDurationError; + HandleError(e.what()); + } catch (const AnalysisManager::FileReadingError& e) { + m_state = AnalyzerState::kFileError; + HandleError(e.what()); + } catch (const wpi::json::exception& e) { + m_state = AnalyzerState::kFileError; + HandleError(e.what()); + } catch (const std::exception& e) { + m_state = AnalyzerState::kFileError; + HandleError(e.what()); + } +} + +void Analyzer::PrepareRawGraphs() { + if (m_manager->HasData()) { + AbortDataPrep(); + m_dataThread = std::thread([&] { + m_plot.SetRawData(m_manager->GetOriginalData(), m_manager->GetUnit(), + m_abortDataPrep); + }); + } +} + +void Analyzer::PrepareGraphs() { + if (m_manager->HasData()) { + WPI_INFO(m_logger, "{}", "Graph state"); + AbortDataPrep(); + m_dataThread = std::thread([&] { + m_plot.SetData(m_manager->GetRawData(), m_manager->GetFilteredData(), + m_manager->GetUnit(), m_ff, m_manager->GetStartTimes(), + m_manager->GetAnalysisType(), m_abortDataPrep); + }); + UpdateFeedbackGains(); + m_state = AnalyzerState::kNominalDisplay; + } +} + +void Analyzer::HandleError(std::string_view msg) { + m_exception = msg; + m_errorPopup = true; + if (m_state == AnalyzerState::kFileError) { + m_location = ""; + } + PrepareRawGraphs(); +} + +void Analyzer::DisplayGraphs() { + ImGui::SetNextWindowPos(ImVec2{kDiagnosticPlotWindowPos}, + ImGuiCond_FirstUseEver); + ImGui::SetNextWindowSize(ImVec2{kDiagnosticPlotWindowSize}, + ImGuiCond_FirstUseEver); + ImGui::Begin("Diagnostic Plots"); + + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 6); + if (ImGui::SliderFloat("Point Size", &m_plot.m_pointSize, 1, 2, "%.2f")) { + if (!IsErrorState()) { + PrepareGraphs(); + } else { + PrepareRawGraphs(); + } + } + + ImGui::SameLine(); + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 6); + const char* items[] = {"Forward", "Backward"}; + if (ImGui::Combo("Direction", &m_plot.m_direction, items, 2)) { + if (!IsErrorState()) { + PrepareGraphs(); + } else { + PrepareRawGraphs(); + } + } + + // If the plots were already loaded, store the scroll position. Else go to + // the last recorded scroll position if they have just been initialized + bool plotsLoaded = m_plot.DisplayPlots(); + if (plotsLoaded) { + if (m_prevPlotsLoaded) { + m_graphScroll = ImGui::GetScrollY(); + } else { + ImGui::SetScrollY(m_graphScroll); + } + + // If a JSON is selected + if (m_state == AnalyzerState::kNominalDisplay) { + DisplayGain("Acceleration R²", &m_accelRSquared); + CreateTooltip( + "The coefficient of determination of the OLS fit of acceleration " + "versus velocity and voltage. Acceleration is extremely noisy, " + "so this is generally quite small."); + + ImGui::SameLine(); + DisplayGain("Acceleration RMSE", &m_accelRMSE); + CreateTooltip( + "The standard deviation of the residuals from the predicted " + "acceleration." + "This can be interpreted loosely as the mean measured disturbance " + "from the \"ideal\" system equation."); + + DisplayGain("Sim velocity R²", m_plot.GetSimRSquared()); + CreateTooltip( + "The coefficient of determination the simulated velocity. " + "Velocity is much less-noisy than acceleration, so this " + "is pretty close to 1 for a decent fit."); + + ImGui::SameLine(); + DisplayGain("Sim velocity RMSE", m_plot.GetSimRMSE()); + CreateTooltip( + "The standard deviation of the residuals from the simulated velocity " + "predictions - essentially the size of the mean error of the " + "simulated model " + "in the recorded velocity units."); + } + } + m_prevPlotsLoaded = plotsLoaded; + + ImGui::End(); +} + +void Analyzer::SelectFile() { + // If the selector exists and is ready with a result, we can store it. + if (m_selector && m_selector->ready() && !m_selector->result().empty()) { + // Store the location of the file and reset the selector. + WPI_INFO(m_logger, "Opening File: {}", m_selector->result()[0]); + m_location = m_selector->result()[0]; + m_selector.reset(); + WPI_INFO(m_logger, "{}", "Opened File"); + m_manager = + std::make_unique(m_location, m_settings, m_logger); + PrepareData(); + m_dataset = 0; + m_settings.dataset = + AnalysisManager::Settings::DrivetrainDataset::kCombined; + ConfigParamsOnFileSelect(); + UpdateFeedbackGains(); + } +} + +void Analyzer::AbortDataPrep() { + if (m_dataThread.joinable()) { + m_abortDataPrep = true; + m_dataThread.join(); + m_abortDataPrep = false; + } +} + +void Analyzer::DisplayFeedforwardParameters(float beginX, float beginY) { + // Increase spacing to not run into trackwidth in the normal analyzer view + constexpr double kHorizontalOffset = 0.9; + SetPosition(beginX, beginY, kHorizontalOffset, 0); + + bool displayAll = + !IsErrorState() || m_state == AnalyzerState::kGeneralDataError; + + if (displayAll) { + // Wait for enter before refresh so double digit entries like "15" don't + // prematurely refresh with "1". That can cause display stuttering. + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); + int window = m_settings.medianWindow; + if (ImGui::InputInt("Window Size", &window, 0, 0, + ImGuiInputTextFlags_EnterReturnsTrue)) { + m_settings.medianWindow = std::clamp(window, 1, 15); + PrepareData(); + } + + CreateTooltip( + "The number of samples in the velocity median " + "filter's sliding window."); + } + + if (displayAll || m_state == AnalyzerState::kMotionThresholdError) { + // Wait for enter before refresh so decimal inputs like "0.2" don't + // prematurely refresh with a velocity threshold of "0". + SetPosition(beginX, beginY, kHorizontalOffset, 1); + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); + double threshold = m_settings.motionThreshold; + if (ImGui::InputDouble("Velocity Threshold", &threshold, 0.0, 0.0, "%.3f", + ImGuiInputTextFlags_EnterReturnsTrue)) { + m_settings.motionThreshold = std::max(0.0, threshold); + PrepareData(); + } + CreateTooltip("Velocity data below this threshold will be ignored."); + } + + if (displayAll || m_state == AnalyzerState::kTestDurationError) { + SetPosition(beginX, beginY, kHorizontalOffset, 2); + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); + if (ImGui::SliderFloat("Test Duration", &m_stepTestDuration, + m_manager->GetMinStepTime().value(), + m_manager->GetMaxStepTime().value(), "%.2f")) { + m_settings.stepTestDuration = units::second_t{m_stepTestDuration}; + PrepareData(); + } + } +} + +void Analyzer::CollectFeedforwardGains(float beginX, float beginY) { + SetPosition(beginX, beginY, 0, 0); + if (DisplayGain("Kv", &m_ff[1], false)) { + UpdateFeedbackGains(); + } + + SetPosition(beginX, beginY, 0, 1); + if (DisplayGain("Ka", &m_ff[2], false)) { + UpdateFeedbackGains(); + } + + SetPosition(beginX, beginY, 0, 2); + // Show Timescale + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); + DisplayGain("Response Timescale (ms)", + reinterpret_cast(&m_timescale)); + CreateTooltip( + "The characteristic timescale of the system response in milliseconds. " + "Both the control loop period and total signal delay should be " + "at least 3-5 times shorter than this to optimally control the " + "system."); +} + +void Analyzer::DisplayFeedforwardGains(float beginX, float beginY) { + SetPosition(beginX, beginY, 0, 0); + DisplayGain("Ks", &m_ff[0]); + + SetPosition(beginX, beginY, 0, 1); + DisplayGain("Kv", &m_ff[1]); + + SetPosition(beginX, beginY, 0, 2); + DisplayGain("Ka", &m_ff[2]); + + SetPosition(beginX, beginY, 0, 3); + // Show Timescale + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); + DisplayGain("Response Timescale (ms)", + reinterpret_cast(&m_timescale)); + CreateTooltip( + "The characteristic timescale of the system response in milliseconds. " + "Both the control loop period and total signal delay should be " + "at least 3-5 times shorter than this to optimally control the " + "system."); + + SetPosition(beginX, beginY, 0, 4); + auto positionDelay = m_manager->GetPositionDelay(); + DisplayGain("Position Measurement Delay (ms)", + reinterpret_cast(&positionDelay)); + CreateTooltip( + "The average elapsed time between the first application of " + "voltage and the first detected change in mechanism position " + "in the step-voltage tests. This includes CAN delays, and " + "may overestimate the true delay for on-motor-controller " + "feedback loops by up to 20ms."); + + SetPosition(beginX, beginY, 0, 5); + auto velocityDelay = m_manager->GetVelocityDelay(); + DisplayGain("Velocity Measurement Delay (ms)", + reinterpret_cast(&velocityDelay)); + CreateTooltip( + "The average elapsed time between the first application of " + "voltage and the maximum calculated mechanism acceleration " + "in the step-voltage tests. This includes CAN delays, and " + "may overestimate the true delay for on-motor-controller " + "feedback loops by up to 20ms."); + + SetPosition(beginX, beginY, 0, 6); + + if (m_manager->GetAnalysisType() == analysis::kElevator) { + DisplayGain("Kg", &m_ff[3]); + } else if (m_manager->GetAnalysisType() == analysis::kArm) { + DisplayGain("Kg", &m_ff[3]); + + double offset; + auto unit = m_manager->GetUnit(); + if (unit == "Radians") { + offset = m_ff[4]; + } else if (unit == "Degrees") { + offset = m_ff[4] / std::numbers::pi * 180.0; + } else if (unit == "Rotations") { + offset = m_ff[4] / (2 * std::numbers::pi); + } + DisplayGain( + fmt::format("Angle offset to horizontal ({})", GetAbbreviation(unit)) + .c_str(), + &offset); + CreateTooltip( + "This is the angle offset which, when added to the angle measurement, " + "zeroes it out when the arm is horizontal. This is needed for the arm " + "feedforward to work."); + } else if (m_trackWidth) { + DisplayGain("Track Width", &*m_trackWidth); + } + double endY = ImGui::GetCursorPosY(); + + DisplayFeedforwardParameters(beginX, beginY); + ImGui::SetCursorPosY(endY); +} + +void Analyzer::DisplayFeedbackGains() { + // Allow the user to select a feedback controller preset. + ImGui::Spacing(); + ImGui::SetNextItemWidth(ImGui::GetFontSize() * kTextBoxWidthMultiple); + if (ImGui::Combo("Gain Preset", &m_selectedPreset, kPresetNames, + IM_ARRAYSIZE(kPresetNames))) { + m_settings.preset = m_presets[kPresetNames[m_selectedPreset]]; + m_settings.type = FeedbackControllerLoopType::kVelocity; + m_selectedLoopType = + static_cast(FeedbackControllerLoopType::kVelocity); + m_settings.convertGainsToEncTicks = m_selectedPreset > 2; + UpdateFeedbackGains(); + } + ImGui::SameLine(); + sysid::CreateTooltip( + "Gain presets represent how feedback gains are calculated for your " + "specific feedback controller:\n\n" + "Default, WPILib (2020-): For use with the new WPILib PIDController " + "class.\n" + "WPILib (Pre-2020): For use with the old WPILib PIDController class.\n" + "CTRE: For use with CTRE units. These are the default units that ship " + "with CTRE motor controllers.\n" + "REV (Brushless): For use with NEO and NEO 550 motors on a SPARK MAX.\n" + "REV (Brushed): For use with brushed motors connected to a SPARK MAX."); + + if (m_settings.preset != m_presets[kPresetNames[m_selectedPreset]]) { + ImGui::SameLine(); + ImGui::TextDisabled("(modified)"); + } + + // Show our feedback controller preset values. + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); + double value = m_settings.preset.outputConversionFactor * 12; + if (ImGui::InputDouble("Max Controller Output", &value, 0.0, 0.0, "%.1f") && + value > 0) { + m_settings.preset.outputConversionFactor = value / 12.0; + UpdateFeedbackGains(); + } + + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); + value = m_settings.preset.outputVelocityTimeFactor; + if (ImGui::InputDouble("Velocity Denominator Units (s)", &value, 0.0, 0.0, + "%.1f") && + value > 0) { + m_settings.preset.outputVelocityTimeFactor = value; + UpdateFeedbackGains(); + } + + sysid::CreateTooltip( + "This represents the denominator of the velocity unit used by the " + "feedback controller. For example, CTRE uses 100 ms = 0.1 s."); + + auto ShowPresetValue = [](const char* text, double* data, + float cursorX = 0.0f) { + if (cursorX > 0) { + ImGui::SetCursorPosX(cursorX); + } + + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); + return ImGui::InputDouble(text, data, 0.0, 0.0, "%.5G"); + }; + + // Show controller period. + if (ShowPresetValue("Controller Period (ms)", + reinterpret_cast(&m_settings.preset.period))) { + if (m_settings.preset.period > 0_s && + m_settings.preset.measurementDelay >= 0_s) { + UpdateFeedbackGains(); + } + } + + // Show whether the controller gains are time-normalized. + if (ImGui::Checkbox("Time-Normalized?", &m_settings.preset.normalized)) { + UpdateFeedbackGains(); + } + + // Show position/velocity measurement delay. + if (ShowPresetValue( + "Measurement Delay (ms)", + reinterpret_cast(&m_settings.preset.measurementDelay))) { + if (m_settings.preset.period > 0_s && + m_settings.preset.measurementDelay >= 0_s) { + UpdateFeedbackGains(); + } + } + + sysid::CreateTooltip( + "The average measurement delay of the process variable in milliseconds. " + "This may depend on your encoder settings and choice of motor " + "controller. Default velocity filtering windows are quite long " + "on many motor controllers, so be careful that this value is " + "accurate if the characteristic timescale of the mechanism " + "is small."); + + // Add CPR and Gearing for converting Feedback Gains + ImGui::Separator(); + ImGui::Spacing(); + + if (ImGui::Checkbox("Convert Gains to Encoder Counts", + &m_settings.convertGainsToEncTicks)) { + UpdateFeedbackGains(); + } + sysid::CreateTooltip( + "Whether the feedback gains should be in terms of encoder counts or " + "output units. Because smart motor controllers usually don't have " + "direct access to the output units (i.e. m/s for a drivetrain), they " + "perform feedback on the encoder counts directly. If you are using a " + "PID Controller on the RoboRIO, you are probably performing feedback " + "on the output units directly.\n\nNote that if you have properly set " + "up position and velocity conversion factors with the SPARK MAX, you " + "can leave this box unchecked. The motor controller will perform " + "feedback on the output directly."); + + if (m_settings.convertGainsToEncTicks) { + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 5); + if (ImGui::InputDouble("##Numerator", &m_gearingNumerator, 0.0, 0.0, "%.4f", + ImGuiInputTextFlags_EnterReturnsTrue) && + m_gearingNumerator > 0) { + m_settings.gearing = m_gearingNumerator / m_gearingDenominator; + UpdateFeedbackGains(); + } + ImGui::SameLine(); + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 5); + if (ImGui::InputDouble("##Denominator", &m_gearingDenominator, 0.0, 0.0, + "%.4f", ImGuiInputTextFlags_EnterReturnsTrue) && + m_gearingDenominator > 0) { + m_settings.gearing = m_gearingNumerator / m_gearingDenominator; + UpdateFeedbackGains(); + } + sysid::CreateTooltip( + "The gearing between the encoder and the motor shaft (# of encoder " + "turns / # of motor shaft turns)."); + + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 5); + if (ImGui::InputInt("CPR", &m_settings.cpr, 0, 0, + ImGuiInputTextFlags_EnterReturnsTrue) && + m_settings.cpr > 0) { + UpdateFeedbackGains(); + } + sysid::CreateTooltip( + "The counts per rotation of your encoder. This is the number of counts " + "reported in user code when the encoder is rotated exactly once. Some " + "common values for various motors/encoders are:\n\n" + "Falcon 500: 2048\nNEO: 1\nCTRE Mag Encoder / CANCoder: 4096\nREV " + "Through Bore Encoder: 8192\n"); + } + + ImGui::Separator(); + ImGui::Spacing(); + + // Allow the user to select a loop type. + ImGui::SetNextItemWidth(ImGui::GetFontSize() * kTextBoxWidthMultiple); + if (ImGui::Combo("Loop Type", &m_selectedLoopType, kLoopTypes, + IM_ARRAYSIZE(kLoopTypes))) { + m_settings.type = + static_cast(m_selectedLoopType); + if (m_state == AnalyzerState::kWaitingForJSON) { + m_settings.preset.measurementDelay = 0_ms; + } else { + if (m_settings.type == FeedbackControllerLoopType::kPosition) { + m_settings.preset.measurementDelay = m_manager->GetPositionDelay(); + } else { + m_settings.preset.measurementDelay = m_manager->GetVelocityDelay(); + } + } + UpdateFeedbackGains(); + } + + ImGui::Spacing(); + + // Show Kp and Kd. + float beginY = ImGui::GetCursorPosY(); + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); + DisplayGain("Kp", &m_Kp); + + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); + DisplayGain("Kd", &m_Kd); + + // Come back to the starting y pos. + ImGui::SetCursorPosY(beginY); + + if (m_selectedLoopType == 0) { + std::string unit; + if (m_state != AnalyzerState::kWaitingForJSON) { + unit = fmt::format(" ({})", GetAbbreviation(m_manager->GetUnit())); + } + + ImGui::SetCursorPosX(ImGui::GetFontSize() * 9); + if (DisplayGain(fmt::format("Max Position Error{}", unit).c_str(), + &m_settings.lqr.qp, false)) { + if (m_settings.lqr.qp > 0) { + UpdateFeedbackGains(); + } + } + } + + std::string unit; + if (m_state != AnalyzerState::kWaitingForJSON) { + unit = fmt::format(" ({}/s)", GetAbbreviation(m_manager->GetUnit())); + } + + ImGui::SetCursorPosX(ImGui::GetFontSize() * 9); + if (DisplayGain(fmt::format("Max Velocity Error{}", unit).c_str(), + &m_settings.lqr.qv, false)) { + if (m_settings.lqr.qv > 0) { + UpdateFeedbackGains(); + } + } + ImGui::SetCursorPosX(ImGui::GetFontSize() * 9); + if (DisplayGain("Max Control Effort (V)", &m_settings.lqr.r, false)) { + if (m_settings.lqr.r > 0) { + UpdateFeedbackGains(); + } + } +} diff --git a/sysid/src/main/native/cpp/view/AnalyzerPlot.cpp b/sysid/src/main/native/cpp/view/AnalyzerPlot.cpp new file mode 100644 index 00000000000..d8afbaf06c0 --- /dev/null +++ b/sysid/src/main/native/cpp/view/AnalyzerPlot.cpp @@ -0,0 +1,531 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/view/AnalyzerPlot.h" + +#include +#include +#include + +#include +#include + +#include "sysid/Util.h" +#include "sysid/analysis/AnalysisManager.h" +#include "sysid/analysis/ArmSim.h" +#include "sysid/analysis/ElevatorSim.h" +#include "sysid/analysis/FilteringUtils.h" +#include "sysid/analysis/SimpleMotorSim.h" + +using namespace sysid; + +static ImPlotPoint Getter(int idx, void* data) { + return static_cast(data)[idx]; +} + +template +static std::vector> PopulateTimeDomainSim( + const std::vector& data, + const std::array& startTimes, size_t step, Model model, + double* simSquaredErrorSum, double* squaredVariationSum, + int* timeSeriesPoints) { + // Create the vector of ImPlotPoints that will contain our simulated data. + std::vector> pts; + std::vector tmp; + + auto startTime = data[0].timestamp; + + tmp.emplace_back(startTime.value(), data[0].velocity); + + model.Reset(data[0].position, data[0].velocity); + units::second_t t = 0_s; + + for (size_t i = 1; i < data.size(); ++i) { + const auto& now = data[i]; + const auto& pre = data[i - 1]; + + t += now.timestamp - pre.timestamp; + + // If the current time stamp and previous time stamp are across a test's + // start timestamp, it is the start of a new test and the model needs to be + // reset. + if (std::find(startTimes.begin(), startTimes.end(), now.timestamp) != + startTimes.end()) { + pts.emplace_back(std::move(tmp)); + model.Reset(now.position, now.velocity); + continue; + } + + model.Update(units::volt_t{pre.voltage}, now.timestamp - pre.timestamp); + tmp.emplace_back((startTime + t).value(), model.GetVelocity()); + *simSquaredErrorSum += std::pow(now.velocity - model.GetVelocity(), 2); + *squaredVariationSum += std::pow(now.velocity, 2); + ++(*timeSeriesPoints); + } + + pts.emplace_back(std::move(tmp)); + return pts; +} + +AnalyzerPlot::AnalyzerPlot(wpi::Logger& logger) : m_logger(logger) {} + +void AnalyzerPlot::SetRawTimeData(const std::vector& rawSlow, + const std::vector& rawFast, + std::atomic& abort) { + auto rawSlowStep = std::ceil(rawSlow.size() * 1.0 / kMaxSize * 4); + auto rawFastStep = std::ceil(rawFast.size() * 1.0 / kMaxSize * 4); + // Populate Raw Slow Time Series Data + for (size_t i = 0; i < rawSlow.size(); i += rawSlowStep) { + if (abort) { + return; + } + m_quasistaticData.rawData.emplace_back((rawSlow[i].timestamp).value(), + rawSlow[i].velocity); + } + + // Populate Raw fast Time Series Data + for (size_t i = 0; i < rawFast.size(); i += rawFastStep) { + if (abort) { + return; + } + m_dynamicData.rawData.emplace_back((rawFast[i].timestamp).value(), + rawFast[i].velocity); + } +} + +void AnalyzerPlot::ResetData() { + m_quasistaticData.Clear(); + m_dynamicData.Clear(); + m_regressionData.Clear(); + m_timestepData.Clear(); + + FitPlots(); +} + +void AnalyzerPlot::SetGraphLabels(std::string_view unit) { + std::string_view abbreviation = GetAbbreviation(unit); + m_velocityLabel = fmt::format("Velocity ({}/s)", abbreviation); + m_accelerationLabel = fmt::format("Acceleration ({}/s²)", abbreviation); + m_velPortionAccelLabel = + fmt::format("Velocity-Portion Accel ({}/s²)", abbreviation); +} + +void AnalyzerPlot::SetRawData(const Storage& data, std::string_view unit, + std::atomic& abort) { + const auto& [slowForward, slowBackward, fastForward, fastBackward] = data; + const auto& slow = m_direction == 0 ? slowForward : slowBackward; + const auto& fast = m_direction == 0 ? fastForward : fastBackward; + + SetGraphLabels(unit); + + std::scoped_lock lock(m_mutex); + + ResetData(); + SetRawTimeData(slow, fast, abort); +} + +void AnalyzerPlot::SetData(const Storage& rawData, const Storage& filteredData, + std::string_view unit, + const std::vector& ffGains, + const std::array& startTimes, + AnalysisType type, std::atomic& abort) { + double simSquaredErrorSum = 0; + double squaredVariationSum = 0; + int timeSeriesPoints = 0; + + const auto& Ks = ffGains[0]; + const auto& Kv = ffGains[1]; + const auto& Ka = ffGains[2]; + + auto& [slowForward, slowBackward, fastForward, fastBackward] = filteredData; + auto& [rawSlowForward, rawSlowBackward, rawFastForward, rawFastBackward] = + rawData; + + const auto slow = AnalysisManager::DataConcat(slowForward, slowBackward); + const auto fast = AnalysisManager::DataConcat(fastForward, fastBackward); + const auto rawSlow = + AnalysisManager::DataConcat(rawSlowForward, rawSlowBackward); + const auto rawFast = + AnalysisManager::DataConcat(rawFastForward, rawFastBackward); + + SetGraphLabels(unit); + + std::scoped_lock lock(m_mutex); + + ResetData(); + + // Calculate step sizes to ensure that we only use the memory that we + // allocated. + auto slowStep = std::ceil(slow.size() * 1.0 / kMaxSize * 4); + auto fastStep = std::ceil(fast.size() * 1.0 / kMaxSize * 4); + + units::second_t dtMean = GetMeanTimeDelta(filteredData); + + // Velocity-vs-time plots + { + const auto& slow = m_direction == 0 ? slowForward : slowBackward; + const auto& fast = m_direction == 0 ? fastForward : fastBackward; + const auto& rawSlow = m_direction == 0 ? rawSlowForward : rawSlowBackward; + const auto& rawFast = m_direction == 0 ? rawFastForward : rawFastBackward; + + // Populate quasistatic time-domain graphs + for (size_t i = 0; i < slow.size(); i += slowStep) { + if (abort) { + return; + } + + m_quasistaticData.filteredData.emplace_back((slow[i].timestamp).value(), + slow[i].velocity); + + if (i > 0) { + // If the current timestamp is not in the startTimes array, it is the + // during a test and should be included. If it is in the startTimes + // array, it is the beginning of a new test and the dt will be inflated. + // Therefore we skip those to exclude that dt and effectively reset dt + // calculations. + if (slow[i].dt > 0_s && + std::find(startTimes.begin(), startTimes.end(), + slow[i].timestamp) == startTimes.end()) { + m_timestepData.data.emplace_back( + (slow[i].timestamp).value(), + units::millisecond_t{slow[i].dt}.value()); + } + } + } + + // Populate dynamic time-domain graphs + for (size_t i = 0; i < fast.size(); i += fastStep) { + if (abort) { + return; + } + + m_dynamicData.filteredData.emplace_back((fast[i].timestamp).value(), + fast[i].velocity); + + if (i > 0) { + // If the current timestamp is not in the startTimes array, it is the + // during a test and should be included. If it is in the startTimes + // array, it is the beginning of a new test and the dt will be inflated. + // Therefore we skip those to exclude that dt and effectively reset dt + // calculations. + if (fast[i].dt > 0_s && + std::find(startTimes.begin(), startTimes.end(), + fast[i].timestamp) == startTimes.end()) { + m_timestepData.data.emplace_back( + (fast[i].timestamp).value(), + units::millisecond_t{fast[i].dt}.value()); + } + } + } + + SetRawTimeData(rawSlow, rawFast, abort); + + // Populate simulated time domain data + if (type == analysis::kElevator) { + const auto& Kg = ffGains[3]; + m_quasistaticData.simData = PopulateTimeDomainSim( + rawSlow, startTimes, fastStep, sysid::ElevatorSim{Ks, Kv, Ka, Kg}, + &simSquaredErrorSum, &squaredVariationSum, &timeSeriesPoints); + m_dynamicData.simData = PopulateTimeDomainSim( + rawFast, startTimes, fastStep, sysid::ElevatorSim{Ks, Kv, Ka, Kg}, + &simSquaredErrorSum, &squaredVariationSum, &timeSeriesPoints); + } else if (type == analysis::kArm) { + const auto& Kg = ffGains[3]; + const auto& offset = ffGains[4]; + m_quasistaticData.simData = PopulateTimeDomainSim( + rawSlow, startTimes, fastStep, sysid::ArmSim{Ks, Kv, Ka, Kg, offset}, + &simSquaredErrorSum, &squaredVariationSum, &timeSeriesPoints); + m_dynamicData.simData = PopulateTimeDomainSim( + rawFast, startTimes, fastStep, sysid::ArmSim{Ks, Kv, Ka, Kg, offset}, + &simSquaredErrorSum, &squaredVariationSum, &timeSeriesPoints); + } else { + m_quasistaticData.simData = PopulateTimeDomainSim( + rawSlow, startTimes, fastStep, sysid::SimpleMotorSim{Ks, Kv, Ka}, + &simSquaredErrorSum, &squaredVariationSum, &timeSeriesPoints); + m_dynamicData.simData = PopulateTimeDomainSim( + rawFast, startTimes, fastStep, sysid::SimpleMotorSim{Ks, Kv, Ka}, + &simSquaredErrorSum, &squaredVariationSum, &timeSeriesPoints); + } + } + + // Acceleration-vs-velocity plot + + // Find minimum velocity of slow and fast datasets, then find point for line + // of best fit + auto slowMinVel = + std::min_element(slow.cbegin(), slow.cend(), [](auto& a, auto& b) { + return a.velocity < b.velocity; + })->velocity; + auto fastMinVel = + std::min_element(fast.cbegin(), fast.cend(), [](auto& a, auto& b) { + return a.velocity < b.velocity; + })->velocity; + auto minVel = std::min(slowMinVel, fastMinVel); + m_regressionData.fitLine[0] = ImPlotPoint{minVel, -Kv / Ka * minVel}; + + // Find maximum velocity of slow and fast datasets, then find point for line + // of best fit + auto slowMaxVel = + std::max_element(slow.cbegin(), slow.cend(), [](auto& a, auto& b) { + return a.velocity < b.velocity; + })->velocity; + auto fastMaxVel = + std::max_element(fast.cbegin(), fast.cend(), [](auto& a, auto& b) { + return a.velocity < b.velocity; + })->velocity; + auto maxVel = std::max(slowMaxVel, fastMaxVel); + m_regressionData.fitLine[1] = ImPlotPoint{maxVel, -Kv / Ka * maxVel}; + + // Populate acceleration vs velocity graph + for (size_t i = 0; i < slow.size(); i += slowStep) { + if (abort) { + return; + } + + // Calculate portion of acceleration caused by back-EMF + double accelPortion = slow[i].acceleration - 1.0 / Ka * slow[i].voltage + + std::copysign(Ks / Ka, slow[i].velocity); + + if (type == analysis::kElevator) { + const auto& Kg = ffGains[3]; + accelPortion -= Kg / Ka; + } else if (type == analysis::kArm) { + const auto& Kg = ffGains[3]; + accelPortion -= Kg / Ka * slow[i].cos; + } + + m_regressionData.data.emplace_back(slow[i].velocity, accelPortion); + } + for (size_t i = 0; i < fast.size(); i += fastStep) { + if (abort) { + return; + } + + // Calculate portion of voltage that corresponds to change in acceleration. + double accelPortion = fast[i].acceleration - 1.0 / Ka * fast[i].voltage + + std::copysign(Ks / Ka, fast[i].velocity); + + if (type == analysis::kElevator) { + const auto& Kg = ffGains[3]; + accelPortion -= Kg / Ka; + } else if (type == analysis::kArm) { + const auto& Kg = ffGains[3]; + accelPortion -= Kg / Ka * fast[i].cos; + } + + m_regressionData.data.emplace_back(fast[i].velocity, accelPortion); + } + + // Timestep-vs-time plot + + for (size_t i = 0; i < slow.size(); i += slowStep) { + if (i > 0) { + // If the current timestamp is not in the startTimes array, it is the + // during a test and should be included. If it is in the startTimes + // array, it is the beginning of a new test and the dt will be inflated. + // Therefore we skip those to exclude that dt and effectively reset dt + // calculations. + if (slow[i].dt > 0_s && + std::find(startTimes.begin(), startTimes.end(), slow[i].timestamp) == + startTimes.end()) { + m_timestepData.data.emplace_back( + (slow[i].timestamp).value(), + units::millisecond_t{slow[i].dt}.value()); + } + } + } + + for (size_t i = 0; i < fast.size(); i += fastStep) { + if (i > 0) { + // If the current timestamp is not in the startTimes array, it is the + // during a test and should be included. If it is in the startTimes + // array, it is the beginning of a new test and the dt will be inflated. + // Therefore we skip those to exclude that dt and effectively reset dt + // calculations. + if (fast[i].dt > 0_s && + std::find(startTimes.begin(), startTimes.end(), fast[i].timestamp) == + startTimes.end()) { + m_timestepData.data.emplace_back( + (fast[i].timestamp).value(), + units::millisecond_t{fast[i].dt}.value()); + } + } + } + + auto minTime = + units::math::min(slow.front().timestamp, fast.front().timestamp); + m_timestepData.fitLine[0] = + ImPlotPoint{minTime.value(), units::millisecond_t{dtMean}.value()}; + + auto maxTime = units::math::max(slow.back().timestamp, fast.back().timestamp); + m_timestepData.fitLine[1] = + ImPlotPoint{maxTime.value(), units::millisecond_t{dtMean}.value()}; + + // RMSE = std::sqrt(sum((x_i - x^_i)^2) / N) where sum represents the sum of + // all time series points, x_i represents the velocity at a timestep, x^_i + // represents the prediction at the timestep, and N represents the number of + // points + m_RMSE = std::sqrt(simSquaredErrorSum / timeSeriesPoints); + m_accelRSquared = + 1 - m_RMSE / std::sqrt(squaredVariationSum / timeSeriesPoints); + FitPlots(); +} + +void AnalyzerPlot::FitPlots() { + // Set the "fit" flag to true. + m_quasistaticData.fitNextPlot = true; + m_dynamicData.fitNextPlot = true; + m_regressionData.fitNextPlot = true; + m_timestepData.fitNextPlot = true; +} + +double* AnalyzerPlot::GetSimRMSE() { + return &m_RMSE; +} + +double* AnalyzerPlot::GetSimRSquared() { + return &m_accelRSquared; +} + +static void PlotSimData(std::vector>& data) { + for (auto&& pts : data) { + ImPlot::SetNextLineStyle(IMPLOT_AUTO_COL, 1.5); + ImPlot::PlotLineG("Simulation", Getter, pts.data(), pts.size()); + } +} + +bool AnalyzerPlot::DisplayPlots() { + std::unique_lock lock(m_mutex, std::defer_lock); + + if (!lock.try_lock()) { + ImGui::Text("Loading %c", + "|/-\\"[static_cast(ImGui::GetTime() / 0.05f) & 3]); + return false; + } + + ImVec2 plotSize = ImGui::GetContentRegionAvail(); + + // Fit two plots horizontally + plotSize.x = (plotSize.x - ImGui::GetStyle().ItemSpacing.x) / 2.f; + + // Fit two plots vertically while leaving room for three text boxes + const float textBoxHeight = ImGui::GetFontSize() * 1.75; + plotSize.y = + (plotSize.y - textBoxHeight * 3 - ImGui::GetStyle().ItemSpacing.y) / 2.f; + + m_quasistaticData.Plot("Quasistatic Velocity vs. Time", plotSize, + m_velocityLabel.c_str(), m_pointSize); + ImGui::SameLine(); + m_dynamicData.Plot("Dynamic Velocity vs. Time", plotSize, + m_velocityLabel.c_str(), m_pointSize); + + m_regressionData.Plot("Acceleration vs. Velocity", plotSize, + m_velocityLabel.c_str(), m_velPortionAccelLabel.c_str(), + true, true, m_pointSize); + ImGui::SameLine(); + m_timestepData.Plot("Timesteps vs. Time", plotSize, "Time (s)", + "Timestep duration (ms)", true, false, m_pointSize, + [] { ImPlot::SetupAxisLimits(ImAxis_Y1, 0, 50); }); + + return true; +} + +AnalyzerPlot::FilteredDataVsTimePlot::FilteredDataVsTimePlot() { + rawData.reserve(kMaxSize); + filteredData.reserve(kMaxSize); + simData.reserve(kMaxSize); +} + +void AnalyzerPlot::FilteredDataVsTimePlot::Plot(const char* title, + const ImVec2& size, + const char* yLabel, + float pointSize) { + // Generate Sim vs Filtered Plot + if (fitNextPlot) { + ImPlot::SetNextAxesToFit(); + } + + if (ImPlot::BeginPlot(title, size)) { + ImPlot::SetupAxis(ImAxis_X1, "Time (s)", ImPlotAxisFlags_NoGridLines); + ImPlot::SetupAxis(ImAxis_Y1, yLabel, ImPlotAxisFlags_NoGridLines); + ImPlot::SetupLegend(ImPlotLocation_NorthEast); + + // Plot Raw Data + ImPlot::SetNextMarkerStyle(IMPLOT_AUTO, 1, IMPLOT_AUTO_COL, 0); + ImPlot::SetNextMarkerStyle(ImPlotStyleVar_MarkerSize, pointSize); + ImPlot::PlotScatterG("Raw Data", Getter, rawData.data(), rawData.size()); + + // Plot Filtered Data after Raw data + ImPlot::SetNextMarkerStyle(IMPLOT_AUTO, 1, IMPLOT_AUTO_COL, 0); + ImPlot::SetNextMarkerStyle(ImPlotStyleVar_MarkerSize, pointSize); + ImPlot::PlotScatterG("Filtered Data", Getter, filteredData.data(), + filteredData.size()); + + // Plot Simulation Data for Velocity Data + PlotSimData(simData); + + // Disable constant resizing + if (fitNextPlot) { + fitNextPlot = false; + } + + ImPlot::EndPlot(); + } +} + +void AnalyzerPlot::FilteredDataVsTimePlot::Clear() { + rawData.clear(); + filteredData.clear(); + simData.clear(); +} + +AnalyzerPlot::DataWithFitLinePlot::DataWithFitLinePlot() { + data.reserve(kMaxSize); +} + +void AnalyzerPlot::DataWithFitLinePlot::Plot(const char* title, + const ImVec2& size, + const char* xLabel, + const char* yLabel, bool fitX, + bool fitY, float pointSize, + std::function setup) { + if (fitNextPlot) { + if (fitX && fitY) { + ImPlot::SetNextAxesToFit(); + } else if (fitX && !fitY) { + ImPlot::SetNextAxisToFit(ImAxis_X1); + } else if (!fitX && fitY) { + ImPlot::SetNextAxisToFit(ImAxis_Y1); + } + } + + if (ImPlot::BeginPlot(title, size)) { + setup(); + ImPlot::SetupAxis(ImAxis_X1, xLabel, ImPlotAxisFlags_NoGridLines); + ImPlot::SetupAxis(ImAxis_Y1, yLabel, ImPlotAxisFlags_NoGridLines); + ImPlot::SetupLegend(ImPlotLocation_NorthEast); + + // Get a reference to the data that we are plotting. + ImPlot::SetNextMarkerStyle(IMPLOT_AUTO, 1, IMPLOT_AUTO_COL, 0); + ImPlot::SetNextMarkerStyle(ImPlotStyleVar_MarkerSize, pointSize); + ImPlot::PlotScatterG("Filtered Data", Getter, data.data(), data.size()); + + ImPlot::SetNextLineStyle(IMPLOT_AUTO_COL, 1.5); + ImPlot::PlotLineG("Fit", Getter, fitLine.data(), fitLine.size()); + + ImPlot::EndPlot(); + + if (fitNextPlot) { + fitNextPlot = false; + } + } +} + +void AnalyzerPlot::DataWithFitLinePlot::Clear() { + data.clear(); + + // Reset line of best fit + fitLine[0] = ImPlotPoint{0, 0}; + fitLine[1] = ImPlotPoint{0, 0}; +} diff --git a/sysid/src/main/native/cpp/view/JSONConverter.cpp b/sysid/src/main/native/cpp/view/JSONConverter.cpp new file mode 100644 index 00000000000..88eaa6a02f0 --- /dev/null +++ b/sysid/src/main/native/cpp/view/JSONConverter.cpp @@ -0,0 +1,64 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/analysis/JSONConverter.h" +#include "sysid/view/JSONConverter.h" + +#include + +#include +#include +#include + +#include "sysid/Util.h" + +using namespace sysid; + +void JSONConverter::DisplayConverter( + const char* tooltip, + std::function converter) { + if (ImGui::Button(tooltip)) { + m_opener = std::make_unique( + tooltip, "", std::vector{"JSON File", SYSID_PFD_JSON_EXT}); + } + + if (m_opener && m_opener->ready()) { + if (!m_opener->result().empty()) { + m_location = m_opener->result()[0]; + try { + converter(m_location, m_logger); + m_timestamp = wpi::Now() * 1E-6; + } catch (const std::exception& e) { + ImGui::OpenPopup("Exception Caught!"); + m_exception = e.what(); + } + } + m_opener.reset(); + } + + if (wpi::Now() * 1E-6 - m_timestamp < 5) { + ImGui::SameLine(); + ImGui::Text("Saved!"); + } + + // Handle exceptions. + ImGui::SetNextWindowSize(ImVec2(480.f, 0.0f)); + if (ImGui::BeginPopupModal("Exception Caught!")) { + ImGui::PushTextWrapPos(0.0f); + ImGui::Text( + "An error occurred when parsing the JSON. This most likely means that " + "the JSON data is incorrectly formatted."); + ImGui::TextColored(ImVec4(1.0f, 0.4f, 0.4f, 1.0f), "%s", + m_exception.c_str()); + ImGui::PopTextWrapPos(); + if (ImGui::Button("Close")) { + ImGui::CloseCurrentPopup(); + } + ImGui::EndPopup(); + } +} + +void JSONConverter::DisplayCSVConvert() { + DisplayConverter("Select SysId JSON", sysid::ToCSV); +} diff --git a/sysid/src/main/native/cpp/view/Logger.cpp b/sysid/src/main/native/cpp/view/Logger.cpp new file mode 100644 index 00000000000..5e7773dbd0f --- /dev/null +++ b/sysid/src/main/native/cpp/view/Logger.cpp @@ -0,0 +1,222 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "sysid/view/Logger.h" + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "sysid/Util.h" +#include "sysid/analysis/AnalysisType.h" +#include "sysid/view/UILayout.h" + +using namespace sysid; + +Logger::Logger(glass::Storage& storage, wpi::Logger& logger) + : m_logger{logger}, m_ntSettings{"sysid", storage} { + wpi::gui::AddEarlyExecute([&] { m_ntSettings.Update(); }); + + m_ntSettings.EnableServerOption(false); +} + +void Logger::Display() { + // Get the current width of the window. This will be used to scale + // our UI elements. + float width = ImGui::GetContentRegionAvail().x; + + // Add team number input and apply button for NT connection. + m_ntSettings.Display(); + + // Reset and clear the internal manager state. + ImGui::SameLine(); + if (ImGui::Button("Reset Telemetry")) { + m_settings = TelemetryManager::Settings{}; + m_manager = std::make_unique(m_settings, m_logger); + m_settings.mechanism = analysis::FromName(kTypes[m_selectedType]); + } + + // Add NT connection indicator. + static ImVec4 kColorDisconnected{1.0f, 0.4f, 0.4f, 1.0f}; + static ImVec4 kColorConnected{0.2f, 1.0f, 0.2f, 1.0f}; + ImGui::SameLine(); + bool ntConnected = nt::NetworkTableInstance::GetDefault().IsConnected(); + ImGui::TextColored(ntConnected ? kColorConnected : kColorDisconnected, + ntConnected ? "NT Connected" : "NT Disconnected"); + + // Create a Section for project configuration + ImGui::Separator(); + ImGui::Spacing(); + ImGui::Text("Project Parameters"); + + // Add a dropdown for mechanism type. + ImGui::SetNextItemWidth(ImGui::GetFontSize() * kTextBoxWidthMultiple); + + if (ImGui::Combo("Mechanism", &m_selectedType, kTypes, + IM_ARRAYSIZE(kTypes))) { + m_settings.mechanism = analysis::FromName(kTypes[m_selectedType]); + } + + // Add Dropdown for Units + ImGui::SetNextItemWidth(ImGui::GetFontSize() * kTextBoxWidthMultiple); + if (ImGui::Combo("Unit Type", &m_selectedUnit, kUnits, + IM_ARRAYSIZE(kUnits))) { + m_settings.units = kUnits[m_selectedUnit]; + } + + sysid::CreateTooltip( + "This is the type of units that your gains will be in. For example, if " + "you want your flywheel gains in terms of radians, then use the radians " + "unit. On the other hand, if your drivetrain will use gains in meters, " + "choose meters."); + + // Rotational units have fixed Units per rotations + m_isRotationalUnits = + (m_settings.units == "Rotations" || m_settings.units == "Degrees" || + m_settings.units == "Radians"); + if (m_settings.units == "Degrees") { + m_settings.unitsPerRotation = 360.0; + } else if (m_settings.units == "Radians") { + m_settings.unitsPerRotation = 2 * std::numbers::pi; + } else if (m_settings.units == "Rotations") { + m_settings.unitsPerRotation = 1.0; + } + + // Units Per Rotations entry + ImGui::SetNextItemWidth(ImGui::GetFontSize() * kTextBoxWidthMultiple); + ImGui::InputDouble("Units Per Rotation", &m_settings.unitsPerRotation, 0.0f, + 0.0f, "%.4f", + m_isRotationalUnits ? ImGuiInputTextFlags_ReadOnly + : ImGuiInputTextFlags_None); + sysid::CreateTooltip( + "The logger assumes that the code will be sending recorded motor shaft " + "rotations over NetworkTables. This value will then be multiplied by the " + "units per rotation to get the measurement in the units you " + "specified.\n\nFor non-rotational units (e.g. meters), this value is " + "usually the wheel diameter times pi (should not include gearing)."); + // Create a section for voltage parameters. + ImGui::Separator(); + ImGui::Spacing(); + ImGui::Text("Voltage Parameters"); + + auto CreateVoltageParameters = [this](const char* text, double* data, + float min, float max) { + ImGui::SetNextItemWidth(ImGui::GetFontSize() * 6); + ImGui::PushItemFlag(ImGuiItemFlags_Disabled, + m_manager && m_manager->IsActive()); + float value = static_cast(*data); + if (ImGui::SliderFloat(text, &value, min, max, "%.2f")) { + *data = value; + } + ImGui::PopItemFlag(); + }; + + CreateVoltageParameters("Quasistatic Ramp Rate (V/s)", + &m_settings.quasistaticRampRate, 0.10f, 0.60f); + sysid::CreateTooltip( + "This is the rate at which the voltage will increase during the " + "quasistatic test."); + + CreateVoltageParameters("Dynamic Step Voltage (V)", &m_settings.stepVoltage, + 0.0f, 10.0f); + sysid::CreateTooltip( + "This is the voltage that will be applied for the " + "dynamic voltage (acceleration) tests."); + + // Create a section for tests. + ImGui::Separator(); + ImGui::Spacing(); + ImGui::Text("Tests"); + + auto CreateTest = [this, width](const char* text, const char* itext) { + // Display buttons if we have an NT connection. + if (nt::NetworkTableInstance::GetDefault().IsConnected()) { + // Create button to run tests. + if (ImGui::Button(text)) { + // Open the warning message. + ImGui::OpenPopup("Warning"); + m_manager->BeginTest(itext); + m_opened = text; + } + if (m_opened == text && ImGui::BeginPopupModal("Warning")) { + ImGui::TextWrapped("%s", m_popupText.c_str()); + if (ImGui::Button(m_manager->IsActive() ? "End Test" : "Close")) { + m_manager->EndTest(); + ImGui::CloseCurrentPopup(); + m_opened = ""; + } + ImGui::EndPopup(); + } + } else { + // Show disabled text when there is no connection. + ImGui::TextDisabled("%s", text); + } + + // Show whether the tests were run or not. + bool run = m_manager->HasRunTest(itext); + ImGui::SameLine(width * 0.7); + ImGui::Text(run ? "Run" : "Not Run"); + }; + + CreateTest("Quasistatic Forward", "slow-forward"); + CreateTest("Quasistatic Backward", "slow-backward"); + CreateTest("Dynamic Forward", "fast-forward"); + CreateTest("Dynamic Backward", "fast-backward"); + + m_manager->RegisterDisplayCallback( + [this](const auto& str) { m_popupText = str; }); + + // Display the path to where the JSON will be saved and a button to select the + // location. + ImGui::Separator(); + ImGui::Spacing(); + ImGui::Text("Save Location"); + if (ImGui::Button("Choose")) { + m_selector = std::make_unique("Select Folder"); + } + ImGui::SameLine(); + ImGui::InputText("##savelocation", &m_jsonLocation, + ImGuiInputTextFlags_ReadOnly); + + // Add button to save. + ImGui::SameLine(width * 0.9); + if (ImGui::Button("Save")) { + try { + m_manager->SaveJSON(m_jsonLocation); + } catch (const std::exception& e) { + ImGui::OpenPopup("Exception Caught!"); + m_exception = e.what(); + } + } + + // Handle exceptions. + if (ImGui::BeginPopupModal("Exception Caught!")) { + ImGui::Text("%s", m_exception.c_str()); + if (ImGui::Button("Close")) { + ImGui::CloseCurrentPopup(); + } + ImGui::EndPopup(); + } + + // Run periodic methods. + SelectDataFolder(); + m_ntSettings.Update(); + m_manager->Update(); +} + +void Logger::SelectDataFolder() { + // If the selector exists and is ready with a result, we can store it. + if (m_selector && m_selector->ready()) { + m_jsonLocation = m_selector->result(); + m_selector.reset(); + } +} diff --git a/sysid/src/main/native/include/sysid/Util.h b/sysid/src/main/native/include/sysid/Util.h new file mode 100644 index 00000000000..38cf8b2e42f --- /dev/null +++ b/sysid/src/main/native/include/sysid/Util.h @@ -0,0 +1,89 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include +#include +#include + +// The generated AppleScript by portable-file-dialogs for just *.json does not +// work correctly because it is a uniform type identifier. This means that +// "public." needs to be prepended to it. +#ifdef __APPLE__ +#define SYSID_PFD_JSON_EXT "*.public.json" +#else +#define SYSID_PFD_JSON_EXT "*.json" +#endif + +#ifdef _WIN32 +#define LAUNCH "gradlew" +#define LAUNCH_DETACHED "start /b gradlew" +#define DETACHED_SUFFIX "" +#else +#define LAUNCH "./gradlew" +#define LAUNCH_DETACHED "./gradlew" +#define DETACHED_SUFFIX "&" +#endif + +// Based on https://gcc.gnu.org/onlinedocs/cpp/Stringizing.html +#define EXPAND_STRINGIZE(s) STRINGIZE(s) +#define STRINGIZE(s) #s + +namespace sysid { +static constexpr const char* kUnits[] = {"Meters", "Feet", "Inches", + "Radians", "Rotations", "Degrees"}; + +/** + * Displays a tooltip beside the widget that this method is called after with + * the provided text. + * + * @param text The text to show in the tooltip. + */ +void CreateTooltip(const char* text); + +/** + * Utility function to launch an error popup if an exception is detected. + * + * @param isError True if an exception is detected + * @param errorMessage The error message associated with the exception + */ +void CreateErrorPopup(bool& isError, std::string_view errorMessage); + +/** + * Returns the abbreviation for the unit. + * + * @param unit The unit to return the abbreviation for. + * @return The abbreviation for the unit. + */ +std::string_view GetAbbreviation(std::string_view unit); + +/** + * Saves a file with the provided contents to a specified location. + * + * @param contents The file contents. + * @param path The file location. + */ +void SaveFile(std::string_view contents, const std::filesystem::path& path); + +/** + * Concatenates all the arrays passed as arguments and returns the result. + * + * @tparam Type The array element type. + * @tparam Sizes The array sizes. + * @param arrays Parameter pack of arrays to concatenate. + */ +template +constexpr auto ArrayConcat(const std::array&... arrays) { + std::array result; + size_t index = 0; + + ((std::copy_n(arrays.begin(), Sizes, result.begin() + index), index += Sizes), + ...); + + return result; +} +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/AnalysisManager.h b/sysid/src/main/native/include/sysid/analysis/AnalysisManager.h new file mode 100644 index 00000000000..d572578b011 --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/AnalysisManager.h @@ -0,0 +1,358 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "sysid/analysis/AnalysisType.h" +#include "sysid/analysis/FeedbackAnalysis.h" +#include "sysid/analysis/FeedbackControllerPreset.h" +#include "sysid/analysis/FeedforwardAnalysis.h" +#include "sysid/analysis/Storage.h" + +namespace sysid { + +/** + * Manages analysis of data. Each instance of this class represents a JSON file + * that is read from storage. + */ +class AnalysisManager { + public: + /** + * Represents settings for an instance of the analysis manager. This contains + * information about the feedback controller preset, loop type, motion + * threshold, acceleration window size, LQR parameters, and the selected + * dataset. + */ + struct Settings { + enum class DrivetrainDataset { kCombined = 0, kLeft = 1, kRight = 2 }; + /** + * The feedback controller preset used to calculate gains. + */ + FeedbackControllerPreset preset = presets::kDefault; + + /** + * The feedback controller loop type (position or velocity). + */ + FeedbackControllerLoopType type = FeedbackControllerLoopType::kVelocity; + + /** + * LQR parameters used for feedback gain calculation. + */ + LQRParameters lqr{1, 1.5, 7}; + + /** + * The motion threshold (units/s) for trimming quasistatic test data. + */ + double motionThreshold = 0.2; + + /** + * The window size for the median filter. + */ + int medianWindow = 1; + + /** + * The duration of the dynamic test that should be considered. A value of + * zero indicates it needs to be set to the default. + */ + units::second_t stepTestDuration = 0_s; + + /** + * The conversion factor of counts per revolution. + */ + int cpr = 1440; + + /** + * The conversion factor of gearing. + */ + double gearing = 1; + + /** + * Whether or not the gains should be in the encoder's units (mainly for use + * in a smart motor controller). + */ + bool convertGainsToEncTicks = false; + + DrivetrainDataset dataset = DrivetrainDataset::kCombined; + }; + + /** + * Stores feedforward. + */ + struct FeedforwardGains { + /** + * Stores the Feedforward gains. + */ + std::tuple, double, double> ffGains; + + /** + * Stores the trackwidth for angular drivetrain tests. + */ + std::optional trackWidth; + }; + + /** + * Exception for File Reading Errors. + */ + struct FileReadingError : public std::exception { + /** + * Creates a FileReadingError object + * + * @param path The path of the file attempted to open + */ + explicit FileReadingError(std::string_view path) { + msg = fmt::format("Unable to read: {}", path); + } + + /** + * The path of the file that was opened. + */ + std::string msg; + const char* what() const noexcept override { return msg.c_str(); } + }; + + /** + * The keys (which contain sysid data) that are in the JSON to analyze. + */ + static constexpr const char* kJsonDataKeys[] = { + "slow-forward", "slow-backward", "fast-forward", "fast-backward"}; + + /** + * Concatenates a list of vectors. The contents of the source vectors are + * copied (not moved) into the new vector. Also sorts the datapoints by + * timestamp to assist with future simulation. + * + * @param sources The source vectors. + * @return The concatenated vector + */ + template + static std::vector DataConcat(const Sources&... sources) { + std::vector result; + (result.insert(result.end(), sources.begin(), sources.end()), ...); + + // Sort data by timestamp to remove the possibility of negative dts in + // future simulations. + std::sort(result.begin(), result.end(), [](const auto& a, const auto& b) { + return a.timestamp < b.timestamp; + }); + + return result; + } + + /** + * Constructs an instance of the analysis manager for theoretical analysis, + * containing settings and gains but no data. + * + * @param settings The settings for this instance of the analysis manager. + * @param logger The logger instance to use for log data. + */ + AnalysisManager(Settings& settings, wpi::Logger& logger); + + /** + * Constructs an instance of the analysis manager with the given path (to the + * JSON) and analysis manager settings. + * + * @param path The path to the JSON containing the sysid data. + * @param settings The settings for this instance of the analysis manager. + * @param logger The logger instance to use for log data. + */ + AnalysisManager(std::string_view path, Settings& settings, + wpi::Logger& logger); + + /** + * Prepares data from the JSON and stores the output in Storage member + * variables. + */ + void PrepareData(); + + /** + * Calculates the gains with the latest data (from the pointers in the + * settings struct that this instance was constructed with). + * + * @return The latest feedforward gains and trackwidth (if needed). + */ + FeedforwardGains CalculateFeedforward(); + + /** + * Calculates feedback gains from the given feedforward gains. + * + * @param ff The feedforward gains. + * @return The calculated feedback gains. + */ + FeedbackGains CalculateFeedback(std::vector ff); + + /** + * Overrides the units in the JSON with the user-provided ones. + * + * @param unit The unit to output gains in. + * @param unitsPerRotation The conversion factor between rotations and the + * selected unit. + */ + void OverrideUnits(std::string_view unit, double unitsPerRotation); + + /** + * Resets the units back to those defined in the JSON. + */ + void ResetUnitsFromJSON(); + + /** + * Returns the analysis type of the current instance (read from the JSON). + * + * @return The analysis type. + */ + const AnalysisType& GetAnalysisType() const { return m_type; } + + /** + * Returns the units of analysis. + * + * @return The units of analysis. + */ + std::string_view GetUnit() const { return m_unit; } + + /** + * Returns the factor (a.k.a. units per rotation) for analysis. + * + * @return The factor (a.k.a. units per rotation) for analysis. + */ + double GetFactor() const { return m_factor; } + + /** + * Returns a reference to the iterator of the currently selected raw datset. + * Unfortunately, due to ImPlot internals, the reference cannot be const so + * the user should be careful not to change any data. + * + * @return A reference to the raw internal data. + */ + Storage& GetRawData() { + return m_rawDataset[static_cast(m_settings.dataset)]; + } + + /** + * Returns a reference to the iterator of the currently selected filtered + * datset. Unfortunately, due to ImPlot internals, the reference cannot be + * const so the user should be careful not to change any data. + * + * @return A reference to the filtered internal data. + */ + Storage& GetFilteredData() { + return m_filteredDataset[static_cast(m_settings.dataset)]; + } + + /** + * Returns the original dataset. + * + * @return The original (untouched) dataset + */ + Storage& GetOriginalData() { + return m_originalDataset[static_cast(m_settings.dataset)]; + } + + /** + * Returns the minimum duration of the Step Voltage Test of the currently + * stored data. + * + * @return The minimum step test duration. + */ + units::second_t GetMinStepTime() const { return m_minStepTime; } + + /** + * Returns the maximum duration of the Step Voltage Test of the currently + * stored data. + * + * @return Maximum step test duration + */ + units::second_t GetMaxStepTime() const { return m_maxStepTime; } + + /** + * Returns the estimated time delay of the measured position, including + * CAN delays. + * + * @return Position delay in milliseconds + */ + units::millisecond_t GetPositionDelay() const { + return std::accumulate(m_positionDelays.begin(), m_positionDelays.end(), + 0_s) / + m_positionDelays.size(); + } + + /** + * Returns the estimated time delay of the measured velocity, including + * CAN delays. + * + * @return Velocity delay in milliseconds + */ + units::millisecond_t GetVelocityDelay() const { + return std::accumulate(m_velocityDelays.begin(), m_velocityDelays.end(), + 0_s) / + m_positionDelays.size(); + } + + /** + * Returns the different start times of the recorded tests. + * + * @return The start times for each test + */ + const std::array& GetStartTimes() const { + return m_startTimes; + } + + bool HasData() const { + return !m_originalDataset[static_cast( + Settings::DrivetrainDataset::kCombined)] + .empty(); + } + + private: + wpi::Logger& m_logger; + + // This is used to store the various datasets (i.e. Combined, Forward, + // Backward, etc.) + wpi::json m_json; + + std::array m_originalDataset; + std::array m_rawDataset; + std::array m_filteredDataset; + + // Stores the various start times of the different tests. + std::array m_startTimes; + + // The settings for this instance. This contains pointers to the feedback + // controller preset, LQR parameters, acceleration window size, etc. + Settings& m_settings; + + // Miscellaneous data from the JSON -- the analysis type, the units, and the + // units per rotation. + AnalysisType m_type; + std::string m_unit; + double m_factor; + + units::second_t m_minStepTime{0}; + units::second_t m_maxStepTime{std::numeric_limits::infinity()}; + std::vector m_positionDelays; + std::vector m_velocityDelays; + + // Stores an optional track width if we are doing the drivetrain angular test. + std::optional m_trackWidth; + + void PrepareGeneralData(); + + void PrepareAngularDrivetrainData(); + + void PrepareLinearDrivetrainData(); +}; +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/AnalysisType.h b/sysid/src/main/native/include/sysid/analysis/AnalysisType.h new file mode 100644 index 00000000000..7feedb3f51a --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/AnalysisType.h @@ -0,0 +1,63 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include + +namespace sysid { + +/** + * Stores the type of Analysis and relevant information about the analysis. + */ +struct AnalysisType { + /** + * The number of independent variables for feedforward analysis. + */ + size_t independentVariables; + + /** + * The number of fields in the raw data within the mechanism's JSON. + */ + size_t rawDataSize; + + /** + * Display name for the analysis type. + */ + const char* name; + + /** + * Compares equality of two AnalysisType structs. + * + * @param rhs Another AnalysisType + * @return True if the two analysis types are equal + */ + constexpr bool operator==(const AnalysisType& rhs) const { + return std::string_view{name} == rhs.name && + independentVariables == rhs.independentVariables && + rawDataSize == rhs.rawDataSize; + } + + /** + * Compares inequality of two AnalysisType structs. + * + * @param rhs Another AnalysisType + * @return True if the two analysis types are not equal + */ + constexpr bool operator!=(const AnalysisType& rhs) const { + return !operator==(rhs); + } +}; + +namespace analysis { +constexpr AnalysisType kDrivetrain{3, 9, "Drivetrain"}; +constexpr AnalysisType kDrivetrainAngular{3, 9, "Drivetrain (Angular)"}; +constexpr AnalysisType kElevator{4, 4, "Elevator"}; +constexpr AnalysisType kArm{5, 4, "Arm"}; +constexpr AnalysisType kSimple{3, 4, "Simple"}; + +AnalysisType FromName(std::string_view name); +} // namespace analysis +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/ArmSim.h b/sysid/src/main/native/include/sysid/analysis/ArmSim.h new file mode 100644 index 00000000000..af6c10e5a34 --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/ArmSim.h @@ -0,0 +1,79 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include + +namespace sysid { +/** + * Simulation of an Arm mechanism based off of a model from SysId Feedforward + * gains. + */ +class ArmSim { + public: + /** + * @param Ks Static friction gain. + * @param Kv Velocity gain. + * @param Ka Acceleration gain. + * @param Kg Gravity cosine gain. + * @param offset Arm position offset. + * @param initialPosition Initial arm position. + * @param initialVelocity Initial arm velocity. + */ + ArmSim(double Ks, double Kv, double Ka, double Kg, double offset = 0.0, + double initialPosition = 0.0, double initialVelocity = 0.0); + + /** + * Simulates affine state-space system: + * dx/dt = Ax + Bu + c sgn(x) + d cos(theta) + * forward dt seconds. + * + * @param voltage Voltage to apply over the timestep. + * @param dt Sammple period. + */ + void Update(units::volt_t voltage, units::second_t dt); + + /** + * Returns the position. + * + * @return The current position + */ + double GetPosition() const; + + /** + * Returns the velocity. + * + * @return The current velocity + */ + double GetVelocity() const; + + /** + * Returns the acceleration for the current state and given input. + * + * @param voltage The voltage that is being applied to the mechanism / input + * @return The acceleration given the state and input + */ + double GetAcceleration(units::volt_t voltage) const; + + /** + * Resets model position and velocity. + * + * @param position The position the mechanism should be reset to + * @param velocity The velocity the mechanism should be reset to + */ + void Reset(double position = 0.0, double velocity = 0.0); + + private: + Eigen::Matrix m_A; + Eigen::Matrix m_B; + Eigen::Vector m_c; + Eigen::Vector m_d; + Eigen::Vector m_x; + double m_offset; +}; + +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/ElevatorSim.h b/sysid/src/main/native/include/sysid/analysis/ElevatorSim.h new file mode 100644 index 00000000000..2d0c5f68c8b --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/ElevatorSim.h @@ -0,0 +1,76 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include + +namespace sysid { +/** + * Simulation of an Elevator mechanism based off of a model from SysId + * Feedforward gains. + */ +class ElevatorSim { + public: + /** + * @param Ks Static friction gain. + * @param Kv Velocity gain. + * @param Ka Acceleration gain. + * @param Kg Gravity gain. + * @param initialPosition Initial elevator position. + * @param initialVelocity Initial elevator velocity. + */ + ElevatorSim(double Ks, double Kv, double Ka, double Kg, + double initialPosition = 0.0, double initialVelocity = 0.0); + + /** + * Simulates affine state-space system dx/dt = Ax + Bu + c sgn(x) + d forward + * dt seconds. + * + * @param voltage Voltage to apply over the timestep. + * @param dt Sammple period. + */ + void Update(units::volt_t voltage, units::second_t dt); + + /** + * Returns the position. + * + * @return The current position + */ + double GetPosition() const; + + /** + * Returns the velocity. + * + * @return The current velocity + */ + double GetVelocity() const; + + /** + * Returns the acceleration for the current state and given input. + * + * @param voltage The voltage that is being applied to the mechanism / input + * @return The acceleration given the state and input + */ + double GetAcceleration(units::volt_t voltage) const; + + /** + * Resets model position and velocity. + * + * @param position The position the mechanism should be reset to + * @param velocity The velocity the mechanism should be reset to + */ + void Reset(double position = 0.0, double velocity = 0.0); + + private: + Eigen::Matrix m_A; + Eigen::Matrix m_B; + Eigen::Vector m_c; + Eigen::Vector m_d; + Eigen::Vector m_x; +}; + +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/FeedbackAnalysis.h b/sysid/src/main/native/include/sysid/analysis/FeedbackAnalysis.h new file mode 100644 index 00000000000..51754a241d4 --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/FeedbackAnalysis.h @@ -0,0 +1,80 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +namespace sysid { + +struct FeedbackControllerPreset; + +/** + * Represents parameters used to calculate optimal feedback gains using a + * linear-quadratic regulator (LQR). + */ +struct LQRParameters { + /** + * The maximum allowable deviation in position. + */ + double qp; + + /** + * The maximum allowable deviation in velocity. + */ + double qv; + + /** + * The maximum allowable control effort. + */ + double r; +}; + +/** + * Stores feedback controller gains. + */ +struct FeedbackGains { + /** + * The calculated Proportional gain + */ + double Kp; + + /** + * The calculated Derivative gain + */ + double Kd; +}; + +/** + * Calculates position feedback gains for the given controller preset, LQR + * controller gain parameters and feedforward gains. + * + * @param preset The feedback controller preset. + * @param params The parameters for calculating optimal feedback + * gains. + * @param Kv Velocity feedforward gain. + * @param Ka Acceleration feedforward gain. + * @param encFactor The factor to convert the gains from output units to + * encoder units. This is usually encoder EPR * gearing + * * units per rotation. + */ +FeedbackGains CalculatePositionFeedbackGains( + const FeedbackControllerPreset& preset, const LQRParameters& params, + double Kv, double Ka, double encFactor = 1.0); + +/** + * Calculates velocity feedback gains for the given controller preset, LQR + * controller gain parameters and feedforward gains. + * + * @param preset The feedback controller preset. + * @param params The parameters for calculating optimal feedback + * gains. + * @param Kv Velocity feedforward gain. + * @param Ka Acceleration feedforward gain. + * @param encFactor The factor to convert the gains from output units to + * encoder units. This is usually encoder EPR * gearing + * * units per rotation. + */ +FeedbackGains CalculateVelocityFeedbackGains( + const FeedbackControllerPreset& preset, const LQRParameters& params, + double Kv, double Ka, double encFactor = 1.0); +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/FeedbackControllerPreset.h b/sysid/src/main/native/include/sysid/analysis/FeedbackControllerPreset.h new file mode 100644 index 00000000000..4b13c6c38f0 --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/FeedbackControllerPreset.h @@ -0,0 +1,164 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include + +namespace sysid { +/** + * Represents a preset for a specific feedback controller. This includes info + * about the max controller output, the controller period, whether the gains + * are time-normalized, and whether there are measurement delays from sensors or + * onboard filtering. + */ +struct FeedbackControllerPreset { + /** + * The conversion factor between volts and the final controller output. + */ + double outputConversionFactor; + + /** + * The conversion factor for using controller output for velocity gains. This + * is necessary as some controllers do velocity controls with different time + * units. + */ + double outputVelocityTimeFactor; + + /** + * The period at which the controller runs. + */ + units::millisecond_t period; + + /** + * Whether the controller gains are time-normalized. + */ + bool normalized; + + /** + * The measurement delay in the encoder measurements. + */ + units::millisecond_t measurementDelay; + + /** + * Checks equality between two feedback controller presets. + * + * @param rhs Another FeedbackControllerPreset + * @return If the two presets are equal + */ + constexpr bool operator==(const FeedbackControllerPreset& rhs) const { + return outputConversionFactor == rhs.outputConversionFactor && + outputVelocityTimeFactor == rhs.outputVelocityTimeFactor && + period == rhs.period && normalized == rhs.normalized && + measurementDelay == rhs.measurementDelay; + } + + /** + * Checks inequality between two feedback controller presets. + * + * @param rhs Another FeedbackControllerPreset + * @return If the two presets are not equal + */ + constexpr bool operator!=(const FeedbackControllerPreset& rhs) const { + return !operator==(rhs); + } +}; + +/** + * The loop type for the feedback controller. + */ +enum class FeedbackControllerLoopType { kPosition, kVelocity }; + +namespace presets { +constexpr FeedbackControllerPreset kDefault{1.0, 1.0, 20_ms, true, 0_s}; + +constexpr FeedbackControllerPreset kWPILibNew{kDefault}; +constexpr FeedbackControllerPreset kWPILibOld{1.0 / 12.0, 1.0, 50_ms, false, + 0_s}; + +// Measurement delay from a moving average filter: +// +// A moving average filter with a window size of N is an FIR filter with N taps. +// The average delay of a moving average filter with N taps and a period between +// samples of T is (N - 1)/2 T. +// +// Proof: +// N taps with delays of 0 .. (N - 1) T +// +// average delay = (sum 0 .. N - 1) / N T +// = (sum 1 .. N - 1) / N T +// +// note: sum 1 .. n = n(n + 1) / 2 +// +// = (N - 1)((N - 1) + 1) / (2N) T +// = (N - 1)N / (2N) T +// = (N - 1)/2 T + +// Measurement delay from a backward finite difference: +// +// Velocities calculated via a backward finite difference with a period of T +// look like: +// +// velocity = (position at timestep k - position at timestep k-1) / T +// +// The average delay is T / 2. +// +// Proof: +// average delay = (0 ms + T) / 2 +// = T / 2 + +/** + * https://phoenix-documentation.readthedocs.io/en/latest/ch14_MCSensor.html#changing-velocity-measurement-parameters + * + * Backward finite difference delay = 100 ms / 2 = 50 ms. + * + * 64-tap moving average delay = (64 - 1) / 2 * 1 ms = 31.5 ms. + * + * Total delay = 50 ms + 31.5 ms = 81.5 ms. + */ +constexpr FeedbackControllerPreset kCTRECANCoder{1.0 / 12.0, 60.0, 1_ms, true, + 81.5_ms}; +constexpr FeedbackControllerPreset kCTREDefault{1023.0 / 12.0, 0.1, 1_ms, false, + 81.5_ms}; +/** + * https://api.ctr-electronics.com/phoenixpro/release/cpp/classctre_1_1phoenixpro_1_1hardware_1_1core_1_1_core_c_a_ncoder.html#a718a1a214b58d3c4543e88e3cb51ade5 + * + * Phoenix Pro uses standard units and Voltage output. This means the output + * is 1.0, time factor is 1.0, and closed loop operates at 1 millisecond. All + * Pro devices make use of Kalman filters default-tuned to lowest latency, which + * in testing is roughly 1 millisecond + */ +constexpr FeedbackControllerPreset kCTREProDefault{1.0, 1.0, 1_ms, true, 1_ms}; + +/** + * https://github.com/wpilibsuite/sysid/issues/258#issuecomment-1010658237 + * + * 8-sample moving average with 32 ms between samples. + * + * Total delay = 8-tap moving average delay = (8 - 1) / 2 * 32 ms = 112 ms. + */ +constexpr FeedbackControllerPreset kREVNEOBuiltIn{1.0 / 12.0, 60.0, 1_ms, false, + 112_ms}; + +/** + * https://www.revrobotics.com/content/sw/max/sw-docs/cpp/classrev_1_1_c_a_n_encoder.html#a7e6ce792bc0c0558fb944771df572e6a + * + * Backward finite difference delay = 100 ms / 2 = 50 ms. + * + * 64-tap moving average delay = (64 - 1) / 2 * 1 ms = 31.5 ms. + * + * Total delay = 50 ms + 31.5 ms = 81.5 ms. + */ +constexpr FeedbackControllerPreset kREVNonNEO{1.0 / 12.0, 60.0, 1_ms, false, + 81.5_ms}; + +/** + * https://github.com/wpilibsuite/sysid/pull/138#issuecomment-841734229 + * + * Backward finite difference delay = 10 ms / 2 = 5 ms. + */ +constexpr FeedbackControllerPreset kVenom{4096.0 / 12.0, 60.0, 1_ms, false, + 5_ms}; +} // namespace presets +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/FeedforwardAnalysis.h b/sysid/src/main/native/include/sysid/analysis/FeedforwardAnalysis.h new file mode 100644 index 00000000000..fc9e47c185b --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/FeedforwardAnalysis.h @@ -0,0 +1,25 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include + +#include "sysid/analysis/AnalysisType.h" +#include "sysid/analysis/Storage.h" + +namespace sysid { + +/** + * Calculates feedforward gains given the data and the type of analysis to + * perform. + * + * @return Tuple containing the coefficients of the analysis along with the + * r-squared (coefficient of determination) and RMSE (standard deviation + * of the residuals) of the fit. + */ +std::tuple, double, double> CalculateFeedforwardGains( + const Storage& data, const AnalysisType& type); +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/FilteringUtils.h b/sysid/src/main/native/include/sysid/analysis/FilteringUtils.h new file mode 100644 index 00000000000..5884b3f2d01 --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/FilteringUtils.h @@ -0,0 +1,209 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "sysid/analysis/AnalysisManager.h" +#include "sysid/analysis/Storage.h" + +namespace sysid { + +constexpr int kNoiseMeanWindow = 9; + +/** + * Exception for Invalid Data Errors in which we can't pin the cause of error to + * any one specific setting of the GUI. + */ +struct InvalidDataError : public std::exception { + /** + * Creates an InvalidDataError Exception. It adds additional steps after the + * initial error message to inform users in the ways that they could fix their + * data. + * + * @param message The error message + */ + explicit InvalidDataError(std::string_view message) { + m_message = fmt::format( + "{}. Please verify that your units and data is reasonable and then " + "adjust your motion threshold, test duration, and/or window size to " + "try to fix this issue.", + message); + } + + /** + * Stores the error message + */ + std::string m_message; + const char* what() const noexcept override { return m_message.c_str(); } +}; + +/** + * Exception for Quasistatic Data being completely removed. + */ +struct NoQuasistaticDataError : public std::exception { + const char* what() const noexcept override { + return "Quasistatic test trimming removed all data. Please adjust your " + "motion threshold and double check " + "your units and test data to make sure that the robot is reporting " + "reasonable values."; + } +}; + +/** + * Exception for Dynamic Data being completely removed. + */ +struct NoDynamicDataError : public std::exception { + const char* what() const noexcept override { + return "Dynamic test trimming removed all data. Please adjust your test " + "duration and double check " + "your units and test data to make sure that the robot is reporting " + "reasonable values."; + } +}; + +/** + * Calculates the expected acceleration noise to be used as the floor of the + * Voltage Trim. This is done by taking the standard deviation from the moving + * average values of each point. + * + * @param data the prepared data vector containing acceleration data + * @param window the size of the window for the moving average + * @param accessorFunction a function that accesses the desired data from the + * PreparedData struct. + * @return The expected acceleration noise + */ +double GetNoiseFloor( + const std::vector& data, int window, + std::function accessorFunction); + +/** + * Reduces noise in velocity data by applying a median filter. + * + * @tparam S The size of the raw data array + * @tparam Velocity The index of the velocity entry in the raw data. + * @param data the vector of arrays representing sysid data (must contain + * velocity data) + * @param window the size of the window of the median filter (must be odd) + */ +void ApplyMedianFilter(std::vector* data, int window); + +/** + * Trims the step voltage data to discard all points before the maximum + * acceleration and after reaching stead-state velocity. Also trims the end of + * the test based off of user specified test durations, but it will determine a + * default duration if the requested duration is less than the minimum step test + * duration. + * + * @param data A pointer to the step voltage data. + * @param settings A pointer to the settings of an analysis manager object. + * @param minStepTime The current minimum step test duration as one of the + * trimming procedures will remove this amount from the start + * of the test. + * @param maxStepTime The maximum step test duration. + * @return The updated minimum step test duration. + */ +std::tuple +TrimStepVoltageData(std::vector* data, + AnalysisManager::Settings* settings, + units::second_t minStepTime, units::second_t maxStepTime); + +/** + * Compute the mean time delta of the given data. + * + * @param data A reference to all of the collected PreparedData + * @return The mean time delta for all the data points + */ +units::second_t GetMeanTimeDelta(const std::vector& data); + +/** + * Compute the mean time delta of the given data. + * + * @param data A reference to all of the collected PreparedData + * @return The mean time delta for all the data points + */ +units::second_t GetMeanTimeDelta(const Storage& data); + +/** + * Creates a central finite difference filter that computes the nth + * derivative of the input given the specified number of samples. + * + * Since this requires data from the future, it should only be used in offline + * filtering scenarios. + * + * For example, a first derivative filter that uses two samples and a sample + * period of 20 ms would be + * + *

+ * CentralFiniteDifference<1, 2>(20_ms);
+ * 
+ * + * @tparam Derivative The order of the derivative to compute. + * @tparam Samples The number of samples to use to compute the given + * derivative. This must be odd and one more than the order + * of derivative or higher. + * @param period The period in seconds between samples taken by the user. + */ +template +frc::LinearFilter CentralFiniteDifference(units::second_t period) { + static_assert(Samples % 2 != 0, "Number of samples must be odd."); + + // Generate stencil points from -(samples - 1)/2 to (samples - 1)/2 + wpi::array stencil{wpi::empty_array}; + for (int i = 0; i < Samples; ++i) { + stencil[i] = -(Samples - 1) / 2 + i; + } + + return frc::LinearFilter::FiniteDifference( + stencil, period); +} + +/** + * Trims the quasistatic tests, applies a median filter to the velocity data, + * calculates acceleration and cosine (arm only) data, and trims the dynamic + * tests. + * + * @param data A pointer to a data vector recently created by the + * ConvertToPrepared method + * @param settings A reference to the analysis settings + * @param positionDelays A reference to the vector of computed position signal + * delays. + * @param velocityDelays A reference to the vector of computed velocity signal + * delays. + * @param minStepTime A reference to the minimum dynamic test duration as one of + * the trimming procedures will remove this amount from the + * start of the test. + * @param maxStepTime A reference to the maximum dynamic test duration + * @param unit The angular unit that the arm test is in (only for calculating + * cosine data) + */ +void InitialTrimAndFilter(wpi::StringMap>* data, + AnalysisManager::Settings* settings, + std::vector& positionDelays, + std::vector& velocityDelays, + units::second_t& minStepTime, + units::second_t& maxStepTime, + std::string_view unit = ""); + +/** + * Removes all points with acceleration = 0. + * + * @param data A pointer to a PreparedData vector + */ +void AccelFilter(wpi::StringMap>* data); + +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/JSONConverter.h b/sysid/src/main/native/include/sysid/analysis/JSONConverter.h new file mode 100644 index 00000000000..7581d25fc16 --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/JSONConverter.h @@ -0,0 +1,24 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include + +#include + +namespace sysid { +/** + * Converts a JSON from the old frc-characterization format to the new sysid + * format. + * + * @param path The path to the old JSON. + * @param logger The logger instance for log messages. + * @return The full file path of the newly saved JSON. + */ +std::string ConvertJSON(std::string_view path, wpi::Logger& logger); + +std::string ToCSV(std::string_view path, wpi::Logger& logger); +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/OLS.h b/sysid/src/main/native/include/sysid/analysis/OLS.h new file mode 100644 index 00000000000..cf979041565 --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/OLS.h @@ -0,0 +1,26 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include + +#include + +namespace sysid { + +/** + * Performs ordinary least squares multiple regression on the provided data and + * returns a vector of coefficients along with the r-squared (coefficient of + * determination) and RMSE (stardard deviation of the residuals) of the fit. + * + * @param X The independent data in y = Xβ. + * @param y The dependent data in y = Xβ. + */ +std::tuple, double, double> OLS(const Eigen::MatrixXd& X, + const Eigen::VectorXd& y); + +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/SimpleMotorSim.h b/sysid/src/main/native/include/sysid/analysis/SimpleMotorSim.h new file mode 100644 index 00000000000..a452c640626 --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/SimpleMotorSim.h @@ -0,0 +1,74 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include + +namespace sysid { +/** + * Simulation of a Simple Motor mechanism based off of a model from SysId + * Feedforward gains. + */ +class SimpleMotorSim { + public: + /** + * @param Ks Static friction gain. + * @param Kv Velocity gain. + * @param Ka Acceleration gain. + * @param initialPosition Initial flywheel position. + * @param initialVelocity Initial flywheel velocity. + */ + SimpleMotorSim(double Ks, double Kv, double Ka, double initialPosition = 0.0, + double initialVelocity = 0.0); + + /** + * Simulates affine state-space system dx/dt = Ax + Bu + c sgn(x) forward dt + * seconds. + * + * @param voltage Voltage to apply over the timestep. + * @param dt Sammple period. + */ + void Update(units::volt_t voltage, units::second_t dt); + + /** + * Returns the position. + * + * @return The current position + */ + double GetPosition() const; + + /** + * Returns the velocity. + * + * @return The current velocity + */ + double GetVelocity() const; + + /** + * Returns the acceleration for the current state and given input. + * + * @param voltage The voltage that is being applied to the mechanism / input + * @return The acceleration given the state and input + */ + double GetAcceleration(units::volt_t voltage) const; + + /** + * Resets model position and velocity. + * + * @param position The position the mechanism should be reset to + * @param velocity The velocity the mechanism should be reset to + */ + void Reset(double position = 0.0, double velocity = 0.0); + + private: + Eigen::Matrix m_A; + Eigen::Matrix m_B; + Eigen::Vector m_c; + Eigen::Vector m_x; +}; + +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/Storage.h b/sysid/src/main/native/include/sysid/analysis/Storage.h new file mode 100644 index 00000000000..52899a0096e --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/Storage.h @@ -0,0 +1,95 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include + +#include + +namespace sysid { + +/** + * Represents each data point after it is cleaned and various parameters are + * calculated. + */ +struct PreparedData { + /** + * The timestamp of the data point. + */ + units::second_t timestamp; + + /** + * The voltage of the data point. + */ + double voltage; + + /** + * The position of the data point. + */ + double position; + + /** + * The velocity of the data point. + */ + double velocity; + + /** + * The difference in timestamps between this point and the next point. + */ + units::second_t dt = 0_s; + + /** + * The acceleration of the data point + */ + double acceleration = 0.0; + + /** + * The cosine value of the data point. This is only used for arm data where we + * take the cosine of the position. + */ + double cos = 0.0; + + /** + * The sine value of the data point. This is only used for arm data where we + * take the sine of the position. + */ + double sin = 0.0; + + /** + * Equality operator between PreparedData structs + * + * @param rhs Another PreparedData struct + * @return If the other struct is equal to this one + */ + constexpr bool operator==(const PreparedData& rhs) const { + return timestamp == rhs.timestamp && voltage == rhs.voltage && + position == rhs.position && velocity == rhs.velocity && + dt == rhs.dt && acceleration == rhs.acceleration && cos == rhs.cos; + } +}; + +/** + * Storage used by the analysis manger. + */ +struct Storage { + /** + * Dataset for slow (aka quasistatic) test + */ + std::vector slowForward; + std::vector slowBackward; + + /** + * Dataset for fast (aka dynamic) test + */ + std::vector fastForward; + std::vector fastBackward; + + bool empty() const { + return slowForward.empty() || slowBackward.empty() || fastForward.empty() || + fastBackward.empty(); + } +}; + +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/analysis/TrackWidthAnalysis.h b/sysid/src/main/native/include/sysid/analysis/TrackWidthAnalysis.h new file mode 100644 index 00000000000..b0220721e81 --- /dev/null +++ b/sysid/src/main/native/include/sysid/analysis/TrackWidthAnalysis.h @@ -0,0 +1,19 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include + +namespace sysid { +/** + * Calculates the track width given the left distance, right distance, and + * accumulated gyro angle. + * + * @param l The distance traveled by the left side of the drivetrain. + * @param r The distance traveled by the right side of the drivetrain. + * @param accum The accumulated gyro angle. + */ +double CalculateTrackWidth(double l, double r, units::radian_t accum); +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/telemetry/TelemetryManager.h b/sysid/src/main/native/include/sysid/telemetry/TelemetryManager.h new file mode 100644 index 00000000000..b636bc1d2c4 --- /dev/null +++ b/sysid/src/main/native/include/sysid/telemetry/TelemetryManager.h @@ -0,0 +1,237 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "sysid/analysis/AnalysisType.h" + +namespace sysid { +/** + * This class is reponsible for collecting data from the robot and storing it + * inside a JSON. + */ +class TelemetryManager { + public: + /** + * Represents settings for an instance of the TelemetryManager class. This + * contains information about the quasistatic ramp rate for slow tests, the + * step voltage for fast tests, and the mechanism type for characterization. + */ + struct Settings { + /** + * The rate at which the voltage should increase during the quasistatic test + * (V/s). + */ + double quasistaticRampRate = 0.25; + + /** + * The voltage that the dynamic test should run at (V). + */ + double stepVoltage = 7.0; + + /** + * The units the mechanism moves per recorded rotation. The sysid project + * will be recording things in rotations of the shaft so the + * unitsPerRotation is to convert those measurements to the units the user + * wants to use. + */ + double unitsPerRotation = 1.0; + + /** + * The name of the units used. + * Valid units: "Meters", "Feet", "Inches", "Radians", "Degrees", + * "Rotations" + */ + std::string units = "Meters"; + + /** + * The type of mechanism that will be analyzed. + * Supported mechanisms: Drivetrain, Angular Drivetrain, Elevator, Arm, + * Simple motor. + */ + AnalysisType mechanism = analysis::kDrivetrain; + }; + + /** + * Constructs an instance of the telemetry manager with the provided settings + * and NT instance to collect data over. + * + * @param settings The settings for this instance of the telemetry manager. + * @param logger The logger instance to use for log data. + * @param instance The NT instance to collect data over. The default value of + * this parameter should suffice in production; it should only + * be changed during unit testing. + */ + explicit TelemetryManager(const Settings& settings, wpi::Logger& logger, + nt::NetworkTableInstance instance = + nt::NetworkTableInstance::GetDefault()); + + /** + * Begins a test with the given parameters. + * + * @param name The name of the test. + */ + void BeginTest(std::string_view name); + + /** + * Ends the currently running test. If there is no test running, this is a + * no-op. + */ + void EndTest(); + + /** + * Updates the telemetry manager -- this adds a new autospeed entry and + * collects newest data from the robot. This must be called periodically by + * the user. + */ + void Update(); + + /** + * Registers a callback that's called by the TelemetryManager when there is a + * message to display to the user. + * + * @param callback Callback function that runs based off of the message + */ + void RegisterDisplayCallback(std::function callback) { + m_callbacks.emplace_back(std::move(callback)); + } + + /** + * Saves a JSON with the stored data at the given location. + * + * @param location The location to save the JSON at (this is the folder that + * should contain the saved JSON). + * @return The full file path of the saved JSON. + */ + std::string SaveJSON(std::string_view location); + + /** + * Returns whether a test is currently running. + * + * @return Whether a test is currently running. + */ + bool IsActive() const { return m_isRunningTest; } + + /** + * Returns whether the specified test is running or has run. + * + * @param name The test to check. + * + * @return Whether the specified test is running or has run. + */ + bool HasRunTest(std::string_view name) const { + return std::find(m_tests.cbegin(), m_tests.cend(), name) != m_tests.end(); + } + + /** + * Gets the size of the stored data. + * + * @return The size of the stored data + */ + size_t GetCurrentDataSize() const { return m_params.data.size(); } + + private: + enum class State { WaitingForEnable, RunningTest, WaitingForData }; + + /** + * Stores information about a currently running test. This information + * includes whether the robot will be traveling quickly (dynamic) or slowly + * (quasistatic), the direction of movement, the start time of the test, + * whether the robot is enabled, the current speed of the robot, and the + * collected data. + */ + struct TestParameters { + bool fast = false; + bool forward = false; + bool rotate = false; + + State state = State::WaitingForEnable; + + double enableStart = 0.0; + double disableStart = 0.0; + + bool enabled = false; + double speed = 0.0; + + std::string raw; + std::vector> data{}; + bool overflow = false; + bool mechError = false; + + TestParameters() = default; + TestParameters(bool fast, bool forward, bool rotate, State state) + : fast{fast}, forward{forward}, rotate{rotate}, state{state} {} + }; + + // Settings for this instance. + const Settings& m_settings; + + // Logger. + wpi::Logger& m_logger; + + // Test parameters for the currently running test. + TestParameters m_params; + bool m_isRunningTest = false; + + // A list of running or already run tests. + std::vector m_tests; + + // Stores the test data. + wpi::json m_data; + + // Display callbacks. + wpi::SmallVector, 1> m_callbacks; + + // NetworkTables instance and entries. + nt::NetworkTableInstance m_inst; + std::shared_ptr table = m_inst.GetTable("SmartDashboard"); + nt::DoublePublisher m_voltageCommand = + table->GetDoubleTopic("SysIdVoltageCommand").Publish(); + nt::StringPublisher m_testType = + table->GetStringTopic("SysIdTestType").Publish(); + nt::BooleanPublisher m_rotate = + table->GetBooleanTopic("SysIdRotate").Publish(); + nt::StringPublisher m_mechanism = + table->GetStringTopic("SysIdTest").Publish(); + nt::BooleanPublisher m_overflowPub = + table->GetBooleanTopic("SysIdOverflow").Publish(); + nt::BooleanSubscriber m_overflowSub = + table->GetBooleanTopic("SysIdOverflow").Subscribe(false); + nt::BooleanPublisher m_mechErrorPub = + table->GetBooleanTopic("SysIdWrongMech").Publish(); + nt::BooleanSubscriber m_mechErrorSub = + table->GetBooleanTopic("SysIdWrongMech").Subscribe(false); + nt::StringSubscriber m_telemetry = + table->GetStringTopic("SysIdTelemetry").Subscribe(""); + nt::IntegerSubscriber m_fmsControlData = + m_inst.GetTable("FMSInfo") + ->GetIntegerTopic("FMSControlData") + .Subscribe(0); + nt::DoublePublisher m_ackNumberPub = + table->GetDoubleTopic("SysIdAckNumber").Publish(); + nt::DoubleSubscriber m_ackNumberSub = + table->GetDoubleTopic("SysIdAckNumber").Subscribe(0); + + int m_ackNumber; +}; +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/view/Analyzer.h b/sysid/src/main/native/include/sysid/view/Analyzer.h new file mode 100644 index 00000000000..2f30f610000 --- /dev/null +++ b/sysid/src/main/native/include/sysid/view/Analyzer.h @@ -0,0 +1,261 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "sysid/analysis/AnalysisManager.h" +#include "sysid/analysis/AnalysisType.h" +#include "sysid/analysis/FeedbackAnalysis.h" +#include "sysid/analysis/FeedbackControllerPreset.h" +#include "sysid/view/AnalyzerPlot.h" + +struct ImPlotPoint; + +namespace glass { +class Storage; +} // namespace glass + +namespace sysid { +/** + * The Analyzer GUI takes care of providing the user with a user interface to + * load their data, visualize the data, adjust certain variables, and then view + * the calculated gains. + */ +class Analyzer : public glass::View { + public: + /** + * The different display and processing states for the GUI + */ + enum class AnalyzerState { + kWaitingForJSON, + kNominalDisplay, + kMotionThresholdError, + kTestDurationError, + kGeneralDataError, + kFileError + }; + /** + * The different motor controller timing presets that can be used. + */ + static constexpr const char* kPresetNames[] = {"Default", + "WPILib (2020-)", + "WPILib (Pre-2020)", + "CANCoder", + "CTRE (Pro)", + "CTRE", + "REV Brushless Encoder Port", + "REV Brushed Encoder Port", + "REV Data Port", + "Venom"}; + + /** + * The different control loops that can be used. + */ + static constexpr const char* kLoopTypes[] = {"Position", "Velocity"}; + + /** + * Linear drivetrain analysis subsets + */ + static constexpr const char* kDatasets[] = {"Combined", "Left", "Right"}; + + /** + * Creates the Analyzer widget + * + * @param storage Glass Storage + * @param logger The program logger + */ + Analyzer(glass::Storage& storage, wpi::Logger& logger); + + /** + * Displays the analyzer widget + */ + void Display() override; + + ~Analyzer() override { AbortDataPrep(); }; + + private: + /** + * Handles the logic for selecting a json to analyze + */ + void SelectFile(); + + /** + * Kills the data preparation thread + */ + void AbortDataPrep(); + + /** + * Displays the settings to adjust trimming and filtering for feedforward + * gains. + */ + void DisplayFeedforwardParameters(float beginX, float beginY); + + /** + * Displays the graphs of the data. + */ + void DisplayGraphs(); + + /** + * Displays the file selection widget. + */ + void DisplayFileSelector(); + + /** + * Resets the current analysis data. + */ + void ResetData(); + + /** + * Sets up the reset button and Unit override buttons. + * + * @return True if the tool had been reset. + */ + bool DisplayResetAndUnitOverride(); + + /** + * Prepares the data for analysis. + */ + void PrepareData(); + + /** + * Sets up the graphs to display Raw Data. + */ + void PrepareRawGraphs(); + + /** + * Sets up the graphs to display filtered/processed data. + */ + void PrepareGraphs(); + + /** + * True if the stored state is associated with an error. + */ + bool IsErrorState(); + + /** + * True if the stored state is associated with a data processing error. + */ + bool IsDataErrorState(); + + /** + * Displays inputs to allow the collecting of theoretical feedforward gains. + */ + void CollectFeedforwardGains(float beginX, float beginY); + + /** + * Displays calculated feedforward gains. + */ + void DisplayFeedforwardGains(float beginX, float beginY); + + /** + * Displays calculated feedback gains. + */ + void DisplayFeedbackGains(); + + /** + * Estimates ideal step test duration, qp, and qv for the LQR based off of the + * data given + */ + void ConfigParamsOnFileSelect(); + + /** + * Updates feedforward gains from the analysis manager. + */ + void UpdateFeedforwardGains(); + + /** + * Updates feedback gains from the analysis manager. + */ + void UpdateFeedbackGains(); + + /** + * Handles logic of displaying a gain on ImGui + */ + bool DisplayGain(const char* text, double* data, bool readOnly); + + /** + * Handles errors when they pop up. + */ + void HandleError(std::string_view msg); + + // State of the Display GUI + AnalyzerState m_state = AnalyzerState::kWaitingForJSON; + + // Stores the exception message. + std::string m_exception; + + bool m_calcDefaults = false; + + // This is true if the error popup needs to be displayed + bool m_errorPopup = false; + + // Everything related to feedback controller calculations. + AnalysisManager::Settings m_settings; + wpi::StringMap m_presets; + + int m_selectedLoopType = 1; + int m_selectedPreset = 0; + + // Feedforward and feedback gains. + std::vector m_ff; + double m_accelRSquared; + double m_accelRMSE; + double m_Kp; + double m_Kd; + units::millisecond_t m_timescale; + + // Track width + std::optional m_trackWidth; + + // Units + int m_selectedOverrideUnit = 0; + double m_conversionFactor = 0.0; + + // Data analysis + std::unique_ptr m_manager; + int m_dataset = 0; + int m_window = 8; + double m_threshold = 0.2; + float m_stepTestDuration = 0.0; + + double m_gearingNumerator = 1.0; + double m_gearingDenominator = 1.0; + + bool combinedGraphFit = false; + + // File manipulation + std::unique_ptr m_selector; + std::string m_location; + + // Logger + wpi::Logger& m_logger; + + // Plot + AnalyzerPlot m_plot{m_logger}; + bool m_prevPlotsLoaded = false; + + // Stores graph scroll bar position and states for keeping track of scroll + // positions after loading graphs + float m_graphScroll = 0; + + std::atomic m_abortDataPrep{false}; + std::thread m_dataThread; +}; +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/view/AnalyzerPlot.h b/sysid/src/main/native/include/sysid/view/AnalyzerPlot.h new file mode 100644 index 00000000000..e5fbe8ca959 --- /dev/null +++ b/sysid/src/main/native/include/sysid/view/AnalyzerPlot.h @@ -0,0 +1,203 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "sysid/analysis/AnalysisType.h" +#include "sysid/analysis/Storage.h" + +namespace sysid { +/** + * Class that helps with plotting data in the analyzer view. + */ +class AnalyzerPlot { + public: + float m_pointSize = 1.25; + // 0 for forward, 1 for reverse + int m_direction = 0; + + /** + * Constructs an instance of the analyzer plot helper and allocates memory for + * all data vectors. + * + * @param logger The program logger + */ + explicit AnalyzerPlot(wpi::Logger& logger); + + /** + * Sets the data to be displayed on the plots. + * + * @param rawData Raw data storage. + * @param filteredData Filtered data storage. + * @param unit Unit of the dataset + * @param ff List of feedforward gains (Ks, Kv, Ka, and optionally + * Kg). + * @param startTimes Array of dataset start times. + * @param type Type of analysis. + * @param abort Aborts analysis early if set to true from another + * thread. + */ + void SetData(const Storage& rawData, const Storage& filteredData, + std::string_view unit, const std::vector& ff, + const std::array& startTimes, + AnalysisType type, std::atomic& abort); + + /** + * Utility method to plot the raw time series data + * + * @param rawSlow The raw slow (quasistatic) test data + * @param rawFast The raw fast (dynamic) test data + * @param abort Aborts analysis early if set to true from another thread + */ + void SetRawTimeData(const std::vector& rawSlow, + const std::vector& rawFast, + std::atomic& abort); + + /** + * Utility method to reset everything before generating the points to plot. + */ + void ResetData(); + + /** + * Utility method to get set the graph labels based off of the units + * + * @param unit Unit of the dataset + */ + void SetGraphLabels(std::string_view unit); + + /** + * Sets up only the raw time series data to be plotted. This is mainly + * intended to be used if the filtered data has issues with it. + * + * @param data The raw data. + * @param unit Unit of the dataset. + * @param abort Aborts analysis early if set to true from another thread. + */ + void SetRawData(const Storage& data, std::string_view unit, + std::atomic& abort); + + /** + * Displays time domain plots. + * + * @return Returns true if plots aren't in the loading state + */ + bool DisplayPlots(); + + /** + * Sets certain flags to true so that the GUI automatically fits the plots + */ + void FitPlots(); + + /** + * Gets the pointer to the stored Root Mean Squared Error for display + * + * @return A pointer to the RMSE + */ + double* GetSimRMSE(); + + /** + * Gets the pointer to the stored simulated velocity R-squared for display + * + * @return A pointer to the R-squared + */ + double* GetSimRSquared(); + + private: + // The maximum size of each vector (dataset to plot) + static constexpr size_t kMaxSize = 2048; + + struct FilteredDataVsTimePlot { + std::vector rawData; + std::vector filteredData; + + // Simulated time domain data + std::vector> simData; + + // Stores whether this was the first call to Plot() since setting data + bool fitNextPlot = false; + + FilteredDataVsTimePlot(); + + /** + * Plots data and fit line. + * + * @param title Plot title. + * @param size Plot size. + * @param yLabel Y axis label. + * @param pointSize The size of the data point markers (in pixels). + */ + void Plot(const char* title, const ImVec2& size, const char* yLabel, + float pointSize); + + /** + * Clears plot. + */ + void Clear(); + }; + + struct DataWithFitLinePlot { + std::vector data; + std::array fitLine; + + // Stores whether this was the first call to Plot() since setting data + bool fitNextPlot = false; + + DataWithFitLinePlot(); + + /** + * Plots data and fit line. + * + * @param title Plot title. + * @param size Plot size. + * @param xLabel X axis label. + * @param yLabel Y axis label. + * @param fitX True if X axis should be autofitted. + * @param fitY True if Y axis should be autofitted. + * @param pointSize The size of the data point markers (in pixels). + * @param setup Callback within BeginPlot() block that performs custom plot + * setup. + */ + void Plot( + const char* title, const ImVec2& size, const char* xLabel, + const char* yLabel, bool fitX, bool fitY, float pointSize, + std::function setup = [] {}); + + /** + * Clears plot. + */ + void Clear(); + }; + + std::string m_velocityLabel; + std::string m_accelerationLabel; + std::string m_velPortionAccelLabel; + + // Thread safety + wpi::spinlock m_mutex; + + // Logger + wpi::Logger& m_logger; + + FilteredDataVsTimePlot m_quasistaticData; + FilteredDataVsTimePlot m_dynamicData; + DataWithFitLinePlot m_regressionData; + DataWithFitLinePlot m_timestepData; + + double m_RMSE; + double m_accelRSquared; +}; +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/view/JSONConverter.h b/sysid/src/main/native/include/sysid/view/JSONConverter.h new file mode 100644 index 00000000000..89bfa3290d1 --- /dev/null +++ b/sysid/src/main/native/include/sysid/view/JSONConverter.h @@ -0,0 +1,57 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include +#include + +#include +#include +#include + +namespace sysid { +/** + * Helps with converting different JSONs into different formats. Primarily + * enables users to convert an old 2020 FRC-Characterization JSON into a SysId + * JSON or a SysId JSON into a CSV file. + */ +class JSONConverter { + public: + /** + * Creates a JSONConverter widget + * + * @param logger The program logger + */ + explicit JSONConverter(wpi::Logger& logger) : m_logger(logger) {} + + /** + * Function to display the SysId JSON to CSV converter. + */ + void DisplayCSVConvert(); + + private: + /** + * Helper method to display a specific JSON converter + * + * @param tooltip The tooltip describing the JSON converter + * @param converter The function that takes a filename path and performs the + * previously specifid JSON conversion. + */ + void DisplayConverter( + const char* tooltip, + std::function converter); + + wpi::Logger& m_logger; + + std::string m_location; + std::unique_ptr m_opener; + + std::string m_exception; + + double m_timestamp = 0; +}; +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/view/Logger.h b/sysid/src/main/native/include/sysid/view/Logger.h new file mode 100644 index 00000000000..d06d6508165 --- /dev/null +++ b/sysid/src/main/native/include/sysid/view/Logger.h @@ -0,0 +1,82 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include + +#include +#include +#include +#include +#include + +#include "sysid/telemetry/TelemetryManager.h" + +namespace glass { +class Storage; +} // namespace glass + +namespace sysid { +/** + * The logger GUI takes care of running the system idenfitication tests over + * NetworkTables and logging the data. This data is then stored in a JSON file + * which can be used for analysis. + */ +class Logger : public glass::View { + public: + /** + * Makes a logger widget. + * + * @param storage The glass storage object + * @param logger A logger object that keeps track of the program's logs + */ + Logger(glass::Storage& storage, wpi::Logger& logger); + + /** + * Displays the logger widget. + */ + void Display() override; + + /** + * The different mechanism / analysis types that are supported. + */ + static constexpr const char* kTypes[] = {"Drivetrain", "Drivetrain (Angular)", + "Arm", "Elevator", "Simple"}; + + /** + * The different units that are supported. + */ + static constexpr const char* kUnits[] = {"Meters", "Feet", "Inches", + "Radians", "Rotations", "Degrees"}; + + private: + /** + * Handles the logic of selecting a folder to save the SysId JSON to + */ + void SelectDataFolder(); + + wpi::Logger& m_logger; + + TelemetryManager::Settings m_settings; + int m_selectedType = 0; + int m_selectedUnit = 0; + + std::unique_ptr m_manager = + std::make_unique(m_settings, m_logger); + + std::unique_ptr m_selector; + std::string m_jsonLocation; + + glass::NetworkTablesSettings m_ntSettings; + + bool m_isRotationalUnits = false; + + std::string m_popupText; + + std::string m_opened; + std::string m_exception; +}; +} // namespace sysid diff --git a/sysid/src/main/native/include/sysid/view/UILayout.h b/sysid/src/main/native/include/sysid/view/UILayout.h new file mode 100644 index 00000000000..732a1aaf658 --- /dev/null +++ b/sysid/src/main/native/include/sysid/view/UILayout.h @@ -0,0 +1,95 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include + +namespace sysid { +/** + * constexpr shim for ImVec2. + */ +struct Vector2d { + /** + * X coordinate. + */ + float x = 0; + + /** + * Y coordinate. + */ + float y = 0; + + /** + * Vector2d addition operator. + * + * @param rhs Vector to add. + * @return Sum of two vectors. + */ + constexpr Vector2d operator+(const Vector2d& rhs) const { + return Vector2d{x + rhs.x, y + rhs.y}; + } + + /** + * Vector2d subtraction operator. + * + * @param rhs Vector to subtract. + * @return Difference of two vectors. + */ + constexpr Vector2d operator-(const Vector2d& rhs) const { + return Vector2d{x - rhs.x, y - rhs.y}; + } + + /** + * Conversion operator to ImVec2. + */ + explicit operator ImVec2() const { return ImVec2{x, y}; } +}; + +// App window size +inline constexpr Vector2d kAppWindowSize{1280, 720}; + +// Menubar height +inline constexpr int kMenubarHeight = 20; + +// Gap between window edges +inline constexpr int kWindowGap = 5; + +// Left column position and size +inline constexpr Vector2d kLeftColPos{kWindowGap, kMenubarHeight + kWindowGap}; +inline constexpr Vector2d kLeftColSize{ + 310, kAppWindowSize.y - kLeftColPos.y - kWindowGap}; + +// Left column contents +inline constexpr Vector2d kLoggerWindowPos = kLeftColPos; +inline constexpr Vector2d kLoggerWindowSize{ + kLeftColSize.x, kAppWindowSize.y - kWindowGap - kLoggerWindowPos.y}; + +// Center column position and size +inline constexpr Vector2d kCenterColPos = + kLeftColPos + Vector2d{kLeftColSize.x + kWindowGap, 0}; +inline constexpr Vector2d kCenterColSize{ + 360, kAppWindowSize.y - kLeftColPos.y - kWindowGap}; + +// Center column contents +inline constexpr Vector2d kAnalyzerWindowPos = kCenterColPos; +inline constexpr Vector2d kAnalyzerWindowSize{kCenterColSize.x, 550}; +inline constexpr Vector2d kProgramLogWindowPos = + kAnalyzerWindowPos + Vector2d{0, kAnalyzerWindowSize.y + kWindowGap}; +inline constexpr Vector2d kProgramLogWindowSize{ + kCenterColSize.x, kAppWindowSize.y - kWindowGap - kProgramLogWindowPos.y}; + +// Right column position and size +inline constexpr Vector2d kRightColPos = + kCenterColPos + Vector2d{kCenterColSize.x + kWindowGap, 0}; +inline constexpr Vector2d kRightColSize = + kAppWindowSize - kRightColPos - Vector2d{kWindowGap, kWindowGap}; + +// Right column contents +inline constexpr Vector2d kDiagnosticPlotWindowPos = kRightColPos; +inline constexpr Vector2d kDiagnosticPlotWindowSize = kRightColSize; + +// Text box width as a multiple of the font size +inline constexpr int kTextBoxWidthMultiple = 10; +} // namespace sysid diff --git a/sysid/src/main/native/mac/sysid.icns b/sysid/src/main/native/mac/sysid.icns new file mode 100644 index 0000000000000000000000000000000000000000..53f0d699ac301071435484c4fc9f7635e4349136 GIT binary patch literal 378189 zcmdSAWpG?Q6sFl`X680CGcz+Kwqu5vnYqo(%*@OXGqWAX%#@g!dHqdI?QGR<)$Wh^ zv$yNEq;6G7t*h42dCwzD6FX-B)UcwZ2`d`_fSMPfq9lz3j}H$30FY#5B-FlAk^gR3 z=&$!mOUJFR1k71YS`1J-LwNjEkTBDd{i&!3p!>?h0>Hv70g(Sy`MUAHZU6ux9}EET zm4f~ESw8sx`K?Gk#Q)0wS5Zn;tp2M9V6qaT8XjQhKj0iN4^uw=#Y-I?iGgoY0|SD2 zq9I{z!m3yd@mRum74}vPkw+QE*9ZulhkiLyR)B0BCP09uvrtM_>{!x<zMsE7mKk>(J)`?fAc@JZl%qi> zMpw0J75U$)c6W9FHQx|=E>BL-!>}R2sFGy6{+avC&OS{&;>SpJ{o{&_jWsr~+xX#M zdwF(-IqHoo{0JqYp^3tP*zOHaj#()B<(4mG5RVJUG@lQ5f zS;Kq?4tq%NSKWW>K|dD_@;`odUb5lG*w)n4OuM?eE|!#(a5L+5CggNp;$W`cM(bTWb&b^Mq+$=3EEsquhM@DhP zKRotZT@ida7rQ$m#xYp*-=-+L*(au!nXCBt_@Wh>va;5L0{Up?CzK1pe!NhYxrG~N z;xK5jMA-a!59pgpYPcPnotZnNE+$sExeJ*D79;ry?`+N}FyIFh^XEN5LM^|G z{8Sji;cBN}m|lf-mCC^Pz9gQ*t~!6-0xHEkeh2N9+-Pnn#DxJ}V80aB>Jl|Fs$~G9 zXfK4kqN33xU6E02`tSHajXf!G3SNTP_a6l|>)x7d%x7>13nFA-hyWO2%=dfV$Q{Lr zwZ%FzvrFo$*u2n&y30Tz3)p6*T6ZdHV<>^J&J~%e{gB*&Psv<>^0Wb*EKOk z?r2kOtgQ#D%}e)(G8m%un;?3A!=YMKkNn_PNlJqfccoRN?sF9ZLQBL1OUodRym_!& zQ42(U%6cL|DN~W258)l%$Cgw6TaWNuBx)%^!qTo{+E>IZnH|c1;%IM&i9n=zE`T!A z*B}GqBBGFr9}d76jbx~+ea858UK z4B1?I)FB4>)pNqE!^xC8kIw-D;l~@o+uxNmo_c>_bn$zcPX|i58Nz_5HsQo_`?Uy{ zuHJWgbnVG8m(t;7i_P7$TLE3@slXyFMc}MoV(BvR=fxaF2xznbF}m|4_@I&HBea5?04O3fAj>Iz^NviuXNgv#6>Qa~N>puo81T@CVBwuK_TM zCjEvpTZB;k;YsX@MLnMGRu?6A9=`O?IK4CZuShtwzJ_c z4z(!*+A8ZM-Ne zKBonk2J8SQ1o{NPFu9sIGcz;d-My%~87XUi(02>OnOxo&rFmO#pbo}>VfN<-;YJX2 z6lqgIC8n1-I}hn##(jG@Sz@h{$J_)AvS$nP!RBJ>p@u0$x&yCjhjnuhck6UHLgIe&@Vb`fDeZ zt0p!qYl06Aqk5^*@Kf;bb~gqn4hSg*FNo!dtm}bWXVGIC)|>s5pF{^i!*dyKzSWPX zOSK~*U2M_1H?8Gj+{%Q(VJ0|lZ-X+0I#(0)%*G4t!*a3>>oaQ?THMJp0B%#|xwOXn zpmU2ZH~3+5p|B`>RI08Iv_^WJtGi;jmG)i6Y-MF>O1#mV8z&#-m!AE1TP+rDyhHnM z>g&RNj6is-3`-h*Z(QrtQ^#MwQG~>|E}N>Fq}kVok|%wX01+|_Ue%)9gN;jqR;;EBDuJ>pAnnzuy74$e3S4z`O`*A+XjCs!h8ZFJ_U$`=scSm2m@;O*@_AVh0nuKuOI^JMrXrsu_o zHbf*t!hr~ElXxk=Y#|0%1(~&h&jYiAMNf!h(T2l`2L6n>>CQm}$5gH$0qbw^-}7<= zr786F&dV1hrJb|%jn<6``H+C0`brvSvsGjUik8*c=GSLK1Ts$;R|XZsPj~kIBLBF5 z8M)mAEiH;ejxVgiHfxagH4#nbEsviQ69d|SoL0bDk>WhQ&lNr%y#*) z;9Y_(S0o1^YpE6#F*Kn;oyZU-*oGEwP97*eIKsZilsrei2~TS<4*9+TGk;KiJ=&mC z`=X*+7@6s1F#whlGLtudSwl7@pr?-;ga1h!+(!|MW&{;MSa9a#JL8GaPxJG}UQQQB z^|cI06_}ET~&YPcB@Z8L8V0I%pv4XQ{Lg;fi6Rp0$JG#yhG$Pf;}W@aTldHq_xKA2S%Vi zVv!kymH4f5Fs~c1M-FJZ7-G8s`$ns6TD5=E%_XkI?Lr!e5_{zEEao34`a#(l2M;}O z>jtcxBPcE0J=C)W=T zkGC7>&Bz1A#T$$U`30+21T!pEp?KG+5&*=ZdQ_yPG@BFWn?cniH2)Fwn8s{k4FWwq*m17VIuy>ohoXqBS)3(p-72J=HpK z2;AVT4A*)T503KuQQ(Elu|(p-RvY=tTtRQ--~1D5-)x6NhC|f1OpS`1oSma&T!_a9 zn%Pmjy7gHv-SKbSTZ`cmC#{Y3LQgkOr{ z_G*O%djYv>^QpZEi((d+?Mt{N1wpCFaZ6Wd+u!jQ{REGCin*}SH!A7% zm6aof2U6pybXM~H{e6>x!NH(oqF$WEj>H~bbQQuMs7R)=B*sR4mOOr=+ma2wFkx+& zHA{blWj4sT(~>eWJQGgr&;d1fOBGQcIZ{iP>xm20WD%kdh;%QF;)>hQmNdquKWVQi ziJS4DNd!v&=1+!wV^BqWWtXdrfcbpXpq32PYX(paj46C7Q(Vz=my{?2w4lv?8&?>< z?^)~H#u6Rrn_aiPWuHFfhV+xgrXF_X>(1J?UuC?yFuOdy`gDBgO5bYrp&pTt4+)t* z^)1Iu{tw?9H=qZ2^_evER32ES?em`~ASm)75=x#6QKW#Jn>%(0GU`wcL0E<=6}i)dT>4(iyfa-NrI&O!I0o^@<1aTRBcRD zNVLlE$ZwXzmA3bXOb@G(J)Ih_8&$5Br)x`klTCDFG-OrPjrgYW1H?f7)ufEa&%BHz zM3YqZaRnI?XTM&4XY-4W!|Yez?dO@cT>3p`KiDVIoiGpy`2Uy8=Paoquih*UE-sDR zFFgkAC`c%%h()WE&Q3l!B&3wYMD&QbxU|YjIyeM`q^m23ii!$V*U5>A;Kv*8%U#Et z16ep&*!YtZtNZDPFKI$TQc~8;ti&qp@k;+;wDT;?^@*R2P3?Z#ZNLo5V_S@_L*9yvLSzcRf>$jZS3~ip&KdNgn05LJKV)Zg5H60zg{{DWk9SRBx z2|$M9T+4+^9{%d=xYKPenXF?B3^a|PXke^Uip*d z^lEc}B7A(APjCH~4nM0Wy`S>v6B>l-PWftmJ9C=^QGXI$v=ku`p$KDCPf}R6&!gW(P~|#OdxM{mfXT^8tcGS7(Wh(x?1p}~m#m~@$lc|( zFfBQ`$y7KR`N*D+%;Ux8AJ7rxRHuwU_3Y?8G2lKQg}_h^x{$~5Xs+O_y1JTi+wb*! z;_DwZ5)GZS0|HhWts3UsExOXQDt-4Po!xxqDFgwhXETytNn6+O3lj3N(50sRkZW6ULuck{JSVjA%o5AXxYI3y?0um?o;g#YCWTV zmq&jHjy_NFjf|XJWMYbfgTvYhCLs`I)WVy98Z`OYp5?l*<0x7vV=)A1f1A(bw8qX5$nK5hh5S~n)j-3}&d$rqsw#r0pOn@$k4l3PSUVis zLTAz+2=zGtc+KPDy8CS34}w9t=sIhh{3)6`5m;%(>-W~)T@$zd6THuBmg{T>kdfze zGj6U`r?$>V^ZBkQzB86U&YPy|G%l$^&;$<;&*16lX-gK!g$4-0IC-3l`^EU9)rK}4 z*nM2^TIYcP4ueeiWP}dSb5W3;O$bJP_3h8U^Es8o++3vqX57<1=(meg27d@pwK|;s zCbqY?@9YkS(N~r7{_E0cGM~-GuJnl$d|0{cz83l55(w)niW7R-9ui%y)%!6${==2L z+GCmfs>f>fA)r}W~X00D^=xZHLdo?6gc@#L4=z1u;*h%_Mtx`Q6e12WF)53>>-1lrwJquHcXyL*w~$+W>LH7ZCk-(#mQU~o5bYcd_i3so^nnh@0L z2hAyRg}X1^LmTdEfRej>plk~# z_QEIwK~GVbV?SASp>adZbiftq)t(?iR)5P9ng;Ovd0i_aw%uJ_T}{l&syf?4JTaBQ zGQ&O@1!~F4%c}?EZV|`T{A<@ZU`F+}4G11mNX#Eg*t!@f7Zk7-KpDayHanwCvq~~n z0A#;wd;-Qi9D*E@Mtrr+PnT+LF8x1$q%vre%>_^j3-_*Gh_usnoxI)7rbRLLq`O7` zJk8Rr=Iv00Z~Q5zI4r73-*}4<#W0?vWi0LkBhHsU;C)BwE}G*EO#stWfIe+21DjEd_cN92nFu6|zE zbrVSxs9pvAU9Yp>?_k~Iwg0cNaPz!pHR}B@)6c;gtEL)mQb>C$g#l~_L6iHfbciDl zPe?B*u<&#J9lO-+kB7FvvDKHJntmhnO?Gu-FQkNWyJK|xb8Jcw2gR}nzZNJ}vysU}dL${t$34@r z$-xaxFu_$BP+8V&-^&c8ha6fPA*Dy;)(-My=ff@0G0_-X*Q^LR$po}m-Wh^>a#Pch zxKKkEcoW67LLd{^>{2P>vZ*|Oq{%+)Etk9vk$Qf#F(p#J~C#T_iP5+u*wy53BUq<#!QHDe+Qps>mrx_MyqX>u0uZ*oo1xseTG|6vC<2kgH4(a^&SLx z5J;mcvm5FcmrQ@IqFQPi<6?;lSU;W&YBE$HxiLkdJW9l|pvK;74kKDb#YrZTgqRpG zz*N^SPNL*4Er&!9O0i7W5-!j0r2-#)Y#?y%*qv=z=GprUaJ>io5lUWcgm-?wYZVJN2vWK@)F5p;aq=6w=Y^GNHBx1ZS^ z3qg<7LEhv9>WQd?6K>t5n0DXRi{;t{s>+FnA*TrWzQ7v))gYs`g=j`onOkqM#*qlH zl4PO4hfnZjdZ9$*ZZNK@P?K0N>*K+@Yl1PGBzUYy53Bk)8?XGSM!UP@)9_2~wNt&# zUS1@A=>9W*3m0?SGV^Rahb}eK#-R#zwfh+51la&BU?j#F&VfL0UpNL1Bn8BFF$P4A z@LL}nnD)^OBA?!8KdB!h8!3|KSquI`Mnq1@FVqe3LH~>OU6=H`fp5#4peRDRH?P}S zx>MZ6dYf{*bJ)FafZVE3^Mg9=)D~S(t*1zXzY`b}b28`4beE#r$0^>kkaeBF8+AgN zzj?w<{^asAc&2muy%}JB#KbJ`1(z1UNA9wz6Q+ z_rV|AW8o<!I$Ojl2(vJpYf5 zx93^^RMjG>3KzSV0X>vbZR=k=yhGiOTlAORkGbeftE$fp?~TXI?sTsptl(iWG8sI6 z`A+1lYQNr(gfZ^Z{2y(=7j&A|6T%9{SEbF-xXv{;TE>ll)k`f-*}hEJ#x}tp2D4Gr z@Z8bs`6qU2(N>OdK+S@Bh&%=`juBMP?BnEz@so<>TX#*z9vfeip5(JliXS~5@??QE zPMi13Rob)ON6;nNd-~0)!3j;x)b&i7#iJztx_BvCc~S+8b)QOdMl@svsxyYYzNMe= zR%PV$j}g5E#Kd`OzUm=94V9Hrtv=38gj=r#gu+iDHXmNK$yh~t)L>Uz&}1GG$ZuCV z>eDSJ{)gy>yG>lsaU=MgWB@e`e4BsQ1lDVBy*d2u6YKW9HFigC4=xc(L`UiG@Oy4D zhst!Ku~>G$_U$61I$dbp&{)x&WV&i=5iS_S0D9i%ErIn`i_}oVM3--(<6s&%wyvCV zn`gYcWhXC{ie!_^5y4yqpAPAqE#G)O7-Vmh3FFV{?GrCkXA%O*Ct3IXeJ~>W&{1hR zwtEqoc2&$ZrS)Gxi%Tn%HWC0xGIO-3ePejs9h9c@7nC(%5b{te{b>M>}2$wA|BDTAI-?L1XAm>(|R=GL==E(AnOs?+K z7JV^%l=t60NqDK84tPr5OILfQ?Gp50I_0n+2S6a`#b&|yx@F()utIzn1QIF8zEDnt z#hm83+TUh&uobo+M%Uv=kNLexp1db*TfhoVYk%<|Oh!TiiO!F*+3{Tqp?@Ra7%J`G z$|8}Z^4lp~bply_oqO+49X<`XHSwwoQaeZY z$|JBaks%Rtwm&SaTvcKFW2J)PtA&4FcK!Z|5dT!Jmceu8Jw7fUKTH4}s3qg0bvt{_ zxNiQ5FLeMYCHxZ(D2GvRn%yvcLEGJ(JQ2@VfzP@NO*~?C$zE``@c91 zP$Y#(;QBFtGU?RVm0sHu=@s%@c6~ejESbtE248;bdc!@&{~p-80@E55;_MjR54h`c_zelG=pdU zdNK~p@MdfE5E9e=Z1d?qCK^@VD-UZx91z0Vxad-%s*iOaHp4Ipb>{7_=QdfPOr=^) zEN9WFGT3Y9RdR&=v@*Yvl+a)q|J;zqXA>GwhEBumb z`K?cq*_WaolWd_94GRL?Q0?8f(`;CdXL$*;6f^xsT(9_H;HoqP#Ol^Z`2Fa0Gu>bv z(A034zc2;Fv{|dpjFCGIvp?j3A)L&{m$h*LUG<4*3NGaz2;0q}IDOmJ)ox)#l8C2* z7!^2H7c_9)8VmE|QqqDCq#6zfzzW!E&1w9cZ|49S3yiBwowipn@`QOE#aq>;^htFC06vM%PMe}8+x7;mhr~K0j)B~ z(};=LMS6eV>t<7R%RNN{G_c0o)8l|n`!T(#73x%#pGu=)x!Kv(ifF%H+oO3w56~w{ z8w6J8_Bzil&A;K=eIY~u40oxn1e|&`!&p~f0}S#PV+g#?VV|e*|yu4~iGR<+VZ5 ze|aY4YnU5qLAmb2e!}nvFTzZ;A%MLh947ZtY$LK%E@@j~I z-YD*=qWem-nU^0MUQYA51ua~Ud>6f6D>Ud2UkN|zCV|bgJ+xQ71}0%bQC1om$0SpSu!~5m#*l9`Iydu;ot$W{Pbgx?&2%2lJmDxxyt2Iiq!2;{D+vFRDQ;7Jz z88d~-YF9bN1L*D`+ea<(GUa24&wk$#;lrgA5Kxdpl2-{OLN3OZ~}NcKBWZ7H(%Z~^e!z(7OWJYev%`LM5vvnD1!Z}5lQEDE}eii z=05-*?KKF=?qOMEhyWF=;eCIT8i#2{+HhO9b%H{dPGgqdp*+Lnph>8?-K}Uj3fiZd ze-=)X_&1$J-L~ab#bN*|Sza)Zxs0+K>bzvxiN9ArUw>bnJbB6Y6LlJ$r7v#hP!ZA= zl!2EcH``gEUK?($gPw~-vBOwSo;%&jPGAPfEVF^UA-3M$H=JkT-1@&!trA^+s7h_T zQ6Jow@Fj{S;EymAIJCz!#Se}O1eBzY3%CrSa{2D8b6~PMOzE;2sIa#9sJ%no#6-@6anyb4}}0O^9pvmJe<$HsmbsCfp!Ec-AZ z9+y&l8AM$XW&{nrmY2%cf`YJ2$&+Vi3PisTzJG*;DzMcdq*kZfBr2X^ogdpYTlO-J|uYa!#^l$B4QWd_VDES>LpD)W=6_R?S zZ&T;=wW2_Hrl2Ao(tqo{9$qj0{Oc~iT#!_N$8qqK6!VzvkTOA8PRGae_Zh~hgCAN+ zwe+V5&@?>$h$%8Cc!WX@@b;2?abI0F7-sGFQG0*$?)?eDc~|c>bXxmMDcAEK-t*Ib z++UpDr;z0Di{mZ5ezHR6ZeZNwHq0!|og{og3cMgRuy#Hij+7QJmr(ARJb#j@Syj}B zf26)u60Ps=y_CY%HFue8-#y_oj^#O3Z65$6gyt?5x@4(zY%S2rxNXq|&ax!|&L*(> zu4Fxx6b27|AKb7xm*9rTFetW&5`0Ls3ta7~PRs>lsMrwF*G$6qrI#Rf()6v8 zLe!APCP^}XWN}za0BmHWC)3qZWe*t_3!1meq+2$gCOw^C#a?&s5fUhy(Fb-EQd%%_ z7p{*sJ+6f)|>9C1?5bxoz;Ge@jMP%Qe#^G&-U>UxcKRLI|7h%`JJOr z->Vt?#19&J!{0EDwGW_I4LLwLP&I=P zX^F~ZtVvM058)zp)X8pAdNLLFY(&bSnG`l zTk|EzzUbRkddo+tM?qZ#qTGS;iEQw)OdXoLBQ+MPJC)t@=Y#i(owJ);C8Y{2zO92!a90D>I zogXlsFNL7|~(KhnqTxcC#Z$O7i%a`zP)o~a* zq-P8BsX^bPs8;A>rL2sUbbjm6&7<=7Ir1C2K0icYUAWbEp60x{`=eadjoAfKm%!ooL^DhA+_!_P4rxAt2v-Q$kyIF zb`?O@+kpldPu|EY51HjTmirEt=uW0`{;%J0-V*~04;TUG5#k#Ml)c0vGvn+owvS7K z{Yw|`q~(`!Y?5GwC(I%LbJ|Z^?N8aH;<1*Mp=j6p!}=oe5GJ&1!F&Ge(5jlAesyY= zP}&xqH@3jGQ8;M-u9GspkE4JJsd&kcJIrU9YxgX$;!i?3FNL`20T76o(Ef_-nwr>X z$YTq9-VYUNXAT5soQp`Qroqzu_Uxd|y_$=`z%FGU%3UWje7@cQHW%+0C$DB-%{n8d z&b}SP;s4?Dp2kLeAMzf658I)H6fJ|vz>kln0?Y9iAXP}FjbMAs(6a|99jhCKRsv>% zSfG^ft4z(@rOLmtq|zMRf*nf;gdz>po20H|ecw^&y*islCst$3tHGlSi&fWYB~`tp z1%8&*DprYT*ohX&pA_?o9VGpQfJMhAj=H;GX~}?uQbrfm{cO^7WyHqfX6Lu!IP5y0ih6{RgTL4+T$}zUu`#~Wg?n5V zwfgXL>Gz<5r>u`mGT!Y*zLnnG;?-xQWCgbnqp{5Zm7rZDLQ(=TY=(uzdlQ?Z>G97k zN22j2b_SzDynB;;<+mIt>KaWn+s9mV$*$;N@^y?(4BW&}wF3#e$qWmBGS2@RRq~XXA=qv<3DcMCiORR%?upDf(|-Cs zu75+NFdF{tBwr#w;e(_}7*x{=yVZ5s73-6T{@5HD!5|*H#WhYJojALU3`Py&oD1ai zzf+e2%bwDH`U<-dNr1Q>`)slml|YQ9_;REBke{rt5Rh8r{ogQH2J!n=H!|SX%{x9IH%tb2| zorZKu2{=^5-B9dwt}=m39R^qO zMC2O?|3ob4qa*?#fpUjJ_wtRy3~>t}M;?}t>mh04u&0+Yaq&l%pEA(E<{I*gtbRxA z`q*}fKl%@1*e92BT)dw8mF%{`-E{PjKvaF2-m^SEylz=Rz@URI`%qcUw4ZHpK{+JC z_B{V1&~CCS5pa7%YCLDOxoh_dU=!yagN$Vj3mp}aEOrA}cEMq(4mR!5b~}~k%OHzr z&K2XL0rn^Jp=gG@vj99YJvx+hEskU?qC)GyUzhmb8OUERlN5icnJv1d-=2v8mT;sC z|1DN8m5M!H@|ujuc|J(-cKrn7s`t@x+DYfrWN~p3C4)tF+=s*~T990WbD{Ccg1+0& z;sm?OkrVD&8x#JT;IG-3@?;>*t=AIPuazzGKDH8^ZJXj$JqN*RN*#jyMg5+I!<0gywElS}S$ zjiPYB-X=ZefaUjjEO2Y|gecsZ|I$H2xv&pldWQGA{;|iTBEk7R7R^R;^+$4{< zAC5+|?V8cZI=m0XWR+-=DNkW4YgRQ1OTUDoIEiWO2*6lbXZr2^kHqdH&U?aWwoG>O zSU&T+1f^g0ccg-E7&G)C1eG9tN&$=os5=iD{|`K)89R>dbtb=_56BrBPXNaXA2EI+y=T zu*-9+%d2AChSk2s<(9hsiuCc3V$g+}3}&}RFI?%rTVeHBg)r+lK>BcPC>$!WXnjHr za+`41DjfSRsmm+~^cINm=U9@Z3wSo3ZFT=(gu#4Cw)oSzO0x2hOJSNhCihLDwoUhaC&@^D zw6l-9l9x$KOUs)P0{e1AO6bnSbM}Cc!!3pt`H1#@Ds!cZm3+r9hmoIn|9e7!}lspm_j;G2%`i5IO014P(efmyVz&z-@~<@ z#Imz4=XXk|6$w1DBt}t^3inUv$Xd-5bAi9%!ZFVcLw?N6ueG_I>$E&4BbOS5^FE4M zOfyk43X(aBfrF3$(fHV`gJ0oTQ`#BIdemjDBRB&zjzj>)!yhbUG;bo4xXQ~rf{dr{1(4QT$n zzNlKw7QeaW)0p&>vir2YhyCqq3krBJ?|*g0MZ^i3&hQH~D@a@m=xr8;g!MkFd&1ZQ zr-X#-BK~1MEhepJ5$Oo#f@s7G`xQ+$B&K2Zd3(A(FFNat9`vWX86%JDdYj?D>_Q^c zAb0JC2hX3z0IOeQ3GVn47!w{y>M~Mr>tfT=)A@ep)RNY^9+;I_(d@`hM^ZAZ~JbIAE!~A4TYCCrU+~Zbrey^RfbNaQpM) z(I498*{Q^I09QxrsxJV7kx${W86Ch+jRv%z2?R=8LHl&5u*GVuz|~3+Zm?Yj>`z(2 z@h39`<@!?^$)+2(N{eqIj6}8aA>XjFXv#nqeX;yN+`vF13Yr!KrsAEkbRNe&q!mXK zw8HVo83s(RkLF-Bqmb@Md&o03IPn2=mKeYd?UlB%$+$(gdRHaClVG5Rm8gpvfQue6 z5P=snHiCsvw|u}*@+=}v0_iWS=~%o=ury_WgK^(PJ4Va*(LJK8r)Dhv8*n;QBh6sL zSn{jG%TVb{eh(dP@wr*aSu7DBq*V2nC;Eg7O^7%fB7@=xvwmxcTe!J#Bw%qoYPCln z(6lmiM^uc}4;}m+B@(#vJzPvsuBo10QhHwi{o%|3Rf5J0UciIpqRCi$xBvC(@3=mh zeo&I5c>1l&u;a-eW&@bLI*0))!=gIy0i*IN1{eh;a8)=YV3rT*35%y5B4y=j zic`do@~1BrJ#0&>*cN+2~F3nn9KAE_Fa zu_sC-aolU$DW~SO@PWAZzsy&v0a=a~pdDEc_KPo)F|$>H-eQ2t*~T@5!|gb^wa9C+ zBNsd!Hni*>DI-stAr<6~5qKX~H4i4(6?dhR+Yb@U6M`n`xR~D4!R+f^IgP(nN~UG`1tTYVCVsUI7s1eu zYrb}>U|~O?`;@?dpC$_kzFXNHU2!rL@v;(Jd6#83kCoG&&yRjAh~nAboXGsT$Ox$VnPkeYNNg3C~xv_VqhS+ zWmHvFp&Z%R*fiF@b~byD zufvD86{i~;x<)TPVUAj%*o->mw`XTISfl4|2>xGW-pO}e-RiyD&gN!~l$z>l1>7%g z>fwa=kDUr_HO5kGIC%|V1qr{tnx%k%LDq<|et)?S%*$K$aeuz~ z8<`vJh!Zq?0G?!CSiv2oXN-wqN%Lbd5&@krkg$b%6O8?CI+WkdtcX>KXp1Gbb z!Oi0N&*ln7lD65dQ*HioPx~4PT8E>hnyj;x260XoF1HU@nlGeK#S$&p?R>3dV#cdM z;ERLQ%Wx*pH_imJT@X<^dsg&xdjKU#R0A19wrM^ z2{kup07=TJ>3XM(f{u-cfNI`>JhqUv4vvWdf`G|eKQ%y55HC7^u(rC5oMqkuv`HI{Udi?Fo6GOc7`1{cJdcS~T2}T_|oU>hX?qHiPR_t|GwmCR?yO zwrEn~r5-Vv1(u_eK_Li)S}j~ur84>A&3OM<6fN{G24vdpmpmNy;-L!d_PRBl#qIr^ z&GEA*c?h<>YqYW9EO|*w8hoS6^A@(9$Hnuxu~MlTVV~n*4hRM!qZ4K!;1z0( zA|X-OF*n)ajXQ(-&Ef?5*je64^`Iu{{vpre=)5t>e^x)38K~|2yBt4Awb79oK~R+2wJwhpA7gZ2XSu=%VNGVLzWnvSeAor15mv<&lfW!7sjUoh6dGSAkAq znWUjR$lJYysTmVq|EF(%k5=VLu`tQ?S!*A!+6?;xHvvsV@tCa)U$iZKu02G&J;cgo zuuBVyW3U?5Iy5CbBu++NBJS38oqo4YfDwyLC;`JOUqApOAOOkm zYWVhW)_}+TV#CvdJ?d*S+8HqjFNcy$F^AVqg9H}+mW)d)$q_sU1c3H#(^*Y)Fbb3OK02g6WE7E9#QgbeSnk#>tR_=eKJ0ilfa->TDvZP%LXsFbpK z{zD;~ScCcccF_R+lC)rhWS?iNO^c|EJtYzLC$ew=9SKSM+97X!h@5wcv!YnO%H4 zS}=eKr=A@SrjQWZhqieR=U!!1?F$582h%6KPe6~&4^91_M5zcXV5ex5*!wJER_N7+ zkDnNkdUK9bHRH^n-JxKKgu;m^vB`#ltE}paxIGWFxGZ%Fl`BnB7V_+K-}dDWm;k;h zuwa%Wz$c56c@U`m6FCZ9bh$v2CfvQ){MB}nzQUyF5D&g^V)FJkFm($lVN$X1@$2XQ z{X#0AXnGz#I-mBaP{hFq;LrSD&)Y~sB-RoY;&cmX!B+T$U$f9yIhXwLqj> z9bkL=j7-FL(9j{y9UoXw8I@X;UC32{kC_iP`!~(t0-x15m_Xe}PLB65+ZkFMK3)CN zU=_1ZB_AEWuh?(~jyjtqeVQoI8s0{6<7>rr{yoouCO&`!W-$dpFMuQAi}O$W_w}!? zFY4_6`HOO$;0GETk)i)i9#;`j2bg>Ye$ky*y6HBbH(!l?Ag*I@$Ans#$?ylBueY6+ z!#OI@06>At$ii<9IM{>jpyDqJ;(aqtZU6d3<-Ku~FVc|G{Dl7+2u>)r(O4pH>?Q2v zx5wVk_td3|dMX!D#~N%P<@`%vFc`qJ^zswMyGR`_;`9Yx>sZ_2)?J$s#+ zYY{sudK7qeEir`Px1#@pqqAU$s_UZgW$12@MoPN7k?u}O1*E%khE${*q+7bXkw!qe zyFt41oA>(z%nbM3bN1eAt>^sLO`rw=^M$6@IRshG>bg`RApj8ZA}&i<{%fV{`4aVC z`OAdZ+cUMUp>sdWcX1j`1W8D`2B6Tr2|xxM+b;(8NhdsxW`_H7fv<>G-8$>JYcSwZ zc{780a*uTlN*t{6<5rU$X2Ocou9&o*RfFmxG)$v&JRkd>_h~?4v!x;roMQ1 zBqAMg%`gFz>5h{*5*gdYUQ!m{_rHJ0YKEoj@SOjkuCx{gQqcrjD>h9ZIa8~Y`j>+6 zJpA+uibzMDoYnn9ec-`nePIlH;Zqan+sG5p{10pU(`j2a9LE^+gAGE4`5f@TDyH0) zO**DYn}%qx8vNH5-5ov&a7R&p`T0;_kqHeATXHY%NL|M`Bx@2qaSr0jNQjq zoD4iB)vyz%V<7Y6`)%}9ci;WtTc1(1Kb8jN;J^)tl3o>ylU@?y<2Q7>4L_wy{!?Sq zVoxJRnIVJc{JTg7DeOP%6Vm2zGiE)4J8+3Q-9HkX5ddNzeq9W5XOoPn4myawdw7Oz z1=qM6c_(D&iu6*juf+_qa!ygWt8!Lk@D+~$K z{yMHNe$7@^ElULW*Uws@+ms{MmRS^ZgX*_Z^3FHVdoz@f{1{q@t~bw5nw!$cF5t=aS2xot zg|6@Wz?6qxWV?(o*nFj9MBFAjGDiZUiZACe&8Y#eO-1{60mTDtE_D8q5c3?MU^78g z=wE%D-pi51{y~@#7*%uIUE{hL7U0tcW4aT*%Vx^uN0DpUP5$H{{x9;t{6aWgtP(Qgjx3TW+wrvEVj`wqLt>JSWlAzEK!E>^;9#CC| zrSt)I+A@Jb&V(>q7{JO;ObpQ(Ea0aTZ*b7|HO&)yQF9o`{Ub~>o*4S^m&*eYB+JVT z)_skK<~=f9Ajj7H-J28h_CUNWn^Xo&D#i)3zcckKZH0j@^1-MY-BvVbn1Z;wGv0;|v<`sy zU--z0hH(eGUrKjt`l+Yyh{TrC5}|)R8x#wKNm^&YLl)6j(@3JF;C_T}>C`mC0E`lQ z#rLXLCStrwR#EU+BHKE+3DvpcusML&4m&fZ1G;n$gjMucdOweI}bSx8$G=##0Xlwx|uzHq|Q-d_Bz0cX;(@Q1EEKO zQU%Y@3cV4$27_N<4V@@dkSSST`?jfICi9U!?`W^CNRP8ztK~oYec&cBU}C=!FlPXa ztx=yu592s_~VM=9x9ae#h&ysT(+L>~UvN>0>Xqc}kGa~d43)xn-!5`o2>ao6 z3OEAM8SecHx9tw71J4|~(4Yp`^ay#TMZWxflypQY_k^swW z))k=bjuEF`!f*;L=_em?`dA=~?o(>TZu?S;T@UydcoW#!UyGZkm*iv;sACXvuaTxETQEUYOX5XH07++08d9e0dP5wSCa8 z4V+el6h*->kVH1Ql_j2KqN;hxyP#6Uo$wlp1jvQrnF8Jes?vhOR<4-nk27k1yEL?0 zAi(f9fVFXN0t5II5~vUercF~#cR@Wfmw#m`{`0_)ty9Kt%Z!ngt?y?CvMv}HRW}+| z8#O#X&Ufi7tDCKQza(Idb$uCr&}iQk`SzUK4-*C-RAuN<@ec7gTQS3Q=a> z_uCuEJEPgDooQnsAu>khY)S-up!`n;yo&h`*dM3SNQ!ZvMDK?(Y zqv+82U|G0OR$58a!cw500u#S(U%lgT@ZGpGslc2YWvD|`EKFVWrcaC}G+P_7Jh9iQ z0&bXca27q!MLhM&djyXX3(14|C&O~eD;(`|X^Au>_j@FTnDHxAy&5)od(7&0h7Jq|lL$|SGqXMCVMS?4>d&}&lDg%Jd^j*QMqE5I#S zo>YGz@=+M^b~wvj(flfdq1Iwei($Eqn%n0brHy+O>O22%*7;N^eDNE1rD2%YILbk= z`&n>Z5+05{vZ!5E>&{u4GS=QWLSGty#H~O&V{$`f0ro?twUY*(!MSY{F+lnOf%W{r3VAoUw4Q=KrtwZ6&%mw z2WQ2}?}9cI6-|RL7a|0xn?cCc(_pqMNfg9~8qm3_2T29pthDw#zu2vt?X+-S4-ghU z>2K4tZi1X8RBv)lKh+P0kED>mz13?{B;KIANI48W{H_o5(h|1l2F!x z!{{V_2u^RO!)2Mt3*%AeDPB*w;hSCTB8usTi#WsCQ5lK?r#O+u6epn26`#9p9NYUP z0CqR;g#aB|W#?o#4-lyz>spI!4MCql7#avVvrq~r7T1@w2!Wk3O7S^Ax%vX6WY6hD4gwZJ->e^TYjC#l}Pa zwHc_!AqTH6F8|IKLyOf%@drm#Dz%YnhmOH55rd-WbNGpI9VHbuF>@3#kAmpK4z7jS zJM5lQ88Y^+ah+hGie%~p2-$OkR>i~5S}>EzAu{GFh|o6)zHk$SIzE7Gf#4}*%?@-6 zzU=XJ#Wk%5EZ=_OKJzZP=0BFL%m4m-#bOSwk_rW8-zx}p%fTIceY(2HfPUJSbUF&jLR_inJ6Pp7X z^<;szujNV^{OZcG(o)rHC6asdi;P%${>6!jMRGsJn~s*{{b`l~U`W*FFJaX2R*h~> zJ|JEYMArJlHgywSFO9VpN2<2ql{mR~Iw;!p*#n}`sB#|%`SR~(_}XEMTAkeW?rFXv zS)_|Ot|N6IKd;hl;yz{fwn(l)9#kO}8sHN#9q&udAAW{=xu5yudy2R)^#~S~~ zwM(O_kk5gxh0NCs#i@D6lOoR!)rwupIPVSM!zLTkmYEv0GY0yYs8HyM;aSRzKT8fN?9@Q6A4x|Hb-F zrc8vFqfG{dpMVq|;1t%agP#Z8>wCckly2<1l&`pFO&WQw(pGic8c20A5b00dZM`KB zgrnoe5FhKl`g3omoGj3jSO&2E4CvL+(>oQwAG!UPSb^H9*~JZ(DC?x=xbZ5D$Kb!M zLP0_T3B=MM7(aNXU5#Xp)J_^SK3wgi{z-@Sr;52IApEUA&jC}iLi>28k?s$|tZ7|ug_tE-bHOz}+K?~q#9PmoU4f&m zXJQ{E*R*Gu8hnf~*iA)`1Ml?=Zb&M)Uj^*jVBm5TkuW}-aORv+;U1$S7+%DV1sr-T zHU;R*)jM{*=mgxgtq()1popinlCsB-#-*F^zONY`eDW&cZ5&G08gUAXr}DKnbLh2Z zqpT~%LEJ#Qjod6C4i<)eRR_SXn={OOOaEUwD}NKW3GQKOuFA5fLn}wGEypt$<_%qy zrIJtUl@9NgeQB$nOs}6g*u@4OmI+@dQP+LpK0hUYyFPJHgOSozOU2RXR#1D=+ZC%;No>aVEHH9q=LH`t4`;&>C?vzsuFA^x|m+4mNL`%`9 z-)v6XD_t$yH0rI<&PL?&LP^jp9a<^bzu?GyL5{RwCCyu^me#+w%6S<$< z*sGsb(aiGWkED9}_V|1*ydO8uC?cm*;Qo`>DHFa63>~R!6Z=eMI`kK*WR~vz`&D0u zYRJQXwJ4@ApHLZMvGD*o?4y?i1gn zExbUs&e{NXisfC!>B6yQjm&T`l_+6g?1j88YEG%Ee@r|KE#5!2>XH(<%H}N;@9ikQ z9cUfC8^-+JTgOnm)A)9{u684{tJfpPaFIew7*!~j?4$8~U*VH=Ad)W?r*H0%X4MmA z?(c1`I&YmUhg5GZsfTjPYMWPF>$}i`)#KJpq@O z)XG}3jUO&&{&!3-Nc%It@i ztkt>cZTFj5N}z~pv9AqAkDI0zl^iVols_J8RJK1{q@N&}_q@#$ha2M|zkZquFGx=r z^842*{1DQokcZTCLqvug|CxDDhs@Bgcp`bQq4;pAYMg&CtaA4GqQmobWoZGNl+TQr zL273G2oV(j(#Q~r_wcL4Eo*){yuT{u8;%*Ffrjy!(^;9i?o-BmU)UzQ11U$v{FH73 z?@GCC6RB2xuM_#!{WQH1TCc{1W)TZ#X?!2j5zwmY58dT(3Pd2GvXw`^#}!R8SkyEc z=bx8*--ag~SExnhc+^GE-jneTI20SQ5U~r_B5=M?vxzJ8aFY_v$AR7acG)AB&gEuy zZvPol{?vU#OpdD#DW}qtpd_M!@temJaidec5W<%9{4v+eIL9O_9@;o=&87$@SpQb3Btw6NQJkI^2ykIp#o`nXLa zeUV7vAWs%IK|`BH^)55h{+DRpvJZ2npEf<+1o_vvTr1;IgVap5y@JF!L;p+0CaoJ- zvYsBgt@Mvrhu?JG2-9}N*+F>LrruHw9c48y?ER%~uD#*=Xm~_qZ%_0nh4@r8bHIg`vkFg?NWzrLmrruWJwrAf zCi8JUVgV|M2{9SB@ZGKaOI&ra3xkn)D4y^-^?3`a%n*kZW50|3Z(9V>f|$|#%To9+ z)+p_c+bH^AYtc3*=-MbH=g+FoVa;L0j_Z~@w7WmwygaF!DCG=I@%*PH$0QaI;p}O7 zpWn?RK(gL4?cB91Y$TU)=qlX_(9P(eOpZ}hpKn()YTlmdv)U4N(J%!DC^c5S;cyX> z&oudrRiP?=hqPf;WW7apCRNM&ah+ED3UI zQ(-;CCHJ;mJ2db9NTnSNpcSucGX7W##PfKGi{?M1JIVXOTH8Qdy{Gxpm6O+(-$yg_B_QUMpB_Ppo7q z|2y0Mqozj9BL^++zcLTy6rW&!p?!I8YrhH(Y9y^FlIP?dYVu!9TQO7Mgj^3TG$!Oh z1}MJ-jc8eCmMN50-7#e*uj_hB5&OZD|42#RafQ3|(9Xsuto-HHf3d+u<#*e>v2TT8 z;LD8y5#a?p1|L#q4MGqgLZr@yMczDQH5|yEn0pZ-URQRY9Sc)+_ZiP1S=vY$h>Y!Y(^<@fq)@t;1UE zy*@3wCHTq@R#TNEc=@uS!j>d2cl)A=`98{J<7p;I#C2Nl3suWe12iw=UW+o;3NIIi z)jF#1B*(c`Evl+2=01DTzRz>=VHL&`UrdTy7PdK4MeWjNueeDL8Q+`^c#D%ISLb?v zA^z{&<;a#7&*r`imLHCu7z3SLSnq?Tv!TF)iC%R**HJkDf9)ZuTKTOC8g(%+N2Iak zbZ5>rPBr1sC7xRrWYQSaSl8Q*eR%jnvgMS{CE_C@S8lC^&o-c{rOgT1XQnLvX*H70 zoF}HJ@+&ks@IB1!6Fh7*q-fFjByY=cg6)U-_E_~@?9jiaJ{fWpk_serdA@PNnLe!# z2VwmkXuZXVn0B8KLpOed2jBmc>Nw|^EY}p{7i6gwb{|f^p%VKOWB*Q#Z7gQWhod5O z{?Ur3%#^{eHxp-USh01#>h!Ln^dodJli(&6>Wa`!?6OJs zqwV_Ml+KoL;pr`?urY(L34w8*wexbpnfKejxPrZ&}_Edy5va$@p1<);|0 z+cOze^Jy(p6(!Gomd)pDQzWF>gidt+Faa;I%ks|D^>Bvq$a3CuQa2;>T%6$dbCQq z;{jHnm9D@*9!oO`eJ7ouK`C@N76srvOox$i3M6Ulso2c^#S=T=O3#yV_9PiIyntd5 z^%jpbLYuETB^QFFOA{6zRsW(}22b6RCPchje;V?FCKT4*=vOgRYQir<~KvC~A3uU`$JAQut1m}U~S_wr{0u70zAh^|_GL0hzeqHmgnp??wqbY2d z^4zFD-D)M4qu-G2s*x9j&z567y(Aoa;3T3}u(6L0WRwB0G&NF2z~dn{Q0v-n$S|;% z??y_D&5t%@$J`R?grbJMv4KaOFYsdp8&F#xTTdBV-%E{%r+Y-E6>R(f5=wy;>Y!Or z2TWn}UKk&-FUXI+gCPe*vN_>0nWX?o%c zpg9FSm=RE@SC%@cZOYb&E&9Bk`=~z*Iv%-&8@%Y?7;}#Dpbpibki=Q~`PWM+mS_sa zh()2I{4JsOeG~6_sdeRPHw_7eD$3epejy^I(~47Vyy&4C04@0ZVXtGsthwEsLhyQs zPBJ@~NKYy;ZJN2D(sr)R{BF%fzJKWbjIX0yeJU#w6|F^TQ~2?jo+Kxi7?BZ|P&feR zK3+Mi)%ruGZm5cg#S-mq@&2G5jIQ>ELk7_6=);QKo9{I=@V%;Uzu_=H>s$Lv&$>gg zQuuvYvEesP5=(VGGa@2HDmGtqc#Y1I|FgIvgf z{lrWH?L2e+vSsG4%?Y7y3vb1Lc?f(O&cz4v*aB5k57~T`6hu|>UAQ8of51xoJ2ODW5nxZZE=tvg;h@8ts?A2T+!I-+Fs% zu@^Z~6GCHT4SvmMK&~msraLL}HtnK{&sfIYKeuAW}F# z+*=rhT-yGDi-cT|#7#Fi7tXuki8te=yfRulEA72c!kl0Nzs0p;8}Tu!^##w{N)DdO zaTv-U*ZM+R$xbu9Ea6@W$sR#cvU zMToYecF8-qk6Qme=pl=_LbQZ~$&gMKGT*O{AG3*siDYXL1k4uVCLO!AWKT*03V&#eK|3a+iE+|o55Hn1v#MufhwN7yox+FDjee=tio%$FgvMX zUbu78ZX8}7_#qvVfteD_m)CGa1M5W&C9n3@_DYsj0ZAP4=4ot7k!O$dCHxg~k!xoI zM#9k0HPkMJe&M$hi&UALqM=Qw8{&@|HW3*Q5~$**eKKyeQbLxjFbgb#GtcKfv{s`U z*Fs~uT^Q;bYSmI9p?SZI~UvNZJe_@l74g0^MTcqx@v55edjqlNEg6qra;^&Z(gOaQN z%SKoSzse=c-niHx+RZW`6*eU?N&d-v2(X;iG2NrD1N5-8&|Eiz-*?|EMzO>3dvR?= zs>Yl)N%?rJfZqekL$r)YR(q4kKHU?f@^yUDYXl$kJNaGrSj@l?J$ zBZ;?J7@aR@mMo_lwoR}!R`h6UFz;en`~$kr^8fgL8UAeyGbf&jNHk#W*0`sh=?W58 zZs>ouBps;GgB1EDcOU*8^DB?5=8}@wzU~t<9j;VsveBBv=PuS%RQzaGOnTf_lYk|W zBddj#6Mh+1Q_5EU$YC^vmdbi;m0@wyfIU5`E#-m-ES%HBS9eP>^A<^AW(vBaFi`D3 zC^k;-tyZ2KjB0GA|FSR16vl;`&16DT3F1vf469Q%nkK2t-6O=Ys8d5RVTPX5lrQaQ zfex8Gx50tf^7K8^Z4Dl{5+ww{RTl=dg?LrWGv@t@6%=Z;LBiOpUQ4t6235zB9Nq|S zeUwr>Dujy&|54R!{xy&nT9}LwZ)^VUQl-mQM*Tzl*R4xKHVbgxLNU(fBa0U}lE{GH ziA7C5w~5Xv;`^2!5djB2oGzA4_7ao>cvRZ;EAb+-QfI3Nw*+f^;ZPCA4i2d^a#Ap z!&g{KmaE&_oa4OQhla0qF^B$P6CsAj)1TWH{njdQ{;pgH&4BzFnx3t7JJc9tX<*j> z?WeFYdmZyYD@Eg_7WDLZTt#hcyM`}{Lw$GgTJKqq0Yj67b8?8@LRIIZLIwP!Bv^_9fz)Hc48^E| z!u0Hswv^9x@m-B8T@H4J2{+4$t-my6E%5DW9clgXecaJOkYsf_+>w3r7W0a{f{#kp z<%8^b9qKh+{TF;*5EAOD5TcH@Mq8JcJ>(>)G28Zu36&U5<~oh-rOiGLnp!9LnT%F( zl7#St26X3y&FoY_NzU_Ddb&gq(j;K$1nQ&J9bvzHhJ(?ejDtZ^_i&o%x6ugC z(bL(hk89f)J*%jiNg${32#m|!G2=`40N-1_UW3;WiEh|KCKeXOSEp4L)7LQD9Vqbc zC+a0;@TpP?vwr*nApS3Kz0;rR_eQ!+p1l?J{HI3I^W^7u+TVw>*t-U?oq}f>3k+@N z%Hxo6>FArR-eVq}2X&9GedNp1tFt_t$P)V;PD3+^&<4o%IqTXGlNPXI`=Hf^<$3&? zDuT{5U(nL($~zb_$-JFd-cA+7DRcfgGW*Mjvi&ij_^NyvE4rV^(^WRz13in-#Gu+8 z)(4VV`)?|`?8(;y(PSjp_RD!titn5K2}~kpJKck6GPMd8TNe2ba*kS06RiXMbjhLTJjx+z@D$9?E%W& zq*hpT{w)CMfU%bXRFabaEx%tT2%xxF!-hTR2HhfwHsKN2C4E6;=}z9B>{nMMdG!?AGf<_!@J0QrO#9s! z*Mt_mBsKZK1%kDa5wO9xZOOXwhhKPy;3kP+;ZC(81}X5HtwZdHeP3_?8!MS+;U{%L zUPR=Bz-F)FYSW)ANGFgVY)xfwKg#3R-J8(A+xRMC$M$h8!C1*xG=4W&_rwF5^&n#t zY~O!t(*J3$qywNP-wJDLR}#z#9~(n$pesndg{t`KY0_8Q zv(l6m^1iRkWU__&T;#sV|3Nve#!1OrBRiBhS}H)m+0>)s>UB(?Ny1-QOGN@@Fzj0Q22s zu4L#>Up-jQ-}+)NxYsJTeZUcjUwZDQU|rutbDz7AjL#t>FMOJUg{p1?eSC9J!I77l zF`57LZ6`sMD&CIo1a0`3m)_=V!s73LvYQZszR7q{#pD4siSG65+}BOYjlM@n2koDN zX-dZD=mr^{{T!f^HrPgz28nR-Vrh7T9>B^)0+xKf!&^uyCOge)>q_IfuSTjCy!!-M z6abl-KMpg!b1JVFeGd8N`9V3IhHup^fw-;T*CtjYys1n|_UC@2StL4Z0GM5=jyU&Ys=)|^9VWkqLT5l~=Ll|-N=b)SxMTeGM0_h)K@}L5)!PlB^Z;_+YYS0*3mjyJXhrLq}_|`Yx zAw5OHSGP_I?^sY^G1MqMZT_@H@o_C&MQvQ<7xG$}UshNB7*pm_^2mK#09!By-x$S5 zsZn?z-&tQ5xj$KAewe6=GsM|~P)Wtm&;B^cppBy(%ID;4TBpaF#*)>ir)eyuiz(4=}?is_X~t=6Gj@bQ)275j( z4Xn-7IC37iv9Z0jiV!1yb+W48y3(btwVJQY_gcyPtC!FAHof$^MxB+y8#*XeVCEpD z0q!2(G-`5KCCxVa?~HG5euor=?MIX&n%s)tghH>?js0)53u!EjRYFGma9kF8E?&pdxI#B>PutFx zEEhKqOcaZ2QcBa%F>FtQgjkGjpKIlGR03GGoU_-Y&k+|v8lk$K+4I`}cE7^I^gUzK zlwBeSsb1o^+w6Q`gvlhAfj(1n4}zJIYaP6@+5u#oO(?1-30LKt))C9owZQCE9CjW& zTRU1W(ZI z&W3-CM}VnBxb8~}Pup+Gw@JFoQMvf#sKmYz(H)`#avA@*7s1RNxEWPDazv*V0yVB` z-DJ#B{WaML@}vkmYx}%RZahefRDZ&!02O$#2>wc)rVM&rQ#eh@e_$ARhN7A9rxMKM z`;I1~B6N9iI{VfnU{U62C!52?`=k|g)aG`7D^C5pJ}wxQ*Ja#`IXXoh&9laCd9EX* zCU{}5Pz+4^ApNhMvv&RC;f$ps64IE#67jgOONi+60qbAt<|$`1k-EzFT$!nX9Q9m)!K zb}2gkGQiILZ)3xv&+H`A)-3Ea3r*Je9(Wix$@yzipdW;6I$ZEjE_=o0?Z@@A>t8uN z;0PfFbvroWBZ{<4r9Wnb62V|7{}_s;$FG$2I;k1lfodR;OQxLF1ubXN+l7BNaA93v zAR~HZ2F~LmZ*yq@E7D8cP zX_0}Nvkd1~(=jdtUF4J}zfPzI0*Rnf+fyU`#S`tNqz?6AE)XyWYOZz=z^9Cj?kzUU zkHvWBtI}VD(2~@iULDh18>18CQB;eUjVhb@ft=lk8_Tqx-+fPIB38tfU?k!@TMrc4 z_S#-Lf{Q2ji5Cvx_7-kYujsYh`fC%TR?ckg8GQkyMxY>Z1e6vyA0fbb-2aK=q$i9) zy%!sn)BG8oMO`KcAoEXANMlnK#PCx0xfNv``LyR@fwus~pgXw1$$oKOC6@Er-N@(k zbHv1h+){nD_^y39rcO(#t`H+}(=1KF#31=mjFFx`_CKNVW^5DQ=<#nt?cUF~@HCi6 z2g(a6RCC_jdVznfif^M7i2*61l*%=ebaUdrzfP#YQw7c-=!QQqgkqH=nB1wFov8*Q zaB#ehWLu1v1(qg0=!a8Sri_TF+DWj5nt@4@ZBFSp&Brvu9=^PE^Ijlb3dV-hKe~Dy zxH;hgdi)2#Ons=1;9>qWeAVc67$yZPTRR{G{H)&T3mhtCTi2R%zRe23?EKAhlR;;@ z__YA7_0gH={z*28$oW2gE7)=7IkITbc1y zj3fY`L?AJRg#?AQFiLEU;N ziHO~rvwGRqzj9H={PZrHH~aD^_Plo1zH;qMPltzf zSg_iDggKA?Xrln@)0$$sVGjL2@~afWiT8&Rm|g!J{y48|V7R5|{9g<|lD_vpdG_T~ zU|ipLCvs)40fO(+H!DQPjr=K}Scqn*eGET7hK!2(xZIDXiiDS+x?dPB4ZwYL46AKM zEFH7P-V1H62GQ}b{l1Jeb*O^!ywAAi-I~~|ZtB1HKa*GS#ec^n*xDeP-UemwW{a?u z(Y+mSz>Y3LJLnyXxBKv=f_Pg}==TtAAgQN~@Z-AqAON+u?QF-0>2MLvecfyK!K+r7 zF!wuvPlVf`L6V|q)~PDTui^0D>s@hUoMa-~PUbfJ(125&_c=KsoZLswq3gwCG&8u^ zd?*WmJZH&*dur0CQ%eOQ9qdGg=pQI)oy^duC&k7EFNx4yuVW6UU$er5A))+9Kknb} zN|0aQsdgd$5c48M^(zV&o+GR`Ey%}JQPqGM-hO_#vX=m#MH2IjfWdUe=+UVP>*#TT zG|{%d;C^G}phdW0TKYd1bZPdelR>B0$t<53gYohR``^Mi;i_?-8dg}XDRIMuC-TO{Pjqj|93w9h@%26O)&$MR7{rpb@%-IX5M6!p*SNi3^Mn% zUUQ@Nxb3uc)C2Le?TX|}h8rEl;d`F&*~H3BH0Ut8-~W~0NZKN_)1$Wgdptqp&yXiz z5;4d~@5ds9=&f0S_fOs@j!Ei@%QR3M_s3I6CFMbn2_9@gtY@B~+Dh?9r-^iUg}+Ts zy^@V1qA!B0>TfS+fx3}Z#Z(XFt(4+Fq!bXKg-gbN4p|rI!7^a+y^PhfmSR{84kq3G zDg)v3oEZf7#uZwU2{~o-ezc)<%8UJ;j^NvDEjAVl1B=mX*x3+RP}(sg;q$6Yz)v))}&xctw0tpfg$tWUwhxRmFv z=tI!EL6W|j8I4L`tsg)gVy_Fnl3 z3~&7G2en6eB%(!+gU(_5KFce^LvI3s?!sPdGwpo#bN=VAN*<^4N9k3P~myYzEX5=UGkXuS?ilW;k*Jh!eq0@JSC7lp)gQQ%J>K7@bUjNmz&6O) zkYOzR!3ZhB@o8|{{78#D$sz#x9Rk2FEGLA^eFsi`t)wQO(LV}W3@ zl9GS~-1rZr<~64auilDT_SS&jU(hk`yC&w)n@Eia2u?4I#GzTDR|0%zUER9~QDkkA zTDa2vFj?3R0|EMj>Hz$r?hJS^Mt7afETeBtg;ZdyJWDetT9>u@WJIj7C<2!rX>>8AO5}AJo{+ZTB*PeaihE5?hNDU+3xiAFpF+K zYsJtb2{RUbIenxPmOPEKEF9;f%DWbL$DL7;7{@^bid;5bI%G7c>OL;^=C>P8d0o-1 z-Lp}%;ER1@Oo4(WgM(B^05;(e!X!0L=(4g=turkSf||*rXv1OLq29w)E*_KOYHUp13%bnARewih-@&R>>BOvsl*5Z(!rSHr@z zR%|71LXG(I=Zq!Cys}wzWP`@cg>8*PTTK-4TYqdnZV_Se%VAuihr=wPV&Owps8)tI zN(9pnwDj~!VilkXZwX4*+LfCG9sDsz7A>N32&OpIy9HFhDSIfTs%>X)RJzrzejwtd zy_Z+~&qE(CK&iGm$vsH>A!`Cv$KS1bh$kd@Ni9%qV)2YjVTk}&35jnUBB|vBSkV@AA;p*_gdOi zsQ~GB@oHwaJ4N|!9R2<)pH+NH_QS!o+5p8bhQ*3+aWV1+3ArvXG(?ro8(PL*lt^lC znp#=~sbWx9)h7z?QaAovPyq}B2tEBV;+pOcJ`!`lz8N+00#=mLg!r@xBlH4ALFWS# zO2lxS{0r!<*Dr=xZ<-vau^0)ayO@-RNnjrH0HIoqrj+PhKa^-8j!%u|g+noF;}iG# z<{aaEraM}*YCWt*Yl_PKAZm8MaNb{2`CN@Q;i>B#nyn{H_6+vvXZ_@U3qswR4<802 z6HXRW7&Z5A60TU=H8CiJxoO(?*1Y-%;NCH$*AFIrvzN_8?Lx-l0rf3Ka0}EkEY~TY zh=b!WwEHQOz$H(A^$eR3{IsKUwe^ctGKJ48Huts4p{Fu380fyaGNdgcWVXU{E$w#C ziVhx|sFlnsJMiY>5DE06h@*al-E|IRv-EEK7}#VPJhWFqRY%zOesE1|v0<5d*@NmM zdu(`Z&7E->!8uIoX7aP8gY`6{w!z+23Y9W(F@OeY=k>J~N)v4Q;bz??Ez_r|YJ-y5 zC`0j(l;T?`uTr$)eC!^-&YSp<_5!`Uszkx;1M&j;jbOAW#aehJ!c_{Rt3?%?+u279 z`$!tB=W1TWOUxU9)Y$d;jOL0<2s#`1jIyesZk_uT#2+TVw84HAJ`E|@#F9|lB68wg zsZkbJt#(!YLNu9Dl+8_$7bU)7f8LpnP~awKO+`;zx*xe6>NjEJEq}+-=Cb?rpobIb zH9Fta`!fLCy;VY)W8`^9q}~FniVlJ%hNb&GF{((aPVW?^7Huj*0;pIWOw~-v_;=0kzFl>bV&b&agYqNhaju}|^!3Uq z7z6^ISL2#WXs|Xh@v}_>bN7t7UF*tLjZ)O+iyAjVfM7HN3L7}z`_!1oXF&l7qfk17 zMZz1>P2IZks>xU&Lm5kd__A6bOzE^}k+P^Qxmso#z^sTt&zw6Hq)jD32``GOadwZYh}ThsI1=$rYgDRbf=7);iG za%R1^uX&kFuCqK?xo8A^Hphv%?P?_Ns?X6jaBYp!?)N zI;EpC3#Ysl2^lY6f}^X*)(z_(=jxd}FzcG)#;$?)Uo$i)ge?uyxFXx;Y_P$%AAr@xfG_GK6~$HHaFzh@NNa z1c;ykg1i~1{GNzv%hCwNl_i9F2v-zX1VnsG6%~$!X$zV(=8l(Grj-`Z7*Pn_1eK}(0?|Eh}pV;qh zT=C_Y@50m#U|>;A8BPL&vyNO{QjB3i7mmE73U#=NHQ!u0Nj7w1*sM$lnhRSeI z@d}1B1?YG1gL~gM1kem}`BE$@$>jh}OqR)hRg5;I8yeCGvAqV%QopEN=fl8owpw~% zz|d>E2J2lW|2G7utlQt)V=SP0cb+l?P&x&rt?kGq{*{jpE5cXZn-`D{0;3)ytz5nY zbxye-pw4n${JSmGt|(7bT=Z>pfp2DNl8j0 z9ZH8t%+LrD0s_(@Aqps|(jW*TjYuOP-Q9DxKF{x*_pkTAcdhfTHH*dCvu9?{-F02} z{r$Z9{S|_pWfe?!=3aql(6-fou8(XT#G#?uY^~9KZuWFc+(}Pda$RcAA5M(jOS;+Z zX(d^!^H{R$9jO!CDpvpf%by|G$O`i>Z`WFBVyN{*!QKPs&s)w4{Hkak+hFbcZ_1)n z%Ovw-6Ddt&VU>(R>&#Z0?3lu4l>cxwBOAw0)l}o<&WvP?hu!m2~k}r$|QNYB_ z^9T>bziTI^xSrBuzt&}*kNj%o`kMt-#H64Xo(M>vmc=JC-b&r@TIu(hW=4X0UUVb= z?YH6SU40hg+xNsPO!QVj>xXgF~5?y?l&hHh! zJ4uDw!Di=2l^ID1dUKI1t?x&=UeMnZXgMsnA8=x~HvGAaVrQDilL&^A1zD*ZE!wvNR1L!X;nWp@U^21mNI-Co1Axh^!5_G&#@8Gu9hiY&XI(Ub%e zNtIlkjG@Sv*v_RN+~d#MNOw0yYF5-~M}sIEFB?)6Nkd!3yo4BF$=L7ua_6{&(&x6r znh!_WpP!w@5q+=4a%nD$oDg);8c;BnOL_joaH9EL8v%4E>$!WT7u_g_{O;Ph?#JTH zD}R4AUkX4~|C~RnU4icrcyh%;pTpV*_)VN&%reh$P<`LlGhl~t*vsGz%Y0Zulm6=y zCi749mAe5yyN`Z8PNILs`@UjAkXw=Ly{=(39jX=7EE+vtI?_e2FVQa1?#DwV_YEv8 zEPP%@->LwY0Dkif<&JxCs}XR5F(JzL*K7vV*je_$=3dXyEN}Q=_aivw^HYsYd>;rR zHaeA+eDk|l63xN$m`|oS*}j7wp(ofY%#z~<8MI*J3gtp-^UMNB~F>J%W*w{LD$|hzj|R> zt?S+AJz52&Sg97#SZZh^;LuXWL!t>gLy{~Ni^}J@d{I;DU-ZvyLOIy;3wHIf=d|3t)Gb~4H zd|C1`(1oRaAqPLizHimfF|}>h82=&oqC_;G@o{0{kw6nb4tz5L5wgCGrGE$NOEW?_ z8Gs@^V0#V^pJlL}Q6Tt=!+3NBcTIA>-y{s#oe72iVx+`=V8%H%TT>X!{oumP1s7@{ zf_@=3%l#J#PX9BsOo5>Hg{wqMPBi36D=Bu=Kn>RJNI(*aA9z#;tef?=JvZ!#RYwWp zKk1N$$o2btK0HddXq2BHagwne+4dE7KNRt)%V}ZiDf?K#1k?XCBfwUkAx&Yn?z_l({Bp1*xxOM}SrWOKTN) zxb;-WsnqX>U}^^{v{6RbexBjX*TVACrk~h%qV@@vhIV{$yyi1;eykUcKn;+(;7vDyk$2BPFHQh&PC~<9)4DTkJne(bd#{9 z@`w_~&qp15){o$57ae9nQ4d@vhdxJWUtgA#7v**2_gtQTF~o)bwH*&_u2>zW=gM%U z6?ws0v*S8Cz!cJ^eZBMhZ1hm_o5-l}mv7qBl+jdm|4wPY4k@@DUHJ;Tx-}i&eKx$u zNqtnfX)+Y~^Z0}*>9qXZS?z7QWhD{z=FhYlk8VcKadW>ii38B=U;+x9;nzybNGpE+ zxzH!ahSvuqI#3+w6)cNdNqYm}p-ex4-_tzLLiz~=!QEh6d&F^1OY-A1>?6W*di^IX@W;3eoOp{qNb!*}T_17vT zM*`v@Ilm(*`B#CI5BO9QXGbJ$T2$}t>B`mBTR%|GPz_PgbU>g;Lgpw(!!zeJ_2K(< zD%dDwHV}Ad@bSj$zTB4_{nG0f^l)s8fVDSt31Jev+2S4rSwY7WN9L)<`zH!`s`bkJ z`*03NMC!&+om~QFo1+H<9zbDeQvc+A77cb3!2iq4t-C5uUJK_QJFk4+R9;J|b>g_* zJ0#L7FIbi|aB?fTCN6MI?Ctg?xR=%C<8%wicn&A@?-yT;OOL(ZmCye2FXt8XTs#V{ zlx0`AoYT&crxkojVm$h?B(&N&p6UlE0ze>e+o35%7g86QFM`{Tio@i zImFK~wytz}qZVxWPzLQZQSZfyC^5-dZx=PR*dS9#{MNgcGGD9uZehrOC5%)ykygb1 z8z|Zi3Xa^@wOO2x(^IyNeg51Qly%(CoV&btV`9Ffp!F3w_n=>^bCQTd*7~lP+iVu$ z#sV8eoCKiI)3JIJ-ln39OJv;LNP193&l*W-vi?*xYnd_*e%-4sPiGML{Kb z{XU9_mhDnkq~B-%H;|Z{yW^kZlge@zG81lnAo~+PZl`3INYCo4hE^I_1*{-WgmU=E z2$INQ1K6q6(Z;)3r*#ANrkXhWvFOJIUFs0J-l`5KRmi)KH*C-kDj-&QoGhFh{zMRl zamcPBJm}#(%Yh!*>IEp%kao8y!FK%-H(Y?A)oV|TTnu9q;Pa<`Ywea1%Oi(X-)SuBCvy*1L|AgL55b_1)pe2OFXmA{jt|Vx=2&| zb`8XyUoh{-nc5k%l7muH>CkJnWUeHYUl)4#tLz6}FBGNCLPc`H=g5ndSqufwAlTE> zNMJq(glbFQ_YmKiNTdZ-k`k9FSlo~*%Y}5eR<9(ykCUPtyBI3rVgQm4`MN!iiag@P zgGLSq?>H`(qOv#L8&rA9fTBTWDVMIU)>_7Th&Z-EfG9uqbEBpOTp+8OW5kALK1>%* z4c%Mma(@U6&&J28%eMH`fiqh~JM^e)-SAB~%x8!y((gt>KT{S3WHG~v+dW#Z_292=I1!!ypjrSc#DC(# zi-&Qz`eRuPbr2ZqdB1!ttarTy{73>~b>LkdeKiCjM{p`^kt)1KN5DajGk6gall?pd zx~K=_o$h?q&l3<37$E&>HQj|S(go$JV!YO&iV(!@(D|?01|$j6zux`M6{j-?@a@|3 z@1tIVvsttRTu!Z9{L%9CVg%z06GFI~7+wAsPRUE!)?H^}k!)di?ABRk6{cZp+J-U^ zHqM7fL^C+>+f~yu5~`*M@s|j=0QC%m38m%VJiX=rh5T^5JM^Gx{6(pG|fNudZ9I z{wLQ(e$x<^2JO7nH92$Lylhent?@ZfRF3om3l|LmgEIxvWxu84Xgpva%CYFl(3B3@ zE$BELN|9yy9@62&FwTnXkNXVp+aqO>&$7P=isrR=g=$M)V!uOvFRp8Pb|QPfTTDd} z6{&>+r}d2qv*_H!=ubyRx8g^mQuWlk27g6SqCB#%M-FS}ER+#GtKZZgDJK)=n3@^$ z+&6HLM6zIY^D>O=z2n@(vgnADH;Vcw+CxLY!HbhOVR_ekbujk#i5p=zNG-rhzja%= z#5i&+gn{dVm9g94qB4g3gcT4e5Kh!07O$MBanhs1@sLb(G*bT%72dG)QezuRBi?eB zQBfuV7BYat@^hzYx1Dh3QD%t;gMS{8w4B9m>++lmUY>h_>CHZE&(R(@k{0!8tT;dY zhBrLma5DvM1?HR^WJS5Z1pk+PG_M;S;? z$OlVi9)-u`zu*>fF}2~k>3G3OfgYOuKCd`4zR<8h=XSx6p5U%N!zj3pToGA6;b|r^F23n18Kj|%ftk(u7=4VAbD}s zkJ8yr3VvKT9#L2Npoi9tN`O`c_arzE|3Agcdq_RT6l^#sTS7{w8R1alIwAaQcfRfF ztQG9&Y>NS+plhEQpYbb3pFB#2)L>4l%Ll8Sy?X~a-ot9n{kidoQi1aCIx9fl?I@>~ z=Zt3f1SwGCr*Ksiuvr)a@YvI-$?5emBqu>P&%*k4^1o>>tH|_npD#|v^0fs1f^{N5 zh|oDudcgCO5EvAPEyP>hlUqe3z69QYGT2cN1`fu(#52I!9{5^7*<#+3-$Ctp$Mm`et=NX25BquNF$g z^86f!6B3G|mqg`)Q~3Jdo#fgKP&WJ0=w(oy5vqqAnfNP-dHPq$keDi220_Ab;#JRV zw~-J(KxhguPygwjnQak%Fh&nl>12wzy=re)$R8)y3K}#-vLJz3qn7}`xf3WmZF2gR z+Om&MCcvASMxA4)*zH{gKJjblFB-qK42PVj8(;vUIFx^)Uoi!z4wH5Z^B<$KTk1je zW!b)fvs+gm-;W!W8Ua>s)PN^Jof)XdQ+4=C!RuHl8n%KhxZ$F4$#?zvl3*Gq5 zgKDND5`clgeVm*(*qxYJ*6c+T43O_&Rfp0s=?OkI-k*K86NHswE(2;l=g=r-@c9+`Ws>}O@N zAdp9RKO3On5OyBr{!OB2ESi4^f#;9LcSM&U0hNNs1op7IdUSH>D1(TH;Pm)$EU7gI zR8z;xI}W-Ur*2hre8hac8-=&?X(h*qwbxCFeyNXg zmvp#{dAoVyF1auVFOX>R-lXy)vhfRi&G z;y6#Cfk_*1&Kbt4Ndzi|t2hAaB1eOlA{3?JP?~`40xssviT-xD7jE5#3DKX~C(WV9 zUCgw(<`VDyR=diH5Tui=L1#}LXQF)H`W~6rxn?kT7&O05WCc%SQ7Co`44#(zV42Co z9)12`4L#A)lLHD$th-o<#|hxO1n-~2;DHr`0P}6~N5%&hO#zgTh!v=j>SW&Li*j5g^D(7zzA^rlkS@o_sY#Aw%4r<%uLoS(Sn6Vq!Q;_@%qfyka@&vVr`_{MB<8X_5Tb6s>-R z&o<%gPXoPbEvQap0^{%ILj%l7f2O8{?e*qA7HIo{m98m?jJIJ<4`hDkA$Y~__}gzk zT1fi!P=Av?ccJm-j|uDDXTPi8=H#65bamf37>;)p$KK7m`p{icT6uX|xaBTlrgU%t z;r73?r}*HG)@vfKw{V$HP>7>}`Dugqor-j`FbFN_982m+*vh(uEL~e@-vDz7h0oO; zLE{#hT!T)#K*3-F`6xt@=^n3tMPGC1+FNgb=BK4zR|&+i@^dS92F^wX4t2YSc1#k^ zWj17jn6@&KPcn@B&)P>wTb897yYuG8Jb20wOcC&;G<8r}MM6(0QAZAd?}o1R)Nn{I zK1^tM2RolCg!Rtfe-rDqZJ94^ym(O7#Jd~0Z~w#L+uP8!p|w&ESxJK06P)^eby2<$ z<;R6tj%-R#v(oFW)oQij-hqZ@_Pt2x?3cjl)5iUi)Kv2*kZI3`fs%S) ztbpAtnS>Hy!Oq8YxWIAO*e55QLg>xM2SBc-rSst*UDMS4j+YY#twFWKV*D_wb%uc< z*T!k^P!`a}{yKahR!dH%(2zNRvo<}-elwB#GHX%0PDj4X_O|$U4O0jSah2^aoI@XL zwKv0L^NQS`7%bHvD}|O)f_q-e1GZVhj1Cu~3ju&Q9|{XSNs<0`aav{&+vc}tj3Y&N zZ+hg#jh(j^f|n*YyVwt`!ZQ@|ddJP4p zD*$Lwc|QbLhxH8LH6`WhjTrZ=M=7mGDd$=_=I?8Fg^&^7p}pOf521M0n+mL@oP!rP{6d0&U|MfJwq=HsuB-&#zZz6G2hG{no z;S;+eJ~S{UbZYi>gg9+2NeHgbP)y$V^MzR$D!77P@*p4fF5cfV&7i6KFrE3}L#MTD z9J4=7gN_}Etd-evhX!Sm9e&pe-|~+rTWRxX3!+|WTG|YyYTEH@m-)e_QaS^8PRFL-w#NBe!DI^=U}C18`xNq9yNY0 zyHJW7<882HB|Y|yHo-|yd%3dmtfIMOfHncq^*dpYHgvo; z*FRi9H0$`<-s>~mgP$yITkkqH2HuTbNbd(ltydoC+gZK7Pya_()YgKip``NZ+Xdu@ zqc24$laK_-+iw_iKZr#M>uApCzEv{awV|6N%}zE+Q#ddemMJbWU?TownHO<4Wzu-P ztxLWKU^e>fz1IFh-9VAkhMJ0sfFk;N4?b?3Vhrkq?5_p`?Ot5c9@cQ7{16sosrSS# zZSD?v;Gm;Ee!AG~A1-cJY5pe%o#K6&EJ!aOj*-2ndvB4-)QHn&Pm-RMHqX*-fSZ_R zo$joBUnt~N#F_|mahtTq=nW_&k=T5U+M|bow^%F6?zarnSkUs1JG9Yx!;4aVcqi$R zlMSIxg1J@a<>8AuA+_drzkmHKy!%a3FeDgZh?MI(Ke$N#KpSOOTAg@Js6va5c2u>J-Gx8`6NSxs|qG8tV;Z)7m>U^GvFj^Jzc*avv&a-}u4X58_k z@jZ=Ex7cevc<2S@9L$cT1Jfeed2iC+rsqdR=5?G*q?cVTJxj09m!(>J@M3{`iAT9El+#!G%+{TjrG@GyOEJ$(A3@u60i1KrWX zkXNxsHbH9C!#5B(I##wvSH^~+SS@1HZsq5m_nh{ZdV={CZ*mI?GS;CKIT<_ws}pOV zLWi)M9S5(QBr>A!cQe;CK9~PxlZZcA_qhBg51gTjNnQwR@x!=Pp^f5#h%muO1S;l{ zeNoKa^#cEgZCSQ=yH+l26|PUS`UdX(=u#`@N)~1e#rj?h2_>d_e(Oj!MgQ#ydutM{ zF>@EYoYk_DL9Sg?yZ%#0`?GKG#Kd2_=BlPgFKu~-kw>hnRoBv7&R0F1mrsfq+pc14)mEEun%}4%U@F%CBGmpj!@~uy&Fu>~qS0eupHjtn=h7I(8FDnSc z2Ewp`Fl-yf;2Ewp`Fl-yf;2Ewp`Fl-yf;2Ewp`Fl-yf;2Ewp`Fl-yf;2Ewp`Fl-yf;2Ewp`Fl-5Rjw=Ks7x5Lwz9b8leDC9EApokpQ5MLPL(P!_d;2U^r;>zNdsr?d8@L z8Vv^Theo^T)}wAW%=V+vet++`MB7gP7&_NapwYg6?++!4&nHyuCy{8vfA{Fu{9Zb2 z*(fy8e{Ro;9$LN-ia?@i{&T-RUOR>MVGjHEI2hb{#}E>Y=c0Iw_6C_sNHlPTLStX; zpwVhz)QZ3;7K8#24UaHyh=)cZkO)9j+{3&e?kZpc3cyc`z;E3HpV&J?qpy)@GcX6- z(CD2=6T2^4KhM!3KGr!@B3E+^;rW~36_cfo(ID_to#P1Bt(1v zZ+KuL@XyiLSLoA?|D+-xjAuTW3f0G9o)9 zOJXn0JE$v14a^HL)?i5_MmMKF#%4Fa{7*@2dUPJoM)8uz|FviC?^2>?^nQoI`AK?!g&w?Y$M=1;Cp#sMgI31 z{KY)1|MU9q7YR>mBLF}SP*alE_lIm|^QKw*%#uwvb7`b@D(nIO$1SF#au91@c&&cKyfLsz(Q+wvU=_~&2hvMdd{?% z)u(+O^bB_5viZLBI?HdGP83^MDNnp(V^dg>g$l|j>FxgK&z}m-%)9YByy>Z_sTB?b zIZu|pB|SM>AA17w|0+Q6Fh7xEz1?@J@lRe3=qV%w%S=rzM(X->aVAT`%WSId@k}%s z`*b8R{d8K(rCq(_5SwMoHrxG7da);mk1NbR4ZmQLnS5{l-*Ez zm+IW+wkPY|b}G@k9i&(OYt%OOu3!|rK=^rHY?r8gAIN4BbEKdXIjUb$2f_txGTPz7bg7*M06*$pgUv8XIfEM<|SI$)7{J= zn_r%;=0|PJ(a`W~t9~xHIiw`Z^ZB!tY`JE9twr`e9K5+v|3uTm@VZm&Hi+ZilaNBdY~m ztXc8?!(Zd?9xmc{y)`JGuCnf!rfxa?3Or(Or;k>}W>9v=;#FBjzp+v zTlcd+X&22y{pNl%l+hC~CAqLqUMsk4d2KN_b6_6(J|&u&%L5)c&%AeLW#H8d7rb4N zP^xHmT(;6+-jZxzlhy{MZ&-ZuD430);~)!~EFML5Wwp2P6-9M453;-uf+%z3=bD3L zp0E|S}zyh6w8 z0htps1alwj0PXu5AJT!~9@V8)oXQKjKmK^P1o0XR1zQDO1t|r|M#EyN z9>F$AP=`J_UtGTSQxZW{$$3dsCv~lpPTQ%Q=WBj_0b8O%N*2{kfm)|O9$)}jX~N1J ziAsqI9cdN;J*>BKJ-TS&-U2wy7u#Qgbu}hdeizRakrG#Q#(mK_Ji`8XhrO+5*2o5HYcjHqpQfRNiI%y zw9WCnSi3j^ug_LkyS9(UE&bT8SzmtY!Xqd17wexI>&mC{p^PSEVLHqPvxKq}%SO`At zMtNm(Z;&DxrN9^|qh!h%ap$))ulcXygIRKctFaZN83<7^M-Hn)D{O1I)?5$PD-C+Z zAawTi22;M^!PTe41Z7P6>|@dkAUdT4v`64jb$H%jwan*RH83`_77b8NGpKv`7+1g8C>&K zj;1C0`Rxk#lNrBUa`wJ*2o_^b(DB5!Sj*Xq7Jd_~L82kq0lJN_)K@5^5bz@~=V_TT z_CtW-1~-o}6@^+#j%xKTyKY`_+H)!Yg_xUJ91jM7Dwce@$cD@7lNN_IdFT8bOO8_} zp&P0#Y>BL$Ai2&Sb8*AIF`-*!y*;nEo`asH_^qk=c zCvGS-nx*6ZX&vj0`LEOM$U*8ZLe}K~GQj=ls)T=Qn7Mz1v?|XM?t2bvqaOKP8RfA! zYxS+^);uNUIe>*-tt2%~%_|h!y6M4a^XU5Qg_odBM-=IaSI^~$?8+yxt0iM8baU=u z#PwdBAae@#j}R7VMeF$EurpHYc2O>x2k|-cBK3WQi^#G^jafGRG$eBw4pomV#6uxR z5%iOJi7UAh!y;H%Kb~!^;M)VZK$jX_X5tC?<<~|@r-(~wCa*prEtA6C35VRH(`qI` zQf--|lrOvOgflxwIU4Nb?Sh4C)H5_%C*=U8@58@lrH&%#!EG&`NIOsU#O0Ch9y>FM?(gHLH<}CLRLaL z}+DBBX(bOjqgSrXF5+4)U*4TCB1sh(~(NGf#qrHNZPCw=NmUj594^f3@9-rpU zt=`0@EWne;!U`_rg9)shGWWHmpx30lIzzQBTM4HNHfR*RnI{*Uhw$uUp6NzyIHkF? z<+eZFEjC}yYH$C6CL576J&f>hmpMs*y_h6Qx^#+~V=GW>`NSou(y~g3jb$I#>_u$s zLA=$rxhBmMlpu4oM%dEkjb!w3ij|}gTojx9lha2#M@!f+CV~zoag3D}-Mch$=^HzI zlXF)2)406wY@FtyU%5BQyH@s5nz#NX;so?HhBZb%8d1b5vz!E8-C0UIbSwV8ty%+b zEJv)VS|hGYgIgH{yQL8U0!?-5bWJ*wye<4ycUfSq_w(MPdP>|hiZtixmM_3IKXw=) zwH$uXmz>(J+)9IlW=L5CSTui*z@cE{kIC_yCZ-kc)JSdo_RBbFlI4bYfG$K$F7_6W z85L3|JRu_LtA9!4!*?EaBem~qs%ogbbP59A+bX*8Q9ixNcWSOIH?{Fg3;RuBw2~B` z?3RzY>D8Rp34bbG;|r>)pPwyF$N0veku7TUFY@1iZoisbJGo&v5HuA?|Agsb^KhJ3UwKMcEa{|x2#x# zlbCh)_<*d!(Jic%!VSl;x%E2Qqw*&*>mv!Dw@xEnrsA7bwsif*pY58CIt0f~E}4lo zM<>OkCzX=cP-n+(%Ug;wUuiR+GRt^#6c!G?g>9dM$ zpUXPUaept`mU36heo9HtiU%#$$&2TY&qKb<7J3HFRY)3~y9RB%udh?%nS1N!8ar#b z?rLBuRz8c%Sig$3(xkSW<6}bFdlYQ6-ts>8Wdv+Ru))_&rK_J?jde7(Im|$17!Gmd!*6&` zm3G&;yo4hHWnz538c3Q!6!6_*LXXf=jBkC$XS2xnS*g~us{tP7AZNpG(DuR4&M;9$ z?0NSq6{RMH@Tb+YXpN-B~od!qt^B98-lRx**Dnjjk-g{?|6*W@-VTfO=;bpXj^U=wzV}I^e}2!X zI4{WDnYLcoj*78i=818rk_{?)tyDQ{$jrWqAI$X5B~mUPE=Ti=zs)MS2ErVz>uxgs z+hi6uI^co8$8nFsy0oG>r{0uXVYbzorSA1Z`#j7gz9%=5b_()c zbDU}G@cKz8&?us86*)^t2g|LY@v%(KWi7YpCYT%863?&VXe0k@Hb9YFk4isAwC@;=Z}`X zRxHx{sa<=V8E~rSy1$+mmiFN)4`WmGG}5e_MWeA@D2ZAR*G8J`k>6;t*+s{q#_flw zzlf@UV@x7DOZDS>Ja-;_Z&JAvqdWiV&r;N9;{J(lzwaIO1jMMuBB|Tg!Iqq55^BpR zMdjV@wd;Gk)!EozWD?7z|A5g2<#Y^-R;n)G5;->uSjiO2R1FDNtyZ-jd_d4nEnMr6%=s1^H zeBLEQyjtO%SZpj3pp>PZgncRFU@|c~fZH8NDi2>jd_+g0@8|O9J>7>n-`oEd+mG0E z-qdcq>1KMi$=q@=v$L&dynvSuvn}A2KdRJ`-?=SUz#+j+p1pKZz%qwq%b>`EpC1V= zH@!1?^*6gYk!xlZ;wJm$7sLkqpI6!Tho42!L`tnx<}>wrfFKE?Uj~S_<@>vq)`aY4Ri#xg}7Sg zidh*&qeH37a_t=Kz@{FwFQFRQbc$^iLK=^LnuhTGXk{o0bP_RT-PXW@zl=9?DH_n? zPAg6%3R4eUDv~+nxOiakW!#fq43{Ort1@s}RyKF^%f~+#`dPKZ&DuS;wI4>e)bD+- zLu_|}{iWgCkJY1`UaQ|18;wW6lnrvgQhHS8wGrn-3Bk(#`3mW=w)?!VoLEMOqDXrw z;Jx~E9|_r>-tQ!$Ay4cs`?!VlBC3$y52E6AJ?m!lV=(Q$aj{-+m@1Q7CA;rIo%BRc zK<>@xWtiLNwc?GIqxWtz{9}l_*M<_?FYh?OXrPgDH{g!tW}Fuq-=AJX@E8U)GH*1! zS4AFq!Z~6dCJ7UqHxUX_W<6cbkgcuigTTsyqaO6AtI;S{uZKASp3>P%^WFUk)pKVn zx!O#R?=Hv&kE_?LJm&2}_wT|>;Et)Xo zP*VzO1AJ`FZ7^iGO1V9?6T(k&7mi2&ty%jc}Yemy!AppUcPfGsk#kbz0+m z#3#J&^%{S}n_wMOR~Wfo0hjD*bQ7M+K%cHH#o9nD<()q@k&?b#`tcAkaJ?Uhvs+0( zad*{^+11xkbQl>2w}XhX2Hwo}ez1Ey6%REU-1(24`WG##Zn!F^^l`++ch+6bHyU#s2hRAxhNoD0Np?34+AHwMI_2Sf zs8oNLF%yzPyv?b=nJuXDaxKZo;&}GpQiR> z1+OGFPYdmBn6{=@9&0SEr(H4c1p97wOtq+*ar>gT#?8Eb*vh1n((WZBydM+&n+z6y z=z|01>lLtRwYdc!WZqO?7f3s>WI?@C^$h_X5Et*OenYe=z4v z)J&4_&A_gp4adI`@WTBbfpr~|AuON$ft*iRbI`^4j8S!iU3K#)4KkoO?KF7vN)W=X z67Q{zxT^6xR9r}N;E4%RkT{L-oA&6g@0VD~${dY*Jg-Ok%6IZ#H^IO*X!6idn@P&o z^>o^6pearOkTq7n*%$DFtF=dT{#&oQr1g|xL-5iI$S>l%?#WoVL@ZGVEiTmYTdpDP zBv-Vur|_*C=F(;es0A)BtaTW1$@=xc^y zL=sSBt72tZ=lU@3NV3z?1+D-m;S~p;-R#8s&)$Q zr#eWg`9wvMy(DNc@vo((!elS*OWD00c)yh`p{N$AiYIeO3Q5;b%3>4d(lnk^kYxPR(4|nWR3=At)@M_=-x9?=?gR_g2Z} zmDa=?X_W@&F`k#_r^G=@hkM7Qooa?)C6k$x-l`dCHbvVwwEQbSD;Ng^qIMdkUT#{E zvN@pPWvYM;^rKYK@Q~q#+o7#%}emJmJpprlC>q$PCO##cYRU`xtYott)T2jym~Z&3j1gO18A zWggOAZx2^Hs09xPLf(G{XWukX&1ktj(9n-yk3nm05el}{)YPQbd;*Q!I{m08^Q|ab zU!O_m^jc!~$RNUZtku#8L}zElu4FkpjIHVMZ2D-^4tdI<0r}AObA%i}q6M zOK)C+rhiz#@#Y%i^{;(ul_aU1#)IXdLKSVN%e5-0|2Ckd8xZ`bVH{h2EgKbIu5XQ0 z3>^0IS1vu3rPZ&p z`-A29_+RA)8zdw2#w!0ywG-i^JhM798$;8>69a}!{2tb<87#(U_%%htk3@m{H5^y- z;pAGoS|K71{X|8$Y)zGO^LSs-Z$R62^o@Jd`FMGDGB|u|G4&t7h|0w($(=z+C_jYA zYoRpW;Bya64rrlRO(19Z;t$#uX|5My1?p%5O^C2qYC~AMWtq2c`e@6Um3jg!M;8p} zNujr2hA*$>8RiG6L@w^?{2Pr-NT82NWDW=Sw59ht!+LS5?o7%g5>-9IRq#b}(q=tq z!QBY#u5dnrGW52gq7%n$r8FV!E z^yRgwHI#)KSVqc+;eOhl`BI&LJi&L|evP!xCZ%1=-3%_eG%zgv>j?2byU=ghKNa}7 zWV8c1wVEi{_G=WbkE5C3|5FV_EwPn09T+`2$+}%akYmFHET;w<j=!vu@PfHa=b|CD@xrD(hDpc+ODSfJI3ANqiE{mXi3r39Bc5mzjc z|IRJ&Awx)um&c|vA?Pb@RUO`Y#+|wh-EtWb9rd#Tw_Bz2h(hC=uwT14)$zD#R?RJ( zfHw5qy_|*9z^<0bD#XI|?TY5}^}=|>_341vcu%dzf9u*N6GS=O{P+#%^Wu)cdBqM_ zUpSeZ_c-E8SrGW~NmPRv=w|?jwv+6IGb{-oY}YGp5&@PaZ6Z0LyUZSbj7u=j z5`DDd>jUhmU;lO3`^L(}ETE$hXG_T^E{Jr`z7Ao$@Y2gD5=Oe0Tsd1|sj}iaJilk| z>a5<(e1j`D%`hd4`|;q5<@J7=1-VY?xK+JxZ8@ZNypJ1n@s+#5WIPfR};iHf(@!ifW)aY(69K&#WHGy zSqr(a-MD2L-eOE{CgU_*bPZ0nUCBV5&2SdnQPg8Zo&Hiq3Q> zLs{q^J-uvT!^U`JZZfcD1$%Ak!6a<$T|IQfqnm z;m2d)$I}0LW*X=kD@(!LLs6SA_uI8&p42=_0N4N+j{dP+$pP!Lu5S*~O_79ozSSa- zs`2WNm!JG*pWdARqA$+j4_jK57nK`JQel!<9@W#nQh@Zm@EQ6~JoCulIbr4WZfAK%`*J{t)6Xcx$SSiJXS$dv}*x_8XLd{VhfvVV!^)_lfg zX3A2H)V^fjt~fv6sB}<_)_Q^WVW#K5S@0X?eGM*94-Njr;V<2!QpM6Kf&l{3FBK!3 zY?cRd6BMo5qmnF6UK3*>d(q&0<+JvAHR!)~y$ku2{b3D$Az=I#^eL`>Ah?hclZk#; z_iqr1l=D)NTU*dJn$YfSd5{DsJHAN8YF$axJ(d%59_7w8Y?k;v=z2)|TJ+{4=5I+@ z3kg3EiRUfp@0tI=R+F#4?d?eQ9(t>Ky_Tbo{qGNI!5ulbJTkxRG+&U30^!MvdR(7x zyd;$~u@kfX2EQ2sSj&AEQoEj!=e5#LvVw^4@jq(Om;80z-P>g| z972w8_kH%ScD;Pw3J!JJ|LScLZr+0+-bdBqzAreT^QlG_tO(>teCQ9Zh~R1~Ky}d{ zTpd~+`2BLPSrI7)5KkADRG}2T$00FXqpoPRpo4do|7w7!4D^jdZqTvB`n_n8JXzZp ze^g(xlr%x4_uTktp_#;3c{&J{E(ENZYe1XEmq87ke?x*u8g!CtyPZ3H5BNI*gTIq# zi>)QKRa0Fg#8jb*bk6$r6_C3b`-MfbMH4d-!M8OyatbfqW;omH3ZqG|fBFMsaz60{CyAL`R5v znXDzbMxl>Zy%xrzxK-^+CWZUb{P;sRlb07FUsR(DfcnVFE zQcZ@>JsBOI*DHU9KHU4ylCl~0zj%7az-VMe3q#5sG5`*j0AoqKPWc0hz*yyY}D3T?w8*WxSQ8VF>JBa*Nl=_IM zl3XZ0n-nTKjITywQd|AWOs7PzU9|tNN`k3y)4zA44}>NPP7vjQ5J=&-6g!gYW1E=1 z+fDD4y71-ezxATa)xTg#WkKfVn6htrm}M-iWM722)ajQq?yP zwV(C-esN*-O}Ms%fEfc%o2wKzC|5oTo4xf^y5Y+Zelken4ML|C_;mJVz_>06{4j}$ z(dF0w)e~PT5CR73l99N1*#tMV$dgRGA~i-H0x?oJ-U1bGVaE1; zv(_dz>Cx(lSJ1*~^4Ry`<&w2d@PDHOevq%lP`d;BiE?8Tl4{3Ly2bk})|%r8ffck% zd+xUkC1ds?8qrvwG%iMPwAvp=0^g*^5Ae7=DT0^e&eINu ze7hV3DY8~uDM0%WukjFZl9D4o_*oRBaqCag$?;@wCW|17@pRFLV*n$^8U%&Vppd5& zJ=w$FB2xCU+yHaQnQ-cp#936P^Z5T7pL z!hieA{KL~GmKz{n5TSd)98xuX^rednM17o1>yrtmxPpB8lyU>c)z%6ml$-z`y=wV% z+rm5ji|)bp|Ek>h7qmenPF;0~XGoj!xHu_pa3?STblPF_8h83ircLmDf^)ao1K;?r zYqvj=jHD8|avC04DNzg~(@&8^%g^4Uoa!`8K`?>-*WJ8EaK^(`nSTqfnFwFCL)jQ> z=Mh9GK^jKK9pqfoFe1KF?LdGfzo z@eD1b;8OhYw8!(U`FBAE+Grdf^MyG2IiR#7AZe&i6R9)3MgfhoFst7@D6T0i7=47_ zb0&V9|Mug+0^1i)$K`+MN+<3hpV8Pae{}O#Ly_#}3K6yN#wr@ z^aF&(_~=y`;$u(yy&G)}7wzb?5r_^6Ls28@yDnqCF`%kuj#8?IyIVuc4Z@oHf?;?` z#r|rNd#CF?4@4NZvugkKX5EsK+gn|e2=UUVT!_X#Kh`$GBmZ$wfCN5w2X?>c{-s3@O)f z(cBl3xHGO55&bw>(eI?VK!W;=c({tb2wPuK%JQo#3wlSn#7|DD3vC|@*h z4rRCnC?3bR_JS7aoQ#2ItXiUi-^eEBu zLBoaA2}hJ5Zt(2bb^u7-k5r@WMRX9DV|_QE0|Wi{Wh;LsSl}WiaAxt}ndWvkbDwMQ z%!pSlf9ppyg^MNFZf?|Zw#UCTsr?%S##*#8UtT2JnG#Jyk?4}LyhlS$Ro@~V_Krsf zSD?R*#dysF!hW4WU`pMK^zlXuuQKRWNJ>0I*Zl+~LUKyw#d?4=^ZuuruR`1qsZ$!0 zF}vFWi;nN8T|23|npBE!Ny&SL_10GAn7L)%L%L{K!2=&7%f(|WDK&|su8 ztzi*zDz4jMG2UGLwRnT&9h>cg9NU`a7GG(I7CvFzw}w$o zn}^OIt4w^2ZGHPR^77gpNMQa)zy3glM{Z=Kz?_Rw>cDR!X#W^P z=!M;mn|5N=p7^5uKZC|WjH}hAQZn5pEOL_a!;?s-899l23)18=Bww-dBvmBLM@dmp zqoRf`#w1R(Dh!V_uZ3Dwh6~=)o%?~^AI}D!g2QyIjWN*t#MXQfN$cgd=v|*Ri{yh$ zB=s0q)V@CuIl^2;)2zvmDuP zj}py6M&9_@5~q(LQ%X(CBXlBB2A)&BEt`$>r-Ui1cX5IoE*-~2FR=8J#@dmfeL}Cs zg6!jo>u?x;zeadL<-2b?kt2HyfQLz*TM61r8fs!&(c=@$bX98tAPr9E{g3eMD2p!6 zH_92J^9+<9!mFXUv{i7$BaNABoTUZ#!j>bmiWX|E?vU=nT~1wJNoDDodb(y9E7W~% zr2K71sfNCpga9g1EgPrhHkD|`?%T({tlT%96rESQ6ForX|0@PiAIMxwz@x3j%xdVU zMy@2>$K8>j_d^3k&mz^vF4QVXW!e6+c0!`Of1cpK(i*CMycgVh^-b!6&v9EBeh0J@ z$F%}YBFBxJOF&C@peneI)PehIe~vhJHREqn<3&>$6tZLPRqZ)u*w@0XRh_z156Xv5Q*lD^aN zlluHU&AvLJOTzoOaa~nSHw#@ZfNu5eSpoEqCon)K=9wn0>N!%i7JXYN@iYXP%RU4~ zFlY00`yX-8YA7M^0GGLN!LJZF`##KRQHEqK#kUW7uM~l=_fJosI+1dwqjdF|GUoQE#In`mJZFT&A7qAg(Z z6R#ithVYikJcQE|t58pfwYnw~(#4~gyu>i^G`5rB2(+X@!fcUn(PcYb8A2GvL@i!0 zWg#0uuf(P2QS+unI??X9Pgn%Ng{OiKK)aw8Mgwb+4s+amA+WSoYf#*>=8yT@Wmj4y z5MDsULm)`x${@2gUT~UtWAQe{!{Q+>Zp2=mlzUebKmLePX5iC$dSnV-nJHBfJSE-V z81&t(yUJuJmQMUGioUDR@V9sKDLN&2i_DG+;(N?@O2Vvq^?$ujJXbGdjsfJt*fcVc z_ff|*$WM+&TG%Ftsj1`X$S%~`Bb+abmt`yNR^EV%o>DsJjvSAB>*&PPp6VVgYn%el zD;?ZsgclClxfR>Xr&I?0EW5<^EqbV0kNp_*_=g+)mJ>@d@kw?eh5slHyYY&{6|K{9 z)$3y97@!0%-`qGr9hMRi=mIV2)TU!olMFb#N+%=B^J)WFY-hAGHayyN5dRgb8+=-4 zZm|2{kn*Cu89@Rm=*6Cwj^=tvDY1YE<>yE*fN+y=U3P{x@r;S`{45F;IrT4rzV4Mk z2;^J!LZIeNUBx4&3GU#plUWJQc^fu3CWXN9M963^uRtCnJzoC`2@y2sCJ>jr1*pE? zF5KvGZh(r=(f?t+R!!wCu6Z5c|61+Bla1I_W^Tc@X^YSm=$((}$hb4b7@0o|S}L+Y z%XcWD*(dLzCEi5PW&;Lj`;9TQz)?-@w3uL!jWmbirKKsZ^hX+WP(XtEko0M3sqCT9 z&t2^VJLgwv(3UbQ@#!5z?IxSBMXmZt8y#_@9f8IY3>ybzz9Ef?>-^(%$5DGgH_fr+ z+I~UidOpOkv!|*8wKm0vTg3Mx$tdu4n(E3<-YTpn`` zdEBJ%bbQ}#`*Eq@*TI}!;DMmA8noOK0yP`dfi`QnYUf<^*}OCOV9x^o8ay*h;`_2g zBg3ujLZt2b@gkJDat>1VWHe?!ZWVnX>_ssqI*z^IH++=Vhh^=OrrmbJ-zqU+W6;u_ zz?QmKZ=;iIQL`k^6>YQ@uc3MtgZK=5c@uVfeO^pH;zvG<>Ni)G43w!6No0J{h9eNX zyNMKHN6ZgV_v(4M>%~arT&PJ|%=i)sF{}2c_$dA>O!6cUcBcixDJpK`%sGKE0i`J@ z_CC*So}=~tnX_*KR54ZN0|3W#WW9q1x+MYE0sXZA=OwD1b z&(zr}44*3Fbt)LueZRw^J^gr)GM9=XBlK>e9$FZ{apOkeRl!Z>IL@bL1ic`l` zjcD(=W*|g(cXv25r2uPU?JHYsX79PSU%pA+ZH`!4O>jA&$yxkR;T+*%h?D&BQoT#S zWx`vL>77(h){*7qivmgA(DokvLO+^i$rK!B{sec8uKl|T7LsKv+lzreP5ytXng7i; z0zL9_Zj|`G&utGy^O*Os=N|+=2`r$!pbfp1@8Nr1 zvOB4)Bd0)c?5)`P0BeMhZ!74_KN%i_G&5e$NYSxqx(u*nSvLx!0v#?yki8p06Agax z7X+VH#V{&+DTtu(^ek0a25x?6dU&47fNl9sBaMD$Xq-VI%(Kx%amsCr=Cihq8uNsm z#V#k(r2l$Amikijv@?a!&{Z_O>BB$F<^86L#;C8No3m^H?x-64DIS%=YrO4pQt24D z{E8noh&qyGmF_xtLwhBN>$t#p_(70(l&ts|lIk0fpVrrGd}zXh4NC^b-ntJ0?`8QIN+T17LKt-J8s>+86j(9Pn}b z=|*DciWrh-wOH4HM!)~`6M^pjD(dA<*LX0Y@JY)!ypyT?qjKoC2|Zt@bNr zt%Vmk?CkBgCLJQ{fP7;6$$tMtW$H2Z%LWCN$@4M&OhISuK>>>B-pTd5?ZNu4Uuo?3 zEC(#!!!)Ug0k*_HKKKH(y`R4<+nPldlZgFNvIh;!R`%LdChv zeEi4o>85R}^Mmbpc413~DUL>nAp?5XmWt`vmUS-M+8m=% z?(hKF5->p-z50NXVj@Y7?LyMaL5ZFp4J?dE8Pqq40$qD=0Wtg8kAy4zNaHEt6l$IJ z^l;-kRjB4_1lTJcZ}Otp&agm{kU)4<=^JwRcdgj#Cze3MEUhP_Jbmz21cm#l`ZUN{))-`f$b!0@Zmx&8Od~cjzd!a6B@nV_- z_zb-NN@VRz<`^Xb+Iv@%0;&K?#pcwKm(*ubmE6y#<}~u{4=gFfHOs=laojzlZOcqd zP_QH&hQlz54lbfnD>?xA{u)`U|Be=)+P7%1)>_#V@@B1JW4$Ms1o1s?)Dpw5$Eym+ z5$tId{uD=G>BFMc`iNWHfJ*9>YPFnQs+KcFo9$_N-BMig5Z_~hvT#GX)*tejm=Ycm zqy}3lOA+A9WyhoH6vqNkxe5|M7%6A-#p44N0o>v*C-^IN$T(wq?rTs?Hoq)q_kA=P zWAr5jql9FoVyzM`?8Z+1Swmq-T=h5~F(^Zx2!$L|MKhm4o=1lD^jZ<`d%CqUH z{~A{RbD6^PxM8^w)Al_(jEb)Ww(z}CZr6vWIS8L@rr;I5y2)gco%0ipAXDxcUKN-7 z`Iidx!6H9i_HU{{HL3q!HL;IZB(`zHqqnrc>tk&u22gt}>0l8WPL~`x^(6LtF zMeD=3jqTQ7^Qq%mfaTq%%La@*!besl%~?Xg##?eu@ufsFc<_PBNz8Lep@onqP5SI>CDDg zELx3B8U?pU=~GA4F8dSaKFcSg&^&dB%x>LQ#R{Zj*{)6*hp*+vW@41`m3WJB0x!Xg z$@>!Kh8n#PbDcTj&@`kFMe~hA+Q!bwH!jg?p#*OW0I!@$iV!+mISWI>| zT!%i^k3-Zr!a~?$5iDMRR5nK&oT=Nb(l7PFLG4kDu2`I9*`I!ecE@^d*ev~d&*d&dAAk+&qcFI*kr_Hm1?4))8I zDtAxM9=gq)WED%rUW)Wfx5jFf{NsSAmZtAB5YOFk^ucZP;io$4TN~NiFxdd+theI~ zIg^cXwNr+Izqm~0HbNzyRDfHz3-!yj?yRf4u6kqng0k;-LqTx$oZAs|Ky@q@QZmal z%+hY1WrOGZ(rPIypz!vxEv80yMScsNueYf#$>Wbeg=3ny?r%0X^F|d44#$I})=lPm z>-cF7cmVI8V{+Bx&?_bL6ASb*(2eb?RkS&ZaHZ^7NNBmuPR6js+=LZsYho5&Euzoo zIQra!Q}3nTKR(A_;ddQN3pWKPyH@EO&s|E}JiCUYWEd@sgbF6sijMyCe8tHWVMEj^ z;#06IVi!R(;@JQ=S~`-rdm8WK^K7=F-iuFEeoRqkbG_Ff$TL%x6joD(9lQgv1#L@0 z-orODQFyXU0Yw%Hw8hmRw5#nMNr->QpBe`Zvcn&W-t8*Bti|87Y^plHFrDn~pt{2Mlf*Y*oCfSHKtOg*@EP z*haXF>j~}fXh8u3O`5C4VJ^ibmW){UPmUew`E{R{5n78Hv{3uS6P zp&f?mA)ktD9Ol_has}X9;u%-|i(1$A!pkzUw;KvDES5-NMGf2(fP2pr1@^UM0#(YG;T)L z{+MyzbrU$gfK$mgma9J`6*}7-4%Y>C=&szA?zHbGc3g+(iJfQ?Y0b`^m^8%2|1>ck zCLFuWq#Ij0x>pvRy-IWPwL5Vv>X zehTs}EJ3P|RWFh0Z0dHpUyA*CXpX&p7^C z(LI#xixyfSkpsq!x$z*|je19!`pnj$J@& z#;X1!--M06?;O#Bt_2dB?7Q*oeb119z-Z2K=4kdzEk~bP0Btf6rJ!D-v_?HIh! zYPmgEdS?<-Ak39Q@zI2o>St-fh0h))#P#6IqFrRZW=mxGi4TKd4#OO{QunV)yD}o3 z%|bKIs@LR5^Mk}U*%h~t;|@6N81P1)4yo@Oei-bPh`m+vOy3vAhH*ekmgkz^F7A2W z^%vXr#8!mixlPzCEofmw#M=6^encLAbZ&s-k`J3lg|1fPb}duK!{df6&sT~*9$x zzAVA}hL@seP-Ed2cXm*l>3|pbkp89SO>p@@W1)d!RO#}0fvhW^Ibl?B4>8bRfk zYn$}yNhGw8(TA3wx1Pd*%M>s8PKbFijQDB|6*)r9L7>#uVQX}(BG8L+pQ;gGpElOD^Suh@2oIV zZh1h{FfvsA6JhMfuf(rw9opoU4?S?i6}SIfs=V(<$^$!Rl)M97oxyOuE%2Ov;y7Ut zBuyf<_#vWh?;ST;@t?Uk9!8!QT&8npn}N!yNcb;flb-^|oz415BNN5<jxv5=c9^7Svp7n024kZ>=`=v98a(*+meBVnxj&kF+5Ci9MyYD@ifJWJaV zEG`y2oBUtI!S*r3YGQ$^E0%fQkshmU8o~>fk28eq`nOCx+CCn!2BpB;qP$f|o>SMc z_{6&PS@E1A6BM!@_GY|8HW8h(#hfa))UM;n<))$IiS4@X$m7z{RNOUyMbp|{lbrO_ z7^}4OZNusMqJ!$=`f=z($f#W^s*T9UFo~c^JgvR;17~I7hrb5bW0|E{ z<>>0Ly0t5&gfj(s6Hp%|c5wcYxE23xAUO3x0v2YQ^@up=?hBDD$7n)8A$R*(x>P^Z zc5}*M%7;mB)Nzdg1Q@+LpQ+Qqw2XMiH`|9^+rLK=f|%STk+Xwj7>evi+(oxe&ec4*~tPjg@7jU4<6f)g-(?B~7$V_>Pztv}G^sr=iyYfGg|A81m@obvRqS*o zl-+lh#RNm@gX*IX=TBe&Uw(;{X~6Uu>Gp*!MNaw77$h1+9q%}Vi83{a8dVDtMW7}+ z(SZ8)bV8n@39u?O1G=$46rVm;v(3C(6ty=Lfut@T)Ib>**NlVoVkatp2n`i@_p8CQ*z>84Zyjc>SI}XN{s+Q+ zo5i`9`bARNlFIj2oID3r1n$mHNBRr=hVYL+I>>wan=sVeHVhLC#WIr0hV?QdWY8xh z0D;l6BEv5k)(VD6Q6pSeL#OMf(OQ`?rXyUDztZ5um&u5=`heK}G8IMIU;?EwVB=Y1 zW9WUQSpoiYxuV~&y)3YF(DC?_#C}I-@?knI zSMIY`Z`_Y=wr1cWv&hQ+$+uZ5cicy2(1%|Y0KDW|^0IRt@B7{PR>q$Vh;K0ZxGOxA zw)9u9IeZJ#kK$=p-cUGV5q7%CVgGa^!e7yw*?wyMvd)sIK~H4=Y{O@pC)3_M!@WQR z;PVZDB$ZZgoSe)TU90v12JPc&v?yre%4}nRue+1VfSRd(sG=d_?~7M zpc-Du@4JO3+UXpvG(Di&)_5WPAop%RJTb|;5;xP^bq)QCnLGLvnRd5mwbcJg$%OAN zU{SXv;F`(R+cU}Suc^UwZvwB%&&t<{&KwGi+6(SD4YniQ;eSCNP@j8_L3qqfb>hmc z&7Qk9%?R&;6b9^D(0hCeKA<$U(%ltLp}+2_Z~M_ypMRDN%3yFHdX|#`u0$+y0WF4iYnlf24lV1sAIS0x$mKXjaxCew9)^96FnWM0tM6V`<5O*lZeSz zmqUY-0Yj7{VOLkrjJp?gZ`9g#&g`2Wx@<5CF&tSqy%3V6x(1zG)V7A+j^GeGZ-6X;G&$dC>*yj-gq8CbCdk zf_rh+8JI@O8dmnN=glc3=<~cYn);bJD`KX{$Hm z+4oNH3%iP@}x>3f+cdpWhCLA_?<^Xqn|!e`57!d?y~ zNpz#OqUkyo%~AT}40+3@=1{gxn8SwMqeTqMYOSi_QJH?i`LwI8-bT5QgRh9WG>+?) zrgqaGjt;K|Osjv{nCsed9CiW0Ry%#RhuvZ^q;Bn-D-`soWuP%wJd=hf&FPUHWbx`~ zQ6Tp?i7lm!R&n)vT3+?oYyp`w$Y!iFprEmxATm@nUleu=(QA2CT2B-xr)JerI(HjB zn|+wvcW!gAG^?UitqwoI_{{}wp^klke_C|IX&d`c_5(ZE@U>HY`GCD38N6uehSM;N zkNxUwpI;H+qvGFFC5yPSt3v!p3x3KxhUGbY7U?%(OZCfZa#?VEL{O9?OUsL6`&TfR zH6{UnoEv59iPV^z_hZ=V-OMB^SLoV!23buOAsdOJj!|k37wfh1%ZYU?ODhD|&Z~l- z^GGBlnHzsHtI5o{p`3Ud4vO6@O_4c`ONmPe5QoE_9y~P-RA0xj?qtda`tukY%$SsX z{ruWE@G}yc;+NLiY*)IO{LFhYxo<};Q~Ks+=GM^s2Ev9zG!lVv!e8Z^(Py?t=}Bf^ z=T3_~k3CG5@0qm?-!yLG3=mO1Je(}}u*0F_|0J7KQl750uRFweY(4rmI+|Z8WezeS zN}A{FSd7SX48EM|ciy8@Q(_U4lKgv9uxQ(I1b3qKlP|idNR4{O_*I+~02qsKSEI|u zH@UBb_HOlXPKC`|mLmS_ zG`W~zE)$IkkCaw58C_Db5RpFt()4sV7C`qCj5N}R>jaEQ(S->1>Wy7R_KDcmgumjW zy&eFr>4jjbb&&vJ?qAZ(pSzJ-uvX=jB`bcXfbM6sJVk5w7skrc&p!Sx|NCiffy`B* z>0r5rzLt4bR^_AO9=-m1acIJ|^i;eL1M_f0 zS9RLU6+RbwnLN}bJ&yk0C>BY_UhE5nu_Z_5tM8`&se zqPbdxBadngK1cqosiJ>LqbH_$-C{y~ig#lRe_5Plsf|<5z7nee3yIJ5XSfRQJtKIO z@Ak1)0ga-7aVKb+4Hw4vSW#{x}SFe*IXxulzRln*`-^hmS9^wR?n|G z|Jfcejm-67_jn+(oo|(}XsX%Cc5oTZuZ1xb_Qdc7gM0dK?YSEx9~zZJzbv>{(6B*(4ZnFzs4I;x_k5 zXg;bv&za<=i$tyQ?gmahTIS7ckoP3*MNYZI*&qsSGS(VLSqqfG_Jadh{}oAmFG5xQ zWdEzM2Rl>udoVQO zDottmTyuH(5!$h}-Fna0U~^H8a#C;BgK%?=nbaJ_17Ri;6M5hpUC>NI*MS|w`R3#w zxcCq(GP1=yv_nzQCR$^v2vTJXqpT|0>M0$-z!4S%(#@)@P=H@b##&n`b=o$J+%HM6 zE>u3P@s*ET3S=TPnb~M|YM<0xzpx%fM4RR>aGxq$v-H?ul^y;mq)%laP5f(3gzgJA z$?^~c$6$V6T=^UUdgbKkS)Jj;QTq$nJ&i;XZnX8gd}U5=2GXrTbi6|4%(@XVn7`6* zLePd$ebuygWl1o@KL>Xw+}UEd=*q~idzA*0A#dA@dw1K#f}7=nYN6wvpqs||3a=3r z&qLY7UtX02npj@B!Z|@D?J1MQ{;}^9or8%roi61B!kWe4Lt4p_hpV3J(mJ2u zcW?D!>q;5&Q)!{;=aHHE5q#GB^!Q{edO@m?3U`68+$%tW@KwWywo7I1 zCQ<<_1{i19SFc5t_uZ zH%+)|)d)Ccr z+z+sStp3AYi zA9N!Gq|68toy2Z7T?kMjTz{g0+1}f8I4%m5xt_p|2Gl8%p!l_ONyi`Y3feTH#LHKy zGMD$fyy2~Ps`+VLdSl7=OYwAK8>{hR5w3Rp0B*4#wesmOW#&C7*GAnMOcT5BH__QfBB7BVh8vX zBYPesRQE*oWXy<3*7&#qZoC|uV>B_s%r={L#EI7E;{uQ?P_Er}RK6@NHsIfl5Es?G z5kwE#QRPPKXR{(|+e~abz4=`S(rkugA{I1GsxF%>HBUb6eV*QSU>+eLFBYCy3X#~n zQcJW{)ll(n>$tG}nbHRjcO4SR&;1ia6gnDk0!lNxvKul;^eX{N( zn5wUebX}@q09E<`4)Vw{z`uzXE0+}Lg;E`Op1w&AY+Bc(E&Z5ujIZr{J zU)2lYf1BjDQOC+2LG{HOW=Nh4EfF<%e?cJ#;vyWh*y#z1}`d^4(g z&w-b%cXjO4@R)$Qu`~%4+KShBEDvn`en%Z!B@!3>la=+38&PH%S%mgwtZ24Dn1;?S zp+uh3-#X@TLFi$*YMsN=O@`A?t10#??*`lDZP=sEW*RvB_QZDkkQA-6S3OHsJd=G?l{^hvDBLI!pA#d2x`=UjVl2Ul=X6sO~{*}rM z`0}UB`we#!Utqb{1AoK6%#LuC!GQ>poo6i0{Rgi9v_9rv_AyU!%mUtYhKYh+HY>um zBXO@yqXi*O#}=;yUb$b*Hx6yrDWnJWQ5`xZeNI*@XCcC-y%N&hku7gQ*|}Qxt5o6A zg^XrqW}LIn`Il)+u4b;@6`t%JrAo^pX1BjMe?CjyOLZ&|5-`HVng8kzjfFsd%+0#a zKO0-_eHQk-qCTKDu|NF~BD_$>l=;^KrEoM;XBl8BTA_rs>WdW%dqpHD zq)n+wEdO#G6{@nUIxJpg=^9D>jmG^ocLi1T%v9NVvk9}l**rcHAx@(`3=i%_qknsJ z;d37P+Nsw0_Q<%IW(Q^a+qtcbGLRUa4mgR3eNO=c@wG7x9^N0)VtpOTzM#86EJftT z@q0cX*Yf7^Vr*dFrQ%7|p%3G+!mQWCK%)Vl14rh|T@9qfv$^YJ_37C4iLe8=Y}+uJ zllo-CD>C7(hwJp&i>caRe_WS;Xxi`?)WN9oefzUtkxI)Y*+z3zc!TEACI?e7_TPf< zL)riXn298t(%y2{-SK`Qf_EIxr&Z#&q8F#Z+rl|N-g3*b;{IQ5D8_)GyemgGOab{& z3=ReCIXzPEve4ng$dXRh%#>+=yib5Dma#jhi^_RlY|wep)Z}-#?G>L)e+Q0X`w!}Alaz4 zsG)D0#M^dHsjrT6wNIj)C2A#l%W3fBu?4HxS=ZjNar?lU26z zs=hczk2TdRW-Ah7Zihlc&W95MTVev%ONSZ1QYp+k6J;L3#1~3YQiTEwH3<$5m_-OD zX0<3%r=LN$SusCC`+3n3Ilr%U8qmz*3k=IxfxfxwU_1jM6dxbK-_SeE5t2i8;{?B8 zR=zEQoBvIYsot5(Z;6svaBN{>fofzc$e8w7;WQuV@y}?O?o0vWSHkMw0)BYUs09Be zTt~;)$8D4(x6%zycWC2P;cu@Cqe%qDx5ht|F*d(36tpiU_iQYwV)?FOix%p}B+5UQ z8Wi&%?u)UK=Mq_&=)R{5RGpQKe2JuP@#; zBGbLZ$|wnLIK-utF`LGr#dNAtn3dAHq_3Nml^C6!Zq5d7y=m3!&U#sFYWduPj8N5Q zA}&0YXkf9BvWRbdl@cCo`jCk*nh!J}QT(}57qV?Yvn^H(zV zOpzDS_vs%H3+enU0iUD?ZGHg{;^O&5>cqRTvkc)#F1PnN!w!V+am6lEc1jpB9|!Ej zw(6NLjM5zdS-VHh%lY{Y{i*bQ%1@`Q0$Nh3pDRG!Y@08)@qe&SiRZ{2&ABEYOxw8) zFWSsi&bJlWP*n^0Rb^4%I`s66 zm!v0h6z3$ecDxx{Ojp(~4I`TWvafzdqlSREXNHL=r&E8vp_~X%5=E>8;%U`(V_@s$ zpf_K$w3as_IH{Q$zuh7(fC;b(ct!%VHrnm5N(cv!S#Qd!Z7z0%?3|HD zP2FF=6b9sPRlOYpIs&kemVZyHBD3kb`S*AsvowM4XL&ISK<8k|T;r^*_awXpcjd5^ zS-27~=(Wbu05%+uF{W3=brflolQ`U7{mOKX)yMtm3ThgWJ5`BJEtj%W1f6c0;n_HP zD-L8;KTD1qboM%q17*ULmmTjOBR@tK939q-MLMUwpkQ|~I~n^k_hy_U)%!=|_3}er z>#F|^V#B+bT<84Cc%m6Ci}_yoO?mBG(VfvoxB6)hyrXro^|ztdn3yu+~jT?O4h8_#yR+%?y~yHFeqsX+)kQqkihI*m}%~)dWId!=t+aE~oGPNef{2S8^+Rwa+ zw>h+HIpPnt(~MQxw);jCj=^b~X}WIMIh$0rS9GNZ^-dV8&_qIzrs>f>Rwmoe(pp-E&c5 zz(TsZGpEl`7>Fm=F|~u5>-1adq*RQMKwGMjf3E-h@a)W%V{qYWp829_>_M`K7u_Wt z|GAeFxtGc8gjv(*N04iyO7Lj8!3hYVzWuH>Id)Ryc z6H(kDy4VS0xC6jR%;7S6U1=T}CY;6sO>?OIWS*ie;O|^P8m}=|<3P42U%SiFQmsRy z^}!G8tChQKTy~4xNm1=6=oROjo5xs zuF0~;@?-G|Vd{{`P}>4?Ys2Q+^jF`XKg(>pCR3m04i1v>AT+QmF_QW8o%!ugTLIA+ zVjHAbpklzvXg-qqDyvJ?1E}U8Hy}b>egkLDFeX~kUHcf+!v8Y*TWVOZmENxT28Q^n z^D2e;3azrmMt*~buXG7^I_ECK5AVS{ZzjcakE+hm5pXw@(GD2czFbG#Sa&>KJ6aDW zlvo=)#4J|3n6b`09xs@9<%_8kuxCUhakz-O;>s_UzMF3(oA51IuRI!_7xuyU1crsImE*7Ns~UtQwxN2ng;~1ZKpnEPW&DxbHcBE6J+VkyEd#yBQ3 zYe!oY{Di)G=YGeQAPf8`JBIWw=aqEN|E8Z#&5;zIfe2C|?s!MpMxQ4S3Ku`xKo`li z08xrElCKDZ|D>K{+)deL%S3Mex=ERq^RuOG4zql_{%c#58BFd`1id^p`859qOh`x&L1z3GpHh=qOfX8z}dn}(8M=q;qNAUFx@Vg%{+ znc7wSKiEyk+LXhkYIQ$VmP0RtF%b7+yZtw%DzFqF6MVvea{U?w3xs6!z=GPVcb;8| zi@=X8mvx+X8~1EVu!5GWe8TxHf;GoNm|NM>pPV*A(c03IDejDoD%rSOKW2&46k5q*44q9-a_Gm=FtB`U zo3(7oqMKaQ@2CRUs@O+kbe^S`L4dwd(*7EyXk6}to;KT=vIo64+w5#N-H})S7z)RZ z(5E^%D=GWv*BcV9mJ~M|i=2P_((2r@Je^%$(Bu~XvEQPb0*grSF7-cm(k!9h8)oc)0Uf28i4kXuCl^w&#C372@rrSFdP zew}yMFF$y0W42DQ{Z%o$bJ1?+sw?(Ozp&1T8S8#X8N4-5E8N}p%q_^JP5 zP(+10OYr7XV{632cjqyB&4;P6d=}xRov-0%y%M^Sg54EcvFMx|tCx1{CzKSkOxxu2 zz`qb7%V>-UZGq9AC$HYA0stbz^|V*_>joiSBT!awZ-c}iQFii8K7nf77^pS1-m27U z>bn$_m>Xh+NF@+neKfn=oe)o|=K@{PAZMs(8n>dpApW=7@zI;n2ws&G!o9~KB3HjZ zZ5kY<_V#9>Ha~(0Eftqg4b8)4{t)F-cazx_T_MM)$pj(%R^XDB_tkU}MuP(JP1+Gb(erC6=~+|yq@IiGW0JCD!X*rhp@X4-FBFuzbj zJbQHfK=87#`U2F$r$0Jos!(p6TB8#wunjvNAO z)vQ+AyX&_2qWbG>0-dmqc_?A4Jjm9t=4>MDU;|sI+Vy+!WCWZdQ}6N5?0x&+atelC=rc2Jrgxx$&Y_>RK)~b5u53YGzX3%T$Wz*+F_p z_{SxF1nO1QzkIj;lVMOeU+=VAWcD#$gFn^}^V$S_ikl|yPe!G(Aqe7QQJIVZ4@*`P zEA85R5e^6WMKX?ZG%rytLh%Prpl(e_3|6G)~ z>1zJ@dw*zt$!aridMP#~^vmg|eTAgcb1nPdPrLu0AQz4sx8|Mvs`sAk5zevrIz?r8KBl2x+b$)WkL4mN+Ej z9ucfG&-vFg6V@<>rI&&g-dfHm4Xsjjb3!=1<-PT}kuzoui8l@XAo-<)|KcI{vKXBr z!NLD5M3i9nmky~I&(*ZGZOCs4+sL1PT>UR`1^+YOl70ui8>eB6@GsBXi|;R$!OfZ2 zN0Fm>Qt@8y0fEtzqehqZAP`Ng&EaRkFm@W9KfDq~X_}(alR#7&lf*D(!5>y(^52QV zmyJF#j+5b$;>l=75tj-D4I#iul>d3T6~g_Ygt}C6dd%jK_OouQ-s$4ExSi6#Q93$r zbTK8saR*FcxadPfAE1+*;#iYqt6#T*(Bu^`FsFI{%fIfh#fKnp`UK}fG41sElM~mGu+xn;*xPL)R--CZF`*@Kgu0q?5)9D#0zJ8|Jly7WZA-9vf@-H3Rkek@PU# z(4RH01Wn>;4nAunye|E2gJRCFZ2#0Xko2$B!dA;$#sd<7P*Mc62j$YA85XV;z4l$s zeyOl1Xj7#%u!&+2%k*0Trc>y*zN$p|*2;!l zY6cT`SATNu`XZ23Tvq?GIl$6^{8udozR7}w-g@Hx!mm1)52>7{zPq5|DQGll?WqWt zPz|8J(C*%V_Ks~})vO>=*%J2!TO;&p?5{1~!jQjspnrAc9-)Z;c!+t}NY*}69sPwu zW@yAccO}cM=w6U#kT!C^n3zcWHq4{)v*q-ziv^S=j%)P!qd3jOwAax2eqB##{LCYU z6vFbkTPIIAY7%WVrtmj-|K^hw*nNMO-VXhBV=TB5J6q8CD;umQ!Fm-L9D523OQGMX zE&X(s{tK}@z0+v;oaNoiLux36u3?C!PVI_%UIKF7%2yI?``h10lM0gWpkbMR*&Pok z&QSIn|BXF}=qEq|ku@I|0as`L5JheZ?i#bSx07@0(eSa#`)Eb& zJDLK*@kDO6(9_4NOG?BSt?4;Smp}AH`nB|mKh_psn|vx)=4p;6l#qbkx%%L{^(i8H z259f;Arf-58K`nbFp!3un-KoH{?cfD@pDbe<87()n)X8C!tBDY@#YJw4|$71m%}1U zB60VxG?)i1lU93Ka^)^pj(It~bI(%zV_U>SS=a9W1r}?@ujX0$r*|<1u4ihJTl7}c zDWqx8UR;LOW7Mk$ZO%L&-C)#E9y;^`=h=&{d2c|Rq?WP!j6)LD`fR{d7CS~W2nyA& zc#jhHNJuSoyXi#^L=xaPlL){^8l~pR^?wJ{zNS1deSJ-_<%rvuW88m+ z5BK(%=0Em?Q$ADO7@SQbo{ebDB4(T zihDUU*0*p*=iY{a*7ltSC9O{%cb-`z<0|d=E{oX%cd6=F%^U;ng_lnz(K0>uCS>}^ z6-y_+?-nbd?F!Kv@%K9n(Zwnc{~AeUw(tFIxS+c0q20d=*Qop9zj@BjbJg-73<8&k zXjD{n`f}ne6rRbA1`zLD$6ckpBBo=pM9-MboT4E%Bwti+Cd1v=&14stp4mh#NjE<) zte)>*TsTM)tr~-dIor;lxG=zwMNW;$4W)2FU_i>^YieXZS%QKB9~b} zCD!OQeKjgTwC1S-F1rdP4i zPZr+(uPOf$hv@@27`e(&ptqP?t+jd2yg}V)xLREQTM6H*6mK+#>|e)8vkI^&jh|^%gD(>nQ;Tg2yu&R zekEah(Hf4(su@!$QY%;SkXv-CpJq2*z8n!pm_Afgho??Qqg5=8@=j^jydm zi{C@AgM+lXeP%ze$hPwjFo%5FZt}c!j+3KJ+N>|pEleHpN-J)6&QLFniPrx+-S=@n zRTB7G{vn5UTdP%68S;CsIVvQDkl)G@?jBOjpSj`loyQf$~Z z>aO<(6hAVWaZDvlV;AIEXez&T^3p7UAe04%FGz7B)q(HDa$gCOzA+N~OMfQ-0R(+0kmac&ix)(MOtP``%;MLu7kSXB!P-^#aj^ACVSm3u zR~9(D;3jHP*{qv#i(L=>_e8(3e_eUc&dji3Vjg1hi7=NZ%Bgf7)NSuG=}9lNP^yoJ zUYnYCu)LwAwKpMw0x}-FK)OZQ3cRD`fUnB>IyT(<*!>n182y1wAL}d2+7ARGxGbf# zbz3a&SNt?~Vd$gv&qRry)4k;VP7JP#s=&oD>>o8>j)us;`J>}onDP5Zi*z;>E%itY zkxE8IZstrr0A|{Ye&u63Tbbi}q)zh@@UbJ5Y5%#J3JrZLJxNxuXYiWpmD|uke3Xjq zm*oBUlo-})r0&|8rA55p5s*;IE}Nd+y!-1!^y1bWo9Pa9_7$?Fib6!8x;mHl;?EJ` zYA5zkFWPzG*mKPM7IHkGt+5^j5{90jt;emi5gnkL3PBo=P60%NB?+T5UyaG#O;EfT=(Hhi)|et^_iY2~jZ@f_I>0UTeS z7cu!b`#FXk#MRd=BcAB4L3qVxu-q`kpV}PHIINr`%*@m<17Gg;TDpUMqe`$|%}@KY zGiJD9S@{M)UtILM{Ve6z013o1crjWTorv_uE@&P7zz?2%g2ZqQjcA7f=;UTx@OCD%M!er z>y*?~26|~_ubC3OoBPFG!`DzqjnlctLYW+hieV_&nr?N{9z1-d0J+fqNp(DL?rj-P zHvCZV%Ao2)n5xUhNG`bEa$n9jl_Y9D-)gGZqmI}TP?)Z%rn>Re)ae?#yyZrr0caQQ#m2^YCHl-Idl7W;)O2?7RC3+?MGwYPYOz_ zkCLwi239QI4(ce8Zrg6)fP&b(}z@1aeFmF39uuNoRQMGLJ463 zr84A*$Upz(xy;ttWKal~bNt63#h}CczA&pi?6CE*{OlcV%ismb8<8bD3(KXgQB)oSadB*_KIY1)Le4-Hspct~+9lY8*9e>zNFc zrrXz_ZB3M&XYjYq4uh!eZ#VUyWF|MVZL0kM1i%vI4^U((ffFEI3X$5cXBb=!j}=3g z9l)qOsYrI;U4iuxZOx&Yeto0uJ2>3XkUinSuHm8kS9a6;d_$C~ z0~x~Qx?X?JDO4oh{0$AAfXVTMHqNl-18MN+2~oh6c!I&$E;Kp?A8U5Dds5&-kO|wl zv1u-BP*t&H1!jM-RC?8Bkstf@`H-b=Cd3E}=X5VCvQZJaWA3}%4-kUj%Jr~@q6GxOpZzL7^)L2imyp)d1V=tJB!v?nt zg6oq3j!Q0698Xr}+}eBg?@elxvAx7yTMBDh`P18ZX$SdL2XAkp-lLECzVf1L?jEu; zcYvEE1yXtGc`6maJHGyjLJDI)51!_EyA(f|mP+!JQ@Sg;|8O95^0klSfHLOF`*5eh z{z}cfXuG20P9ricgo(BPxtz{tmLGMZR2ecz%jnvBHSw^v4-efVtqZS4*CCYx1~8$weH2|!_@akB<4TQ9+73c zuF-OIS42O47B-pg!NNC5@ZQzgT5R37jas6=Cj9fq{9#QI)N<5Cwl7wS%sA%8P5}rT zLb)<494gUw1%RMCU1g81ksUWF`B>i2PDQ%bygz+cWL#V8P&fSRa19pB0vL0kCQmWpjdf60DB> zJa~KeauPtxOpW4~a4~pemrSTD`Dr)(4Tzdx!4;9VUMQh^dpBYmhBOVTmn`G%M=+Wd z^WM>sZjW_6Y~EitEtEfq)w}3+_GoKoD_ShE4PJos@8LUl^XY-mtPNLOu;7cBp<6gX z_KHVdM;?eBeU|O;(*#%qra)CrJ4W2aojmyArSyZEDaN4uY++I)K)gD$b{3E_p(r24 zzbX(Zsd-dW5n3l?W?>1|8}XbM7&y>&$eJ3eD&fZO&Dp!+kn$i_O^5sidET@{K=9|q z6wHrZvnaQ&G??PVF%P3xBl65lCDDsnd1m;bi*nD>%Jvc-b7Ok?vMV6S@A}Ms#1U`y zAU%~}zMUJgBq)NAbv<*%jjNPsV|B{5bSK`omKRD3AyZk*^nhlbN?caBaDOH%%#aNo z+KVr-`r_uXh+Z8j`v8Yb@!suxhyID6mu2uN?Y0qc780&&jtNR~@31S*Uy8iIt()z+ z1H8fbx=FOD4U-oOzeSZdZ1K2{y_APLw=GVKjPLs^1Y1AN#XpOuy_szF*jP;At91Bc ze%yKm##UMJI(A`y)DYm8#* zHa-jTMDQ`1k8wfmzjr|pi3{O*#5pq)6;sYXmEeyTBeotrO^M-66sS5M`r8VVKU}t6 zSgoRfOKKJAPx9nPxe}>ds+@r%R=pKadP4+7xyWD)<)RDpKfrxzSjPF_Z^2*Y{(*rw z@dS2U`Y6dxi{bUo&`4*zt@fwddm>5z@XG*yx_~Q5DhXb?m7WR9PV;S%JrddYiM9>U zfKZx5G*6YDg{65$H|)rKtRQ9Ts2u#@{dl|d+Us3wOlv9XFDnQpnj*v1obWBZ>`3w( zYUKv##C=&60oKzhdHR#gvVmLn+c(qZcWnH|t6r#OS%pajQw0R04OTdSoFJ;7exqYS zgwMvnang+9aD#hW+;gWM?joWz`Km)KN$n97zV{ zmJg9s=PVWI^3m?dUAlsk!*$TATJru))UfjUzij55cgXT%4)|HW*y-77wb;jN znjwF0LWPa~aEv!lQf`KRyp4`9w;gH>SNXU&BAm)CO%GTvPS48l!qO`;bTAcVz8{|+ zhE{GQC_}vBDLT+o8;%U9Y>m5 zB^rz!B_89VP9bO1clrfhohi9enhgYc`SYRU5=??gHz!%!`g}_LdGD65PC)U8?8E(` zchR0fIETXT=R&s;0_E!hotAf3Jz}{7CA2KZ`g4kyZsE}t6I4-qO})pQ6wmsTCoP!a=}H)s(-a-;^iE)mP!wo8 z)E^e!W!wK34?czbNAs5_p#PaA3zPg~h3=Q--x9~Iv>*OhxWA_`!j@;#;%8;7TReH- zQSc_m059p3bPxirm}z;7Jw*My=CwwBA*g)iA{(quppscqPlSMJfq97g)v| zJgMWdT;^(QFgokgcojcT7*6icc?mY4NNYHCdshpOAFBowG~etL#cd@;XO?QodHXI+ zc`oj{tijL0mPG%Phx}^FpGY!$shR^_+@RY3P?qmu!{rf`^TqWmZ6YCVi}$q}-=#!< z?USbXAm$p~wvF}K1QxzF6B1t9x>wAaF^vX8*ZB52*kS=S?ViK9!jA`e&1Bj@wP}^+ zOkJZtzgP__;E2?;l^H^!FHfo+Ir>gd&dva(ZT8y&Y)*~8i`9O`|3yCnf<)2WmFtok z>lWl-_R-I++H&cbQQ?})Qpk-#H3`JQLs_tKEy(`~w&GEi z#4ca*FW-^V@x0EH)P2J!V4ZZ&;d_(M+#;K8olBV#;KR$2Ygvm1?Y%3yCF%oXd+03I z{b;p2C^*}%<1%-H4jge(gyYfg2w z);a(i6AHrj%+TX!8ciH6&=GK6EAu)p3NLIn`{Oa&xaBDac|R~0_;;9ldC*qDEAcdu z#82u8(pH$}NQB?!rJVAf4N+JX@DF|tZhZrkpm`#=09WwePmOW!Sl(~&ua+ZQTO>>0 zk7@av&%b2}63osf+HYWN0}o@06nl-|{1B-kwH>+XYBs2+9Q)P@t;)1j;YvP7htaSU z0CC$JnE#l!IrpW9GOwvX;tk7*a*SiZ6kr18ulHZ3%>o6g5L0o>H16VZ%X?VMNlobH zCuaH2F=stb(x=e>*7IMIFMiFQCF&kS*-s|K=2vizpdoc!VIM;Ol`=86cQf7kKo6o8 zJ>vn$-jeylF`1y?=_B|itxXx&TJ(lFg$v zOSWdlyZa2gV9Q{cR0JJbIdM54orkhMHE$Ee4b~c?^LIf?kQ1_>OEWR5h13n$WV~|n zMNj%7`i5|iy0z2{@N@V`%>I_n@&5fvn_Lv;chx8?abQ}HkW-B@Q7ly*q46Ty%-OMZ zfn2BehfrD9+Osw^zR78M41xh{(L-U`ks8(a8;!P}y9O*2mMrtg<+eSFpX4?kA8ro^ zo&c?a1611}x-$*C;mX;=R{13o|Ik7yh7Hr0!DT-crJ({+SBPp>_J~ggBI`A`onpxu z(@XlEv}0LjcJj3&7Kfw^_$^_%D}D}uT&E>#GgB_k|9Q^*nB;Q%-BV|iCFrB)wxV$* z{=47c%cR+8giEvXt;=;W3}3iThhWDUWStf)v#Pvo_S!JBHyL@QTXlJHFprKudRUK@ z{r<#tpYp(N33QLAPZB%6P?kOfeu`ImJIoigyGLDXYMi7TddN0R2shV>Mdl`W+o+c% zSgts}Sh$$m-E;&KOKgZ!DKr`8BD9K!CV!ptZwf;Fbq1ts zh4BMw88?MRMKuw+;0A9JJZBamq7#5knu(6p!4%?0>jMe-OuxTw@=>5rUqBr}Q^HzW z-~LPpcW;Jfcgc%v3}PnPtk8t&)RtZaHfP%^!c#w|btXfeB5C4O-EC}2n_pW@)qWc& z!gL^(_}&Xb0jM2QvcF{fsL-5nt!kqP6Qn=UN=o#lB;lEHGQ7qz%NCg7+_kMVTNo!MNRpeb zc1fnvag+HG+O%iW7r2}FQ-V^US(bz?h{t$AOrnJx4R7apUwSjN`oiU8BJDxTLeo)F zGW9hHP`sMJlLJYAJ=GpLw!8RM3wLjBXG;eO4L5pq^}QUW@5$6A0NHhyeQHv=NZC6? zOJYW@+j*?kOTgMbzq<2khyc>PA0Jp`!a58X_IXPnKt~KsaV9t+v}HEq#SN$9enIdu zfO<<+qw!wV_M7$?O!H>iess1S;@>jRz zgy?#m!@J;`ROkEp0HT+O*pFBW?=w-rF8OPk1|eolOnh{^rmEjSj?P)RX|Ef?hN`ZB z_7ATEZ?DYlWPr5@1L)1#w-Tnz66-=YW}&0kqGHrYtEYl@tPVmJ}o-1?%V7| zF!Vy8U$pPDhi&j|RV%mIe(mS^ty-JeZJ%a0n>PpG-O+>wMNf0QYamn4pGFy%2^ok5 z(jkPW(_hpgWX3Z@kQgxQjXueMS?n<*=&Z+muIez~hOm)|@@%1USw#PKY9ieB zG>pT1K&Xc!#`hgG^GCeU(}SqX{&~GFg3@ch_aMh5mSb}lfYGU_ppflyxOf64Y<#53 zRspYTP}<7q)kEGJ+K#%e$4?qGWutTXkfy_bpAUM6??a65+P};!7+Mqe%_XV^iFKp< zI7^f5SkqHQBPw+7W@=2+J@HVt1UHi%z8!=OddbGBz}i}V6idj*?~kok<9@=L{{zOK z8poD--|wDOrQNd?>WifbEl;wV_cly3`6s;?Ok3J{NSQZZ7dv#gQLyhncI7@#@Ys%O zmi<7%r;2$>ieIq4evv*OB@8~2A7|XHtCEmkRO2th=HH>WlcLxyHo5lW<7>zgWxo>T zJK87(ONjtL21d37{?$)ken?U&;<8cP$=MN}GZK##2$=7Qy7=e@`~^X6;l^Lj$s-1G zM?SP?E|Jr|=|=DMS8khO^`?=2Wr)15aGK=_g7eowRZrZ!ZL1*|ERvDHjDsS1-!IBn zYAqTPng+COJIp>_vzL!(*8EFcw*rcTP`L(pR9D>fs3O=~ff5N<@$fo)j=`C^ap-$1iUfCrZKT7KFibnDq!> zju;=`HCN_+NI`xRjXcW9`Fs&#R(AD0R??F4vuSPV6DGRfGM>N(jFc^Ekunnx29ZST zR%s)(nF2V;xz z-D%cK9vZdm52MHIrT72+z`VBho=Cp_1%bR5m)82frhcng<_Q7ZS^STh_ovWaeX8f@EbJ}`XLe6K2t5Dw_*HEn8 z4u6h&9SUptT$o=|s~W;?{h@DipPz>vazV0N)LPs{e9p)M>-q_#BFyCuJv%I>H=p#-OFMDxw%rj5@?~;d6hECpR!cteM0p4(JVZQ0w ze>cH-y7Zm1bs+WLf1*$>EgJiJ@lS)v9_bK4^HE3#J!IbpsFk*mj-qh6iNHCQeR^OJIcPS5%CCybk9IoU1%?9- z@Z@@cJ=wqOqO7{5yaWh6cfWz%f+ZS!n4kUIn~|$VY~gza42e)GtkX~TO>no|$%6%I zR-+rgPd8UxQ-NkT%H3k%jD}ReCRr(2P+caBEa#o))`{6X4*r`NM4K0f`%vIK66*8? zLi{H&E-cpW88+t;Q5MNKgHPr?m@MYjeWo8c*e=RVvi)O#LBif|lK}3joxdm)#N_Qj z)hK;2UF_sBe?DfU{u4Ni%#|jmG6bgxh^kDn`)$>hCqH^1X%v+_@f`^v z5{cdf{EU}E743H%Cg7I~0pzzVk`qDxzC0IaUIdlf?=TI%^LDi${X;r)Y=K?BwRF0V&nVc{xlyN9h$^#h)I2o#7!&0cX4 zUi?mgSOkE>_b`5bV4v5%$wdT22Zc|d&O4DF=N!s+(RC)uCIhNimNSv46pPKuQ-gOQ zm}1ty+t{D^j|1FZP~D%`fnxD61dkUKqJT}HZhvzY@59r=0Jh8i(=dQFRmS_LhkO=1 zj5_Qa2918Wb4~?JDCqUGr0Dsx2QfJYs&Pdvu0>}~iHz-DsruxYQi|Yz2CDy5{5w@3 zz)^vl$2=y0;NW|Y(cY#v3jskJQijw0*$nCtP8Sro`S^7=kvO9QV8$60sxp)~2eS=O zgu}0~Iyg6e2j40bHy`sk=!iJz1VPWx)1~i0==pL2!#wd|ba6B$b0Gz07Th*5+W$7k za$TkP@iskz7V+%B)4QUzp##cz2`7 z{EC!hf@i2J06L}y6pl24TAV{uB?Uah<0vW)D<@4F2f9-RNU`FUkfUJ zsBLX|u5w{SfbW(shBNlyi&Ob|#l7-oD9`+`QJPXaPjL?q=J$TKb0XV*?gd?)s&-6? ze_*56PdW1kaXBvH`}3a4_0zw_uv|zz!3r(3&7X&w18?z8++Uf;A^x7 z1OS#NtkRL&eDe@fEI`RWpuD8*?|M5Hhk2+)2m$1mTByR8B4#%=#7J9jZy|l-Tb~_xRy4}g$^v4J57@ocM+H=F{dd>JI0j^E!^Q`(an^WpAG)Is z=fQgPZTp@gG0G<*sz07mRmlzPxUa)(=rh#W@a^ehq9H z+)>wwSx66|0>?x>Kt+v=eoB*3ys%V9J!9%uiKn=l_3n+ebwYH+h+x+RQBQIP3D%|S zTRSms$uu!#1+LczB5q`7f6@lJRgI$eLl)yrntPnlQ*~NSf3Cw=-fv%#Y6zR6($HOW z0LZVA$gaBzkU3}mPznRf7fW0r_pb|A1BP(y(co<&0^hN}nJz=jpYw`)31|M8O~b~t z3#Gx!REU^IhG;>?JxK_lLXUT+al1C$I~yB`b4b9>eH30BS{+t~ia(DsF+s}vO|@gM z9jm3;VncOAsr^&fO!QoRgWcGKn1)j0N&RV@)oh3$q$I5@f!1#khAZB8WR|lzniV%N zH`TzC^I>t`9^O#qiY@w9x7}~aXYdm~5T{_{@PR>R0>xanp10@-K$BR_IBp`9&x?yW5}#!%YVwBnUZOLUQA*N# zmTFtx%?lyQlr+?N-+Ml5^9M7R{?wX-JtlO_$HT`5)$ej*VC;GL%drn)I7nitE^@>5 z%P&c>)6If25V(X0o7MxcA$8uNH}QKZ^N(2PgLr;BST@vE;ICar94fFi@kelr=M_KCp9bb%I$p2P zR$7gDtunLCa(8Ri-F6$*Sm5VKr&F5AM%*5i1bOjoez0HV@$Z|QZe94c$DgC4-`QCV z9_TYP_awva!$n>wJ^okoih|cD|FCYC(l)Z46gN@q-_1zi%wyYBO^N)>w(Zv=rtkRw z=r{+t{W9zOjLWGc_d?1BqnR}s6hZ5M-Uv4u4hn%d#0~P-`|%#n%oA8b(~Ba?=7P;W zV<<3JBK{iP{|tfgiKdY7oTpj`GMexE-fNhN8Datu&5!!FHVn1P1SLT?+UwPqLGG;j zZ24bvJadcML03uK{l7G{&sbr2KlX5(CO`JneJ7IiHziku(HdYD$P;uEe zdfMU#<7e#didazhKl0&mfzV<{t7|%q>ba|t;Zc1{GD)M5xtjNzpQ4@uvXRjRr9?dN z5%e<%|6?3Z1qj!Iol7)jC`15;n2wK)WvYpWK=}EF zgh>h0$zgN`nsuM&b^KbC#=J!s3PaVG5c@Jx$T^~~g1(9W2ED~Xq}q;mN+t9F;S28J zHzZA6oCV3p6LZm9!ANEk%RwHT7=%N@xy3>iiO@ma5uc?Jx^(9e{=~}}!%ExJ>71KR z4spU1B-rSut67i7dYgPNRCmbDc#$R2v83U0;EJK}9-6(ou3}$MA2b2r5A!yeyL$dM zkVJswWxWx)9MD6cmOieq12;f6>aad8mKr{q&mvFc5${huS2XYAX^j<8?^Grcv`Z(r z<%y6LJl#AMv<}uGfP3zsym*%mZv#nrb44w)mQ0cOnB`PeNA4NNRF)5pnwCo+aPdw` z&BBEO#CM9Pmf#XBTSwG$J&<%<|3>dEgIHli=8IQ!Z?;u^HIdEWhz?@a@sD7PeaxGq zHY9Zs&vWaD-ej>wOjx-aWLkkl^bG5-y1b-`bwLeg1#TeTQ)xK;iel zgoBN-!fnb>7J*BFO)|{-4B#41WP<4-@0QB-SsTKso76J@5N^3Ka;dZ-w-Yo>At$F* zh*Y0Thp-BfVnj!WKv|K|DHbM@V<|8_Zs(VD-mh4twz!{rT(1dC_s_XJs1B8HN9Wr9 z9!wi-I)}p3&8X8eGpNEiHbvdy**q_FF|+GScEL#4bx^`c&?#@rb872ZCgltGhJhKT z1E8=eqmq3`l&LN^?z)5u9FVGw*1&3z(&>R^{tpktS1}P7EhIE4q>}%;xCg1m8q-U& zIqzuO#DGb#_?{Ig64oi(pLU2d+t%ZaUx8V9q1>@w6k}!TH`qN7L=#W*<}D5bayX|3 zG#Xv&F1a@63DfJT;FttKPMl}AYd+S`xUUUw(|7sM-n`v$;B?d=fIva`ZoY(;1I-sO zRkm<2PHA7MPD&FSB@_JVROK-D&8PzA(;9KK0X5BzwH}TqJp})!nRF)>6P>qUBS?bh zoW+Ud3>>_e;+cdz{;_S5N>D(EDUT&XvG?ylf*od8*H~=IfEY^EO)a-t)<_E!DzA+t zbxPdV9I)cicjwYkwNe#m6GK1pps}-ZK%#iP0CKTi{(cF(5yj|FiT&yeFyy^gxtKO` zSH>BqU=;K**|8vb@rz%=@kDeZxl|QmaH8}e^^=#|<26Bg$~ZY}CeV|`D{PqX%S9Z+ zHjbd6+B-A>8tK8LB(j~m`@{eiu=r3v(;W()-nKk1X&x$pq= zZ9gA>JQ`vuN4DT?GlLQcss{it5Tp+`7yC7?NJeph@`6g2L!&RxsbAeWpC66o&A2f_ z(Jd~RV&7$xCptZhG4v}zg5XpjK8j}l!5D^mURqL9;VTDQgzL}Hq(@*1Ol4t6VOc%NU z(7LSyNfPjf1|)PvBqGs5Hj?BJjm{OryV7H%>>rAX(Awp8wZFOvPEgggShGXVJ|&(C z|DFD!;AYdZMi|fh9XOK|UEX2RfY3eCqV7Y2U zloj2qjBgB_`6N?oXf=VJ1*%ZM6YLaau)v4zOuzna0w4xZI}pu4PK1~;EII8DBiE(Q z3%eIfZ2iip(eCVJV=0UGJKA%=vaHXhvj`7%rNWN@koMqoqt%YiUvz~~zX%)Nkdz^w z5lwfL*lvp*#3eP@7QR9I?lvUl2Pi}vxoy+atJ~j(qaxSm=v|5|p#qUIRBd}k1wdQK z^8Gx%6dZ>2TocRLn)tJ_)vw(D=_~CvQ(RK=_~vZR7oCKXF1#&=NK{x^2(S#Ql+vk>n=sGTWeAl~8MZ`j^)-4$z+L~V>k>2>C7 z#GH0g=;)4o1ppL>nai6PeLB5~PN(@HfzAEFYc^c)0VnXnMWUoPPzHNA*4A)Na>}OK ze5558#uQaXKy)b<#Sc;0nH&>BMRt@TtrAOymMdzq00vONr&Rv)NzN$Y;Yt0>c_}}gSE!i(^^n4A0iu!6TYhN|ketQekv;dR_hOJK+ z)CFPMzu`gK9UDF?0lOCmkx4>jeJAlRqqWN(^e;*cilNVIa)M7qIu&1}{-CY9Yo#F- zD}>A75+pXKt6WfPrcFd!$s;D*YFttwkbU*8J*+$+d!!#d5&(8A86MSH00qD#;=^y7 zA?T7uEr7003KGG0V- zN7(o;I>l~W)tK2+YePT4?M!Ny5^ex<3#H2>!H+~|$vfc5ht`AD-OB)TMGK^FQb|1C zaRdnkhyo~3miZZ;XT&6|1_!qra)3_fXbfc1H9C2@K@jz^$TKh)@DXSRLdnx{oBO0G z=gb~f;sto$MklVs6v*D1cOQG{R}3@m^1JeATDmPQ6m9n9sv7;E1du`zvgD9COyo#k zL7Z9Ow_!(7O!j9^_YE9C&~!~wEcBY~8(HZ>vvTdQyQcr1;c?kge{O_v?ETLlMVuW* zT7)-Bq&y$kd^adqMNSmW&o|z0Yu8JjIPB!KP%|~V%b-C;AFj;Sr>xEwcA&7+*4lZ5n88RnJ2_F~|8{s}Q{O*Dup5PWy7MXKI^Cu6VJ(Xvk!2&5 z^)7}DteFgv<%FkGQ<8FsLkzLTE+=b(nTs4nWo?Kih%L{lWy;R3G6sE+sl%MmOns7!Sf>iwo@IZ9E9d0oeKkoH;Z);h+^G4oRMI!*GyQnp z*LVnoeaphjQ5O8??sjxrHH-jG$toa$8Wc41A|rRyMPd*5KDJ6fNWXwnO#Dz1R&o%g z$6XD%#n%`^D^hTSBAZ~70QhPJ2=O~dUr0WNTbW+P>Oy`hTMdSGv>C)Xy$b1YZ4Amtno+R4 ze0`+iOp(UdqN}hh=C~Tl>(Ki%!JfX~xE;87X#j~JUm*c?Mk05tfOmVudXp@ixL3O);@WZP*CYq~rsS)Z$LJig_O zp6Y!MTBPZBRBuSVajwr1GRM0+^vzjIaNsNhO*bW<(+>8(p1(vl&da+#%FwU;RMVUG z`09iX(bgge_#9aZ&(&I9{Rb}><4{0KkRib$INVYTz)^|`8DWYo2tE#(ocaRmK#L0) zblr9D`{^*}3rzizlyBQXvhR7ciBo<>nT`jKJz^JaB}> zBM7!vKb;hf*I9i=g7f-cEsEm5>jK(rsfv9_(GX*gcL_qAxQL~1(5X7ViVsFS-it8= zK5lX;?!?z?)de)0$xP8Pl#!HnzZMz-E$J$lWbgtoKP**8He|NTzr+&Epc3I#E^R5! zyX(mjvABZeYT^2Z%XTx(Oe$~$U7b4M_Rg_4$I-Rbdcvgd>w8ujd1sK%KAAort(xJ8 zVGN7ZuiDjq&>#s4_TrIQkmCVs6u+o-@* z(tglSdp66x5^2>7z(oi^&}F-qUNU^af>!e2%Gvz36S`OQj_=b{iP}u_HqyU+P48?8 zYXgx=(`Y~5q9V_9a#~Llnot04kWrjSRD}6mH41_b7KBmQmWTT z22WpuVNQt-vvpQuG{aY(aAOv76DCspW&n8}ERJ_=C?2s^hweI-;1Edud?hzqB4_k( z>pT0MV`6MHlmkDA(ATS8Hi5gw(njT!`%wsJ_&vp3e{IYfJCS#ZxP2Kzr_VAhLHC~^ z3ZzJYsQ2hMJ@<8JpedR<&qTy`v{bsZtt5=I5;e;5Ja#>|R| zYFhUJhm4m=?giWp3MWh7gZvexRo}G60TK#hS{{Q?(pLfa=6EtTIua=o1O_nDv@0Rf4jLmEVyp+luZrKLkaLQsSmKt!ZN1VKQ$ zJCyF0l14&6MCtCC-@)hpzAy9t;lz%$*SfCHntChxxDXeS93PM)hX!Kr4IK{Tx0Q4C zRobjfq8UmfJ2CA$Nm6rS((4wn0(t2pN~K?m@sd!&tvb0jwr3MAEyC;DO>BVxy~O*( z#xLH+0{E}@v=xH_deK!RY~B>64aPD_09A0omj9=IdHdmkHmPY zlG3(EjPCMTgXr4u3LlAg&6xcUubQn%p%Gs^?n>_g`BfD@%gc9Mqv1FJa?5&IO1-`K z?t*UzE7|w24kd^jilw&{Z0k>c2ICG4LM!kAy_nt_v`2cR_SG!)p(MuP1-u4vvN3JxE*rl=rO)7MrZJz zUoEmP!Cdxx4q`YixW--gux+Az^kVq&3p^LJ4`2!xhQwhEyDTwx1JB5|-~MpIO7AqT z(8Jvk9831kH^sO?7XDStbGz|D4uZk@S&HgA1 z&=O@(Q2tqx{GECun{a8~XVK6JFyr}srT%j-r9DH@^1&al4kduD#*np=#}Iz-8u=8? zEIjZ4fr$RY^li(_4pXw&g9`(8gM7uyDJ)+rq!-Uv_N6eNQMhw+Gr!taLf^VqKqd6^ zfv?pP+u!}rL+$uL!(=`4kEP1zDj|+~)3Bd`FgcD{wN>3m<%J*k%uP7Bw39-uy?2XF zn(N_^aN}Qne?M{cf$~3u?XORws0Q3oG;r}aZ=>JwLvKt~Sz`U{mB*>2mn-7>?Dzac zE*b##9CM)=g-GO*%F#nwf+ENpbfg%*a%(+;vy6tbl;+^!`eQI1i;nTYUY%UXT^;IM z8F65`H`A-LtuhFipzU|V&Am80eDaNXg;BM5?^SK$OqVQ!q=lyDFkw@zj(;N6wHki*xSsHp$?;HElk7Xjl6{$2I` zyJH@C%tBL43Hh6dU;bl1!OCE(ntF8V@A%YWV8|KDrXW*Y%0$*3hiek5;;i|r>8yi_ z*7xdrg~&?&ix~Xzm!wc9;e&LE+Gx|~KepnGb!OH+NzDp_4)XkQ2;+R&5vISu1~X-O zcRe=kHeLBqzVxQn%T_;nZ=`eo$3;e6geeZW0LFgZg0m@e_2W6pb>mu*WU#deG7t64 z%u0xP@^7(!1dHLHd3aZY4jk|@L_aln&Fe*;)lJd)E* zPbPGBR+*f#8F*8o(m%Ac^cf+ta;HD>=~1Qa1;teTng9WAG`0|#!eRJJj)zC9rwJBE z0+ao__Z`69_wb)~{WuffCkkV|xHCZ=>O7Z8q$x;K#{b@Djf8FI2Cmv{t+bkXifp$h z`3Rc(O$bMp&3LsMyL6d_AN!`4MI#dZ1oPW8c*;H|hm+pcX04!}mVCr9J}FpOuQlye zoFEwRd+^InIb8PmTViHKIkq4`&}F_@#z@7(af1E3mx6|0RBD+CqT7k@o2JBB5_;jR zEi(1>Hh$$!ROC@m$3fl-x(coOrQ;uV$hW%r2~q7xqrEn?qNaIzg33mX(Wf`|2jG6K zYnr$DLK`q2+YsVL0T(o%yJzNU$rQUhv`I_xD-qYi6Jk1% z*N!NhdTQb{g|5@S%TaQ^3Yl)xTO2s`yazjP8Em#2PHe4@Eiw(@RA-`3g<*en*oPlU zFwZwPr7@F2k2gcD5J-jUuG?#F z@{70-q4gRcm749Ov$;BFC?xsO*)gfHvk9ZnZlha6eH7Ps>7~0Z&zPO2kAeqrG;)As zxh8-%J4)uQ9Cr2550DP=`_Xk1jp)mJ|9l97LN{(Vf-?7ad-3J$Vke%r0Q3rTo{?Iv zv6OxT(L_mu2r9RWW1-sqN1u~k(9+L|J0kv@loJ;w)|P@u^wi*DF111{SV? zP~>g1=C(K#=aml=sk%;5J(*n4LC0&0_|bm8ZQeN}kGer6L_iLmI!hvm8FTt{Er95C znl85z0Wn2Hb2N1F-nXf$rn}MX0{Dvy%Ify@d0z9x2UA&R`B(JjH7dE0dra`o@UyuD zw(>fXf=z#|$)V&H|GVIK(@d)Ip+Z!VX=E6dOS#@4c7HHjbL~6{0-npgflXegIUEcW z6k#eXH=JARo~@{IVDfko#k5x_TH)m;$0SrE&*nDf@a%*h-kEZSI{g{y0ru^=_kbk6 zKvHl!8MVGZ9!;x(_LNEyWz$Cki6NI^QVt>k(*-=Xcfi~lEt{xMtQ>~DYrGQrJ-U)_SojC@vHb29+M?<`k~ z56Wx3K3cCeN27g3QFd2s2iHcvqPnP;Ym4VRxbW)Sw`YtTI1*>X-!Lg$S*!Yd_*CrV zR~P4pf4*;)(EPGq4oE%*01!bBCdc(yY4l(`f$!5o&J$zcpiED~=SIin%6-ddS7svo zw|5VI7q5e^Ms22pI!6~I`T;>zR3LO!)>MMUw!#`1Q7r-W{`sY<&(C3eliQI#Jbcr$j_V?*nnnAO+4WP$f1Up!I3ZQ_ksj~EUrbVJ9;O4*}X1V8PXl#7@jkX_}e8nxQxwCue$vYn^p}|Gz$D9XR zpzY*wr#RDii@HF|-=Qy}s4>f>*1%Hr3b0X-O^2GG=3~{wqKzME;1@J`mwX`kC%a32 ziZ3-L&RAFFn@}q;CU}v?4m;bB4+g?-^FfWys}%94lmde|$ZQqGP*HyvwDE!)B)dc< zx^7e9!@HP6eT_gdmAQoB35$Vexk?0G2;vt!X`_!bf%Fu|<-ud#^CN0~a?ID_ViqP-9 zLCT!uz^LTW6q9WiGU&DW?863)=K^x~oKA+QQB@yo6^p=5^q+|erZIh_JGXZ6Y=3o& z%%I+8D(`5JlS1kLlHI$GLU9ILs&_1Rm?zs9L9WehaP=yamYCghg+ZlqBPHWx2z3sJ z6|bF}iafv(_D7w|j0khYlp%)RTj#s{V|y6;w{<;*o2>M}7-uU@&B%Jt9JgE$#Dt-P zG51RzvfL_q^RY*%6=qxG=67mG2+^af{?)DFP|ft^X7v?m3y(_r4C{zLwNC{&@o7z) zjrNHy1_G({4%PAfD)%qX>NSsyjGc_BC zf4T#>mc3dq6G5bKE@EmgR+V0*@r307FQUx8JU}9ulz~?DnsS_Sakqv0chLSH6F1o0 zKHDBC*SgGP^6^Pta6Qv-2nvk(qQYZ^^tFbQTVHIM9q~(6U+9Y-M8`(C3b;MNU0TXepWMR-AdTYp!9ZqBjtJ3U`ZGR9ZDnNn z3pKJ~1>~1>l&Y5ZrgFp{X#oW4!G3!VjiybhA24@4VA72IQa=6F`OBNV`e+JBU&B9J z(i=UQl?YKAkY=m-LpxSpl>hVT+eR0vH;WE1Hu&4ztXQW|@%a+vAu~o5$Bs+g*!c_S z{=#K!hIHhcsA`7qr!NVh?a8R;<}GYwn)^n)X!PNI7&Pw3gKAWxtS|@mGe2ODO)vnB z_a<6$XEwIwr3d#Mp8i!K>VH&a$0G=!A@Ts4jL1MBK;G^OE?C?m2>zX1^CT%HlSREb zYool2=IfBhWi3jE{HYXw9!@>{n@x0Jyn}9I6@`gns-`0$Aw-W|7f^weG=MOqs z7caX%30uuIB+2e&p!uJz(O;_5WqPg+O8|p_1Zbt!EXqP}?d3o1IT@!1MyB1sR*byf z>rsr-V1Mp+R|SNKj-J}(bJIDJvAv>?Y+Je+d!RL&b^UlqqRoWDw;amNIROcZz+45^D+&}L|J)aOdRwpDRjQD*!2OBd~bH#%)GLegw zXnFHr5a8Jr^5K1w&Ct@W=$RJgPGey-%lWVCcCO;?@ePA2eB{?)QZKhkM}F+szl-ezdRFfljb5s1f-l z4}Kce>urm#*k?iSTD@twioiXG17QF0hUAvS%876js~ObFtRUv*s8KIC}(g zkwWf&H94sYgb&>2jVd&tdY{hb#?=`$kRM~=(~*>O)6L@S|9WLST@ zY0rt(C%yQy9=jVO*PkozNg_PEql+~vq*YRu?N%H*Ge7M~5RQt9c!@wI2Vk?EfM4#; zOal2Fmw0*kYOyoy2LHa$zhKi99Ztg^2TC{}C#~KvEO59NQL4O#vmC!~8bNqX%8I(x zn=AN|>ZY@=Mxh8QC82a2k}j@7OpLpcU2c;Qk&IDStURCbjy#ciOkRFkCZD)fM3axU z+AF?}Ub0IUPHO4ooco@N1njeE>3p?|_}CSGbKu8U&y)lB`nf7tjG~ML(8SDV@BJgn zJ43oSrRoUa?YBZM?mtrvtZwXcn%vxU@gLUoUUSo*6vm%U6BG;(QXKPC?VG;Aw54}F zYQ#V}YbA-B+yX<&e6z94Bp9It7oIQ1Z!wvlrd;C18~kK{UlpKbUQ|?6P)jOr*zgpr zrl|1TN3`ED1jHU!eZMWjE`$V3+F5CZIHU+|Xw10j9=+fx!CmJaTy$070&UC{S|XlB zwx_PqK zGO(@r)WAd;ZZSGTnRot>1xLC4(raJ_1m^FwP|FFvXQLCaGfPdr@nbUm^N2&Swcp!*nDBytUM_#Tyb#oq--A>f^2&5wZqTN)yjX>UA!!86-R6h3% zY{c*=pydS+8KuoexlCq=#fycfdPWQWV4kU^Ssh_Hy}qaCzi*rau~rr#Oh#6PTT-#I zfIH);Q)xOV9ecM}-b5D@)s6a*d&_dM+5Z>VjsAdz6dmG#E_F-mC8{QcE2|Fcykr0S z@s6{BI8w-89*JfK&~0d_3qCtZzXJDCS(_4aXLTUVWrjQL{it=^DeO$I;lj|{n`*_F zO558fOkj|CdisLK3jmOShO&ZzL1OX0jD>!t9cH0P(4=;UKj!aP36M89l@<1ERNL@fYRaBb!5q`cK>7W zx}T7w?if%AUyrg2X@{A>aqB~&u8E(W6=sayXXG<8*GDJ6-z0B^!xD&J9|}0V<hDr&n(dh1p;+IbV63XT;j*E`t^4R0G(k+kfFh2T4|m z2^pi*2aQ|RWy`W7C;C^#NC)-Xh>kZT`YfB?=~waBpsY-;`m4Y{7pKo|z(;!GMga{M z*SSIYai%@TE!XG9j0)G&Zky1LY>hihWAb*R@4vvR)(Z2}#%M0}%-FC-kmBp*Da6Aa zEBEyv*V(4$iJh(fN=?1%w-oKZn5q_zoE2>aR=$%k|5=0VU`83HQ26j3Eq3GYSekr>CsL>t^;2~Mmi7FE7#ZY6VUpmUChXE zK*;1yEwj~gH?}LZ$SNmRSUx*`6(&?5rQ+&e1foJ?gU6dnjpIfF~s@*&Pg-W*Wg& zC}7Md#oyth*k&wxfNTl4vT1)!K#}%@R5}OX{EW8^67+l8*2&^Vl@ucl%PBGt_yyiE zfoP*r(*ixnhAS+i296j<$aNd!=7X5bhb9I@Bcy-?@>9D%cQ?t1BiZw3<{}&r@f-7B zN|dGj;3m8thvgF@0p&h%U?#xKYe-A$lcc8|ms&K#vQ$Txz&4@-^g1FEMXb4 zfW*g42THAQh^n1Aivpm5_z9Jmf6Xz9hhsV$oKTp6uz`Tm!nEOd!RohqZLRHeu$I#VPJ z4k>88d`kHe2OL&)Jb%A^6ju6?&>4)*WD^Jz;HBrsM;x?(USm_4zSLO)99q1Le0{>`jmg=D4j|vz1EIyky~Qo%O89KMy0Wc1gUW~`{te8}X7SChD1o^O z>rg_&0f%?F%4(2@XKt5Z%jyf`-7KkHL?ILb$H!&)OxkWJi|-wdBV|$mR9AlhK=v3m zW`Ezqc`!-1y4WU3<^8Qz)j`wXM@BzU@)96>mx_O|QcF!UO-U6RpJK$Okxxx7D_l~ruBY2?=UOi2cV4SH zU*FZ>@uLxg2Q#2CXQ@5)jw#4X_;s`8RK?S#e?2WOsR+y)vGdwtdDrgtwJjPDOur_J zRnH+>6V|7^2N6UfjluZhi0vP)gl@b=r}?x7+tzAfWnnk@EE8!Ahd9zDS6ZJjJlY#< z(nGbHwI_!V-6ULLPok8?amm0%WVisnTx(fNZuA+TSB;0`i6EGDRkxvhpP67-WW+Ns z9}FAq8N-EUG(lA(1iIyG%$f1Y?Kl(HuNu7P zBrblRXKvgi%qGR>exsSuSJ%j<2vTvoXO$Q~P5ueEaWg}IUs~}Z>|mdGHp1$%yPr&Vpby;a^01p#h(xt#f~-4-_3EWeEEtO4ba0yw15?y z>8e5ZmoM5bU$lUZZWUWS;+DFZ=c*u!qnbnk9j*Gu<}&s5n0{nSa>0HJ_M*jqVq#** zHL0@-WL|<`9bH#ygb)WrP7{W7A2W}Qgar8xCamhUl3c%%JRH79^`!>p7>6%|ALaEd z^{MZY3k8fkNq+VU>Dsu5D?BLw!r#yb1fElroL6~T-WVZ-`*vMw_;VINs&>%br_Usk zNtSur7+Qs*#h!7$=d@mK2HUp%D9j(RXv&iXGIVhwfRI0Oj~w8=GxExqzjwn(G?3&M z8{?!0T#i)kP^i}vO!!n{zx2Tyws#5IiEis`ZvJwtU*2+Cz^^fo7mCi*?uSsE6OV z7iBX~G64vpjCWT4qbfHEJRsakNKSLaJ}bT@nCGcYQHE-86%-)-5J={=oevM@Jbrx| zR(ls>+RXAG&Pl9H0sZYVGQA~jQ5j4VMHDm4G`P|gU!ge6MNqZ9=SLeyF0|jALuLXP z*{|L$k^?a}W6wM*`xS$|mEi`*kdH0z9LNBNy~R2=i?g{!3@03Bd06{1Jq|#h-3YwX zUN%7saT=d%R{)YXx36Y0m5k&A@@0w0`ZC^q<9+Yu9QWdSJ8^sPNEWq03>_1x%(fd1 zt=tW3$f+3mv?#}=5!(+Ev>(Wz)s>xoOAucfh#-b82>^*)%M{1J_f4}P-vM4-lV3mC zbbTAJaAKRI4V-xmFOD6vw{l=CmH$t?wiR?};og7c(byEo~?XmruZnp64J5C97v;jmHQD zKF$WQb1B7PvD;H-Q7}Mkj5P8Iii#s_O`I!l^=gUTuj1OKI5aBDT-G_lJ*Rs;uy2c`n`DFIhm+h1D)12gPZ@`n{*!7a%0psZnh1 zY$pgEy54PNuGCR6`$d;_n8XdEQ@LeYnyreQNUZlv_L&0!d&9Z`;FpAG1FfpFCgu;*f8I_5Bs z$I7yx=`wVginS1AyD*PZOMUGsZ>4G?_YNWK0ys(04@e@X;1Irn-}{oEA(}Abj;Qt+Umx3pn@3{xq!A?bHICUfux^xGx zd`j(Q)ob7QO2e!vdPAYxM#VaMPToP?s5n8CH!_vr250a3XqJW!GljrSs@x|A`Qh>a z=`?q4HaU*o1ZM_?BiG-n4x8O0pDcsJ&!J2n?3g^~JCOjG z?u7v8t1p_5KF8k-iGc906$KVPb}(sUf6hW3c!9^hO9;+fiivEE_*H)PQlNr=7E+!S zzw6$GD98w-eq)vmZBY}@kPTcdhjs5X*;ApJDONUT**5D2eA$U*(HExnx z0f(b%`(RHHsh8iXhNNzD6pu4D-G8D@_{KLf4ypfJTUDF9^$y2(2fT0ux-_u|Xe0JchvAO&Dzkymb|4vZ<#=zr_Fosj0EVT)kTb4Ki_+`)yl| zVKWo&d6sbS)rX10cYllYMsNMr=2QxnZ_uH7P;r35{6@XGr8*ZnS1cJ=zZ!RMcJr<@ zgKh=|uY(D6DT`2w9YS7M#PdFv3O$A%flrJ+09#ufi-S8I>ZD=uy+SZzSL8fPaG0J`!44< zO@B}i#ljTZnzo%5(j9EDGyop=*WQkdUumaGjE;U?%ND0{_)%p~Ml$s0h3Z`-HT*3S zjr;fh!@DliLNC^m?OhDLQ*NzSEBOJfbn*n6i<+#rXCWh3(L|Ag_`ojY6tp0HVXlDE z&j7jEoH$-M5F_i7RR1SPTxQSPofw#Y{FmIxG+l%f`R=N0Im3XWk-QJ-J;raBO1LBY zAfM0z1M*9x1LPYpQG!BT;`)G0t`#WoO?4UDPyY*WMAmYMyj3r%oFZkA(3wPpk_3x@ zrEX(LYl-3vK+Gs*@aXIILX(LG;6il&uO&Xz(yMJZV!N5|lSyvMh4zjR?~Aa@UrzM=ret2f7noWdpu_+Cj)@K@H3=6!G|6;P7(7Aq%l=$g=ESC2ny6e%3}U~P>v96jQ;t3H#+$P z6)gfES%614*F~bQmjbOvqd_Rxqpw$bDfzj_Y5E9y@}*qLpQ5NBymuFUr;flC*r>H1 z>^RHs*0}d(#l&Omu!9*StDLQM)=~k{Gr`Fy7>$-X9V(ZHMix4*aK{q#?{M$DvmHpx zd3`J6m=}1gH%63ES*aIxMQ0V(O|5KF4Y8C^6}w?3LJuK7u6Zg_#YN2%^$q_9o31Q^QJ> zbi{UxS--?0K`hoa^;;jO;4<7G1jd=3$)y?)&&oAW-%!`MQRWgIHJ$&VfXv#}C;l$JbLmP}9)p={;@Q@4u}k zFz$5^{O9n&p>T%5eb84VvLIrAMfg;A3d)|libcGV{UPL#YNdHI6PbD4?ZGVnfPL4n z5e_-{J^bN1g_kxFaJu_*|3k~A%8bs7=igmlviat00osLZ2cd+>f=m`_oij&n9Q4O- zysH+Ry8FL4GNhBC^~N!;?L5LkQu~?E#!1`sFkZJd`I4H_=_o!V^+s#+%T5cq=a;8@ zYJV_VxdGeUI@5lXhmLfW)}Hziowm)*V$nW{@i;Sm>!QqP=mhwU{eE6u57mQf(Qu~E`AUebb*)LAQ^S6e}P?HuS zLQAd$Vfz}SQgl!6y%en`^t57{nHazMf#16nLRFPO-&?r!Ys`jKN#T!m(Q#<-RhLgJ ztX>wEmeS)srU>s)s^AHKO8}wCjcb(es@+ zN&qb?hY+N8PFAJi8^7}We2OFgb%gc%G!P?UR^3T-&Ei#&z8?qfutjBw;E6(}fb|5# z?rL6BJgu0h^<{E^NT4n5W0LFOn#71i;qS~8D}QfN6MR$o zq_YH0-^99@&IqfQjvP!oin#}!H?;F}^7FYDqBo*W%7SlmP7L;wGdcl<+0@LLMVuwr z8C6tlLkyJ=SjlWHnY`^a^#CAL()6&42!+sB}ekF*$^Q6GvinVBO0P5 zxNfn4RHE`T#qpFT;VHM8v95GEMk$c_=+F@?H+UJ`Bg*&;)@3yN^ZN5w0@#uzZKFy> zx#&P5Ngz0<`?Lf0Z%|i$2z=GZ=M|5M#-5UW-Rr)Ulbzi;V3Oh&q6_Fc_^|R_@$^dT z!!AVWfyoa1CddZvZaOYH5RpBmKx>XmQTB!c+EF^``F-YX@@jp@Q8fN+4^Ag3k`Vb! ze#+4SE%r)>4)F?LR=n=|o(49kIvHU%o{^DLpqj4oujRvThE{qGsOezF!{kTy?h{pH zl1pToi&S2yPwcvBPP{FWmX%j1vt;@n$t`3*#Bc_}|FV}q3YBYDhs0^qpXg2?V^LsT zAgk&9*C7_1rNCNzmOp}T8qUns({HsMZV*6QKhQ7Xw91G@f@m@=^0Av6fp|kbz;CgyakMJK93QdhIzt}}RPoW^4d6A0{W5&1bGMkYp8&V#fTezOOvFnuNz zvxK8OKT(TZ^~H1D?r6U5Mxt_56*(f+FvM{11`0AFUNRQ0y9HHDeJ+t`D*OGh3MF)< zs%}AFR9F}UsxjowR^w}fWA0Au9tzCjL6_%5TA{&@&=muN$)Y%!v^8XU05w4jGiew9 z+Z*lsT9%*5G;(?QzlZ+TaZ9w%BZ@;wl5e zbl%GXX9?RJ901UP86!fUfvuldJbvPrT?(>Lx2`h3gwVn>b?IZpeLwX*&+)4Zx40S; z`S?S5C69jQOFe!(9z7e z#LtThI2HMlo{_6y@56|Xs+TnmH!}w8xlKxr1rtSpr4BOr1n{8qd5^dYL)8LiZV^Zx zG$U9=-6SWzW8|p)LSNzk?lU0+usa?Q`YF@fAN1!o0Hm?$sF@@vyZ!j0+uz^63Zm<% zyGu0QU*GArAbu-i_o@#4#Q-M6AcS8c1Hs4TPE=6uhV4?RgF=IXv3vJrNpOh4U%fDn z<#-)K)j4cQcu=zA3pVx2bJ7jMpst`0*bjZEtINU+67c(Vcx?fog!i+vE>R3^a#KIC zy8OeJI68!_Aqk<{TkjGaA^N)i_wXe=z!mn1QB0g2%{vSM)FE0`1MrQ$t}|UrLuyKn z23{KqfS22d;6`aKDh4TSj=8+0s3g!K3H}ZRcV-K8jWC>j^u92a(7zwZ+py%TS&|KR z4+b@>lj3E%=0LSd)-x$3k*V?VksFA=_8jN!2~Ysr(&P!LE#}_2niUPEkI*b7+vOF3 zac8gw(ZlHB%%hq?VJw{V_gMpzI@xpeK0ndCkyYTF+-ZD>aJEDm6N`Md( z!g}xFSowZad7-QfNuJrj1YoOPHZYP2t%D`A1Mi82BIA~e#isKMuwvSvyS?$V@?{M_ z#aCZn)mrmj{~A>Vk@C$5(V;JiN_3@|N5PNIsG%W979D&(0eA+-#)v{g;$z{xbQA1J z!LhunEZ4|OB1^Dxa-pW{pXem7PmF$YvzlLxG9cQ-07AZ-1?01KTaMrOat4O0voET~ z$qgqJGswB&gn=QUK=mq=YQVF+g%a={o{jgjPd)pMkRm1gD=Fan({M>ZQw+S^##L$^ zL%A955;UT?>kAxxj7kuR0eXQS&%l25>7F-_1j_!qpyHA%g~YD}{Ylof7NsUp`zzke zd-haE(gfaWA1~X$Wi{y&;FGchB^1&pZUyt#rnkEz%H7E=QCOAr zgpw@f1?5|#E!qP48((u5`2WNLV8lkT-h5rg_;nbfAJ)L#cV8HAt#Y3nKEJ1Bu1FPc z0x^r${kyh%G{w^WWWlOoERBO^ZJPFI(!zI)DO5*f z>$|6uSWJdr>aahxRW2={P!ATGq+Ct)Hbg?9FODlCm$iomz3C(L(A(MZT93b3KY!ez z_<;xfRNxDKh>ss(1q_uVD5*KVjooyNG{K6EF(<(NvcFyBd@!eL6b6bb z4qf_sCy71)R9(b`bdHEyUB}CH%df%UINdvWMsMK9kHjMPe`AUYdO{B!i5j?O#iifF zz0HnEs*v9jfqXe}#U4mlMi-p4*GukumQg!~bIEuTqwhjXAJ-H%fZ?-WEnFN~d8ea$ z^mIHJw~>HkNU$1t#P`3O<%WynK^*a(T!H$cu(znHv48K#dmyTIr<)AC} zzMED(5zioazoi#NL;zkQe_$E`vP1o_3U0Z=ovXmZcE2@G?x;W?c=bHW?y-7PR{#Ho z!^GSsXd8&V7fFatQOhKP$ z=@m%%Og%{Qj$c36bSG@9arYkR4MjbWn}~)#wi78el)}Sh`gM(3e~Wu zG3OA^QWot4HoyK(o52BKBQK;7OZH}Oy4Q6(-?F!M2iZ2A>Ecumq!Qm#|r3WrrdKhzLf%VQk#%S05y)Oc! z4z50Lb+;6M$0f?MZ+s~@swVbb;?5RZd)aNCR?H(_W_j z=vRwybyt;LciLUHCf$?45|oVe4$QJy(n61D;VCB_Fbpg)p-1n2^;O70wtcwmNq`(B z&Y!ci{!&#uw<~wvt0w0mGdxH0D%=1MD%Y)v)rZC{!bnyT7 z$RLu;)veG<{{Pma9&!mV8j1d$np`FtJJ^k)1A6bV_p7J$lwLFp7Q;XG%H9|ywQXa* zXK%z{7Y8B#;W;FkcQIMlJi+KSqA=Qi$cjr1`E=y$P#h^hcBlzYY%uJ;I{~48Z z#oWQZM~g4dZhfZe@TP^NgI#1N6|(fYa?vW3(GX}B)2 z5}U6{JaJ$oOB*vw_Z|gj;8LX<<4c$^wvG9+4I;LGbwBIBg{yT;6_|A&U_6tA7?P@Jv?1hob)B_fm%QppO2t|uXjD89HZ*iEe#Aon79PRmX47w1MB}%et z;b`yV0Vq8?d_Yp&fw3MooF&YBSQXOXar?goQyt&E>++5uhVwV%mnucIA&n}ep<5IGy=9+)nyxCGmk zdd;>ls3L9AC6+*KX5~p%><9V%*yvYFpoD3m4os|Uf29TTrT!a!KSbdm@&DE2K3Vgx zM3ZKDZp=KSY{!hN9J_b9)oTHnvt_GThe{9Ju|+j!5Y6{stf>^YwkfZ_RF( z@9utYLZJoO3T$h72zucSiPs;3^$W7p2;C1hz|Mm{%g4cqTC)Gm) zvzXIO=}pkoj~aVx3arkyTwo?{f8W-tYB2+4`MPMagL^dpbxQbWzza9D!{jK2Kew2NjD z3ix%~;;eq6$T(e)-@VBKx0RX27H$AAD5x zO2pjWts1{%D?lnKkYYnx0MEuANHx>K&HildAW9cR4Z>p_)a@!*}db(rs?R@?xJvoFfX(^0U6(O;DP)89dzr7iz0zAB+W zd?yj9^k#WS32ha!2O|WGgpvpR3A)#LpQ-7Q5hL2XK8Oi9Y$p1t|5rFcf=UQOw+s&Ekid-x2&4bGnjNgJSPvw8#0<;i9YX)gcjZp}y6# z5_ke`4iqg8E|u&tj1YHsUc#3a=o1+=d9=MXdXw0MW#KC>PP<9^UWEN-L;mBhy!!v* zQA)L?Z%IC&I3nE&`UT2Ob#`xeXM|K~iKaF694|}g4XK3VVf`ZJk2dOMUMAQZ^|=6y zkFzSD7Ck8>0vX)(Bp|0xm9qb4@vDop44b1rc3M?+^G1$FY9U`-eM^8~9e}VBUO&{J& zKdmC^WO`EsoQsxGu;b-tWKGeiF1?RFo*j*4)b{(uXcYN7V5q7#-YWQOq?d{uACn(@}|=x5-(iii@rQWcsm(OX-}uTx+i=w6t-* zpN}XXwnT{*^{1CR2gv=;yH<~p^G5DnyLBylk#4UJd;)&^q$zovm{iMV@EZO5y35K- z7pTh~)a40Rs(bq*;+;n)c^_wf@4OxkOOIFJd^>d6BSiFdD_Y;yPXO{amf`TGxvv!- zW3Pf|I7Oz)0FYl?0WJ!^TmVVQsY{AK5w6W=c2nnBL`b%VV`ffE3BKMrc#3(e5r`fe zl}dW;_H1q`Kn#AkzbKSX9KLN?hP_29f4Ljaf;q7^jeh+>vvv+6?$M1^4U=yX z_F|FlX1|PnF=+kcU=cg%c4gF)3}NDLnJ!Nrw;vS&CUtCE7cZI?50>AIR`f7Q>+xDz zzZ4>m+&*e!q=fk3DzhTh9Hrr^ycF#mt|59$9MLbwv(EEme(`9hXBZ{^H-mA)TQ3$) zno%qH7Q<&2ZR~sV8OY7O;w8+h-AH)`IU33a_oicOPS?Z_ZD){82R-Cq`2r zc_3;}Y)vxqU@wz`^KiyaDSbcSWD2bhTBxGADX~JhvuFHjudAPfMU&ZgB_V!$=DGic zn}MwEAdeA)*K>@K?lS3qSZaityrRD7AXYz^I2)6#LOHZ2SqxL6@p_MjU#*E=fMV<> zX|OB#%{zN_XEd^~CB0U#HT!g1UnKc2KcvnfY~*~C9Ku6F`_+(qTc|2PD)h^Jc8Cz} zz&c+R=(fP{u@lH+!6eCzZmv2KZLR$3gM07?P{pS zvgioAXX06!&Of4msOtNHVo0%Usm+wR(eGYe+W(!yWT9%z{)f8P@yg=bW&mv++j*W% zv;EfMihn2!#eU9m$+XjOFeDwFewfYW4I)y52b$(JxIV4+1)lilZ2zL4z^ZWKr$sJb@}_|8EN-f z>V#Zxulbar@B{p6a{$d0eiSc8a=?D8Z(Np_qv^YKT-p&yfy zfBxS<|DlF|`5P>A#&Y}FukB1nJ&Rln4iHyAjs0s!hdyCA*%-9YK!3!N`L8SW2>P}W zorAq;D%7Tmq`@3RBJMBdStku);CWQbSxO7ti@_{SrfZxoi;xrmdhm60TLxfWiHGdT zkj)o&o9_ddSh&0C?mIo=#^~nr{#tOnCCWgrKOZ(&X>Os9_S4f>0A>5IXwSv|;IVx7 z(+?1jZh7mM0-@F#688Y6^A(#BPprQH#|_rH1YQ?2YHZe?Rz?wB<`<>YSki9$8q7}XQ<(Kjtry<&s2JQ;@rT+Ww)<1JA-j~4m*XTR zdR5q^wM9MA(gXL|@9U3-UmDfISXuPW*rb3V%pbl{qNMH+Qfdu!Jv3Mu(EtO_(c1pW zryDa?`!k)PDLe&M(v4PV1D>5%IQb{ zkG;44iYn^kMu(7)4w0cdln&{TkPbzW?v(Bx20=nPq+vi13{pCWk`|Dmq&uX0U|_h1 z=XvhEf5H9bu6HeFondBJ=gj8py}$7ZG~E@ku)vG%(BW5Zqa&61w(|fGpz=_9>sR>- z7nbW)3f~cB#sqnXx3RzJQGU>Y#Pzm{9L>QfZhhw>n4Kbbm8@n*+?8GU^m zi~W2D)v*ZFd+=yeBIrV5#?4haT#TO2rq53%dP84zQm7 zwoE136uiC4@t9Lws#m?T6HI0w0M$l%?yFeAJvRpF(92&)o`iKUzaZ1afofah?&RH) z49iza*>zzbxuzIju_VS!Ztt^M7s;}zuH4PXJu3X$_ldt|ji zUfIAixqZ^xR*f@TkVr%^v@^^p)ZxH0>eV4Xad56c>70VFH-H}SM<=Qz>9(eT~7 z5wy%|MvTcF;2P8@w+zL)*3*#@eHaQ@6`t#uRQw|MP!k4~lkHGTJegq)58cUtaA(NN z_s_lTBt!kUDJ|^2(ucZ>8lws zDirt`)&7wRHh$FdB*di@)zl|P*g^Rx13!AkTn!}mIld3DK?q7rYj}G#>a;??C4+7o zCZEK}boIx-7M(U>#TqL#5wgnTe#p%5aD8}@H+&dfeeoB}wDR^z0UNaakzK)GHL*EW zRlS|ghkVRNqXS_um7y~XI-0Ydo#3JW-M9k$n6%=EJ1)xeMgJ*7dsA(^Pq&m?_UVVt zFy?2wca2R@SPj~zd*rCqqbLGa-Td|p{`=Y7+5ExuArQ>x5rRsU0XSB&SmJ1Lu zUd|uj7AE$?JS3gauDhv7;mAZcKvf3<3%S@C`~9z#=wiqm?MZg`ZBZW>S!!}W(c8Za zLXz7B;mttFwIY>!EIyp|#Q{yyjMFmD0?pU@80@9e2K;)z@QCNjJ1HGMfsN~M9FP&- zJas5oWOVG%ZoG3R>KwEEZ*8*~Z@x3RopDVFCiXMupOuA!@r}ZbB__*31{oBizYHeu z?luZ3{32-Bjri&~+T89oZ>W*(bgta6req0#AxNd$Od^b$@kaGdtw5U?556SxU{$$N zvdh_{`5uf_zW_AFeyN-#wv{5-3G;;VhDy~22`yl%Slb=ySgy)6RgnugTV6Pw>J=P| zzWIAY-~Kaf?BSrbm03747LJs=4>jdR!lWAn2do-%=elt5$S#G`?e>@cqC2p~QI}jx z(YFD1FgPbFppztJ9!-|$ACWS*SOhV=9QALtkzW}8NQEUpqFZtIgQ8-HAUXl6!;ayZDH~<;#t6S=S&Cl2EzH*0w&@y+5!t~V(U$*|>us0C z#LDy2T15#UY3*25?obR_yxA0E4C}u$y#u1?5U}W{6RAk;DHK>;crIgmZD~(p8&`o} zI4L$ndN0ZlQhzOhKL?O+gX*n=9t8XCe972MhyRLQ*D--{0$ih=pfFVy@C!Sp~ZRo(PJSciz_+E$3% z{K20qAFo~(NO5aRJpNCeor_f7ez5mJZ?C5;> z^C^l1M@fTw`yH-NWy#LPq#_o6gqUtEMN>X2MG49#Hm$bVOH3LG8 z8n^MO?T{dEAv0eBcaG=OVL&wIL6lv#20-v#aJO2{U%&iscctUK3RLhk5Fo+%0afj` zc-s+c-HVol>Jh9EI)3(Tir&~AaI!7$mlx_79=w%!bHndv3LXVX{j z`uGElROo$P+o2PtZ4Vg2#xWX$;y9R1j8`2763(yx0083}VNi($Hiba*@_T~U)F!=u zF<7Va)BiMORBKkni4W}*0BM^rKWCg1M%H<%yEm5qVD#1L+R?Y41yx8eJwS^J~x z)T5RmP9)vi|I0rfM0dQP{K~&9ex}ESE)}GJrwB>fZLrDpij{68xa{XbmRKK9XTGm? zLX!vOGi;|Gja(d$+RAFjWpb&V1s&jSOGp)<0C9UAA+Mowqd{i|%wHg92JKW`-Gk`6 zotz>S*^}f22x|ZFK4j`x#r+$(Yr})tm5|Z0{3_;y9@7fbBGX=ZR>cl}_4l&4EsUCc z>@4L(!64(J*eX=4+1Y0REj~kQ8u4kfv+}>8`z1T3_0;KfA*atKK4)%Kw(W3i7G+aA zW7jC@RxpQfKxFL6G z7i01~M&^^f9y3faFxz4GI^KQc%=Gjv=JFz%r)hQiZj~SXnX>^PZ9tDxv#mgoSL>1fi`?;S z7R8uM^gcc9=mS>9tA0GePjS#}XfmE^|FJm-7D%OK-WD?h7s1e1q!T z`mk!i9EI~e2cC4@NHca7HTG-|-0Migpzl{*c@(9yTR$=*x##LX0}EUS9cG+PLlLSr z|H}x0ED+3^LO(CO1ti*se`E$U82iw{CTs^CgX46_y(24lY$Gv}wtw_ zdK#)_u5ci`2FCEXaBn_)-aGP5o7Ar!}2**IX-Bv0ukySeSTrq%?}H zCL#{E9~4J;IdZxO7eIeWf28rYzA2 zZd$2td-^uPGUv)DIfk<8PgxJWmZ@jIRZ3}5HjMJJ#$N23clTzg4B(zv#Xsd@0zb?~$v5kAbpv@_r@uD#p@@Vq z<7}50tNN*biLW^M3aHIrIg+f{nG8yy$qrMa4h?t3hL4;+hfbf1J^5!pd^Vm>x4yQ= zc**dhh%vfVQ@-zttL<8Uz9KvIHd1JEtyHN1=LSaJp;a_Q=pMhZ{d0(Km#tq26g}jb zHMRlB`#(1;sQ^X54lUEpL-vP9-aJg>-IV%>TvCyh98b2yJLZI!P$Y3eET7=fmRKAF ziR^HZYB#twdat5Ph*#ip0gJGo^Dy>^sQVTYiE`*lVWSK-svEh?F#IPQF5ifIj3FDb z@e#JQb|dj`jh%io@8>bkeO2?47xStfEcHyjQig5onRfy@iqrcnXz4k5fN%;bXWlAq z&QEu&CG2>o8EBDhajXjL&3i~4yB0kxS<6hW{_@7rbvt=tlq@JReRzbZawW?ra4Bz6 zSXyi9Dqzg^ndki;`N+=7n7RrDwS!%kxvhWqhvrXw7~a^gIKcp7?yVas(>% z;08ogG?0RE5OC6_7W#>By>!7p*v61tfX~AQ$Jsaw3o(&6Es>m;zGC`=gK_mpQ-0j| zxkSTBXCF_sd1qAfqm*!5W{DXZJ4+`pCUtcA)h*pszpnrL6)f?mD`)|d%kc1wP6J}B z>PK)?7DKPV!AeL+QbiOCFXzG8NyKV5>SbaC`%NPCPy(zk>Ytof?}^@J)>FSn{t#^B zrt4aeUbRa*2ok$!b)A@QyX~f9Mr}#^S z^!Z;ey`zIPu$Ztzn}11x>vlXdaSx{$I%m{BQR)g+2fb)6qBmTo%Yge z;HD>;i}@t+qP#KnDWG4bhAKtjEs7l!4@`xQ6yK0>yu#Rf$+AA+C)S`SZ#CLS`o3~O zAd@t-o0{tGCaySSP!4}bdtPY*CT>YgZDFJCsf&9c8ASW}lG!99qX`aFf2Q_i^{8a8 z(>gijYJLV=z6d5CxuH|~nfvENFxt_9hZcRcQyJoK^_zSkBI}P%k=#p8--Q4_J7ydT zzwT|ZjmXK>8-YA#*J6p^GWeReS}H=k-E~`Iiyk>2PgwQ4-x<*j*|yqc!w+~h2@Y#E zO3ev`_bb}6c536dDnC_k2QX8R4zM zMgQM1h&oa;%qJCsGekK@9Ff&zn>4E`u$*Rgca~w^fiTsSdajFmN+`obIAh7#%ivz%1S9{(i{o1Fa!n2?%{hD=nIiZpD+|AxH)?g1+s~HL2pYLmxdT>qSbD-?PKl^Fa>qX>a)}O3RU&ivBr%A* zG|&N*}6(o@|m?$vu+Yy^ZvUbPJ5W zRor7fvQB5SIS6D2ZPVGbnLBzAbbNk>3GJ+ z>Y`@sxx3s8k2>l*x$2S0m*WE1uBJtFpWbmo}z07qBE&9W7oH=bi%w`S%vYy?k!Tv{*g}xL z{mbO)Y5w!}m9L?~zumaJa*bsOD+OG>X-_6QN9#`LH|BF^2hlXtGa z&Hdt!ONM?z=R#jqQU)VyZqom9+KrP=jY^`Nski0!U9s1QR>rBigJ$2F`0LQEftTds zTz3*@jdR6Mrsugbd|S7uA1rQ>=V)*W2lUb*s*hqy7mgz7XGeDfy4mDgP5X4D**{lo z?bZYB?n^d`6DD+1#Wew>1i`xYnXf zH#;#@LRH?fKfDgeE+kZ<#_Y~v)KU33Lu5_2(C>BdKxGeHpqW}#O*;~d1CN;0L5xpS zzVvi*>hz%?q$pQJFOdeO=O#85q7FO zVL&&`xl+1HT|#t*upPR66j?(!Wh~5=8R+sV-+v|j`gD9&{Mg6Uti)bibKH3p1Kudw zs#&^XD<0ZhC%*4Uy;l44*?cxUrrtXRBb1lEOLJBaz9KV4Rr+C}YhP|>tGrbaE&Hl( zQ(J;df7i&%){Xl2gS>`Y&Ynd9#7cSMp)>_fON3$EFdLXzCXVqS>)04t2z;ToG)Gld z*JZ>MYVEM4XTIu&ypuPuWdG@ovXDjo$O-$kHng=?MXXOELrJ2gc+09l+mTC(R2rc~ z4^@M+IcEid!%{%=L!i+N=|GH~y^3$}9WA$$qXM9?6&eihCYFk8Y?};xe%f}3L1Ga% zy!KuQ_^r2_FRb0kNM<%Db{Ap()GgMHZlN@Or_TTMi+zA7u>NQ0bnhtjgYT=XHJ>r8D=uXhFQ(w4~c%x>mZ@?cdamQ7cvZ2N!fX zF)!n7Y5WS$DPcos=18PYcXuGkg<9Wuc^!!k{y%JMkL8RiEIVnAeVB9{qDpu#$vzr_ ziExQLBPz|5S?Qb-U|t?suG1J3B@ePk7k@fxCd;3$PSMIB=;9I|nl`{$%YNpXX9Y_ENEU!4vJ|D4zbnoV(PH1%Lg{d}+`hAuh z<0RaXT+Yc|5k_v0_T{&elPrq%u1w>UiA$=|hWc~l9tY?c;9fDi=A#Xt;Znr!XsJ;s z1Zxh747Yp`=5drD-N_9b@t+EbhK2q1%qi&&!P)OwI-xHdXgq92D+|F0&O~tF_Z@X2a zNQVk@zh$6#O;0ZuyalS)sDhrBqGwV+Trl5J`SJ-|8Dtjj@uIy^4Xp@9p2xNyb1v+n zmu4r|jZo|^f^~Fk`CUc{c4g+LHLkTTv*-3>Xzo&58iDM}TcXtVJ%sz}#IUza&trIm z7$Kyy>6c*p%5R;}B|!>MyaNp{eK*ZpX(OXv`oY;*f#ctAh$Wh z2%!h%E~-4MM181tl*ioakPvqK-S4nnJ!Fr@GjgeL1J-u4Sn?#*1K^HNazn}$=T%05 znWNIt;C%H}dMMB{U(`61P4*T*YRy%D>658q{epEs*ufv(sDS~o$!**3kWlcZvf{Od z;_+URb!4GDe!3Jiw_T7V^rz%f_yqq=!LvCjgCrGC&qK%=TSj5T2 zf~kSOKNiicggaakvsGFPk+EdN+NP-%h+( zBFMZtA$+JvgRgj03pcPNbXvd{QYkY=AxfIr%Lt{H8Y3jdiH}eIIEs~pbktY<4*AC? ztO>Rf6I=q@dy>O+b~XIl((odnsVa-{hqluB!<>J_Nc`kirdFoz{#Byi^)-k3^^mDV z2qHJd;D5QnTwY78W3nZvcD6U~nL5%lgXv6;Qk|mso7Pjbe;Z_m5o;OZPLjIYBi+ZJ z5c&o?Gf$Ou$K&N>m9N|!heaXPkpX_7K`BOy8(T_31P)>MF@qQZ+uBOOs=RX`F--|# zubISkN8{RZc6qa4JqYJUp9$N%F?I_MWzFl;`Xi*u{HjsfZzH@Se|~ zHJJ9;HWQW;_d5DaXd&`ve^2{o?^N{)n%`>8iCdLqy}MIuB3wGDW#Bc1HJ_Rs?d#mK zH!?31QNUIe@+Q(pFC}XAqP>1>L2rAsa?5HCu+o{wdLPN1(zuh|^)J9Z#`%e4=|#eb&g3;A^_GH6Q59 zA5;4uh;d}`*DkuAWhR)|3+L{fR!0_~&blY#{VhSr=x#0ngW4)$wgeuqH@yR0kJeCY zoD?Cshp@~-NIj#a9?6=a8SVpwVD1jFk7_gMvq;f~AoEDC3--5Pk6Y7A2%$UR-ZPPs zh5U47VXc|y9E=G`+9?5Yh5eG<7N2nNAk)-8Tggp(*~l#4hKeaI>z1ta!;(4ocf%iN zz>7jom!*!j^zIs&JJLonT63_K8}O)zcTGO8+=3Cq02EF&QbmKPl||R05VdE<;)sdS zo8WBip+3K%u|ccci;A|Zh6|@d-ndLBBa}{tF&yl8H!xd&K2dv-;s3F_WWQ1>^Mi%h za2#hsW@GFp7gmm$8kNN=blg+f-;C0aIswg+VoWQ^Pb%|q8gz)aag3M;gr;^KKT|oL zU!R5Yo~5=IVyKlq?Q*%`$C`Pri7{ zCk0(Z@PwMZUkS`se?NbnL4iX8w4hwi|4m+vVU%5t6@Gg9HZt~dA@QwXu99lY$0))A zNMAPB(b02z^Ge3=D4(b>Wmj2a|1&Xx<32*GS0AhAf~X@t(>seJtVjj(O!ihRtfa?3 z!Vb{X7O!zW=2)sK{w)pvQl!+iO(Lik7@k6rF2_^XoeXwe z{Npw>sCVUaisKXwe|6oYWNZj97+|~6|N14Ox#aDlV(0$thiyG^IzB)^4kQ~1rd!s- zr2r37Xz{K6vzICR;d?4bw4cW6+Z{u@^2&F}2@<)MA)fwMXh%E1Yc0nS{1`sb8JGz_ z4#}>hc5t)YBcVAh)g&6Sc|Z5wE!2ZF6$3u;`+9q7ekZom@q1-G?TIIAzN1LlUZ^69 zQ|p*5f9ah1bAG!*^F{pdc$DEE@W2-W8Ndh zIv^k+S@mN0rUi~_fqUWq^rK^O?yK%%AWydr`a3yc3c1>NdBRGYT{oyFY;AqY6U6Z;@7%HpS1&De!!3CVQ;Jj2YQC~0nk&N*G$8Y`!y}tj{PdjbDN?_ zz_7%2uN`^rupweXjv@f7ELkIxh2Q-(qd+{dlU>+qA$l#2e=u?+4y@`qMuw$^gWc_5 zBb{ai%tPt+RJUR>XNrfZ)&{r)h;!~W>-_YrPCi${*Eq2g3Or@BSjKkygth6T>%v~I zYX{^r{F}+duJH-=)p>rpI!TD6$=LeV+n8z%iMLDjzY}8wZipSLlu8fY8sVq6^n^s) z9q*b%dwyF)d)b9FJBd~346VcsT@Nff;=+rWA)BN8R$^mO^(9t*2RxxD_~GB|8p-S zT7qaC5ZPMHn>%wTt$i?ek#YyN&;8RLhE`;}*1hf+oBStejhBXP(MwbI$d5^ZnWvfC zS5Id-Cwg;&cDbVvdG(z2J8fZZssJHnn-n2kF})Jo4TE%#+J~3xmX#F)@nEK(=xJF9 zUd7sndHAr39RVQ^xIp!3hJR*#cx$+rqmtB2XVg!-$SsRLiw$R1*L9d)2M!u{sdr~qY5%fQCu2U)sy_D`CLcG&mR6LyR_>@`TUiuWxXWq4~Kn_yGx+Xd^dDMCm+Pa&~AVMTCkPM$#vL zj`?O4rsxj|?>o@*5NwdfrcD!eh`QKH8F2nfZ!J%>{X?zeH^c+EU_3p+@BK!x4Y;R2h5DlT`ozbZvAubBdA>Xl!Zr8c*3ypn?!j7vOik~ ze#@ok2ROglu{>v>gb$ao=n{66)z80fx>e;@S?8#p9$BU_mpyU+2bq~K`BYPH`eHeJ zG!C@$JUZE)M4YJ~+db8ivosXYb9*shPyID-AU-OLv*rT;`({^)H~u9wrkd8;sj)f= z%CnZqdn4|iRe{yiFo}oI+_YvhxrkL-x zD?5Zw36p$>Fa(LPHsp8r9sVZhS!89o%nE7HY0fiHqJl5b`>Y^g|qwh&K#eJdhcK-Zh0 zbp@AK(Apvzc|I&W8aDw2t0+a^L*xF^hu$3jA=U3Z(m}85eD>>rQhdmtZaeU4%2oWl z&Qu3@)Q%WlV&Kv(e=`HG+wzgJC%|La6fmD!uUM=x@rR*+uC@~ihDYSCejlM`q(_z4 znBXwb#4Jtwd>6ljj2GbL(OOp$Oy?7dmf(^!xSce=eRDTaDk~~X0ZWs^`VwAhn{EJ3 z_!}@fuAT*)GtVF=QNXFm5KBmMr$pBh~sk z-CPXM7O%llONGTEKueL1H_8KoY6z9uiOsTYXw7fu@OYLVmwYZnFR6XB`g$;b0|o)$ z`|4)72H+CK%|9ZHsF}VCvw?T{J#K)<5J{u}DSgPoq33X!Db7nWNa#@~Zt4D~ z?LQ?80McI_+_eYK`06BW4y#eV-U9lD^tZA@G527GUaV{FE^%3|3qJzb(obyjRdYL! z`{}vrJpKFoC&s28^EDnFWrhVxtU;c}sXm$2WE=skop$6eemld?=g(IUK^uFWwpjLj z2inl1OJeCvQhj{v2!se53wfpLlbI$`De{PeF-4Mn{YtZahSl|rvhI`2L`OyOmV4Z3 zva2{KkW;*;Dri#}mc>qDU+|7)s1`s$<8v1cF;#fcFes!2K2J)$yhn?crw9naVhWhb%ysM23KI`XRjCgALQAk*fzWAS(R_z`m9?UtI;&mtR(Nw~nts=8?6 zNTtv$u`kc*;}niQ`S*i5@z`bXlc_(_-g2cdM;o6>np6no$E^aKr&s$r#?f_y?H2*4 zau*BpszY~!OwH$PnhZHX0GNwCZYjsZg6%Y9mO%)^8NMs+&`v4d?0=darWMP7ESh3|3i4H1qvZMxMA#$Ik`^;vB3P&!~4hxCWoX$=3 z%ZvE!+W$48H#S&cpGfZu9JM!UE19!vcTaai`2K7~_z1yUgb)F*QCqq3_$E2^cRkh& zLkla?I%%Fy{%?Nf|44)X=kWiR0a?~2Mc!S$ihn@KmC+688iLf6wUsIqEZ#d>3rK)4 zXf0xNwN;27(mVv-B2rUTdIbVu0#7kPcsRh}%zxqzbM%nsM%?0 zft~=*@jw_+jv(y&j{pxE-~j?*6<~m{fFs8JYXzA9_q&*&0<8b{`TYk8kaZtG|I^O) z$Joom^{4;UbZO7t)ZcdL8t(CcR`amOTVQ=0n8E29&>zD4t#%cZ`2JRy!8))VidqRp#RG9RV-tK_;bcI&VvxGyQOu$04!hSU0b-h3NzJlR;vOWMv>-+K%DmK^- zQB5~_+273p#wR9fYB5rPPRK&8gqO)&z01Ai(Y;N_JRmz|d+&Q{4nJVg%%K%?J#(o5 zT95GzGPC8TEmHucYj7V(+$uCO_|TVt%M$&q9H4MxlE@%4pTe#Yd|PhZaE&4c3$e}A zI;KA5+u(Lsd3V%Ja_hhI*xJq+xCAd;2LFQC zUJ<)t>gi@5C%F;8h@fu^ibZ^6T?{{~X>Oi14+2;`&EX`nGrY$2JO%W#*osHu09aT$ z9iX@*!|wp+jD?OcEYni$ym>(BX|E*!0F*aBt!y2a0mwWRjg2$=4NH*r(0d!aAOHwD z5A4vZ0F#?!_A&&({$)r3vfCl_n^pkc|KMv;f@jF}*|87xD2cJ-PBw%5~0 z`3h129HzIb&$@jLTA9sA#o84$4QHl-P6>YR_cuT00hR9gdjSKG6>Ar5v??~8vO5;9 zS?5f(b@+V@6&9_<#6lL0#5S70xdUt)j<%EvFa`0#qOF+TQ{2GsF7Mv^>`pyk84ip7 zzOAx6>XnD*;|^#EwZxA*csVN~bK zfSAH*$fNw{fP9jSD@#cyK<)qs1CcCbZzzMGBtiDtArn*1PLL&xI&As&a_RDx%9=D< z96LMF0x;J4Ds&U@dm#bxk?fQ@rT~Syms|^@CNXydG~dIhdF2?-t^iqv(|uhPactBf zJXFAKQF@7Ua|IAyB&KelrnqaNCRlnrTf|7$l$c4dMCJ9vzGw7-CgoZX;8=mx8w@~8 z>l&|ciyYARymvXqVdhbs(MO|?x6TtfY_9yE_77iB-B`q_#M5l}<8lk&wiXF=2sjHo z5+IuhkEyc4+anG;^T}^<`Ze;15L1R zL2ibSGFy^Tl0tWeS>OOOH_W3KOzO@50O+x_Kwe%0MCpHD&Qxb#%s%$G80UB;)#C>! z;;D8sKh22_`HC86ATWupZM6FJ5ckg;IYr)x{GG3#Jh2X>oThjxx#hF-WE5xW;iS{rl8I>~RuO&;}N^t4dNhTG;zrlNVh@ zVM&a-Jk&A8^Nvrei$%uCD{EME(I8MbAa3FHjIAIwDm!8be;WyHwFUSSw#G(GG|6R^vKkvirE z#bV%tcY$KtV2C2wBmPMeddajaqMrUMujOCjW4ZFd+p!fSS#ly`4r~@@7TA{Z9WW2( zTMb&pkh?teE<>Tf>FuV(t2;{;W@qNpGk_6(b)~X8DWfP89)@SMaJAKRYVGQJn#h5( znR#W;=WljzCqP|7T29~<^8%OmA))9Yp%F{1`7j0zb*8(B#Bkx_2C4M9b|CM^O}4Qs zQmyoSE%Q6T`r93l)Phm44*$Twq6ZvP{vL?Iuj1i+Mp$Ene`H5#cEdlVhd~8Fzk~Aw zzA0lHg6PP(o)}P3s-@+t)*P|EEGWtNDCNHz!(EICoiPwIGpbzstW%Qc_sEAis)RLYLz zn(q8T+@JT+Ox>EudS>$FU-MnivB$jx%$tE^AougzQoj9h#t{TbRe?FF?=@cMW5h~j zl*ihlMSmOj@}o!BAS~<}C8_zxJc6+udmi-GR_LpEF9GZBD3VLBfg6PER+HH6x`EVP zJM8QO`Z!Ji(4P4n$|S95nQ#$)MPk_{!a@BiA%9u8VVGbI`pv2}*LsAScqz-i%F0aq zJ;wP5+S!7nEttf(Fc#MDp#3d;J3uG6SB)ko>5}5+SF5DshZ|`Ifbg$vRCEMzpwE#t z3<4xNGUsV6fZ^rB;d#CWD@B(;(asOl&5^W$qZuAG)|lod#emrpYkqLi#fDTYjtUh4 zm3^^qv50dWkBCw5E#@(>nBefp^EC1-l0Hb_d2Q5~jD4$s^&GLfhR;tRLLeB6d2Sf( zkoqAXGa1UHcr($!!V6Wd!`9ff5uASHR7ha3Ui-ChoPV>0>Oyy1Vk>qcbQCnk7yE>O znSe%l35%@Gib^&5@#TlHmx&h=Ka*H?SYJLDXiTrCeoP>A=M|!aY|8ij+U@u64^>3Y z1roNj&58Z!GwyRNEJzVA9{(1Sakw+>Zb!@32f_U3U1~*d#@V&@Ke%==K`*0r z9W$IdVO;@7C8nFXU0uKL$Pn_zXCFM=WiAu(;%5nyZyckRSUxMln>Zv@;M)Y)Saxyk zUPJ~SMEjk4JJL@=5@pVJ2;iOGPBOHL=-^{9*7Cn4ob|_zpts5GyNkeDl_6 zc=GH^{#E6a!H=S=X=+2iAKt`e9jp`7-~CI)AJW$9*S`JT8b+kD$o|l)FIVZ1X3O8V zLwod#Il_{v;{*CDq=QbNPg*XJzpY-KrcHO22hLaZj0vwpv!Fa|pwvyHSZkSP69vrq z$+Hhqn-QnOsh_%(JE)%fB?zu*{<#QCD7DRZHci`#G@OM$wJ;Q2-||(o|V~Zg)l-`%6)@ zk`%A(zK^N#?UME--zS>Zc&e(YW^?07-bu_zxEgJIVR>`c?d;AaxjyA5eaW{p@kFa- zAHL*`WVmae-{|nT*TFlJj*O+Km_jb$)3+n|6>DM@vFhFlca!LZrEe;aztQF;9t^qV z#y-4^`RASxm|HZlkF`~_>kz*5uO58Le7O_MpL2E+R5EEiBHi5D`8`#*UhNkKP8pf z4Qa-a(?X@o=n=1q_QRVOC==rbxjzz+#Dl)WiM96N#1XxWuK!$3+`kEQyXh8bqKu+( zP{o1IO}*B%zZV$(!}-z3BT3JSS8&VJwQHB_(3Zs_&yb}G$v4-|A-m-b^=eO+zWX`H zE}H*yeq%27V-bhGVH<0!O>HyZ$B1O`9P;*GTbVBHMj-qt%O*zTN5L-n?L6YMoXfw^ z=VPcnROz#BfQc<*bK6n6eB8$vb%mFhCj9-zx)rfY>(+{a*cLU-tR@v2TQ%V3!H&b= zD!A&3>ui8PkqfZz^-s$&ac8xW^ z!xK@&UUt7#QEF3&2&h?{77Ce)#xN)y{r*j_v?8@~Fe)%aqCsK!_9MV0f<0y9ah{Z{ zBC^9y#fU4U236M43fbVH!P4J;T>&ky?wv82!@U ze6!7#1P}#a5yT;=ooanrv#d@prlDa_vBXNGn@o*eDLU3nw%T1F%Aphl%~EiwzGwsl ztcRo+-rb&zfk zw_>!26CL=9|L3$vQGG`7lH*_+ceqVW&R6$_KPOKZOMNfNlMjmu>ovyQ%b!Lm3$4yS=6WohSj7C+I9I!o@%!1z4PJiboPyzMz)$c1YI5lC^mm7uJyMV0uDEFT@z3 z#ItPU4^&H|G8sKyOlju8ar$>YxfM0Q&9kic1k5yzcYTEA4 z;}#JWV2?>+WvX#`@kG>Ws7*yQ=H+tw#(GpU(a2w*Mc&=;kSMIRSn4SnV$S|eLTxil zQTeEE2mRuxCJ(!15hy>bvQ)j{cn=<=Kl#jpmyZS{@5Hsn?*gOShf{wc*>^5U%srhA9F2e(;=po)znk(dzbrsD4qvMMwH;e~XJ=%<@!!=m@;6p) z6o2^NT-1epp%*tb+)v1mu;8B*%n70R4O^H3PV390%Uik@pe}ocymt!2y#vawnyIYI z&$5Ux@p)wDcr-z36-T&9zQSyWpa7h-nZYRPR6kHn$*11?Rry5^Ej}YLxRi!{oyn&x z@k9C+&)>DyV*W?6;90zuZ)^-kCa0vfr;^I!XhSO+;@5soR^>F+OTJJ4lWbeD=zgi& z{c_K-W4!l|InXm$#m&UC`ONeDyi)i1;Zym~Y!X})dFz*-nUUH#+%&B6`Euyv=el9u!6WVHRn!%~qVuTb@$Pa8jJdWZ!;v|Dn+!KegZdfZH@Z^=` z)xwjY%p!+;Koo&@8oQ7mZyG(Ia?NR+(Q0$6?Gs9x>>P=9LG z|NgUPg57I-Xsy)%0erJDHoUX}m1P~d>pzJQW&c8j%vhTfo^(g1i9b;!gOsF$uW5b~ zumouK5K>bl^?m!f5A`CfkUj~a;&HwL=;U<9edMTr4f>yCU{$gw9*>h<_4wt#Ox%RK zHSd({!U6e|1-?nSXJ~zigA`GFJZj8Hd2&*RA13T5jiCTE&=?xi$RTelSB0K?lCs4Z zCJQ~hZX*zQlnbc5%hpv5W8i&*M7?zP=lbHtxgQkT?tDAFb7v`W5c$9JjguJ^Cw1ghv>Y_c^-GY3!!Jq30>K|& z;u$`*eW=X3EXK)NNQxg_woZ(J0IlO`JlnK{A^ny@rtMFx8zgO42>@DLA%D;DW9~%X zPhGd)D*&;Yq77!0u^`6V?F&<{i3d)-_vOGa1%-kiQ^OQ;cUPl~yh~q|XJajxWnX=y z;j){4^|`p8wV-Go=GO69FNlw|4;p>>2YsksZZop6Z4nA`HcXBeJ9jIeE(w zdvyQ--9n`O_WKIatbdtOLKvIUsWG+OaSw&;d6O@jZ4Glh$>mNoLFk#56s9%kX9uiN zpYAs8>D*x`AMrC%T-yG29dZ~;7Dmc4$%TpAWGaKF`SPxBI8^0+r>+@J3+ z^O(8<0=)&K>}oWBJ(WSjFKsAyMq?j|Zq!Cf`f|KZzz_rS{on^jl@BSOZTm4g`#Ok> zL*qzoF+`YyIrF?<9bL@1NqxJ--z8Yb-j0D&gMMCrihaIa5+97-1z1a{58_6#Tcen6 zEfc`NW{Y7C5{&6(VU9}NQ^H5Hgzd96F=*M3GYa0Yi-FLu2TNB^OI43fEIR0tbo z@25J4UC-Gr^ZIuv5-x)Aco$i)Vr za+<@b{*OQ7)SM}-Ow~731cZSqulg+s0S!K*j(#3J=N(&a&jH0LVc0R3dJ|x!(<;aP z^lH11;4JCUz@NmUw2$|?fiOLN_#NUdgvMb6BJ|&(>c_+=uQp{*(n^-_&BCq#N8pnO z#=F0GXj#vok5|b0O5P{DJp^^V@V2JWwx)f88X8!VfrRYc3Sh9RBzWt{-PZb@DXwPN zKZyxZkU)O$oA>Bz0QhXVITLX%%X%c~zO(;XCg@nkj12X47^Hlik${a{TO2<~)s@kb}w`A*qWh?{&Gd@^_M zO9Keq+RLG2L@mV+a8#sh|Fgp8lX5YLzMJ@C-5bY!1!(G^>Bi-fLB%#I7Jz@3VZpg% zkGT_2DRc1P^;&l2=)!wTubXu7@;tRi#jMnMn}Q3hTriQgc)*X6mAJ(h;k~awT~lP? zwwrBvqTbz~0oXR8@wk+Z1RUQ<0d4XSogp4t@^qp<8Ou~%lw1M2P^#r5MdIUR%o3uR z0M9s#ui<_7mCeicOBn^!(Y1XyzJivj3U_-!bS~O?#h6Vc4F(H78F)M0G|~Q_{ni3c z1OrnYKe%8R!xVkd0GIg|U8Y+fs#z-=NZClx(8^jq}**MUN=UKE+$3;v_lG>l$9$g8iqVkU{QJ6T>Z`|L5X+@T9M|iy8(PcO})Xm^VRc zcW*wfK17}GK5oA`84>{DxfeQO$YyaNKzIb-lH6G=Ss4$-75rnwRjp9WH_AURPnX5j z&~lHC#Rl$DxBA+_|A`Usu-9)I;363Gb=q<<*NjAbjFR`tokPimpL(7*2$3F zx(;enW9f#=qBNy!vsvP7`s`%C-l|EdMRKzvufitK)1n(Tf7|}ENC;s6Q;~mihgFx} zkdio6gXf0l`<Bl>l!xhAs|w>CLV7-!IZCjR2h}Ix zcQf-Iet)0$JJ(!?bJpH_?R(v!r2UvxxFmK^HP)h!Ftcd=@B5jcGl0QL*Fmp}^h@IQ zhm@W4rBOhGzKRGu=x80AU)v5LyIvIwhM`@BM3p6~34n5ASG`w1h9J%$iii&prz<{R zEWZV#;9b={JX#rSRrPia3CM7e6)|~AA9VlMBIks_5@DTj#O^16m$;aWny&;SjrB{> zYPBTZ-xh9KnnLLUWsLb)cIC3FINoYJ_w7J<@#+U$y2|wLaC0OUy4qH0P_6exk+Jx@ z=kUYPN(&{QQ7>?D1JHewBB=&To&Z2UggykJdVtB@T2)mQUsVr)+!}+vcFS$PA6#8# zKP6UETO2X%e;Qk8kmChup4~-7J=*Qq91=$H`>A@L!^(t^Xc;yfFX#02Z{e@?eA85g z#9jYyPs75u%&uw=3i$&OwO?#{_9;6N%eRkk`2!XDV-9NiKK7Pm5>)>~Rt9koC>YsU zXuUh9N9?Oy^`bBl~>4qjhz(+ofUTR&asmd!_Wh~g8# zlX{=N@2KJ#HdiBBLVWy_P!cYt^*LtfqxG0SkkFSK;yHI+Ywv&sGRn+3iLWhSz6YRx z^e>nDJCyM0Qxb(}(W9ob&5>*cb*uZGGSPnvXq^Cz;o;A4;MNM5SHM}vN`}t+I7`<( zq{t;JXrz&NkZbv&Fyd;;&sE|%f>9{uW83r{7I*R6ZS6UP)7`?Qq3&@n77*#o=ru-n4Du#z;zzq6W4a#RR zh?Rp%*Ic@^jMj(%Y^1*g6UfhJqGgziKjGL3sVxT{R5Dan@&=6atQ;z(=Bu2G!7?&C zq~=Sj2fo1&)@)xRg|CKk)sTAWVIk90Luq;>s1KQ4)FllH96>Y}cNBAP9r@WB-=+X%@cL8lP>?hCuIV&;!#*-rl``cFvjPpnyqLYjLIgJ79iOr zLm>NW0f^L{nHXvYTyf*Y5h8>efHZ-!MLMk92ChU^THvvf*_}#L*bReupqTdY243b!+j)aPMT}MF* zVKv4c8}a!&XJ)EjLQg|1S#j&b$NoDJ(0%dg<@d7#B*y>?qX~}~xc+-28WPYZ49Hok zKU`?6jD%fbSRN+BKK{UczLUQ1lXI`7UGO*valg5H+j@GH1PryBiRezNq~Vvr zRCxba2K>e-vila44qf;?)==2Q=u?_&EoDNDYTynPaQX~WPDnaB=ra)XVTqp1fj6Ls zOrwPxLFs-?c)FEy*nU=tjtw$GyuyCx0`&U#wPLc7)-`-K$bA2L3k>iG%qZqke*ubk zP*>Dom)GrjP0=Hn6xdn2_=T-aECb6gq8TOG+N$P-y=vLg>J@;YAD^VHUVC-7&Xz$| z;cO)>x4YR95cu_w&{S`=!@pYFrvl3b7+&TAGcT6FCkga;uU4<-(AY>MGi(DNb8r#e%xu}x!6mt@&6=#jc z@YC-`gc>R5zN$WoNUt5%!i9{6^VQRp0wsJWq5m47emo$EtVe1TC7n65oTBG5KR6(a zO~xkrGT33C%DoMYwyc~mgH7P0RXGNVn!5q!il)}aL1WZvu+_t+1LJ^JT|xtKtI-@d z@Z$DLFQDH8h9X^t9;*ZBej?Eo7a;O_Foh~1$t0q#L?ntrzY}tD39q`nsnYaV(2fau zvc8oo7U(_shx<3QJL>p15AoBPia#lXA+h?5#cfyB#^>b&w!F4t|Lx4ANISGNSxfKu z%^FoY)I;p5Od~;bAoM41FD3KOXg$0CSco-$#msQ6|1V_4D@L#Ve0qvhb6aw1)POUuv$1; z`9kl%SFnQa37A&Mc<`^9{|=F_l1>VeJFDtCGwNNfn$aLR z%kX&Qwymhwmy$xC##z#}TSQidZO)%3^D~=L|A|IkjU0eP-L@tcQ*WSe$HM=d9EtXw zJ1aUROOl8F`$084OU46-6u=Vf4xb+s5WDtt z1?{B&f>!S)WjJjO;%q?zUED8P-@crN_w;p}jY0__pItrwtFD-DZNO2d{$Jfjqh@G& zvzt~5yM{9&EywE^(L!Kj5q<+qfj*TcAjLIz;C5(o<~IGgYKt!q1o2p1S41M}yM%@? zjoToUyw83a|5pM0;z+qbDAuLOu6!_GhQx>P4aFFm{ARG&i9P3Yq!euA3=N1vHw3+f zX-J*al|l)TNg#st7`~!ze{1pg%i{?Q{7%#d6gAO&Q5suD%mr_?{cL6Xd&37m#x zHuH7ShRBo=eo9m_^DWPsa6uu^s_b;!xi&P(Fj(zFs2SVjI#0_fxn13g^jlE}sq!!X zDwBf{oD?Uj7-et@FbSKP_#8vFUkQBth!K|=pyCFI(gH1ioCvXzFhr)sJ zwdhB@2HF(t8t71_mHk#k#SZBS*E#dVt^MO;O48G2G=VJo@_!L3`6}YG`;M|kVr_o7 z0$2xkKaiB3&nqtU&e=Xq18>jO+S5#gHQsEdC@qi%E6-)ZNj}BD$y1pzCbSYkoL!>7 z>-^u#<3fph{yEFCM>YxkA_N_;{3_Z!F_A||IeT9|g5uq=KQQx`R3e)P@XBRzIL5;p z;x;gZ z(+4ynvtiwb-oM_!<7s?lddrU!5BWqEL8Pizpi0ruo7CwD-`W@{m;c|DvIU(2*ydw% zF}4TM9d7Aa@lyV_gMR5%zewb>h*;uBuawM8@H-IkfYUzY$}` zyQIDXqkrn+_-pCkcTn|*o%Zf$_QMEWu3q)V`J|X^W0HYuQlNlwIVID!G!6#4E~?~D z(pn&$5-lBZzlAJlO=EzJCdq^9vqr6|%kpd>I=RV@(rirZ(pBewyCj$v?~(7>6Otf2 zLXrhSqCi|zZ%Jwntzp78>ot_y2^4BRb)oXP9U2^={K?^d?{3rgx--OckNsIh?gPg- z^VqHJe_xc4{xdM4rhmk)d}^eO57rlyM0K zW)~(XPs!5!K7fv!_Ghb$bpCRKDMekKx6L(1@bWUB7mg3Aq3ul9WLWgP{IAx4dr=&E z6+Xv|F=c@)rlcZ`8Y~B`oBcDuhp)H_(}4(?GxIgON%4ZR6(Vssn~tSxKlBnLf*{Y4 z+N{CHlSKZ*dgO@x@2o7YKmNC$z-U28PtoR$B`k_Zc&C2exg~-Zp$Km`z*}B{eB>F0 z$&+3X3$@cVu;a~6*xjyG*=B#gw?5z(wsamngxwL%+vo=UyGjrQ!Yq4R9666v>grL{ zT6B4FuNiC`_HP)I<&1g?bGKOOXFO@I?TU>bi};-;WMQyVBW&QBB4R zULOJ&Io2OgFg+?&Qo(}*Tn3q@iw#JV8#;NJ`~U&W1zm>!YlOP!hd*`&<6FiR9Sg{; zvFFif#AHa;TX@OBeAxbYfu8h$$~L%MNhlE7zjVRvk?0UIFrqb8u$u`UU4irOTN0rl zc^*`ggdoI=-%rh8lM7z|uz3BjhUE^>7epDcUj&zrAAD%%0nr_1GWet;s4t-J-X&du z@pQBUh$TnB2hSScT{rTN|6shc``<1%`~m$B3b&pn)HAqQWmtj&FQ^T;0JPcT@SC*3 zBvVEN-XVCK9e`ha)xO;wK}lZrq--1!Q3ff5QyL^mqUUDr(2TViB_Wwk{p)T>kzDZc zRA*!ml_OzG_Nc2vEquaAKT-NH@cMYl4jG@EG%u6F0JRzF2jfwEdnkhsb&PLN-Yb@! z)_mdWv?snTE~EcW#S`@4ymN{B<4#W*i_gN$3{ki~7PGNT)4raHx?-Md&gZW!M(emI;vy`PjF9I9gnJ7bw3g}Nc;a6MJg=~UmKo) zc6gf-Es|>Ez?b*Vf1+s9BtmHa%sh}~XU25bDU}?SJMU=bv%^|Mz_=$@tgv##8XC=o za=9RgEVbzFo#?+E=qm`F<=(3-*vEn4a|ik|9{Rz1V-O?CQ>8bNpY>RBP542e7m>;p z2oIa762s7j-$8Kv?}dKqk~_yMop&TpuP4?2^=2KClA9atqeyYm$2`a;K3|vD!XnnW zs6j&SI|4dLRcyI1zk#Eik8(a?G&t|9hP0;gP~?Hl%}+b=>4&umO|c}U#Qi4U{qHD_ zgrW5N(%t7?r%AaDi)CX=;!U`fhIiv;M7@&Y0SOzh05;?>q>YcL7WP3Qbv$)^N#I-J zQ50R{f2%Mi5{B;0rGl^o#o@xL&KOWmDVh0}>m1hR0g}~5^++$ZswysKI5^l9)OFHf z4KC}9!j$a904xsw7|kY+IH3mef+vSI{Xv?(6mOcbqXNNPE8G69PceR-HwmVLh0dY_ zCg#>pv^G0l{B{eP81SkRYDZV8ifGVr>SIXLbyEq9j{$`;bn&xwBbp=E^-o8FQJUwJ?Cc;7nMFBpx zFk|PHD#hME5h@Hu1y7RkBo|-l3&g_58JnPZ_QE$-V|gCZrQ*!k;``B#Vd(>0e8wN^JAc6ag|%UT-( zMZwwx#Ic`h2eoYP+5)Z93EpfPIHXXORBb&ekwNSkI#_?eVdFpn3*P&72Poe2K0yh{ zIvb=5_%wjN&JxV@(*3Z0D@Of6APR_Z7zVK{RhUW1c9^osODgn@q8z7XCG5;fQ^}Hl z#KD(T1w3*n(9j|ydjU`3qeqd2)}=_3YG0lPknO->bC6^jI`G`rjx2TP360da0#X|aO~5IwOz~ud9}QeZvz;5{c+uV9ENfqgd z8pZ}V`;^D@K#5Fi(HjGEh!7e|6$iJ~CaqZ7w#@zSjO^!a)NL2rBb~s`-!Be~KA!N* z1FyCUGo!Y(;z=3tF5VV|$rl|IHHlIcGh3xBm0|b8#u}vrkfI z0#2JMh#R1tIII$?7d@<7n+IC5JvHGKlvccFyVGRZOKI0b;=Q&@+?8LiEk3`gdXnfd z#dZ6w@Cfg|M|QOj{xZz z0Bv~M&@i<*z0;hzrQg*gc8%AF9oAFRa<|mu0miMc&P9O#c=Q-a?3p5=<~dNl9Ce)! zdFX{sXYK=6Fc*tdhp(|y6;s6gJviNwD8jx60udiX`nFKTGk> zIZr!%?X*o2y7_ye4L@!8Qz@cjZw;jz<8@K5V}1pKWi8 z*kKsKQI>Fp5z_nqVE!W6yD%m)Rk{)JCbvXl#yC_{qNk>wCib#i0ao-Vn2iuuJ&xnW zUZg=xw8B|4Hp&5vGCU?eb#DfgBc0aU_&ESvc*uJVv&f&u09fQOaTh$Q@C zGui?~QmUT`=(BrAxoK|vCN*)3IM4a`@{FWL2L`n``lm(FAl z0p!BOEFyvbUe_$pSDs$_rEMTS#*$2Ukef{sJcz}q zyWny|Z?jtRIvY3yMuO+huNnO=zdBereW4 zUeDJwe7EwV*8a6)5_U-g5(Fg>d&f&xYvpGVnUE;W`v@;!;0AG9aG9zH57dvu6c%n44QTq zicQ=ASl=?USNhzmpaKkxbu3b~Wd6cRQhz^E^)pWnGB?@jS-biTVmF|7KAfiHO&4c* z@%oRI65CYC7R^-Vk;c?dZ<477L*}WLE0d`_Cw2AXLc%{B6j{_nR%Uq8Z|N~W{_&c< z(#J(ba{D6Rwsqp|U7n>(H5OY-jBg?9)Z2#6Y1fR}>Pi@I3Dy04YU}t!p!dzlW$t0B z)1U*uo93E#YdNEI1HuEhcGOg-Y|ID{mT}!EvWonz*_JBhbl{i4I9l{4mE<%}8e64Z zkORSAg$vD|YV7>zO_jW$-$KJGkz@D&)`c#Q0bjtjX?o`7YH=V4r-?py|UpufN zJ_b$nk;8~u-=w)WpNTeK-k*iMD4T{BKNt@=3|mL-z4W3U5*x;u_3b-I`Hf}cnxfNu zB-jM$u{CV$i04S&sj=0~wyd02;E6I`j(eka5{>)_e0dXhc)g!XJP>?x64`B`A{iiC zDVo57-Ha;~w7rHBY)>W#)%5Bl+V*0hb;;MFDP$o+LC&c9CNW6x43p|R2&c^w=@<>K zZsL^CgpkGz6my$nKEu^?`#7_&2Us!Ue-k9UJv2tUUH1992v-N`E`OlzGqSc;j%|(_ zebX5YA*186GGJ|MdWje-=6B8;)YI5v(;2_tOPWqbl@)n4TQimK&vvjlbV24+&}#f! z`+!5ErZ1i&^{_9Yd9RPSsgU%tT2!x~UbwLpSNuFmJ;E8lF5J_fnxIx`Ne&av|(^+H-Y4f1{I7bKH#UkJu~ylLOPDP<#Hu(mtv z`CISzx8lY6WF62WF91ohyFS;Q)D1)4hfeRRr-(?HeXkYP1Rwv08H!NZ*rr8lsj382 z4>U=P9QcBqBJFD(+PE%0P{m0j1|idRII+aFq^oA30S!FWqWtGZ(=w_J`LeY8>gYDT z(cTi^#JzC3fmcgGG_xs+OLp)jQncTN+Plnps<@PmfF7?;3inP-@a6+C1?mO9=yFqM z1}V}FjWe}N)Ly2;Tbq{QVq?J}Z?QeO+Ao)X?dEPHE2&WNg#xf+BzN*s>`q?`zZ058 z$7Tq*R_GLXd}I#_IVWzRpqOj%l^*tR5m*!G!@4Y=VTw7wXN1^L6k{4#vbY14MG^2y z66Wkc(n3d^^@9-OYEO-eiG-09A0DX+3&6=gl^T|#+GAI;RYz}-9ujMq5BIDyRT^{O zpntDptNvod-g288Wz=uQKSOiAVcdmUr1v6<$?R?&b78l>v@Y_a*xDoqfIF%My^90F z!H1jAN0kqO!>{mem83OMPWh&lKcovnR?P#(CkTYbp=QLr&M5T9fL$v%E2;VV#!Lnh z=ym8Z(TpGig#!A*;M{(MwDt5Y8z}UOF$H{rPY=qUU>Z@>-!i2=j)dNK8Uj~GyPeV8 z@?D{~h5m0hAFd$17i7>J>$&P$bf(>hZ%B-{7m-9;?ZZLDFOM3B5pAp`M=d?|*nc-0 zar4A?wOcM!v}duiI5}IcOezkEhgE7?)5m4{o|@6-3pFUbV=LSD zx)bZOL79o~BOS1C2h+4P8Yqc%0mST7OSfQgrVX1MCJE=cWG6bFX9xr&2S~dyuc7ukD62^BdF5aNh(QF=MoEsG1E8ePP%UTCOHb$Q|MFOL*`fOIHbRwPD-w(<{mLdn%1o1d$ev#|}4PTA=n6k=KSAqel$~iQ&!=AR>_E8yvQvQwMIp2TG1|2%j}Bbt|_-{}gL54i)~^=iaT5 z?0YGW))4)s#PJTgA!Ld=c<~xF$yAaG$CbQ`iv}Y%3V1LQ70~Zd)Tw0+OQ`v`ZWKJ} zdwNfZbBImK!`+qJSiZU&;7>_%f0Yx-ae@VkfCeDSi=I;1lP@SorfUuG18C_KIS; zJNP{r4I(&D9lltcBqWf{iBH=mfd!y)rQ`rHQr`B%m)Ep}2+MwM@JF2BVV2ZvQc!fJ zpd5F{Z4^37)HyW^M6%3kjH%Xf;}utd{N@frB>M>&NSLh(1i;c4`ka$r-+`KhfN*nG zSZJ3=60T%SdX?erB@l2$&$haxAK`sxe4#9~KOO2dN)dbQ2CnmkHp@%q`40N`)OmB> z+6!%_+BeiJ+zNb_dw@jC9Y0E{9&>mf;vMgmooL|r4BTKMKD6;=4RmO3pdDlH5+4XX zlR&;XDfuXXJ^LBG!%TzA9swj3SQv`%X|3Cfy)ECbw80X|$RHe-08Hg3LHZMQ8G7fa zxTHtXQTHXh=Gy|b=V9$a9j2WIC!AK`Cw%sEo&2^BUqc`P||8^6HI3+S$CwwL=OZ*O&S*uAwj4TNfNkCL~f0Gl* zaw1FE^XH8guMEtWk>+}31{tr|8lCZ0MO*nyV)fCu=XhDH$dGT(`eqnOruiJRY*%Oy7 zkF6hDl$nZ*sga`;AH zqqsUe#`ISG+&}<@jYp16=qE({tAODuwB-(J4McRE|JwDqP`4Ry(!YZa+~iTIheIWo zZ}*+5gs_|LhHdRO`Ypx|CxI#NE@S4SYtDf+c|(Q>Piu!Zh4S>i!Js6MM-t`@mY4(=T4-O($#e*4c@nH1+151p2#j4(V!Nx`@AYBxZt!Kzl4?9=tEDwI{~6%@j@tp~T3omW%U4l>;a&mTVY z1klhV8`CjmDE7SAj{2ZplXEr8We#=*pyG2;>zF>V9Zw{NG%(O**>LPvtIWzp=r&hSQT218e0e^8r*V>c%Ch8(<@Dv<#A{IVhfH2uj!MQ0xA1jBA$@jI@RZEGMmBP_9IwOr!Ce^9DIr=cFrGt|{uBZ$-9=4kk!Xb99 z${))R$#)C&3{lwp(d^meV8FXiW(j z_*KY0?_-&=_l~{iyZ-tdeni}~&d*-u9c^2uay@n_%`=>DoFqdT;N-M$@g@w6Z>NjS zW=N}I*5U7h+>qM|8<0WF6!9Zy)bw3(cqDGXuI;uYms33i6iB1cL!gl@P%# zNrB9&f&{UY9tK7I=zS%P2Yc7K@~E^_E>b9VkQZIsE18;>q1-+1Ufzp36(9Mob3a+3 zWp{92Xm^n1W-#L?wBU+wm2=b0f_L@8ThP)1B0<#ugp%lB*rf~QC}Ya1Elpwxl80np zJH)s2mtvWw?n(~gh)MMju77#zZ6)O^0-9rK0q?{msN5%Ma=6{TAQtkfy^!m^uKlS&qpK}kH10Pg0T8pS!ececK&>z0dASe5 zRSrhdgXvvBmdzrS?sY2?^Zgp)>ZTu43l4$YYn7rU%3CZKv!S~Z|34ds8>P=`6bXd7 zpm(!UNVE#@Jc9>Q&4WayrRxL z2%DMFxQp82AtI2^)=dtH&Nn^~()w}~ZJaBx{+F|{-{MRRKmp7Qr+x)P95ZxqrXbFx zm!5i-D#m{}nSUOTjw`n%uG&Fu7_u`h7n`JB z#YA%=`-atr@}}o?wWUHE9uDSeIs!zbmkHoZ&di7D8-Dq+R&UX90NUfK;j-;6ba;lKRj4b`y!)Q-V!Pj09nh+`cvH01vYXI)8LTgUq(!1VIelbW8yok{ z)TEDi=scZqX#U_zmI=pcA#YoVwTP6&l$B)$YrQo-o>0Z*>rf|GjI7xxDMG8dn-R*VC!@NS$%ABp@uIK3P;N)QqDfx&p3u0VcKkzom~36*aNWkxe7(rr9Q#2hX18@4 z;F_^(e$6%IVETQEY{}RN4M~KpK5F07AW%5{Deg4=j+xcqLnENArHnCpnY(w~yl_2) z$hTf-$(G(4#S{v4qgJ{%rJ(&*6o2Nkg9&xp`!Hu8k*n1hQF7$NES$wW4KCB`S8Y*2 zX0)Acz+Lhh9cZ|Ne3Dyq4?b)~zz+d!^l`7|uF>m1U67b-WzW>zmpE{)shbGee&`+T`KB7)G%xMvp*|e|Fj44 zwr{N`@`~!WBBB7!gFIf{%>T+_pXq{*rc~#<9co?4H$G}aAfk`_q^BGA#JJWnFU4W1 zc0u3Gr*eh>%JdaI@XGkQ$nznAt3EJtDHCDN`6kU*k2QC({_lEF-@%*#!aEXJ@(3fn z@7V-$gc`L(Vkc83FR^dzr)ds4`OG3b6ozlAHQ$Ft7?h*ehu6Dj*`T zAzpG=4g@Rd61RE^*mY91=dHifnl03E-49pWP0@12K+9M6Yi)JcJ|Z@H4hM{l>6u$~ z_$ZCq4Ry*rn)T1S3=c2nN}Q?Hyt}SinPxQXf;7v$i}q@dJ_v0#9py|MKVqzpK`b}c zPm`|sK;v*qG=rm;IQJjPNUI#1Tx*2VDI>}=7G{nQ`G(+h*cylA491o4k&UC9n!VgZh>Lei!)PNVAc-PL^a zo8fG(mV9f1A0)sI(S7RT0cwj@Io=UpmYUzZoVB{2Am%i>KZuPN~yD!7HK9hg;8@C_3a}S;iNfkwFkf3a-I2 zPqEI@(`9#WQA!G94fH0YJ4k5d{tLO5_+=21C`<}wq&WHN5OeCmcccy&5at&3?D{z_o-H%4LCe!}HlOK>g8tIN&{nql)Bg)Ydu@2C1#JRfK)1Hu}XVB2P6%toh}ma|VF>B*)%uR6cIF0N?sV zQ@iRj-NNfEIW2{!Sg?a9QA5n;LbgCtyWo9bZ9F%?)dMxxNe7Jvace&dEVXX zHQlrdsRuQs`WuVToul&Plv);Np?U3n9}j=ALZUx1qJf&*pY{ZEOH`-EDs~+sebZfR zmu`~MQj*XA?g#>}q9J%A#|MK9wCKH!Fa2Ukq=GZ5g-X?!R&3~T)y6gTvDYZ-vPZ3h z@MJQ$=aN52s#wv&e#9zp(T3w~eRE z5ePsqdQ6>_WiMqO6*IVVm-hU?Ux285G5j4831Ja^JG+M!x7Xn|J6s1 zjgj|-Rw?-J`JzGX=7P}tUhDlga*w|6hD#yoCwhqni72Eb_-LK#4gE*tWt+|J(Zo=X zsy@p4Rws)e<9fnf(1eP18j`6`w+2f2W(GQ-9-YsF(YuI2JQ`Ue!W@B_FEm zdf_o?{oLc=YGVQ+I{8G!FY!7<^@jJreCqB;DF83QeiF6K;D5e3-AMbp3WWt>47(vh z7>a%bSs*qreW?LkV567ebMWIeE{BIJQNhx#^p;~AqG~IWT7A*olT{zU7R|vT%_C0~ znCBY;PAW~_xLN7g?Mn{+hAqSD45;W5DjY+AuDgxmv+-c`ZL&mpe#dC8@UII*;L@h ze@?H_|B}_s+w;47znS59S3JM!w=&WM7cNB>ommguTDyUcuzt{Mw8x&~4}9et>^g>M8tFpauc;lZK?(q0M-imZgv z4n8boSSQVr8%L^{m?8m15Z3e6YEB!z+fHiuur;%5Gt&Q|Fg@5=sFQ^4)4zYS2N{zRa?SdTcGOBEs)+81Y6Nrn(YFoKYSwbhkzAO)#GDkg~ zerBzQ4uiZaG3i*1!)Zos5Jw#BnJzk7teHojiEd47o=%N!HEJ@NVzc@jIa%7 zm+gx_Hg7Ms?2+5;HN^KNMUe}U-HSHhQm)CX)Hk$yPCcB!nb{VQ)wQi@2UMwdYkou? z5g-}5+*JHZDf#(yVKO|FE`)dQ^1kuCisYoQ;5g_gYx23+koei4XK%9aFs$?Ch`1~= z<>xjqwm@v~5^w?d17?dtA%AP{&pKd&_9Hr7AU}gJOgD({VRD{nZi?N0_LEG_Ko) zmQMX&u2!#FOzZVb%oQDZE_?qV>#g5*`yJxZ6z(l+i_}bL#h@X09P1k~`r`w8=-kD@ zoKW`RcaEfD2BoFXDLEBGlX;XbAlsof|Gc^u!iW&HTrv1HRKM|AQ4L9eyt;L3(e!oL zWafV2?^D~o`AJpf3Qfe((_cK`M!J|g#Jf3n+~%Rz#b0rPj7XhpN_rfGDG>$pSKLOS z0-P5oyMju7N3w5Dz3Z&gJ(7|bqE74%Qooyj zoIWn}Jp5w1aQi~X=y}~5ZVw5~-QCfw4<}-3cwMqyHR<6}=dx9t&+g0b)z*e*%ISYt zktHp%wk!t}xc(50b-U~^sw=aJNJ;izXq*rK zyH)RMj=4ZG_;R4Ayx#bnmW_n!0idR*BCvpQKjA@=xsAQ^oF)63|R%wUHKtp0G{!)4@&WHI$Uv1sZSc$`2ZTv>e@azcvt|meZ4UXi1N{woYFGaae(5q>qme62VyuFMkOn~`22LpInZ@bp!c*fqL2_8n5HS`Edyyil*~}!c0~pDR{J|CzHfj>fgb6LmskzufQZckt-P+!bTPR!??^)Dw zP{YNtwTTDr)oXnY{F;)*`YEDD#`)c&gMA9OWAcAk9%ZNx(@j1TuLO%oOn0Zbz1(?3 z@MvD`Vl4q2MIn#8$+k=*y@DBpm+G1HBKjXjnDiy-vh5xRRpRf_NU1 z^i*9LH!N`g-s!CNs`An~iwn)}N({G+IOwP*Zr)4PMluLKHU3z3X~=au?mV^-%U)J0 z>KLoOHgx$T;^fZmOiu)L*ZXe`o~f|=sa%PFg=9A?u7uVK6}03_P^^8bb@ERf>-&nC zC6~XOJ!TQvKAd0fNbF{sAeJqa78O~7d!l578q~Z==|QLy&1CX0H=QFr^tBgyfmU|; zFJ1PSH#}FLgDBXRORCDy`jD4@fX&Zv-;EEWqq`@T?NiMi{A{rAS*3dr53 z--*mbw&b{wU$v8~*WFwp=mv|uUl`^*NPAJy%yZX@P1T!d52G#z$l~}uX6s&%$8{l< z*Nk>Q3tiZUEG*a9FK(ZqPG*2@K9^eaFy+A0h;% z74CQhkSx_zo-y3RXS0YImQv8H&ljSPs?^~@i!`=n|R_#fV_*faP zhs_~b5{%>&BnZP($P!{wNsOA*?MoPRID_BPL%!oh*}TeC;r3>x*!Y8ipRbZ$Js=ME zQ~pH^S~adIANMZ%8N|Hq=;4evS%?r@9QbjoT5H&r5hrxM(cWt+-kSn?R#JCRoAbqVvbp#lF(9Z;0fiuvdqA3m|K>$vwYcHH`kH$Iigby}uWy?QzDL?1Gxaqsi zuLuZ#_SWpfSw%SDa=`JlFI1r4lxOR|9hhq#ASS(!505sYW~K6J@n!`|y!;`=&uU*c zpR4fJQwUiz!?{C0dd;aO-hUoUD>u00*|D8y`R>C7^2Y6D_2YiADZZTjU@h$kE}PLA zRd%)UrVmpq9{?w9Rk3`{(UFx#vLWt!DM&nqv~I<@en3`aK0bvk;gl)eS~2$>%=!cs zX|>gA;;#Hql~HWD^?rlv?g@ud7u_Z36I(^yaoARa3C{L-VQeEXQ>O618)XemzxTg8 z9>_OfOZrg3iuYiLEMM1xmP$~R^t`gR9@?D9&e3KU0{t-}c^s-dtK7(CoZDCY)OTS! zQto%LxPRM`s^RgTZsjU=?WdVo)rEM!Cdi)h0U6<`%3dSx>mY|7lzL!n6%3U`=VjVw z_%6!_V*gse-8)huY*)u-uLJf<1WDYgDe-ncnXAoD`_gAGO=tn~z7%ceI&@%Y{5osq zpm#gpYchfa>{{oA;mxF@&^`;(=8c(38>O@>No2mE)JDN8w*P5Hgr0PFUw); zX!U-UwW)C*RT$tT#!LkUP%+mtB!gjY`g@AYcL_)+%A)0z?s4L?JVFcP@>a(P_iH`-s9JS z6dT#G8ps6NQsYJM=CCGdUQ1{`zWP-S(rSRFBj?qPsx6q#H;g{)ydU3md@(>sRrqpb zJ{Yogp`Ku+_D0pax%JHMThebtm|L%CZuWcsc5`ajqbRA_+D~Q7Y07hr0ug123Svdi z_$}u_j;Z#nK+m;28epaO;652x0OoHJg(^Su^h0R(Jdd9zf8WnR(22k~JWe@l9X3Ya z*3O@Z;@FZHI!CJ?$Ks5YW%~yByl3ZbP;9;-BME(mIic=zN+@L76+ErT?y-tf>pIi8 zD2soWW%%M0$8CRByoRgIU%l2bG=XKKJZG|-b0GR!Nbu{xiBGir)7u=kI2%}6p}gg9 zuSY)x1wl10r2mTKmvQUj4q?UF^B2$@Sq2h1@b0W)Ak;@Tmtn|&>Q0`QGG@1nwV9b} z@8#8?+ASA;rvAmDbM1XR+Uor1l*mThoBNW0rq4HYG3BDMLEqTfZ+MYq7oLbR5XFdP z8iu~n-6n?QIQLh-7#5z|FHx&@e7H(;{$@SKdEs4ax3CGn*Ii2ihg~1pZSGT`w{>Y| zC{N$qP$zdGo+8WM;(F9_8~#@dAYofc!ZHoOq_dyv9G?(0T>WI#o(YB?PC-HaWjj-s zmc3sp-T%YiV(;g?^#TDUUU!1E>*=jws(*UI$+sS{IFGM*e&Yt1{hULd5}0}XsmvpJ zT^!cL%?A=*YsRx8+)j;N@%-{X8m=6hFOw+tY9d>8fBts1UOWkYY1Rdi?uclV0cB=u z-!9RHN$0beo11e_KKfs#%)6Ppd6#-}wiYQbh?-yj;QsbVbuZGjM2deJD)FLUuXiXI z`gMBJZRSzfa_cj@;}!WDt)BDYs|fL#3a0FO=M=S*xh7i=Yr!H7yvaZed7%2(hHtVV zxx_0xUNL1%9kTEPh_WrWFW)a*Vrw5r{)Nu_F?$hB?ZiyQWvw2wrokdE0x9-QODI0V zi{9Y+;LPVVgw(mp<@&&+fqn~h^V6xFtcsMTLMosnB7+?R0^&;(dVKu96om%5G`|CH z0tKzG zwGgL2?{lvXFabfFqWrBdeX(Wmo)<%bc0%uQ0m{0om?W zT%(pDTULET45zW1&3YX;Z5ddiOp|b z`zsYKH#Z>3g*bHeGLe*vXT*%F%7wbLh_DUlY_z7s~fhSadCRZ93blr|d z9Tq4T*&NyXX^m{t{vr9lxr=SMIHNLN`STtXR47u-%^t$Yi2yKW9+05^!{Ya*^XiJd22a}yCM@r=j%~r-c zI${_ARvcSAmcmJ0x_ zG(}lC6167Bp`8>z6OEAl5`Cl?!Qb+dy|QM*{ImzR&+R*lKSbtP<`8{T)Zs2WfVI;K zXXAcFm*{vGnF?yWJ1$ufP4t>cNFk$|6lR&U9tCNGiZY9f^VLbuwKs!i^+^|-ZIys~ zpfQ@}MEIGfGCkZx)3AC0o6IHGdWp7rk`d=CM>!4|Xd5RCbi}Mc3Lb1HO$AIi4*^Q- zRlj7+i4s3D>|q_Sg>-qOfR8eP);@s$;Nkm5=*GEovi0IhF0}l1f$zP%#S=eI+WN_y ze&1s+zEShy%sAB%ptXO=BAS_5H5g0XrFnPUB&02s{Js>_!LdfPN${0(Od?DEVA?Hl zZ`|I!Z_akQY^J%umaYOrD$H(_AOvduTX3opL2Gxs&85IS&4Y~M{*iS!>kn2Qy z)*`?jmmJ*lK_p`(+gB-**=zNFRt$KXksx~!st%fe=4wLxTh9-#>{xa;5zBsTmFo`B zc$nG}&gsqDO*P}-UkY$ZHnj1m&vkVbrxJ4wa7)kx6v%PCYq(-Nzh!4Cn4%xkF$+W6 zK{ZYREPsV34{AQ8!zSz@d$}39B>S2nJP9?nYYqD@!8gL`LBa{hUkh(dnQd-ibaEn(^ds&uK>dmBo)OT%fjW+p=I1~)ma8rOE` zS}D=LzgYpIO}+X%a*>6u`n>vy_r5DL_Wd2Au7C)z9(YGWleRi7@G>YDpLti(l3g}V zxZJeym&)pX-z4TIpUS&hdvt~1!Hw$=OQMshdbzjw!ISg>8k77_^FXIy$!wF14GnVs zyqgmE;v_;Dxac*-&;v3YkO`(&>18BEq_YIVLG!|Fn%&3a;bO`xJbSDRgHAqat6*xp zeu8iHKt=-as(z##*Xr)H9tOyUsw_C&+(*2P$UE4t9ExyB!KUVPH9s2qJN{yX=xmqVvN)0nZOfT1#8pX^jM&y-oqNsr7yN@2@fDen%aWA>=L_(2 zaHgRWC$OSE%Xbia0BUk~E@c~b8J!MbSN8sr65B9^w?i?dC)MB>k{1sAIn`y2IEU zAGI<1Az&}x3Q8;Ui1zdrK-jvAGI(5FB;; zT`@)Aop!za_Ue6OZS(}C>@L9;Qi;-B^UP-hj|n;Y25>kh6P{X8`eh`pJ;Fld)j`!C z1f$%jiddYrRt7NU6aw6{EgxwPGSo%_P&PmPB_@8_x5O z)CfhNBHFvBIe$jNm;)4{V}?)%a3?W~&ER#Zb!ZrO5)Bs3KkX;7Q_PF#cJE>|B|4$wEDk!M!x&uV%V zc5U7Ec;#r_7guO)a38f$>0-w6_u**%vsaFg`m498VevWjg=_*HLB9W?y9TzUD1?bh z9u$C=A2{oq4550m%m*{}@VlqVJ(w;_&J3x?(Sdd-1OJ}f1DvarB`%v#2rgN?W-L{2 zt}fBJ@cS@3IB~6;Y$kHV@UvNq4oePRy8%*yoFxlb!*@tfvbFkU5$)p=UKFr`RuOPR z;RcE_S4)cvUG@o^j|jVC<6Jc|da#U-Jy1Ls6{c+q<=WM+$(F-zNKcn96Z7Bj!t<3D?B8}&Kra>>om+r}WTq+_BI`-ZY#EBI zU|!rX&F1<1?fG_ZaFy+hXTG4J)x^i#1&UFCLH{49SJW_+-;!B-c8@Cd`UapWYj8CF z`yGH@rI=i4)}0wz!~3tudE2m5a>%!kbH7E~!(|gI`(!GgCg6sUP|M0Y*duP)gqHZp zE1DwYe3We>t$L(M){o!ZJIfAJg#5dv)F`}sCcb#*|GJ-ct>Hwj-Y_zL&R9pOdY?xR z3Ku_`?=GS%{(=-Gq~_4R4Y3!Dy9w)b$@}XeH!+h^9@gLM1I+(j4cX+U1-|ykpSd{s ztT#stAs``0%ypX{uRjEZ8x?CwyevM<>&38C$XMpj&Mz-likk>ub29ydoDRIupEths zxqE&dqS2`(V%*~MEXn~ctT{+mjHMQAef zg6^L1O#=5{5Q(>cu9lI_=XAbwy#LzUIrO(c9i5+gYXU(1ber&J>g!P>&#B0$01kj$ zAp3}12C9}(*1nJCwwgTs2X^tIaUDG6WE>F5T7nf(TE>p=v&Y`R8Isz$O(KnG0jlmg zknmG;Bm^SU++rFcnbDtgd)vrbQU z&>njAj3Tma^Xt_}TZ!3660M22exbNtTVNmb`(5Lf?&<7;L7i1F_=RIFO@nXJhUEhq zPPiM}t>peMvcD3Xv$zHUG0xEnnZ$r56S(cX;`tPW96~|aiF~r^c?h5IB;uck{%``3 z)oQP=S8CGyyZ1<5Hmh_zT5x^6gH-+A9|@~=Lj;GiiJy~DNzE8AhF`Y?@|)amn?s3# z2Hgf819e;7&Lnn&h`+fdAWREI`tLnN<$BLFrp#MaV5AK<$q<|)yB94Q#tBC zC&%%b9{ccVs!acZ&QT9I1l5vFf+i>ZasBtx+(mLEe0|d7nR~st-{3p0gKpq>l8OGs z$6eqU7s(&$r<`@vF5Y`?p*2sk4k?-4y6CiW)D-w7pIfI!^?Oeo>SRpY4p@+X3-LE6 zqs#v6sMmAe_g;xJo$p$&zB%mP&Uuth>wa=HhgqOu+dTBNOXNd1Uq{(yGz$CL@`df& zV@ir?#;wp;WE)(IvOg!Vo=3ERNt()9hkrTsXd#1GuC{NLA7@Zbrf&*;sDV^ky)6u80rf z++}+&UAs4B5*VQ(aXnw16Gn)fgiWA=?BOzZfOzp?oyiqNHq)r#Gc@#u_kxD|$ab8h znOXzvZ3*oLQ~~AK73Dz?%f`QU z7G%FKeM{zDFR|P&#`3syx4zuZV?8$KG=>Xev6CeJqt{v(-gM0lQ4IR;ZO>>k-ou`!l2Dpwi55s3_wWFy$Zw?m^3?yNn1YaP|`!K7_JOqgwUg zp~uW#rRic48Ly6UIANze$kw3dVlwP#3!T5({b%u1geY02?(^Td$But1c^r1edy-sy z-W|mj1I2j#II8c9vky*kSu?5?-a*9%2HcBb--_a{=zcdF9VLSAt9x=i`tR`6{SU0w zMs+97-#92MgNti6pnc`H(oHOvq|=rLw-;fmm&~`aqOu5GX*8m;_)!!vx<49dU*JRk z^CD?YPC?NP#WCSz_y`*490!;Sc)f1y$`KwcM@B(634uybDYfE!~LZ(4r ztO8wo&~xby-S%@3%C@dTV6#i;adufm7Og^uC0H`0+rSSo@S~GJI+%f!09A^sPgkBC z^pK&g`M~I_0>X#89!xmZ63v_f)I#oPbJgX6BOKs&t|_pCf4wcFsI_DD_o~E0N8|6m z$79oLW}Agi*CNyWP0qg^DkPj=X*&FQIsM1J^NisSePnMU!_ftQ6=Sr+42eJbI3(E^e);stV~*B z{d;-(A_rnRRqTI0A=wdA?;MT%J!M=*e|)$`hj9a(y4;#2OUr%75nGH}r|8m9_a5t) zlf1xOh`&t&OpzY5QhNnvx5&e{gU$8YFpz-!zYnFPI@K!Pn;QrfLCyDNHgVZ!81tJ~ zJe!#b8z>`E%fa#=EM^sl*C=|}A?&_#zIvSS8FK~%+XnuS{8GI2c*vs+N|#V@@Vc3h zBIVT1jz%PwSqMJ7339B&v?@Zo)t6zle zY-F@}D%wfNwL)HhT%s?(->zVtnAuQYIshQ=3JL=kY> z15+5T`eD&W$VBHDRwUVKw{0Lac@+%IX*slC?+IIa3IexJq8tdHy8Qm8MCR^(b!=s3 zwk8n#b!stuyJ~4{ttZG;9n6$Y9LuLDY9`gNpvk{<=-&R^SbL}usK*1Ri|T=l)3O>g zg{3is(};Il`qKu%lt;sh^Opy#7R_;vd;xl_=L%*^o;`XYA=7 zK+0KP1hR_D>R-3~uy7=8szt#zUKH2eOgvm{s&h3@W&iYTA2d7#jU{co6yf43KWMMC zdbXf_<6CGotFTm-#6!Ne2;CZoTZ<2r@b+HFZtk3;Wbt2)QI8u*I%cb*?a8EvM?G^_ zvpk9(`M8FtBM*xS@U`y4yehw1%#$G*(y?L7P8NNKM>n)9+eMXUlS-kS- z;tEGhqOL|2_%1rI{bB|7Jlv$T>gGqGG<*WW^1tawn&4uE{Zt#BRQRRwMF1O|AVIVPCq1R z@25d4w)HlH(n!ATo^1{a!KKrBr0c=n zh(m5Z#9B+FyG5F77C9*VLKh8XfM)wv3k_ApfwKZ??-^fbm$s9UQ{~Um3R(|u3h*Wp zIaxx_pR2CPVfLCc^A@guX^Zq~X%&8LEWJ0jE?44eiN_Ncr+jet!}jP`fb|YiKhi?P zWvMd|Weq7o8g6bv_@DY~!_B3yH7U>cr7jys=2HAv0+D(d9Z)Tyto zL+erM)q=KXUyW_it1As3`-A)JCHFi*5GSc=k@M6o&dV>*i!r3D0q>Q#J32z$n( z;=kYaAq66Fv0I3EMMoPY7fAK~{HT3Te)Q@6E!oaD6d))W1K3F}Hw_)<{5x`daKNze zr8k@$M`dehE{$L=qAiP*F}=;zQzr2DwNCuK;7^KAT+goU4|>L0G-)imY>vOQm>7ZO z-Xd{OEwiTPa1knlaef_~kJ1`}(bd@|v#=7;4*4YK z#S0qGb`+%cpKlP-`t>ju7}Yaw(oP?;7`-r;t4>u-QAB;P@=3&7XT}9XW=`DEwB!5l z(SEewz}h1I{iK9-Gs}s(MN*g?`hFiNsP2C12>dv+V5pI`UxKa;crjVe+FAZS0n| z8WEt`k-!o%jY^l)nG$lKijwFHhWIf+*eNN44SU2U``h*EEPn5;jHl~;s~_rE8Y`2Y zp2X#k`6GFr%wQ-&%Vs}eczH{e|DyH6EWzp_l-{`7s!+~}OqFBZK_z%5%^RtCz5`C}Xpv$&=y3EhX< zU{prch(du%sfvr#tViuUyZQR{s2J?iQ$=-n>P$3J#q!uY@@^T`p(kNbu!4^Sm?U;P zCew__Z;}3o1sD_Cuo^UKa!``!js5+mnAXS4-EMb9v49*oL?F9XB{vFsE@Xq~SBQ%8N$iaT5~)JkKb_5RKDe>qH*0Nl#W zbEtPU+k}-Mf96}FLQ?Q}OwHV|py=nW}*GxN1M`WYyg+S*l~EG>x%^A9)c5js{W%O9-((bJ29ywp8^g#g>D zgE?_>d)bRJOL_Ko@wMN$O|SWU-n-shcbB)*Mjp-79H; zHx;mUH16dE#0vd3DIE zhc>wPxKAkM)m;t1XhVT4Z)F**AbfbDtz{gurV$^~pmY6=o1W8PtFyv^0r~DMaCyOr z->ke{H|-I-8M^*Lzj1h9`N+yhw`FV^Vr-3<%N6BZx&Z374;gf&7F)^HMul%bnRYS> zQd2t^6F~uKFK!^+tZY@Zv-Rj*mDO!*xbLawJt#2xOF46@rzGPr7zpFAkkry?wRl|h zSKp^Z9;?R@#(zcgn)@dKcwH0)u1;a=RPS=sh1M5NPVXs=K0lkKvnXq-MWP5*(kpN> zX1)U`KlLHs_}R`?=D44zz4-$8+2Kid{9a3ihJKKmA}Kh~e^2q&WB4dOO4-&v`7k~u zhWQq*r*?LE2`hLMB$Tqsq-VG6H=PMz-J7B_JRr`!g||?ak0?}AKiJIR^iUqVc)+0c|kQ20YIpup4eI-NFL>OnC(eBCI!iR5Id-5{&f*REPp%tBWQ*)-ErMrjdvbk9}&-XaN8y* zkPxMuSp52F0h?o63*FUew^*+#c1DJK)Zqe#C&WlRl$O1AU=EUyD(zM~f?~6>OJz3u z%R+iIb$j$oa1pC#WMlr04tq2XK0foUM``!8KM|1}KWZg13VKr?;0y41O;D zPGLuJ^>r(-7rJW@Rzt5h{l zepcuoDzQ{kInT0Ehdss)rCG^u)km_~3z{7zy=1jagChVdHM0`OaS|YMZt^be&!@BV zb8i|R3$a*4?5{X@uzK?=3KOiN(oz?vKyNETNuhOAL{i!^mAH*7mXI5kd7tK|yZ!mB z?I5}h{a~)h>drU<96i&Qh!|q8eNx;mijKM#i%p9XteV@D)KofJ zDJ7rT60Ez&rG10Cv z-cgPip~QRf&9C{t(qQ-)WgX1NV+puZuot{T=5xz0O}vf23M-a&oH`wrV-$nc!u8E_=Zw1QIB=6JGNC}I=-k?uUhnGJ}TOyVbb4*xjnT)TG77Inxzx6}^7AB<^QY1b7?{U!4 z)Kq;aQ^mKSp7Nj1RAooXc}8Mqj{;0~j6*9#8AY=@u;V>-My(KyqDE}JlY!E7hx&`1 z$+F7~p0>FW5VigNuHIUDYAf5O+8=-cOi=*wVJ>3{Ssg%P?w9oQRb}{wL_sGs^FvyypzAX3}HzU zDK`l@Sg8MpqicB_P_R6FY(OOxsPg65?zgv!@NG7WVe_n7c_t5`s~C zcRy`E-Zn3mKZ(@4>U8yLX=N*zEwc<=f%NZ@2T#+P!O*NNcTBM0irx8pm+m=) zd-pe}VgxZyV>hF6j0`2wOIdj)*r7|ZIB8`E3D3DPz5Ur05crS%CcokcwtL}TO0aKT zTQWole2`6DQ-!UYlxQP0^7eFR?hh7Mii;uBS&X!RMxJt9R=B`GCNrf03o^71TYQc1 z?zxCo4KDi#gGAxc<8qJog`k(EZ=H7E2)OVI)V0I}C3$w*73VKUUSZbF^*#W;V0_&a z()5-w;o=`*r7c@5&Ql+yk*-~{^CF|ifeOAh>-l(`csT6w*uP#eA*eykl#>|G^77O zS%Cs&u=&I>wA|!_7_T71yHH{L>tM0s-G3&cKHS8_yXrn?Gvq=M^p6|#B5F2%i*op) z<8Qvi1$F${2SFsRc$X2Ej0_YEIqS;7U#>=Ny?UDy!<)$vwao|G3zN;S+pa9v5Wq`n z6BLy(fF^4sH%NL91%XXThiurOowh#+;Ava^n*-yZ4URSxv08EVY`f6E!W6e|Mn* zhJV>68pz4FL%-ZdN0{0UH-;;JSsE2c<&>fYtd?fxq`4{6D>AfE6{LTjo*#!+ZY3x| zeB#MEky9H^^l5zy3ksrijJ&nJPQDf025a(k*)x#ErT!m)o50l`dD%7rH@}8I6gx&R z&OwzzO0VbK1h&rP94RgOynQ_R&!Fcxq~ItOsAy9f``9Ro2B$ce9ACR<`(WUszfDT$(YG%Nn!N@ z0c>lC@I!j@3aB38(G`;vQ3uU^r|e`n1IbfnjH2m^DC9F_ogK8!V2n@{Xgky!5!h!r zT#pCuLjJSq>od^*%#?*n`lUk0e&vt&X&bfqUo+3oWQOQ+ESfyb^mR*TPh9f8q-X$I z2W$CRcA324Xshz;g88S~1se^>w^{ne&vM^y(!NS-kr+G~dLF*(H8s`8*Fg{ca#iN^ zY(+3|g+C&$Fv|B9V`aIeDB~5jYKXo0WGf@5^?*dQSwh>o&sd5|b?-@Y~ZB^;Lm$Hy`|xMS)T4)NE}Jm1Q*yvG7QD>XSanGAxmb0xks>F-I@zxGdNC z8XJ_Z`ZR6@b25XeJsKar1_UW}=N{i`fr(R<9|bLUdqr_ONzs|5nzFv%mZ!a!_FXqb zFTs(-z>A0cW;y_0B73=-4OvXTI^bC5-P4xqGa@_T?OQE;eonK`wdy}5g_{nEQ~Y4_ zjUKy3dMvz)ZY_9t*S4M&b0!R9!O)F&2c0ajfT~vSaa`e-qr4UpEui{SmBwscV*rmx z4I)lBiCT8ZG>T1nRfO4Ea z2-`bDmxp02ajZa_*JY#3=dvigu*KxB*IeU{w=CrI;C$e}5zdt%TX~Vbzay(M#~?8zcwK6TtFm0`@X>Z z=e+HC`(E>6sSNxiCLs^7MEK*QnsGegl=0i%6*Nw z=zWnsh5omh|C)5kEqe~XXB^=$84sOD-X-DcBFSxGjb@ngXqG?0y3jDDxbF+ZN2yPnaC`d7U0Wmdljr@x1OKwj|X1>t$c$N zyCAwV4ZY#U#miRdH5||IVkwFZ!?^zS00p^$JY08(N>=u$Uj{7eJ*S;Q$pyn}+TOHN z8AevpjT0uvqzut}ymEK!900yfQ^sbtT#V=Iyy+>?_3p=)$tF|K7w=sKqe|?Lf53-H zqtOua&Fc4V_oXmwfjVv6Jr|I5TCl>b{JOuz84pc%n-6FXLTtJK(lx_)0M(4U z!lI&@2p#Z%Hx8aRi4fBMfli!>jMm8z;!o`d3HeHUxM}=_w@{B)4fdvlxwO6mhadA` z_RapX56L*hM50B$8PT~ty$T%8wpWCweogC2hP*`5#Ho1N*p#-sH=C~gK3Ih6NFe^R z4}=0xIi+OVXZ+?oSkuoj9n+;vw0AVvcYJ(;9W2*KOt(GBzH|v&=>n#Gs)@IA$a=M< z@!1HUJ8xEpmTzwB6dbB15fE++D!_t3u+MM@+Q$cwz5i;sxi*a=qy-i#dStkeTbIN6 zZcATbN)`$vXH3i5D7*wIYibGc{*)vv6Lz}yXeQabv+Vn}l_rZ51h`4EGu5ui6xtrr zze1Z2Z2AND6Mu`7^R~zku>^4$EsBV@k|JU4z3NYIfmUC+o=v7bX_{#`Nl2u=CjyGs z61Z|8>F=jIBFFca+%z!{=J$5A;gB$+*VaDEl7Bm!-UcB1o-!{(N>@n-$7l)E$W1%1 zwR&;N_OEXrd>SHvbl>MECh4$FeY!*L5(v;4^QJfx+z{F_ns8%=({K{vz7F~P6bbJ} z&!+T2W9QyDxH6yDMcuNw_AcOlT)HB#{Ok8JckPJJ#0c1tXhPM$#fARqw4UMLZnF6n zSWD-tOt;uwjr!3{ivwaSRUViBHEbnWO&u&B3Kgj|YZm7E;z;|NK2?0O#{ZA#hcBtH z+mhNlw?OTln;~?%&`i(Ca9a#5$?kX61#XBI} z|JBPjc&@6A)8w%B>%va0&D^eEi-(Qi5!gE#zd_K|nCKqN)D3u}gvkI8!~*FMyz?1* z)d(3A+VfOR$e8WFFM5w>6sClNaG%34+PBBK($kMciM?-yO2vROUl2$CT@UjatYDa= z#s5Y>;+)rG1`MS=3e0!d!nndO_h*<5o{Sn+u5J5@~y7il^{?X`OMo#^*!m_(F)uN zD+=FNG&}!0XI?*!rTIR&Q=kklf9!kEJ9u}st7Mkq2@7fDU>~dgGD&72)^Zwb;rrIP zCQvBR`4v1n`e6dI54^KzPL{y;v}&-#m-K3qY6aQEg_L~o5ct^sx2D#n4`ia5jLoT` zX+0GY!gu*zAR8nG%zC3u(q|NT&Ir2b^_;Id&bPs9WFWs-tXvV&yPuv6w>=MIGacmb zWsCXt5t{icp8w@W)Mfv^-4sITb2xaCC*=*QznC(H8!K@ux+a+nlVD6}SN9Hmq zwO|i&Uw~5kEVJ($ska93hw|rH-XJ)C6IAuYE!eghfWaae35*yB5|0DI?@FzNLqgMl z_Fc!h=UdkDQH`2ED>9*bb*4YLmhY|%Eq4NV2Sfn?jo70Z`~KX3BtuyDYG`z`J$(33 zsB*Yjy^47PU&6hy{a4qD{-R(S0I* z7F^h7yEr2Pu}D~`hCkI-8_Rn}?SX>*dk-QhZOE)v}j* zE$h?RDQoHDf4@*~t$ZhwZ<`>H&tg)V|2NccGpYRj$|O(Ju}eh$72}=E2njL2L-soG zUxg0U-Fq69quufmF#k6?;>dS@x&#eSy5-PEHI6jSPUJ40pFWDjZ;&4F+qO^Atbk>3$ws1*ZPnnSORs1IOTd#X4+J0vMrC%!h z)FBrOj{%tpD?%K#X&0ew{A)9~)$QX&mVoF~jI>rdwC6LpUae$40Ue*KMe*b^bWi<{ zNX2aLuS^H6(!!$_J*$8xeKN#D$%bS@hj}sn;|U~MuDs?=l&$y-ST7!o#)E=0M_I}% ziA0frodtgX6oc39&#^RcN!b%h+4{9Gzou3tgw^zS@AtzM7i}<+(Ay44^EQs3ay~#n z6+Kh-&Gx5qyZbHkMMeao-969c`_zY%K#_wB!TXgX=MXB~r-0Ch0Rv;3P)3S->zICj zFFW{xWRIwgxU2Y_(M9@u-m*%HU60|pZSeUnA^30x^T+?ttgyAM1}vY#*i zWN#ZxeGHf^lue69zg_yM8F*lF|SRsVltnabQnp_NAI08lLZWH!C6?l51Z$3-~t@t%oR-RHvuMP ztQ`(I`w4y)(FC1e<|CLa=FxMZ7dX@*%t^HSYmiRd!G9Z9)Lkooi9d+J*O8)8>T0Ig z*=ylUc=s$zAI(hEtaNJH`D5A@&HvwTATN>A<&>Fx1K){UfEGxIRqk#?T;>$MHx>fC z;OMgZVhxs&7iuWaqPQKb!DVEw6e)!PxJ7_fWr{rRs19P{Fq~NZ0+%BEC8tp2pK z;si_poIX&U-?xDx@suzwA1Fi~9aqia?jqigtCbEMm;I-%PuW}I~XQ;TrEBE!tbuDgrG7~=&q&L|L-paeOn?SO))=q*|& z`_`Y}d->v)(|3;ALXO%&&QfpYhtd0NOh%n;tBH3%#_sop*A(J#G{Xd$|cM_XW zV9ku`eA}B)=vJiCd$*Tk(c}0j-AkZNyC+OGW=W_Dh@CI963Qkty(9d1r@;7@m}rt~ zxcdimToouBZ3MMA$Db7Cv0%?*h#1W5Z_?P1oih*$(mzl_g0`+uTBNN|07i%_YVfl+ zcHIp}lR6JTBs&RUPK;q|BEat;7;6G3hrC~3OK-W%f643Dw{7{mr7QEEPrrvNl&k~gCGGz+_*UA7QPEY84)h7iM9s>`z#Tfb|8zV+Xv2j*dvgSQe#|vOR`k~`M zfdIi8pW?6ghD7zf-;PniT;FeY4(DV+R=wl)?bo**(Rv}usTilhQtyEs{RgT#5i_Y_ zMBo&^7pSO_)=OzNj2DpXtfxd% zlIM7TB;-MI@i%R-N5wGuFk~s-xTV(xIaRy${P!j$)92kAVs(K}h;L}FIsy3ia3r_g z1@P>%f5`=am8)frkjM9hYd?lD9FRoYg?N9WfB&=sF@41?<|B~#Yc35P)h_f6R;GN! z0z5<$GT}{x3*~=)IFH-6;oRHWN}PuS_8z0K+L7weGL!?jln8KBK5wg@`s`UQ&lMY} z!Ac!o!e*l9>l^IGCq>j18_(*`<1FVw_#h=|WeL>&OO%*m{U;_l+hbXAgY(l3Tsh`T z3l5?UW$x(0A9OnWm;HvU8A-gVW5W}fXglc?JPb3Ss;8z8#V){JY-f3%?#az!rPbe$ zI=1SDh9k|d!xu@uVxRbvvheTi$Z_uMASrzp(ZS=T?+t;jzQX$kG+sLNsIZIvd`JD$ zfwQX_DAF!b&uCrOiq}0Zs==Y`W|l=dFkvvpCHi4LfC=2k$pD5+5j`iJC*s5qadA6I z8Ej^=p-VLl7=#^pHWFj-uaFDNlW2;OpdFbTw?9I61hEEpc;7WL<42lqiSVdOlspFi zKNrcbC+sZKrYL?K+mNLl2eb3>M<&AMiik1gCA0aD-qv17AaA_Jm%vX+`pi^q%e{TY zPo9#7xbW@qot5d6iR(aW&Cvk^GV1g3^OMR?SrIVyJpA>zxd;ZFNUE#sNd3xdV)S&A z;0zch9?Yig2pmXVcIr<4SkpYI~$LUAx{6y z`hKHw3WOce>- zq6ctbDAsQZ@h-WlwIO5q-#+_{Ffc-l0sMurZ*2|39nwKb(5;SowH1&%t2S5u&lJnl ztaiv<0`u_S8)_V8N~~W87|v5)dh34TO9Xr(RiLESM=g?hv#`R4GEE-c20nFF_fn%+?Ey zQoEXrYHxzryHzRY@F<@%M$!OcbfcfoUmj%Mze9w}(&zr>-R(Md21EX^KT@D@+du;ibS) zj#=N#c|F(L?%+ukrlNs}F%hyhN|- z4UuJmUR>4m3Hd!yeR#u8tJ7l1k&}fi(nKz?fz(R{(|)eDSRu78B_ck%bliKc2pPWf z?Q=e>U~ODc?>z*k(FV%Z!M>#Woyod1W| zUh(v@s5sNk3DtZrBpoxL(RW8bRsfbs_?AX+SLK@qyoo5RlR#zS3m9V`BY4sdrzYfm zX%*3zEV6`3S+2gD#ZRqbNR>tBkF?%{o(3xU4iV)M$}!cU=^y>=!XMe3gu^a(!evpu z2~aEyz(x@va)_1kpKi480I4h__%?!wL%iWzZSTV&&-zOLahy6(`12p$P-Cn> zyAqU%_nLQ`1hqZ`xWy8hWO&NEr*Ow$T5OG8D{jf|1&xr&%4!zE)#uW{ zEJGyek&z)#W_V<>#mVGYGE}eog=Ou}tCp#)o|j&?8@w|E^R7=S!{xitxwe0X(uSHZ zp`z&~ROy)+6k%-J!XEJ~-d8%P+4Uv+U?l7&C}G6ylC$MHxAiWQ{04jr12aqqL19xy zCF`CrLtSp%Z3zXqAXOc!p{#*Rrv+Ac%%2EuVj@sliQc3TOZ=~K4^oLWqLpHC+0(L# z0h3^{y(X2(Br*rx~88{O-! zIkp$@((5TiQE`Ku*)Q%l{H$;|Zw>C#_unB2e%NzlcT&fNKtcF!zPP628+$NSws0s; z@ldf&QUe_!6a48^WKj=ID1I!YHDYK1sv4aey=*Uf2p;R%bY~`G?GNA}NSy1E$(iW_ zT)ce3G7fqEYuhTBAP*B!8c&9zA3lHtJJjy(@z|6>5rnF{T29rh(N-u_P76))oS?tu z$EsKVgKKBiYE__34DINX`rhghk;3gF$i;U3XCHVcj53fC>-G(x%loW+HDlCcKqgsshnJQ+$&A&CTic9ydK@f|PPL(3{C8Yy{8#DvoX!gO5-3 zBNFc$siCAKlD&t=*|IfoVmL)YNfkc_P{*V3$ITo$j*~8_p-qk=^5WL0=rFv@&h@+S6B)b; zSRNt3^T|px2?qM_f#mKT0c9ZV608LouG@Vc@7{?752dZ@;)pl98|`ECl0nb(~~0=3>y8PdnQs_GzK)8-S_?-268#$r)gzI zQNRwg))&gc5+3ynq?(rM8J-KmP*}o-ZesKLU>uFlI0=#xj1WWJlSge6>Lm6435E{gN=SQZ*{fjBHZ& zZXDeCBvYwtHiMo8icr8CoD^j+i4H$}a{JQ^K=h$@Aew;`A2w}Jay}47sza3*_9&9r z=0>mH;o@UsA%pcN+I!HVtly@q2#fMYnFj{I9f;D5RXe%Z>+mDm3mDuHmBDcEXF5x4 zcSVlkk{WCa1(AMw3`_b0^3jGKyR@`w4)@`R@bx*m*FwvPK%_K9`+;Er&>ph#xPUDw zN{RML1I@*X;H#2lQ||xtm3G@HuBlk|o8H(342*ya2M#vf6E_kv0{}#Ys6lrA4ZfKw zsUVO}MN^LXHYDZn2fgj0uV$l#pZh4(?h}0=*73jZ=)ST&6&n)x?es~@mK z$WHGH04N3{hc5y0OnNhocFR)&i|3QiTsYqoM&OmJcu8NNH2O%at--v+v`w|?XlpJd zLsS_q{!!i>`v*!5GeB{0#OjPrjgM06 zk7&?t=a%2bT?&M$zo_dT+TIY06pBh? z;wHAFD_>D*q)kR!%E2Z*YFtwxkVCcZga1d=Uk60-e((SIY|yQ=0!xQ9h)6D-(jn4F zgMfq}2)lrQ64FRXcc&m7f^;_$0s=~hbbN>B`}O(#*#C!nX6`t1&UHNwUOtdB+=m?n z0Do;*ZZ$aoWxy=by4`6Ix}^0Lz}BSmD||B#rdYcn88_*pfPcdk07*SB#zz~4w4s+2 zftoG-PaLE}SA1`EgJQfDCv#9i>O}ZS z_@I2LFE7$G?m8u*n77kJhx9^~O2C>kVEy4E@k15Mf9n>1bn9gf-Tvmb(6crB$YVhz zZq8o*o^n80_`-Y*^YeI7Ea3EZ$*r{r>%1 zq5;bNyrONGO(pfbb0lE=u{{JI82RSup;4zeu+&nbM2#4$t7Dr-w@)$@PknTZpE?It-m@6dzh*W_o%<<+o`#A?3Sx{mdOA@X%3ka)q2NR|PHyv$ zUcUVJEOWpgP9NccW!~PZO?hQI{^K^`v9mECo8{>*Z56DoRmpw1@f zB0XxoO&hdn%VYv#Uons6dwqsLxHhf)+!er^yZWo&s$~N3%2Wf1^q`{^CE9yHA8!SDVaJEuA-Nx{$~5IH+vZKw|?Y@ZONGn&ON_Je46=&%8vP4w_O4xs+L)Jg?@xZx&_u zK8dp6redP=`5toc#pCSqAhq<_Gs2yj@Kpt^zuu<_3cG^dw!x`hMnT(lsh_06dc9x# zJ^Qm6m#+ON|KVfP3sM>lj--KbL4%fc^w0DDFIBI@L`^q9(x~2U!xpz3PkuGiyS=`_ zNSybHZf&pFDaAAiOVYOHcv6%~5`T1%%0RS$VBgEOwS17RP#t`MI##*hezH983}D;B z>9qX)FHZNIxjQ%+ zx-3$>enm`#PKM=_%@}xo0sgY_=CHA~m})$$IlgZdb=ZAbV9sS=SROYnIRNosa1t9p z?}#U|mk-k};6v@Vs4ZPQ%C3eZ^zLI9yyo7m5sHl6Q+V*vm)ZOl<^{jl16xNB3mBE(*=|AA9wi`T6;Y z%U%-z5P~TACo7^vUfHr5k5`QWz^yuwX;!|Ei z^wN9iR9#@DwTS>~G4`Inx8fHc^7FNtLWYf0wwPF&C>oc>g>NA?OqFc%M8UY$OEpp7 zvO1J#@q{z!#08&~wUp#v{m2!!Iz!~?5C(iw=w_RlQ0Dn?cH~CbGso2&&(!wS7a@0D z|KnGK;0*lO(fs~M^$breYebYm^_H#}Du2S$f^rk%$i_E$f-54%R6>Iv*QdWMH(j_i zPh{8&tDZssvv`saa12FXoCD8^--<~%;dH=|T@YlOh!qyE>zZPiUBQ3f9mI+3Vr1YK z$q}Hjp}I!(thp`pOwBnmcjN^+a6vmIp^I`c)Eay&3&qatnw;PYT`yyf)p7H?(n zs&femffUSF@pC5e#W`V;24r-vKPjH6h9&B*>7j&KMxNv$I@hpkB{fK>LXQ0BE=G07Z$-`$MHJU zk%B2~s7*vhxL+sx<>Pz%Q=oFs&C zH!I-!=smt4>eN^n0Px=?3E1?-gG~3@p>(pWoa}51BvK)c?@}}yfB@AHi&7{g`rtl* zCS%6|n&6yyiL{UH)%N1l+vrFz0ywv9x zt7weoqKy+gb<9InC8FFgD%xMSel06BB&87S`#c0C7M8I*5>i<_pW)d zNAM|7;iH_g>IBB*irSAOX;Z@Xd-qrOJ~Lv7zx(@zntnx+G!$|I0$hhP&{8SeUJs6Kvb@SBRgXs}M%|D@%BK!3XGp4AUQ zs;k$H0_(%8oCF@VV>UnCYj>u2N4&7usyzB7*W@_Ou0mNy!!Q8k&dU`M#g39Ei(Z`! zMC0FVOA)yw%O6M>H!XezVj%(Y1i$wfguvTe^OJURMXWQe*8s8GtQW*~WZd2Ch9=s7 ziPfezslt~LIn&U|Q#^(B``;<7%3U|R=`=~5ux(Of^?0FZH|X5Xbz)PHN++I6A)+_V zM0`9KF&q!NwwK3Oq(IsD=+mLu8|FoN?zVs3Q1%x<3epA+qV_-TJDy4SQy4R=8> zFWbD4e3EO?cdqq%g}JXR)8k>F;;B-gL;eBb2U%vfR8s6n81PwA{+~oz&C0%>Kn0@0~@z+60M~1Z7vp--RiW^;XL)1nbh5Olk=&Q5G{7NY z`oDYseqrqe<$nmP-(Lh!jhLfo;POTOR-fJHo~Y{bgoe3m*E2JBC&b;i-FP)|01~64+{!l?~sXQ7FRp5ir)kjq34nyL{rP z#pb9|;^6S#zGJ_@%3zyq@W^~#k zs)~OFqT6cTZ9dcrRoRv$F&;54DVqOYzwY z9xx??#qdmaj;9HtXIJ~t42vOviT^zq z2QUv^eP^7KXJdN>U<{X!C&@w_=CkmWdC1GT;yu?1829dDD$IQqRWL~r?{*^|L9+!1 zF=ty&)F?2CmYe!8ZM&N`A<-5$8%BZCHc`1O)K-@3g$W8n{&71)94g?6eDiF*VseC?xbNJ+nN4H+?D;-W`2fnINN{kt*N0XWl+R94IjAw}^rk*P%x`tg3zqei zehbl!LCz#_9+P<$>p_eog~~=rW;~NXAmuzViI(Q5ZfoZ;wr%A36Y>6gFsNfuiia4R znY!>(lHZ^cZ6N)g{pJlBN}Be8L6zml%~ZUME*CN)=`L4w!ZPeC#GUX2pNjvz9SWm? z3_ne(>#X-`l$f(ptlQ`TGe!f)(cXuLmb;CoRxeLXvvlC3=K`*n`HY97u;#{JTu6FgsKe4BW0avq(LZBy4sx6sm@Mn?!e*$y#BAf;-$9<4h|E@47= zH)}oRYIhUQ=j$AxkR*fi6GD9lLmJ-wCg;Y6Ppspj%THQg)7j7b3mm{u$_0`nngPn3 zPhuY=Zr2Qcf^>)tgS#dgkyk4J`4D(`?>}k+W$vK|u@y{$r*01b^eSDxo$=&C3v4`cl z^U_d^djX8U`YuUjF}0|Hj#cOPq0D?_@_kkkb)S?MhZs72o`@4QX8+|*0MTPVQ(?{z zVv6wQ$*Ckg9+6hhbfcNLv6mKQ6>S>w-52nWrnAoruBlCG10!{q4i zJG9lkUX^FQ$>%_nP+p@b`Bs|k5>ZX;+q*Z%=cm;0?uVBa2e-eA2QuoA4?A0=<*}xO8!p>{d2C?!B+kz)AlHJi`^TpRT_i-oL7ASg=l#yBRaLV{CptXr4^NIZ zN;W}PqdM(Tot+~R{S2r2lRtD#+(?+-s`4c;B3}yX{R_(EiA8hoefY)qx>d&q0C3P< z0~Sm|UANe^Gn}rOw3uuIHeoMU)JmPsK);-J@n|*#a$tRvvkYP^a^7VvXpC1Up|(PV z0?`3e3JOxDT8Ud_s2VYUMeDt0}RJvkZvZ$w1j`oX( zCg%;$$Xzz9*Dz>Swy|eR=yi93NbIlsfXlC(I7nGR z8Vj&FU7j9lR4h;m9u5x$%?_M(_4OYGtNWmdSDin#eD7Yi2=yf89as{5!E&Sq+D=}4 z7oweLRpf5{J5(=#8Z%pN^Dk4Z1RDieb}H~FzmQKT-ujsazCpv#q@$;Qa=Ij^Ia8xz z^fl!MdE4-B0+-0GZ|52dz(Dvz0jSY=mm>7)9`^tSGDl82M8FpYZMtLw$u6G~oOVgE z;azkgUV5MyjQ{p;AH%ov^^}~Z4w{#5j?{i_n7o;_QWm6cDIb4@z6esk))4YL1gmym z?)5!X#l&EPAeQKf5$P+*Nc1H({*c&_DjDINEHpgRqd@Y`q-FK1BS^VU8amz+Aj?7w zj6VH0O>5PK40vxc_qg$;~pa8pZ)f`J+sV`(F=9oY<+XOjqk7(VQz$*a#t zR+vX_zi=%xzu8ry7$>uX;2B)^t?dklD5tNqD6Wc{x>iwVybS;I^%XY@HlAGggF@>Bjf(qS9^d{ z`MX79enbk((#_Y)HJNv5>>qQ1x1WsbpCOU7vOt?+Z3RY!kn^JIW3+E_!WN@*rqw^$ zua2`>oSaWDSzjyJ2KYzS%dwjyyX~=^45U$P9Q9|_=JMkWq`&60Q`2A-)n7ThK7(p&b{+r?kp$30csksElGfL7o|0A`@bC1FCwcE_l7I)x*H0eB z3w6ko@>UsLu2hmg&!?aN&A~g;-$S=E2*3nxYD8vhn(GO645pj0_^q~f849XRAGO0D*0MCUXm)Q+fMc@(^!=Wimk^<64WExpL`bPB2Vy_} z!7~Xxs!Mx!2toy2b4}u%bsvD`^oeXjI`x$zRhHZOurM$H2!mE?<>GAg&OyPeAEy)4z{rd<*ou+EWAhV@ zDA=Dn^tuoi(fQ-+%7xK9!Pr4@GUJYB#sO%}X4pI#Qu^&H!jBq@#ivW)%XdG-f68U~iMzr#t6!TB$sG9|@T}@nE+=$QM1=yIOhBX$Hk?~)yMoOCe zh5)axk%Px5R+7ZpC=;UDmt-ImK;AIf)|z<01Os2=e)J9ZlB z`(4v-x32?2+dRlwi@`I88DRPuOz=Q>^^~uf!5C_8To^?$s@Fpnm0w9xFVuyBVOw#p z#PDTeD_-(j-=fbkXdSB?p=a9C_o5)3Nbmutlo*!v{_I6PXM-$DFQL2(CnqM@a2`)g zP4z@G)=sN9a6u5}e^x?}$m9H+N;>V^n8QA7;t1kpPV&nLIMPGG6NQ~jIQ{cc1h30q zWfsyxz9Z)ay-Fph)|d172}K$uWO6ioCSq!EN)TED7SA=w34m{A54PEC+y4zqE1Nm| z8OsgjU(;+L2X7_(T=Hc%eo)1xo>U4jKN$eWxTihtM{Meollu}2(S~ao@v*PN=*Ow~ z7p>UyAJ+Fr?p{~EMFKphvy0(VP}@^+#s@Lztb#O)01P=fp;GQDX25bc4!gpIjsTJw zlW=wQZt45S`&@^-{{@>)=rD4w7*N9bB601$ZlSG8c$w@v#!Bp=Q8?}$DeKdNo;)6J zQVItzr6PV*N?h3lBwa`jA0Klor@}HWJn2SJy6R%qBjQx#1#!h$xn#mlF?j*n{GjA6 zddVqUJpD=~;n4ev-|vu7P2-z&cyd=5MgPxlZYf9b%?o+37=sT?JvF@xr#fLqU#>3;sD?R2W-#c@kc1P=O)(C=f z)+z#LiN%L03oZI$Q(%M=Sah)zyF+VomU4v^tMiK~zS>XCq`0`a@GGIDZsRMknj*)p zis*Q(3kbfb9)HBo#ES$BI~XW=nMH6d$&J~l4BoPrVs3H_EICQBf;Q$#HGa2ZtFyQz z6+NdQU%StS3NYwN$(0Tvtt~(KrzcYQUbn%ICxYK9BNcgV~%B;=Xqm~ z$5_z0&zHy|0b&h9{c^1fkUI2lEZ@=0k|Fnu%1H_x)IMwPNF9Fv;4dbeDWLB{47Rh7 z>YpISCP<|#7U~OGw39e2y8~uGV7~T?Us=HCtal1_W~nXE&s4(*CR6@lA%MCkYKeu` ztzc(&oA(s-VbDP2Ul9(lT;`;5p}7Z^_5wwjQ?+?<_G@aepvwUziMRiGU45~9F2ue# zuVcb4neFy0o$8CeHV?FX5A|~)FJ<|0laSS6W~2=C;K?{@ zUzQF^$3mAXnyI2bb)$afJuq8p@%;^Uqd%f2L zA$ffzk!U&q-HwJjVlxr+NwF=Lx62^+*7`p>&a$P&kG_mKgPm(NUg~;ykgn>Js(W~T zp74-0VapWUW}7TmBZ3BVu#t8V>jS zlk_}48zp1k6MRtgS|r087{-N<=|+_js{L`P!+G$N-mXR%kU74-i!A9BRFeZYeR!X0 zjsZpR%}>@r9WX;UW>c2VmRHnW(G`B6sxmBHkzw)loeOIVvvT+sJoZ;gz*gPiTTd!Tl3Y~K*gb8~ zxK&fWB0h4eeO-dIReXf#3?|T~-}Xqqj=ckAWwAC~`~SH-dwm~1@*`#xP;zvdACR1& zJ+RwxdZSMxb+_zxaeau^*|L?U9yNLW7g&8YzxidUH=la0uUpGQ^6lyj;_7lM@$D$j z!SaWNwUzd2ZG+Qbih6HUbt`l3s=5>d=jlh^Ih~w98Zh%I0EZSlSeNZWqX~QBV;Wzr z4<|`R0OvlS0SOmgV%(^A>1qG?-5*_3%!%;XPL$8*J@9=FZZ{lqcu= zy~2j#UffDIE2ie=l6=g4aK!rPsr3v8m82z&*2UL&mXJWS?W_O5DO?O``|C22z!8dW zgU0-(X>-4fi+}H+(Q1{IN9BdQ-uKJzt{o)A8t`>wghPLWY(pIv4y9Mx<*XPpgh=Ad zEJq=6m75*OG8_~nWS1H)&G2kmlKEtV`Z5u}$M|JqNeD&016b7JlXSn;($H8ADTpN9 zfVS+N%Cz3g-~uFgCD8$uko~MDH4O^#5?OGTSr%};I)iO}QEz*lK&g-8qGpDOwXLc~ z{>;Bm-7IaqsFc3Za#O!^tMkRvz0G6HdGaPkgDxwr=TD6au|&k5b_YUcXh$%m3TX-m zvG+Jhc4>;AAzS^fEj!-hkfd1l!Vwb)iEf>|0uYn=+)xK^gb)x$e(CUK>n0enBYN}Ngr6BAbbq0~R94gn zZph(!TrtV-SK%20W&(`eht$-*Jaw~XRfv4};%tJ59>8`fErbvA{rV&zOg{nxu0aD@dNC=~1@hm>LiWGB;KT)@utxu;N8j?2Sj~B}b8*Gf z%LKc-f783H#RA;c2P*HpNY zH_?)>vyyS;d;p}RX{Z+4$=+yoi0fYE#|P4;gGFc^gcrv&9|-~x4~9(%CmO`1On1{D zX0fz&KZr-rhS0-%8WcV?U<>_Vc6p(cO2LKg1yUu}Kz*Fc0h60O6K)h%^so6MbX67q zW2M~hL1PXJ;P)F)pe%8F<<_;PWXZr;_6KSUgFNv6qqbe9(drd|*0H>KlOm7z-_309 zc!Qi*SMWQcp~cQZ3fbUF!i0^Tq9Ib`CXB7|7p|cH5p=GKODh$zS8Ae9Y!d$&uF0id zkIP3~wx!4U07pR6t%SJ7G4~4}NR+$2(d!_`rIv-e{9OZZVQwTfEeX~ivC;odWyqo+ z2U9`9Qwq+mo)L3houY{NB$QY2Sp9sVCvqt*B`0TC(L9Q7b%Rb#&iN~=S}I$!_rDkl z(|4nj1a(}A@w|J0)N8wGy>*;~V!#=mo!GKzUo_r?mD%(^a&48B?=o8M^ulh~k; z>!TSN{c?{32idb+@{@r~WQKNHq)7klMsNoC%J8bvG3D0jZ1=-_>*d1UdwGYuQ4O3J zjOaX@1&uk&9jT9vKwiRciq|HG9~O|)vXoYmg8x0#xoT2H;sLh8dIc2r4KFV7zu91JvTq1uc) zl7jFka95cU?}=kLW?&*R904!Z_3UM5>I~4U#?EZP17=+nE$_u=#pxF7u`fsl!bX3L zVL~$+BW(v1fvmlON+T*f?2({zET|N^|9Qd4$=nnI-TE!+T>tb@jG@yvC5{UMN1x2u z`xLl2gxGAs${D?NO^nhY6}Nj%hUUxEAHVw)8QO=kB0U+Bq}PTOa@ucz8ky`Z_8lOq z#Y9c=+WjrqTAg8m_0JE`X_hkt>ZjkYpn?IGBcd+Duk{2L#qw=-Z9v4RFOHIPz(hGx z5P_svANHc%viHt*#^|C`Am(-27oo(S6cV@{Ygu@b>s;mijsp!)!}-;KRg9VH0T=JL z?N@JGK}WZol@@+$-Rv8Aki}6$Acc;U|6_TT`hHA1qBW`Tu=Vz`)pv4oa>yz1do{?s z1i?C*PGksPW{89`4Cyjv5*+~v@EV9)(`qBQdnEZ7oCXbLIwm)^^#jS0T4vg0Pl$Q_ zMl6zEze74T9bobeNWS&e^#pjBp_6kA#6Oyk}NY_U7-Cj|56c;>)cG!Xs8Y zQWq%H-Qp%}I-yVWD3~!cPCdbSlhN5%f&mNxY3*$Ad_E;SYB^_Q-&%iyK7<)hF{HW`xQwzvpD6=!;)(|To6k}7wAqX6;T&}B<3%o4s z!@cXe#}<_<+6+FG)PuW3Iu*dc9@Q0&W)c(SC85A;1^{5?^H0N5y@>+9FaCgWqGXI> zA4AtwNFim6AL6Yt3>@6fQ|yZCD}~NU9>)Aud9KOk;;d#Sbj3tu60<9oIg$;Bx)kToP0<1f zyo^wD-%&XV99IaN43fnJamave2IhIbrpQ8-SPKi0J_sb;`rhYf^RBq-y_TV{YZp zmn8{SrRYA8p#4k?tte~1A&h^m!;cuc!U2Ty%u?+9UuaQrZ zaH_;FEr|~9W_dZb-|!t591~G~-p#zoowT7eOfn85a)Fs3gs6dmA@+vX|3wanol7bC z7`;1f{0RmKjuA#!ph%fNt_!i|uc_pS=R!bfWZ8*50G14+Iaj^i^3*K?M;X7oK^hoU zbym`UXhA@D0c0l+Z~2vcFZV5m20xSaGb+JY6BRSSYDe-_$>|*mBIk*-4%r9}yvFPX zET!Gv6|p@RJU%CXlxKh^NwR9@)n@~Vm*)G3Toj8b!}yO5F94TVqgJ}*dk0R)(A{Y( zE{W6h?%Z|K00*jQq>Skm&P@pb;jNAUI#0aRd&1Ll|Lj%=fryhA{qr~i>kbR|XOLPO z!ySNB^4@~!KDFJZBemaQLy5Q1xVeQ74WGSMxMN37nRiez9kJfhAKAR4R?hntc@OA@ zB78k~=3wYMtVe-1y;kn0AR6*CfE*39kww(UVLzz{yM}ox^Dh|Yg-wSb2@Vmzyuha!HN=SqKWJIH*K1JuV#`K zxH?L|)q%_9>qRH9ePzg;9aVZ41RbHa#eWIkETdz++Ah0$h3a1Vpz0?R#8We(*OpJN> z>KFmK?IU#ayitG0-+{s`V*O`^cYQ+VpHMDhBhH7pucw7Wb5xMkUEolwJDI( zp82~)A2fx05V$y9^ie<0QYiAWv$M<59yoZz2GGjlpwk(^ITn#8h-N@Rd5cUlSX|&8 zbKiWWJ?)5q|6~Z^R%f~#9WzfMY#4|Y3r6(jG2F$5D^`O)B_v2YqZkc5dTx`5^6Gq3 zxg(1Pc#ubE zm=Su+?kj4)#$6$qb|=hI*Lo?P!#~;#a(hYGBRSu=f*tJS#D-Hx5}?bEu_~q&ysO`P z#a8KNPgCpiKGG}E(6aXk=tjlxpgfSNIQLn4Hb=9SH0VgUDM<4ybPB>G0m2!!yc}W- ztx1*)5C)F+b4A^qENu?!!=BkX$C)9tu1q)i4v!-MFx?9Q(AV|K z2AQ!GLE#Xt^HJXH z60|siVURzCRG>Gj;H{Gm>Bs_0M$1jqL@##dRkr;?nVTl35X6r%G?^fRYIv}fxH|R40jBO z-pkTdUkfBAo!g`DH!$tk`n;($O@ux1{+f8j!+vQ!Nl!u*n!zg>%#lNoPiT4r@=HYh zBpYu&@$j+=X#-+;=Aghg)p6`F{V%{A@s*kXgJN;jG~q*GjVVM3K_EX^>eh#}l}gV7 z_%tFq2H$oUn+=r!M?BTPX4p_O_xAnp-4@O-hIuJd&z^Vy*H=eApJG0;N?IqPp6tZ# zG`|r9FWYd6KG%l!eH`kJc<|f7^fFoOu!nI+w{pQZ|I3@?R1luHLn|Q4s14BCU^&>^ z>j2b6nUIb+Pioi%Nz`kQ##E&ilqC)zNKi*9O9iT+93fC2{cC(bGU+oZB?22+h=n`f zMWC&f0&PH}K`5BPw`;AGg1nP7Z3H#(a^AgP0;mA2(97O4JK!2@)Y=DjoaJ(EItX4h zbR9eHqyxz+=j-3Uk^+&lfk`MBxtbysDvzC996BNO*bMaVug(E}-bG(03QAW3$q!SL5H zYP=?GIWXRYdUaHu(;1691vDZO0#YfvcW0ipdRQMgz4Z8e5uCZF`Sxf6V)-@i zcTAvk*eB9Wv(@qr-ES-y^HjG96EeW`#IlF@?ZuybjE^=t0ZF+kpZh?&YR2J!g3KX^ zx0QN}BkNZBZ5BPT_m$=}lqqlR7V%E}C$DX)xiUo-GV89}gK@zT)4pyK9CEZV{P`}0 zmp18lw*Tw!bL*Adtj60n<4)d;Ub#DfdJ*GM2rjZPi=Is5+>Q+co!pIe-HK7C`kOgJ zGzr?EANAhaH4G%RpYv{=w$BV>b*mFEE6ALUVnb5zx3zeGHI#9aYs!H|=n@fDSKGP%$Ajx$CChjoOd{oaJhA(}k{#Mc-9b}2@6Cz;$Tg$4eObOwqB$k0NehZK* zR?&(Vp;U&RRnE}iW4Ao>2~EM3m-F{}fJwbhr(2yE_CgaKg9aaU#pL4JRY_SHd7k#h zj9usxQh=!F*OwkQHveGXU^#tc!=<@}1%&iDFHnQ1JR$6QtNriIUd%lJEg*s5A#+HQ zC+D2FcFR1&ko-2nFg^oB2^-gZ$Gc?%FAy&w63SxJa?v03qSZ5HNvDMLcfdS4d! z>1hF8S(;EYO=z3TKx)R}bJQACG3f3dB+5s29(4q-JTfG09ifQ*ZY>57&tn}7SeNKV z1?wPM3SYXDY9P!yPWK^NxH&&xXEkWTIxfi*!V~z$=}1=pQjp;c%6-vT2A6L_UDWq* zb8kCl+CAyKqwn|C3vvqz*cKzVKAn~aK4O_1=p&}F2a0mY=(37gN^fT|-G3QXSt==y zuu4qn(6(MA^1Za2tFe$h#JqP=^|2w)W-yCzQe*qg}PGoo(?-4Akea=!N)ruYPD0-Cm-44l{OJ)+vMO95(NsuQ~z zvW2;yj*0e1SVidUIMESzP+Uv;TC zx$mqz`Jq@;TvDpsjCMSNjn`)A;W-HZ%UMb0tx&HCiczON)tp2|qrkdAc60o&9X&rBoltYM36?>3Hj>v0K5o{d-#Ze@zM!36fT@BVY0bAAl-M&q?WQzE5sn$oQ{& zV_6?{w%m0ik^5I2F(T49^zbMc3Nj+RX^J+T11hI8ONE=uH*rV7eayYu0Z33Q@cwkdI)S}z%g*;Y=eN#FEyi+AVjxT>UK}`&+ht}3 zfXnXCAK+HdFzEK#|v z!sEtlZt_GCQxYtWhjSwWCTl8GKpPUzy)@%F20^9<#YZBhJSNDqD^qC2SL29RLAWb& zf^McVkpF)EyE2gdxK0h8^7aQ_98qd zmb+Dj;s2{yQ99nv=(k}rEIr{#;0KmFi6rB|51q^d{H`0)RxopmK(eE0z$)rCG5%vc zJN38PQvYw9aT$R1Nk8u|v7WwwKaT()jZs6vFizI_XT4@$U*8&tt|RL%Rf@kG=`Ig; z8)E;u4qdMU<9*1BT`C5_#$-#7QtXE9lPZEjgTgTtRdE6geDK%6hha8R_ptf`w#+y1 zw6p#;_1bO98S+q3O3J?v`dm|!o(?47_i1og0YE87rh_J46lGF#AHJgGb8id{+_s>& z5cQqVI6H{8=Ks6-Qg-0_)zDX#>0Mc&n!?xZ2LrT_Zh>vDsa+X`nx zDKAL}$ZU@}ejusB(I5yMhk_@wDY}*q&NQmZN6P!(59Do_an>%2hq(lTn$;9d!4G50U0T4a&Wh zm4zhDZr%9ZR(m(n5b4UX#{ z6av(&K}q}FDq8OW9>a67J~pZ68we3X+`mt`y?*H~b1Msim)p8dt$SEujJXUAFX^g> zqfbzA{82y;@bfj;uRh(4;vaYU|1K!K>_j5`J5GCwVZBwRS-|F+BTL1G^q(k>heGmI zJGiYTegQmFmZ7-3+W2i?{`zbizTc-(%Y$K@iywbW+G|TEE7(6Qap_2f9)mqcekl#r z!X||VwT08Wh+f{dN+;3txYfwxpu^FzYEw5qjHH$xVVHevIHFuO;1}ouTxed_?R=e= zhjn_Ox^9MUtN_P{58(Sht`c7NPlpu7DrzRuq_Kt&<48@;)ooLl z0Pji}dan%BBMgh+bVxeQy)!S9KSJwYVhxjyV(myW%#5H z`;wXGQ36s8V4+FG$w+I9KLq;rq$*-XeQ3agI$R6An-i<{V({gg7oF0d*}+!@KH%rr z*x}~DPzB;18S~&6g7449NZ^o@H+Ri3H1UxNMnDHt8;)4D5*Sl?CqJt`wWnF z;p0--As%#{tkkW%2ZQ5ukEB_x{+~Y+ie3JjQ>4&SYUs$P{ySD&x(enarklh{$sK-3 z{i)OKk+4~0;b}+1(?hp%GP^KVF*khl6KL6s+M-4vfR(`IpN50%R6MSRo2|0tNwG7kw&hFwE7S(wz4>JQLa{l!@BgO5n5@|v-2MkCzaYydCZ(5yRFe$QvXd4Hh2OH zlvBX;)}QFzGLwC4szIy3E%CKb;qf-rl`AG%bol0<>8(fJ$&Gs5UsZk}bztpHn~RxH zD60Vbq5c)msDj|Q@Z%lEj`BzBZSK{doB!J)q|GGY&xIroK$=Apc}KaT!S7bSnyzZ= z?zAV2&6=kJr6@7cJ(yX`Q&TOx#aAp;z%Z~(iynRQ%}Xj5+5Y*F8xC?5zhK_%WqozY z{Jz9RkAj4&*zi30yD%LH-rcNbgYVvlBhHq5`wbUe^Dn3BS|(}SN2EqOju|k?AYcAD*p@_a6P>BKd=YBddF6bGebRtX1p5D5?Hbss z#Ax|)PHt(ESehun;)K3R(|Vy_>@Q+1Iby>ho7ST_o#^ z{6j*)fEge0RczEw8dej2WyD^;ZM~J?3hpPzCa2cxlX;Tg?Z$>8|Nj-0cum*IbU=wM z$@KDE-Zr?Epp%JzFBP)n;8 zLElbC-+e&B;=f$wOydpHzip?xYKI6OUaMyRZ{unklLzKp`sqU+9$plew_IRutNnR` z6cO6T|7G*>n^KHV+)XzJ{5HAsnONBe}G zVRp5ZEcL*M#To$9s}%|!FdKfT@mh;6pB&WQ+fNl&ycJsPYPISL#03`cNKe zg)TJ%zGhXOW=DUPJdBQfw+u>{7VE&o%I-Hxpg`n*)9r+F`JG_cBFT2M z04Y85kM(u$*^MG;bNs%$jba>IuQVL)?F#hYHL%9xJyzWU1jW9^7j7tbJC3{f1cyKi zbEFv8wGh;NTf*-@2Wl5)E8w~uZGoK!Jy%Ww6V$~2w^|eMp>@}tl2@Jch?}L{?t30M z&3&k`4@SV+Tj}gA58oVXzTPVU6!+77SPwqDJCq`QV&g8a zYdYLDC}P`YHs4r*#^D>P!oCVtG^8ws4S!F&cs7y1Rep=}rthDg!Gr}}S}h3LS=qq& zPe4q{>YXHeJ9F4Lciao|z`c+J(4|q7_|M9hM00>9VtSwPvtNc4NG3g)a#L1_@C5{v zZKgv|_}=EFIQ^Sjfb*C+nK+Nqq9FS1?x$P7Y2rOv9H%h(pPwrNw!?{puWl@=^D%ve zreJQO?Z-H~prspFHgX@0Vf^Z4i60pXXApxJnlDsJpKhwm6Ck}ULu#O>cDBSpCxdr8 zHt@WS+X(_G&l^;f&b|R5jDA8Pj_Yr_%i(_!U)69>Quhrq*{#a1GP)Y2UW^E6B%C4; z_2yysBbHWUL*^j!rZ+4~!)D?+1FO-*$*NyK-rAMNF+q9LUz0$De+#`U+JmjJk+*3ZU0^!iEM;vj zWb?z!?h1c>ceb4S8OqVm47t|O<)DAR@ntH=;TB`>a_}jzI8ef0I#hGKW5#iD;k)i@ z5p*i2t{4Qd3ECntVVi3txYlU`+mC^4HGg>C$Y=1IAEi=X_?qqo7)QXYa2s%WZk|8f z+Z`cOUZ82uz91|R2_uuTJ8GK8pmd?WCHX*XR8Jv10j`=4bV1`HVmO0)?!*)f*)ou? z7QPj4)tDOP@|qPHOur~~RVySAmL z5|efFikq0RM^#t?vJ)VBwFZvd3Lyh!l_DDBR}LHAf}Pcnc5@Y_frMnbDBx*Wv_;q968J3_Z?`wOWa&w`R-n2>dZW*;zTbnPXV&MweD3hjTFBpIe)=95 zMZURG+cJ$n78+7@D#qhaB2ZwOY)yJZ_?9+-3 z3%sgfuxre@jd050AHR+gOFqX=($0>=%O~DhosZhc4gg0`rMS;UhO4s<5Vn?JVP$sVI_3RfVFWMm6^UDF@cuZ z!%d$3lA78aTg;>f_+@{w$N1i~cXyO{1pJtk?1 zZ@U<%1MrqAhx=>zup!FRbNzHVj{YF3&SCLh^ugeXVvl1Qj$4nSjjvF+ji%H?5X;5# zixGEhfDkA3o%&=x2eVt)f_=MLb<<0v>tu-Er99uHdw!bxM~XMWtNav%{kO~V+{@Z$ zm)|_Q%{CboSNlLMSOgI#wG^Q&Wpi;W^iX5*?;Yo<0xsj^&(mF!R;-m_%olTX`6QOC z2l5%S+wO>GWU0I!-BzLxFhEqIPIzf6n&Ih zXyr@POE%2Kel-4l6v&I*wDVqi(yc~R0ItB&AIdO zmRmA;s=@9;=iEP%cU!nZg-)yn=ZHE^8|JGZS2bg@sb>Y^Bkpw%ht080Kz!zhiD%Py z9wy@Cb-m6$p0C2zDC0{UXjpoH>gEH{*%Ti_+eN5+WRRg7h}%-=32kVsZblFg&krj` z7hLm=Yc@lIm45i*uPwyn9U>Ra=|E+z zW`)#Yu`R61D5tdlp5iveRm;O8Fi0Xani-mct)3;kjq%c zf{|NXdb_gTClon}<1)>HuC@uuyT^Q)f-@Oh6LKPnCnwEc|a@7V< zL!hX%K;ASZrM_wX4odW=%aZq9=LVr;`MMl9U873Lc#7yB!@1GMh{SdqO)O}-sDy@Uw~r?y0KT0r2Xc%G~$R!3r&z>erzug2Ei{rx&GPt zu>B(Qx;&@KRp?rS-7KZi58_kHBW4FluU&ws6|N4aoS8e6Az1b2E6J7!U9fEBVT{Eke(ncFm9CCk8_4V z&(cwO-M#w3A||tu7t#cXT+5SqM`Ax;i|@$iO+>>6ht{Aq zoNGl10(g~9H#rp{7@=z;Rce4wu`lXJ@vS9DPLdq497Kuc0Es0`18<{U3(rZFp)zci zVBMXdL#v!?&NFul@$q-JafX1F7pLH7(eN|HU#zC$P_SIRXuows_H-v95#_0Ps_pjt z4@^706#A5BKH|#976#`=`*e^e&R{6xy+aeH=L!OiPlvr*UMS5DM$zDjkn5FWKT)?2 z%5P$JZXMrYJIS!6Z!ZhsOBkX5ek~#{NS71GEnOk}#nb1+H4C!LhONP12XNyB9_v{< zZ)j^SKhLvH%dy4#hqcPmz^1i*Nwr-$VD55Fk~O#wYla25=m7e=DF?D)I^$@1E%E8J zjpg|*=?%gM!s73u1LU^CjRWg0q=~12!?%8QHh$Oqy--DIYpL)r(JQ*qs)Y+Rpzk+t@G*6aSN1FDxoSlb4$rL-w9xr#04unMAhFQ9K+)6nJyv41B z9Pnp5Yv5g-4}x;w$hp^6)IfX8wrvV)%$LO1lV2;fyXcqYg?Tg=I?gO4?p0~u`U8^AIp^+yLD);K=G7y1$QGs-DX1fYM_bn z5Q(@cX+l;9>TfQ1){?g{ylv!FAfzbk0oV8XFmm)t#VLt`yyCR|pMX??huK58pAjqWN9x9$u|_I+UgKfDoo%AS zwFH&Mr*X@8?0 zBzouz9D?%#q}r{q;2|5mljgXpA-n)4Va^TeuYq%%XN_OuUB&M}yF?lXf)!#uze2~i z_N2X*pO_cDH*x-|SJ?NtImOMg>kkD>C*W!XsD8#>t^1}o^qr1NMV`Rx#HNXzD-0q6F*V(y5t=K~Hb zxL-gHEILVgdOHzVR91ny!a>4pAbOj2J8*no-Q^>dQ~kB6#em_`+)B2cZnJW;0<#_^ zcI9?qtv3pU&8&}vIPa8^`h!dgqAStS=12K}wfH2XS!l{yN5!A4`za@`&G_NOdv1?4 zV(#q9Oz>cI#?8hy*3Myyb$>2#pRn3V`sMuo`P|T_3>5jplXS)HK|SEaloD&`#Kr!u zaNF4u2H30Q_M$!QC(564KP0x#@QYBQeCJ1GbYsX$p;7DXX@&38(;=@mq&?>>ugC*- zj}@GoR8VNCHmWTfQiv-+dzMY%GaB70e@=8qaDf+Z!D{?G;!Mwhf1*##AD`T+Y?D}o zRo8FGJ-3EiOC)}|pg}S4PpaQAL1}4vfm5^hFd;Oz1XuiFDy{oaKlWYK@{_v5{XquB z;lZ;2t(m(qj#fl2?rJLyG>ScqJm@&bc`{1W^pL!DyCfFEwz|KELm+Ey`xd1o} z=iSDqK5jgvky4bn=D_1174v2QN|!Z5yN-eQyT;eQzExnlImTwULBH8D(7Ik8WQuZ{ z1Mf%!IGS-ET#MZYj2@w{0UttMbF4uZ-X= zuH?Lk#j!MXYfo&DT#82;<+Dm&iMX=IMx6IcZeCIaL;?|FY+ejE^2^JX`_8y$!c5RD zQ)vg3g@d{w0D)8_^;I^N@wkcG7}^>4ktz?ZdrqUq!YKDZ6Wl#G@1;mXPWG5V2J2*naVNQeHrIi3h4dL3VQ#Dt+J2u-8&43m{a*%nWV@k^I@vB z&)Isuf=&}38hX*BVz@EjdDhB4x-U|T_MRe|Gv{{Xi?*f%vKY$Ur0`wiP07JM`+Vrc zu_WJ5$l%dvF4M~L7V9aCS^;ZB%Oj=UbDq`P9s}Xp^H)3>1NI%NSV&-22}*FD?g#!gj5aj{~*`hn`+f7F?5!I-6HlkQq&|BHHJM z7gN9E4z%JUVl1}Y@smLDQ0UYByv^g;`;`9e00~@ z0?XjHOt?}5;XaN+=xP*fefd)Q=Q1brT2A%8z%QxhsUYro9lh*5r3!hD^?R@5FyY*< zkNoEEQ~8J|qO)eKW2U|IMw)~7QB8n~Y@KUKWNXG%cHgPsdhv34LRHaIJEx6=v0+NT zu++gJ(u&0l58wHm@8WVATUA3p=nVi8WP29FW=ya!`?}|mmYY3n-;ziSF>hCrBeo0~ zMDcosmnZoe%F|v@6b+_6u*_6)_$a~8Oc68^FL#&1dMYR2EG9NLq&x8D7;bI68x+M`UL)p#5EW_#Hv+ouh-$r7pC7d?@E-JRKqq)*Jp) z(Y@!u;538Z>y~#Q{@I$-vY$bfV;d+idhWRwy0)ZdlTGK6t&?hjQupN%d0-G$Ekf+| z4klY%8u#Z|`}fb6cfUWi1eN^46VB z4^3K|hvX2(?HwgsVEwV(_MVCT3kk-Gi(-gg%{z)2SLC}1_pdIAj8P21 zg0f3#^QzL*)S7lbq`w^Ls;6WddMO3C#YXG{Oi zO23z6y|R+^a4*H1idm6#3TPJ{4fZmoFknED7^O3#G6s{fBBQf>q2;DWxFh4on19M< znwHiG2c$paTM7m=3Kz*8+=?~T{#I)KR700cD%IKF4n!mDUJ5W`&QTQs-qv5K`a?6m z=@uyJb9>JEc-gWMP+k2hzeXZIQ<&rOm5WZ2X6RZ*@nEUCk?nmAqV3<~al-c>3| zj=Y>^1Fu2ml3?Iq{djmF9U|!bY53 z+W3hnJqLHj_q+V2@i0S9;00=q2e`3Ax3EnAer&W5FXMZX+H3q5H_u$E%P1rv#QFpr zijX0C5;_hB%DWmof~*svIPZuIazj67U+nh{@16O*F5W*PGstTePL~UxAQ=d&87vh4 zSb`}VQYe{UPt3T?ntOmw6x98+TbLIDR)C++Ja4g6+|HDJ=r?q#js++?EH!R7tN5

?E>@KyWc5V-MuFCWgXN%9P2~sSDFRbBX!tUvGdRzmk553ct%G*jY zzBNi~#ajxSS7EMU&b|>>%3ExEHmMvhc6>QO8%!@+E$luH1Oib=9P5FY5keJmfqClYv64;@>|2U5w-tR~I?TP_w)g=m{?(bsJ=;W{q(by^0dAK|y+sO1PtA3G z1VKtXZ%7T_CFR~6Ie6vt)xs-wzZg*+G!1=Rant{-<}&pMx9up!_^=Gxfo?-_+X;V} zba9lX%WvwLskbiEGX1<_j1ww;$|PIrU}Ay9szN_*?n>rvukr`}$%Qz2Y; z_Vd;(^`bUn+<3p4Wi{YfTC{caD2~o&hN>^ND{qw@8i^^_o0+OOC?Y|uhGg^yIq_wY zNROfYE)Hkeu#Ja#=RC{dW@{Zd>QMD(oYyaWGT)P^(BXDvvFfTvO_JI$&GxzPTvOko z&wG?qS;aWyPXG`7u8SNUD~I>gdQ6bmExd43G<`GT+$W1?%U&x8y}B!y(^%hFYm(Uj zwj8S{D*ODUiYe@_OCg6;VGh!Sb2w!9(FZ4jW)Ps^G&x@!)K>XNI7-|3U@s34Y(f3u zU1YK`4b4;A!v0Y9dSYAI_uZM~p9IOzTzT_#>Dmlo##9UJ?ju>3XB5=BlCgF#Cvv=L z1bvB$MGKdEX|0{S>G78y#VOn)ab={`V48Equq`^F_OeNO*6dqe^xak+b2__-Z3)iOjGv~iy;k^I4!63xTW@GPfA?$a_m0X;l#8GPf4J`S{eoGkGPB~Y zmlL&ewa!1sFQ2#2w7qr2l#vOtUX{cy3LKKuL(_-Cbi2BI$xk$UN6S8w>k|LOw{cxa ztHiUFGF#m<05PeLkpiDj@+g4gJ23%_L?YjC#n*) z({6O~NFgSS2$nPNIptUfCcg*RBg3a#t+EA1xZC5U#>?7)yw$tlz&fJA*qe&ea{Tq$ z6y8(F+;La$c=5n5R?KNHy*-uI%W)*EpSCgjln1evBk+fo&f6Vi+mMahfeQ3W$}^lZ zp{O&LE*`qL2FD(lM$=ude3=n$5|qqBR`#O!*~V~hZW|T(+})nV34&5784X6LH&^z) zkFF8nIh#{1#`qo~bu3C-llp=GBZS0Y^ILHNJ8243cJPq*ct8X!_^Vr1aZfO@BGN@E z>HPr6A@hQh0@_oR-D4lvgsLz(WVhG^%UvXpSN0E=ta6YijnoE9@0SJzh8_Mm zU^s|tK4Hu5c%0f;xK#G6OCy{D@jm-w8b;9U@O1XINYyfpAAbpEGU@FJ8rj5p7%istcVLr3S^mWDsQTVt6L^{CN-az|@q; z{?})U$XdrUjM==d51sPT#L|TXiR;ZxbXi8R7NTcZz`}Z$1h)T&*KV6uz!rmB*!=rd zSnK6nF<+7^aCZDVZ(y17jQTJzbJW}G9nL?n$Uz_rBE!-%}a% zx)e)Ck5R~}*k}lQW?!9%2bs_)Iy@RZoTWv&>A4yPX||EcopBqF4(Canfh&>9%XxQK zvVw>E+!f3iN5m?BZY@l9GB|nbO3mI?&Y>Er4HqHM^?BaF7T+J@GA@c&85b!+lG)Xs zd4N)v=Q?>GC)0c8#8Or&!_fA<<}K@hXg_lAE8QHX06qleQtQa}!?72+pO8Wq9 z&_Ya;6!`L7qO5ev#P8L_UTz!NT(KzI(wO+JG6S*lUM<|nio|}FSWLat1dS|i;w&YR zn{Nn}ks{ka_+}?r8qi)>`8D9DkoY5dYe~_0dWahpOn394cWW|HXi$>+TA_^$#)RJ~Tp(vIqkJTu{tj&8rCqT^Ss7)Em;1rtXIf`IUZ4S4R?AE9 zO%fylN!LD$gVL}xY==IT8Rf;7BW*q3DP%7|B-pfxe}pQx1zt1)FjN}55}CMrea zoR+NUpyOSqYY=}zjp^Rn*iWLRC#mI5We!b@ZL8sag~UCgF^X4%%963V$cbUGm(OJc zW1M;pTUX1nP)4?~uG;F7NCu+&Ge`Ai-QXsYGO`{!k1=gz?$p-_?@Ux>kEq3!_Oz6B zamFjGW+Tb`K`o1*8La8hbZ=YtinD=jfs`7y^dM&}b@)`e)*!5ur-KAP4?1=_wo!(@FXU|Z>{V2 zW(Si%p;Tx5-L}5`PqOvRx1PYWn*)~Ye>;-6q$!c6DVJz zU{#cDsK*ii;}_bN)MAn#6n)Q;MDc8Hs;ap5WJDIum<;2%2-Sn_;>~7{5c+}J<3GVN zYY>I74A1)Vac!ICjMUxYX_r@nQIqs@V)mycc3@_ghv_J}=knUqu*FOIVTso@xq^zb z&sq9|;50*(49HpqOf4E&dt@So92>s$&(uNmdLc#ztg}zbThHrH>~{rY((Rw4b<<4X z^mf?(sk-B_+LJWzsIKDe3fc6xmXd=p+;Qm*(J7AXT$45GbCsAFeub~Ba<@7FpCyI3 z)-oyTGcgaDkk4XRad$|}Y}>1oxb9yZK?RQ%=ZxjT1CE9CeT~RXve3Uw+)`_h+tCp zXI}ykhiBty2rv#YYRVdp?n{k%N=2>~y`*2b$I$Ec#&J|E*DfRU+(ZFUDw=JyVC%o! zJugN-?#4*sH+m;_()DySX~o`X)6qL-^&#D+QdVJ%vhkPB%fz%*5f&qSXXYXj&6p#6IXjN-Erux>SUoxwekD$ zeatNId{zH|oiX$C-~-jX*C3i#h(QA($nK292i@_-Go@y)mSyG)6nx>DFp(?7L>mt1 z3?V*2hXhY<57PEMvgFwJswm5D3@4|D#kaYmlz4*?WF%Y#fUUAjjYI}<*N3z`srU{~ zaqHQLi0}sTn0MJGH#MU} z$cf|$LG;)Ifl@|16WeW)+SK6{arY;+{Yq)xO_Y)s#3Y7V0@Y6T(h|w?V9&Z2X4(j; zHrc*clB@tAP}YeRu7Wk<{8!8*q#Nz88t-<0wTy7L4QR5LEZ0RW#vm^G7wib(g=~Rq z!@}0VY*&Ta(h&-7wy9pzL;hv<*K=mNd>UfMaLjoh+ZGRQO&!Fj%(MS78<6O!|A$Hw z8Afxst~T~7Ld=8!5_ZBo|M~D}95L1*Mn|wUis@OMEh-!|Dob+JPP@qT(t4EJH9|)XrCqUgYaO0|vSIJ%JI@q@#e7t+|}(qn9PM*QQSrvGkDaZ*9RCW!4M5 zi}sQ4KSgbblJPBj7)oz>-G0C((8TL$pu3P2u{OrI(Ek4H{6701jPJ9PL`ZJ7%91b@ zGOKW0vdDF7zSUo`swnS|rN3Q`nNSEMDqns(10Phky+I;CpQpi}=AB*_(h?$Rry@Jq z5ngQ@wr<&Lx$3~~v;s3|7q}5Jo?a_1E2_Ip5-RhUWV5bM-giMwlE%{7>+kOq|AoTz}5T_(3XSt!OZ39*9uq15lyBc2)W6AcmK+b@{~Zmd#7Cr^;H-*p7b8gc(j zZ7GWff1}g&LI?z&upS-|_k5&AIb^@Wj?Gp_2RGQ)&#Z|mZ#&QTohqSAbRDKJCvV3w z<4L>UGwQc9n?lTFKq@l3Ve2O3<<^TRpA-7S_rn(f#o8X?uh53tx*;qHK9j@Kr}MH& z>pxw3Z&b{tWDrrmKVVt?O0K#ZxIOim{uz(57ZCZ?_Rf8loAANXJ9;GTrFAn;8m}~j z)mONxCWaOmEEEo0eg;m?6sOeGnW-&=499>__ahP@RGJ$oZ$(DnCF3Pn zF$ZOzKa_ak@Cf;uX^&})K{TaLI*-8|*J>8v_YHX?y65Oq@DVMg(TmJCIbAS3Y2rKg zh#ua~`L;eQ2dEVZT@8%2?))*NntnU-5AY(2grDS{Cjv*56mL~&bBmVqW9aehMP&5O z3ga7xK(d8##EHSj>uL@Tt=hW&-HtqdgeO!Q5Esp7ijUTbldNA{ZQ(6R)>;r%tR^XK z*qRxZJqNeUbdOiEIg2LKlNeYwXQZLDEMMH*f>5#S(IXyZMi|{Uy_1@%kr8(MdFu>3 z{%TH(R)m-RO3XuKP!1TnWIJt`*p;y(^t9dPO|RK!_%=jwPu2~Q4dl_BE}ofYJgX-` zIQ-ZhE!j@0Yn(5XI6WxpghbOcA};EG>(Kf}%E-5ogDP;=?gxLG5x-31elSBX z_rFmXcI@e5R&?{d+JmUy=1#Qkcr<1!=daxU48*7%GCsv2WLo%WPQL;cqTq~!M{+#C z<+oY1T)r(Fj0UvY_T)IOVVj1%B#**eE8Ry#2LUB!Npe0mcK$3@L{LC`MMX4KNGw8{ zN5<&tyT#R0>{yAyU2$qyvLaqlNC`OAh(7Lz&+w?a&K+?5j4jD7nA8SK{B~@l@ zv~pIT=K_XJA~ibBT;c-w0*^xQ$~|g!iUpG_e>}_gTa@{5>@iX&lpDBqU)L#VX=-)j zrI8n18HHv>JP^G|-rEQgSqy$>=UT^=WOI>fAxQ)#s<+Zszhmj6t;{4C?iz@$hsvU& zGr;vNxoupo_i|$rj>VW|boQ2>4CJoD0s-@VE%R(6`eNm^ZxXEN$=(z5{#UtF4v-aV zfkn}BR3B4Bl`r?29o-={cSe{Zx<+x+SeWddF7yKF*LCl~=do!Rvs}j4=o+J`_!k%5 z&OnSI@-Pt!=78BGC0X0d9UsuY5^-~ zV%`G8?Q(YpmIukc_unO*{<0P=&GHjXq9TukpBp=E&K*&uKLv{S9_-au zV?c5PXZQ9-P7}SB{-D8(m7dIgQm{V#4NaXRDW-P7I-a#Y+*W$yR)x1}MA&)XrO(kH zzPHyt?n}KQCJt2$X|sAXaWAZ)ker7;K|>Ei7N!EtkSw~-9P?l=#k&vGLBuIfoIn@F zc*T>*7GZKEV_Ghj8?ywQd3wC9YZCE!pzXv5UFK+MQMv14l>X>G$0L?3KfsuaGiE-^ z)so{dV2VWy#{s@6_p&$e6+>}R_ZND25)L|OKEl!LPZMSsF|G)Hl0Sz-lo<0C$4x-f z7mKg{Mh=!htoK65b+p{b?7?`9ouo}eYTJ1x%#Jbqhu!EqC7oWt3>WuWPZb5p8!JEa9K2Ol=*|Ef?S#{WM8y3XuqMUBB8{gmOGygg?_`l2lUpiz# zhvE!-`Z)I5O`fzaz^@@lQ&mT${DI{gI~$R^AP`~k{m1GLdO$e1_~F-Z@NuI-*KkZq zdXW?1lh-DYy(Q0a!az9GO$k_>ChAb&skS66P8)6r2xOju1p#hTK;^)-{0#^PXD|he zGl&xm!XcOdQWFF~ig*f0O%eY}O#`Xv|E8}0=idK=ssEHl_`3##KpD7SfpWj%z5#)% zfO=K|^@RXeNC*h$MlaBk-Wx!h*n5E1^{|J5u2HzuBWD-F7q2bMBI{iMMF1`?DRm?b zE;T7`HxQAX`en_?)a=aE%+%D(3~-&E9ICMk2jMV&0Y31B@hu3{orDE_3H`H>S3qHv zVOY?4G!|3|q!A(58>mn%dClN8EcX28X$TfH2;Bbu220u_#Kz9X!6DFrU0Yr|e1ipj z2QnsuvE++rSy{L`D?w`R}oJl62Sxi5Iu@ugnB11<9D`f&a=6mBkO&ym( zSezeBKvO4zuoNd!9B&WT*5@YuImP?iYMSPOS0@;Ly$a-#uZwWh?5wRXjuvw97BpuA zbpSGfH-7|S$#%rqbNAQQ=f5X%@)hS!ga9A?{T@&x$rEn1_1(>-A!PyioXOC?b0&hZ zH=0=ZbQ(rKY6vpDTzmT~<5xZ2V6TU<@No%p2{PYznf`tIcjZH{*E3~#I5{OALtYVk z{O3DB38d%iJ1gZesi~XgH)QGDe;58|i^wq>E9(;-ZLlBM?fYU6=wAO_XP}=54pzUn z)MWuJyLMP1G5<0E@N zSyDuUK%|i*Akv=y%P2Yd2TImMjSY<6tYESG!`uHrN!R`7=7tvL_uJ6D?L9yLfs#2z zj~A{&1VP4b_0F!-}SMe(UgvoS% zPV`p*CL5Y|dYs$;fXTPQK>#K{RsIE&BLF6+WB+f%gX`OT6JOI(BF4WB> z0+A`v2_63vDEk(nZw`Ku6YuZ`c+8A9lm7*jMLXBB-$2QAwV-6-$^0i!P&U39zkw3t z_k@Zk<6l5|k@9p20Lp-F9tUT}f5!J0P(EA5J*ymiuN(V<;r%~>66KuhY~z^gsQC0x z{QM>-08qZ*a@+d661iz^&+7A^5B&m47dZ%oOGeIKST0m!{V$-LGJ!xhSXg*7us;n8 zJ1zeOlpqi>3ky#M0F<48^lr<40ws)^nI{7P%Bp^v1IIss633Vc00pJN_Uq}t>B%wx zl#~BEK(VtC6#?P8kw@z3sFPl2xDG7fq?#Hkk3k@OAc+qmA^W`2NLfpFY`r5sc~ z#DoI=Q2`ri+G=Zq_<%GK2q)a`_X{|{e+`&+df64## z!~a0=zsc}FO7K65_`l`g|5MAN$QFLntWyqML(Zj#Y|Gb=F~Tz`GySZqeDrNSMV_qO)`wyl~zwEv5?lEsAFDTlcT)d%wsUu$M4mB9O|PYEdFJ^8sUpD zONJqN0%YYzKMJ#?X7+f$&iC)D0IF^vs-m4;lE0_xAi2>*eO5P98MHnD>z+%-6O|V ziiWTA&r;IV9jIXxP)`ie4DLqV{W?DKLIW{wh}T+{T;-6_`U%+ZXIM*PxhnnDK$QCm zy7=g7K%lF0w%XlzRXT-hls7ozgF2b;lDnzaI{iwVgq6Aq0){NQ%rMZJ7n;8c*nt!p z)VU}Ym-*iG*sty11=lV|xydX1r0^Lya!XTBkeuK>IF2?jGB!uWA3jfiB;-6gz5Fcu zQQRBGALQ`f6~ho0l($pOZ5 zgxr_L0sH-G15;gT-ioExmg*TpU)`k6l~fe(rs%<1Q{ACAZ;~S4!=CMid*=_mqIQX+ z&r)*`QF8i*g$B6d=M0a%&v#Ifr(;Qqjpb$4C;cYf>bd!J+5h37EO#h*7~R3kA4+f_ zX|qToeg^IP9KC6F=*ASuIL|Jr0mo@oY3-Fr37WKPZf|)N99C~YwJK^^ELKh>z>Q!` zHA$m~iusQs*`ZsgsM^Ljuu+EMLE%A5T*AH4{y1MX-RR+|(V4A- z8nm8cA1hD&1P7=+gfOzX3Iq1j;Kl^*(GTU6^A%fC&$M^6B(<$)*`9;*S)6En?l=~@Hb(#xJ(GwZ zIS?ECAAVk3O^Gy7D!Xs zN9!ruQfecsT^K7t$?9R~Z#`kK?x}DnYqB~)xvDDjL*J7=bw+-I3UvZ8$@OPtj~(Fs znX#F_C#Ed}E9Xq3wEDw6q<{FpX#?!U= z{DM7zGWAf^)Q%QKwt+2b;ni)6r&(K%zy>d|Yd0j#@0x_l8_EwfNI{an#qnRtVUuuu zhFb;ByuE#3Hzi*H2U#mb^3YCs@0~oA6@2doTtxVilB+p@N1F-UM8xl4)*CSpD>leFv9<{I&k!Dn zt^8n8sJm$1HcG?f`*U1~dw~B?{pz`^e2jq5glyxooH^m!TNCLSY8l(UAKF&$^3K|< z#=DKm$GV3zpUPaKYY;NFUdi-K`Q=wXX^*A!WCvt|jt=u#&i377tHPIX*#q9W zxXYF-S;cs8PN&(F7NdGHt!F6rbVboq$lFzyqUf_b&TVr<{NpkiB}5ij%o8v&Op~g)(9rr}W^k4ujl4RaZ0DP2XJGa8dF55-)qXpZMNEz$yg5}8>U^vGNVP?^x!-Q^ zS?c?~h{Mp!zn5tdFQN^0R$Tu&K^_H+qe;KJk%WMNfaIenwXjj21_oBw!ZRi(yL_uP zt5-%vJ+a}mq-9d-g}a(*Lq$?|SJsONOq|AOS5=n3F6Ud(qPldB2f(~?qdn4z%&{)Q z!b_v)Ygb#tm@R*1N|sf1A1i)^B7^6;u+b*P87qFrgo#<#xEE>XmoiIC;DD%FX>A$x z6Mk)jH>s5%`=2 zqh}~>orOhmf&*4ph57N+J$p!z#46=#?Sb#q$>+k0)Kkux)y6x62tBg_f7hMrxsPr8 zaI$7@3$10VZC_R6YNSVZgnDzMhu^kk@j_Uo-IBMWOXWevr ztq_W3S)BWsdj;-dfBVVxeb2)meSL4*It|#_8Mx;bcp2^`%rh!|EX@r|e(QrL^5v~b zo#fBQ%Y5PC7M@Ie>=Z)Q4>b-$mG={b zM^6x}>roO3!Urcc?4^T9H?;fsb^H02+(_5ppPWaY^l;s(h^#rwS!oUo8E*Uk_jmedGwKLHUm9dOa1nYRF#Bi z=ldR=Tp*H66vO`^>nj|ZZoBulG3f@STR}uZKoAg_q99!=F;b+YyV(dqC6xv#X{BR; z)C7^1lo%kPba##I_u+lN&!fJ-e}J*w=RW5;*SYR<2@l-5#{5WmF|zc1)!ORtJdw;X`o!9PGWPYeC42mlJA$gm+3)N!T)Ozl!ri1A9+oz|v232de{%I>)w~c@ zZse}QCy#)()rL0`b1E{q{Htrr6BY^H+J=T2$%i+lh&1y|bl!a|f+tH(ngMn=zGK(! zbP>y(*LLH1+jzElONp*&<=E232!TPbA3F`jx7zxIcNL5*1d8Xl5pN{FrLGPMmt6no zrf4uei#pozX`JN#)(6~np>EZUt33Iex`(yK@pKOJj%mV`;i9j1y$y$X=HSP{S|uv) zN^k4NX~h|hWH0)3iCZ*wZ?zORI3o_=>N(M$5+eQ*!y=0l7^ z6^+SucdO6%?KO@<*u?^qCp|O%Exgl!ez4d}v;w z-q-vw$Y$~2jNZy@{$`wehcmxXfV$2U@TH7+n#hHxw4%!{=4U_7@b7X=q&e31TF^fk zl2Sf!);JlLU5wbF%VuTRrxY?vTy9NU8FUrO-K5)?&)<5vS(kTJXJ3nH-dl%l*Sl+n z$4ExaP!V{GoVD}IF|4hz%i~??E!~pvuIQty!nwNu20{&XOdTkC#l2a>u7^9Ozc?ft z@*HjsFLvAZk2m`Eba%73Wo@hWrLZ*hj_1T&1D&bdG@_brXAR=&TYuL+a+voeW#BeE3~r*9DL8Nk(FrDVlg`whc(J!FMyyZX3wKY9wN9t#Ha*_0HO&uF!N4o(7FhGl6=X1C*wU0gCm0bh8H*S0P zrOT#!{%G(v2dvx;ByQZ$ijIhIvk*3{-TI}TPiNtqd`a?ol$LX3Y{-;&xW2n|R^n9I z-t8FbPY0-KfoIPXDEq_sV_@&wfS?@k(5X??KXn8!*#03+=R)hBy>>bbNH2Y5Ri|&i zxPria%OS5Gry2P!Inq>28rvB_ws~!`sWa`s(_ndR%jLR}{qnEPmDDD;L%@`PvrOX?9j_kP0}_wtgbzs|hm;*U)mbtD0VI>{Nb z{WN)-&h;KK4BZ@hVB}_2>33; z=YS?Z6j@(v#u<3$qLg>jRuv29C7~=?vfYvX?XPMBncGFrL1*Wiqn3az6(XOWb-uk} z>lI;O{ydVq_=foN(c5`nPnxO%^_r0Cj{fi#w&t1=fxH^fI)jgBxbKZgd4S6G;LCko4r zD@fmaX<~lwQ;6@eMQMV4n@G#L`0@WWNvyPi&U6Vi1wYYEr7I$}8fiq=2BaxQ0GAE_ zMoVtHsZZ|Mw<<#V9F-K;r7_?i8&{=CpGw>VJjq-2_TJ1d1WN7P={uH~r#@2wQELx%;Xz=&!9G(nYC~40qEu?A zQe=J-@M*}Le^#|Wv20hs9=PZDqII6be#c_r$uiHn&7KbN;kDLoWe!9gOXTH_F9j{< zJKMjfXgdxq>84UQD+D!!oKPpNs5jvd zXCqbNsA+;P>-*?-S#hZ7wpihcCKVk{i4#c!4d29&oa$%A{o#*x%GwQmsJOb;xTiZE*-bRk^iGdHa{lb@mUglXyGncG$@VrY}!pT|IZ2&58xqEQMG#rbDNw%cb7nS(u3SiHC}TdW_RK8k^5Mcfi* zD3f@bFN{&X_M`Q^>_t>d?-&%EKuSzY_@7aQWeoBT%tKmE*^@Lpea!`aXOm*|I!NWG z!+t_4Tv4iGx>7B@%_hX8aZ47?Jf4CbV)y>_Mi-DLull1Xw>XL^sm23;(*-(eGhDsQ zWx3GJ$}}pW??v~jRbKO0awb&LHOiXXypQ||XUaoqq;ths$}SWW>&PhC=O*!Iq7qb_ zJw~6A1IYvprh7@Wf)tCPhP0}poAPiyIq8d7tX{1GcK(pv;YI~jia^Vai8o68QT}_% zx&8(ki|`fipt<(E>6@rKeToOwYUyg-EHZ$>mT=k4lf{V+oPHiZ{<=!k`^F$9^?#<7 zmT}0wOJ#Ro!i!yJQfnq%x{J^Eyw>(A?+u(L73(cs(ViFoIpE2yjKU~ja<9$}t7``c z%LjHoYj&ru+9$F$0Fgq2=_R1-VX#Z4?0jqk)PN%w?Gc&TbVD5hr`H#;N9yZ+LzwGY zUlt3`fEbqd@5%9(%iGiCJ+ej2Y>YPJ_W9C$RtgsiGA_n zhrSv$3a9of?;Kkbr9m#zEVCv7xZ_2W2Gh?$m20((fpVYQg8q*WG995UI~ej=rLJvr zBk?;y0ULB5h(Xt$zV98@@_oo_uT`}5lB}lPRw5V0N1pml*T%W);vmpz**jukt75r8Zr9qrhKMa=JamAuY)PZs6BCB(?acJ??GgGj#ei~`Z$0tk)%)8v>I5L26bCz+kgq2=W|$ObaGE^muYZ29}LW|E_@3q48csu2B(5Kttca z0z^Z%=js-+_{yg7h!v@l{fp&PFAs|M3#~>7rXET~j%#aYV^6w5MCFQYh6$K~ba;r6z7LU2k#*n9sl)Pbt#6!`i#WD--R_zJW@m8L@FVC36QnYaLYN|{Ho zyMQU5>0Pnu;epDuFq;{5k}LG&4vp)^wK`7XwJVyqMI*0imUttJl(mHZQhHi!Y^I6& zrf%GvY$Sh^zVBLjyRn@PwzNt_;p73)@3B977*d)bM{-6EzbiL=?Me{8H}P67+s4%! zeWWj$z$@S~O3>(3RmK&_n;fGjajz%>r4%_8t}RZ!aK1}D#sT&nI`z15sgwrya3QGP zpLJ3_aARZ%!MyD`YjO;%9kLl57OP|7-|+>!K1(a2N385gC+vB#Cg!umc*u+2p+E#f z|Jwha$FV$bmF7M&g}Oguf^wKT*#QayUAN#z47|x#yS6oflDE!W2^OMqB(2^o&zA&NQZriuj&fKXo#x6 z{J@|DiE&!!2#X%u8G%Rw~2b>o=RcHr0AQPcGQoB|ExJovWM@A>fCpY_rLx`gLjeP z_srXrmn12(DFDFBjz%cE@%Fif74nz~OTvyPVMs;&eB|kr*fCut_*X342XfmnInU{5 z2>KltHRRj7I!+-dL;;N-EjBiKvD_w9zlg{X$Et9I&dCdh=D+E89KzbdeIk0exE+Uy-W>7q~(PII@rygpk_v#QS6oHK3;EtpO(|NgI)CJc|*y5D5N8hPueAn(B#=br7LE4r!K6wo(?ogUXw$TQ5 zq`v+VgkIx`d67A;>;9Y^%$JETGyYmKUhQ@F5L>f8Z=9;#3`=<7H?MM>It*Vsw)=vJ zpuwYGQ2Z;Wu_OvyB4%V^3C{&T=le7xWD$tcfyKLBaI=4cw1h6Td|DyaY`85dVg1XY zQlDMqRmil|y-dZ2DLkWJEXYZ~`(2kHh^7@UExvm7q56CMr8nnF2LgOMZR?Y|pm~Y8>mrVTZ>sFZQ2=&YTZ+TqHRJPuP||33^*2*FF%z-0GrCs@=5TUReQvE66XH{ zhQLJwHtgHQSXWmsI3OO(^K&7FoYUmB@0>(x& zG|XIBwLgVblU(`UjtbldT;JYJT`KWfrtGI3WL&R#|GY1DuD6S~s~dcaQ=|ZD$jLn1 zr6o-K5_SW_f!A&HYc0OaykGi0{|R^nsu}GNabWvFH-(1!cm;5Gj5TKf9R6e$`!evN z^Zz1QKy1@v52^Q9KS@3Jvv8CJ63^&_YJbW40ewATh?6jgYtO3Q+BRXEQbmkFdl7kh z9Ej$md#N>ew}i)?#R0Nne=(4Ha>`zKHYs#|b|qQ=|%CRmR)+4l6w3UWF zHg?$B9N`yLuD}&hl?!SeVi#JmuYmZAY` ztnjnlW0mU0^y!wL&DY_=_9VE-;@#)xjy)gkEYZ5Eozrb~;;jE%zVi|z0x`I>=t^$_#+#3RrK)HSYexTZ3tM}(|Vy!kL5?NfiVuAEbZ8ame} zMIE0-+p3Z&xR)vyR~RS!O)uv;ym)}2T=i%KfHdf0500At=5MeKkyfI zDgVtrl%dG#yQ7Hxk0$;CxZKIe8>rg`LeVKBMU z51ueGI=B;$X@zpAK7L3RXu~ygZ>TCxHH-SzEyx)z+(NImTJfXCzOG|YW5~WJB?Ue* z@X)6L1wDO0a@4m}q4x@;Rr43CTGi3Up$2jn8TSU=)^Ys(ir69C z#~W=XHuDEnN&_avKlE9S9qrCWo==Rt&_Zan{8Q6`+jZLvvOW$f%%tA2=w362TfuU( zU&c9yzl+sIxIQu=W4W4 zP$6OG4=fy(cza?mfwa@e&v#F4ywc(E{ z9(CxHsN^TU64;?MiU#JKS9$!isa^W(u5ujvC#|BYJh>PQ75YE(0J?S zi!PG_rSXigRqWsve#5ibcWpFaee_3z(`<`Cex^D-_}}2=1O*asmjQ@~%5Nt&!*3PX zj=kgD9g_$iGkt79@OWpjHG$CD19s$Zgd{}24is@+mA|(Ik!w8qJE6Hzr<7 zgf$F56VPJb9}O4rQT;CPNu$r&`dE0-n-48mGg+|!nAx5330PHkwf+%0FaQa;NvEBj zSCO+Fsl|7dKfX<<$!NKstkGsZFPvKaifO>yfNiiY&@4ntxbB$WH8mi92DUR$&esIs zc+3lg?{X&_UY1HX$>*WYjzJ5;AyJ&CuC{MzU(etle@zJ_(|2(avpV|!z?pm{$}0$7?lv62rs9^$)w4Ek0) z*<1b$CZ}5@)=KEaroG%nBd5<7R*NYnZsZ0Uv0+e{h>+8gUg82fT>*Z=xRQ_5*hb6< zjpjHF8{vTQhSEY(aq9lfg9iyX?8)tAv{qyP}RM!Xf4Li#!`%ec!+Uunm)MjBkTAZKi+ zjeI(kHYdj?Q@`(0Wvp`ukG5$vZ;$dUYvVv%|F^XP1&%*Nqe!tcvFUp`)6-Qpv6!y` zNiOJ;YR7t;k&j`y^C0I}q_HFuRuBMoe{o5|G7{g`g8Vq$yDt_?1-T0o&fRgT z0I-aDG<0IrKOGI!M~NL1pbh)n{0VShDJOKfdmPYenr=iMJ%mS|lBRT=$e>TOGQgio4(k+;>4+!n83t=IZjxxq$Y3T`SVizZ*n_xl zs1vgigFnSlhS1s^sBju9D90E-1dM>XULY>y6ygVNXu|vQjROE{5Z#hE+PF$}+5O>W z`6C9wKWl;^7w0?@@OJPt#sV+1_u(FDM(`6%brgtXJ3x;J){bczprLN@M}i3Jo?b)loBH@gVBwpV_88p7g|Nn>VS<&73?TCg zv#_xEhRw6>-#hvZ=Kw^@%57>tFDQ315G^FPQTx-uu=;tt|dZ}6- zY1z9V(!J`OLZX@U&;&Xgg8oUjbj%Nf+rzkIpRw*GWIG*_^E{p76w$#}{Gfi%!y>f@?% zb6;52>%CTFr0u(VkgMQ#_mbo_<3jL$$thsd32fc8u`0WnPQoP0Mx|n^cps;|=Lsy` zknkDjpG<%nHhOK(eRMUu^=}BD*E}fH4z#wi8E{x1?@rjzD>V8D>XyUO?f%Rr6&(Vz zxAcV9e=0|Lv`Z5(uQD#_)z*~9m$1Hz0I3w;utkwK|$faC7gg-ZYKG@sgaq?ythHPt+iQtp6afGy1P+5}_+YZBGM+yC+mKXg(8_XDHHh{9V@are^J>4%tNS>hdeu8>sRi; zQ!zvXRjCQs5u69SB|ucD`^xNeBEfyA1oS`=jem3+e%Wt{mlHv%SDifiP z!?T|lnOl5w-Nc)8cKSj<+p=Dri$$Z&5U<)P-Zk$moc@o31A?3Z6$ee&BUB^dHj3#t zpzWV3GYf`#%N4Cpm3!2PhB3F<8Y?Fj^K_QP`0kZb&ekCHG;{E@FCq5@HH zU=HyPBn>*^+2hG9#OwF#LP+q^Z?z2RTAIbrY(E0gc!}K>r>M8fQCs#0KH%Isf{NQd zQLeNnMAm#146CWPXDI%PnP}>H0+b>dWCFP0e)T}{y3nkg@U+_TZDSh|YGME)KuOlv z+qh5(9lnedDh+;nF3z6X2YgRAMw@a+;NwLG)m`~#a4++Tlm>sG8?`=VxbjCb1tu~v zNNMokrNHO5VGhMzn8|BdLMW2qok_zF(vTvG(%U8V0^=Kfubjwb!P1~moNyTf%*W)5 z3b*mC8}V0-MSPa8#?I}Ut;YKOGBLonx3^E*ttOU?!9|6B*G3>FW?&=*f{pI0Ba-=h zY8W=O41xIRNQ*5+*Z4tTlMJ%@r%Ijr_8qU$=hOLfWud?uHmOi1&}cfz5#nxT*xvho z>t-LC*zH8s<&khj9(>-r%Z~e2+mVe0CB~oJmcPHDVfmMaIY*aXPoZ`zcz2bA>viAg z2|P&KkQfq9%T*8iOE6tFFzU8si=PsV7S~PJjy7fr_3a>zlYJoXv25s|1cNkVeY6Vb zGU;*Qg%7;tv`O&F=?b_;No`;)9{$SX$v>}@*Btbcu(4ltZ%N}lX|P?LeJ-ko0 z#LWF5l=KG;_T~zHa_8pwQYqojjt=)|nu`O8O+t_8$Pdq=KlYKzzfNyCa{SWW`U0P0 z_oa1hK07hS_;&9(m?}RmjfRx}86BX&LawcBz(x4`IkK4^dx#j7hI|5e?uY?g5=AE6 zgCtKvy>^%#-4YM}#*k!gYRYS^uA=kosPEaGSJHAoOKgufBEh}b+H8C^5}xz|A!BQA zaFz{_Wc^DBz?`&Q+;h^oUH{xCkSM>zG7kFJRfd8m4mQ{EJHq&i5$rxt9I6IB-n1R@ zsyCXIu2QSnN!k(?U?IVaw%H+B!^~@m;~-N`MpC*0ko7kRyxhYr4Pgphq4yzhl%0+E z`n0j=cR(1xyz2f4v#^_i$F7hG)z0Jr!2F5yU%|;KvJX`qKkz@da}@ft)k3y;GYw<} zzeJslpA!3aE8AAgoi7*rVZ~YsNG2Txyf&E{4vzR#xj}XR2mH>NBq9W+nT~x`Prki4 z8|i4y5D7te=WLt6BdsTBNbrNO6d$(K^HCx(e#j^MD(jyy6blufIe52tdol0aIi)+7 z4lNC4=KqBnGw5~$`p1Wt(lghv}&KN{`*owO3JS&Io zbg(0Ri(<9$*!*$U2Fy%k?H|&(jQ<%zfJotau&`d)jPBYO=C(t9kc8$U&xwTIXt{*n zDB;$mqZoK{ggg*nOGl>KDonmlwf;hr69sy=Iwu=i+|6{%*SN9XTv06_FaC-*+Xi3V zsM?^z8G;Yv2sm0N#s?DrbuYx^O@S=Ds1L`op-x9w)+3nrH}&8~e2F3^wuGhCi}eW# z-98sb1g(zp+?sY1-3bdKHTaNs885ZcBF*ZC8b_Cv@c?m@=nkS6ezC;a-<{3>0wM5z zpa(p$vH5%=dhdJVgSp_}5D{o+ErWo|aPF8_Qst_YzRM#>R8aLGlYf=HoD#B0UFPLD zoeF`urc`CnLr|6wFIG9%44}d-;AFq)UY(VdU7A;cImp?4iV4dfKos+Q$T`y3me`pd ztHPg%WgPby_$D{-GyK89o?m|8Ck509%^TjLWylE0x1S+YYcy+efy|9Gwi!sEzo?4Be zA{%w{UiuSZ3Vw!iKZ9M9X}2LY+kg|mhw9{sl-J)kwG}o4cm(bc6-PE<)Yl0-Du!H; zUom^}3E->O+2RwM|O>aGA&|vF4*5>KGO=qVo(u`D1wQt@5lKQ9ct0!+ziF&c2Ck zu&rIaT=A&}Nh86`PY(RibKf_ad%|}=|1-k<4>IJW1?CC9I!gp)C*E-5ePBQ}xSeYO zxG-T=ZHx^p&8p}56|_#FzLWGf z95!yU)dQZh4i+nj%+|l~=M3$VoAe=I3&|n9NrjuCLXAlTrd)`zf+WEq0X>xc4?;{F zl9R|Y)xm9M3!Fd^UYJn>^a7_VR3);V2jm*xmX(~jwpLemUp605PBr>^RszUq6IAAo zA7uj&Z|M{6|4FGwP?Y_|!Qw~V(tucZP)HdE>Y9lMahwV`PC+!t6VeaneB?S5l6gzA z)WNIt1By>lW3hYy(cIVR;W>CBTti8Mm33H!)~*3|!{3?z_m77Y+l`gYRsbgF0iTwj zOJgq6CH6E|@0x_Ex)FAyd0uepGuG!Gyv8U-L|iL!i>M@6WlRNjILtA8hX=2GF{p_i z_uYW*nQ)NLd{;d4v94iuwfuiPqHOYTWDI}dyvlH7Cm8O~u>F-x2q0a2ix;?-eEE>; z%>D7&Fc#`HjKs_U*9;rzlQN6A9odIvv;Eu0Ua1RD7K6UBc< z)?A@9n{j#tJK@7scjmR>nsItJ1TUeF{VP|qLG4KKOXobsT^;f4aXKYdW?y=$3U2!Nzgb~d&L ztN6(i6Q`She1!bNnRY-qml`d#z$m!dTM6o!QtJkDtJVj*tEs;n2XS9?=p^m|QNNLT zdXMoPPoh{uV%9Q_7HjdgNp2l7V|+G7pYfIb`84GI1hOM(P)^^S7MH5wzoKJHje7z8 zJp%;@zi|yTYBwOedb_%~hKjhvpjw$B_X^sfTQIDXq#}pD|E#U(=>^{;)}(O_WUAEZ zrkP>jboW^VZqz>x$8S@rRqTM+i`-~YdA<{FF!frI=HjX6mT0m+34$PXPe%& z>sg0YDU>-jcMt9z`Cs|+CtV4GxP~JWAb!7iIP}eRbD7X@3799Y_0NNK$c>Hd`~f+q z7ay{dp51{ULOI{!YY)hYyYe)Q5;^XVAEvA6yO-J(H8!zKPlIF;`v=cljxwTUL4gD_|x^LIe37NM+yzE&Z%-`c3*fME}sT^%m3Ce z>zOwpNDR!{UUZf$X=|(AwhxoA&@kLajxZnB5J{4qkm#nNPGfbQBl8Gu?8^=Oo#R-q zWafg-35}9l0LgI2R1|i_$n?_4c%_v_)6*fA5jB-C`7AGX`$-uZ&O^3eezz>Cz$Af5 z`pRf%0RP5Ieb9Ey2^~|)ZS!c2RLsvb@QwZH3Y!&tr^G&fN8ji8(O&?B`W7)nVh4W; zpjbs+_$8AG;c?CcNC6`q&dBm%_sj0L<{mHrk6!{@lPoX&5dY}XsfG8`1@u{O4?(awRuS^xu3=BbRbY}@V- znGu@IkI`x1XSPbt?QXB!Zw`(9iYmEJ*~wwKm<;X;NtT6PCVpzk1eSG^Uc0*&g#`MQ zc}nnVad;Gx_@ljnhJ8zONrlAh^iRZ5D@PM_7LhRJ^?~dUoE#{B`JCT1Ii6!^_G;>d zmZ(Z)QZc7&OFA)0|^xSe}zc9b?=OyU}i^Nvt&lviQ zy>IW822IjYS!gv>;ks9;EDa7fsXQ^b>^lcz=F@sP?IeGEAefk(B=B6MxQU;dKAW27 z>L@j=t9YFYddpK4taop=9%4<1q!iQN8bw~VJfO)WFin^eBf&4TloFW(maA*CTjqg`bI;S7tf%v49u%gr>yB; zFBN27GR0uxAfN12z)!oK7oUkLZFNNvquK3%_LThK%w|+b&eUh=wXx)WPu&8-qAW~e zhu{CaOpT`>er0hql$DSOoonU{`8~}CG8EV4GQ07L?qWLA>q3q1ZrYK4xk(071`D`D ztodP#sU(>+N`e=z&cAv2mE8%VpUJxAqur!BQ@vwH-QG8GU{eaupZwI$o+l`$ ziM0~{i-1AGu8hyf;eN_}6QdUrwr(%0qR%uomwA=DCBaW8Z+Mc}b{#2^20k1Di_Az~ z{gB8mgy{ICu6)Z-z{()?r-QF%CA#@(8>wuSXhmwc(5EHyjh{q+B?}~y<`!Tk{lmH& zd|BSQe#@Xc>^n(j+L!A+^CW^7h-;P!V){3`I%J((RM0Up^dU^9=f|_vYon_c)Xb!d z&Z?H&v0g_U!>;v2%!%_UqCAPmhVh9#8FF~l2T%Xx>wuxgOLWT%vcAUs5%}(P5E(FR z-6S;)4!<$OShjMmbx1V!vEf(zWcc3i4Y98iNt~pEldV$k0as?aB%5VUn%LYbVBD!o zmCmv9S!H9P_Gi@T*~7n%ABb^I;&bf^P!PKuS46jDAaD5JwE4XGZ*mG z_QCh-K!0c0^JLqfh>Tn_*^L7{@2 z34bZ9_XqWj!}1G>)NvjDyeX zmectMe&dr}R&o@!0w>)=mn_q+jy*xLr8=*Pfs5!e;ny#`q`{XxezF|80iq!`b3uN% z|M)(T+nXgHI2sURUypo3L`z;kM*933#NZWl@b>EnF==T`0lDwXP3x3}XBK}F$mbsk z$kk#wQ0E5g1ASv1IQaz27D|$xw6eZiKO?@SdH!H(X6+N)56?Cl$kc|_46h_+lo>B-_kJZYtIJ%;^TA~*Jsv-M8^114SzLw0gzmwNZw z2DHClo$pR;2R*Yt`4T6;^B`oNwu&6q4v^}8$ch+q7iQLAc_bzBa~;F!@MYQCIL>kT zd6Zg>Gd$%MPjGSXfN|Q+*AYau&2~|=9L`G|PjuPtufAi(nIs}I^6XpckG;Gb{B$*6 zs(VFB?32s8*;BlW%G?UBZ_;ZLp#kIL)cu5u+seUAoDlt&teMhU@k)@aW0R&@jR7+q z%r;0Oueh?D3DkRZR6Bxej;qFF$LqhkKf07 zTzF{#28v-mR#6f8Es;=6pVX;rD__c=`0bD%^J_Uhi1rD?kagTB3j2{PGPUVCI!OMg z6achO*s4kJ>|dAgpK1AI|7_tnIUy+*wi0R@EW|Cr4{MU#A;T%&c9o#GFP_ktG|Q{D z;X4g>;~|LdpfzF5V9U$bpAv?{PSa~)86OxO#v}L9-wk$~eGfOj`urMB7JI6LPpt>0 zR97N!R3mD+5`V^hk{VRP94@aDIt_Pn+}2v)C=Ur?Sq~`#r}e2pgQ$o=L&q2_2n9 zT{duLa;{`_tQM`hVygHFWS3Z8(o4BCmicTEu#YF1Z5k$-fkSw`74oCSUCb%Pz-}Pc z1(yEJJ%EQBuvtgg>)5%tOuUw7BcMH*8o?lXtI8<@6Mx>QajSM0S@-1$SOL7k$?aidkBO zaBgle##AwNum|k+O4iTqJhT#3liK0%&ai&mA^8AWOQQpIA$>j2*zfw34#c~NPc<=f zj-JaRgU`B1W@l&LIm3s^VP{VngpILJ$^Oy+03Ubj8AO8dc-Epj!N~lAyWP0+s3p6t z6f)#AYMr>h{Iim0K3!)T)js(0fPz^Pn3EGs>v}|DebV&&%?rFHHZc#Mc&|BM$AImC zdIVq?3r+Sv=nBdKGMSA0hkrvufJNmzS9UNo0|w8Gl@(R4(UK({76O?R-&2Z!mRzOV*9P7hF7p}3EiOSFE<^K6k#`hE<;b+puf-8RF@ zB0~LA`ya};^LPxD=i_Ah=?<_l;nn15OGqvGQ=j$~z|+B!YdQhEbbs7&qvTieGwzZI zUB(3wYT(F3V4JSW40CD+hhg`!@uGRp0Ma?m9gp> z1I^!GOe7a-*STH#PjVUswe0 z#3*y^W>Ig2J)nBv_9mAocVr1r6S#YBO!5n+rhkjWAIn>G;pb*Q+}X>b%EE4HZh*Z1 z=D5yiV?@z?{u{1V20^?Y96C=YF7?ZRRT*FjYS+i+FOBn#9;t$I)p+MxqGem53%y&% zx2Bq);*BO1%@h0>4s!d`8uNBacgWRSwzx!inA&G8VZ*bJ%_konH6ee0HBjI(XBi;u zH@V>t!Vic?I?6dL7TAAv=@2P@rthL$E3gWRxz3}XpFRFfX(2gkMQZ^}n@O|)x~pa` zstdBF3Ra&DYGlPI4gt+4ImM=arMpBgKw$6A1XFcwhRKGkyr}no_UzZ?`Tvc|q~{P` zv|~BAL#M`mBF_jUJ#VHGUk~)POJh;b*m_M-wYREz_4zubKWJ~T#t@0^Lhqs99gDdt z&?Lp3?3N&6ahI_~SxfZ&(y5pbM4$Pp)9q$=+IQhw90h+3e$Kz3={@XH^Vvjmn!uU) zlYl#RF%=beyD%t%VQWOJ2h=I~!G4+F#>iW%UPw~ZC#{7*U~V;o)>l*Psvx>9N6tHJ zONh+S=)(706>9IchvS!je9uqwVD7?`L;oU8sFRE#yuR3qI50;4o&<>n^7xC*aRoM= zcQ5r~C5YScTd?^8G0=;+7M-Tq0KgA0YUa*$y@2G!*6+xrYX9`Eo(i2?bLz!QoHgH> zd&!eN|K{K20RJa-Nm77FoRof6OjNQ{a7nPR%d7atj5GMu!=1JV%25aP5^8!$5nq$D zBqaHwmhxH0<->j0+WunV`r+pg{7EQ_12Muzat)(fG_&IzKS(j^R4Ld!P*meG{z_`&g)Bc6tbU!Q_2dVxCG1QF~w|-H1U}d zqMKALFWKxoS6 zG~SkQWfYTcC>DQ{YzBB}8Q~gcM~71u19NBeLYFRvx?E!&QZvn95u4)6@#E`noeDv0 zz8qL;j$9hGS#3681D$uU5)P9EUh@OwpgI;CJOb#q95N&wjRU%_v;K{6V5S&iKpj<# zp+KVu-ii2w(g2jBkz~jn_(Kt|7P_2t4|aSeGG%EruB^%M}veE+@bIOktgf_oTC_k z0`V4j+$J7ZltW%Nye2%}=1K5SEV)rZ+ewHA{7@kqZ+SZ+BbiUcaY3V#DHxgexd>iU zVkNEm+VwM{HI$;dIJeM#y}1v>$iZu`aY>}*Mw_wdxQvuzMKE5ILkkg@sJpHW>6Bu8q;ekBHG8~^7 zkJ%wD7r&($5cZGlF$;nj-`LyQ8XncSRVbnyr*X{;f(BnGL4*W<|GGV_;Mm7acB?p( zqYj>E)iHhfZIdxt+*EP$H;H;F?1#)r=Z@%PGYBp3jj%u%pcrHxPQfAiWDmWpkO1O` z+X&vhQ_`^0r4@pQh5p&O0$=DdxRbloZ(cxg{hhwT8yS1}#^Z9qUVj@`JCY=njILpF z`_PV1&u0CpRN;^rv-Pmg>}&;{H)N-f|f<-FeTaWg0^f3C$HVv9mz1p2w!hnEE~XM5jxFFL7WTVhz;K9sb9A2mk>j-GI>1(H+A1(0%(u1g4cB=~M~(x9lJi zY=y<7V`XN&4X+z{M5t`?>uH-SoLqEb^3eDBAFp6f$G?kRYH5z#(jCmSp{Wi**x+k! z-w~KG+VmOiB*u%mwceum3-$IVqB}Y|lr{mUc=d`7#{QxNVH4xL$Suqs$j$s~We6hH z9wP?s@~h2%1DXJ-^GtdS#1h~dvko|iQIdHAc$FJdQ}v$FV zAKys4{ijX<1PKd7S7w~qb@CqO>PY6*7x@lrDSnqY5uP=<7ogh(B9jG?j;by#5yUWv z1)n#R!DZRm0ssT4e4IgozcHU{47~9_d^=8%ZE)QB<^$h6V&gWz0QD)E>HP_=fd-b6 zB@ocB0LewDHAlIY9qBaDvmnh+U}tv;7X70#AUHd0{a)zO7eJXh)2oiypB&R_i`D(he{s41o@sr6Cgksv0#H>p0eYSl zPB;_LDV|4O_BO&i58eZLx#Huq8^Sg_HuMl^wQNEr@|PIb53jPEB^s@o)dKEEEc-Dw zr*dk^1H()j&*UUrVTXl4BWxo3$@DWs8U!K#`}3T}h#yj+1&p^z?ZMO);V2PLeO^HV zO)u7zGea8^w?|3(pu0~O?4&`KQSKI`!tXo>ee}m^kxSGu5Oj%8N6!&~*}dk8ykiqM z-n-TvRE9$k0{cY%9Pfaj?5W6S^b>`uud1$Oc8g#rHQ^~WE+?6J39wYwM`5bN%E6u~ z=eMXA**ypNYGA03E>3=@MUF9u6-T}byDw{{{PXmA*ND8ukTv5O!^OW*3m_|3zcm|T zHU0$2)n1?;*=t$C?zeTf&UW32*T~9Xrzp3Nw0<^}Mf}z^&m>Vqh?xcfFx$xkKdi9Zz4}<(GUdFytC@B`HMb9!B`#mg#Sf@u z9?E?}eHEdjLbkXK=Yd381o%hwYMr>mK==Qe8USn~H1Kk^^|(v6I_R-78z|)h^;bd} z*-5ty8$Qr9MXx0|q<_;zb4C2+^|7J*=Wzg;DAjX^S~DY2crl%c69%;xh388Q5S-fV zQ?WjFc143Hc={(Mh_ihw3ALZH5Pov9zez2$*%eNv`7_|bveJk9OF}F_Em;Sd^CIU4 zGxO=eC$u0k7yb6ZFQ9_AX24r9Hqa1xt;x2*E-kMhxB#%ex!BV5{<*Jp0}srh7>^i? zO?P|x>+_%UHvp@PT!jiXY_+%+2{n;t7U%#t<><+xO}~z)1}pGL5qK>wO)9SUIyvB6 zk1J=c7C4~)DR1dLRyS;79niC0Q?tV}ILE7H7gpi$IkD=4@_#(J`_D}k(S+K4YF-7$ zaB|3ib4Zm-3T4vN6C8UubnvpT;=p<8$hZr((&v$u=B6{g(mU9iDOW?8+>cyN?=%*X zy7~BPK0cpF(bfi=rPOs(+vN}0>3^u;;JfHO(7R{S-Jc|!^poGaKJKz$Tn39gK*kfw zi~^>pvr3e2;R?&*njiQ z_OUV0z$uy4?IqS3Rsv0-a^-(UVvlPQzE#Tl9@M_03(nGxD!Hr81dzcaRlY~b66a^b zf-x+^eUWylNw8_^Q32Uqizt0HFwDr*3+g{W0NhE?3gGZFZF(w~-wLb<_^r(56nP1~ zTxq>f(d)NysT=e`5AWCws<@qFaUS1Y12^H)QFj|qb&vRfY_s9uVLcUOX;80~Y74byEe( z-p7z21wmrWf4zM{qBCh?dfqdEL@}K`5th=2v64pY+CedquPs1Q>f1?$eEplDs%QG4 z^#C2rz(_w*-6$g4k=J^k8Q+?}j9sJkk3`dK3H`m-m= z?4V9@*@~#+daHM{bCGe`i{UYpAVH3Y%dWSg3a`vS7Kbk>+1%xf)3cThPu__(naF5D z*^4r#67q00qXb12axS+{@_1Y=Di5=|j}hnN<=wak5c!|~p0N=qq3N;qB1V>d;&m1+ zzcQlSA*y;0WTaJTOcy^BajYfn?0y3{3uy`Jl{AoqfWbEHiJDu*kKjf&5NWF_L7?}L zChr4Y$O*wJg4KB3raSzaxQRi`p-b|X@Pr~ZUR}Y~`rJmzmwXoSmZY3Uw7K)PE> zy1QZKJKXR6e%Jdve|tI1nRCu>uf6tKYu|ZatAD|90z}WH1>-_@LqHlj*v!#(z3f$% z&l%{c7*2)m{?7|V&?2GNj(QFH-(`utk6$qBo%6+b=s)eacNP40O(Wc8LPq$%$0$SV zTN~x3gHz|nSq88i2ZUk%_s8o)v(x-*gtpD$w9jw;EzA?`s7Wtj11)SW$ZmzETLHWHFzt(-!-Th zU6eT@N`#xlXC1WnX~dn~ONkuCsh#tVc0XyJ^ch$M;FkZBWy4@@(bCZwj}|6xLDN}j z)}7Ye=(a4lF4YpUaP7ZV`59C=kB32S$oz%Wv49H7TniV!Ta+qr8$5l~uwu@jUgkgp zGIv_#+4Uz(_yyQPxE>=0Aak7mL$waT2olj1(1%BPG0(+%0NrS7){azT>d#Ygkl{f{ z`oy5k^bHbt1rDfIC6`!v3`=JGKFJ80Fxfg(6!oTGF?0Wlry%(jNJ3 zTCpfW%z^)*WC8z9D#mx_Ahq9Oc|U^SUcq3w6FyI(-Q#A-Mo;K91kA)s|NQuHzuA(` z103_dfd8Kh<7>rkm}*%Kq}6HYJw0sqw2LDaee*F z-46gICO`4!W-kPbOvXhxO z#5~YUKV%+eZh9O#DMwi-K6yta0^Sq-nC=COeQ>(N*B79)yCFQRf?hO*_lrlm;p1W- zP`ji#uj|?6oKl#oDppwbx6{4Ai>{QBZzKdGPQGfGGA&=|DgU~X>5YDErC7~&&Cp5nhrl;p*&fz% zSki6oBt-=yl@E}eYBX}1z1&-$znHxY<|{q?QE8}_f66ja$B}v&+{MZP06$NEKt9&^I}Zo2~HK z8GtvQSsj{vKU?BQNA^_32m)#3>Ds_h5?3X`W52~&8PaRAUeBI0+A=E@EdxH_IXSp#(In7(4=EggpMM8^Z;E&D_=z(+U;oInYuNfK^)$G@@$95Cl?6g4)~ zY*kFz){&MT1%nmM=P1mm?%QLfWzZIr_ah#_3sAV-pXgOJ`MM96Um<@wCT7^GqSlyC ze{TuTK+HL9tJyA}G#L(lupCrk;S5ZSbj#>aWMUY0511vm$NiE3+1^|$;rptYfa=+5 zrO6-9jM;{y>0t;sj4Nllg z7fhy5GLNJXrn3#|dG8x%YWwjxqyThw-@$%qbPNOTReUVA@)?wo(4`ObcfSeCgp4 z(=P9Nh4IMsGRvivbPN{uLlV{j>T+#8qgE(&ZD`xAVJZ7c z$>X<3{3eC=^|M|}G>%^Gn5uM+7Z$QWHQU~M<5XnWU9zr4mxoy{pU`7)rP+b~LfPQ1^^D(Liu-{~}&!^!J#;(%Rdhhto)}G%5r@rx7 z4KHHhU?t##++ny{H)=HT165hMn+r1ev;^BV*NSmNqi3!v9y8u6XP)oyj1+jqSK#++ z)_n91Pksed7Y=aaJjze2W@!`7b;&`8LO;>vS{in(`dU9bnna5J@B4%J zdKmY(bNyV$38>W+zXv z+>sf>x2bNgKnf8eO}RgLYKAN5b?AP5RM7HJ#{}P;Gy)_RLfVSVw)y+HBXFPES_8>_Y60@=FL1N$GZ9LE&l`t}iB2I1ERJ5dR#b=NGoZWpX(FeQr=h`1Cx-wDmS1QmvN)J&GvaD(Q#@+B$Fxbcp{ zyVFYvR*`pFj?9&{UdZzQr#f74nENRItgPR1`r=fgm*Tr!J#uXwzPf$;E$OXj_I9)L zOtbw7OJ}bZhPR8>q|dqH#Z_RoF}p1B5C8j%-8L5kEQyeD-esw?1k$F0pM4kFB21uj zG!A&#Uk1fFnBm#z*XNCtzNkl9f#4M@yzZ#Lxxjy;(m&4x47O5OWM6y6A)NFMxBvX3 z+*#2$Q#vdVyph4^o>y3!q(K~S-ga<@6jO{7S9d`HumJiKQSCB-4A{|ZPVxh-clc%S zCM#4dNWUQAxgjQ`XT;D^tEFe<{+YrvBI&ucqFk3_liM9xO@E$F1JrcaO5YD(|@o!HZKN!NQep5`gHbLE5(8iql^1eb!x%68{z!+ z`+5EBMg97gn*VB%5Ovnz5hecj zn+nJq0-xJDX*+1F-Xz6!wNaXa!uI)+o9XQpkpa%xsii#h;6yLsJFKihYw}X4cJtSZ ztMenbL*DBA7A@p#77BE7{7gMaUeO0VnD_pU%wG;6%?oef0>ZS>tN|neP2Bx!?iG`Q zb~>e|FF6-=5`3HE@T;aSO&M;csQUn14^`K{exyu+WbU#AqQ-+z^QGzUK}u>%i`To; zl=;?WIUZW|YU4kX1Lg!~+xc5qwU<4Oqqy2BSfH=KO>i{TZ2>)Yb#L_tBlHjal9Hw0 z=02N5lb?p5PD9qeg$sV;Fvo0nW$4=#662cQ|KBfV&eWGz5XW{H@3|J|B7{;41Inq= zV{;tolD2ZPTGhb28urLr z8sBvu_%!k-kmIK`n?_SdK-$ux#fT+1?^Es;!7H zs%6Hyj!cyLzTmwZ^1!=^`1zdCK@{#ZYUCjG(d)3O1Vpf`-06mkB{49yQHy@p7E*Sjet!mJ(?0vJl`zs13wXX zM*(&FfIfDK-#x&@nfj@gyN}!%`NXIFlUhK&(4^`x=LPnk&Bz}`ie0U$ zA~nvx?Ta~hg2%2DKV#DGm1KV%FD?B#er8{O@o0n9>y&#WGDN}vC+}+n z+iYowU=2qH-Uv(&t>O#Q{Kh4?SFPr^-t|pHXj#Qd*XmnC!aG_malyUYZL+-f>@O&3 z5Hyr3NbA`Xizgw8+deCe!vc9BiK&I_Pp3zwSNzR-3TnElPp}@oHGS1~6D1b-PEX6D zEBKT2UN;AVRyidLNso1X88Eh|98qh0KU2XS!E<}r?7N^M5D~l>h%6(g6|q#VwM+B! z6g!ZdbED*lq6;#xBf%r_Rrg*NT9p+ppnP@D0QKQS$Fj4WlYD8y8 zf~fj2JeK{S=n(}QT2=A20&5Li-@qW(#jf{e(+MYtPm5pxPs<6Z7sv7S6{efkdR7zu z=+?a5q~rQI29<6uytFfx(4?aLj*`~fZ+GYAlW>D4u`psc)Le@R^QZ%s*OTDl+d|uy28wl{Az;o};3C$AN1LuwVcBw7pI@P$`w$_%wM@ z>2VU7#ym_{`pWGsB*%BTz@>Se3a)J9jen1s_?oCt|sVP&t@4JSdE-TJc8k44_A1e6MG&khVBnvLwO{(yg(dS^#O(TQ5JZODn zPFmb+4Y$BDsA&WP5ew{@fk-)Wbq+vXDiUZ~besng-X@i2Q!Vt#0kK5a897i05XYtn zq?@xksEz=4*qY$>_dh9J%?9ET6Vmm}Ezq5;FV2z!zgdAfIN)j+^P!{#!}sK9-xf?C z0>85^E1dsHF;e<;L8uOz=(;Y>$6Nb&hodj6H%P5?%fF~@ax=R(-z9DCt&7nS{bbo3 zhl%u+w~d@`XkI{wtyHmfi1s_Ft8a;=!nifFOgLn4fulSSSxEk*%zmJNkQsDHcF&@7 z+YNRWN$7B#EOA_kgpa!$hg8KbdGK&Q(#{MYOTa_P&@cNPzX|CZ^h&QVhBE=57kX~d z12Q+$TaSfD-;*%t?|`6T5{$GkV4!CfHHMoT=!*RsdN3^ zup!NR+`<{tMbUgI8C87>vuEaTV1qB-g6xV%k^wh~Q$tSs^>mt!!rw!= zEhj_b9FGPwG`HxM^E- zO64mV{W+O6da*co%24RX2+L)RVXv16x7Anr;1-!XPBdGmqm-r@LsC%iYe#D8Wqu>- zrxblG2w$XzNcdr$zyO$?dAwe0e(JoH96OCs|2DtCBF-eG1$Q&ke!x5c!U$<5GQUNb zo9v?gQ|P{?C>m}1ge02R>6VF1tMoq}J_w))i1MC8zeiorIs(6+;2}k@!Vq&iv?~^w zt}PAuTjjbSyGgt7(m(F{#U@ul%V)cTG3$e1qCEKkU6yuU7sM*(q^dOcS05tm%a?4! zPQ4lOVq@CkFG{3^30P>s+3J_NKJFMIM*q`!xJMrQU+cl=lQ1P@0?xeZ1A>+I)u1Lq z_yYz69;w@4P8``2Alm$xrz0e#_+(517q$mpqVH=kHrafiBC<`qlWM5%(a6hZsnXs% zvaPQ-2*C;I=We$2J>~7^b%_>ZQ7g30uk#8E1$$ZGM>ior667}{39v+igaOOXLv?S# znvv%FiyiLgYuO z#_SyoPJy>kzO*~}rvi^=@*jMP_(Kg@c1WEM>f2xgc26O?P=GWf)fy+t zdkav*D>f=H$pl}Gi$_Yd9s)2{H8^WGszT`Z8X1@VXEvCZTifa2Fn{{I~f032)7QWWNQya6_?o^pqJeb5CzA&)!U6hY1IL z*CmGqvSPA&_4xSsisl-KmYr@z5&*P*a0sS9&v*IL=WdQ%J6r4{RmQtLwgO_eVVKew zWqA6hKkPIRB=wwkZ8Hq$iBg0BwjPq$uhE z%2<&rU+2{#h0$U2E6<4VMVX8yGu6QRzP7jbG>;B-ICLUo#C`p6ub`xs#-PBLdr;tS z3kw1c)RB zEYKqjeiu^C>j?`mgv|pybc;ZJPlfP>wMG8f=H0{l^|h|;Ai}2{FupWa%9+T z(Tmq{L_+hyV7)H6`sR$vhMZr_vYf{o&Uj&`NpX6~SI;$1Ze^TkWI*25Htj# z0DW;4c`mHwghLJ`%t)n0#djb&}XcH5BE8b@@G^p!zWd*3hFZq6}ct z)o;P}0|2=e)a3%p+In75Z~Lx8JEIR)CugIdVUbgk)mph_3h6t=kO6Qj!%pOli zepMH^jC=YjBk5Jmhtqokj}OBBSqGo>^*jZy;FU|J&8 zpO91yIYxs(Ku)}T!VdY_n>+q&W!BpK7gGB_*YMb$K3#90vse-WmEcJrgafDKG@mU` zeUH|utjOYjCQHg{V@K9-pfy^TIs^|%4aDw+EC~z%x>X%43al$|mxm@YE6HxFBSvOD zXX9EVp~ZfL&v*6K?|X?Gi(ENp=8isoUIQQ3uRqnxBrkRwTK|K=h@?B5AFk;e+_vS_ zs;9KTCMj|yzb1zU2j%Hf!RXo3@quod+h>6kNRRVAlYSykM2^lGMK{OouCA^aFuVj3 z6ZM*N2@iPz8Q0@f1PDX&Macnc{8^)v6L|JBsSzP}?i*-9{f~_j5Hx`HgXAF4U`T(! zbmJ|kuu1|xKQ`>wUm_@2!x0I09jPN|Mc9p6?%pHSJ|nAfVGr43$YlB`F{MTiha%0p z2BjZxus#Sxk3IK|0MkXKycI|gh~-8ItF#X#8!{3dXYqg;VtaY9&t~_TO!^A}a1a0C z?tHe)o}Ei964MdW56tziX+)6$nM4>xApCA;IuWZ0K;Ri`sZY{Re#?w4oz6c8o2S)f zz@x+oBpE#W8~2hqeS6-zTf?v`PT;71@fvn1!4O^dA9UlIXr>>i%}Utx<>Ht}DjC1A zDN)Hlzg&=Jir}tjnO-jy<*00UetOco*UqBTc-kryT0YAzlE(8;F#&g3|4x8dD09n^ zxnmY)ZLN?FK3oZBMtMt0I!TGB9=;6zcNuoeX606;5QE;2@~H&`Ccw{#OQJ~h2|g^F zUG@tZK!TS?)`4VIFL4ZvM@4#DBlD{!&u&OB{u2oE97iYpuIVh zygBc0wCE+J{Nzqd8-zj)qYb%6&#S#4T}_?JfH}gt{U(sG?XkCp`dI%oaII3tW1Vse zOrx_rHzwg~`z&k(xPUplhgW-1sQW#0Wx=svk0KrbTr8&JkxHS*NeezuSMzPlV@20x zkNLym!>M(*b%hE(eg5EMa@8d7fOTv9@Vgld*wqOlAPM{Z?6oYB1=cOX>wHfc9?i^> zO9lI-aP4qqe6tWCDfo^K$xp2Z1+t9#j6QpR<2+C{UoRI%5&@@(k!3vnB|N}N>58Q~ z0RY}@QqVruutm(t<}Ti;P}8yzx^lSh|)Y;kUhL^VIdeJ^29 zNRI1VivC2anSfKTdmpP2Dvi9sxX%iwRYCVOU=|Qb5PN3AY8n34`8%_WCg`)W(!_ygYfx(OnBO28AO8X~)pP_z0j-A@kfF%i#G-9!vp&P%= zQw{#E!6BF!9XSoK2fg8pzR6Q*KNO(qw?YUsgr~3xUO$Iq@afiVl=z8L!Bw^fupB+0abi4LbB9$Bzgs;2E-*r*7tjVixq3#B~ z?>s@B!pK#!wA;%BJu#ik)Vpa*p0P>!2m}Oaxa&7!teGX%u4<4(#mxU{Zs79>?t>1_ zK)MqQTMhh}4w;jJ=zD;Ys+UE)i&5Zrrd0#XSSx4!?_HC_Z4MV~UKmM#b+ws8PBF90 zT_$62!Ksul48i_C9hGFC-&J{u)8 z5c3>fJlRM>f(CsljwFC33-FW4QROLv#LNCA>SlnHNyc4>-n@uQJ9%~gk?-ATs2MyI zz|cHPl$2Xeu!27VczJmbv$*80DknzqlZ>3qBLfoMf0%n2Zauld1x0sT#Ki?7+u*~a zql0HFX*$>WtZjY|B{w~H2gJ9R?Q&K!7K~H0uvcH(j8^fL@?6(j|8EvRdRH{Z>gorf z_{0!z@mm*~O167zjZfR@fw`#DOI3#_ns7Q+Yt}Dx>1>>|ke3hRv~x*r2%y36 zV7#gvl6)nTbc`#wiiil^Dk0(mgj%*|?N$rp z-kscFgCSoGE!_Ij#iD>j{Go^JDpPl-x_;f+mH+)|zy%p5lPR$E@gH-ljO~bd0mdr# z{zf7k@|lB2DG5kQq>#v}X~J`aIbX_}Xpm z9vqJj@=D$S93jXEmGXHPtDKPU#M7k5LKO#W{Yk0j+zYpPPrw?2U<|+~rndj`Yfkys zs`UQ)>|nZBA=M7n*qq1IEehQ_06kvHp$suSVf|A6GUkG4Hx%9{?Y7)q_tEKvt_4<$ zEm2;E9rlOiSoHNCE5@X6YaS1v$)=Rc22qh9*<$_^StX8}PV+E?BG8U)w0N2wZtYKw zV7+1=b@vsDL*(1f-{^F09dEl$dPL>vN!~6-3|QvlqdnIXVv5qvjm5cH$()Ce;LG1Ak@9kO29DcnF zUca~Zn_>;j)lpOK|MQX_{I>7)*vfBdp%s0eijF}QFqU?!)ED-z>3pOh*2}Y&Ga6qM zVkS$eD^s!`zQVgcXVI9ugIdlHHl=*-Ff#M| z5(&m(qw9m-IL`W_NViTXJ(%yyNRhAIfh$u69Q%=`f9GmIPLs;Wtccw|=oVW85kucu zl>!0fvON67y8*Re;N4!Tb=-gwIwf@>dgz`=E7{2KaL!+8MuQ`G3h99Z_;2lBmU(WZxxZQ>6v7UhyS8t;A=_wI zUv9os+b^e08Ez92%w9UcTE}J~C}0m@kofj_b)c#;1A_ib^hq0Bo`NPo6B80c%yDG? z8fLFj{#u8iFGPQF=Lp6&fzOtkz8U#-RBUBTm%?+> z&keQXZj`QHy>YVa&D5~EsIfVmk&Rz^yGM3^7x257n(aNS>LKCjM!CVM{QdmcRf*$_ za^Kyg_og_S!F4v9#pZ+O4CGn>SQnvljO%Xby~W5c0HQI{Bm7y*E?$BHzY*ZSX83lEHf4aYi9Yj41Pef(^={XeAm3*Ubbyzy3 z`w9k8NcV>AH(gdv*&#?84{3(KY1tf5#8L}FLxs#LzrXi%GS;~#ng4BTBW|$bZn*tM zCw`gl23Mu&6G^a^-%^||-x^4pbf1j}*-jOzFQ&Q4vsU>kDo}Z^c2FMkUi=FSY>#f+3UQ$5>X%bTSF@Inv~%P=4HidFGNmGj{WQ}8_oS) z8R~nAI=_g3663Pts4SYB&(%dPHgzJ#iC7g%=^p`%PQbMGK0gBSUW|Cx-3Tkv9LPuW z;O~>S=PWI2^4s%x=3rcZNli`76ZTJ`B?1pW_5hY3{T2aI*7gK*fvRYGKp6fR29bv& zw@}T&ME*6_(-lG?>KktcZ}Wd>Q!{#O1)mG{KdE>zS>i7}!k?y=)OZ;xu}5`uU6$6X zX5l}r(?|33#fkcciSe?{^ z07mT6*E9Lm=Cns+8P#t@6A0d`>yPYA_GX`T<@gM=m%TbpD)SgI@_hR#!Tf#9c-^j5 z^OBZR%}M4qA&U}%bgltpJqfN$%JWjR$Bky!wTA~-O3F5(Hx(YdhV2SQ5$OduJ6Mf`pOu*w00Z2TU9 zNIV!~U1)3utA@fsT35vr9%#sMy?E02TS|pG(&GiZ*X>_3d#Gfym~}%Gjt!g&@?2~ zG_c3yF5-ay!YK%FS%CA{**ucDxRORdN>c~C5FWL_Xe2R&o{BcdaG#q4ri{nRkuWG3 zDErL{I!6VoN*T{hYkh$m&eWvoBJ!B8uv(r~qy(_SImZGfW%fIsu?*l1vZo9%F11~X zJ#!w(0f>O;9E4VZ|iT}dx_pO4Za!gIM0_)jBjag zNQ1OZKcgbuu-E~aM(i8C^&ynwYJbLYoWRpi9bA3voH*cjEXqm^LDO)7KiaYC_1X_{ z%ip2(e2Tnlp8by)k2l*X`5egy;RCmcRo`4p-Y#2S7_*;9(ouf%%{$dt;GX#9>&~n7 zX8mL7e;dPYzcq#{>`;;Sbxq7lT_YQWH}}m3o8z&{T{Av1+|J9O$>iJGQ1%emZ!({I zHG}dG*BQdyuFDOga0K$Y@e$5ykavPizCyjK&N#6bU>clkwDj)Q^c;l73a=W?Ko4mjoU=&OtAF#)_(eHXhg z_@Xu>9HGC{$uTyce<9O@{YPvA9ut_JY-)x-0T5P%Xv~Oj>yw{0Y&QU6!e`5AlBkd0 z0ec0Yvuj*=&Irssl;aCx%lyEq`xx%Bc+=9kMEdCg*3Pv3<5aFRgU~D<8*FxR!nr?? z1{b}POSyG=)o!LLODY`z(y@kRjxVc3>bKBuSdap2voy9;U7s236! zdU!)oqJz@2Kkb?%q@e5oJThfUPYm}geK(jIAchQoXw-ZEy7g2H?|U=APRXiSubb65 z4~t$4B>?c)H4yfpNGB%&kTU$Z+?O_6%p1EBBvkXI=B6||<>VvwFkQcqaQRFXJ(dgs zO}X&F;V>V;P|o7nJ4QJ!L7CH@iBtCyHSLPL-P;kK@rWJ z|BQ|^Bhf~9=&RI`g~hZUz$Gk-xEXln2^JkEsT+%{4iXP@R=N|v>zv1Qb2PpEnv}~4 z1tOF&b!8tZ@B)XQNzO!%hi(_TivyvOLVL?2(~ovuJ+Z}pxC?+Sfqp${L^dP%(BB2{2+}w^;^!( zpff_@e-!CF6(Ri102EBWW>(+R*gSl;G#7yB4`TU8xiMMpc>Q`*RhmOFmoYu`!0#mq z#XOy4sYiQ{PPJCaVd?ch0I-K;1?;ulUEcxY#k$58N&es=USY*%=vXoV1F(?4+h5P@ z9O7G{z)=7i-Q~n82_jmgJnpP-?F0Ag1@x=oH{0Jm4e-LLk5U+n20o*35nC5H<1$D7 zvUdXhM?%4Qd?A#Z?O3kK<5eSj%|G@H{XVn@vrz+wwSwI_ei9L^UX5VfBA=OVZa2m*kEBA{dxUihd%MK50LK62^V*W=(IBR4Q=KWmSGR^W%@6 zpr;8zIVyb1#PTH+FhGSHP+DBDtmx8;7zVjs0WN2F`88gaYl?UHXkZPBa~<4iKioi1 zbzUH1hqM;kH=H%qz!n)TKls$hPs2>RAx%Q)TnZHv{Ygv___#kO)~LpG&irR9e21^5 z!WOUIt=*f>;*-;NGf)8PeswfP$j;G?VjWjp8_rrG%kenrN?eeKtw6RUNpIRtjO-;A38u7>`-?Ub~(HPttt z7>r|h)fsz7+@cv~mPfrjOY;ADy9lGZm5EC+_g;vHCk)6ZxM3?~d=9>MK4 z-VeLHO*K{&cG`%|yap8sz@e?{SC;IiCRWAiCPvsjw7Nm=d>JfYJ&9-H#~ zX+y$tp3}zyhsS+=79_72&x4c9ZwZ6*`HuwT%kmrvicZ7dwrJPOaC($Q!Us&nzEkaG z^AyxSr0=kFH!?r{kMcniOvwYrmvL{OyUCiJW*5<2#rlH1CIw)coq&23&S(?17D5LQ zL%|sZ+BydF_CY6e!23YT6XU58b9mHMBYrkb_aSAQ0tk{*~T3cst=CkGOm;!b{m%W1ets6!y`k^+uE4*99_5Y-LV`{4VT z!vpwujRLH;Z~scvJbSH>K8&b3U(YKy8rO|49L9z(F0$~BxTQ5DCH~gT^%>yK_{a78 zAP5tA#20J65)*<8@pO6~lcqt-JVFJf&6=XE-dkwb^OGe_qu2S*R9aAz??PUE>->_8 z_+2`WgG7^s`3hU#W39~_rNMZ*6l_SK|A(dsD;j}%!Sr(dWr-?U28ORw1}2{xFh{jJ z9YfN`etNM>8LD}C>^@{4|YQV-M)}CjlW`jG3F%bMG(=J2>~uA zRceKTa#uS4T&PN|SsZH^qd+u;6bF6*MHWWt*}84r^3sp_G?M@q5g3eGv$|ik-0Fx% zTUWUX;s@fSJJeC@&i|fQckpK77Ot1E506y7v=Lr|_f!VI}KsQwGVxvI(K+)&*V(d!#aNv5*3a$c6q*qJ8_0RX(qa%Zu|9MthU_~;1?H{|ZYOE>2 zY{gyiB9tjGK&aw3Rsp@P~N zAI0?wLUlDyOH-Z86ND5@RvE<8fbEO{qV?m#m78v@rRi~ipunDF0e)ew!rooQL zc{NY&^xM;1rN$sd7Vb^RsQ)E>4{BS|f-J`E92|js0~5Iu2uK;#!4@{_)pX6Ba%2v? z`BiaUU9!|eL`ei|tEI>ZPJk;+HufRcolojK_jW)DD1|=B9v)tECKxX|u)oyh0B%4% z1Pft5n5gL1&>&3sx58FLtMS5;-erGj*zT|7L~xC8)K z(nRE>vdpQ&CL@yLcamCq3#L&oUnP5)f&SH_2@i3P*%L~W+C!U`*sGWz1dw}zH9Ftn zmxTpD7153HO=QO1Cm2HXueA_8_t?G6cX;P?sW^lE8$iO?e#MX$=g9}O`lGkdxGZT! z;HNP9FTqzT>M}s?a<_%{0-T3EDSPAqR z=0Q^$Mat{43m!>t#qOdta2?teI!4o#EYwl>yQJ)thhr`%VnJZEK-M zq+Y?3hgDLhG5s61_5O0;b_ea%1#1~J93ranV3O(uDSja_PV>?We zg)hu@3MxY!KoyU;Rolmp=PDVGylb_^_vKMq1u{k|7BXPe%5*dF&Q!L_yVtsDj2M1#Ulsh0xe-Vdb z=6$a4!OUaC;1JBNiXfGm12Q{VVzmV?JXZSy=Az-GAaw!?~4cM67pwwt#Gp*rZdY(fj~-vOwxe<2Ac&ARLD#uvw10>?X62W#@K zKg5Hzxkp1s<%VN*?otEk^|siN`pXW|fPbep$xH;sC!_ShL-mCZ_uEVWYH&0zyMEsS zSjdMU+#Z5c4pNE`BB1iaK~z`eX%Op!4>#Zc_@^=l&IU6;3=vX;ag~%;5}4F~FQY2> zLFjx;=~`LSwG^!ti9g?yXqT!13i9V>#LY42KpSiT z8+$S9PoxA9?!wi?73^<^KsS|+j{KGQRXgfZO@dQtqjr19;c!_Xd+4}aQ;C7&X0xm3 z3olw!YRkjy5(1=$Rssin>peWSGAi<*zSp2#Jo!0i>TP9n&gVf7!44KAdj>s67w>2E ze-Sg+p+yRx>}C+msNasH#K->e8(sQLc&(ahDsl4_#VgwR5_7{J(>7wmYnM&EEvB7v zdT7>)SsX&WQBt~X@R?P26aLI|!X`s-FP#{r>g0P!?D6p}LI@Nft+X63P++gMbJPMR z%5P@8xk>0mf21d3-vctuI2m^FVp5nVjwG#?Jb?uUQD7d;6=Wnf7|sX0)2(ih99-syQXQ zw<=m|jZ%+{yEd6}w&fTnh`Y{|CMNeu4t{+!OB<4#k97w3f9UA~{kRN|!YNH=;Cg-o z6j;zi={^X73~LQ@wGxrv(yVlseqFw2d^GDRhv-~h%DdWf0%wUxSJqw7mN`f)RELtSedm_KsPA6txWea6re%ieGmepD;vZDbMwPalN)%0?9P?`wUX&*Li z#8tK+%ZpQ~3TkDW*E*3MoDY9&cT zysBBt;^8;$v6y(OGoW^YN?U*96xE&lHA%f_Ap2S>ZC_|ScP>^$rH97Moo(5xtgK{H zWmJpfe}_Z9Dynu86G7y5-F2=~y!lF3!IdMt{<$FKef;^hCVyo5`xiaj#=?*}9-yX3 zQ0Pad+N;8WGcrbL`?p$unmc3#U+T`}ys`_1SSL+zN%C##dIXMXf(>;EyGzgAvEZ6A zi})*W%T?=zP=P^qs(zEjbhCOR_NeH~SNZ$rN&4YrR)tv(%?HBbkY??d+bW>-cFcgb z30#VHZ*yMsTcgdyiujhD+4qzrL%U(Q8xf#Hs}ZosobvB$lu5d5BXt}e{O-v8-D>}d zS!FrvbFj4D_;?7)&;@*`9>@utOZg=8pU4UO^Tl?G;`U0Fuc(VuBlp||3I&i1PLWV2P$DH>7e<| zDmrp!*7kYeU{z!Io5w}}s#?HqfUL=Y8H??kC4&Etr?(7?s{7)G&kO?$ASH;Tbcu9> z(%mf~CEX|?NDb{xBV7X0B`r!Lf{Gvw3X&4iAf5B<`9JUTe)ID3!|}}7Yp?aIH4e7s zNt(8Lb7B-5idAd*cu%ZdV1Db+m+&w50v-(Iil<-#mplyTcgq%h7^Aatb6O6rZ_(PU zg&ds@1rxRZL0_}J)m{%!Uy-_nc-=foDzWpkfg_GJ3UkZ~yYDM_MWEJv7)aKOGheO+ z9DVD&A6{h5lF01SYme-NUxS6Iq?y!Cg zGl|f1v7^|l0V|4D{iu^j>~fPe(qX0G05p=p-k(X8M}U$e zUp1r2Eg0mcR2rWwob`*!)rV?J`XRU&yN8-_C?pl%79~i;%m?f}Y6aV{|0N9Io(4yY z4CcK#^|uuW1tQMB-30DGik%8X$^vsD4+kC_7VM63Vgb3Vx=(7ZY{p2otLde?V^c4~ z1346*&Yf&)rh+2qFaIL?*6ARDiDz6Vm{{%D;$Jzn5a|JkX3YAjDd~)_j3pD!_CK%|I|{XW29x3N=KIGv_>ifz2T@Q+47ryfU?Z<7 z2q8g_CkP0~^D~AfB{)ITHoy($Gzp_A-dJyMZaN>wQD)wwhuj0S%|6~i;8TZU8g%!z zo%bVCo+FAa|E9xE|J<3;F(G@u!!kMLTAY37(CP54w&PYMZ-u+^`1`VJNyCxrb)vWP zdHTI**+|;3ey}MUJ>aLMOdr&wC*F0?Ps8|Z_=9DI@L)3q>aHcy7HkEBXJeGaFE=aZ zD|6?E1J)ilZ4a?Om#`n{!3o-tlx-84-7D*2HN8j2eQdvO=192tVvtQTIRrO#wuL-u zL)`}Bgo!U?veQ-UJ`eWE3XXt%w&oaqeEn)XdF&^myRx?S#do?lYTN`fFW#F>KC_Ib^oVoU~y0amY2ESUdO91Ic@h9 zY*2qRZbDPrWFIjz7Tcp!c#cyQ4k^N#PD4)f3pL$;3Ee#J7yZEU2kAW%g5SLTut&^X z8X=t@Ojl!Z6qnDF>>}y7qB#+O=3*A*%}Qb@ApHquSGBdEe*UV|#Rh~6j3oJPG#m>xR6tfJ=E*2x)k4Ie0jwFn2s0n9>_xgmP z;4RdR$KV2k^!d;fgODHD7a+)IMJ(#vtyf?ot*xk#mAslstfxm&=D7*Yi-0nNAOm>yHXi;gg(~fW#Nww+% zW~0WUBYUdWQu_)Wd4|4qygQdet1Q`?wL-;E2U>yEMAq=qLeZYKz_ly~1LOV?To+rE z)Sph-{d&^lrc_}Hiq0z;j`6_sA~>zcL-H|JZK0{RWXF^pq0hb!YmZ*cnE~8{=zh#8 z5VO7Yi&tzzA|d1NZnV5Qc#s(G_}=`XM>@+TOeYND!L`W;SC$9@^0S}6kH_uuTk`HM zt6iu}@XeMz|I#a8L$T%0DXjV*a2so%|E%|9fiSW!uJ_ixQIzUEPxpzt$7;n+bxon% zjCzF!Jk$_rP_F>DC9?Z~UgOCppoNvlT3#I`%K1-h%TnvS$OCEda)Xsx>WLW9LO0bW z3jK$qRDsi43X_ulZy{;R|M*@28{xz2nJ2_sF2F6vq9E|ouw&|Rmj+D;e_FX_m4=zR zq%_i7YTvE0oOY`$w*EbV^v9I+K;K&am*;FOa;U&A7*!W1BD2K=q}#+6eX!ua4s6X| zT=>rvSwI;AL<5P%yM?gs=&}#fx1>XaXTLpqke+)b8rhitT-Wt5+(^)^5VjZ(ht?MA zZ5U5nD_*|%J0k1fK2hu^Zx(n#Tt+#7S5S_2v1Q@4MUYtVR0{#6mg1Xp%bSzN(994k z5$jJ8U-=8HJHB&_^%2LFi>qw^YGl7&KwswztbY}@|Gwa#K%vpeJKcLhJsi{bH;HTa z-{cqVKOuFHjGh?M^=ezCA*HRC@lDj`j~eyZnDZ}see5#XcXnkU!P7K7IBqSt3J(IRJ9h^X7poMP6gHB)7 zv&8xdW*j`)H=2RIn!t_vb4;9|#Uo(nSkC2LmH@p-4--VQSy@@Bv$hbhZ4yZBuL(*3 zsrmVQtPooKgdts#TG*NV5ip6F=p?=S#Q;qP_%SCuHSG)($7o?n!Thl1{W2)=n&Ox~ z#6;`Mk>t;q7id|__HKzw#^OXvhRqpH#3#AeGdqV~&MkZBm0NhTS|fuQTBUB2hh8G~ zJh(t;_2ezLja>{Rh`tv8Ev|LEb*{&Ly`5?d>X$w0zSncl3qSWkTI%M*Wdy?*?+!2!9VYhB#l2f==bL}xWvju0P$daBS`1~MjDchMg7zC@?7p$T-M4b8_u|aSds43XPX1XvN%wPur>S_TtPSKHSq5oj zAjmLMGZc>-CI0yDakA0%0^bXqpqtOU@!Z!S3rJ8&9eJ)?5EM{S|F_GA=p_R=%O{ze zo71ISU(x1>NOWM5(NOM~fzSN+LX_y$KS}wlFP4@prVUKwV{)ma#;3m!GffvmBlX57 z=k$&nzn3%CUXd^y)v#clDWIBj(>^vz9U-Lml5_&eh*Yh4hOD7Gdx(3L*2_|au`A*X zaOx}6TuF|SRiahQBy>`KUc~`D*lG9~Ueb5+;28zHK+FGnoi^<56F(*KL9G2-DX7R? zFp%QkhLyhy0c=zM`h3t&exakQoVameMNgpkKUxY}5LEn8LY9`~y&Ivnjbjh-;l6tQ zi56V!Ps6Tl-;K%My@~5Jx|db86qwlPw^`J5*6fLJ{9bmDA>3KRN+n+)MOuXY{WLS4 zPH5L+b86k&rm2g`cKnm}?tO_ibnVpi*<3-gsMo7*F6!D;Jy`~jzfgJv-2+xLg#^Bk zKxCyM+6RyldA^G$lO;uA>!9p%nX)*AaSY2-BWI6)LoA$%RGM}3^7bT zCC(6$gs~*Rtt6=-5jjW>3wq7(vCxl`EFjA;fE>)^XC_~xce&@?|AMLQh;Az*`qPz7 z4|0#4GXxny_3hI{<^J5iPXxRX6we#${h69rBP?_^FYg5eJL>1Oa0rdDs{Z_bg@w{y zXicXG6ia@M=Y_uX-Fu=<-*GYY+U6#7{Vx5yQq|o@|CxcK&O$O`IvlUjZ&$4IC3`}o zsUq1kGv;@%OG%Sr9!m%kiMrW$u55k|M{)vUtd0srQEeP_c@p0PVn)o(<7~XmfWn78 zMRoNo(arKH__G%|R6@m|1?7Z29w|9lYpsck4}qFqIC z6TdbT_wK~FS2+4O@b8&JdBgYex~~N0vIQoHOvUHIQ0A#B-(EQH6oNj6O-x8)m&W29 z4m7AYQfbSv@n?%KjHL;9;N*UGB7Cwc)I6g1)pa_QnO{o^GZ zLG%VopoNm9@{_}KMfc=LfkN+sy93n!q_i`Ot!|UCYZ-{oR(>YIA(4W9cCz-%p(rI` zpDVihPKx- z9}Dv}_KUk8V?Y9*#s#FCL3+&i?~h*cMZ6J$$^|2V{4!oESBJg&;ipW~@7E#f<2>o4 zJF)Z0XYV$Bj&^ywR`cG~UzT|6-xcfZVLex30E8p|+nU*9J2XUA9+a^((cr@y(`R<@ zO#St>w`*D6Y`Xq&>#5`M@;VT6cGT~(T27U08dLiY7O^IVLrL_A%;}9`X7;RU-C$@D zi-97xgb>RQYzk%($A|p5a&H7E77L z#&=zL54;ux!$v0b7YQ*jl>`kSVF zaOU-AJ(`&u@`>GTKFcMYGNchCe6sN)pBMJN|oCNv4L*k=` zw6o_08c45}!J^!?g$`wGkw=@qaB!aSe>>MHZj!|URUwtMdjlPTM<$oG+^vrmByat7 zdk*7n`&S}uuU`7=W?Q@Xm&h1{C{jV3#Y!IuT>Rk{0XxFWBWjw${6?M6F9@10dLPG) z3aXZ$CNG`+6}!Iw_GPY(>HuY^YbH7lH#y3Q^lWA5`x&L7h`VW0u>d==E~@GIs|0z2 zM+|}K6cMnTCSvT5HdBtoK)f)?e^@KR?qTti9rf87 z;#R3mBEg2F*$QFMp^Go_W(C~ytD?+_sg>=xXDR93KehadY@X(AJ|K+= zF8~&umx;IUFq-Za8Q5c4>PpC7QsK3e_%Zn=B`EtC!D z6WDY4$BX9qkN61vw(=5Q_66;>mI~gAky0G50#5x>9YsY&M;qjl6;j5fN{1}i55pNW zp>HmuJ0pf~e9ivaoY8eRJoVo1TN>Q@&Km5XZ@LqCo;ZIw-{FGgR%_2r0k{iV=I*X% z-QBYfGW#e0{sk)YI#0g=)hq~A_S90pGQanXpmu`e`3=4zv`AdrZ(0@qN)vB`JpZW5 zVZP3>N|b+hhsV5?cgDLj&Y)R3amM)aHWD>XXg>MST=>>^oYQ z&%2BG57RmNZ2#n+coyO3iLk=gDaVs5!KDvOx;WjV-@LuZY_l47SB{Puc|dec#HR3o zFE63(Ro8F*&TpEDIvEou|pu+(0~in~d@2Qls(u1~dInt#w`gmk-eDBu)^QGBTO zdYh|1^8g{>4c8}VTIG7jO96d8>#cv4&x!|6RMZSVC zWwn*fH~y?S{v|9f+UzC-5F4aQoB2`*YMN?BLX=Iew<&d0O&Gd!#O%l#QU}tEg;@v) zQD8q`_`!>m>30Si&=cbowq@k+pwqd22TB)R*}PNfL9w}NWW#6w6K3geF$!#X3jkxY zz7d4oA9nMM`El}}{~JZ$-anG-AZF!jf(lND!_Dq}wJBvT@271Rm%7n6y#kpXU2Gv2 zZCxjQ^QM{Try;!!QnCzU@B|7JTLF-MsI0#d<_THJgccdnKu`Dm*&@CsgvlQH*=5^c z*@cI{+mGOns6;iz7(O--SFiugfA(21tq0M~XMAS(>xrloHwF{h*ZJe!$oRpgSM6f?T=iFyHgZ*J+BHu*F|zwVUN3jd|F94wfYO6~I$#TMCmvEA4ar=( z#*41+-SR2fkz*7@8SU-2nJVh>K>xwm!FY-tq0nXU6|Nk~s$TKnePV*FTOVh55-Scp z^nkw3m;e$%SH^ky4AV!6RedfGaBqC|9rKkdpspY5#8Pm_4ZHnhl}=2(=yGFsx-h>x z`fkW2uGWw&SIFshUeL*}3*CQkIV+%xOjYUjuHPRY%o5zlc6o>A!w7u5k;|^jWNA%q zLrmG{Ib8AD4ofZy+(nHVf40<>bu!W3e-#?F0wION4)U$)%u)Jo+&nyy7yTLRJZ_iy zwt$z-nPxRX77R2ILrtOjK5G>^?;>G@UhiJ7+=Y!o`?1F1CsvzzOfte7- z(aGDt={}s4` z;qbCH>+zSOOxp(DAo9e1veHnk20Ldq2bj-GvEgdQ-SkA)+iq-tg0dy~00a>6!>i!7 zR4|I5t=g%y&<1&Gc?UkuVIX?1i2i0j8uRWI3cy@}Ew)u!hQYd`?kAb{mqON;Acxu~ ze)<-E&)se+TC0MID}B7fg|nO2dKhnnB7|G2#nC;1A3R1hW}-gRU&wh?CN2e$Yp*K6 zbgsL-`1hLc5_0ZGW7>wLNkcOA!Edkr=XW73IC6t`2_PRfsL^bLUHWu>=c{T zkR`w*Pd1Zn|Hu=ohu_LT?{fZ9U-9xse_7+pyl1bIS%HMw)-qm0gX9%0oL1@aff67! z|AqJC7QTO6@MCT4b95<%5a>^#Z=;oL%2?1~*K$5nOE)|x2?^cmK=R-**^u zCfi~(ZdP2Vq}76!kn$mvA9O@~@a6uIup;gS9qIlVr}DdKCg&2|(`WdrAPS5Jld<-= zJM*qxPUEG?MgOK;&74Tw5KR&`O%7S-+YBRqz&0wdx7cWR{ll$k^V*Y{_$>GKPRI%I zm9NwL>)2Y+*btu6&fpScAKbogi2yPZWWy#s6^Hm+5rrTux~e-Jtca`POJ z7FPL_Ki!6_?(84&A~0V`Px=_%V5gRd24rlyD)4UvLg7KhrqwfVXDfdHy4vgoK6?e& z{+OB*7cnMUsJyDG2m~g4J0pLYAT}yCRDekFX+HYaizaIdXuKwo(5-3`o;9XcxCh&- zP+VcpSwcv@*rlx`u>z*o|N#WZ6IDFPo3 za}+;Z{U;uXj0q@#EsiGmHkZ;7LK*pTv;UE?H^5P>Y!J@;2k^>Kf18y<$z-(E@UW1C zsHl1#Ix;9sAx@fdK7N;xxg|^{m=sm!IbN~3FIZlk_8hXw_GWllr%%KMwuAb6_ft7U zC|dko!wdDJ?J?8u}}&7?D+saGgjuE*l{2Nb_kR@q@ZS}q6z~}xi!PD3W(4! zIj9W%(7JD3<}!;|_E{|gz8DY8@5Myw&m3cV^=UIb#e5!HL1a*8gtoxZlp>V$C~4m! zOD-}G+Jxs-UEt_K22>%)-<@w^i*k&jr1Fa(1%Xeh2%yE*x%N6?&B8Q}y06|0V7_16 zyzHY`KKPZiT&|U?tmY;;%bi2j+rBiHp0^aXy}jqsYJJB#qSAX2InU0wTHn0j!oCMd0c))RT4=K zd9*a`yr{$LF6DO0A%9Zx|KBbvB>TuAFdFy-_bqPy=esvQ2ZSITz}K_)7&KCXj-;6#D}j{pI&(@K>c2l16$tS$m`IwS)wOP&r!C=cUab6Y$h{h*GUQ z=fHcHnjgk6Uu#Q^iN=R@~r83KhjwQIeraiui;=P?IM<-yO%p zh?%j>K(v*JR0gq>u$F)aBJzBg=18E9K}QJbml?8(NV;nuZW$(>H!z?^P&hXI&b;aj zgr<2mcq5>PbtI@^)6+Ut3FVK)R!H)7-V7^a#7^W8K4U^nCe7 znhQD8L%)C3j7PBCMZ87HQ1Wj{p3qZ7mQ;uj25s)@tif@B&i);Kkbz{rd~?9A#D=3V7s7fk%nTe7!{Uwj#%-^0wCK`_`Ay{@SU)v;YX)5HE;v@@`BqK7-1P{-H{lNSD< zpa~Z+DO}LtOLYZBD<~82p4~5YU}S{W=uM%7DZx@AdS^~uD3=d40mScp+8f6Qdz?e` z8??t5=_mp+L9KgF=8(|*ddiu$a{xodSMr9vR0nSQNqdLpyWTC$#K2B%IsRNloejBi z7h|0Lb%uDEKX%w$`?(6r3n5w92)abY`K8U#P0+aBja zkPM`%AZuU^?{+9l2ln#6JqSn_TqcVkJQwCsd|uQ+TYE`mITIWSN^<8XrV%=kce_a9 zv?RR_Kv%Xt=)+@}ahq>9ar6D%NYv<$le44-i(;9>~TBeTHmO-(yca9)W0X!y!jV#&k8_{M$Y5<`uQkr~hRH zPl?OkFJ-lH!cA3^1^HDn*ZJ5+O3E~RHv&aR4U8hE6>SY0^R^3MwQa({_wPB?88OT9 z1r_wdeGPh!V!wl4h;<6AU0oAR!BrICl|cz-tq1|r=4En1wB)p&2J^$V*>eU_GAU^g)ck~=)=BW8&xmmyWJ^2|;o zbd`;d6m6XU;H=;KhxK+Yw7GJHa&;ZwVgtaTxFWQ)rBSAZMJ%i-K+=)DdU$pe;#1JM zA<^SBV;xPG{_ektJB)BoTZ3(`(EE_R6#E>7 z(ojBhvj3ezO%|i6m{x;4O6nlS2S}kv)SA~KB1sc^()o%RD&ChuV*O+&oOcTke;jl+ zQ;_%Y0`r|qbvsvAJSL3PzIGG4`Bw@$V`Y!$nM~ z1E7FQ{1my0gu-uMf=NKOt#s!!*7AzUt;2wV9jFuUx`@f_(X@fU?T*C$-85ckReqZC zn^nZwBO6{g>p?{PMv%4pJ!p4}V7EFXC*_x{HX7HiHBPJSoW7CHvxJr|L~dh?PB|mkUUX zApx;ewEp^)bpH+E(L;o)4J6%M3=El2_aUo#rzLm|i+KkYkCvcWmIG?T@MNc2Bli&9$%kZ19h; zrb+)AkQh+AzwW)yXtVom!%rZSVT1&Rg#ARw94f?Eh8Zj60zm#CT`vVLy1(rJesO*AI#mJj4TxVn$V-X{+%D-{^bhdjJjrkXOCGvaF5 zlKQ^USBrcMb&x@w*S{()qV|K59~?PZDu21?gph=R0WM}~?JTPUX3+nzJK^0#he zj7y$}r9N7bW7I%wZf^bsx=nrwh1y;%K{Z~E`bqkB+9sEoV26AYt7>xoL+|pI7 zZ8nE0-a?++YNu2u4^#j~peK%bdK7LZo&upDTcUgNGNDJ5@OAUaHQnlDgUi z=yQiZhaUh;Rzbeq6_52e0-^3i{~I8v{R@km#Fm8s|BD+xRle+M|WU8qg{VLnHDT(6$pQkf-rKhRUVr?M~K7XzoM!N5vv=z zcqc;(KPi#-=gS@;XBd(|fRnch_0>mcQ7W@1F*; zQPKGETXJ;^c=q!5I?pYVOfvVF2fO?=iqxL%7q*N@h4aL39@$#3Mxp*})5f(C?l{ol z(*X;Sa?wN9gVT!dX7wS$hF=EJ7CU+p-{ku-CLNpdY}cPZ?VJ3Is-C;SyF1L+<_};= zPX)IF`Lbyh?ju5>HWJuyd{1j4js>-CTeZGLD`IT|}nLL;H3(!xjaE1CLjSGPMY&l}V?0*qj!pXf;;N+_*Fw;+tL z(%rB3e&qv1-4WaFd`Fw}IN0r!LkDfX-z_zw1EEYw4hV*4!XWW+Tg$FyCYy!o)znO) zCBX!*Ir~qUjEwb#CdN715}s3J>T4xraKtlXwm%HKA*b~HP8Y0>Cj6Vio8(<{WA827 zncRFF0m2oHb(t=oU$iXjU9{lQ@HMUE+N1M~jS<1lBjTDCB zo&2%X_JsQRA9_$E&b~Y-!4+W)Mp)ZCAEPnGgSS&dF4OM}uSGoOT@N^`Dx+~V48Mj@ ztMq%SotB z-&3n?rqBJg=A!96ym5HDoKl}Cfgs3XWa(Q+5Kf@m-v8D-qIcbRKcFA)>h)TdBZ!UL zZOsDv#IOFTPjKG*CJr7rYg#UAc6f(Hw38Iv4jx~r_dG#{`G>*wakxF?obu@nwl&o8 z$b>-Vk#ml2dYtg~o*NH&NvFwvDaYqW&~4SXaqODiemuz7k$>u zpbnEc4rpHBrzvv}X%sV|{_sC#lCO8+v)?}HvY|_+4XtbHY~mC zx@p1PX_lB;NJYJD{Cm?HE8Qs-R4{e5=uC!WV240N2jZM_^r44;7{gtXW!B`Cet zxnaOKk`LWq5ciPL`i2=DV;e>U--i{Dxj-L2LHkFvI699%o?~dPU4VSM83sfjytr(Q zU+ou#mmG8Ti9WoMtiwSOrroi>F(-p`RM}D}lwqEDpAe`L%T20HzIo!PSrsrR(K2C@ zGK-3i#XeVGyC!{$EW8OB*A&IhiaFwBL@Xa%;dlOn9V^~7w+;NskqPs@XFC<=)c>X5 zT8$9^Q~0!s*C6Iqw`=~Xd9DP~ju85O5MHW%!Y#$pmu@ zMYqS*GLaoT;KKcn&qF~GMw7w|`t^sirjyvd5B6c*>~b<7zGv_VZ@CxXmIYCVf&H zd39VHA}sNo{1dw7{LH7w1zyjbC`3d5`wS6jHBZVRtc-$av-wNMV>X6!*fw%3wseZy zYwY;K1l&>%$cgD`4D=hH@L2a(AIGDG&u5QM8btH==eW(I0ZyWzysa{=v8hHI8WR)q zS{_=6#3y9LdP0q8su0WpKo|ja z@+fsS)E#J=19ewZ&rC9WkA9bZ{&?6a>UAZiC6p0_&dYs8nbj+w*n`W-3Pi#rJ)hl= zQl?Q?hRLu#v}FRJKY}?+fylq~;(aX*M_dw1 z5oBYcNS!vH$xl$npzj9%Kb9hdsJn<-0(in$htvu%!>_h5d$|z7G9`Nt#EGN}v1{}} znrf?$AFI!Bn0McH?=5I%((2~8uxgjx-xK2~qm`V~=RXdJ&sTL$p^Nb6e1h_5S6SDcxYjtrFtl);aiLwor zBGC!FO(fp|0)#C7>z16HnljziCS)-*yU{WXh63XlHODbCn9!oFaY?S;U-|%794i}n z5Q@p%;jGeMSy2(n@;zXtR-{D??utx%xQ-tRu)8mRb?LuQn~&GY_hF63Xp8=z;S^u7GJUgt479 z%LYQYuKo8USj7dZJ83$#B0n7%ruM6bY*aFoKxSgGMob_R-?L=}SFL7Ff3MB>IESEG z&Y85dGz!T!hJ=srX5&6$ zFdJPPa=rEIbphPbw%Twb|9hTQkIVnne_SS4c4| z<<6S4m~Z5iekNKjz(!!9pJY*9H&*)?FM0SO9vVC4jYE*jACk05v@UV*x2fQ%f@d|v z<~}yxu9+FWnB4HsR^hVfSzR5k9SJ#}9TO2!^qp;q0OW=bO-=gED;~;B{nh9|Lqnm} z2w3v?Q35%~+08x-Pc_~Zf^It2<3#$Aa`dS{#?rasAX3l2@askA%Wn=Q<6qNdKpLjK zI#UVy-2++}{$W1cPFETn_leq;Vv6fA{~eFAYj=-5<6oodp1 z%d7^E#7{93eXEB%%>L8W-5&K+)?xF z<@zWM4mRM!J51&2B1KEM3ZGLOSC8$ztbNk#e8*`x-2y&OLOB8_5rlXpp67ER&giR0 z3ujKKty14uKK*Yd&!B~Q@xYWUoX)cwra7Tf&oCkeE<2sd3gyIm{TZD(*U*X}*nKhd zcmI&$61=}I>2~~&&EWlAo!IVbG8QoBZSbLfFmjxgMLkTNdSj#^#Z(n^n6rSWU41>3 zjpZKt`%DQG^G-(f9mt1#KJ^_-jP}Lkqhh0k>j4WIGkwR|_chM3#8_o)vl}M>P_bs< z3%c+wvNbdE6;>POt*4_IbQX%E9C|!@;6fFC@Oy*C=9$rG}eu$B7-mfC15_^tB(A z__5HoK5saeRGM3q)#Jky$y=fxyz_|xCxz)+vZkwU1$)im1imi|MFgrk%YXmDk`V=Q z`(LRrs&NqsqjovGrns>q`D)OQ1!s%So?IOcd%TYqB0*5g7o=V*<$8X?iqNFGVPa{4$sLuoD@F%@!>p1(HqUf6B;_cm&*z>$Q*P7u`- zj!P4i2v`JXO!cP2rM-=5hMZrBnv~oJn=$$vuG4*w_Dpbvs0AN1+buo9JGAuM)3Dzr zhOMPB{A+slw;~Vvgo~0Q$4)F3hGc$?zC96r)%1fBGvMDcyofR-KusFFDlz22#lW;6 zj8#Ov`NN~g2hy~?m8QeQ zRt|uG`U}ku@36xM**`uk%Q!utjS-oEpoQWyrW4rWKbE}pb#BCk$`r8ch<1FPkb#FVpHv*is%FY`2w?+xxH zT90TweLBMg5uTBjcBkil81E9;?L##GG5JkfCDw-@9uZn2Z;kQ-uynBT-9_ej3 z2+y5ORC=wZVkhWp_Vq>f?s)(TD*GCOE ztMsS}sjHeT{x?L)M*Q<&IpKTH6nq|v<+yA{^ZZ%+=_xqGL%O`7h z8PXi+K@LSb$bDS?@65`uITVsPG;7r|{F*O=xs6C%Eq%f^yHctF#mHoUeQ&aK4p=UK ztC73^tdn(ux|gtL+Y40Ko5;W>BS!xpBv$NPN?-1~{Oad;)b+XYZoP|Jc!gzGFir(t zg&wE_LC~UkQr(xG{~eqLRcSp6eBn~rJ4+vE$UKOCY`pkR96T(K!v7w2 zN7cd^DTCFG7xXUuM|;wDcH!IDGLwwA7%m~5ogOa`jnHCQVeRPL!36Q4ijCI0R@2Q~ z9a2pBU}s=&gRHrS-WgO^09$E@R*YQIr zyufW-F8{+V1|&Hnd_Ppj(C)_r$Mw?5t3SNqKm8e>{^}gov6-;U?tdLZaZPZTkMC4E z*tKh@f;m^mW-09vq$7c(4BboYLKSljyK`-S=7W@&cd$^+kikb~GHCKO9MjN&Zy2N~ zCu74*u^=rjkg+u~@#xpIHT3A3TMQQQ=$0TlU0Jw)T)`bXbf3hLvOypx`TnW!X|LGV zhuaDry1YwBG_F%4i!1{TLM@1x&SygRS9iXZAw-)j0w$t#FRJZI5s8&F&y+Hbr3Sep0sD<>~Eh6-j5PAg}nNSqMuM}(Oq%==}@Y`MsUb@rK#ka)QP63#{f*ls~trBTOO7Zks#ED{7d zQeY}&e>}~!Z65d+Sxh9cX(!X$01p$0ykF$oY$j?q!BeeN)0#<0AmQX)N-JLyxuF(m9~d0D$n??Oo>R$UkcNR~?6d5KHLFzbJA7J6o z;sVB?Kc_ph(;SZ&jk3YH#(_F7HA;83GIChfbBto&(*>TYPFp{A3l5?#&M}kPG)OXVUdYkL~zW&TXp+dNeh*jqd#CcnYK zCfFaD{PRlA36fFkW8|tcdFI53DzPz>Sj{DEc1l_1pL_c4r$x>a;Z*4`85l#-9tlcP zq?#}0wNroJ-<1gC9tNFFI0|RM%cQGi$A!W{lbHry%AB|TlNFAN+AA`S0KcbbVB^0B z$nB;0MRXjQAIlSD^1CzEeYJ14dUHjzYZHML4r?t>I`Mr1RR`dh>k)RZ^%Dhlz}T8OXS^O+25-z_wb#V`8fu>e4xeu&!}Q&i$R3^}>%5I;-luZVeu z+PUskFtUMVX-vvk`dRwDw@}1JS#!%e`T-Z4H-v2ijl`J7606!#@-)i1}?5%s451580oI%Z~7lrPR6jjQI! zA9~^ITUuJ~{ZkgxS$$<#8Ju_Mk`+$l3l_%lP2%fnMonpe<(I1h)=n zYpYINrhL5(AK2YP3@C#0-?d)yt%hL)8_wtB>vzvlcD9-@-YEN2muURaa2>kk{Agjo zw{F)B3y$&4z#(*|-H}cl?j__|tfywW>QoScwT&gSy6?F`i1jrm9|-A=Na>+_D=Y7} zN$PG@^)1G_<;U zcF>PVA?CazQZ`diq@3tmA$hNFX+tlqXP4FGunkQPgioZ10Ys=mL>U_O_2|DvBFSwX zwy)oX{v=?2md&lL_|8&;tum2fCA_;T)$h>0*zdPHL9pS@oak!`{Ll~hu!!>v!uv?_ zDAb7$&W;0ZScACGr?*w|dYP&Y?0o2ILpLvPXtG~F|9ZRP^{gBQEn?(Y_2^Z@7&k>M zBlu9c6a7!>tYDze`AvcK`)bMCwu zHzk6V9DEjv@i!G(P40x@a`HjQgFyDxh1uxoZzsai@gy&4QV2I z5R8RlGIN3c@}UA>IlEZkA8SeH`PjF6$FE>x0{O$N2If@IAHpf1PdA0EU#gnU=k3l+ z2)f|I61PbOdh0c7zVg{-!d$h!0H>QqaL5E+dB4uA$9{cCy&BsJ z_^$4!F?IAX9?QXtV2mhcC`ps9=q{H&Cv9kUt5l>YQDKP_8ASRua{qN@YB9y_#~c49 z8(f?RZzfcl6}PY$e)SU0xvVr-(vvE27~Uo2M)>X1r(p309>lm2(Gh2fMdLpr1!NH4 z?=f8xD8I;`E-josEZlpCc?c_+i`wqcxoHw;n4bd&{qcV?h50X}z8M*MbtDVA!mL{0 z@hDPer4Lq)YYW_qG<4W9>iz9L&%vZk0RJY@DE;dCo#dRm$OB_Hx0(e`l>ngN{2D4F zkTs}FR{gW7KXJi?#Tm@#-g@rGl7;u(Ya^jP8Hll)U~gM#1O5v9#E{CE0?F5S)J_Bp zK~_uUFD2b9%!{4k^m~gSwcX7}a_;W&|7#NMd`5Fd!d~Lv&cE3rtbB9u=9k z*~cBF@o)FjfrQ}(Nr{%-_WHJwY63%Tkg0>*q_r>^MMkTcTc5zwSk{pV+ha%QxTKNO zhU(#glSzD&P+Z0U4XG)&ja_%!01vSer!EL!b`@|tT&kGum(@Bnto+TzM`9a}`M|6` z_y=rgs+vNmq&uylHecT68xqk&07G#9BL4TU@0+I}gJ3xkWp{>Kzi_8a-`>V4$KLqr zo$?F;JS_s{B>2kv{>+HK(Wh$F@W6w+U9-Iun9ux5@;3ftJS3EN-T;aqF}3?EZ+2S= z@%9w=<$oqm3U)O^%KnB{a)P~Q$sRPX1MIIRqbA^xFTA{>a__iMKH3y~gm&w2;y<*P z4OM%Adu-D}Ko|Bj5tYVQwY(M3vmuu%N>Fy+k|)xJl^Z)$kJ+kBzvP~P%|kBhvoih1 zT{r?tsnK#INOer{Wc;g616-%@izCY%h~XB)p&Sys+>bs}Ro*PypG^@7+H%!M({+bH z)6MVt+%3VRd{^9SFV6mX49A5%0-QxN6&(!K$9|Pg)+*=b9ML30j*5!HSzY;r=RZ2R zyy_tHxLn0#o3!pdo*i>enbRFpQb^(CzMYk9K>$L*t}`I6vMCbuU3_T6)@0jX){F&b zOuncD4#@eIqhbIq)^G%-AewkqCLr#8Kd)hrF2PS;zIg=|h+P?YM4ODzjQP?+m4r2U zz=By&Qqo5k&ua169uj#AsZh$?rTECHkJv7+d3+R-&v>OlKz>V8{VQgBk6ib@bbEoR zE;92r-23QULOA|o!P~mzJ|rBNFUTM|YgI{^FHZ{Y#1{uaj)V};C)`JV_gRrB2zAbV zy;SSvoksqDV|<2YBdM^PWyK$Fa<nEsb;tDBUF>0@8>ejdV)qe0zS+^S?VXXk<(aEC)X*n#Ia45h;J{W~DWblGWD2K3R@YDes^(VRxJ^LlOkc9; zl+fo`wP;cguC{N{K^l|cik#T%6eexj3EA|tkU@GE9S$k*l)6|XK-BSQ9v{?b0#C$m z^srIY(@S2Fn9}`eHph#q7n$(4xN(ZoSsi5jSLOqU=th&%(O~S1e_gvLL=+Q}g``kF z`su4b>XS?(iXdB(Kn9t4?QDJ&)58vh=?37pwfSRd{4H<)((VT)ReA@U>=o26*Ic<$g8elw5 zN0w0oVQI=@?yC_+$?kZt+i#c2ZfykQ=^g`>e?oLnXIOpzqb;M?EO2JX8=7Zq{}Q3m z5$Mz{y<(h>mpfJSxMA<53Q5jVZLK_=W&fI4pk6LsvZXJpk#bwRih1-F*=MM&stvGa zi(w|VzgwTSvfjh9$g6TINt8Z@z;_X|oL7IG z2Y-v6{klv9(;5IoVu8@gS>u#1y8RE6{qEQqwEO{78>q3RWp;%VdQXwH(RTTP90`oy z!FCrnkP3BK2{ov^;eWdP{?JutY(9T{u8%A&GLkrFRP}hx0)zGz9qY6j{i|`G0jMTh zLKjn35L9mk>RdvayHtp9mMjl;dS4c4EGXoY9Xu<842KkdWfZVPp&t{Tsr*P{B_Yu# z%PbHlTw-SY%)bB|#_6`3uCgUrZq!Ig_seI+i;ajp7^~tbmo7qF@@%Zgg2Gnec+J{H z?{kJ_d?9IxB0@RSH;MJVy}hMMV65x3uY_FC6D~9VR}`DZ%`J=r24fUmL*3o|YzWeo zIqGjR3Z&mbA~qoZs9i_obztPy*~7m+KQA~3ON<;{KsJ|^sqQO^6F{_k>rw)ijqxAYPBIzuC#Ouk>U98VAl(F~?CX6|SBy^8H1E8VK=O7*hAB!FaNtAn$XbwM%Rm1dD zh74q%aZ{iD7@1J-$*w}oXAA+YgPwVx2RucS z)@PtE+XMRN@@fbS{Ptz&$%rh6f4?hf08vGgAfNCV$qHi=CC8p(2cJdG%7H$HM7{Y* zOt{!d*#Z)ETPghE*jhHVJ85-XSyFO8ApWn}wa{lLN_hB3!HAS@!>lBh zdL|~kcw*Q<-E^vmV|O7X;2%s)Vm1qUcPkiotcL$C4?I5)W zE&gfCKmC1#RV4(~x4i!d+{pE`(=(WI4JX$k@lm`wG0ni{~-WE?o8H(MpQ|^e*hUNq+i$#jl(Z>*lldC-0n~L_NCnFUK6?z=Eh^hllySR zhQq+6w1v!y`1O?i>)g--(l_THAWjhlorm5`7I^5ef z8Pzts$*{*?-z(CLZGF+t%UU#Nh?WuC;B?><{cO5oa{q$!u>xUpZ*|ItY0-o3g!dMd zeQ`{re&8&ueJtMFA}dEr2dvZs-#oy1^^82$=dqykin6&^*5G`4_%MOYch!Obm%iTx zCUd7iVOJIlOL z3D0<=urX;-aQ}_6k2%-nDed@7bDZn9Wb|KCK-C(!M6|gZpf?6Ac`%c?76am>zhTH8 z4m#F!&&=)xxgHUQhJFm5^qWb28xEDu<&w9x$jZx~?~F3o%k}L3;JJEV@q_=6c<3b1eb%)YLKV2X6`hcZD znJ5d9kY$2m&ZfIx-i)tUJiBG5oSLUgDWTti&xFSNDq59Xyjnpug$rc>Gb7KtUl;Mz z+nM}+Q20-%tVo#S`e&UScVeE=>QYn=k$tkWnWlyg-b>r}3FFH|%9K)v%It9|lF};) z0;TI?jjtqpgU8uNT^6Msas0n+lgne?_s(Vvs53PYRU1+swsn zFV&D4adNe4Hxk*jNDO^hJG6d4_b>zakkVPt5yeKB$}sPF_@&_c zDMZ#)oa+6OE9F+L=?q}|WNJ2jG;OGX0iGV(i`*qeu*gCNKkM2KDophbq<6ft*tYi+ zizBa~Li&*6Qdk!8GoTdBAgs?_#5C@2PK#!T;Cpy5!6)v{Ai3nGa4lfq(wlnRoNDxu z`0E5LsIlSC4L%(qjDEGYbE=}RPg)~J$j!z>kyLX;&#(g{SM6+uAK`ABhG{d2f2Qjv z5Zv(mwi#jvqR+v5u4>K$+n5$U1hxGghM>V5N$8E}4}*~^pdI9HwN_D4;S9N3eF5tQ z>7mX1XiMW5Pzv^F*sIP)8!5t&w`n1T$v=@fgh%00>QOGr&>xi@ogWcQqylhuDFu-- zJ?ejU2XW==<05`onbp8=<Mt+2Oj-lcqyq6w^W-ofbvs6H%*PFU;@MpQ(s*J9+f7agP>6sD{u72e9q=-7a*~0g zTUXZV;opeDmUiGPdg!o!=-?#UhU}2SB7`j;&b4cO9btYwB#lc$XV*D$5&=F+g)SVC zLds(>HpBTCd`N~sz(_#-XD#&Tf#9kHYr=|~^TEv=EVj6Pau7QHmkU!TtQ}LB1t2-` z+Acr7<=9hBB!;a49Sf$NU2=K^e*LSo+C?YAWp+~dj6kV>p^h#`GZ}NXCf&aWnP=fL zCsF4?$Nt*Fdw7#1L!q?sQt{JYvJL; zUog-6F77j1;gFXz0^!oB(kcHS zFrHk$F_@GgA7FmtcR$Vh@3MDEO>c4MbS581Z@W7kv7Y?H)bn{tNh_a|fO3Kn&cMKM zR?OY<^W~`&%EF+HY8l&3Pnb`kmiHpfnw|R8`0M zzAhft_ugQ9Xv{P^ZIAl5Chs#2KZJh;>Gy)Xn=kuoRBYe5JeVjj87=F!@+T!c2*-Q| zLC9)bs6SI`ZjF$!?%=lE`Wai|juqwsUyyZf{F~^>6WIB0gOHfum|8z}a7p4LVQ%dQA)GWIzdS4M_;Z#)#N)i;XCCERcjN6gO$rv!9I$maZq_(gT@M2q3UXIN3BD22!+ zXPc9+Oi@kbfS}l6A=-~;f9LeMA~P<r10kKmjG~Q$gfN6`3jm2Cn*h9_A4Tv4Yz)FeN)La{(C}x@4ro`vW3iM##C25WBN}d`)Gw& zZ)6>(cH5mOHM}YBB=naU6W*j86i{p}lP}1`mRk>ba?b{HcfDxV&jv?10;a_1E1q+A7WV}d zBVjNKc%V{un(Iqkw-1y4|G~EQ8RqNxZf}`CR;g>&mHOLl%pe|!#zR<<$&jcG|78DK zfrw}dCd?zC4fq#Wxuj`N>tLqvbXKA_p{7B_n}`6WETPVTL!J}KQleKb_(YA{ju5$SvM3YNDFn3vbDMDD z>faUVrE|UGhZ{iCGYo1J)uKYkamryppY-B$|js228X`RQg8kwVfnje))`Fn8eV8_ zS{zM%6V^8LfmEP{Y{-|(+r5AI#de3g^H_XY-FhXEMrL>{hK{Hh%N64xiuIvAV5Lm$ z6LOSuEWkT<@UUHlI|=X?Yp`neuZqDOE- zmv$UC@lOIXNmT7mV_vk{gq^**Rt$j!=IPBI)2vdZ?D5aL(h5`xqFjju%yJjfJL(+LwV1$oF?9+nM&If(BymH=ljTOaRV01dp@w^MmCg>Ge%FcT%ez zjn&qVt;RD|Lg3$u^;u@F7W0Cb=9!`u^NMd02BK3Rx|a=Cll*zBhN0No`tH^<%{U#e z|E~PkvZI38u7mYHxiX}j4-sjysz>dsqDWolD^toWDlGf;?ryoGa9Qn@0=wg)d<1;{ zOTJ2K{!X)xi%IVlK#L(i57%)6N4Z*JV{Qg8Nfv@Cihj2TO+e~CL((A~uRlR`f|#$1 z4gMycKuBoXL`KD&_x%_ zkd}BjW)c^rl-#LhdmF!Bsvr6z?!zh(C&%K!i{aE4WlRpGeJwH_Z3x1{O3s6sT63W8 zVQZmps8XQp#KG)39^wCvSp55%=%!SfIpz@RBo-IKylID~eYyKs-$Ns{J;(|tM*U1* zg9t5;Y|eAvkf-u-7Edm;Ec&Jro|Jbg%};iodoptGwCFLnS@-NJhS0lObSOze4u^v9!Gr8RG~30)ol(`;`OUNw?r@Lta!W%G(k@1XHaT~j}Xd~z9{`&w_v)F zhF)bFjgfp7i0T>Exb->33Rps6>>+Y&ZwuV_yg(l*y`nQ3{i)(Ax84<_r_Kx|qvHmf zm?M>9#XuYgk_>Nc_X+TqIAx(@H}_^L?$3F_{+abV(u=lL=}hyI{2@%6_1)ZJ?s+l% zj2y#sLj?ca{w@F!#@?-dIx}J~QbtQCEEEFM{=%CsTsV59KLZAEoIG&Z;2ZbFP5aVx zPpb@ryo3~gk$f>GQt?fp8apQOJC&8*&ed>bRsT!|U7rp5(faLQrFK&ntS8NLbw;Yx zmXz;54Ek!ftBV2h^;;}IRxzoQ!l!VN6WIm-upqb{`{y;Qp7qLCgEgm`-ZyO_&f9&% z5T})dbv#B$v)oe?DLMK=?TfYy=l4gRIy^LD0tv#{@apR7 zs%eKt8iuLd0lVl>{ZPbq-P{Lw{zxw`uWsjR2_}Q!UP04S zQN@WPfu|!PJP*@92_4M+o8dDFnQe{*HED5~I_6%zbu?vhKLE*r$bvy3tA#*N^=42x zzK_t_7=J49ed)@Z;>i5i8<++b%T$~enjE8?E+$RW5$)|@4;Jjxu+?zm1rhGZ>e)SU zcl3RiR{-GBWO)so#%UQGWN%zTTYDdKBFgZ;DfftqNJ=wPi^0d&uuRuS@|L}8X*&HT z{R?PvZp9BxxR$(g+x|K?*6B&w$6mta%7Hn#ifi88s|h0;vV?BnH>wo|6m|^tZv&?3b3lxElgyuVFW{1bV9N=f8SVTZy9F6+JyOjVCCoU7Iv@6 zgSEx7qDb`Oihfs2*+thM&Af4mc6fVnxh605<2hdf7zp`hiAre}6TIi|H{Xy~38(LL z{qTx5y|ew|+#Ra(^pP^CX_#G;P*k~>gkigAw&K&Mk-n#dm6Je{$Y%l2Znz%G;mxGQ z^inE;!B~wOd~KY1?>NrO4}daljK}xuYwr`bTa1>o) zc>NUQ0gB4_oBklu7(Bo6ekzs|tZ0Ra5#l(>S1v}F@Q=@i))U-y!}tVW6v)1Rbqsgm z&7-B?NCW996~hbXLfeYf%@;IzG=Y;pY5^NNv2w5?+f{6{p%^+q|4KT}FPNRoS;Vkn z+>g5Rlt~Mf5r@(R*O4wAP{3}l=&+-MgU%r699_fsWGGOjcP=$4nS2?6!57t+pWBrp ze93<954@U#SqUH+BT-r?>}F4gc6|=z(($H5csw3_fra0+4O+soGn%$b%Qp#lxZ~F} z$2(Kgy4!NmV9!caOzuB1F;V>d6!^it@*ZH#PqWAT87Nr{8rL4R&it!koNRr4;Wuz; z8}R=irW;6P3Az$Qel!U*5^>{t5p`S?sp!f$cv}V2tOs&rs{weeP>ZcmGF5!qka}ZXXc=0tJ_LwrOu-YOioZ3dEfaHe?-VJlOw}}#j#mihXX#o0`1MX z&k0?Bs?B`OveSYfb9R-S{QFdEc_5z@ z5B@9|B34U2feq&HPK4=PMgba^Q`a9`Ah^V8!;0Hey3HRj8wN3PIvE|lgHYrwFsoke zpDF|#l=sd?wzZ`$WA5NR4s8RrfetRGD%_MB#jYPTQl#I1JjOza89Mc{Y1{W3lWvt1 zk;pu@v<-T8e(u( zh_sPN8b(4;swU8ZiM%y8&mmd|VET)dxd`~Y$G2}thl?Hg1j+!^TLj>mh&@jD9Th~> zw~~@ss20|YvyFU&D}25+?sLFzm)Xep%;4KCSd^TuVS$y4F>rg&>H0uLmxph5mD(?U zhe)7(B7#w?A%{odSDMd8;}aWw%Z#>M2YsPYE`O}289?@s(D1gi?N zVbQMVSpjZWtY%yd0rcKMrIETvNI zpH~iR4#tI@ZFg~!-frIFIb+3(r-jY-$%PnRcgM-CW3$!tjS;?c8~D8o9B;p&-F|u& z74jmcruqfK-^lZYM?wDN!h zbmIvUJT+2?Vr;Sb9sS{cW5eQNL?%g3fEd@3ZpVX1G45 zYLzdDq}&x8F3@TQUWI_uNkz=urg71qo4@@FhmFiY3TVsU>EIE zM1VL6s1_W#4U199XSj}er`$d0l-i;{7mwR4kUqz8E5vZoD|s2>-gpt6yd?x_>aAV} zD=T#ofVcGf;dGJ^L5YzT@kQN0pvie3Zr+ok+d5Nc_99ew_-)-|dj=w@VkDh#0wOxU{OwoR;*wv zp0Z(1k|z);B>$|OSnCslyfs@|f?a^8_0mrMKvIbm=n6ha07f(U}U`wOs68l#t0pl3rZ+#2~ zg^aPqSX!qL@?Q!x|2pA}$0sYyX7^DB+ZkqPC<*Ix*eT5R5c%{K?LMZXeUP8eZb3P3 z1x-fwD2c+V^nxaZn7XAx0Lnm&XXrBgM6O_em^&&aT@`cv=?(h7yBmJGNM-mM_AK?v zo%E8so&+I19=%7mHDy~a)G{_TdsQ?S*+^YL7dSscb(;Xw)Z6lI4dP;pmCS@GV#rXt zEt-IdhVWNLkYb}w_eTGwx&YUVSkHmH&5aFh1=mOjSqejS>M&q4#eI^%mI15wH|^W{ zCiVValqo@~fjmt87!B0Pow`zjkoL}cM9oGf3?!q%=B4EvSf9*iy(1QoyzY)#p(~&X zoG&zQ0V0oDpWEI;cHb);aN}{l$YdF8p-q6p{|JX5yGfhF7RMdpqN_NfsyDxJgeH(}$G9E6(1{qa)qsj-$iNfU*s*o#P@BeCei!w~F z#p)#?dM9xLRDRhVBZKB3!tvl=Tsfz&Q21cTWmR`4iWX*7a)VxUXiZSk^Qatif=oE} z7>V7PpU;|cKJF}9o2uS-?nrR%(0p;jAJdIiphFV-@{){gZiw(@Z@bO(Tu}eM>Tx!C zAbIR|bWNX?Sb{n9mY&Pw5x{SSLiC)ngeg=7r>qPt473=qI%SkH6*Ar4P=EHWO(Myr zJd=$CL-z|XFYpvNn6rM+am`4zbtgSnSWE`Cs6X9!2vp8dCl|O>Ys3 z^*aim)sE9PxoTNU_zxg9Dc7YXgpY@#&XLQzDz|W=8DN&)NSV%Xp#pnR%@cN?b3Orx zkE?wbd|Vg>r=#Iyexbl5`qdc(<&;ma`*OW{m>mAyv2T zLL+Y50!ux`O@m)bx9KqrQ4eopL8Jed7aC%|mmYcDpVY2h!QSjC^}v9(aaP zA?BwSkEb0)#M433s5PDMG1*H(TS>we+jS+nOOUp*V(AG?`5KC2zY;t~629SnZM_qV z$wu}3o1pvWRh)<{JA-|!p{c=p&97@kjaVnU#Y=Asj`OEd7F(y5Fq4edl3HF1(8@<+ z!9*YS;C>pIOQi%qf*tye*{%F$-|(W5z4B%{}J(O`qXo~DE66- zooK~t;V-m7LXe#(zBwbbLF1Og4|}bOeu$3~mX_i|g$R?IUyf7bO_3A!Uvbau;|*K> z{q<(mMg1I+#a2mKLzqsf9vOi>Gc6y2%gBpxPAkdK=_zMc)T6%wirveHepewYD(=L; zrRvW8gy;W1R>sST;**j8oCHL(}|JbIPSC;>~V$@rPX;wj9iI|-btY?9+F@sS%xz8SV zxQ#r zeSDix8C><_5t!$f0$|>_@4|=sQWH7kDnbTX-GQ%&p1B7?qzL3Q?D)g($JB&`Blkq% zf#gVr=jrLjYZ2x0KYc;?9`JQ$;dkB8URvVwJiomJ9xgqu;r(C#te<0WYrzl9!pBwIVe1*SyF~>VisSQal6-i#4D@>!(4fu>9-5spUY+^2 z;=F%)7Nc4{+Ck$^Yhv4(^}3o)kq3N(bElMK0RhNo%=1>_+^w&+(ER{Wle{s|2DOSb zhrTTcoPba|Lc~TfE<5(zC)cF!dqgT)#d^xBfypZjg&BcDp|=WdFhV>$JjVEmeOpQt zsL5u{kLr~07lF{l+IXvF#LXG=-C%Z`6ua34W}U-fdB$P;+8N53#h1(KqzZYOx9E2E z`TWiZn-52nvgd`Zk_LxRWaKj041sGYZyiB{T{{?|JE7HaVV_y+y7%M%A-FQ(*~vn* zP})5}M8aL=9}94+5{?72xtpo#tSPh(w_3lkC-BbY_Nm{!OAQ`3Uhwk*V*>_k;nvdP zPn(r~@WO$<;smZkY>}^k+ueKCqke)pn(5%U3@?q1+6<6e&1vp3{&MzKn+YlN z%HxTm|GoQ z-JGr4!m^pJ`srBPv>lafsN{2T=b+}k5ltedoEUXfT*HTte?YB1935#Q0haS$vtje& zv2OhZ&nO_d8xnDrrwKGDNte&Yf*<~erAeBqZjwS_3xQ1A3utIi@kfxGm}=A?x0FNx z2^f;r?R5}Fs9F4EmAdngAu1ZB_b0lUILG*%8-I(c${vWIEl?z(EBIy5E9Na;Vg4)3 zfTg9UtbQd${a4j!dnQRji^(G4^)Zk?H`x14gdWY*;OF@N$E|(Q#Fl**Jm}j9L9N|? za>k4hFfI|ncFYBf_96hjW`QOnYlwbOQ;>?z5T&XE#JLzUiUD#Q)l*Ekf2f4-LE!J zXqw2ky-%qk%C*S7K|alThS$z;RBRG6JYnSu4Z>2hOs@YWWjBY)O_b7zIt>o3;W9U^ zF|MF-TfOujvBl9y;Rh&xE|lydfT=$8)t$O%QwmFY=R%2Dc@`nUZhQBJ2GoZ2hSLa0 zFacKwJnFPuNrh@Lq5cxF`@5|?hvGZwZn6K%RP5UcRw-i87ImE+D5|HkSRHBg^Rs|w z0fA(Oz4=i0bPqG@M4erxa29RmPodiZW z|3cxNBlO#Ym7vAB&I?QTNBgO>J>Pe0%bq_O*p;;PzU{SBGf-6irb7}R=N24wCUw@o z*CBOo7%WHynvNebZ6lbp4dek53^|kV$x(m%l9ukjW9(SqI?xMKyGaB^=)A!Yk2^`4 zzc7!l1T}<((2wb6buZp!Vf(wt32`3OJfVOj8qtVZRUjYuh7D72bZi=K3cE~`_oGN+ zD}H;&#>P6+G1#3YO!}wz=Dm~$uT)DXc;eP?`zvaq0T!6={8Oyp;tAETSrngNrj3_H zwE{A~oOOeOsL_u5*1nkt&iML`Xh#pX;~f6MMaQF?OgpgYkhIxJrla z->Sj{0M|rn3F54t%N36fSFu|K@&hiD#2Ig{>iMto{J)Nu1MaOm;`9$JknSpq#wLXr6gRe& zmPVblP!Y50E<%6Y05L(10ak0}_%p#v)%zwdy#UYKa}r*6;zWJ}Q$%+TY%-_O^EPL|cY7_`ncl+{~~8Skr%_fQiB-KSE{_5f@IFsbb}8-Ti`#O7Ly zedNsF?nQuN&s#R}ce~h?`$w|Upo9a5Ya%KdO%Kz$SYC|$sUK$4umhCAYuERxVZCslf% zl{IjIEy++uDT$XSL+>_$m&vJC@%nELwGSh@_C}4dI!$M}`~JIiZ}~G7XgF-cO?fee zNjDRv3@EXO9>M3GUAUEOAryy4_2Z0^>(P5fuY0m!-VDkF&--| zxoz{HLlRq)>vLHEb>if=*H#M=_UrqwEa3`JfOUM$Zj{meVHN@%3y)PQ7wDg;t)c@w zuILVDeW|zIrV{d#QluS$)4Cuiw;UCQ!ad)u9rVRP~`8)p>bi{rb5bX8E)egSn~b$p6vS{#&@sb-{;ze5A?sQa}+5cY{Iroj%EOtr#C?R$5NJzy&3;gg(2v5 zlfg|hBk=`ZQaEe2TD%@l_fe$&Q5FGY;SVhaGr9~(%dLjJhj^S#a)M_TEkv3+a|eev zPE7JCTRIdOz4u`0-v4?JSEbNmvMRi#`+;Rr2oQ$2TQ1vg!0OZvoOc*K4?|~(R0IQ5 zUM(gHg9d#ZeVw##eRUX&qsabe?sNBg>K#00X!}uW&Gi1u{bR?Qdf9B?vYKI;uSTzO zLi3An7CIk9`~+}^G8=uyKjt_g0Q3jqSG{?^k#^mAZE`~X6oqpS2?7gY$iAJCpa%p; zwvYylsq4oCG;}3&5cTT1Cpx0kKc?v(X|lvyC(eVkw}VG73l`l+#CO7NW%SFF)-X{4 zxpAsDRUkgj`}HSL}ZHeTqZru8zFWY7pTvHDeL}TQ- z!#8MVb7iwG>x4XMlj%K;iS%8p#LQ?C79|E1aO9-#U(7{6@^ydo@V*8}gbXjCe2S`RpcQL{uV z+*xzm z7MhFb06osAVT4v|U0n?LHT7h7IN0JKTx~V61V_VOrF&Oz$vpXvsO5;D4Xv~P(^wfL z(8nQQCU_OU9}r8-$f})!yuK=VthOulC!(&Zl!1`GcVhYdyf?2fm^KZ0D_bd)bzI!| z@gs^0bxtr>;`FV?&f0o-1HETcqc zgls7<4L0${3wee9Ochc4s4Kc6Gs{&U1^GL<4&gbX|BKz#z3AblaqZVF^d0+#H>-Nh zyzLS;d$s-Sj1IeW#>Z|K^+;(>B^fh-)gmyL6R8% z8VV`6yvmyrQyqVSE(a+L4={7F8Y2DwgR(L5{h88W?kCpM6l7ztYDVI!>~5;9of zU{cP36yC={@y*g9hHKb)@Ry6xJ=vdl`#cDa=6~A-crwuFIuPM!PelGBg@AbAe4FqQ zkkWw#oicT?w%?#-9&Qd5+NQ_^|MT+SB)dHwV;D*le)x%UYZhBn&wV|Q48@B4Qz;Au za^YcFeHkr8pkG(%#Rh#vOxND=a4z}426_%(wtACTV7>5Yx@W9{-;{X`aE^Xp!}#T^ zs~5ht&7yxa;;VKoCbp?J9rY>6XmIb?dVrie%32!s$--s zoKC7zA^W=2+O1NUDsW{3yXdij?xTlwv=tVobdt=^~C zPBp)r`k zHcLZ*0}_4;&90>{hgVPXh%yfeEYi$E2@Xu|1&o-0&p??O;y`)3o^|C8Ff1TQV@A`K zZ)<{Spa5)sSLjf_{&@l2{~>FZXxXk@exXT!bY^|@+_BlhcJ)@FJW=MI-;>Lc%^#+k z-Us26L#MDkkMEbjsaL#_Xqc3dMO4kDhh0 z8&#nHINO%9*6p;E_ZF)?oK93xd^OEkIhyNzckTy2=|{N4yoL5fboK@<(UP9q`|80n zz-d}wt@}U2hHmayT(Ga+Q^TxA#HL(mZb-De68n?67&^~4kZOvK+KiFEt-%hRXH}=Q zBsFh_jy8jm&YP|Y|AFvV*`KshzD?Z|mez?~WYE{?yLTy@ls2^;Z1O#40cJ1+_t+>Z zkb#-4JQ7ha7RunNX~rSS8#FwuRG*l+rQzY+3QYftnwy(TZ0np4^JxMJ}SE-BEiDu5w$#oh zhlevSqJ?Cf+f)&dbnZ&qD<+KI3u8Q0OGWLK*1~^KzNM9w|A|~iuYv@s{*pZbCx?u1 zNe0pmD@TY?xk|s3c=6)t;9K8C~_4%~^oDRVovKr4{JEQ<)RSbEM~KX;Ai-No(D728UdV0V*x>V`fKc|H)wK2;fy(dgI~2nO;T55 zjj;|)whNsQ;AoG#Rw zb9$$rh|E2jmX7X?NAb>n$VWdjv~a_t%YXCBp^r7+3aYAm*B3vn> z%n9j6c;&H>_y`I6%FIX4FbscOc*PT9*1V~jkr1?};Ej=PD`Kf-W!n3BRm#6V*UlCz z!+~hZ(vD$Vm2>kki_Yt|n5|!}*RBog`6F`Qt^REC(>gDTmFIL3+lv?e~T3+~l_~=JS z3wchR(jOn_mtH*02nEHr!2aG9;%R&>xiUlwLv5oq$~GjJd4>dYnpZQCjvjns^+5VY z?5~j{Hw@+{v_G1tB+s5t{b>@Un96@2DRJ&i>o#AM|NYkESNn@yi0u#Pi&ivuVYA?m z2;}qUbgnMnv_`=NWs(oZb^)^mM#~o*%frjdN#zJszuGU+o}XaN zk*G4M4c<5JZZPnAo8nr`_1}9@tx)m@pEqb)fGni^T^|So+#tlJ9R>ord`wD%d>0*1 zGpM67Su!c|g5YBma3utRL!uHatCfw@`GgmR#Xw`lpiu!x=rTR*(k=ESS53Jn7r= z`wG-4=@3_j{DB5P3{_JlDai21Q_veK3J?*5P;MCGn3E5QM42 z_4w%7$Nl%8s%A--N8d7_P3mGe02oLD-{PF%x$to8>TSHBnx~%{Gxj24 zZQ-WZ7*fu5^T{j-*ds{@qVkGMrcxqYxV1!S7NaI<1pi51#D*997RTM-@^5Pc-tUJp%!d5Cdnn zXF2Pg8a*boz?4FNFDIB3Rp$~YJt6=#{Re^yOCKtG=- z%@T{cOV2nVIXbB)_{qja?ymE8OdW&XB;>#zyO{RI%Y73%!fp)J^<)cPZ*BI$Oa7KWl6FSBJkNE$0-+*E zKx1VGrmb?~QKH0=aUq=J=+Sk-M;BX_E(1bac6=RG0CUJqkCG7SprMdF{8X^>iEZ$@ zWsg|WAj9P)gOT^nyy~ObxXl1FW2EZXPUu~Db;eLmqy{@KGxlgg9<|pIu@U>D~O`A{GMRy$IN3abH|7M zty~t}#`n?m`17MW(+H?W$61=L#*bO&orZn#S(5w06Qvz)92kH4i#$u>i|T(fuR2&9 z<9CLxBF()v(68e2P0Vyne1wP?B@KVay<3Q{B7&t|%J*J&c9XeXYdk=ktDfup=11F7 zwb0QXL>ax=DVlaY+a*h22d~Pgh4?P!RS8H#Q}${1C=pDx?N|#megIMfvAmUW+6;5= z7Id2^(>}{?(k5ZVWQY%)B%e6DE@YX2^C_yxa)sv@7OnU7C4R;@(0(cGk?h?$QL5m& zAqb6i4HAAxiv?3Wvye7M^r^h~(b%5M(zaih(U{l8i!aaJb;%7{U4)yDTIWCle6Gdm zzaY!*c3eioBa?jK@f3FFaIRFpa$X`)@^Y^;w&kJ>XL?C#E-&~^TqEEY)5u&mdn~PI z4{XZ+y74KLd@O1d5Pvnv!3~;LF3p7jHkCU^i#yjHZCh^xvo* zZ~8wgs8FDQ_@plS>w$gVzh6}F6pf?tr?l=7(1YEYrJ|dujzA(J(`}*Sg#R>YS zV>!W*&$bw^)In6cQXXJw`4yHMye9-_9X{D>mJI(B4ey(&vgR&(O2P*U!pi$jcm5)V z@M|-2LMbk!p)4gXVpv4B$ghA~@kMcd>9Qc6`)AsE6V0U)zSpF6-tI*&L;kacxdnPTP-@;M=Xnu{&R6N9dO801&7njFpfdspn zXk?89U5RC{OL8I+l*caw`0IRI3<}(snqLZTOax`{sM5a%H|L)c+qI$W_1lj;bM?K% ziL^F=y{|1143DS@H*eMpgc#z&1`5yDS?wRPqB{K^M!o#;lMI{bU934{oCZ5d05XrM z?TyiTS>q0Yy;zB53lijz>scMDke98GM;+InQjH0o-5Jfr8f`pX{9wKOJ?3zU5uMyd zt?L;;`FOHl>JuL(R)p>IUJ$ptFz$wEr(DL!Ex~#&5phAD4b7Up-CwrLLtqMliL` zh?LJup8(_$b6W`Ec||-XZ-vGKXsLjl5n+t~0{VES`vR(eG{w2PG5;lbd?f3C37BjGXTVon|&4!0-Z)Ps#QOph7_DH~_>etBq9(q~+P0n9cW?cm3;xFbcs;a7n zl=zw-w_YEW;}0ViQ_ck=vqDYIn2**(ILoxQoQz+epRDk;KBY_Y8M0^&?RZ{B`#A1+ zZFb*;+58qOLUjAoXnpyCBj-zMYu5iBfj%RBm?iB0SjbG8o&;){wKVZnID$2LvE+M6uNa4{>N)^ceYae0|C}| z4s}kg6zID?RKXcnC4mo52!VE;yO2MV@3U5Q5ly+?+wWT5FitG0t`;J_p}rd;+XoEDO@0&vMQ+`EuNNvFA+aGr>$|4^ za{q#>R&aN)w$d@GHCT9iQ1$<#>c8Wu{{R1R{CX>IkxOoL~$~btz?x|vJ+)h z#yLbnnb|^Qg^VOgoX9Fd2$7Y{%FH~@`QFd-^M3s-f(iH?@2J;E8 z)XB)G4UDX{wY9H4rm3U8GxyDE2c{AA?>DooLe6`WN%=Jl-ssx6)9dHe{?raU=_Np} z4h;HkmR3|e_VI9VYl&z1HhwWw3R}f!?q;!&O{&fE>!+Aeo(60Th@SLHdrxxRo2t%@ zQp@!qUrHUM|pL#be=sJ)oTdTNFO5PASSICd*AvDg|U%sg~+oD;<0G8(Ld z)OtdrenTCN=T|TGe2KP0fH(d65#VSvc8BpWZKjikhPin8 zazU-apur1z$BpBm9<8J=g51dD->CIa+gLzw_qM1T9WfOTr_pResI5d6+1Bf)ZBwgj zT#=n=eR`7r`Pr{E9UAee#q2_B23RGg18L8U zFYW{483%?qB)s&EZ2E@)-Pw!&g4FRAdw&C)d6)9HRk!yCtH#LB;@HL3Ahx;sBvGY> zFJGi~^h-RoN|$;1t|Ba`nlR9+lGuiZhElEvYq(==&;R-JM^Z#U2qA4-pD+=+?{yCn zJszpkNq4o>(2XvK3-smLX(U@*)`;gNE2T}4+S){)`W&LR1`YROoaL!^6a&vM;aZM( z+v#{0l6g1haZZqvnYK2(9nOmN73u^ibG@k-I|uUkQY_` zDW=W7NC}R$=EU91@d*ZlupT3N2$~=D_Ve=Zb%$b$${UZe6WxEWPPbb89+n@bWWP zL5I~L&R1+?lofr>&HD6AAj_t7Af#k>WBzz`#^Dd=aw980-NeH|?8B6cHIkzt@b@3@C5pHR0U_MXL8Dn#oOGlG0fpv@fO zGN(zVy1?;Sqs!JnA1JA)uz*tsQ3-4pPZZ?Nt=!#2^gjRWXYX?Uqf-Nv7T!4aWE+3J z2#$q<6IK!E;9Jfmxl*HEYWj1vuYhM`2JmGL4{{lE8jV{G$_MeYL!a`f zNt+tMhY#6) za$3f~>TnUpvAbSaWYA&JzVMLt7~_a`qAT(M!Mmxm)wjhZio|puZ>?@8CZIr z8)fm93ubumBX_l)2iXYw!09mku$20zZ`gu zv#mYSHK|gf*L>Ewc@?_A#T0?iL@er|VK`LFyb-L0ArZ5DCxVzD6Ry!k7a3hp z_||%Enz$@bcr1ke!5Jg{h1Q$*z7)Lqx+hAJ?Yg6Q-VeQbw3fzLbzXfCcHQ%{B0eOV zdtF)hmmB)HuH5Eo!iysp#i*o=th?e`y433pSq*f+WcNohxjaaIZ|`CYPz4`jM)kcJ z=Wd#C%sB|N%LgVhk2o|a+-IAc9DNcq8i@PwKJ?tn^bmH?naYk@7Y4;%K4h+d8V-H6 z)iE}6NV~tvW}&#Zoc5&%_H>IOI?v!_5%VQA)Yj=0m+v>bMUG({j{nNN_~**0hPJla zw|Dh#a64&Ht0^}eD&fp%49Xw^D1$o^^4kwv$0`8P6GLA5J zF7j8s^K(Ku(oE5|oI`;_Rl+!nFB(7*idr>Gt_&2j3Cf-{YQvkQ59 zI!v+2q=jEqXUUN~x%W%7+J#(A3L@7>hEnFa41T)065y;W0DJCKufT^aUo@)Ee%{oH z`4yGi;A-ri_Dn$G8cN2xiWm}*j{n!qI{e{XgFow;u3##MD3{>h&&NAF$5MJye(BW5 z+;PmvBOfy)C`;hOXzD1eoJC!E8P){d*t$Sir(dGI-NkKOK&@DmcMzl zEA!CF&i+$H0{?Ie2?@ih1keN= zH!9(XKN}V%D48e`@1S$~Dy*4|psC~f{1yw-9-MiUk0-tvRd8%x4`d!;kUn|g^1D_3 zU&4;d4Hi#d6k_esRQL9-jn`faD;QjYIe24k}BIKOOFo^Bjk=2)! z?i43IIy{7>f^g#PcbQ~D$j?fOus_w%zw0M29S!K4FAZ#sJN#H5!ba~c7AZ+xd%Q~x z`>Z}nrRq|}BCn$O#0kf_P|tVz2F~oxU$vdfT@gHF#;vpudE>5Qadf~X+2xpiF8Tf& z4jGWgA@44B!ZC1>4pk+P*oq>kl)ZNA&qvKzLe;uozdN-Q_P(PCf9xQm)VaQvfO~!Q za%>;Om1EJtF@VpNmB&oY`yjb#&38%j#_wXzlD>C-K~f>454_5hHHZFhucf5?Qr50m z*1Y6?d}@uug9i_W2LHuPqF8#-S0!()JLs26QHzBsn-832pbK^62)ltGbf9nwBnVno za<>9Rr`FPYnY+hBX5t6%;dDS;$AJ@pW0yOR0=jTOvcJNtvHSGQ?LW2`CdKPuB?dM2 zT4Eos2MDlc_`yv87+{H6mz6;bUR>)Ll6_~PAikuuwDh{v*hXX4$nsv3D6ia77$z#D z?TV6Hm(sT0nUolQ{0KsP09Mv2@33&LFpaO~zTKRYlilKqyoZNT+}AVPq6~C~({y>eAfMIj%9=-|M&p<=&$Z5pFSjnMSE4RT5^BZ`-e<8L-=6`Az3uq0Lri8iB=OvlL+99~~+5Ry-nvq8$7p_=Y z7c+Xk{{2gHfIj}9@p@Uq&p7pk`k!&;Ki2|1^dkZE)z8FpgOl!UCM0Bu22Cp_z$^RY zFchbnVvs_B$zu3O++jKst&_>7_hF|P_SH(?zCH3CahVq^8)^R&P%)A1)+9;@Sxm}( z7a}gbSU!3636tkwW~dui9XjZZjlVe7{`#DPtn0Pt%wx)=1SPk9 z2Kt(N6rY-;6Tcd>^XFJulGu*z(}rv=IqCMV4eWlq;#~+^hw25fXoTWa0=3=@6~J^M zbozAIp>+Jb77wm%)Aw%sBIO~w@K?iB>9ZLwn?q+ty<-*z~EX(I{% zrwx~H)WXM-Zt~gMHRlvdK<=FUu2x^bwdoBTvH1ue4|! zATnerB1#7#1S-do6TnK^5Ca#mmTtSqtf_gwU(XIH1{}#Yd%rwDl>h;?53E1_OQIHu z0V)*w^a1Xs)kx&!Oi#tde9G0JzdyR!%P|J9nf0}3uCO*>TD{g|ZlgA1MN0Hvx%cz- zGi(KC-~BcYiF$PXL9?cuag)aTmB5V`Y>TgRvsYvo56BQi{QR?A^XU~;AynsoI;zxX z#eu2?;40YF=!wcTKqq{r2c`y0NaF7@*bt4wK@6tGFi4V5%un+pP@&E#ZdU1!d zhz|`Ukq9*Cd#Y0R$!9ql35q6;s`-_`5Yj_dpP!cCBNsM~f9}@=D)TLtCY9KW}ZD7vA(0wDOO>!Mdil(+O(B7~a zbH)DSRm;0!&pr3b0&n9qo~Lu{lLlVETDk-&aPS(L1eO$;#Gjaq8X z7108kZu(dLdpq4ic_HA&j|K~+gHH3+_2yeY&)Ll}f_m0R8aZA8RWH*+zg5k}-!8l- zqXp=S(nXs6V$RCFlB*g_yGDAIlfsF!+z*5zUGzi<=g4EvGol$m<(+E*F5!}<;kajL z9YGY7k=5M~T^=6veD^HU#QZx{H+s61=clJ$`2Eer7c9eE2CvuKwlT+^tAD?ACY$5t zeh5*ZG5Y!K#ga#?Dy*XZ|G~hg;g{6y+G>0KD-whn1 zXhdio7WSEc8u--;##~9l^3zO{&pvRv1_{W4|I-3smEEmZ%%ci%z+RK#%J?nkuBfeo ztz6IBgE)fh+I9qLZz9)04htUk?sXM^U+uO9t)o|+R z^(gLW7T%M2UUdNbp_c1efe1Ws^aCQ4fHHL;&2ZoMm(AyHY+1QCqcX(c$A0~J85VN| zmABpuF>_y&T=5R;r?_TTEBo}P)%PI@wlHYr{hK~n-PfFgxC^WLuJD(Y0Mu#f!0MmK zNt7{|y<;NGh_kb^^BAphJ}L0LXcudtwA-0-k}!~?1jP{1XF1c&^mT>6K0d%?`r6|8 z7dQ(qTT5p_7xF)elS-72l5%?)){;dly4Zq5>NK&3ARl>pZ=nDYM88ru(<8nZ$s1Py zGX^?wp)<5$=|WY`J&gBuQ+W*WE z!91As2h>(9G;ZSkKN5Pk(aMrk#RE@X2yP3OY;!N$LQgB zzRW0~XdesT-oD0`8VzfOcb)>VJIU`fK)n~o1+b&6<&La6Xx2f1O!$mxsMF%_Yiz&m zJ(4$@`*Fdk83GPZKlU21dz*(B`l^k2$bh8w@aImix1M+LU9NcZbrcRf|1^@%fMG1x zx&-|gD$E2 z^1ZWA$D*^+9DnDRSC75qzn7OzDN$aWQ3mTGL#dP_>&l6e@SIj-i7?(VmTM-}Ox`^A zU2bR0dm%+2ME~wv6)m%eXe2up=;6I7b1|Li6!pLL!pd_3J~L6z-H$MB;>VfR3FVa8$&+-=Uz)& z?N3)zM;Gnc3UWg7w+lj5(BW*Z&^HN;9&&6~y1PD`^vL0OCg|zup~?Yes(2s!Fj!Sx zohW9Keg55_I^OAyH`J>R8#Y?7!c~Y!fSOwe`Gvb1pMsWF-Vb+ce5ySOrj@c57aK}a zFMaz7AARR=N0yoXbL$grGfYX6|D-68LNMF{P6swv{}JsKospjLh+I$YAt#8i>zsZp86x97|1vGwsetn0nY|m=$ zkM=U=ti;MSm1xj2{l!vYPdJP`0ieJ!$oiWT&;s(C2C9U8c0RhQqM~*ebB|hWt&mLG z*Wc-3x8RWU2MR$j<&p?e^;D<95nAmiR*NAx+~=IJvhyET2@!m->7kf&+&BB!v0p%^M& z+&1iLdC0}dPv~KEUm7fJO2<##ft25`4wSv&i)ST&{uk^|QGMa+wD<>lg1CE=K7Wy{ zO-;m<9u%$YdjK!_dx)qWu()|2i$xN!C3p7-yYnp3k4shLJRm&zb{s126Z`j;<*Am% zf|DnYs&yG^r$NDFH1Yvvp}&Cs2gD?zdS@;a1^%s1ns~Q-*~4z-0sZ6KYKj3VLVZon z!aWBAUYmQpvd`;!maj#HqY(|EqK@QvP4XSB=gHW`2u>4>APzJ2JRUkXp0gk-7b;qd zeS1K6#xM$T-D{C~@5Z+$A0QRN_SJ6jqtJColMn(6#|j!{YL486xJ4(+7op|(Y1R7w z#3t)+6%=`%DyF2WF7_utwr4~X5a~3_3L&j^wDLX&p9Fe??%Ox)N*}g5Gc<7-$L21C zPCrXDDYpJWS=p>y6dzb0&XLzv7LkMz9jeZH&cU2hkZ?|mngl)sh_M2MW2+7)Lsa2; zs6>BzKK`InI37bP7rd48!Kzei_a`p`(XVpdE^x#p^;+1j=^Z|Rbg+eE#_~ZG7h#wU z7tW6mdwY!gQyT;JK2{$iaTs|)554-*x8;;d-xeopk{iO_Y<5Bw`quY)E95Q7a7?PIk2{i|NIon)-w^=k%ZD=EzmX#LBy=I4<&$sD$&bh zXVYQm)k$LhOtHuzs#7sTIcEAoLg)b0fU|K+>-$cXHw+413{v))|DnyRjkXd;W@V-I z?Z=Z6Ab>dU2BO485XaNqJb@NM^_~BZa(h*f_&p5+7l!Hkunj9dmy{t1Y6MDoEkZ6= z@l~xqw~*;Ba{@@vwiDD{*_wH?ZQw8`Va7q>^u=r14K0VFcEu+eGaFv|iduG)v=4Nd z=+SWsK9CZH3i~Pq=Cdms*BOnoPFB>?1S(waNHvD2CAk8X5i#DlQJ7t~303+3G060% z_}%+cSNY_`1{>dtHohsCPZreGo!lOZ>LNK|6zF}PrSigaMzbN>m_GbIq5&L{eU%QH zXENKG+oaQB&!G|u7VW-azwnsN!ft}$F+bD~Pd<%BW-73Z*fpF&yYU^??&Up+5GSnK zcbUj?{O-A!0f#N@{xbLuo&dlmSq}n;mU;WP#%NNM|QnFPSeu}@mAea zq>YUtT}~p~<*$~|Es(HNZs2+Py#B_ST98n@iyLHN7=e25?L4P$KWC)hfkw3~d;giL zwmbo;A1R!7WVj{h{O6aLs;MX8?=3F>F41B@WS{$lBD4ZA>+oF1F0RvdVgrkQR1L|P z-FY(}hSZ2KI9psAU^odcF{z4F){nGZ!=V=SU(f1vv;)+Q4oae_1-J{7g6e@|mPaqC zAg>HpK(N(#aW=_9kz+^*bzUqv?EL}#U5XG29iB;*Qx5x!fx1p36m39^$}!tDt)|1p zJk7sfO0QJe4bojNiUE_17x&o+(sQ|Gx)8Se|2ooN7Ng8V^f)3pdPw&(^jduLOG~>h z*WJi)S-((R`CJcRj{=+#)JUK~oecKlJ`=pXyE(M%B!8s$&>kDF;kz6k1wlCZ{0{rh z^IyW3Nt-_gNfW*kGciq-bb`1;a%K_WLY}M>BQoVNH1~}yPoUb(qxaW#5;vyZ8lVJA z+vTqqRGtYn637Ncf?##^ibUEa6qWsnY%G5XcguKb2zlN|f~ky&lYlaOKgBH1z=c7|fmJ3P9uxcSl za{?J=aNVseJ#;R)cICtqL&k>$jZ#*4T@{dfgOgH5{mvh|HE}hkK0*~snej3hs2-7Q z_W_+yBu9ptYv>RNX}cY(>MHC#_{@bXW3veM?viD}D=NW8D?j{Y&IJDG-|Y8{H}Ck? zW2f@uYm5%|N56^8O0$t%=!){ajrqxk{2TZwSC0iI@hwS)t)VHNDiNFui%=Zm6-d;h zzBVRA)(Oy%|6}oqz*WF61LS&#EF6w6(;*O5yo83b2UvqQ)Oianl;h80SZNmAKpson z;*%vjg?zv{E(d{67ET;DIL%vsL;Qsv*o zfs*Yl>DLLD64A9@w%VUZODFS>G{^qg3-$Sj%~X9Bzdjf|NeMC9rZ^kw&q-#2X`(dz zF(rA4Hq3)cU=QvqH3B1~Q*FH`JEqLrJi}#))HvdsYFW z#Eigt^JxUl&;!@%W&e!fYYY~5@v%n&&lgH}ps-<8hktL%eTYMFLQ>ULnI{-Rp>6af z$&~9X;GeVxco96`x$YE(3+!&rnQdUv8J;lM9C_6s5_%VE`M9T*IuxIM_gA~?SiZ%f zW|dj*a{+3)%V|xfvAJ*4zRBL{aG2+K6S_06-j^44;%`Z5t+5cwXIf&6mmT@!Pg!y_ z6SA7x6Up>=251f2woh&t!K!L^Gs|2qo5hD!rLwkeF7cvB zqX>W#bmTzba8sv$C~ugmaS-!$V=;7QPRooywcYtPY)BX|5%z_LFC%84CR)ijBeGB@ z4-Q%AjlO&Ip08Mc*JPjQT2ItpU*;3W8qo#xk3Oon1dB^5Ek_W)z3!=nT%=P^CVxC# znz3Ac|9RPc^31-O;^^J@XbkqIx70|m4jK{>7O7;sF^msf{OIi4`)r!ieR6HEUhlFx z5G?T`82A{r?WmvPAt|$7vQfe*?DM&^{HyOsdo20W_98&3;jhqRFaEM?=uJbvM&`w^Lr4}&L$ZMC<51m<37xFsZ}MNoauk`aqFv!{;Og+&#? zz7wx1)A4hOUxUxT_^ezI&!?{`B?_CyBXkA|`1jqO3Vtu@uJz)$fSJTypYf5EdSuMQZ*Vo+x|*fc==bD|Gh)1v}PQ=;3$_P z$9=Ex56nDTbF9a%OFepgMEt7a4r}G4s(D>Mjg2k z`Bs05Bhqn$$7xk{&e`T<-HjWD-+nGQ>q8Vk1!d6Tg~pPviRO!UWevmRCXJxsm+u2D zD!zw&vGJr(n&sYa{<<0*+&JANiZp5sYo6vn9CdlX8bQEdkb*>7M>vLAf4qkl#O8|Z zC>c|nJ{p&aDu9vH8Q?2S+Bq;7M(|y(QPVV=IEFkP^T*%ZQx7Dw`&J{)iSLyHLfyHo zWR1CPw%jzvVEgh%a=M45D7DB0S^`a(EqW6j*4TyLI+?q33vD%#P;uNULxJX7^Y7x; z^$j^jr`XigXeTZegQ^>&H4Rrlx&3>!W4yd&f`oe^Fr@ImQII1_ zQQ)%P6}(r9mCrYuTOVQRK9R<*=biAdjNJ9HRuNkwQbu7HyA`4TJ0GlRXoK@h<;N(h zok+*cxrCg0Q}kvMXFkUqG!e$b=n?X0~aEAov$X1Fl3nK?{4@FDMVqSre#&3(nA!NAUWRC-X(LOI<2 zf=FTZX&tO5`XcfGt|{_X?cU_C%|y^AO3)9SWFXve z(d0r^MFS!w--y|V8%SJJrU={@B?|A3C!J$QYGGq>nw|KqdwxtiByR1UVTx;AU88dh zn71XfwPYI0u^E180$j+?pZ4WXP2N2i?D8QI z6Cp#2tQ5ao_57u9TxR9gJ0?P6DA~U44hLvR7l1#2++t>%{9)i&!*PojR|^ZyLDrU2 z!`EH{Da-OH56wWDDlbsIx1s>jKO^(@1M}G)iX&gvmzd=4 zrw~6&#}Q{=`Knf;|m&eBEew#0CcGtsZxH}VYH z--!TBHtWD*^Cmy5{L+sk{qsD0hI6B)v}EbSH{36LIF@#J=S@A2V}yX$nPFL=b3q?H z8-eSGudLc*XJc!MO>0MQrTg29ZZ8JzTz`A(T8|Lx`e0-0dOr)ED>bJdeRxfUtIKPWZ2}4fCqNFI8K0}7`JMAY*fI6Z=5NK;&f$*`)e`# zP6htG7-=>(Eh3VMWID3wE3J=m`&jU_;A|4U*)$r&Mcjr4kuDmb2#>2kiIX_s2o~S9 zS?{fB1FK%(I3SRC7duY%?(zsxbe_cylH@|UY2w_hI{Ib6oo+UYHVX#4I0TY@W}K2i zoF|v4CHMzYEC-)>ZSh%$ONhkEV2^<-Dd zXItdV-O;K4m3n38jrwre;b_vvhxY2i`NEZ5x0k)D!;ZuDL0%)(PUwQ1FaP?~#8DB% zMl@j__3_L`z@=RG&)&_1tD^j2qyY~#M|uJQx5PeEoWTT0l!G*7U%7qNPwF_w(8cEa zXZ6ZsjU7)bSy7}gU}xv>-z$q}!4F!3*J`OEdTMr7q>Ve4CSlfvHV;d{Y3rl?9^x`O z@vro*KO#g4Fio>~dk0whQ;&)KL&mdp&N#Luy!s2}_h$~rP*UtU@~c2;LxS{CNochD zOi|-VfW)!<+JmCkZnS1J;xEimQr zu%+O+kXX()g1>~NDCmG36@SJesnk{^asN5x?yVrv-(eY-f!X2vOoTV)vZx4L7W&Ck z(#9>RoyU!LozOw#lM$8LhK;*>C(oMs3MQO&oDRp32fSRPnn{B?cNXW`>=N;;W2T0L zE1K)xtrk{xDR(m`4sX<;BoueW@716de(-(m)WSiyGw5ty6aJ0DTs^DIr{*U?x65X| zW_p)Hk7jq<=_XC5WDA`(M7B`r7EQ#Iuegos=7Le|I?r zPjC95hns@xxLyeOqi!C&9-0<+s1=d6`x@lcZ1oq2P&l)^O&mmJeopMPt2_w$`&PVS z+4)(r4Dz!U`Bi-vKQ{KkC%6xrM-k~{@0Jzc%r(>LWIBXShX09=prnkp%sN@Z!a2z=5`!IVPf+T zfBR_19Wp!LV zyc$Akzq8-Wc$G4HqvDe0BeV~1bDC|fs`Qmln!@)D@7f?q8(EXzs@63(qGQ|`%q-V) z+bmOojq)WfXjHAx#Dlw>?Q@@+@i%@6bol!S-=uMqBC8f*&F%wCYs`0PB(b9A3MdLk zd_V60kU))}Hg48}RaI~ZVHQx+D|T4YI-OWv*3wvr+(?aCL4to}F&ZheuLxW~Vr8p3 zh5Fw45Q!9}Tcdc12=6mIEpnk#-M%l5u%gIqa^e+i2-yTLG@`gHb;2tqp>{vMX;ylui94<&?@pVJLds=veG@sSrMv7 zB&_z868kro6q)JGI}0X=_?#kXTxxLN$o`udcqi37oL zsP5lPntnUBbYqQu$8}hap)%;#y3dye+NKTf4=cv z7@!5#YQwAQJ?S(62sUJv>XJF0wKd#(NDpW>eN&B8Y(PI7EY|)xyt4{uYr4#kHoSq^; zMw0HZ``5^G22TZ{=~Ei7d4G|a{ds;1KUkP#Tkkyy@hXO~pCGTv;u#a}y?tdpE%;(} zmCpPY6W|*#a8yy3q^|xUp%X8B?9Z{GwfS{0j;c>4%6XZ069U$j{rA}#gLHQobXGMz z|5@{t72z%Kg^Z4Ocw3+ro{;ug*tAeoC)r}G^5f9o_uKZ(k8|dhW#6kc!XRwwla^^^ zGQX`5j*BIQ`bA8LHvnhfdd-zTHt+REBtd7=inKgs7PhW;WGD1jsrT9>_C2BZWNLGY>g zz4E^p%2;`kyC2pbbZ|v1ulqWg zgC9{PB3z(6cad(YBWFN#D)B+TKg?yRPj$i+G%)g==4&Z1jaW^?^R`e9GA0~+2VeSh zMW*-+_)E36b4xRpSzVfk`cuKdr==Yp$s9AtcHu;<3sG2&n{`3+O}UK?`?aE~#hw*L z@tlsd+cVh&h-cgcS0Ar*YUL%rS)EgnX0ALab)F92Xm6FokS#-Yw~t*u7BKE> zb7x4DEsDE&s?(A}< z#Fa09_EnDv8+~OIEB)z#1mScRCQsFz*AP|1zl;z>c$)J4WsFGGbzglTf__Nic9oQG zU%VxKUNaC_B7?Mc7{}=}w#3`sHlLmBa+WK7;5ktx-RN^|Ja{Kf`sD*g{-*CnCgk^H zaP{wnC~-sb4}lE~7DWFS24t}NAV9BK>x?V^TJNLZPM(|JXJ=<`lu^oEZ?CVEk#kIQ zhkEPSee%Bt==q;#_gU{{d;_ZR2YL3+c0d|EMLyVmYT?5>_EDvVtsKx45_BrF}ngJ^@TZB9@D9hrI@&5Srh(K86kqd z&)oi3@!Y1*X%RjLS*Z~$+>fGO^&Vv^vy6)@jFq|?Ech@qK7XV49Qh#n zv-E#aSo%otD@}vm4aFGX3qQo@e;=YK1YW*k-?r;mapTxI-VRDGNsiMcpqew#nEQr9 z$#z2{55fSAhP2XMjgaTLUV;fp!*%ycZ*d{6xjoP2gq*T8$iMk&LSuZsp#s(o9#l5gEPmh05viD6ormbXQ)nS5&ryKi14kfX;b~9WDaj`r`v>Pe%#LLF5Vuv_RL~^ zr8Pw##dByku>2DiS*uMxc>6ymCc*jttfwXA*5tXJGzjLk1U=V)qZBcH41}B0`n*sh zZw+`6@JkyuM0@8TUQmV}JGL?TD_=C6o(dXh+(!K&pue+#W+Xjb3C9yUDXXUNQMLz;AK%@+5F?E|6iHII z)IEe~5TuZ8IS_mdzhL1y5&y+gan-Rb<{UYiPI|c|4Qh$4zOZ`lQ8guE)q9`h zTSCi}7O~b=Mz>}3v+N5@>E{bV-jQDq+w%te9_fFxyr=~iJsS`30!o5pn@754^ID4z zIvo4OIrk)6mNc_;{ffnkk-M(E9Qd+%w!*)d1klGH`rGUI)8wS0<3ZbhUpwuUui7d` z+r$mOwDVL-W0yO!iBv~DPtIW>#eS$s!tey3bjVQ$EW%$+qckY3aor6TQLU*~laoVE zT*fE~q1`}&9jbo)lhk_;>|OiWN$=1PEp1m5bwHFhwa7qwj_}PoBhut{A&)Fz32gM9 z)DYe)c~oC^)bt{X;QzXfQtgaim8l@B5Wn?@B@V^idyy=NdoAgNz@7GD!sUE?UP!#= z-^4_OGTmMwfi$PFoP0ESvh@_vMkPuT+kQ ztK$;8@LZ?JG<$o)%^JawR@`g3U6`%1+dHv2So(8%*NOg>MTktU>duWjQ%)<(V<+Hz zroT|oB(=%Tl$%;#2|^K5V4>6&;UO`674g&`A)f|=3`fD&tjq4P2twPS8n=-W7r5#F zql)nT;K$<$GzVC}J0Iutkq5jBT*-OMMDU_HUk#Ql4=2CPM1#ZWA1<9iV{hud1G5_% z$_8Q3(8{fT?ppj-yFRIw;LMHq1gmt9nYB<0qPyGk|G%jIA@r<-pbad+oezA}`*{;E z)43tR_fofTz=` zTlpMqY@D~Hh?gSCq(g{n&=w}A)|y^?hylVC_w|jsHQXZ^wH!NPL?}?h{eAY94mpeP zRmDr|4^?=;y9wltpt8LjvbT71h~{Z zeOhl%;xqq^(OcS_XaG1=l~X)|xWW7)F5RO%P{Gl~KB7bF$C*xK-e)VimcK#<-F9FB zNqm@cK07bqZ{tSM8_yTR%M+>d!aB{h`poN<{NUlkuVz$J`K0po^fMhY@6^Ih9&;)X zqHHuzz%t^*k6KaU(yn){p3E$3pRnVJa;nS|mJ+ZHv(6{Kkwjvsf()p-lDQ`GCdWnn z_KUL0CN-fBEyal^JhmIwrP?THtkBtkKcDxQ=o z=9W*oy%~$dFq(FJJqwoG_=u)VG{P}ka+H?Xkmws0)WfIM;YF?e7!xy3%e{XUn+u%&f)Y?X%=8ZUoDV&|M7k!y5O(z}j9INGW`Fkzu4}5F{E>Y;A5A?H zUKz&SZS|D@%XS_6(AlcDTIw%cLpa{*tHK|IbX$QLO!RI$|=jokwakI_k z-Y@^{bM1QbmziAV(nn!-b15ubk4gLdhX0p*$e%|oAPJ^MOh7ucT`&IFuRl7;$;pde zqG!QlCg(uJ`J;Wa-vhv^?r?1Zqn9w;0I$w33kk2aqZg6jwWR2JEr1uwLMFXV+0R6* zIphcy>BCLb?)XM3J?z z>EEeIkP5Q)cDwkmQ`RWwQE8y~t-o~0?;0Xu{dnDvrVw=)5WR(I^X;$PiLKTJY7xgT zW+$8{DQsvbwrMcmM6eU{55)Z~N*oVcBktH8e(~*QwmApv-NPMtQdv=v1$ThyrR`BR zk3je^@yI5xvAWf1HoPkL?|I(mB~p~0zd=if$Oz4VywTF8!KeQ-rk`KmNu(0XVdt;V zdw3ucb~DrY5z>A)pTASO3_nvjiV4SJ3I3h%{5DuN~ zn?||+w@-7cnFvE+q~Z`~M1s~cEe7h< zoi_B`NYy2ep`?rF?pL8Cq;~O8Sx}eknh{uoN~h(qpjKaeQ8i_hdTS#Ux4%fRo_kxg z0m$FH%t1r!YPPXbq5~QeC#6uEq=~3Ccw-vyWhalkB1`CFaB<@>%6JEqjjT;V=@3TO zK%a8a{=0s(mLs4BWnfdo;o@v_FQK>IR#TTylZ4mWVrpJxQc76vxtd`~euYj)SNR#& zy{L5dVjr=p_g4@!lR)v%WA)j`^W49f+CRBn@Napz!!PRrE#bt5-B5j-nr->p!+CG~ z1+hm=Y~G>K!~piJ!ZRpfa(%|;87+?EbxjMFYt`vlv}W(y(&o1)94MJ#A}TKb$+iWA zh>NArzRC?PFDl9gX=_9enH-dAK_T1kOk zSFy%fy|Oy~X@7hiCV>{GS9QWqsM@r?d8lI)OTbcOYjk!xM4pycaiE!z=V6*uINu0c z5E5$8ckAM{e@y0f;AU+w9qt_s&G);WaxZ^0@dM|xh+~cUW8kE~!oW*fy zhP^R)g-R7UoZIsfw-9J7r9F&C{*3;t$#J=B1b?xYue4~)FgWdkcho*%tK3-D2XM*; zx;}7hU%dM;4R(zZSdCSG`AI7;ftpONzn;BkE<}0Tk}>A^9)tK~LT31zb0+9^YyBv$ z6*}Y5{{_nnCy*i(Kg85Yf`0y@Un_K|CkcKCd5vEz)5s}Or*Dqc5)!&TJ3^Y@KYce1 zU{*Q<|ES3&3hE<(=|p8+SLn{_)qwajbhsJHij%0e6eqHc`pVK*M0?+H?Dlf@kUBn@ zqj>1nO(PC+J4pRG$8NRqhQ=A1y+0a?{b_*WLH}+j!SLv#I9?`S*1XSjYfV`V3N{dB zL7lT&*i{U!!AyycIArBud~=qx@QAo9%y6BRO$OH7F{f^YpwE>&H+bzkZ&K-rMs^0! zv+`ASeNnsye3)?NttBy{mf&=u2#PTlnw_igH>ilM=kh)|!!Nu6iOvVlI&adZBlljWXoQ%uh|(h-+TJJzu)Wn{r;${t6a^Q=Q;Pe&v~8Kd7Wjv z_>hAHLVH;p1?AjwfN$UYG?fNRsf7!~D_AD0&YiJd9pp#aG5uD)FcRslkEA^fGIzDN z(^>c9@%xku%BA1$+2J@!niO1{ww^1y-N8BrFDOk@fej@+fg$vzA;i4TZ-*9k@QNqR z7&zG;hljNRGJy^*wLgu3Vd+FM=aqfrW^AjiI^;0Bku)sBpWf6iZ>T{{w6A0z(4zOl zzNtwPh0@5;`so*>$h%adA6v8y1?l(3IEkhAN_-r>t@-6zgUDm(k?t+&>rRv!0kfo2 zHX+(|5~V@#ivB1`=IcNux{|-h5OZChaXSHwsaC{BNP=O0fbeXKqX@Ggw%We$r$8J zr`X7gQ(vV64eI&h;c}3ePx9edAzFC)DjZctgN}ff&a>=VL$&^KbMIQ%Ly+DU{q2DK~Iwsimaec>rCOipnyTK*W)*tQ%7r z8|zo*TKq=$yyi?aK%b46xLrzEE`3zKP^W>JLW7pq)J(yRNE|l%0dHhTb~0~G;rOw~@C07fveeTVc{}#LGv5bO=Fc$?p)$C;edK~!35ax3 z5>Ssj>;sM(tNVv0C951(aA0(6>kq&HFxj`xf-E3 z)#=b@eUN4cgC+oNY0w|hld^@w&31$WTOwC*$-==`-!MkXtW)$stHG6T`kDw}Z6}>& zwQEGw2>4C*NQ9nB1#Bf}-0htD{AKywt3 zcfGd$tp-+yxdyrP5B!0~kE{zEz};D1!GVcDFMMD7iRMNr}v5l`iLnEa$ZXk^95uriCQ~ zNIhn2=-J%a&TVfFbmoE_Mh46g3c3sS?B;kOBJ37M1Nz0H#I!~$FZ`N%?oNiqwJKIZ zABJ3*j_NnB{7sT`bcfm1#Ysk(!?;7gP?|^}C?auN!Ah-RTvkdSdRFR#(I8qe+5eX1}|}J-+RQ`FS6LO#;Nd;#W{;>7*^xK9)h(GM9tfK{FP4}A;h09z;2|DL+g$@X_8bx7de_^nqA6=EE$sem68u7g)Vmz zk%3&bA0fZDmWxc_dU?{>$4?CLW!1p!vIKKC?&M9aB*}ULPYkjNxXz1KLA#vck$Q`~ zjez*@z?DFW(52!ff4Fd{C{TdBLwOOUpb?A`3`4l#(O=9}g_;=_Dqkd(A@lMxG28Exy8R_<8 zzyknnU-&gh?>F4my(JiCWSJ*Zh2dgP1<>-Sf>P3b=VYd+#1-dkp*iUCYIsmDCiiMd z>R$nNXoj%|g_~Jgjz(ZgW?rvn2;a!S%4JL2uOT!rokCkjyDR1_#ej2W(;QS+b6u#) zXMmnZN(!+&Tes2dYiBwV8A!VA_?p*}LpRKs8PIdn)1xneYsg41y?f8gfMp#0p@mG4 zg@5$c*T7Jm1!@qUf4WoY!z48w9UbRx&g;K1gCW{2K6m`=f@5K=iFBaMLX0ozXGGk3 zt04U}2>u$CTm|{hzjQ7d3?rjtJ(=$NOl&|?Pt<1)$wE0D5CKN)Dx|kD zeNSj^T1&Y8-@|a(v*N|Aj(+sI%8ORIn_moKHdTKt>ppF4P}ilK3f_x5iApoqXbBx& z?N6U+8sDcWX{-Op)ve1(Dz&c6IQfoOKd{uDPx105E7Q>peGcfY7xm1{U}iEDt#;uT zj@}lLPJvr+y3rz_11Xlb>HZ$;2^5JUj?;%bzEM0g(;==7{&Z5?no@o^D zkL`E8T8AeWKW2g&$SGR2e@H0})AJ0tA>Jo$&{d@v>>O9r+a!VH-HmQjb3v7nK*$9! zQbpU(x3QoG7H_WAlZl1cr0RurLBXZ$!vyDxfW#mp8;$kH=*4O&MUb%bY(dKar?Y~J z#EVM45~nYXAV0l0&d~*vLPoDsReFJbh)x!h(mNWAfy2SaFQXJ?*~Rrb# z8Z*N$Yt0-?_3z=?>(QaWk}Qr5`_rVlH)O=?O&U^)MX@+51v#K-;&L8wl?jj=HxV?L zTeRGHAcY7K`6}7CsV)jS@ehiF)$xPP_Z*piUbQn(|GB4~GtLul4}KQOizc6&wubzh z;VhW$siwg5wWE|0P}-v=8_l!OIn%>1$S~|)@59tIKukcze7?D_O}WZA8eEsq8M-2+ zik~~$tf6oGuuFH{;=jn7v1jZ0{hhNhFYyo^_+Q|imocNsX*@c~qKh}l8dUG`yqG`o zzO|e$kkWThh)#v$+`;Jak?+a>r!YgmWPk#uBaTad%cRX+oS(U}tD9?7YEpP{^?AGE z>7eRuWvk%bp{>3*N?=*eqj4%sozVhvQI*(NUYVJm@LcAC02wSCzpdbVljW#fiUJa> z5jA-}NDj?SpV$>8oqETmj!i=TFt|L@QMhE(bQO5i<%k|vD(=72Qw^DgRbs%W@^-z_ zmRYNjRwIw1Gb|HJ6_u=xGLz<&msdYq2d-7wcO-IF$`7ysLV*+S04@?uSObG%j>)0b zRhmQm6zHEUb6Iy@5oO8^e7DjTQh#cop=v6#l=(#aS6A}mq|5`(+MhO^p}<`*J$$g6 zbx9oJhQBK$DofHpSnLl|g#KB)i~o9d%k;?oWrrq!JhXUO^*E6XJOl>j{b%5=q8N;> z=QP&m%MT+G+kkuhHO|Y$og7>l*u>xL%v$$n)O|p&o&KD1=g`Rx84I*dVVGyR+x~=O z#mp|39McA&l~_(kan+u?oSia!?v(23&rZ^^-;?rud#KNGECJv3UscEaIXHa_Mf>>9 zvE4(}Z~(t9(!jMc@l8^PqosR)Eb6s4Kz6WkZoDD}oQ%nqmAb3R|3Bx10WO_?A3Hp2 zWM*COt?g%r4^)sa#}=h&!Ds8A-R`+1j`A1PuTac&oy8mL_#DDLTdII(wTw(tnR|04=rIa0UkwB4JBW^!Mk6#)H1`O8B zGC8!~g2R^m{JTdxWuRW89Nv59ZA_gaGauoE!T}^;umHETLV{JoOvLgE-vhu(-Dy4} zP95uv%uqa9%Y0HC76`EY&}LQ^a{$rw?*kKFX<+IG?ww?4V1~<$u90r{FEbkFxx&dY zpOS0!y`p9R3TM_R+@CY!i@Uj=^d>y>xHCrvd)}z)-AA1`EkFCnj(K?U+&6$LcA!>U zSH6-~b{T^m@BqJ^YtW)pyu5^EIM^CtiLCW?7^ul!@xuTED6v(exp&w97q2p21J(`~ z`VU<)eImOiGL;RMd`MGX(9a36E@g4a?Djuj@C54xpM?&*Gi!jLn1?BhLk~OHmI(aB zgLK7?5TLhr5R)%-?_7mVAfN7*%!QXt<`?IE?EW;^y-rCUmtc5PQ2B$%H0XlWv#N zCF>9x=0bP)i^_#n|(JMv=S;1bDI`O?K{FKS1Z8tR~j!{#CCtuZaB$ zT%X>lKCwCcanpc2$@S#}zn#TzJE%gU+C%94S&<#8F!F0Q!+D}h7bbxL)8gT8cDW+J z1wTF3uzW`{7COXUW3bBy`6%v(usWEh+EvRzrA9~@l^eJ=77 z?qqc)M;~WwoOg5#3IVCcwgw90351g;LmWmEy-)^nkq7B`Ta0Kc28#M+;6Qz zhnV~u5ojtDG%^+ussHNuINIsNiI4;+<&P=phhHOLJ82>FKJM=nIIdw4N!Fv5-ft~N zImA9a@lg5spk7h4s$eWQ5JQ7#lKKX&0?!h{@Az*Y4Jtiu2_gQf+kL9&`OB{Rdj|;$ z`*X1I`LdHTaD3gib7`@M++r|&P9ZfP-bO2noaB$zvoE@n2vj1K|@j#c*a@VTS?K&HOS4!#3Q#ryvAcT z8(y59`-m~9Sy7N_1vg z=r#!mCJi}!usC05Tka5lnj8JZdOi%EI__s2@bDzqyNrngd zbY~kzXP+U%j_*HjPIySkK1+~0e~%mjG%1zk76E0FyD`oV_H(RsM?){yG`jd|T47QEYxlEXU4_ea`ky=PN6edNL}L)^`0Rmz(RJxSo*udiiGe@F~ebyLWqCHq-*D$?*fOWrs$T$~$pRO=ysIE!w;X=`W# z&V9*k0cG~avdEI@k|{6z-ARzxpEVMP?Q-L*YF{q`Xacl#@jqFFmjM!N^}bFwE5slU zU4TilheO@u*z=7At7PzalO~k`#LatBBzTHqzp>ic_X~&JFaS5=jti_ zye$x$p;?dIpI(YeRl=Q}SxiMOo(o%Lc^#ki@tyt(*x=Xi`KY%ifEEI^OK|&XOkSEI z8VyHNVlS?=b|HB{x1aSRFAk2mKA09fO(8X?>VQHYea7ImWS`^@xtw|rds!_)9X7>- zGX88Xc{o1xr1YsXXz+xZ+|~7Y%S0-1Zk2w_dA*j4l&ZdaPiy~HyZ#_AZVU@MrHpk; z0(GF9;fgw6IK*;EMgkhkOQh#iO!drlsp|I3aR1<{R1Y(2xIJ4nn?d*U3NS0s|Kk0x zT?*Thw^r4l6uPA^4=w}b4ZGQH(@0I{lc4_69GVP}5EEsY#fJ1H z;j)>+UEi#DK`_#>aiFUiqhYYyegEP~M%wdOsHcDamoA-K?g@YU$qL}c1s2Zy)y z&i&`A^SP0BvKKEJM{+>@+gD!S?*TRGVdqmm+pwdHVUGlO2K*4qH&bSp+=^C@eYCd1 z0e0aQ3@|DCj>|71Ic$i#WkDWw!Ed-iJcAF$DQ!|!u$`gQZQ4xhV97`sC^fAz5AVnm zea*bS?X0WU(VD$gt3Ccy{yC7cnx-}Oaeox0%3gCbkMDmez|PvE`eYP<*v~*<9rB@t zRbCW%KfC9{d##O8Z@w)f6K$ejdvoIRn(aP?E5c!al~pB>{$q)Zh4)pXoxnuQj7HUD zh>I#2O#WKehg*WQ7<>l`5Hz93kOeK|yW9B!2&R=k-HeRcdde+BX3Dw864pH$SGN9r zV`u*@pZ`U`3wg0VmsRCQ*iD<=+}diV5K!v20Ex_t)jxmy8vtWCK~hz;sBW|3>_(B* zm2ao*y8il@9dh)x6ag~)NYJ-QX8JJQT=m2&_ZMPJ`e#(m2T&d+)zV-ZbSfYGMfAnu z6@tsu%*k`*r4Zzle#mooq>^wrrY_J^=W{h@kaiJRj|nYSb{HE(Fh+{IJ?WoFj8bjGi zf=*g`Ri1bA#h`1RL#BkELaom#i9n8Fv{ayIx3BJ;JOdKX>TYi16Wy>dN^@jX&hzq};#e8Vs)b~*Ua)8s`?O+EF zf7R5CK9dZ-xg<|`oSh-brllLTR}XCy%j`c>m}t>{=%Z&bdD>}S89aLRzi#(L??e7| zcd{~+d?UwEAAG{GfM)IWr0giogyejF09)g}dri?X%n;9aucZ=H zKvr!#Yc)4*`P>-6eV9ceu0?tBpoHNh28kO@ENTB*(41+g1b(nk?&FYKI>&Zsu|Uso zWE?=dL%u$$=D7kf_kRPD=m~RP3o-`lbZ^e)@j_x0Mj>Cwjm?b5>uwicyu9#R*o})6 z+8uqb(i7AiJYn3GV2y`U55o*EH-xRyEK?mezkFi z6=lgooXT+pk)oyL(jOTH|39L(Y>8 zDIDzxea_Y*n9r^k(#rGyoj!Q}lZQB#c_#*x)LFrfBK^_OW1GuBLJ=0aPsVE>?bUx- zp4(`zXi{Z&NUL>iUs-M?fIx4p6u|qX>Lw4nC2IjqH>aLgB4yQ0e9Owg)8K5IJS7ie ziZA7&>U_P!C5Fy+2*+4E9m+Y^Ou>NTBaEP=E>AW1N%p7gjIfbmOootUHZ9wIN;i49 zFD2>a-$ZEZrPZUMPz>$o1d%pONTO(LNCYdyR10HWimtc4SAB~6=a?KOPydY(3MVlY zUB5>Miv@2=6kMj}c>tk1U-1v2(+QAdxGM-h8{lF(x?R=q`6ltC<&DP@jg42Z0rb)YfEv1rs2LUfAcyl4@ODPecC-xh6)rspxAC8iT=r>(E*g0?Zd|J(}yP>@RZ7dH;cw<3DKBxVT0gR-}aM`h5Jk zhPW6?KaHo~c&JMV$QEioa-LmjIgX!g$T}&O+QmODDY5SCJIK1%^}QXL>eLvUV0fsm4?g}&*DnlYGl_3rwK*} z-EOX@`nmky=kDdY+~x(DCCImKm0p)uQba1`JL9~ReR|D=%OE7^N+VMrVx;W2X{hIywlwv?dUc|d>2$Z`dA_nvSFFhkN-?;VqgtnnW_ z1V20q259bZ34fB+!8qs){t^9a9Ap9WcPOKFg>_OFMlhlAy)y6X$KQ2CSkE$Ccq?YwPu?X~N;`85mBKS<;fR z0EtnEkwr4h(AXZda-TB>eccBKQ|8l#{ubF@Td5$3{VU!jG9`&}89-_iv zfRq&Q*=3Lh0mOPUH(!l33ckp;Js}uGgJIULJ4Fts!Y5&g=a7KUKvq{AvO%{ABH(%a zjsbB8ooUR%1TW@Jo+O9Bpj`^SeED>gm z?N>Dr*wP)KBlI+&5@g2?JUF`rnaMXP+?e*rXP_~h@lYCastfeY74v(Q`?6r+3Yxnw z+VK7Yr`G&el`|IjE89e5N^_hUlrIV`7t!8Xr8x+1WbM#Z$KFCFyj21@tjf*Q&~NeU z;7MflHw+8E;ls^@vRJvREs*to^YWjB+1UrIq5;~Kj_x_}ro?1bJt&<2l)K+nd4{(G+kwD@LuweC97uE%S#(?d~~h3(I7?&z|9Wj zVRmvf(5p&r3XJs~u-trN`#Z0#T%Fi&gq~c!X&Opc8Jc{?$R{&??+tQ7PQ$a8Hv;-I_H$Cy?F^9vaA+iPk{mM* zftp$mg@gWb34t=dA^+lp$O+;Zbw5Yn3idK0p|*NNv)GvzJ)QQ&FU$X`R9gW*3>r)I zsXl6XI9ZQO88mTELTLkSDObL>dK^XvSsmSxRK5brj=HVl7Q zDj5Syh+sheZvFB_!w!X8<#Kz~ z#632bcPZiZm)^5x9qQNwByAxHQ9B+pJ45pR{S6D#yYw(I)(Ee@rIYI5&k}GkGX*>^ z4(L_0S~N9Ly&qP`b|3+BQ>ROT=^)t2ifa4EUw{*BTP2t=KR+(+MHZFltl_+0=4n** zcwB92_}w|7Dp-PpW8n-KAK5MEz9Ze!h_Y}=H2Hh!b!x*j8ff4KJ3At(ixYf&%iy!n zKa_t+Az<3CxUeb_2f9yV^4sh7zLW|cctZuBzh*1Ah0zKCyk&@v*oFot`juoypq-KY z5)k10r?(<^!4${ilOdB*8*5ef8R+ZrikWON-^@K)zh!puf)vqL!nigQ3hLEWi65fz z5LLd>KGK~Ahjbz`gwFCB*9y=GJ`|zAkz?Va5Fb&wpWX`6J}@t7CCA1ESWnitWjO#< zfZSO%J3yy?O8nH@p+;&aJPsJCcezihDla4??Yo5r#zMtSFMKU`uOSow&q!OZXuL_Y ziUnTBlRQR_eGY!9bVxwb;gAuKG|e*Ui0;?|V^#_HYlua{P;!vS9}M8?s}X*4Jgg1N zX)~;Q%OC!Sjh7~r&G9?s)ty`&uJImnjFj*xKKLC!&_3XrD4LV(4`~NZ&o$97oMw5& z4#-u^0!sG%Vh_6Fs4-5vpsnsQyX+JC=VV4}r@ob@LoM4%ErU}}@~cpbJn#g+`JfIz z*k+GC>_>d>Z!m@7ZeP{M3RzhR913l*9QL>V2sotm{CQ}|H#ul}L>2zxa$aYvC%H5v zGWuR1Jgdjd$oY~f(c^zp7LCZ%Z>PcAWZf?3B6)e6|44oOFsc?PFt!dCTUy@FxKfy1 zjqne-kfG=yOPTtU>n->>1C_(uXuGOCH~q_`b687`DJ3{=RZ{TUcH~iH5fxR};h1Z~ zq;{d@$#m6y(xLe@P$VYA5>WG8CJm$^H^sd zi1kyzlmY)ilk#KV5f35?%mJB$5XR#Cck6`{pw5x_E+sxf#XRnlJ|mI+VB1>p#lGwz zLrb`r1p{-UWDhKNFM2Ur07oJP5uW5nqdFPFEQ;k`u0nPVnQEw*yW~$Wi{G-ZM8i8< zte+^omv&c-2}PI+dA^HbhIAatcEzIqKKk_mnAYge_s4#KwqPy;+v{|yVjAM9|@R{oryWoXr1vK7zs`5XWNk%%YVoyhX)%abZ@$cLV~Uj^F3oFg(Qums%}AEWsq}t- z0HJJrN(ipWLV9XS8-Gb8=lJ6iALn8oZU*ed42yerc%cYP$onI}jLaSnO0)->V-@Mk;wY#$KXw>ewX&D?{Xp^6EQK)D`sEEPV-{k zL@P3(kjdkwqtfD#;U*PF-OFni%xGm;nSak+n_YW0*d2j$=QaG-Z9mu+mt^3!+1ryU zKb-%iTDES8?0t;Uzyv@pzh$jq!iXKd-FW=Ad9~Yg=ChIz<<})Vh*vz&Y1Qk`-7iqV z?{=7-t(pgKA)E&DXOrk>b35R>D(7eRB`qxyM*~?cqd0b(|IpdtW4A_C#RJh9xO@BU z$mO)+-x5&9#F!$-HPr}Q8Ly!%=`AVCJZTYb@Sv;>>1msFp7y;KaL&w61Tn9M2Kzst zDvx?DUbHG03_N<#ydxkf!UBJchVJJ+Wdu#)Q}XtJA^Gbr7-2*d0kC{S(jfr?Go9QH z=5=+SE?SjZho zeoaC9G3Wu6!Tyw|L0Q^Y%>U7 zWT(<8(3)nOdB%P&c;{Oqm)38pumA=O$4=-aupD+eI;v{!v+A^s)0a@>aY~!V4Is4w$Va{E{TJ#&<`er%^zYq;51ezI_z-q%m5M z;7hMV3wgm=`#m1AS->FM#QhHqz4V~EKD4j1 zn|)TIiQxt61D-%cdY&@j>S?$*Z}O}h-jq)r+F1nXq!SFSAJO)0#};K#z%LCcJkrx| zV}7QzIsaP7qK=$DRC$rYo(cRyNerR*ur~&GrRoN8vE$*c2bb4 zUM=MRrfLw-fn1O~*GOe$hIt^pI1TZSn+=2hQ1`Kry&UNTY+0||^+qKllcyWrBg^h~ z6(mxKQ3F--jj1LjJ$;uq`8h24`qn%%XDKrP_3x}`6=e64DYoIGhfwif`_gr#W|p)WKhG7 zkU-$y8oYMYV<Kw<2;e+=xQ0EOF?cL zOz#;z*jih~Xe39lC1`eA9Zo8ywIdl{l+&FjH5r&e1DB5EV?rauIyAyP{OzS|wh4@Q4XdKSp zT>)sAW{w!8{i|Aj=oET}G*HM7s_#xW5krJoqxbbeSiBw~;IqNy-7{qR@<0QQI?RR} zLq3pK@%s@iG+bvX8+7ux0lFOyQG7ATp@Ck%GKPvv0lAYjdl8^E{sYk(4utQMLV?PaBy zU!3?PiwAz@4gT0mWq-o!pU=bs>Uf;yK-7w0*!MR==G?n%~y^w047 zd+o70)I!b?){yJ7M-a_XCI9(1AG@YrC|6gPL3Wp((O|CRS|Ky8VsC$=A3s1xU*Jr3v|f;@J2Fr+3$m8gO70#+PO$3P*^0R1H_^AbX2<;{RmhxbM_l2*@mY7B|aLU%!txaNF%lg>E_alxtFuW3Eh@ktQ^qd8J69I8@N7C}6v=g>krO z(aKhgG;cMHw=Oh6evAW#nLKrwN}MA$6AwgZ7YCE%+zbbPauGJ8$(v**hlRN@Z3YXf z_MV>K6&Ny=^ur-`#00sWAhRs-1r1K`mLj+f2iP7u@BF0-0PO|O*7uCBPqC3fDX(^= zYw9sH=sB7b@Dz0WC5)V*P4yN=IH}pa2j5?n#_;8`J*jmn zBWbM3lS~E@)}LhM;L|5JLi|QQ-n$tne@SblgDW&Bu@aybkHRsM$ydi7KqtCDIqza- zYWXWCv5O1(V-r17#sQS11PuCUUZ4IfvX}^Rd1&soZzXd(gnjg99J)XO6;Xcg!h@Bo z&-uc8#kfCMAa@vHr1aEMt7(-K`Bye9#3Rv4BslL>v05^bK6vp;*zvoCw9MeWvBs$H z3hH(?h`qIO`IqW?ysw0NCBMQ%6&hbx z9!R>K4ylK5aGanFuLDI$x=31_U@cEJVC`K*2*V?Mh~-u7E_aZr#=uiY5X|rAvf8 zT`Bn&(Lc?|0sn7aV`ii2zzan%!>n;K#uNZC9#tl-DlOWyJ}qrVTBBY zl?RwKS@C$%sUb8N19s~v;4JLlIAjkOCeJGSmun)RvHmk32>(2QTxkuxL>EC-XI^Ca_cq)cmXIv;e2l|l9*^~8apQ+0#C z9~Vpl;LhFDa72bZM;&x(sk9zAIj!mSk*zz14Y1Ka0GOFQQ1WG_FSaOt?*OsfD95q` z(w-qJ=K0LS{HK6nZuhF;se!ieE!XrnMbal`6XX~M3455G3-dULO9!9Q?a(YxfuoRq z#tbXzEPKa*GrJciTJXOIbBmrQSqPpZK^nf_extI9Bdcq&n9dfdfn7{SrIW$jU#G`s zOhtgfP1ZAbHx!yk3l?6t$cR6< z#+>r90s2Dg4x@qeU0?UEzIKiL{Tzc`f`p8 z6O2L{K7{Bp0f~f%6ig^fgh?m+c!LBNNHVZqWWZ|AWo_&NY`bT7*CuGItu8U|Qv}Wx znLId9&t{e1C+7~6;x!Px3kDV`z_y1aI2LsV6vKylK!j_}LfboxmGvt!~YD!;+OpxC3kR#+y zOQ9kpuY1VAY`8XBqw755ZALrFjB$sR`K}WsX)q6MKQ9qZL;8;2JYwfUkN4KD&dnCK za%1vQGhrrRDqACsCeTK4Xn!ro!#mZaTi(dLY>-{C zyZnF|>Y{@}GV{`%&KZm>J6j@=U#e$bRhB#I+=#rRnuv8Wo*8UCq85WhP%yI+!3XWn z8mWDX;v_p+@eV4FA+~?;FbaN&ck^JMz^xoa)bc#*aS;8gz_c}M`naMj)H9%izQJ>; z+R&U7^85XqhuP!UyoG9$@-?M_)9Eu2(^$@q+%uX}wumvey>|_M-do5>7l$0}`_+_6{$7&-}tx0l$T8Q1v zz?S{Mx@OO28NiB>M9gfvDZK{z%iqDU9CCRa65MylK*qms&&TEXyZW3X!`kjEQ;z^O z;Kwxy;-W@sGhmikw-mETs2qm8LIH3DtRfaA^E;;2>Vm{XZJb!vE^G1?#Oat@K~3)99w z;rfQpqT{Ew*e)ELp zey}QYqT>ff-A)cshFc2z`ru;LT4!)NsPevna;b=2wMb=*Vxaa6v#}20@TE_WkFSZ# z|JZC7o$q^w9^`4iOS^waI zJ48V>(tVG8rTysvaF}$D=_|oKWzRU25mrWy^*HY-;(osH^@gJ2v?9pn!Gz1ybME!w zC>P_D+l;RtLJC?k&tv8#wU=ICC=Z}zygJ~E=8gAFf&1)S zt$Rz)Z9@+Km>AT!1l5vZtRUK_K_S{uC#BY_%26S<#BZXNd|Hf*jM78m@?K$MG=8u$ z9sSUBSI3|mba#@#Mtck4?^$1LcO&iE1r6nJ% zdvf4nB%l(TLjkMF)^Y=<%(v(DA|60Z=8sut(nw->i{k%oks4#t`3ZIfuO*c&49xD_ z;U$6!)1dZbZ`>>Nq-N5W!_nxEN(sdoxEBwU=&1Di6C9@<^nDmP2)OoL0SWs>wk=bK zNq^Yr?sUj7TP)PS>#M?mBAglRlG_DZ3sUlq6!~^Ds##xX5uNK>nU~LzeZCrhX$jEs z$~WL>Mz)W}D4Yq}l!HWmC*7{zD*r6f0~XPe!8I9R-5P`}kSx#K=-}vRfPRhuW@-|U z9x$?ITt{8F>$qkym1>gq?@=`AP?cx?OFp=+ z?V{kHBXC%tbMiFwKsWk+N!@#)QestU@B@sfi$VJ^R^3hlvAp}J+YjgU>&x29cMaWg=xjcJTp&$0**3nGfB5$`)pSnk0xd$|lmdblq+F<(TTiXuQqN+f7jMnidjs@R1xd zm7j^Br>*8aC)5GcodJr+`k1L%vMuN=nhEAt&j{GcS?~`^aMG@NS zX@AwYjo-0;0%<%ej#o$Sp8fot@c82f0AsWYd40Uyb$T5!<2cZ(83u7)1~ctAq_7|k zF9~S6AqhW#B5WAyh?5a(n(lXnumRQ@yMxu{d#U*CI#Leuln7RqK2ef{oAoLytEi|{ zz7bClRD;MA7?Qd|#hiiQk2az5q%$6_(wk?-7&#D}JqNg~} z%%almySNdwp!C@Q|HWWVxgd%Wlz8r79ouCoVolq13fLD1X8_dCsK_D1p(rv+y3v4J z{(WBUPinEc#L&WY-^%KW5bq>#p4X+79T5}-b^^uFGi#{m6dbZR0Rn?->AK7WRx?gK zvA8c3XMtvh=m00t5Cv|cj6+@kDSgqn2(ItmB(yn6SWT7eM7ndjjm7q?%3+s5AH6=E zc*sgkh-mZ;*$6|a~R+Pgb#WU6m0C9|x z;>5)?j(y-ariI7EavaZri3SFhVTrX!_)uAId71!p8+GFb@(dCrFnP97oy2=$xBgd# zb_>FR-kU+DG8+NkPgJ&Y|3p69v=Quf4EcgD9Qj*D+DqIsA?FSA^ooDI`*ZGjbCQ6h z8V&T2tk&r(djl`tb`g%M2y{3qo=IxAmlP%G;hKS~5vexUV&-M!$A{>SLz@FEt4o!@ zMGN$~=)jd^Ia+3a1$#b3b&w>IT2eRvD#XTU6cL!1yG6N;zNu|aa6f6$Xqn{=|g-=<#x#`Tc)Eu~Ylll_1 zND_})UFFDXjw_^Z7L{oQC3xFEIkw8 z^iAfErg9g0=}hnG!lm?wKfGaR2c_Rya~4I0%jZa0q2nT7GTzJK{X-^x;u%=k&@~P6 zg!hu86a(Y(bNYl?A;wM3?9v1WNS6B@8IPed;wlM5mYh=l!AYWjU_bCeI$Z!MJw3JG zyiZO@it3!N_B=fJofJ)Z&L3+yK%AUDvBvGWMAi#U_Ac^b$PMW4uHT;a3jcL`%F{w; zy8-mrTw&?q^AgabIxRzC7|nrRRU7h1>{T6qz6MyK+}6eG z4zxbx@UCUmu25QH=!*}$)8v?xM-C3*!=!PZw+YkNKEG?1W0Tf|K70*Ckk*9!LED{i z042-|M~P*LNc0$kI|FvL|6Bht@#{4H>n6DEa`6J1x{lm@Z~^d)q?${a6lS$RC;Is^haL<6OAK;hRPHPGjP!hvCw(m zNhZW?zk{!<5BwdTc^w>Y5jHR{;4L^yXPLWva)Pw2N&D_f8epA}M z;_7R}B!c8nSPq^Pxu>_lhxbs0SGx8Uau#2fHGb%o-5hi3T1%u)29Gng%!eT zGLzw$Zxu&|ct?UDS~8=QBU1y%Dq$FjF9Ys?eeO(%`VWQ>v{cIdGnC22j9gF}l(QTY zs*cFB2O~5r63WDc!VjcdMx9SejP&@j^IksGM+NNLB=d(vt*g3j`F2t8#;Az$#Aqr5Lhwc2pO1S2N% zvg#uOb5H8;(URz3z>_==3~7Y@tW>PIZ<|OfqQ=YYWM3|%FKO_srGqfaE-s2%9jlC_ zeN1A~1|hq*V`pdsEnL{vbO-V_j!rl5dQ5{jS#QkANJBB*qvNRh-w zuhN_J-g|%~=Q}+2_kQ<2`u@onjFEHp*?aA^=9+UZk_ihbcm}-BN>uiy_Z4b8EYA%z z5lwd>I-1S5#%v1?xYlz5Tz&v`)hM2S%!&+n5<9 za1+aW7uMXqg^>&$1619&>v33f##cuLUx}gMcikww4gNds6QPTc-xv{NgjNQzoVr?mSf12qO3?@yY_WPhR`Nq6EqMxEG$BgT&|ErXrqESYsQd4Lr+HTcU=+M>h6l(hfw@Gx%gPW z#pwWBNW(kQf|(1T!8KGe@%=aKbg&{b({^^ZRQl27~^-r+zIgw5CyCi&(?vmdvXlm?9wQ!j$ zz7tPHp@A#{5a|Jd`lp4(7fhQCv3!NXfC_@&;k4Ce>z$I!fQ`dUTg1D=-dq=zKpO-N z`i+AuZJXu10a-R?dVn_-iyp}sXKI~H7N_CsdqJZZrkzvhX?qn4=VjG zPDQn>4p+vzxlMc;dnyOmQf`GSIDSw3hM>A`AoYnN8xjkQ;lw%NS~%bWEERHL6Uvv^JUSh6wcTO&Ht5Ed->WSl*M;v zz>(QYF5bBHq8x{cRvnx$oS{;$cIEPA-%cV6(Wu3$2V&l=kQ&-0+F`Ju6iBKq@I2m(}PBmbkcpu*R46JbU?*JX* zN*|?%kUkfeOL0?n{Ep@&2Fy`Ir5fbTB#6OJjFLx284r7G)jW4>$%li@!=V}0S~CAyoJ_D2Kf69Ye7 zk4f`tQyI^-A)f+m*dg<|)UH-YqYW97g8J&;0o;STsR^@1YUMQcECd{YgH5H=zX^iO zLG7ghF+aYU-a2lv)&EITlAaTQqb$J0N&Q6)iV)?R&a)#&I8(d(!Cyn?d1-J*i6y=P z9mY6u_EV^!OikPADwEJYYY=1VM_D}Bw_Fqn6scJWqxs%cmbklJRh0y-t7ZltDh(R2 zF}{lhcXcJ5)Q6+>y#1s4zN|br{e2TdMjlLIoG zkV-yKX^sbQJ6x8k(}JgzUt9q7dv7eK1x|$=7UFl)RGx|7fchaCl5CLh*3A{vE3`j> zJ2}7!%a(uX#dih$k8}4pqVI4ZGTj=^2p0<1po*YSm=`!Cmj z|8~J8E)x>~K#79xd5!B{0afe5iyHf&tR=a3HLPd0Mx?L!%>OL;9BK{xsD$5Z9Ul+p zW70>H?;ip}G=kK_p3PF@UupQVTpWo68g-U7G)Q`*m2+?e&LaTuPM!m@$j&^iAwQM} z9_pLo1HU}IX+{tHxb$iBFkf=AY7M>?h>Dz6O3=QexZPv>{z z5{^-2d>cD+xsmh7{#w$3Q|;Pg8GC3j6e>tSoB!Fzn@3us;75ef!s4PT@Z{y4anS01J9G;1T$H(JN<%q&%cj}r`g5O9 z$nYvmqTsV&M}4{k)IP9fXYqvwCSzk%ML88)&zv2A%hv6-)uJpBYInzQl?x}`giO&E zYv{Y8V2Nzr@q=i%Ye0ZDM11*v1^vSQjWz=*T=%jBz35ijSJIDC;Np4Q7zZ%SEA)vc zV`Sj)Nme^mFCV@}r-tqP$JX(0&F;nRbE;*pucHn-I%q@@k*%O+5%r?d)vxq zWP6lbCQ}Gnxql+r;T}F*#!yT#%V$U%YJCqjdTe2YW%B1E1a_}pVU^}>NS#$! zdw2ZXJ~ZW8TL8y*1Qk~jL8Y8lo^e~_gCF9e;)_SP!yyi?i)d&T&{V7S2c}I5#Jv|{ z!j-}HqCaVzhCsVoO#C37EPZOz|NpCp!4&#~oe?JK$}8gYHQ=Z0ywX20&$w-Xr@dsC zaid*pBOAz_mFLKDw#rYCfqTLlIQ5^`nbAcYrT6}-yL3e5D%`UFVIeer=Ed^k#tg0^ zh75Y#Uh`PQbeqSi@<%N&Qjn>1n_m;meBr7%iY~|WEu4A6P zpgO~mv>wLD4Zi@aq`Z9K=RJ}B+1SF5+(2^}phG5)y@eDu#ZmFglE;4ls{lIrdhey$ z6W5z9PohfUguvv{-JL_!^`AHUpT#}=PVhWW(7p3q>yDTpK}sU2=m>6klTMy%Xp$|* zl}(5(ACh6ZYX8h~j_et4zV%=!M8=TE9X?1GlW{nh1p2D~`xFKc&B@FOhG7apUh#sh zabJP%cHm(O=wI8u(sCP;ZD7y0@O-Ae~i$YgsTeZlZx|-@UQ^`w8bOpUuHz)}5bbdLvgZ zM6g36*|e+eCr<80W1UTHz#pRO0-S(g=E?v2dWSn$fR*1d6A8Gtp?J>7Ib>nF}-8lpMdpDZbXE?BVh0y%Vs^BlO z`DxvID$q+a*ksX7Pz{^p8(%rAb?&fD{eRZ;pC4oyV*>aOOvY~C8Pj-R3cD=F1W2Yr zuIQ#fw*cI}0-hynP_H<@{X)WIFnI3JXy_?0MxW)cc!b5&0D50G{dZ}s8Mj`T=5vkb zq`WwJ)wWlzg1G@}-Ub=nbh&X|rcysMy7f=v=YRLn;W`Js;m6rxZ&UPt!#DH;;~8Du z*V_ynwoz~=|0l+smSmlSCmQg8ZM;~!Lf)iY_ z?N_aEZq*;pLV#W6j)}u9YXl>!obb5Tar3WCwYoJl)PgOgUS$=d}dfTsXv8(*O zK)>lok05bE>Qb4vQor!2u*6F=b0Qe{Qz@?BJp7fq7aJx;GIO_9%4)$??2Ku$->BCS zUZ}~?rUsgo?WB3N$jzD`;CIbkp3Bv9d7Wg*C~p>fw9a}_CM8BkJEth1Q9Ao` z9=IWJ;+*6`ENNC0WvibhDaC09dU)?87+nogH{vH$DmV=*B-Q$!m^;*Uz+v$7kT~M- zr~dbMtLcKG1GnBLo&mAVX!DvArrq|bn=>G~1j#>t2&pVBeQNhMi+DSexQ2e##&pNa z+vxkN6ruTkAr>es)R(@wvEN?(lY_&RM!7e=_Nq+&KoU5xV)Sgiv~6`>a829v>4RW^^o=0ySI2(f-6W2UC}A>_KgX4k09??LE9#NEQ&C!s1WE~`!|#iMCvaQtzyVXhmFhji zKysdGeeCb%xA4VlxO|DJDv-zMT6^T%FbbmQE`d3DB)n^8b`~{fr;fOjTIP?EK^2BxC;@p ztMc~6eC9NsQ6(Tk?6Z>XPYzyk#=I`Qf;tZ?x z3z)S146_>>$@_h=uYPiouM|0K5y4X(s|=W)Xs+pxQ% zW;7UR6hVtn-&`!wDelFiz3}q5S1pOrb`cnYTDfmQw4$Q~hO&1jsksKp*jIzBGHoC^ zNPnU{e$MEY4r8WEek=(n+F#WoW8SKuGQ6pj`7aQ{p5qNvai4l#vj4HGF)Yd}sEZ;h z?{9#siIKq|I(LUi-mL}WNAVK~22TgxQsfw9C_oLJm-(f`sE9-2uI2BWFiAOcvphi( z6mf%$x-9gC6A_B#=!!E|gG?PM(j&mzQ1EGZtt;}qE2Rg*$!CJXbfbQWeZ|(S*Kvcv zm;Q>y&?jIqxQ;EP=n-ePUOG;JHuNpR^~#BBt2^b$u@mDq8&T75Z^H=R#2e{z&aDUR zG^@M?`YASp*jxVQsJj~9;25Q*Gz{)na4UXgvGzIl8@!qJ1OTBPHnQj-g%oZ`utI<` z3MIVLn^iR=oW+$j{r$aYDkL|bzP8+ANL%bsta7`h1J~;szdhT`v zPG&B?lGBg>{^sjoDMg9e7@?pbHZ*KQhx_SSnKpX&JEIp8K5QU~t8{^ECO{@)e&pA*opi{Rb;Tpuu-I!c!4T1_O807<%&biaX@m7eb1qw0vFO0R(bIG?TH>VZ8N^5}aRG{8u>I4$(&xu1Lr zlspLqwURa#YhF4u!7-;J7fm7gVukAWGUxHGE$>%9bW-YPZx=_K<1rU20U-?e1z z*uk!L(0(EFspt$*3a2>AiSkx3z|r%e2yyhXMu!xY0DT$Jsn&fe%Ut=40N+p;A;^te zg^CmY;7CgEWlLO@`a3Y_>`nEya9`Si~N$L_aq%VaU|XJqC~j? zM8yquXl2VZxE-m8z|NKcTvLM3IW(re2n~Eu5T{Yh-Bay__QIH{(4#3|qmvlptp{HG z!<+Tmd#4jwJcJ`dv5%ggjy*P{c&vL?^woW~VnD1t<#tppl*m*=r6Gk_3$bS6N0Ord zzMK?=_|2wIOU6Ao9=gM}q_QYB@K~xnaD=DMWxdZel&lsT=~YuKi3BlrKV=n)pMs*2V($dnL^OKWFlP?~8I)SPK}dVH$INVB^xc5wTG)SrVA}A$z1X zyalZ1_Na;Ve0QpFwv;p9H{OE^%5R`-YEi3c1AkFE;c0}w&22FRJL;}?>zTfUx@Og+ z=9odn;~oADaNFMUp^S$=7;&2aB{ZI6C6H_i8iYx9nW{pjl?<=KXR2J2k(=1K7H|ND zlLD;z!X0?sV5ZyZ``AV;BMZ8E-k=|V@=g-3+#7e4I|9r^lg63*`25#BrP(d6IB@M--shQ=nfUH zVQ`pqmeu#OAtCQU`n_&RdtOxRkmKugfu@SGwu zj{R^pmXcTknD#OO-4BXv8;j3()b||Y{i&|i!B@JEzN2@ap8WBM=*YAPiPP$e?obdA zZ2#+?Ca}z5D6M;x9`g+iA)H8UT2KL+TH>YN&l_?g{dk=F>r5p4L`Ut-;7!QAXJPlh zZ-0K=9+tazgSMbCtK_=zy@aJ(#~tX1pdFHbJbi(I(}@<8u3#RfQGTyYT#X&b_GAZ! z5KEn5Qb-_|vOU|!7!=k*%XjSE{$_N=Xy8Gfp!0-H*Wg;UcgK}I+gb6ogS%gJg?sy+8{CSFyifiR>&B}VI`ebuSrOETx5Yw;op z_khZ)0*f4lTW=9gL4fl|w7QD=>9*YHji8Guh#pLJ_V;tJF)yuK=LqTKfpqc{lB=|m z0N>vy&F;w|BTM?=FeSCl6`*Mp;Gi5$W#|gD=Y#{EiWWc`bRS6@<#hbIzEXbPC*EGD z`Qpzce?L~JobX#;){*IYIdGU8YEs1HldLDFPy0EX+Pi&+s$U`O%NcGSdR*1s5*@!p zu#duT`~ULmVT5q?txR-}tsN3@odK;g5+WyFHJ3U)MgEfld;Tttcdmnci+sYk#N}PjkMrqbS5@45qz(QoUUZ81s=R6d1 z=4)7~`;p~)(SF18*bPzaMlXVjUGuL(XW;38 z&k1`Vn@ylN@X;;CWfS+{)5I&r&#ErtM>uiL8u4S;txjKIA)fffR(_vo0B-+lT?fYl z%Y%JKgxPYXL*eFjm0TUfMTvx_S6cOCv1(Nt)5dc*o&I_+aQ!FesP}SNA4RuJl=-iF z!v7u0f5j`^kEVn=7n}~ulXIg)N1QHbD%;0GbbZgW#-M25ZTqw;>Se&-!t5MyJ!#P7 zxX}Oy;tkNxVOqgk+DM|r>kVCaPTNw`6`F}iVik{1)o!($)%t!FpmGPQI+uL9TAV(! z(!f2TCg|)LWSU|L1y6&8ubNFe(VH#uIv2pgBLk%L z9;|Q7y;5L7@kgczo0;@Srp5}+Al#QPL|(Zne@l+DpYORM*B~K;r&cv=?Huv*YQU#Y1kzJSU(774mWlqEN3bAjT@fgS0%Rk7 zX}_;&NnPAyou7i=TSmj#fsjz*&0^CN+C-Bg!t^o6w6Ener9zv&<0Z}c7=u^W9j5r3 zbn9V3roaiBm;)n)aXx0;I;2RrB|+GqoTQT-g9BJM8sBEAii~6O(f%$^ik?=sM!tnR zm#&YjN_jk_KVJ1$01YOXgyPDj!6URFf~S5vX&H=Bx%8f|*q{~yTWQLr6W2VdLb1)l z6Q3B2RA#`keda5=W+V_c?wbughJLA1`;Ft$g+$0exof;6#jwF(W%F^VJAM9=mIOU8 zdkrpmf0Biv<14IZ#d5o1fm+RC`@cLwVk9n<9AbXgzx1rJExK?&qCBByykw9%c}M0c zMgQS4frK^4lb_2v`j{XhE&(!zPrekmF2ZAjAWmA)7KxB{P2`%65>Cmn^6(hlCU?`A z!Mda5<3||-R5^~TlzOc}^j5yTfa7uhu9**WTN@^LB1Ei}=q?QP@z9VS$2xs&5H)+; zgMAlgh;mXd(6z!DfFY zv_ANhk!B|Lq)yYqLvo4^&^H76kK>kscZj50u+p6T|ry)uV`i zJ<(NmL{$&AaKWW`{q80?r#4{~yfy>6g7r**10ya*KY5reb_6J*f21xBPmw&Y20aH0 zJ#G@Em~#i3p4W+pi6_E=<5k0wW0zXCy$0Ht{Xs=w=@5uu`!wC35s>F8!b`}_R`5xn3O81wI!V|~0?|fRtySFhq&nVu1 z>+TOiU9}JY01R)Wka+F?hMM@D&&a2swIf~6)OH6?-E1-iiiqzoG<;{H@Q|3Rp1<>! z<}P(|cEDLCCw``TqW&G3v7RS^ymZV!W$FJv9)0?q`J^rdHu{WfpWsREp)*=WN(?IZ z0Dr9yOFXa)!`>@q{vlBL$u0q8#{F4$5;&tU`IKC$PLP!ZZ9tHf-aZ*@XWtw3q*d)G zHtk)&cCwIWpWU2MJbS8Bd(Eo^QWFVd4KAJyL=`LPJUDV0AJo*soECE_di*-Yb z=YrOIoQ!(7ckBQWWF~@(5sW!$o=rujlGMwlw@1NG?dpDz{|bLFxCU8C`DVKz^4V<< z&^>0v;RKSBT_%)cQh`jD>*KwtgLKzsx2ldcWT#@x0?1oEkbG=M}(d`jL;v#E|uE#deM zg-gVomC!Z)E$jrGG|orKjPAW}a(zqtqBn^p3DG?1)0FmsC5BLNP>r;#c z87mnG-oilsy;|SUxgcsceENBf>sPSm7qg822AS`WxpxhPk#NA7Q2IDjbFaAS)*pd| zHe~T=X3&CZ0ne!TrH(-(o~)?vS3-szlVk;9QZ!wWp;Awzn-You#o`BS3xX<4^&F@k2=2gI+B5MQo+}s5GFtqQi46}wqKeAWO7Gw0rcBu!+{6O z+#BBq=5E0fE)Zan!2Qj^YnbEJ6%GEg>Id8_{s(_vfW55md$65fQVNHS0Vx?h+#R99 z5Je7&@I!U0lQ9#7^V)SlyR_YOE$hovyAvEycQwltSVAoLygI^%W23CTaew()!+-Po z@134B@rF7vY-(~S)~kd$hi<9SIj|D;`L}|Pd>(Ad$15{=ll9*L4T^4aEVkQx$r@Qg z_A$4eRlDB2bznrEW=uK0)$l22N(Dx@+E>)N%*t_r`3IMI}O*2&66VNDEE3N5Qg6 zpiVCp*x}gv7y5g^3v-*_HLN@a%1d1qB>7F-OpBWUgzwN+9*Ug=R~6S^mf&h+EDSSx zK(kK(Fljxv+FUBkqk~{!iTCD$uJm%D!g|KCAou@XG1d7`Nw4TQLcQ7h1 zXxmFL?eEtKUCU|l^|yP|7{BJRf0)63foK1H>j5YdM0zE8#mJ>>7kM?Zy=8g>T0D2+ zs23{H2~U}3?eW{Qzq29uDpq&eqZ;3dl53uT3U2s zTG0N1wCx=RsKsH!CQ9;3%Q(TYM*YAIhiig0AFd{;{t2IuBY={x9;7-C%b`$kaKC*+ zJ6;s1_k6q&bfM{E`oo#z(%6jH?DE!y+ZkRzrG(D>`eCs>Revl<40tX-W|7wB6XO1C z<7u%luEn8=hhWvFGJ9gf&>eW|u1HV$Xdy)NN-K!+v0&jo)mdslY1<^A$D}n2LF}3K ztURU)6#TUoJ3R0P1UQZ+(MX2saL}tRWZDM+H?6p9$=>@fQi&ue1nHo6Ga4ZuRbXT8$Nz#q$F;Ag^J)92Isl3N088qf~@Lu!a0=ha{BU?YccQL@Csh;)lQwsI(-u*aVC&-oIeq!|G zQ5xK`0t)rS+s)1{WLc5RJ%J5~KfZfImT>y#2OLk*T4Yu7a=TFA#=yDX>(7Tuq{h@p z$DRMkAw2-e{L}!Ug_0YcF zX02rcgBil#SGwPw)qmJzB%L_3g716d z+dtZ8!nobVf&!u3xAbjth%t=@Oy`Zyo1ZRrNzo;6IFrny&Is!?98Oc{k7rq;LfoY? z9zz?0vGfZ?dAMN%h2dud`-L2w5Je(%alJ_}>sGv(qQ-4!a)OFs`n7nE>_>FxA~2M;)zR_c%&L@+S#gIdy1V(8O)wM0DFNuCT}Z@g8%xA3JIp1N7o>#VP8d7-51o z67Fi}Y6KFH>Hc_m_R51OhlyD@9izyq8Oe+x=fjE!!bGO?ImVj5E~L74ti zB$lzGx?c0#(ff0gk0CUn3F%Ty>R0K5^@2kdbGI+ywo8zKW?V8Jc=FCQHq$i^@*MgS zv5*LSsy2iST1GE`LWmz(R$&-3m@S>bH|#PUt~Uzx>NEWM2>^-PcCmgm?Gt(@<8bu zqB_p8oXGs$rC{qAv z3jg^)wkXmeYdrU48eY?eUgPyo49C&L^AwK`yN4o0YhjG zaTNpLV)FJ*w7Sm{w1GaAnA_LZ^6{ge|_02%+jxT&q4c$5I0Z^zdUXEZfQnki>5 zAB;&wBZG=!5+k0MY=|MPuJ>E#8fo#Kl}wqRASbZYMnQ9#<8d z>J7lZ4{l_|U%j=6e_ii(N9F<{OA;sYbu=QOr%mv-1(~xkpdsFy6+-tgHiU+cxD zel&4M;`U8p{87WC6qf?C4B+#8cIsGhMqy1T>B11(8e}#51S#A3(+e|5KvvUr=r@I! zIG6wev414 zi1G=O+M%p%Je@mQVPWQ#xNrE-2QMKBA4!}iO^h(0FiKn#<0T|n!9xFJLG-^xjqOJJ zc~tw;gANp%Sg_}|ibh1JP&UX$8MxxAdVh}P8+dZfq^5X6bOWomRT%m?_~7*RYwP7k zAKJskisPFQOOzW?eI?!+X$rW|)^5xv7vIQO7_M<0`T9GppyJ8vnI5gL59uj#E`CAZ zlxmh7WU6N-B4lcvmQQ@3{&ywDUqr*=yXrT3@Ntx~JgVOCaNJg#=Zms38d6W;TPkYOKs54zVk^59^;+kwuJ z##}JtPqsxhCv0X#-*2$X`lsS(RnrDp zlrMF$aF#4gU$h?`33%{46Q8L~qR4PWJhfhKioTdf5nX0Ppb&|r2dry6kI&%T3smR; ztBsm`qMr_6On#R?nd++p2J zc4Sdgm?;5>7D$BuEaZzjSHCy|;xqn=SVadcw&zwI(FX%)$|z+BTMf0+rXFjQUV|I( zDu8@vKt2PO7(22>0f7#_A_a>*nxO4Qbump&f{LB!;Xg*jr~L9~@f)xmobjO4`TLjt zP>J_efeW8p*=TN=riBGc&{M7fM4#N6vP@J_QM5rJ_d@|JkEE*dOjQsk-HhRba>Q_l zG2abQG=DxnSt(0kI0MhiK(EHmk!a;T5Z?w#4`-i<{t^BWK~_(2<(rhUaHw~J&Ct`j zt=#evKeI(VI5(!m0i-NKde}G4+t`QoJU$F@N2%dp@xH#nJ!5d4%sI+`%+56%>|QJy z0WWY`P5o>vH_)~CC9QL~F)37T_Z~hk7?6bBzCue_HO0R}QjBfH_{S`JVI4&~NfP{H zno4t;N@s`Qni3aq70B~M&V1+%#DsCAz}J3|%mWPnyN^$h)&%fa_@)35t9-s3(5=bwQKZ2-bjP$3UYkeD!S%)PjV{ZTIn7xSi~&;(3#yt;VHdTOOjLo?-DX!u2tsHx9fmkCr81Xb zI5vz$05tWYgUVKG26MQuk1(#bNND$6gS)0-DSJ5-NUO6hktIyRU(o+E1A+KLxKU_j z!RVPK)R_au?)xSU!dd!uSG|8y6IR4(+0%tu)tCN zx_+pjY=ps#UqK+gX-@>Tf6{Y~K6$;xp-#S@4Fl8QIK7%|yxa4;aK}S|9*~4_JTfJi zEVtPl4EDX=okUY63t80u+NV6{$40>eEch038lntE&#_%CMUfG{5e_v zQs{Fvgrny~(~+V^!IC|4moZ(4^K|-SXaS8A5EBt_4FA%*>)$4#+w46rQ zD*b@H=Vre3LMM3zcT`<9yO9mZhfNz604KIHWErg$LRH1)E>4VRx+WNR*63sRyU-XM ztJ2J0OadMaj61&YtV25>xX8*oWR5jtTW5NQQHtJ*pE+{_tN7taGHXDEaC}A z1ZsabgGO!cXX_Gn0D&!>n>;A2B(aU#6jU=&a+-5{z@Q75N~95_W-E(|J65yImrZfy z6oYEPOSl0DMY95kZqU+{`jx zJPVk0J2PSxOS}8xQ?UNP10?DMJE_ov`%Jh^lN6U3{OmU{1F5y}pq~!+$Z@}LA)EAd z0h<62ig(#Gt$+PKk4x8y0Icgt*Ae>hv7dM5Xx+ zeZMOsQ9O1dGdN<6@bKG_*K4Zq=>HNa-L!F)NXu_9)gr>TR$%Z_{4PXo|I$IG?#ESQUz2j8ORcoQa;3({l! zN?2!3_uUI=@#{YZTws2{lo(xdW-P3nI_uTslOC+vb&k{Gr_Sz?jV zWOq4wsFwOPS`K0UKsYr4CeeM}TMdqSr0d5H8;N`{d1J*RID6%g1|^1lb!-TJD(X-_ ztg5(bsDAgm*JLxvu{)|gO6?M{Vkc(Ddki#k2!86zFjxd&Hi;XFcv2N)(EAQF*U+lL zXAJ(;D^U(Z$@blDlNtxj8Jp8;I9DW|D8atei;#w@IISxW%n5z|SlbmW`}nBp+T^Z& zTclerA6q_W7e+hI>{2+wB{ecSzll*tOP)TdiL4AVv~dmY>4P2OW^?J`HVVA&;O zQmftf)pM4#g3ixHpTk9aB3ax%%)RA11Y5V+Uc^Iq;{UQ8pg)xBP^9^E%Djxp4=l&T zSubq+IxESd1KmDyZ;||svvzFn+)8a8h41YBCr6=LD8!7zHqASEEmoC-{^|7?@l!f$ zqut1)>!gAyI}d>(LFJWvz4jgs_&Z?Ey=mX-z+YMd_wz8bfJP~txzEIod13T>fzUlV zLy@wX3-ZDRex{oHDwlW~7s!2>7Y0rZLBzrIe9yn&;CdkFP?}S?SMG68Zc>I+rYA}^ zInOncY#jP5)L)eCw`-1G%LZ5a$}IX#UZs`S7JNK%-yT`cD>|pVou&312)6jetAkNG zqoinFHAq)f>N!>Gy!WgG&IM7BJ4T14?WnV6)**KBy|$3xN9Rz26XC&mK$_kfI`6F{ zOr&;|_kvS!=hHhDCJgqXVSDH;lS&Lb|5^xNC>^B4-MOIcXUA2~ z=gD}cBURC-C08zruQ(i@>1O=z-ac!kl8Ob>YP&CI#-MEUrmwaF_6NdtRlky|`@3C& z1WqVa@sq&jrPR;Y6*>*;uMKLu98K+w4cyWCRq2}Yqu)saKh9k{{@4)iN)~#2{NL-@ z3r)>wIZ-9`QR;;}r(>-ePl}g3U;09R)ZSj4sWlyOR(<*a3wbigjhbw_b`vLcMPDft zaW#D7S6~Xowvhdhz~Ylsm#6V>aB_zmRYGLak5oOiv8rjiZ#8tKxtzyq0@lzs>IO+l z8!cY~UgA{my)qa+ZiFd>88bOYU{ZH;^Obh%kJ<)F;PQYmi#dVPUj^YutEoQ!Q!&`Y zm9O9Xd$ZcoBQ6n5x}J4Jm*vAL0%LYTe!f;j$IRz1uw{O+&k4U#;NXg%L7oi9PK|Q- zTHy=O*>BC8*TGm?**j?>Opf|Atk0nGnXV`uycke63~cOK{mOVwI28PNagFbOOG;h) z3|bY{t*nfuce8y9_!{Ztx&rhnloUGApVoY(rXzR3yi@ZM(NPuszIHyfR{SM^ zOa7zsFULSVFMQDu&39Y^^zi-8O+6h^zQH%nXM2^PKpQ4H=F@C)$Nb#Lk9Sm1&&B{QwjgRqhAcvI zAK!wvOmP&&M6*=GB*ShdjY3(u0}NN<^u;olQV!3sV$P{lNLZr74CR@@I@F_ufhT`b zFRNLU2b=K9d4N+c$gyuxina6#2RE^l_AFFK@GBo=hr2aukBa`$X>tV{RAvkZo@wV} zp`58RH3Ws%hDi9lu*#3+-cAm%?W`m8K~$o>eT@}nS~%_shzhcp42Lh&g}=(cq2|6H zj(=C*Lw$%0b|Ua#3IHKy4soR7k6D_C!BaP%PnGcUl5(CPF+9Qm^Xp`GIK3I1w2`B} z{lRP)(w+Y+9kRs>;nvzum?`@PMj>%Co$_eCYnf=&z|rv zo=m&~eyDhi*Eq!AP#ioDVU(-@900fZMH`9fni1!A+?X$xl@7wY-wnpLm>Up|rD$k$ z@~uU)Q4HY>s-`DN`pm}_qR+ZM3zcEhDa=eb1Gvo;(i~$}Ec?i0Z4 zR%?_^gKFhv@WyRv^<;`mY^#@>F(tFFvyj4hrSf26mpSSM2u<+4R$x_geR!DXaxY=c z*j#3JdqOubn4g6ccVsGDb+9jHY;}|f5l~X>CXD<~8RfV=m%x0YzRQzR`j}o#_Wj$F zr_MSUZ%3?DB>+S^6*1e%@Nh-GJc>~-m7C#oGo(ost(~^0op$~UM+|sO0QYUcMW5Pj z3;gzt{a-EZw7)7O$88>jdLyv(pvzuH29`)ZvX1R2u-cMQr$2Dr>tmX2o= zrb~S*Q#LJusd{lR*wONzyt)=@`|>_q$UsT%8(Qgs9txCq`p8TK@{#c3a)V2_Sehrk zW8C`ZmK8QD&fZ7kIxq{W1zjRn-ZfjfhBchq3qHE+%58P=zFx2qW8tG++}+JgQrZ^Yws5NFVZl(IRw zif)nuGDo>Sq55gT$A0T3YJ0TL08P_h6bvpkh3aNaXh14OK@S++@}%KcMonwPYSQ-4 z20qGAMng0F2J}jK70aeC_RwAqei^sV`moD5r7eU>T@rSvlARlM>I)jW@n`KVdIH|^ z0EA`^OpNLhK^YWzKUjS*?ek2lG5md$TX}@zkHMEc*w%N65KTC4c7E|28m=w@rc`sE zbKBEd**hlz3X`;4zM&`2eNbr6~!~13CIN zTW3ni+D4uE4e5gPv3xNWiQp4ITcx$xh668H^?_JobG zvz>pW$pqREz{_%`3cW^!UK0rrul^CY`2OKm|4idMlxcYeR&V=EbOK-sXNlqFwe-4D zzr;5VLa1Ms`ow1Y32PX&TAyfd;@peNE_8sCH>>fhTHOOg5QVu|zjmV*Orf+|#4r=) zK&l%B1YCE(#Z=`!Du+y(7E5L>cAd>~wT$ME@iJMjhC8V4ywQcpA`uCiKvf9p(q^SV z)a;LNJpz)`a&7z2@BypGTyyZ`&unnX8KEFkOEGJI)T{qxzo$_Bz0Aaze+re*6X^4c z!yX|qM<{;H=9^tM;msvYJcg)4h=uB9)t7nfGEq49H`~(urK z&>OTtUH%GK7!c;OJ(v-FvBC@3~ZFn)BEEg62K7EvqGj+F~dYbLO|*O*j=EA zUOMX~N?bbF8tkjx8T<#DlZwxdj`&j_vLgvk2T8MqzAX@chMgAdThQ}WAD$r)_x*Zo zg2B=S8`Zr13YF5?#y3aSN4;ETew&li8&CCp!w;ea8~TMLz^QBe33`PeQ#bd_w>>to zb0>-MJICN<6V>gt-nH)G7&1+E+FZuQk(7mBf^D>P{rfHN94r~W+`*k`!J9l;4f)sgF{F2LWVoV%o&Ni;6|_c zqvM#NR;S=IcdX!`oZOw1I@q!ulG=40IFXj6mX}R)d>uHIL@RQ&wdDiv{h6-s9n2rT zhcnB76bQbNX;ln5*o{v1_`m7ymuG}`iPrmz%n%4_^KH1C_JD)99Z>X0Dsy<#Mk?;% z>nj$?6g>kQHez8YcF?>7T`o26ruZK(fPD)=(vfw(N6002b?{T$GaskkFWy^yN!MU^ zKQ@y4j-qrA=%F65INKG17Ee!m*$B$!1FOv*=`tfiV<7wz>^0LJ zi~u1d#FJ;OTJi$HatI-P=nOmn>GTXw4nR2v>@$sI);onO_dS`aspiISo50}k2@cHf z_3L~zbfE<_GZXcJOZ9D(!`>f)hMoW4>3uab?3St8tV;V{<)K}##8*nn+A31U>P#(I z9_k>MmuHvRCxFCV0nhM=@||%PhqI8rY>dJwAFAee+XZ?Kiy!A~pvFQMwePW2`4}sALJC3`_rzPb3BiR35~CShGV54=)lr~y zaa^hIdk0;xv^1~|>{B8RB}Gr^4e(e0t!uFg0w@&pUOaj)1yZ)W3cs(x)D(V3;v4#9 zf$&zY8{3w6Vk6dVyW)47DUaK!<|S;MH#R>YVHBH8@w4!tB^v|$>k&DUfLPU40cTJU zhkL<}z!1R4J8AD}kfjv#H3$0rB<{x1_o0*t;q*{a*+z{K{5lRpRNAsl(<6%R`ij9# z$%T}648HAtzc<@?Arlq!l_0pjvBe(+d_OCKy<*{cvvl>6Pwhc9{$RTb$JXE{z~|HV zZl)}Ljmf5BzkNa7Er~J|wF3e6mUjf8^eIT$;>XY()h^=EwZhI94TKN@+vM?J{s!fuOI}C_B0isx8wI3)3Cv|wrlcymxzu8(v znZNGXDqL}Jxzw3d{ykgY$#5G-EmW#7!<93$w^9eT(u3n3V`(Xes!5bS z9^-f@H4%ec6qMl*JX|D#VP`J*Ix&J9l@$#Vvb zEL!{IUtQQM*hm>=oAOAhzjHHprgElhqVFQkm8U>2wn%kvDxQX^e1Ea--nq?r4jtQs z0r35DrH)(s6#^Q8^}U_q7hiq(RkzfFp_Ow;OzHo})q96i9smFT2S-*Rg_6}ULS$zi zQYqpX8CgdpBxJ8MjHD7OGwYDDIrerA3fW{F``GJbJH~Ow@ASE@-{<>&fBtt}uGjTC zujlhI?)TdraXuv}7~?R9#qkbK+l^j{0e$oT!$ z@|VZSJb&ya6OeTPR?am5;?Ha8gSj+(wzCC5bTRsWTs)O;yo=5JD!OpUJ@XgTZ`O6# zbiYATE$@MC$6pBB3wBZf%|**zOp;tc?C!$Eld~Z78j=)oAoHPx`;KZsOz7+ZZAx;1 z)*+^3Jaj0sL%%WK z8NsO!V4;qETHqQy?$USr;L5!yO~_ils)O$-{=X-sV{FSR zh@%~JwT%voCTYopnSK_F&Bo!-{?3cFEq`!j6P<%xw-x;Wxv}UH}@J!9^ z+ccFB<#huD=Bejs{i8j^?w!@|MdAC$%4bh3b+UMO#!^jYwwY;b?6q&vgZ#v=*PfvT zl?a%x`gCPl=Y@T~Gje3TeR?w~U#7}=eSt=z_5Z4x1n_3dH-kyhiF>}LNupnlB4`KX zPz}osE#XGsldW=8(_S}%Qi3Cv@K(7!0{R+ojGjEI2jWtSf>Djn*dK!VC0)qc zO_F_{^X-2zJT23_@dz8IE7W|I{VWw9meWCe=!3%Pw&sGrE-;}s))8@fAL*|P1ov^a(do2JZXe#;VQzF0sQ zhIUSd7%h?p|A8o*%^m-5Q!hhH&n3$=AN+wN3sK~$!w4c6NK9KvmpJkm}=7L;NdDZ~!j+1qX==he#b-&-N z4b=W!`1KPYDNg038((;fE%Pzvk1J2X{?2;h!#d!d+xGY~12!K*>%S$n>B6#^X6{l9 z%CsaKrk>QYg)002GTJEUhb|OBOQSZ!{aGlZ1B>=7S+cJ=QhNC2{#r6H$NaZ=QHGWF z7>KP^_!h2tMG;kRC=eXh*d4orVl3?XD-?#=jg_)ftfbwmgQx|-NBj%w%OZ5*PmH&( zBz5QZ(T|KJehYxWsB@(VQhQFESy+np5@gQMefzlA;`L?6;M+9lRbakZ^WJ6aq>DmH z068bCg~c290UWX*&Y(+$Hc<@UeR=4)najNQAN@w%GA|U$eX4m0KZ=4AT1^dAmZJve z^!9_BUH;EeG{+2lNkcbP_7m4}r_H!V!)U!;i2iHjN@_C-BuX_nt{p90DUBNK94mG@ z1lxB0?glNtINaWS{>*66(8npz=~2-uu07dP=N^y?55+00=k8_Lm++S4k1aO_VO<)- z&mh;boX_PxQ1|)0$uk!|_$fTpG1fY?=Gv|vl;J(~>n*w)Su!4V^KXf`uevK>Hg}G? z{FYF;0IM>CEaJ$eC2rjo1u4M6;Ea)`#q7RZO$5UiysB%O#_~Zb{Q#`UTr6xq?-Kb% zkF)Ly@StpdKD^g6I`nWS`{T~`EqW2sVjd9Jt<6bu(nQp-EX_ZddQDqu4pc3_uhqOM zNjq>EG{L`sp?Lz*_}1=-ns3FEt9qO9PFg~|q3{Ou4~2&76zd}ll?*xf2UoaXeuh)- zKi}K;C~=LLiHRhap?|7k*5 z4fwXs(1G5(Q!RY1L~H&Z`mFPtiYPv2%Ke`}X*?5$ApifE*x}c=0NqT78i|Ymr$CzS zIO$Jn(hj6vs5p4dxb_;r?s0j(sRzfiaz5#*hEQmVmth z_-L(!#|4k%WD-9*t1mKCccao(zDJN;+1KUvJFPZp%ex>kG-ZdY$x4!vpb=%Z6(q@K z<=(&1@P;~{WbJWv9QT?w2-d#x^u&|2WC`fK2-a`Ebz$G*SfUT;6AaECPAu+Bw&zz`|a9s0wz8kJZ~ zH~4D-;goq8dU%JKs{T8q2%xcZ*)woWM~JBQZ?}vjex+4neTDz6E}@A&Q%+&HBNz@e zWV56A53kCxE~y5;xPQM-Km+_{Od$3E;@7A6)n|;9ppxfk@fq8ygxINSztx@d1~EL@ zG_pTmV;Z_zvg1NP3_ge)`nq?pi0K*`~;nh0sQ?e6o~P;vCAI;&Q};usRW9IgG-9 zJjyEGWMt6RAPm+o+`?X&k5#(!don##zs1fK?Z!-!YPxy;U9_ABAYJ(;Gn6LT^EnXF zNn#I((4rz#ze&+r@NlImpxm28a4?{MnUALD7*w%I=1G_fO%O}HNXNbGM-q>H?(iz%ki#Z`~El;vq`hH{=F`^`!28RBfi+cMDxFJ2ZwU>$0wLA zKUB!)$7Ik$bqSzzANB7dxODr)Gu!=NuC4hlsk&T$QEy1uYL%BlB3vz&iKWEh?asXLpVJ2tpofp3MpYy4*sPioY)PI{RH_U1X zdX>OMa;^(gx{Am>fw26QcQNy%$8ggVH{$0|a(4p=DleZ-fjOes1^9Y!NKLB~B;hk< z%95G#QTgYR5FYTDVx0-2Tcm2 z#M`L9z+n&b^mb?(>6G*QMou6bmQVB)TJ;6$S(6`Vdm*bEscyokMatS=+J&B%a>Y? z8+r8t^8PHJgf1#1nEZX;pv95}^{3VDV;?{qgHJ2zZ=-;Ouk0W(FBYR4W5#-b$(N)^ z+Mt*Xs^Q}Anp4VzE}?&tcaE1%aOuM45RLiNUWhrNrL^N6X`*!!+XA1k!hgL)S~Btu zcHz&J%#&Vc$~uis1)m&uLziv!vm%m0* zjz+}1NRr%~b(_5ryBS~tzry$R0a5jXH=r2#hZ9u;=TZ$9q zPIImQS-r#osrR)QrN7ejn4ctDnw~O@P~)J|A}#6m;tAY0+Q)9z0oSxut)-LMPK+i* zLd%`(6q7|-zR`RZwrj1gwCy%|76>gJx9si8=`QhVdTT6g@?<679eV7kjuz}r*O$47 z&0+p;N7wj$=7c#JA*!;C|AbR*kp~rS`^|!sXnpKiZ?W`)Sv-3>9Mr@`alc;}EYJ}Cc_lf!&iC=L8TXenzgI5{yn)T13huh@oO39E~abzc?|{J!;Qj)wQD zSdh^lrmD`C#^kEUXmS+AI?(RGr|3n8?Y4ap;UV z9H;q&w`GqSu+4&^l>aV{-5+S}w@5lYB2FTS1xR9+q1j!6#xl>WB6V@&9fwmZq&rmZ z2ziZE)SN)aOugO)vL>}!@8;|6fM^1~2j57w__8_h*F=Or|KP%Kz8PXNW1Q!drb~Tx z{v*TWNJm>rEMJ7m+Q=D4+QXVN@2t{Vmrh1Hpugc8GcA3*2i>Tarac$T1Awm$V6tHxKvG`y=1%G2jUK1n zaCB-|hB2qfA3+%$Kg$LqQnr{kd3Gk`j8<)?X>pn&JHwrueb=%!`mwj@_09`tBfMFR zsN9SI!dA-7KYt4_$I+PM=5kif{}K!wv!1uFraB6pjyFDEp(g3eG$*vcMQ)>(Qc)$x zr$w49n;VYWNHeO0+j$q*GD2(3Q=4+eKkW~{_W}yONfJaQ=Hcx}A&pig%+v~h5#hOX zGinFwmAq>v>$!G%6(7AXu4(PiGhv(BS(H~(^1%>#Ktc3@so=)*BDBcyA9n zD&N;a-OIP6lk5f*(|wOQB=`u>xEZDc9TIbHm_s+AT%XK#`~NJjndxcxgCepJaWIOq z^KVMi_^&&F+f4JUBqnp(-rXByp&V{U)v}DluHlH5_MQAl0K%;elS6VVT@glP%z<8N zs+29@VvMoItN=xK3EqppgKvCNlr2r|!k~;rsgo#)G8oeMFpqg~jZ`$f?EM!eJ~SOx(%fF$4s>F2i6Q-(Vh z9|6OuT=uM-mRodAEG>%p(@605E;#_PxcA6c^vGoJu*C6B3t{p+nx!dc>(qC;Y&isxOYpg7=R;$ilq5-ibww)g12M5h2MNngR|; zDWs4PPG)dJmU7`O1CU!bqitjiccUSmf&Rn9*48bBoUB4EWW2{0>NMi6ny`d|*2 z<1vz@>y0zfQjlc&{p{ZPEZ(G^!ZziQ2^wC!Oq@aMKlGI21I)#2Wc#q&w;FslQiUd~ zgtQ_1lA^Ji!L5+7RPsv@tzUI($7~#oLOlneahv2^W~ypu*8Ojn(UgRz1lrI0!PBo+ zj|S<xNsaP;eiI!79xG!Y>0Pf^fU4&i(&t zA}V$A=j(6THK#z!Vw2EdKv_5m39z0*ye1RnS z0ANn1DYkn5X4s1~Z#5gr>^6Be9ckOXxu*kVWJu04FZUW=?RO&Fa~e9R|`?$ zDB|@sA9#DD)wN?cYtT{r9Ee}l*M%ip0y zX;KNejVw&1H*9>y-3O)d{Aj~?Hkr=T?zRzO(J>{AUHA~K+{fOf!r@0JH1GX<6ntM9vH#O|lVdP? zeY$UjcHsW+0@6O_w zy`yYyfp$-5iC~MgtcdnR3{7_8*G?rNsr&3Jvb}CrnkV}{Fn6>(OI!6f6m+nSS*j|V zQ!AxbQR@QnbPi7bKz$r7uity9NDE{qOC3noB0=|lEWfDv(H5GU&9Rr)fXX3OiBoeQ z{YL7K3n}nsxC&a~et0(=IB~SzO=3snDZQu=E^}nId^cHMx%x}n{#;lM7tN6eE20(! z2lfw^)s)b?$~?n#C#GQ-S$#jXtnk>wSqAO8k`qH689D8Z1oY3()s)WG)?+3=bez0n z)B4m>P-1#k>$(9QJ;CJXHT!nCtmcDWeYHCY^r8I;mm@fS)Y}#ABdI4y(2+LHMhp`? zEQ``Ou%lIS4Bsw}1I3X4OFW|0AzJ&N)M!C$1GWVxfBaJRYe&g=KOVM5=F{|YmSaC} z)L*w)o&M=g`m*lggP-!%wQ>p<=|r@SK9gJ{JT4$^wawuNYT&s;`R#o4B(K9;ohnN zc<9o9Zq@xm;8OJJQ{%IjhW`V+1_9Ei>_}dt5Q;Y>?QsMPyP#z;_&>nO z;@(UErwEVmjU{U>k9{t4qK3B&>H1Riov#PV**Jx@O%o$PU?OHH*S{}g?E2~O+nu;8 zxjiKuSUEyY@v&i!jjHTXfEH$NKMyoSHa_#)JG&#L%fvUKXYEO{{!P7zFh;SyTV&fQ z(wB$S>J1K%kL;cv1KSCPf2aMu1Psky?bP7f#xy%p-S{ zsL6L*puu$JgIeXDb~+(9c|g7wnas~t@!q~MDH&dh-;7irnpfFw+Bc*O36Y1G9$tMd z=K&0+o7HW+mi}YgKMCFQ)c5iK^VS$bft-7a)H?9;WZ7TZLZw$6eQ{D}2O=_} zwZaPf&y3E0?RY6oUo|hMl@90@1j{&do3n}^os{v2hhg00k#_wb@izn;&sM$MM5SQkHTv2s&Pl&SlK+XJ7~XVt{hJdHTw8YvmK$TZeeaQd%HID^-mu4BH)?AJ z;_!+b^*KNijR6slh0uCv?7vA?TKHad{hQUNo6+^tJY2aIlj^m?o=}md5W6v82#>gn zQe3yvHY#|T`S`XgI}oQ}XMID~U|)R2s26v8R~fVqdTMVjw8~5&qGu;LvN1qvyTkmU z)rqr+odT5P1bE42)S{EJ&cUB;y0ICD2Q%)O=@vpE;uKm70qF!;GI0Qv~gd~;-bayKZV4Jcm4Ao zEkiTta4g*`fqdT8d�f*~#xaxoBFMW++ea$z%2VV%X@SRYeZgGZ*PL?^}@7c@#uy zm0NMX@AUk+=axUT#ChAtH%&ZfWOuxaGe;$tJDyp)KcL@F<|JO>P++?HJ*EpF)ArJ0 z!h>lE9Q-GKYd;2e93$qM)`q%ypDrRnkeCxg@I+-=KE+S0}S zy)D^f|5jXfeR3rHSaCb$A}}>)$gZuqXYx^(DAoJ4ST@_@D>s6ToPh$ppycqx&s}e| zb}f>t^0wZbDxxt)%kZ4E6T&vYt3FG(jFCRz2aiiTL36QHS0-$5OJm&Zr ze}Ci9kgi3)K2Y!KTr%gqNxesdL_@#HN1N@QM|5VeQl&@YHlp(wgR{hj6U8$M-Go2# z8N1wZb8ZKBHBM+S|2o^VuR%sxZSl*&uPa^?`4kSsIp*30!qVSxJ*!kmd+#a1d+UGg zrZces$z8t~=IsRi(7fJm_4>&ztxtKq63sj!TgSc5nm$oALyfjcA@@e|-UpN<9^Z;u z3Xs`${t?V{BpvqS0QrWv;I_RLObs!LE1P!9s$QR~X zfi6PH@$v#=@3qL>G#^QvE{v))sA!1trBX}fPR={|v&}`m-kEEiXt<^|xp;D`c3O@w z9Q`6Yxz|QUaJY>1)8I>aX!ECc9HDZdZiSjY%}<(QgcYP1%I;Z8f=R(QhgKTw(iPv< z^8dZaZ~@G6nrMMb3gOqZQd41NP!4eFSo~4LS%R1cm(u&Xv}v~M`3Vs27B@`Ml3co< zM-FzA-+UL9GR2ibGMo=bXzFJvxF_>bBaUp?;q>g~6S|@|=vYY|NM12+<@x-nBHnj{ zXzOBq*+&v>r(JG#sxkC!q)zP3ADWP?1%6j+n;Z2SA%c6ltzh1M>z>*^d@bzWPrMIEA12#R|RfyU4m3XR|%)F4C)moJBH! zA2nWlyj%)VY%Ezz3~=NYsyEmT+ODNZcE%dfvUeTJ!;TOGxKx4OxIJG3+j`(By4jrE zhYFDF<~V*g9jEw$a5*�@L5g!}(Ta!Tmhqa_TRgC+ER;+&;Iqq2YPlb}0#G`UuAw zEpRRp_tJnzPBHPqSx!llL>lLI=cG}^$#y`&VuIhFG5&!b571wk9*eAnom>qXOTg z)Bd9(_h8dA`9Wr~TFnB?l%_j*4QqlrzQs&|U0<%(fkmkcS5KS_OLbtYdEbY{CJ(6VQU%0fd4E-&7yv{UTiM!%+GB<-bh! zRE+u2W=>7`4wkZz)?ob{3;0fh<+|s`=x~1z=bq@!Rex_FlZsjO+Ze0&cXGZDo_BoXr zLPNijT3=+`wf`lcRn#Zn&Q@m6fwEHqvi+hqF91h+!n|xfa#=JvWaLXNc<8UZ6w~hH z$^x!*pbOMpHk+h+tU{AZY#9=gWimQlto#o9{FJi)j3^SpUdbaoUqFmJl&SEN2~PL@P@&1Dxib-vwu6P4P>0LgHJ@vjZu`G5+P2#C=9khj(i zlU|P8^+hZ35VHGcI@VFB&q|ei$$ZO6mmG;2jpdImW-!i;Jdf|5lnz2Y+hkIMUaD{G zD9k?43_gSWQodP#sZrlAc0G9NxU|T|a@5lpyM6U#@m6Z?VeAUp%=xk3N|T}DnZ$*O zSM~VH)$^lRsDfQJIDF6wnR-WLC|_ukf~3@rhV4#yu7^|(VX2FR z)6b_(-Feg}R~#4S`R?Hd{1j#zXvEt7o|LA6Kn|V@^&N+b`S~k}fKG+vvMsO4(>j;x z-^OhrEGMIe2(Hb+jpi9_Ut?Fz$yt|ee+Y&+GERWmJ7sFyDX=Zfq<^2>2$7BQx(({{ zo6duQOL0viYo^9+Rk+Wj^3u@3Z$u6*QbFq5dc;?vvX%R~@*$jZ<;oQ_d*Aw7rM#cL zNR_LOpP^)KgSM;gbN2QR=iQc0cDB*5EGm`_bwjg#kiESO8beP5iRL&-(yD z_GyMPIiq@$>RShU5lWp-S<^s?s9Dv=Dy(#CE`O{;stx>_KiVcaw5Sjybd0RF<%bUb z1k^V#xtX;VQ4}uPw!_aJzYM3F(!+SP(E>-=k6m(RW2_xd?n4}JI+MO7wuP;%t15Ku zJ^!+MEK}8$D3<7Mvi1lHb`CX1c7%Pi{BfYYtud`KvFE2=AW?kgzH@z%kt& z819y=ij8uJGl*emCe{_lt*18Zx>}!a!S-Y0%9jZNjhs9&RI>SLUP)FkVL~S*iH{o~ z2ef~wDtOlb+i{08k?3XXxtc}{kLLRzB#4eiRc0`KLBx$=H#rl>P`En^!5LFf_s89^ zLcDmot7P%zq7G#L1OyX^SDxWG!g%4~7s`qPe!o%N{7x(p-~a2mElM5Rti64R-@a9T zwD@PnHD*BlrMO)nG#>f1n)kQU3yrQuubqdN`qyP|kSenl<#>>(xO%Az2;zYBgu;HnQ=zRX3A4jf%uOj5 ziC{;49^j!UeHyr_IcT$fL%1wFRB%u|CD9!{EXmt<(4nr;q$V$;oXzc_2MCkzr8-nD^ODxEK1=Jc4BMuP8i-H zB6VqFqK|Y34eIa_kFYm>%a{K7ekXtbwt3<+qYR&maJ#-xLoSHHU~ZSpLF%t+AFVyV z4_i3M!Mf_m3XV_oht;j!4dzu3TpwBKseBVcp53y42|9K|H)Kdn^S8Bx zZq{%z{v}zMu$ncAP=>gjvR4^AT3xi-2uYpokUlGF$La@5XkYdDRAhw-3%V5XWL2v8 z@rW*nec8YN`rd+=OlGE#s^gLS;N)?03v&>$&t@p0Ssjs^920yfuOCryQ zM@R*0Tu}NR{!Mlzsle6^WM_M1j_K+4oakT07q;S?%)}s_#nmN{WX#c|=Z_6&L##iV zuYrQtvcN?=Kv$M6oR}9STtiKw1-C)b`)=$tmdIyA~9WV zFnnWuNoP)num$q^?N^TAOU1ijv)#>Q8a9Re7Jq=D*FjsHeu2;O9)81;x6zUDfzh=AVDi7lR)4_{C-JGG41|D-0zt~_2@5`m#DUxWxq`STf@&|G+|Sd&tFBN0uxb#^&SMg*wr%C z>U{%x1MoK5`I$){+n@CRM1~1z-qO#YPBG0MAX1HPR?5GjfK7&`E z3N>~}uE3`=lMfr+iVjOUroxrxpRATpmfCShRCObc=r{DhD$k;M&!DtX^F9invQsd& zp<}pF>dJ^)h{)?sL=8WIoWv2JJ06K+fl_5{orJ+LlNsu;-(A$9qFq42wkgyMq=#&5 zpJDJImxsH-lKo@bW;IT08j}3oC8047YVKN46IIV9PM(;TWtV{R3MDap!KX8}rpo=k z=k7c5n?Sa^C68Zu3wBxi((aayHGJus&Osv8IS0JD-rwwPV2j{Y0S~a1gYvrP%x2P2 z`xeNMxgu(5q#yAj0)h4@=GrI{GWh<@bL`+LcDS_qc0NC4{U}w{mA`v)#)duwlM1G0 zhfu+i#Fuo)Kup{lHIwD!SGvR73`P8bw*fZ!I-lA18obFE$0lkyDKIF%~b z;zYQPq(4(=Bg1=i-5kJ5_muH9>%NJR)y+j|fU(u2A;o^L z%!!3ajDCQ0fIIdz7+2Kky0EO;TGn{Rk<~V8pfjjlXQrSLUdwBH@?<-(VWn@u$~q&b z^YsP;>QA>~p=L(jr7O6D=GgGh1Lgkkx0aVtG1be2k(1aYtY3a}Y5nW8e&f~c0n=sp z^kL&;41@b@Z%Qn#f3%a4)JI)V6D?A zs6p^JFz*YtG2y7FP~--98(Z4kZ>lo$NLL)7)RpF5GJTY-J~~xck9YUOG=SBA0JX~U zjD5J+$cpUrY6mMn!S%$7Nl<(Xq^jGwBE4!33>7Iks9dDi;T-oA4bWfA3ViIy_II_0 zrc>-(RFX%yeCHc>ciO^TBc;`J)pYgH578i6zobn}uPDHx_=+598D;60n2&KV2WTQR z`kxeC3AvEQ;VZZ^lCl3uY+aic-_lR0X!#{HELRiuRnbS57>Et+m&n>e5}*~VE|V{h zmerjuxAYjxs4Ot{zUM7_aTy?4&~a;7XH+t(U%z&v-&kR=wx0DidzX8#>y+wU8N!Bq zweesyW`V7E&`f(!_qR-Z%Y6fL7rf{VJUKu9jt~sir-8VFRaX?0mjX55)%E12a9V>W+>7Y@uz8Ef|33Fk5Zwx{PSfU z@j;K-Ev7sYA_r;+ZAvyB@W!xQ#T4|oKknE$GN;)v4hWf1ty79-{ekEgXj7~wxgk34 z>O-@DQn*Nhk=W(DzJ*-CMBt@lAMhQ;%-MOCPGkeBn z4uhJ~ON+a{r4GhtVs)oFuaq}sJNrNrnLLjQ$dH;}pJ@`^&bI?IV`SoZz5G|SJZJpMNq|2 z;W7sA`!=lW6ELx6#AnwnHf)J^22Zixe;c-JUPXP_{8Jj#6@dF(DNC&{Roks{6a121 z@oI2@1!UOy;)>p~HmG@BT4f)!Z#}SEW9k8O80b9X^%(p_Y`PU!DG$t&fMS4;+DBaKO37kcXHi&_K%Oz<8BAS$@J* zCvCGAM=45ogmwM)>8M%$r8Y4`Xg;mZOyPDzzW%_pJ7ssePaQwSsf6G@OZWbsIQ{MJ zTYKg3)uv8wW8k}Lf!)tttF}d$ZnmH)E--0Ono=PtaB3P$DhHbl)K$2iUKSGDLc8Gn zCU&Fzxz`k(8>>E6*v&$}fT#AXCmJdd<$hU*2uJczz=@LuSl0V4x%)a9Z;0`Q{TV=s zH4`3Dmj=CX8;c1I54EO{+nzJ}Gn*hxAJuySqU?5Yn-(YZv%NfT7O$FdaDC|)0>!`~ z^td9jg+srEY7ZZ$dtra|wQd$=9ZRL)=Lc92%_NcAb?yvsp(G?{!Yi19{gjbKqiA7r z@QqDJ*yFhpwEUb7%zX2QG^^!+E+Yv>x1|d|+%8&Z&>5{5I{N-WD0u0yFY&il;wxgE zb_Pj5HVer$m%|Y3kfrzQ6?$h*lC+U0%`CnJ|B&T0eYLCvwjL!Ta&WDkm+|;gxYNcf z@@}AXbkeMhRc}>^%(XI?Ki}$>Q>XQF?}T`b26raUY$O-@@ic1G{3=Otz7q1hLMH9$ znxA0ueZdYj_QO}o_5BOGhGKbyPA_vQhs>#Ki;;I`j^qvhT5r0k!LRGaVqyG?xsG++w~!=$Y*6v>_?=m}&?m{Mzaa1L1|JKr zW5(@!SEgT5hQV`Y>y29#+d)H=4-k(Jwm&c$IQP5#{>RrkAwC`@uKaGeu2mqUysi<) zd)isba4LT~-dtgqA2WbgW6D@_?CH`(&Tk`^b-r6xOMe~M#hyF6wYUEe6ma6csA;Qb z=XMqT@+2nh#;esCik;4GJw+LwTd(Y}6Ay=8+$+({T~GOv9NRQeL$dXzV*QUMAL`68 z-I!DE;F z>5mL0@=xh&{1JtaPQ@5qE9X&{)VVB#xQ&`cP01CZQnS>*aqNHdfP)J;(8edd@W)`k zkAV(ZN@RMvcuK=a)@D5(JI^j7n zR@J}m^Se(A_+6zCn>|TEbPtAk#a9*>+9p@R8QIi%Ol>}mvuVhXnp#2vLZ~!J@hz!Q zJMYys#-*PQ6T8dDPD1@{#~)|>8_P=ew$$6RH&(Q}R?3@e(Im6X@c;zxSVj&BALj_$ zrI=LWK2AwEl$GqR-N>DEsPxT4Id)UKki(rXzM#CGZh1Q-$Gqxd64@+`_8hhSmKi*C z^#XpY$MJf9kQ_d}_bwcm?;d-BPm(EhQtt&wNdE(N}MTx0QDgbW};JcIG?b881ngmPt`Z)AGoqQEx)fnVF#`8^jkc6cic3hOi&CUI)^9f ztdB$G5Mw{?;bbQHuIy_l({YY;JikUTe*N;-fdnUn^i&wN~mzq9wC2HJ;b8abqplz4&4xv0e4k~NtDMWN=sj@9Fp(sAu|4bMC`B7}B?!oaF?G45C z{reG5biuG&X9ry+zb^3evJ^W$)1Cn{KI}(Y{aPysE8K94Pu0CrQ zPd+MfIz+Z75fY@Dn#!~OMviA5k6LuWhFaYrw~a`Lrul^-Uc@S};Ll=%@@cB{`_&TO z1~lGrH&(;TT+mLz!LzyNeON5?W^;;d#bw7%Zr&rWBw%%~>?P-}5zn~GmC?3}&7M(e znrg`57la(kAIY#D=kyun#S~5cko9-jd3uEhDUwTmZXwI#i(gv%>P9e*^-T}b*o@_0 z;A>%6XZ4;lG-88+`^qxf^*Z8R-0LIl5Krq`eBL>lxY=86Z+xW@v~1hm<#segU`i7x zKCSYb=y%x^`ons<_j->z^(5eN09^Dbnyt z`YW_a-k#5NoZ4&j`rvhW^N4z!vN)U9_YivfFS(RD@ne`8#!@B`YxeB~5*FNk$Wj~o zJ{946b(&ma^rU<_Byc4~;xZhik6zV5y2QyO?yY(>X)aj!tsh4euTE_`HzW6QJOwJn zUz$q8E@*9LQUhWOeZIuOP*-m(I=+7eg$rfy*^b4qqKEVEOFX~@9G^!My3j}a<5Hc< z9;qbK{s4MPCaqzZ`Ukl!gtS9UjDlUPP?WWJzbDAQZZTND(;sKUK)1q>)T-+PEjn|0 zp-Wt)HfohgMCwd@izezr$f~*v-W|%fTE4Ts#991mnCeN!hcysYj!cm%&KB< zbutTF2};PEt_Bo0T#~xH+pLwq(Qt^Z+r8QT5i?m~UC|SHQ_@z|u2WmRJl}%4^gG4( zRq1ZO7utKolDRE#Vy6Tu;)&}Cl=^v}eOt4_IbERB%XZRt@8?*(AJWm(ecwz|yc=$q zu+Bi8tfK#JQ{DtVywfk6Z-9A~pe_7eA_bkdgp2P=C#DGtV5FN9s`}d^T4~$hw z)t;9m;RnWkF>YPHXYbfes0f-Zhn6a>3fnQitnA&+_UV=TCgWZ5C;0ScCm+(GW=7MF za(q6yW^8h_<4o0F=Y1MESL0wM{2=s=5<%Z zm}2voeV>K0TudXJU^vM4!W=jUxRcQ|Dh4lS-RqWxw}I$)bM1y-4L&Bh(xZsK>o3h8 zCyWPKM+?2*(Rq?eGT%;x=m#~}h;csj0CeM%ceg4|b^fJ~j6yRP#a;~6quO1hO_nrOSzJl?Vt zH|z3SsTKR*nin_Yf9aE7@P8O3+j*}WDo_d=@2UG8;T#i6pY!vsuwFs_$_90c#exqb zFGGm?UL#)B+t#_1Td22RAI`cvxLOBQKyE<1ZaDID$NhipefvMt-ye9os+1(D+$tgE z67_b?RwLW zU-13ya~|iM=Q*!)Ugz<8Js;;hFX#1qoo5y*xuewXX+0?@W<>S0p^@LIW(5%V&)|#p z1FkfNHP9fd$4@gGmKH{>oHb$^Uc)D6*Ug=b*%8`95;)VJOezoi%(l%O3^h15oyIr? z^|_TBUV05MaZU_9=`Ie-GWC79%WPq3rRDjH(fvSva32S>%%PIMwq++WqLEZ0JHxTH zZ(9^R@R_SObo`7H)6f(jE>olS*?d&Fyv2MM;p|-=Icff9^bR_+ zJ(cBZs>N^Tqn_!9Ps z8U6h;@yLKZF3@X2ZB=pGlKewyp8O{GwGDEwR~g?ocZaCG{o>Tw3 z42>hegR=Ga9u8bgGQd=d_C1JLn}1sj4J@r%MW~&yElyx`n{OQ(gp_PWRM^ugsR`3w zv(uM83mcea=PK~FGJ}X(Mu&G%9&9A3I)WSjnZ%3q)IdOjr3w+E>g4i-K%lIVvB+@i z!qJC(9RFSOKxy`mK@TEDfnMDXfY#bNfDYmpUolG8*ydU)lU(^Un+NmGn}9g;ZT^rz zuhuMao2|iP_hdZ)?%)`GlYD|u?&>+KEEZ2qvB&*v=uP4ciQ1oSC&(H)x7E+6XnnLpYaInk_+T9CzBu^iw^@Tn!H`jaWVY>+5?fYZyR>iP zk-3KrUYmbofvNcAMh0I#{TWM7;WM!E)=LU4#h-ZK%lN&$6|$3gcm`$*Xyx_=@lviP z6rJ-$GeT&B)stCLN2;?P_D(r$P(1&~Zv%;DYbq%FcrG!QtMjo?(~zHMzB^AmZ7!!b zZ%(k?otPb=!6;8stbOwB(pHe&3$1-_cBO)(1dpd-@$q$Q-qOy2SD?1Und2o=gyV4?p6yp|G-4_zbFO;io->jJz?-O&UdwGz%YbA9NA& zI|)%HiO|3yy-Kdcr#BBorHe*;tsfI_RSNUaJigtHa6ic;Vnm>8QLb8gui3)y@9AQ0 z8<_;6f%2o8a=<&Yh2elGF-iUb=H&}{w$pluC`)}63ybRFmEMlz5Mv8PMHpp~SW);= ztu3eeT-n}}Hz-Ta%4U`3AEC8^yycd)|Mvpj#@&%q z1xv+0s)4_%yA6wvQ-tU2_=wpM>NWGB9;C4tNPkfWdU?hcs1H!8q}mZE;tI6O?+Sk} z6q#9s?s6yo6GZA)k1l~P=tq%%n{V-9-B}OT-2s4AkR(<-bw6FSl~jcV2?_o#SNaWn z+>Z~uolsEn?=33WvRzR|$92stj4VDKpnIE8G@dEaT5~^MK^x3SHY1*(H4}aCcaD5G z;Ij9}a+j_vsp9aOGrD{Et>XeVUKiY5!1lMLm3YkBi+j^ty~t@O@()fQZ;1wPE$Had z(cUlUj;zc-hA7n_BEK*$VH;0W3va1i#>$FROS+(3qzhpeTE|ae)6h%ik=jObCh|nA zLqmpn6#L#uoF|BREw4G6$91zHs95qktc5M6Pvv~v;BzKPJ4qG2**}1mS`dI zf?6h&sOfvij2{I5x_uNgti=S>n1R45Q&$G@-DYcNZ{YHJgyP4MX{OB1NhdNwt%r_1 zPeV`jtPh?Pt73RCR>ny*`bbF)bEgPihPEBQs&V5i`^mtJ|RG?HzE#62*nKYvEH8D!qKd zlzU{^+Fgr}XN8CZ0p)bIYyZw(zS&#uTyV;-^|BJc=pS>8PgJ2=l=tQaoLTA;>r%ZV zkN&6i@=QU;q04~jVAR94yaAgU79F~y>16hP_ol5cL(g6wFnY#xluTB>T+5a?E@NN8 zo~k_`Z7$0@;%ZKKZyk|(t`gvQYp-**k(u7cxxp+gJ^ROA`+om2*0h4uOte+Aoq3m} znm)DiU>4eQs}i~IvbDP*+A8VAtE<}8r>>@(;+xX5y5V{BM}xu_H-2V#gs7gVj%&DI$fFUZk9h76Y+R;<-3Ej7_1C}jyiMB+ zZ0^-4eOy%5d`9%8pGklXl!LQ2f z=3mh>bH2%qcVe4Zt5|bW6XR7jvFW3GP^`J0h~ow=0URI+k7=!?`7*NR_!x9rByju@ zJxvzeyTx$r#Jbkf?9O4A1^?t!N0ow>v^TKA6WN%EuNJ%8I=`8+HaZKtQ|Uk2wh*T0 zW~w@`K?=zwi~Anjam?wJSo!h>&lGpVeqojW;dM3%+l`*oF7%=gBkCWWhBsd>K55Ki zqT+Xz@D$W$Md8ZSY7q0$=rYGzV5(`xqTDcRv(zg-<-1k{%ZdWl=<}rJW5lMBSA-uO zmm15xn-ZFU<3jq#8LO3*m3W)d6=!g-_{ipE1(#LP-&sg9orKf{3W^`k=L#UCu5kjsf(mzYcv;bSf*UNYDA2@k@9JQ@z2P zutz$cl-__wPH|=ADkT-o24Rv-(5S1I^v9$f64Rd;VAM#f=ZJpMG$Bt>*l9BM46fqVfM?36+dc|ldCH(oNTi&|QR>CbO z+tgEB$P*B1N~+P|qfq^=r-3d@ZzfLIHtTEt)~{C)Rk!rNOW#o)K*%e+ga@dWM*OIX z5SF&Hr>xHeP!WePD1;5Ck3?)NWpQvX7T#SqP4?D3D(7wF2bjl~(o(=% z!i62UkjxEg(7DfUt0pP@O9c?%d^QONm+bLF8b3k-uX>C|@x#_HT31$j!ql4C2fEg< zr(}_L#EWhfvGQxZskP(^+YHR|%J5dv=ac-7Ef!SOO>qCZL8BZrOcD)3K$!k>D$XQE!Nmf9j(7GkcVFMUIY;!HqN^kA*K z`{C5?_kh>T;=Rdr{)>ymEU$r9zH*F(Besa?g3CH1p?l4)@MTLGz^H3@1#4ox$YESm zB)l~i9Pb2~(Y44oYeuC4jW6{V zbP1M$9fZY}*pj^FNSW)~6N$BklCey6`(QPD|?w=~VB=dQG!>`s#^F3DLxC zJlV}!MR+!it8ZFaBs*?jxnh>u6PA!oW>pQ3I&QnWps$8rtUBR^3WNbl&i->1TL0%5 z$dwtqz+`UIV0@14gO=28(0FYwhmLMA_`Ei&wcVqcEDIRePU6JnGW9lB59hPaqNmAw zT*3!79z=}%%6)HN?=Y%R@~7s(b<9yzL_A_flOUX~)$vOH*|Qb8__A!jFLCDsx)Pz{ zOD|>pYw5d-T?w21^gF#RNhlbsB0cMJlFj=u8X5j29qTrTBl$z~2aEagd)u-TbO}q7 zbzcfh+9+Y!YKZB%H#+qT4f&9-p`RE7X3d(TdThE80amDe(3)OUW*13nk)o@nQLYARLl48&>6Z((T$Fd1(O%6TgHFUKafpoih*IPVy#vP@vhF{6!~+$#X_jL`Tfrooy($KBtFrLB3y`IP$z;q1i##tt|WEFyDIF+J%`K0C+8h6T& zyqi2Zo-67VQVB4bF^sOpNWEh;-a*Nfyg@&rh^+WJQ9RJ%Q7H~&^Ap!eh*+4;J@kxe zAW+VD(OGa4SlX5e$O!I>dgV|P9okYnb#WM?nmW~bM;!<4DEJIp3m+hI2ZJFaMNBYy zq%@xsRn7ekLux+)o9e+(eG2c?hL}o%YK(piXL@nxC7x&Ga$X66;gE%XPY3+kV%)``hQwrk8sHc3IN;up65Ll+KjURRQy*w_%esqvw7eBkEj_!66r zbg$M^1GCLd8wht!zl`>aFiqD?*N)_szUyp?`z$mtYZZbwMNeRDUST#4{_fGQ2o4{Z zAVqiyaM)ISs$6bC!hNIwi3c(gk>1KbBX=KWyp`H1du4ciJ>DndI95@6gkxe;pO;vJjDt~oWIw?ma|T<-6JmltTw^pmlC)gub3hyksnT!T)1js>?Od7Js%K z052W&U=)oNwS&x?B(yB;#!i z4jUHTv*S=SL{T~f?i#%C6sOZ(7zh501jeZ4M$#K+*Cu{)&3buNWOdDXZD?DGh8rDRw}J z7XwkVCXeVie2u;uW0;wp3TeeCKaPj0#Y}%CwL-&35|F$7&Sg3pz1`KP`Vc8$kD-&+;nZ-eO#hbORS5vemt?^6ie#9nVK~@D}|NkGVPc zqC#ZPNR@@+u9u7G04*uh+o!E?rf60Plr;do5lXGUa8 z)_@+gV2y+1ER?F$sHTg&I{|LhC)9?8m#|$6XHn4FHjDjDz=$U_Lzb58gmJsV;(>wW zeB^tQcAqN~sb~rLDIe2>t7BL+-mN1g%t`U4PWHDz zX8BrT2M1FndZwzfUPs^-rz-+Htxy$tp6oa4*wQDF&k z3RMoyI-3^byO`pr^owFvAznMvL@NZ>+gt; zUycU_a4Q;pg1!3HW3sRFka|HSLC)4wu0#Gi<0W#~-*|kZnE)g|5wOuhvp1DS^pg2_ zpk~i+%!UjvliSsjP530ByvVV*e8XJ9gopA^&dyCf%3f`?n5~n-F5=y*%OsuGiyJp$ z_W0|Bub1iVxZICX^*;W4bF6Oo*W-79x>-N`BiA67f_gq11C%w%5wC-elwVv^&;06 z#WV3B2qUv*U;?fi?_jM$aC5{G5MTkAbVZ-OMM>&|^G%7hQv;bnDy71_EQoC~ z+J-a%PHi_e8Rh&4!`Y#}rXH+PtAN(}*`}t#8{snkXm=ttMkc#U!-3Vu=e%QdxmD7N z@u*)`p#nMb{BeC@3;P80v}uK1SW)B}$8rAg7)}TWWKz4>CusD%uXu`*aE4MtaLMA( zjq?9K|GEzIxjJIeCzrUYOgjPtI=u~5QXv(a=TCCaN=|a{#)b&Y)g~{XMd8%ENgSV9 z#-B%NkAbZQqeI*bJ5EkNeM1LOLb}Xje7cc0))n0=bV=VdiQnNCeKMkYu@W*K zH4-U+<9RRVi;?ePqYB_uDmudn*!<=N1w;r=W>i8(65&07H7hO>henzO4x@)c+xqwb zqID=JwTSBJh!S?9K?~VE1X@@YV-SIV!gZUV1kXT7wk#C#a^-<)5Q~;WoG$TMh-to8 z`lGWXNy13M$7Cf3VPM_fY)qm?2Ljq*KjDa$&QlajL@8K3x+v)AkO_ucAIPtJ8|291Vx-URcNI1r$f_LcpResf&e&fQgB$4U?-;R6!i)Q~N+p#Henq#}eBCnk*V_f)d zH#^B(l~~vdCX?cyMWxMs^^YHO9qLNB|5?a+u;epQbx~Z1<=pe$e=*o#GJoGsU|n5H zcv1?=dsL7%Ft7ybp*8k=4{0SGqMCLmf-;X>5d-qsGxSyWyHsxR2%(6?=Gv(Fh5tbSyCP`ZQ~$_PJ;l3tD_kT> z3d$`n!mlH+y)?RZY(HSp3z5FbNEJsZFQNBv3AE+D%4TcOv}hQG?$GCo$>O{(!e#># zGHxg*kDogEwTt1)g3u=$E7!i})dzUv=$X`59K9QiNdfVozz)~BAS>pYh9H}h0gst- z#y9Y3_qs}QQsEas)jvn!^m-r@)+NeVnI-%Qrp-k_uc7(>MSOAuGorQ2=9 z21oGei-RuLg(pZ_5&F`%3piTR{fxNivp*Ng7X2;;P%7r!6t^~iP&@;SJUbC{jj^f| zmpO_#330ob!uGgmV^u3GrRlWnt_CNgn}!Xn=%|8}BE>i!Y)D|k1^m*j2S=X`!B0*+ zE)l|zZR*A2Y_yk_EOR_OHE@7kz6$fftwRDqm7!}{!sG#ho_X^mHj{B(uQsW4iDwSS z@eYD30%L#NqJ%bIXty1Co@i=c%`olH%qA|?vx)EYC-37y*y?5jfydN>=DI6%J_fPo z#+feyH2#3%Iu~_*>AyZmFSFFFc6X0l=|rC+`FQ}q7R#y_Mvg}5NF}32huYc^_ET2` z6$h%RSeMShW3i4=jVhkxaQwuWm)G!=j^rs{BO_x84C5%G`hA;VnZ};!$L%@P3?agm-B9z9V}!{yU0Yw|i+uNj__)ujZ`fV{@7w zQVuC&b}jitv=9^xGc8UAhA}Xk708%F$Xn+lbdn*bS9##Hf668q30aE1i{9G;LWlH{ zN)Y<1A5xUv$)f-#`p%}ZfuuCWC@jmQR-^)N3a2-|*XJ{9s2~=YnnBaKnpWavjh?y{ zi|g+J1oX4Jjr4x8R|($Bt$|cd4dd`)u)y{fI+HFi@61kNmMx4&i^}L}ltzn*A4-BY_ym^Oy{=cemf>D$ zORc(C$)Y0qwD8bc7WP4V$un;rvzohG{8Gt7j}EoWK46>LG1-SYo8C${(mVM`?|oz; zC2K}<$R9xsk%MQyLv&5P%V!TP9Hd&hYRcnQN9S7i{|EC&<{s>syKsN(-ZPTU9uI)w zaQ)A#Lpw9lqQ2cvfvZ^VOy@0UC%QN2c+O;sgHGZr4!mX89y@_^P~2u_gej*eD!CIW z6(;HRs4u1wKC_=eM3$N|)L`F$;-3)VD&a}3{sSJdnryzcp?b#VDwyA}96mIN+TX0yV>IaSZhLzpD!tr5bT z+118l{XCi|lzQ5l42cb z6v%l~gEM3r-Q6s?v@=!9v`cg z{F--WJS#t5QxPQ4d6iS)ezx?Kxu02a?D_Lih}d_Y>>0A@+eN?KFBOA4``0J*#Zd6U zN&67odX1yLvi`i;)S!Hqp)lK!)uoIOe&87Rte&Xt2njbAS@4{&Kr?2vfhVOas5CLc-VVj9;SIGkRxc!31b6S!3_7XX9-_6-rDqwqBI1gZCXk;>2!qu$@YDK$ zNR2X$l0Q8w(`ElrWB#&4@eZl|I-|GZo$kYqJm{FNKO7$QE@q}F8#NI-=-94HUsiAa z;Rju2x#{(BXGpWzxHcM-P&$$a52^jScDx{JY^AVdTP@Zcb9KCs_$9D5`3-e_gvp^8 z3L>%s*H?zn(^YBn<8~^n`fY_ z1-wRggu3}MhtY{p!xiyOxZ~c~2jyzRoF9`|(lQT@4{>cp@I+^{_>6F&887X@xEimA znaN$112cK?9sf`g+%mReUj*DE!2wxs4ch6vIL3N? z0`h;4LV|)FU_)Cj15bz{bT>$X%_WD6#TRbg4+0w)Y}l|hJ?W~0^{yR=mPP10K>IV?JQNdlx`*R3yXDDG6AkyI`QxY^vYx8HC=QkLEzl^C>P^WQF#bV!mm zY}k}5wPBM4O8vc-yYauRhjTamzw+OXg^&CeH*DCl{P!0Px9x1#V2Jajed`=RO$p$5 zQC}IGP;vc=@r{dT&c)w}yY7*ZxUfm)y}{X6ui`E~$vAU9@ z%9Tt-1qI#9Ha0fK2V{OdeEh_OvHg^c`iA(nua~z!1z-b);;3wdB#fFxFHNWR_4Nt8 z^#(Ta!XdXoR#sLQEG>U@P1sshT*deD?^YpW?d+1j`;}%XyZ9%azA%2Q=|JYiprDy6 zNg~qG%;(RGGWJUQI=Q)3UH+VbGhI2W_cnTE{F&O$ef#!3y!mmnWrat_ffTFspSw$H zxwLP%7~VK!(Ozc7Y?d5&cn5nhVN7qu$h}uH#p=hs zdLQ)pCvu0g@6`K*K2?HuhHr)8aK2qGxtFpNcIU|zz0z@}|9pG1$t=qhzE%3nTkfBY z_t?0*q=1827UT)9c)zF6qWu|1rOHxT9MoR}3fH2_cNLrfJ`8U&^#5aVPkT(ysMD^& z>xb?|xL4fKNQ3?mp)^UgGjZ?kkMOX^QES0x{&9Xwjy~J2MDl*V&-UtLr&C|?>I>gH zY4{&_!N#|*h-4wR(7ONP>HEi|OlNnu2brW4xonG@O<0+2Fqn%Q_pg$+GZBU zUeipr&)J@LMgR9Nv(1*t8#>(lhirF^g_+$Y7Aa*7B;=ijoyv(b-hkOO3ft5=Q>CYi?RUP}U$!@RuXb{;^tSwW zUf(SmdWLB2$oa9zB4(>JnQ##&JX;2L@ z{;ZoQH&P{Mj+i}=CjHMI^~1PrRlg78Z@A-Ce1NA;-9C5W`VLLULz}!uOxn?5@_T!H zE}_?D&f;G0O8tS&`o0%Q?M+-*2zTEY@j0(YcW^ARR6nK6L4RR=W+xGJs(MRd4X{qdrhhT`0?Z8!{-fd%k4WV6`ru; zS)#(e3o7X~3V$ZpRXy(#6P0g%%{fxu_ZG~U|2B2~*yveo%z*fuU&NW+s)gTB&$Qkr zTzsW*>}Xeb(T#$td-LO=XDwd3diFRJhv3tKL)I=>33Cf7YcUkOQ%f34(e+xXAl~ot z+XMS-uUyHHRWXY==J)XZ560Ik9zQS-RE-CalRKDvp?dQ1N79!c?$Mm!t)@F4)C=CF zJ?32oO}UY%T>i4_#n{%0ii#iL#^&Zj4p}B)diQz9;aBMs*H6UEj3ssZXJlq(y1TkY zA~H^0GVaZ9^>52iy|~Z$EH2^duLqC3UN`Hwm%V>qRdvtj&Ye3u1O~s-(^E(Nj?N~8 z`Tip^@NG?fOubWqc>2l0$H}Q2xAt+V2dS=Gwp*KW#BxjZ$wShgj(3wm?^?9x$=XFh za(7-?Kji(qXS7FprDd|`66C(K{@}tRG3n9KIYsoxkLl?)qSt>J!GBp&$gNNb-vIdC zg#^JOPMzwN+PG=+maW@%xE(_Tgu{YDL)?$~hJ$YhNovl=B0}%F9Sill69A5Y?cE^t zC>OLx*1^d(AS%HB{C_(AlHTqd9vT`ECzZcbM)APGL#i&vLf{Zc&#v9Fd*t`KIymVC z2SmX4`E0`=7FR#RZ?@^_eT;)<=#}?N>wElbg#u)taFFTz593fIeVXd z_7Mm#=?jboMgskSAwVpU(DE+|5C98M15^R^Kt50ioB&R>{BzSoq+~bqf%||dKyTnY z@D1>Xv>D`t^0$Rd_b_bvYqSLKHUf=~c33V0ou=Ica5>QMSkUPNr)p+qF6qR~eL z-=z1i=De5U>Fl*U<^O#0&<_ zzk`IqW6>I;yJhs}b~>mn%AsKQht!<>#@ngYz}+n{gro9<20<_YSkmHNMadmhM<+4# z`iDpwHVL)P5ElNo=yp?Ec$(a={z?7WZ@rzm2Ke8AD-4w%6bOU>;aLql*P+9|@P7JE zT!1zrhHw~mMDd%YpSr>(&@&Twb$2^t2p#FEE1V96P0NfyV zaKs(IBROj_2%R-7BDQ)HP1R*IR+Z3HT|)KQ@3EAgktZ=Wg@o*BL?)&YnbePngj9@i z$pL|3t}NvE2QOnOJ|%ZJ510iMhoACeDXoe@5X7hF-d_A%C;$+E_gnfyPbzw)GUkq_ ziRp~V7eyMYN~kS3Md{(~G~|9C(2LN-_NL$TpAkP`6w$piQE9Y(-@|UM<@6`7Q+;f^ z+~G68Rlvn?Q~o7I`2m4H0K5o1DGlZfW6bTVh)C$;*B|Y2*r>@rLDBxte7R(u7JYIi znX_*tap(kek+FVV>$Ej-X7gXE`1WJD!{4=70&5p4zY6%8=4tS8tuA+a<@*bPQULC3 z8T5H7KP`)Kzjz8muVg<)-gc_a9pe1f^-6*=!4W}V&`*CwpV71Y@G)Qez^l*z2A47+bw*Hx5%px2z&t$ z2^wwWB+`Kx^_XM%rx8^Uqh9g z5W1KZkeW85WA}6Wd;Q)OMQ-^ zQ@Q)@yO}Uy0=;`HwLAY}(XuBv+-4VB{UoD1HuW?M1$O zV)guV3fBLw!hc+K~WT5_uUK1L*VVtz8d&T`^JIS|B^mq zuJ-#$1|>w1p|2+==W>eM{Q2`)vt|t|R;(Z^D~qV8C_lS)0hLOH)p~jASEtjFnwrY2 zS+kfoZytKRo@2+3$@u*aDh_W$6O}+r>OcfR<-IF1L=xL?C}jsXd$b=u4daGGX1|aC zQ1Qy!yy5MHyKambCn8+0;B8%f=Z!Jq`i=EpE3p7t;5aa}ZDah1*^Ij7aa3BJ&!1~3 z&&OO@h%q*q8)l5>_UZj-Y^Y`9#*Gvg7c*0_L7s6!@70r z_~sjVZzFx)-DJ+bMbWsRVDBg7e)8w`T>+o0h4@}U2fzjNNt@y6a<=ON-VsIaQvT6+ zT7r%&z)IjYiRr)dIdoCJpR)4QK8~z?gsS7;PPP1t!HtTzjNu3>@0K9CcLuek`Piy2$AW4b zAfXpb92s-~RDk}KxA{VT5SW%Fio$=l1n86^;9&{mEI>j_*waJPLvMb9wDI$N-rkgV zlq2g_dfqT0fn qb(%K&z;zz~%BiX?Nnp30ALOO>wa_n3uWm0WxOZ=(9U$D9hu( zpQHox-T#8jzQGUjlvPJRuhTl7y=rNNqmA+>x!tM{fb`CJ#^P`1-d_Bopd{cEnK7CP z%b)i-oolWr;J_d6ljQ2no;{oQ-+w=(uD;o9roLX;gk4!#8Bag`G=~lyk{rvrbv1p) z%=USY+^_yg!PdWew5|9#Jo#YAB79|nAZ~351dSI(;i|yHBjVilHn>+yfJ5K5arn)T z6Pe^4ZAViBN8W!PN1Zgka_!o+q@<*T6abAzgV}6WbZ&HXG}ER{ zy|S+&bJk5>&7vr}IsfImvblF3e)u8d#*HJ?A_xLbr_<|Tu&qQyL@;U6B#s_EN@b-d zw5H(;Gf^5n^Ml^BiwO+hCmCGpHN&qxNN*3vT+?D^Q|^(n)rOJ+Wwe;rJg`*dpA(XX*z%=c)UFku4s-+zCH zA>2@Q0|tZtd52S{PUW6^?vWkniEi(nMe;DIh5O)haEsxue8ASKAp@|u{n7YL?~bkA zT+8{7r0W(}uU<_|O!wpg>h=0gfpg0(w~&~a=+Rzt@*8RkPI(_oB&LxtYK}+S);&;E z8urQufsL&ITmyKl%IGt7iO--<<>~zrmv8y<geFUHl%H2RkdJpw zq|p)+H08Gf;F0yCiAwNZs6iB|IQWI+i)kN3>B#^9j2}N>Cj^azLyo#fpNSsHNLJ->wOuDh;VeSg^p3os1bzkh#8 zo2|j*eHgqs8kKy-Ap zqG$K8Ix^G8jZLnApCvY`ibYdSD}_L@@?`<=wU*B9v`gATo$S#a0K~?|%DTT^e^Vw| z)?y1z!BT|~_@#V#0DR2;xg1geA|oTi4uC+rB&}BZ9$a1rfuPn%0dNPgV66`b{8qj! z0KT$f<({akr+vE%AkkOSsSx`2AP2#g1H&B-mv)K2%9jPe*Zj92GrCrqhSilKiek{O z7kqS&qUe$VDYOu%RH8$pb}n6bXWr&cb(PXS-r=L4lMZy0X5;oG0OZygXbj%FI=4*s zs1$&_(t+d@4E7fSYkah2>7QTU_)%w{QzPx;ZQcQp`3l-6RfdBoStH<0>gwvGFUvy@ii(P^I13;L zfY#{U0=Q({#K;KWtz~t;>WT)3Eg&=6kZw0`^-iS^c4oidA zi&93<_Ou#}jg*&{hZO*U3`|8)WarMEQe{Sa2cXF$eFw48zPkWH5S2m@ROPngMRLWU^78V+%KQgn0jjF1IC0{HM_clQMW{47FTd%g^3XPqw&8Yg-^IV!XVU&Lfs$L+l zheG+S07&Yx)t7nynj;cZQ5ihr(0}^VpTfo+3>1JJJETk8V)_j9+x%zt>r9HeCj=^$ z=r~*4>y}U`zZC#UwdAtHUwTc2R%vvkUo9yY$oJoW9~J;O9F9(3TV7ty#*G_22Y*Q! zJ{QL}$b2-ZDVMv9qKb5^_6WZq7@1k)2-MG40zd=Jg`h5pts)O=jd$NZVUTpe=lb>Q z!y+nZx7#~?tz1`@an(%--l~U)B4tOUR-<>a_L85!?fVS29T?>g1lGyJk6sr_<+qIk zNX$!p$$76AM)%GjGINYa+mkuve ziH-<^3adSWy(dxuxLBuG3V}6LeSSv(NQ&T<9sAllp=u48SKTOSfA!T@vDs`r^6THS zWsBtcKGSaWSqrhQP`bC{#L>+`BZIDqg_F;q)3}vF&}GVR3&0-Q?VM#gzJsRfG9TT* zSaeCA3rMzZ-OBdu+q(^b&cat%Sjd_+Yb5P`CoS-9aojG7_J1yEADnSHLpmY0QYi#o zs{FP9xPkv^f3P~&yE#|u3=CN)T~+(=!w*X;Z*-M-D;DL=YP|7=v>IFLjHNzTNHvt_ zW6t+{PYY&hNr>|tGbn(d%az|20BGLA)HArVHINLC(id;Cs0tSiA&F-GVcV=`YMlOn>TMJ zDJh8&BSwTQf3Uv3UUC0_`0!!wx#u2Pk74Y+FZqOB6y2QL@;4ewJoh^oJ9ZqShNaRg zx<-+ozwoZSFSZz>@x6$4&#!U&_U+hg zHb##g9rQ({PN!2gfkW=R&6_v#=%bIyb`>Lj@tmUS;imJ4$^GE(C)JvpB}M zY&DPEqrqa0r^c-B2!gOvzBd3`ql5R+W;+s>*@VOCByrGKpXQN2jXo=ROs5jK-F zD70tK9@eg1OJZUoDJdzkORVE)5tx^{YgBCu!)HQi-`SP7Z>wRK70&Oh6OO6~r!yx#%?7*d${6`mP0} zF+`G_Jp~sk>MzKDecQKhXWhDWn9XJ)A|i;6j#gah%i(Z%^!;|bo!s19wr$(SBab}7 zr=NaGRaKSjwJ}4cF!rwhqj;;ky5h4Od;1AV`vbQ{GILThyedJIKu}N_<4B5iF1g|U zQ(q8nq77`g4I31~EzU!}{fX7|z2)K_!pAJ1VaI@#el9YA2+dpvvTvui%z zL>PKg+KlZM;}S@pqdkX;)|}RMIPJIvF!>A}&4KuWe;* z4JMAh|Dt5FM*#$3+voc;252kAzy)MBj4nH{nb^$He(fKqi;N|4$aqr5&BKt`pSt4n zhz?88AFl7LWemRlAu?v%Ktz0RpF4qgnEl#Hj=c9gjRn%m&xwhNG&Olnk{vzmM6Gf# ze6Z1~(a99y+&6*u2}GfzD61Y5RjksO~qT77E&QP&ij zQ|+!e004dqJTG@38#_XsknYyU-e= z(M89jHAZ5LOFaa?ArVN>Jq|1oYp2T?A}P>mw%Hz{^XNS^3X#Mc@&Pg z5+LYoDXl#;Z=b%fJw(=v1(fXl2xD?O5s9gO4Z6BZ>Wa>A?1ME_9hOxjH{Em-t5>g< zR1Gm2jm(@mlib`~a&vRrU)GQ2XzKp}ZKoWk)4VCyRNzEQtfj{R0C0fjZPXXjZj&hx zxp@3*>MDzgO6uoxOChhGO zv2WV6iJ?P>1_FTy{0+~V3<<#X-3dX!_PJy?4G-MLf~)}y{&c7OIrRl6DBk-acDo&Y zR4;T={5+2K$TCseFhy4*ts8`{R`wP z$P7;$Gmqr#DMabtPgNZQexMt#c zdMA`}q1eXbFH~ZZS@Zhln{RUMwb#nttGc?H#~ypEBk#bQoTGWy_L8s$pd;nCmD+mv zbO$`K#=m?rk&lR z^z>ALo3D*#{K!a>;-wKoISA%Y%(bQ^6)&E%tT-NcS8m+Y76K*8zcfAx0|NY^+!g|rN^C!$f2%hL($muwD?eNy z5V}(Naxh#pL0%E$t)7y_2+DtnEv3Tp22rvQc zk8;?YqFgdZhY%QzMp@-&-MWg{fg^Cc<Tl;4q9tWZ@0raCAtH&9rvr?$?8 z#p=Ga9jhRKRwK|WMomnV8lzD~d@l_#QEH+i)gBX)twk6Ir`0okz~U zc2UC*0`--ud;q=9N^FFN3l+`xGBxOFw8YUbxe`GT15rLSPvj&av+bUo@|!J}3XRTy z%VCqP!K6}ah)vJJW@*Gyp5G61?Uq@CvJT@NWg_yxTNjhEdGb36as5Pv}?(4pWoKmMH`1{PUV^xR0y114}rR5 zH}iqt_eA9vR;2UQ;r_VX0{LYLN+GbSRN~?#4+OkcZ*R~c&~`lp>XplR3CQk|e!kX8 zX>}qNn_4LZ!CtY`;~`M5T+S=BsR`7R27DTggN&3Kr4WQ_xmJ&cK)rG~zehe-tw)UZ z6+#f|wR$0fz#ei4)GL>>3`p#W%2x)B26()Eqowp*r?#>a1Qo`}_zw4U4m4P#N}EBB+#eiHe*Sl- zMx*rI8T5_JpLoog6x(!jH&*75Krndm3cJwB8i}nCs6zn3C3{q|yW>^A-KqT69W_T} z)G{&as1gerPQ@7(0keT~v!45Ghgzrq((SONTN_O1jL~R}QGVS_6h*9!CR{H0JrO#S zPvG%7g9Smb%>K#zq3l0>d6lsO2*SED$B-L;b3^gLEgPE(j-k>;G3K5Z=#`%BKLkxC z*==eSLNFUBl?5Oe5Cpr=_XC2SP?lvA?dDtjt+Nya2y$p%p=<(~e1KQpX4lH)IDom~ zFyKp$t460WP*T-wE-PydIGw#nO{{1OK~Jg4^Dxjq7;yrv)`-jHkX`lU!#hX>h5{R8 z0q86Qp&ae|fS|_|WCC0?F9{DgScD*;)fzer!7$($kkesKpg$0Fg{vnAf!iJ9=$l;e z)1Fe02{;SDSC0T*_v)9V&EN%KRk-;1!!yq?Ijgx? zqe>+@N~;Y^dyw+I#t8rpzwv8oE}Zn&NyHEthej(cdTB1p=j^{;>hN^}(|zW(d$R<= zQ2vFoOw?)tz1FJO66iGsyTz`)C7dg8b~a+zDN8_e#L(?_UP?JPm*sPM{WFN(x9lg`E=zAyO=9pqwk#ybG8Hq}yFcuI-#0rn^k zO||U~f}wneQ^&!aJ^(aYHGKYUHVsX2KP2UcpgRDYsj@@mYc!JF!%V*_guL=LyY5{Y z<0`F+ofGJjt5q)gr!-Jlo`~J4!r@d=P@X_~in*ii;7U_|(7S`W;fw|7Ebr!#@N0)qO+ z_#cY$I}L#nM)fa?UV z-&p_koj1k+!t6lrrPo^NpVB~aWr8EpU|af^H+rm}AM$~r-CV0k`2ZU>Y>?Y6troa1 zXw@3Gzt{I^Q51q<4Xk#jZpos%ayRp%bQmWPRBE5fcez}A^wCGGSg}Ix7QX|Y3TnB| zAVBa#>+=JGpd;nG-EPjEJIDI<>v`uL+3k5Q&^#B=81#Cr0YLDh@&kaNfB*j6d+)t8 zH8rti%N7nF?yv^36_^9;g8(Xp1{s1Ml^;Y);6?1fEx@I*Rmdtf`vJj^%2zIT1OE*~ zbmH17nzsYq(Y7&UD}q{F#8o~{GpkhMPk&UtVtEG`1Nf8bF1B1ZyuI>6Y603^|I07c z?Y-z}JNT~AT;*1?>6Mk~JJ3_#*GZva077kr&u0nioUuI9c^M?7r@rJN#@ z&t@=4R!lZK%Tu?qk!zPuCT^1fhJi|e^-Oi(#l!1YbU;f>-^GdA*8S3(c7={62X42U za5&8H*aQpSE|h!Yo8JsvqNa)pfK9bxXLQjS1A=-><13e&51s1RogC-mkNWU~=eCdm4${8bNL977g=v#a90+sZ2EstIwS)rhi-Tv>iB{Q)E6o(v2vJ<%bxJMnqBM z{hobf*OvHYzL!*{nq}EaUXw~^X9dwDIr7;IE|-fZB?tllHk*wtb(4f972!%&*IX!% zoxz^|cu3H4*^J&Kp(x5z2HV@)0A#aS^o9zI1(mIWfn>^s)tm_)3rvIngq7*vN2Qut ze!PAYP1DK-s;Z)C8pAinsjR7`(|U)L;>2Dh2ag3NL!~=?PEJH5xBqm?u~&HX$FJ;g zJILj7M59r@|7nyN+smZm5ngvj*yTwF-x-_5#ksCp{+<}SfBDO+CxA(yP)<->Sk+q%V;^XHwxks?RLR z*3eeLz{5l%{vETy-htRt-!95*+1)Yv((wzO70Fo|iIrR6#g1tVEcW@oo6SfY3HczI00000NkvXXu0mjf6W^e| literal 0 HcmV?d00001 diff --git a/sysid/src/main/native/resources/sysid-256.png b/sysid/src/main/native/resources/sysid-256.png new file mode 100644 index 0000000000000000000000000000000000000000..a66aa94a257742eda4420e519dd205367bf0dea5 GIT binary patch literal 16534 zcmXwBbzD?kw4I<^8l(}BM!Fe5N>aK(KjFBpV{0sJv_FL?t3F@RK_ z%j){f9cFs_(Ee#`TAuvlUtQ&%($-^$LD7wY_rp_-VFma4J(M6@UgZNeO9EQ+6H*hijrJz_SDI}N48jF`nK{G))Ek0;iCbb2K-)rSySsEe_^!g2%U{y_HeIn`rxL_M`9n&(VZ0Zv=-;4s za2*(rTh6+It~%AK1&$<|8gYO$FEm(rB-b1rwtQV@3r&IK!&_j@^yb^IETJ{@hPb+= z@fvj}y&*Fp=ybZ(805uUC%HKA?)oPy)Rxq4VwQN_%UXZI??*#i#XHr?qGDvI3}?WB z?3epfG+BD!6_hYhGgWg%Z{xA*8|V^xCmM3{k%3mFKcd(Zud>d@;dBYOPanJzOpeb5 zamkS?nWP^Ew_~^CS72t8ZIF=#cgy8eLts$TF~)nxySqDr3Jh})haQ5H6$uZ6SwLZY zCoF=tpQwdYM-aCLzTkggb2e`0Y=T@b|DB zCm`qpbfV%oi-67r|oUM5jb*IHf}ZuO;6~W!*-`NYo=2;7Z1f(=;l(Ml&>9Q5@9_7 z4Wnf#-R8wrbsfnUCy3hHxAYsJia=@j{YObt%>vrDrD$qJ--+f%$OfGQzl|}%9<1$%X z%)~YM;=m18=({D2AegeR@VEBrtFt6k; z4h^ce%p4vq6?1B;LKut_$+UX3JE=W{z*HL?Y|3azuCAd3y(QbfrOMiCK5z*^|FH z(K08DE4+KkU}+3iWfG(lMutDxqf+^ohud2{B%A=6-hlPA37RR9zw2nAA$|GDBtv& z+s=?`^U2IgoIz!UJ+jRo-_?8F_L#Y(I?ryB`bAf;!3zP*5LLU;*Co+1-3%+7AUpfz zSoip1e4DIb0V*BdexkCYheQYbeqS1+JIL0Aq-J^vS`|pRe2tI`>ly-*rConGlPab8 z#2=ezz{SGEt*Td*fdD%`E|lnGK&?|02zsy_O5o`sFtO0u@!?o=6v=9r1*hFDO^MGg zv^|T6^lEX8JQNrsWdgFc@*c8;5i;G5W!F$BWC;z%bs}_lbH2zQs7yNB74W%aII&Ew zV-?@fSgge!U%{ed&z?lpUQ;qJdU=#_g&Wl8Eh*U~a{5FqOKCd8!U`|u@_1m=eYL^l z?O!g@3TM$nVN(svX49NMd4G1tsnvGySUrC*R3CAjPdS`j)wurY$kOkk_t7TnvYnow zeqsM^N?w2>S(sXRz5A?LLH4^SdWCB%_Wr^pU^ zwD*^^eJg*%`nsK%Fk=}7pOMJBQT8OhMN?qA{ZrQet@Q;#;57~Yz_%MT$b;T}|CeW= zodyjB#vDOVUWjYRvm<>P@A=6-yi4aTmz2qjrvRa;bGk4YE4PQf10Y8(<48X_bYu*<3FXUkCp!V=|Y)N8Pv*8m}m#aOx zKviq}#vA`ZloQM4)*Rg5o|tu*@!bSX9>0>GkcM{fDMOnDvXM=%82VTb(Z(B8$dH2u z3c{6K)d=74sA6zDV)_@wg_EscOdOY6+8K9mvVB5gpOxZu?C4w7v*uk*P)Gf!3-FS@ z>T;1F>L$%8iH`~9J}hTy0$ns(5O-u^xVg^Y<+vL?7D~?r? z|D3_T-1<#3NTop>YGlB}{Ax3h)z>{~As@eiIw}6Pi z2WVj;YiyZ9*{{xATxBHX89fY#KOY%y+i!@ka0^~tNW?V3DXT#te@y`&5#%c+<~~vk)NE&9D7A`!*Mj%S2|Pl zdPvIlpFfq|-Q6k0+@G+svp;|S+)|KweAm-XkUB$y&8v;Jes*|wvY7qpQ_J~p&NPxf zW1OzGd*_anK1X`dzpJLQCHsz2Qd;%4v(k;O(@lIuyZf^-ZHl)nJ(|{jpq?n2R79-v zq_9pK5G6oC-XPv+a)Ke6-s^Na{eZ{E2wnr7Pn^Mu`@UyeZ^soV5>r!wvG5NL4x*vA z(6=|tI_c``PyGF>Y-B`radAN-;T20LeGRXx(7_3aRM6QA7}Lj?Zgt;D}=4-V5a*23w*JOz6WIJmg8jgA!6 zowsEbSFA$Y4j3b?bn?n!Ojn&YLjyG4%-FlV-aXDC{_r+hEcKC|J$vYKS9+>lEj6c2 z)PoNQ%nss%w23n?uoktMvogK=u%=m;37<3ey(t=Y4N9FSCCNIwOL5ox7;EO{UhgLz zc>?HKQb;LaXFfCVLEpG^s89ugj@CeYYkc(aT8Z2AhztSUk<8F;-_G*CJ{{t{IjA3P zKA%t}Ba?w^6f<*GY=>*ICPmd+57hY}tlT|3e7C;ZQc8GL6a;ZMvK;tadU0HCa_~=4 z^50?PMQD;$d0a7%Ef6PwMA=8B)@z*T$%-$>7n*cZIPu}w-Ny>Jw!^JaeFtalm%4Im zlVf{$-#1aGDP1-GS1v~#SLQ!rsY3P3FXkE}!o#tzDCp>Zw`^w({rbXb)Zr)OvHknY z)YWRRlm_xv9ugnsmGDviDqOu~Z@G;Se4OR}+3p&db z&K#j;bsrZDv&Ffb(=ke=4K4SiXj=3#iQh!tZ_5a{E=gKhSq0pZH#Rhkjg76mTx3@I zc=F@1YmLjIc>JAa27ml3ibak){)5){fd@Bj*9U(Ms(VVh(+IDh3Ps-V3Ja1CHM687dHgn*ggaUv^zwONU=3PyLSqUL#f1m zo4*LwURyKe85uUI!tw4z22Faq`+^V+)$8Pbs){_O8lQ%%f`OvyV=#hRJ=}kOfKMDM z&uj7P{HuqdUk{O0Z?I&su9jAJBD2y{Zf=%m&k`RoD<*u|49=!vH-{BBe*1PhYnzQI zmhrum4uAde)d7Cj0O=#n`D1s(`M(dh^mgL4swMZhggx(Zp}%kq6ViIAH91{+msSa}#%Ztwb}M^hyG3 zC^Lk3Ea{Ah$L@z6kFujqV$fgmwwTUQEj9lpwA0|2gu{QO8+_p9-wlD4{~;!3I!1l~utxg+L>_?ug_y<-XU5}ty*l+rdw8r7 z7OYt^D{+L2i?0s^5IUw*p}nPntNTq8OE<{HKDw@e<&N~vhzk>Y3sIW6<-0XMT8+c} z7SxN5$xKRk#HGCqW3kg|wE=OKpjL8>b9uGZ{$$fiLrhD*Uq@D69@A`RUMFAMqK2N{ zmxDuL5s@&;g9t@|(iAEhZ#JKC z$ZYY;v@TbauOBLms+)Z``PTl8xLMl%!|L3H_`qkXnUq5!1ZXQJTE^p&_ccjZM`d^@ z%2(0w9@O=4=n6Hy&m`&qTBqdb*@zi z3*MYa8#?h6)%u^SV-J%+7P;0_4sq-EJ}TC^^A3I#9LZMWFzJs?oyf4V4=Yp7&#y*h zN}2?i@qDcI&rIvsU-0Y64mce&PnpJeZ!btaH#cYFYEV4+Ea=`xjg>^g>wu`rz{8HY zmic$$YpKX3()Wz~A#=w zbeuzldIzZF_nH>&<-ZLq0t>I_0$soMSf2R2N>I*tb?~>AGET9HK`YQxf}P}d3X7|? zvMEmSx1jf`44szz-Ldt+hW9L&u~`HpiHW!0!N|>A-C~e@Aib5Qb8vHq@+kj(d$CU? z9UvMw2-E@k<$Af8)iB$(@8BBYIg?rBh(#B1AOlFD^osX4ns;@eD@8 zf4b@2yQdEoQcaV9Fc?#JtgruEJ^J!Y?pD>c-hD+zv+dpRbR>Py&uhf`u4B<3hqhrd z1`)L3H}!6B^0st*!;0`21sUbtQ9aL8J|CJ!PR`xA(tO5PS1emI*pS*^b-nr^{E5%K zjEh32)j!k3cB}(fy)xcS8=Wf%P~z=e`1Rizw);HW&SdK}y<3q%!A#`i&V9mqo=?B_ z#`zL>Qa$#!B6>L;gavVVM0+<>8#8RG^9wHcCZ(sMXlCVSqs zE3?yOX|6OiA)z~l7pM4Lfz>{>2E{?j5jtfkm0wG0{>`Y+if7r{6*(wO_}*r?^<}a; zGf*lork$E}2DDVP+}!{16wh4ig=;((av&v?Jb}C2v7WnAoH*>54LO?NE5}0_UN>{cH8V37NX}pv%3UFT*JnZ%}d1 zE;^x{uw7!%_1XsO-7kUQV;JEzA=a-|IE(^)IFr+ebL(O#c;5gk^EsQ2m7b;d8$L?I zy5|9!Ly5sC?DUqG?p=BQN=L!e6~aKEzbdYC9O8gxKIqaVcoc5jShn@6E%|HWrgW`; zlz;@4R=2$or0z(|=i}y%i=-nSJ+$z(%-@ji)rlm^5Hu_~$XzeH-ed;3-k*<9gRn-L z6$vR>T2N{2hoa6_>pu<5eZ#}T&~Ed6C6=Dq{-#+S?j4X0P^_cK8MmVn)j1Hnk&4ts z4B2SpFI^sJf*DBfRi*tqHkj%Gu2ON5cI!*9Xp)0Tve-Tm`-hZmw&pWbiRXu2T$9yk}MX7POm2J+= zuWmKRof7liwg2N@mQ1iT37bZNOu9z#nFCGE1IxJE!-Z9w0c|q*9&RDMXPV!%WUl*7 zf7!KEa8(r~zsC#FP+sOFgAN~C)J*eycAKN6LNN}oHab0Yxphs;LH=F1_c!u1Aj_Sx zT+_GxWOA=#gsT%5EW%bQCW57tvebRSLj;gPAC;LA`Gv)IWnw(Z zOt<%EqqYmpZ%d}76}E9n&|!f~+n3$-RC26D=6iF4QnBA?FKkl~pZU*}cw;@WLCkpqn7p;k!BBgvS zg##%7=94d|jkU*3NTaFKAA1PCUX2VSez>%q+zs$}lf07#GLa`6A)AmpUsbW9+nRe< zc3l{aQUhT*@8Tw2LCWF$-HL<_6Z6=%OHr`Qz>gwvkyjasz&&`t&AewC*q)`^&x~w)7^yMODPq{sotLyCL4Wo&peu zD0OlUgO~Zy7SY!dU_QkH%i%HXPdvYursZ^A9zSj+Att62b;~L9k~sr`6hD#<4bN(` zJC|m$Gij78c+cx0R38Pifx`IxsC)BR%q&&E{C&r5-u`!g$Q(Kt;OqK)oxe~*Cgqaf zvGF#Qp&d78Uw z8=G=I;6a>Au?pp&jz5||oCo!KQa4eIU^AxQh8t@MUDuI8?V9#F0c@@a1 z%frpBuGd080Dca3wy#RMlt7=6{A_Snd@Z5Qj`fofFm>+tZWXG?{2D!H=vA-wmD&Go2ayv(l(1IYfS1;u@_tNo#7?IJF>@p->+C&MeKn!<;%1FO3I-9zX z(V#}tgjDqmT?vN=z!Mub&t}?NxGc0~@?^L3PKmmFc(BJeZJu}r4}Uc!O3=Cg@PVGe za195hn)LU3LZ^GHs|5xOSTDx-3aTut3xb}N*l#qrR zo#ycRS=f3rfC2+ZmMU0!)hlU?7TURZnLmlkEm>Y#e>YnHk_htRg9Rl>JhXw#PNVp* zd~|HAF4@sG2!tp#E;gG(Y!&@of_^U~^FsMaPnNifVBx4FK7l{RS{jlsv2bVuN zr+%O(R%KT-qZ!-W|EA?oWKe1DHvF`f{!hDg z-l)pn*vlyoywAs~nnYO7X3H^)K99Cvt*R@v`>9(In$9_JX0jWWWQ@Gg`SWLAY5dAU zq0LM!)wrV}GbV3xAY{YB3q3>wA#;7*6xkjmRrjg+@g!!H`Z2JpDZ?QI@v5AQ*~d+M z6sT|fKr6xHy;D-a5!cIx>5C5OB$a_{{as{#mdf1vr8ze@q`6sCZ!_o!JT*NX?Hfc4 z9-G$sNqWo8k-RP$#DSE-CDN;E-g1KETg;j^BBF7C_CdQxi0U+#%ylU=ld z_iyTrfcWBpy$<&tJlQhYb*+fT!YfO?HJQbFaz0#-hQSwl!Eq_Yw@;wm6Na3nB>5{Y z-+%m2)LRXbMspLTAtk%Wx|DD@@v+aTk8*wz9W^oNrYS@N1R*#ygXn|}aC%OmX&SCg zG||vscVO!PJa`2D@Das~8Jj#6U)g9>V(L?(LGY5_e}YHb%7iQ&-W3IWZ#%YJ!~?D3 z8(^U;T-{3afdw23qm}KZT(iYf)*BV?RczE0eZ7>ZJqZ*TSK`->(Eu1Ual+S|D1r!4 zTPa-z{RnvZ@{zi_df6{OzHu?1!ir9Fu8wrZr@GXjVJkYAa!tT|{+IXgu74OY5KgBY z)9@s|wzn97>$huRWv5w|2kZUX65dCo927K3Pw+j-Yq>YDYfoJmk{&~lTmVq$Mv*#| zSAUv%snzf|B%X|ntn8ORpM?fgoQ7a2@XGAjjHKM0-^VvS%{tFh@9ifx0b4PEEjjNw zhvcoaNG!<8q^69X-csldKbE1kHWOM-7`Dfl^029{?}|jOyJ9{+)u#eE2BN-YZ1@Nh z`UtR^iUX@DxpDms^6q$YVj_=Yk#GRj-*0v7zVM-*xRsjPaX@N(a?kx-q27o;Ri>@%2J-ncEj=C)TmqLX9cBMMw-_4=2Yg|hS^i}ne+@59B6*t@;YWqvZ(x30^bW+kTg*SLHUDiRBYEp^Hz3(bjU zwqH3)U#u@K)Ia4K(xQQc>g)l#L|aHV&mOv<$^s>6T7rh*7G-YTa==+!Spa=J%EZ|C zdNLdNL>NgQ+_{0=)1)KiNSW#vUJ+}{iL94OT7Mr>IIsKky6fL`S&{VuE3CTXE3u=SMBE;>p?LGqmfq{pG2tKIV8yCS75dg_|(eH!t=^H$Ank|Hy>>BA_~1 ze;S-H{tG?n>M2f0=Tl@hkaja(PWc!FpCyGwd4&IxKIw)&_$hW%tfNL{P^O{} z-an>>o?Oisrp5Oz__y1BSEj8s8%A+rhjelvt3V75bNQ8Juu~@x?1$J{_z?2pIQX~; zbaGkt^V28dtbkLM+`5-Wwj^JknYw2;-pD<(Fs`dz8i!Iay52w;Q`oyD6JnMvH}0E z1(^N&OyI*W8upgaR=L_1RQWn{zhW>LBvOOm8_FRkTE(yYJoOVX- zmXq{gRcR<4gGZVVmt}u6S-{O^%7fg!aQcYjK5Bk$?t0$>*fC27{*e2wgQ0rVRLhlJ z1gTx!*m-qSDR9z9vZJ|nOaKDOJ!;y@g9?78`4aF*_9Zr6+o{O+O$u(~=RrY1*}4lg$NeA1UgQ#ReBR$p1VLzFir)hSZj)e(Tcp#Nh2@@0>6)8dvs#@4uq^b6e|SVp%p zHxK@TS)>xUry@=Lc{4+2PNQL%AX|pBKBS< zU7Dz>-hPtx{rmT+g7(_kaQLi~z97iZ$Y{{adr`sOzSJ$V;jD^nJ!9y(dANCHVOeS~ z>Na0%785D*zCyOA4v8edA~kfH6MHbaX9C$liQ$7Coef{mpW}ap)%1NH14XRxF=52! zx?hQ}iZ2JFq%cB5fHn;Jy<1Lar+MvS@axyF7ksxf<&*-vjjva*V>3{kgM-rZBmLu} z=KZET!VBhJjulRraO6qicr%XNdoBT2Q@^L#K`u;Z9BrUnvDP2Ith9e*$1Ac)nRx&* zh}IQ14SEvIN1ec|4!k6iSk=E<@}X@&YiFIJX%qa``mkMEcUc`A9Qyk6{_wAUE9MJV z8WLz=m;4zOZ$ZQ%;d@H@BQBOnvOq;2an)2RT?(=T6DzcXOsw%`5xZe*gr7Fom?rAP z^|9&5tLlNkl$Do%mGtHB>FEJq!P3&wNU@QJe``b2T{~wFzp*XdNWO}K+O%LqHpT_I zN=0-SIf-3Om2SJ$@rU%;wQ&(?^&eA#K;OnYC7WkXg(8JNN$xV86URro1X~*C2`G(g z8-%yiX*DnPgksJ%zh%}b)?i^}WwoS>=v_^aLQm^mwH!$kk_0f-Wrj9zow<+TE5m%_ z=cDUSzcPVsr__E$eN?8%q1 z74J5`UvO~#*PF>#ihpym(gS`(IP>~O|EgC7jD`o_}Ub9UYhdjYM#dHV})ZogCroFnK4WC?YEqceq9ZSUB){=t)_S-8x7A`D}5<{&m~T z%hQp0x!1*-{LcdVd@3%hyiZ!70F!nK0a?npVJ9%1sPsD263M7_qKo_KU?G@)7j+6+ z*xl`DqF)}h9Zvx3BT&mlefV(FR^9d4xl5xs$$9=;t<4~D=fkB*{2Zk?%7wpZkQ13) zW_8)YadgYu#hHxgO?z4z-D@@JiwBtc1p>`M-+N<8-A`Df^%wmT<{Tpku_TVjR!|MZ zuXI7fkZ=aP2eb=60puA59wkgmD`AxW{Zusy=AMOmJ;(`IGn!lTmO= z$H*|UiGF~?ZHl71awd!~@P(*iXxwn0csyfHw1p8!7n0j8nD`yYKVlJwR;RO{wm;CE zywXi{!ffXNs@NA;9|nhqp9l&4v1I@tk1qZpo?hm6nO?ciLG6GjP@50T@EuJTD^tGv zxDbTTHr=H#B8~8%Mb-$eMh2j=0pa>)=pkKo66b4>j3G9C}Ga640&zTT6n?<;&_X}zEw}oZb9UEZSozeTd zkaPtciQ%}0uO=Uc(!vzWlMdH}sJUNKF@N|;qrRE-?$exclM5}UK~=%GZ^<<^d~56L z z>3%!UQ|Rvrt=?%{3f#?WOy!R=Cll-JVd3ZPOI>W53}f*-1U4W_IBmD#s^z2*VS?mp zfI?7g@0-=BZ<=C=!I-+Hz{AEFe(xjGPf1Bsl0JO7xfA;0#$3ttuLa%3GpDAev`kHh zfdTmfOevrgNVpI|W5KgJZ@eOA^m*PkPp9rEaEH7=1N1StGlO(Rn>}sBZITD_Xppk& zKwJ=Kz!D|sS&Qy<(K%OfvZ0#wf9Y~l_rmpj8ChD z%*s#3q`}r}eIx#BFI%4CP-}~dqVqOyNta$TtblrNA9YjROpc%^R)gn9AR)2$tuX&4!Aui@K zZnwBq4t1wnMZLZc7t}I_pzS2nzlUv_MlOQW>vs|*#jFFns?UqxT8yNj_82Sz4Ybg-JFclbi~bhA+q zI03KaW4@oXSZe0C-rtij{5CN~lIe_)^3KVE%Tj6%@aOM7k{AQUn&>re&e#?xeAW% z^w%6Wg0^r6Zt*Hp`U*cPHL`0@g^s^+-u##Mcav;la?+^FJiryE5Eqkw^QO4> zRmaUG=Dv4{J3b9z&g2nj!TgJW+wV%7EPoc`%wuBzZ&_72Ep;E}?#({8B<7iF;J%=F zemiv&#`2mtk)JYi+#6ecxbgLY|5E4cYGb%&1w8b<6*{9Sv*uKRu|ryKW}p=Pfsns z)@<~gfHIt2GOZ@e6OS=52=OUHx;DOpGo{7M_19xN8%_uk9q>QziEUFC z92+{=xhgwbH}Oji-KkRDklLX(?eW{WLqJsbcP_0aJ-w#s>)Sc5W>XD8aVc>fzK9&Y z^Pbh6Q2Fsa{2hGRR3;#Q3qI?Ir;u>l0+=c$osikP73&)Xh>U(kqQ8Bnl*XRVkm{8yD z?-YjqX&5DHel3LARa{vZ^|K*YnilhlLL$(Lw@v>(I(Z`BWhPU?n`cz|?qGBQS>*(D zJ)b;z(o9BKAVtyN*zK327HAA4o4Bb+lPxAFO>^_D!_YujF(KO%VWU8I96+e?yeA^~ z?ZHFwTd~FE)CRXzIlAEcw@tsTPMFX>gc&^Gvxy@m9_kD7T6 zU?DIxHo?-Qdt&nA)t|Yp+ctwGrH5yuq3I$^KFmNF{k zXa%HO#0&45G8MPE<8evp1{TY5my%lm2IJe(x;IpNuG7W_D##QR11f*p&Deycu@O+C z5R;G${{DSQfu)Al2@PuP6C`eKwN`GGM~Ays;P^aFjZ#iS@KoHccu$ejF$pqe=KS>0 z8*xcpv?}tPF*q=J$2(GdYU4N)&%jr^zMSV*;;#}M39pvPe6vCiljIvr!l<|)`+R(z zk$h_`XO;9ULZNi;s3*gV^N-TEI{(eUDVl4=MCp4FglWxyaRn0ua)V?;(EVsr#LavJ zXJ)j$GA1hNUpYInh;o3f?Fz~+>9Lm;4-sYu{`>KtosmQ-BYAeg(qSyia&N3{6T0=X*Lu=nI|B zF#nqDwNE$2Gq@QIpjsUth#}%KkAiU$9uxPi>?Ta&keL9cCe#de{*_($I z{XrprU#92#w_6Slf`HK_gQHycc)Re#M^BH5hS!5J)n^KsOUM~Xvro{H+LspuUIk2K+X zb$yWB`$jr>26lFpa5xTp2_T1zx$y?W9&d+g;7Zv1nt4@Op5uoS`Ro*s4V1Qaajf0p zj87yPE+30>RSIT^zxdM=ci?|0`$8o6=WhPIlyS#Qrh0Y|4kd>c}its!C;=9Z`KqjyShjjm|I(Kp-7phV`e{bqK zndi%O8-Nmke&Wai&c1L@CZRv7$R1zzxve@YQ=q8qc+^g)+_=L#y9-56MH2CjN0m!s ziRGH1xD-5*(Bj4D-Zwq=^($_oZgb9mhw)R(RZBSkYSt6}=4s{|=zcHu5|4@~OcDB} zSm)YvU#lw|rlNw4OU{*3G29Ucr=nO=o9LSrG$3{Nxsc}ol+qxv{@@~^rtTS&0O)(z zH(U?A;V!=DTxjSRa)bNC085z+MR**G6GE>>@pBE6kNVX$L$e2CEG+>`q1MZMoOTHl zx7;Xy@_s&7FVeTqZh7K22yk7PSf+m_vr;kNTlR}6-(-=< zs_D*rPl15re&`XAt%_eA9}5P8E*hT#9IMhOFPDUZPM-aNb z9VWoRnaYr4JDJYZ8xr$dT$hMK&*RM!vL5~p);zTeCtgF16V+uCVhRT8-P@)u5=3ft z|9+^spY7zneaqZn>J@~>9DzYXpPy1VlEpCA`)KhKV@|`h9@bMdP%tq{bHu?pvS)SO z?Kmk={(O>c_p20lEF<*2a;!j3pAn;(Yz`(uHKH5PR_&7^uDr4A0OBXuL4z%$44xle zV=YtR!^uZytcJEw!w@@6N)jrd9v0ac=}x1;EncZp8w4~?;MXj&3@j}D&IrQRjo_%E ztS!Xxemv3GxdFoawXnozJvmuy(v%)di|@bXJG-jRM(vlwNGS5z1pYj?X+E;GxB=!7kxcENah*}yaB`p7Y=ZvbQZ)OPtjkG8**t3J8KvZYowXb7&`Nq zR$X@Bjv>3KM}kpMEbIwl@-pTp&sA$wVg^fg^){H+P_I7Z5TV(K=9ze5-Rs^1ufu~Q zpCXf|wW2w#1A=JHqAY-}D?`vM<5(sTmk;S0WWkov^f|R+@86$RRTus#E3RP88ZMy5 z^K0w+K%YbU7oHvyzVJ_B>iRr?e6_|u8C4_0MLtowMyQ5>K93M0rdZV?h49Cq)UY=E zaKMicC<+LMpfMSw4gw>Sd4NE0qPixDLms~s2q~6WL#?vRloBQ2gUYUVDTuTT?~gVP zQ=SBoLHPgg?m%^5&^91|0k}m+BPBJT_(65MeLo8xY14Lu%HBA?eSUb9iD{h281f1Vf)Nla_ao9=an z5qM!Yg$~Yv?6j8h{YNFfb2l9setazb`8ZtlD^>=#akJB1ao@+(Xm%$3n`%p$OEk~2 z>$|FJ|M##DgXU6vg#ks6P5cUt8QoGO$aJxMs6d5}RWLeV_8$jwmaFvJIO%ca4tym# z3AqM4gz&FulR=PB@FLY3A!a8u0uU}$ebFsM{Q1bJ`=>wYt8VF2G%IFPK$&+V#~af% z=>-+)?hnETXVSG*2E%|QpUb3AqPqpyAoC)Bb9anXVgSb)0G@3v-(mD@BDG6m{t+b+ z-#ISUj(8_B1riU4nlk_E%KN;^>WY_zE%P$u>|ft@p%;{_U1bTS$zR)??eL&jMbPfm zfFRvtL0Tu`V$tXf`j5>7sGPzu?4MReYm-8PIDpUuLBNZ33JXv*;M2gExC#T{I?uoB zpnuo7dg55p{yR|u{uf8-2)N5E6Y_ofynr6!P6Q3|@BIN-|L&AjC-jHtA~4C(Apg=i z0PWw!dkpMZBj8R#G>GXv7z51gW#ZT^4{LIIbQU5A>{9SUq?v%TUGOSG*uRS;@Ik;9 z1td`I{u5(@;Hn&6&npfzG;jiF*r1=jhUh7lu+d!_03D!?#J{;D?d~BV1YqtH*Y2|D zWfT|Z!xJ&<=+*~+>zLd(qlnm{+mdSuXY>PlsvCEv4CSP)#f=G^r=KU8OS^NNQvC&WqA+ZN00}#dl&g`BD(nB zI}cHnurN3|gHWWOWi3b0Xa&%@zK~#DcXJ?%gvpR~nGjJ1jH4KOduE6ki1y#2mLj?d zZ$MeTaqX{TN-(#|*1R?E_q_;;#+_C?Ke`6A@~vP7}?Y8Kt0QQXtd8fHU&JI=-_6lojc4;<)VL((HrdqlzqX(b=n#>D=3 z@4H^oDK(OHf9W0Iaq>R8Tq^3U$wjRcACbl<^1aHC*z)YBT8Zc{TkRcA4cNLp)U(M0>+G3r?J z7SYH>#q<{Plp%rYnwGqT-g5fWf<59Dg?P|PHPK129jf!5%Zpa^=g&%SW zk){oZ(7PCs_M7}*!f5*L)W>vBB<*tys(N>8#^=_uiFU?i5Nuf2>$=$!|2WLqX=r`h z-FiWrITO>n5(-8)>Xe~f1EL*-U5%}|^;w-l1Bjw*4b{TZKb7|<^=UQ!@#(QPB(&_B zWu9wgH4Deb;~1`3E?+J3?tsa2nIwUdk_&R_bunO`uU9H28Ak{WMRxwQJxH)t8|FBc z)?bme)FSKRViinpJiC#wroT8@FvXQ+}AUTp;l zY5ivLLJjcBfftS8mIiwD4>UpJ^9Y6mFWlyKauQ0c4Jan?CJ_droyY!wxPv1|p@Qlu zI?q`!R)a4IM8__h%*_W4#KJgc;B^7;qM6gB(H3H7clB5RjfNplMBtyUw2v11YCLsq zqGV{E$CxE=Jr&s!bpS9=+ml;s*LV~hKd)in zep+v^Soy8uY@OGByw#Lwr~K~be}U1OPjE!5zglhufbTXIWN114cYC3>c{B0DeP}^3 zGzDllW(?;`V4a_FcW|Kjy@wgb5}`f$&^1|wMkS)|U+47KqR&Dv1s0$yL>=dDFD0IW z4}fJ0H`v^*>61tbew(R=v5CW5@q-sp^f~xgDMF6#C5TR%%mR(}-z25Xb5Sk2I)-7DPxxp=$CdY14QU}E&J zl*8fWjq2D4D4rfy%%&#eism@7xx_f4F#G>A8wXta1|ZHou;X}-UAhO* z>aNIA@c;#&gIf1`DtuwBy1d+as^n$fh>cyKuK{$H-o1QU8Mlfm+23rZR4KU!=v>I@L`zdCx?H0$(RluCJh)O&j7pP$pJ8OFX` z1Kr@iZQi`D?FbCV=?X-_tkU&h;x2V?SAFL{um1@^51|rxQ{yzt4=BmWW5Tz#-T=~o zpN`cXtcA0g-MZa$TA-8v(qgOn8JMsVOEiW@Lv0%4yV=E-I6xPcsqn>5V?T8g>Q?ad zFl`mqI;s$10D2NaUm4sYvrSde`5uc-97@pJc^j0j{xfLv%`wC~;4kXY+$f6kpfo{v z?5K?RzqBN+35HsSNYbBoV5Cl@UqgvOwy+gOz{E|i%)rsl-fe^J5g=SY#o@t@@CUC3*bn@ke}O?>i9{-OILrdTOljoBt0E0D9pVLSy4i|T^R5}kcxuF^C~&Z_x}S~W%Ks{ literal 0 HcmV?d00001 diff --git a/sysid/src/main/native/resources/sysid-32.png b/sysid/src/main/native/resources/sysid-32.png new file mode 100644 index 0000000000000000000000000000000000000000..3332bd193f8a4c2824e0a32eaa927ff36356f3d6 GIT binary patch literal 2011 zcmV<12PF83P)QWI3fXff+d>d!sk)PBoL{K1q7bjdl~5OqO;)&UA1T3Kn3s{z%>eZ4Uii8M>9b+#ds+u}BCbz)e{z-%2yiTZte^1Y|#s z&K7JPk8oI;2>{vzBhks3Xp_Xv zz7$SC1Jq`{^vj$n^H%}_UYCtKpB`kcQA>GwIqB)?0MyslbMfLuYM(fnwtOSeDcJzD z->$}ed0)q+j|oIZFnJWg(p>}Uffh^reLy8Z`I7bKOM?UsOnR>DoxHVM5k!f;mIrKE zlu1T{itOxc6bi-AELN)(r_)J8Lj#8n9U@S;hUCJ<1Y|#rr$6A`7f-P2g=f)i&gdx} zJvyf>i%p>fcL`7~hBEZ6%;(o3h!S>7GrlW-V%D@|a&vQsfdgo@T0~K#prC+*2M;3L z`3!6GJp@rAW8oUM{1*D{!@;d~18rUUZ)90)4S@q_0&q$MHYUtjsg6oWL-zY<{GyWG zyLXe6lr(DMDV0hjNdh1-F_E1+cXI#K5&T{cD#Ikwe)KB0?+*vJ^ymPTp{*X47a~xa zl(zr?d;3G4&q<`HsA$~mkBp2QYUkwSu(G(2zLt9c#7&*awcF2tj}~rVl?W86V}h&g zf6~P2)vFOjaa;l;x22?{gud3spssPr9Qo*3@IJ>RygpSpcR1bnjB13-jUPj`3sgn)rSU|8SbaG;3~D(Clk0f^QH6V?4R zlB@Ok_+_O#Hri5J@xk9r!_)+Bx~!eSL6fIaQ&Te`0k79PtY2GOi@}%+z(8LY%N8kd z4a5XbN^Be1so%Q4{MYc6hZDHa`{+(^FQ?>k?DS=tnwrKX;PH5d+U@P_R903JGv$ZD zWNUrE+!;~y^v6)wQ~=;kihEM}`y(ezqvjKE%v^nxr?ws>Wh6OezhM9V{Wu(sQNeva zA3mQi_!v2zR8&+jeZwA<8XaDjornMU1G!Vx7?U1h&^g^V?#&!^<%1ysy}(qInu55j zLNsxcd2H$B&V>`?<>g^87={h7+wFM0UMv<1hYug7!J9~0(J}-<#C+on3)8JkNy{Q8 zy4P*cSxaAg`)kv9YD%Hs8@9)HUX4nb78Nxq6@6+pPaFdKw*4GQ6c9xbS(dTcY}D1& zasK>ywr<^ua?Vdlo3k82l<0j_&x23)vg1u9{jN0kz*BAM%WvK_O?ZOB+6#em`LFNO zOqv$F3B4{m*5(F!AJ@}iI!PcPlRSSdu~`Mgq~{S4r4QbC%?&huxP$H6xAWDxeStO0 z3>&uX?f&>X9pMrEMX}MG))#Nqrp{i9QllGpuy4Rg+pTIIR=vmGy?fcTX%kgdRczk8 zxdV6&C=SLlpp8g*b?45V+n|Uu&Xe8!CBSjOGp+(7ZIq=8uGhf@6P&6Z zK4`%#iTSgmm^EEPY>b*~^@XkhN9{ZN-!~tusHo6XS65@QK+4>un6I9u^Xlio0BF=Asz{NqZqKGDw+W5P7Jj$?1o*4*#n;JP{0dLqHhdlzt){9m zNk|icTkQtA`=U{+MARw~g(4_gQmlh(4bxo4B+Js$4XuOOzC)Fgo1eFK8{%63$pHx|vxLh}j$K=vAFqcrTOtcKMN{>K%`2K<#rAE zsWAZSh8$5!F*Th%+Vb%2h)}rEYhBd+C*K8>u6d)*^gYc|Yd8tn=b`1w-&qjvVb`u* z0Pbgs)9R1XN&@gjn1yy*dW@y(w_Y**53bD!m^8-xw48V)d-m+%=+UDbKYskcXw~r` tiBq9^Zq@gYeIgQn1eS(e@%zAz{{j?LCoE1&C?Ze<5j-GOvDGSLu+WO5RVz|2w6?phwqs|fU3ctWySAO#o_2O; zx>u*IU0u36wzal)-PT%cnR=)_Fe;RTpr{;GAP_)AAQF<0eEUa2!XaR=GyDGcyC0%(9fpbe-6ih<+6_Y+(jV z1e9*eZ3Tg(oPS`_tox9w1O1kR!)l?UriAJv|AE8Y0q{An2{2Cp{NT6&WcVWCi$EYy z0HlS@&mwX8j7k|NfJkf2| zJuoY)r+hpDD&QorICl9~;(n5iL?-uI)o!J`shS%Nl{9^K2+?-SyO31DlqK1OCd?%$ zb`~P?&=ManmV;N1VPNq*wkD;7J+wx$77do zBi^tcK_d0~@XC2E=kKMzr5b=o9(jbMq$DCEBQcpwT)1$7!-o$eiXu|&B$C!VMa0ZS z2vV7wg-Fv6f28))e`o3xP8I$SYT@?a*G8prq^ck&rL|LA?3Q+yAcz@*B!&{$034ij z&njlE{aYl19|i)X0)1caruTX?&ph)Csi~>x_4;97YHx3+r>BRiswxf~I6z@xA>pYj zNc!nk6dJw96Sc?p(|qa!4!;fe-aRh(zNj=bgAXS@h&eOFTOLmg63_q*fc*YB_=+pi-%Pe$8UB(ACxDiVeG+f`S5Gdg&!JQ|B`8(dSSE z2D{h1Me#fTNOI66KKeZbsK;h-)2v@TJF7eYDIH#gVs-0#an>FMdLUAvZ= zPhZ2@djkN8R7ULLHI!6A-PO^SH+A~G-&9I~2LVFjlD&&ut-{gM#`f*o$Cb^iury;+ za|7<+&;^7}@s$Z49Y{%Z(va)+Ku_ z4~C3Kn;Jad1CYoS-b`Y*jtk^YM{uxfA8-!Xy=2{GirpdlPR+_5RxCPCeT$CDy4fz- z3<2*UAUXy{E&AskeSNO8!qDR2pb}oIih_+S=L)6R_LuqvlK|69okY#Aa^x zRHt@}neOT{ELot&+!xHv-bvng(YBFwZ+-Lkl~F!rGm^lU0KKjCp2^SzSDAS5;K2!l z_a&iY$Bwzq&`ArtDYDgtD=}V0S8otso=u{wH^L*E@SqmMzW02~#uougQ&E9OMk;+c zaVxizmzT%s)2IC=(BI!bYOcDvnm6BklPPIA1V(s+v$f(|0H#k>5fgERv^ho!&L+~? zJ-PXIvKdLB2RP7ETSRwLwdY0jf-KZAvw8B#C#kEe^NWDRVi_f!7hil4S#UIQh8)lF z!`$9TThS4o$PGmk;7ZqbO>SUGa*Oeg#R_(wb5EB!FRy(?8xq0&@4u^xz z&Q6XVJ<5(9JLs}WNqyoqbWzj2b=LVpu6^}iJo|)>_?Q?zxz7&zFr)5D-xLkxjGP)KFqU| z4=oqkFBMU>|5v1>q>z`Fhg2$M+qP{~RGbqItkOx`g8jD^^@v`psSI}rQXO%NSY=iSnraQ#j52*Npj0w5jPFL{O4m&1Hag? zVFM{CDLnVwbA;dXQ|>aXLn>F&SzSu~r@sd<0?XWY4!0*Tkw&XigljE28chK>ovwOb zp^%^pl!74P^TI{kJHyD7@M}ZPuuen9CgWhiwHx?3z~n^_leBUx4u=h!)m7Ga)|65I z$?Jn8(#P|J^bWej+%yMs)2u@iASF;EMH3)JrIa8DAP6Fpg6teCi6=}apw)D{58%e3 zsq!%(IdX9}Nh`J>Rj824l&%OwSi_n8K1ml+$^L6k`^`-v1Lzz}Hn%K66kog>r_)N6G8t1yrx(7_1TA!PSQqf0GpOVuTJS2<~L0tO$ zZ;saS=NV&WC($v$weLTpt?*NJ?b^l0jT-?b`@HBrc_4beC<-Tl;8E44L&2%?xdbTf zElcK<|K!IUM#dQ#z)?Y}P^JF-EdnEAX*hL|#uM-I!V533apOkj%$dW$z`$jn9o&pf z&1HfhX8PLsq*5E{^D2y2+X4)KA@GCQ$s?yr`Fm+R@h-b|?PBxh&FtU5f3Sh@-{bzT zgxeFxfsoOc3(bEi@S{92c)_=A+ct`ei>aun0QeSo@V5W0a`Hg*JW&)50n>m=LEzzx uO-=tF;0MPX;J5B9DRZ9~^MHQ^EdK{l(Pn6JU=42o0000F!SHlo-Cv{k-2V z<~Z1^u3qPLu4r{t1#Aoo3;+PI6<^D00ssQ|69GU&0smb1PTm3lEubhXrR_WaH_OMD zxaYR7y}0;#K#?{NSsGJL5{hx?xV40Z)iM>+yQfp9)w`0oLmD5inl`j{RLY+~ znqWM@wK!*m2Erx5r8F=!Hz#(yU9_elo~1sNC5AFP%bz+ zGM>j=4lMv74H-s-k^;EEe60I3zzG-vD1b?X5)^gx+-H*HP)&f5^wGfov|Y#ezDXD; zigiZ|y&?1q$V0$G$rXXN0k@D{l-$FffS)9iIM4|o0YS*)bR{-E+D#KTCOW1Wy2^4Q zPD(>D1_(oIKuSx*< zWD&!tZi3L9xM=1ct#MEG!gsdW^K@aGHZ*o(1Tn+befdG(Ud}ptT`EUL(0N zLr*8EI;$vQcR;YrhNVpCDhJ#L;pTNN>ynjncciEFZvfB99?={N+Beonm57(Y%kPpk zk3@@^8#IaZ?zEi}Pt%E%jPO+4gpL=GJ&+4QfbNW@=|?6p;{dT^LMj=GOHwTQ_x(so z5L!biT8j1^30&GQ%`)zjfG+|JWz-fyI(=P@2|VZ+mM4IMc*6{(EEQRdumZBBHUwl0 zC10~B{%>@JvMdsZ)@o#-LU1pc=~4}Rn}-D!adGDMt-=H z)P`+7;UqBwI1G&!Sf8MQQQ8?VD&VodR@hK<5`hRu$3Lwog(6w&$ny+l3(RZ!;AK|j zpTbf(a;@V2Z>J1$*yaq-mv*8-iL}N&%KY0zRhr;}pV4U%B^&FHU1c{urio8d>Fv_i zQJ}Qr?FJ&`o?nDbcVSZeVxAO6oHXRncKFld;@P?92D51Bw5Wr*@N~F*539>V`7*Dh z?=Y}h^|AK>djjJ0jT}M{!V3Yl3CDs|k+}HZW{0%6oH$S5o92z3pv6Hu1kr?DCG4dqiDbz zpF?~S1Sr3_J@nOgz^^5#O+*m}*vu@tX@~soLulShU#Y?|3^SkNE}WJo$d|7klc_re z0*|7sysG)@_dGsi1w8;0;_Li{l>g}||57&Z^zU`4l4F`-ft+vWCEDLv)HY{f7#<$V zj}EPBnL+TN#yX+%oyywZXcSKSSImD@YFKK028Ixmlp46ACDH-V%Fa(wPRJxg+y!U!teErUndc;HE8Kiye<2_q=rY4NfMiZ zx)<1hJRl^g_kSW-Z}&y?C4m)ql=-?DhmfHrM20B)?1~2MDS7m|R49025xT_yvc_K4*S~TR<(^4TT1j{eKKi<-P zFaiP*=LKH>=TlHh0*qC9fN)cNE~#SXx&LpXn}+yE!?NNsW-`?l?3e#`KDLDLVI)30 zPj#S?+c^4y>52S58+IctLeOXSXZ$4{XD8u69V&bsHoYpRr^3mHsLKbccfIpU2Q(G7 zNY)k1Rf*iNh}Zu)srrr4BP+k^9p;S9Djedo>5O*sCiu}vj2 zKtZ-#zu5iy`Ojk(JFz`(DW4t}p1hk$PKHV&P6uLFq!Tui7ytM5v|udIN@v*9{KqhK z)FoQo(aSRh4Twi2ODU%6nR{6YGc@Bcy!?Wwj{qHh%XG?2D2XEJ8#?AIev7BU`fYlD zEa++iE#V;Kw8S{HF`rn{diw>qN8=O9N-^sJ)^LTN96vob3QWz@>wlufiw}UbGAmj8FT+JcTW~%o$+_Ok4wn8F zdOuN?L%cV;PCA+iBMgpCtLH(=idTUD*~00 zDX1ESDAlFb)&6HH+OmjX(o^4$sinEZmBr1*ieC<^!014ZT#5*#m!S9B$jH|&6@l_G zz>%Juu)+op%23LNzw9U^9N$9fze3xLjGk)lSR%JwX-3OzABHxS4w&;rOGtsS9a`2% z1yg##mV1sP*(vd*V`etpMMRol|IIu1?SoYHpaI@!Pp#s9trjs@D0%&U`Ac7-o_ zWG{YwB)P$tR`>U&Q4Kz=ot)CgHm3$K|L;>r(NW*vrni095tq**8qqQH&aaA%;_xuQ za75l7$aHD@{xc8(DPcHe{tadzb2&T;J!+p%-w}Qt-;yGTFpN6Op{b|@QzW#tqv4bp z3^>#xC&{dQD;pfj47{6<=oCof{rrNoARemrQGebT4A}o8c_WD9{nly z8Y+o0EZR(7FNbusn+P_CqZw%Gc|sIcLhuB%vb1%`5X`~A^&|$#cOTh*xMn!^=1$xo zUrej9SPHCmCUAXh3Q7S#LtRBB2nhw#8MKHO0p|SzEcp+S!Xlkxs=xiBL zlUM>X9@AIxe+$FER0H*m&FbyDoV%}fkavR+_5|pNqW>5tCSO(-fY$vYCMU8tdFelu zp|J4G-7^3yP0gbTRyzd;$qIQqzT<~dEF^WhkyY7UtK^F)jJC#b`(Okp0T2l;(XU)( zBIbRz>$YHf;CMZX1=UwZt{R>SzcM)yxL@!t6bVCD6*}}5aw3`Ku$kq+jt?2at};@t zGE#AyWp|r(aufawWCGgir7zVTYt;`fMt4PXrvoI*u0QmyqQ|$L9#i~)uS4E=BB5aJ z$JDr=#D~1rxR3^1Ki?1%L`jT$!~wvs;bza>xXx5CO_$!>$$QCnQgLZ%=Gd%PeYN;e z8BzKj3A^xL3EQx=vjvL7*|>S>iyhOpWkEbJr*tsqi?wzwbnrD|W5M%A1MXyg@Qorn zpm@ik_dA-&o!Y0iV~L@yf-yoGy7qr0GYB?_2-m91H*=@Je`#kyxU1trN z4ICq$P)AG9h2OAsAhC1+je#9zi3{0sb`7%4Z1BL(Y5VGWnehX08!X~Ym|!3#o)9=b zA^ULMiUZEPN=1$MqZrrZL_#CokDyOHaCWL^8GV)TzrCimpeMCJ-2Umd!(+um)nwV1 zh=IS`{*y#+b1(jiZyrA4c-w3BHDC2=l;L|F%6{;q#99%c%DX%%ft=z}K}+Q_Pa%Y*%I7kgMKSGN1*PWGwWnlf#)M07iWGSnCw6yjaPC0Wc3d2HVF z{-WAB70x8FiR9Yp;qT?Th-?fM28U5u*(-ANoZnYqS>m!wO!fNlRO0t?&2mZ)4q{bC zcTSS@{gxfVrX67HU!^t_HD?#HVJx{NZ`7BmI+^meVD-1|+hfx=YGJyT&wTmjFK8z0 zP!^qRXpdnw-&{QQEFVnmL^ad8bKIJ42LB-aR+$O~lAFF)aek(e&VXAj*{m8l3}|?I zFpsx|BxWOI+DYuwMC}G4iXwC_7X2x-z24X)RcreBn~a(ZodM1OSK@pW~f_QifT4P~LhGy}dRtrh>TS3j|j7(P%3l`6~ zaloi5*HBZji-1$nIHA*12)qVH_Ycwj+t5ph2M;g^uzSl%&4`|e2gYX+iHuSXoVl+x zRI0me+BP2`)7LJTcP|U+jV&ls4q#S2)-4$8EK=}iKi_3I)gvkfoLcP89DouC65_7^ zDPwg!%Q{yxdQuqVDOl?f@vp9_tx`>^e)LgRf%|2yoIzN56DBrf+*-S=@C5gykh(o1 z2}U@$^-`bP&nfE>HxNn2Qnxa|rB9c896wqrf7oK3`9mow0VE=jG1uM1Iw8o0G-Dwo zZN`LF1bH%w%EZOAID$Tv^m7e+lH~0uy{ruw!N#1oEs?x;e>9q~e3{4i8|3cqXgZwH zMa0jiBNW}v&5nGMz=N;D!SAkNmnqezqI60+g%owK9gUK7NN^ewNGuxmJms=C#|NkX z;8Cu#67XDx?~32qBh?=lmUtT+e6PAL+#^-<+Ehh=5;DMluAxC+^vViQBsGveK%OOQ z-plbr@+kl{;2+RfyrlK@W+ru$)_NnOWJpLV5ifj=m?GST?-AY1%2qBND#oRXoXMGv zj)ttRw9X~Uh2T4#hE_Dp?aFlzl-JBn(H9bgj44A)P*y1czQ)-0(4q&9I^x%l|E!3f z%_$|~h7&%Up>Zc9?WE_H=CSfQj-4>pm_+9frmX*XgE@%UE8E(|=DTcaH}0|E^mC4X zuX~onS2$hKZ6SMe`;RZ+bcWI(LtjLH?TWgTCI{6f2G&E)X+EAd2 zSdIhr1Qc8n`%9+K7FwnsxD$ru^S``XY@jU};FSyd2Iod&Kvx3&QyCt@_*3O_z=Pzm z!ejoOrMpef)k{u;5E7`c&P8Mdi4$OIw$ZU0zpa9ye9kle5b?$yLDt_AX@hlTM}O27 zj)ByDmGrRm$;S;-Q?N}j5gP$mCB%=VZV?i{nFYFuw?PONI^MhqZP&oDB`cq| zd9>8X<2!nHooxz2lg|fRBY*FU{*Yv-(09M*(o6$1uwY$)>5hS9YCmp)$|KLub}eOM zx!LP|CxeEyq70YL)sC>SUjaU{3JUZrENCcUYmex{YD#b3SXAqq3uI{M=!Dqwvyc`G3g-u-Sld@0309$GI%{7gm^I{l|vVI6o+!0k^~T8TDqtNcMHCiJ=j z^T3>!au{<0pHl$xoDAA#w|L$kpN8L%|M0shrcq1vM=%a!@%8VbwlGxO-kZ~nu}U+E zTIU54adC0!Nj3?IN3KUR85zX0^K93K_+F^q zX)YA}^0&>eoMFm7$a0Z;&gJ@;?%1OF46c0gLF}qJzP{ROXFSwAwDEg5b%Rsl2>wlgx%NA8Cl+lb^nM$bw#Ca z&q&tCpm9-_&7DknZAi1dV$Q3LVY_T%j_{2i*nl`~8^Dr^+rozz%y@j>^iHcih2IY) zgI%~1af+Xr=mZ2v9O?|eJQ(QdMSlPOUAMle6fho5=wjmy>NKibB`##+?Ok^L$c{+N;yu96{O zak)R$S?>pv$$^O&n<`cf=`gh>OE&z1=U1N=(#?yFrAuOSF(bPf-d_ zOCw`9tVIJ2tFPs_E!JhJ8GU9ujBPvbW>eL`gc-a#-!9*Q%aS}|x(P`&COp$%&DVYP zS?-V_R_A*C=q0{!+k?_6Lk@~LL**(Dy$yY>QU3E|l9k^$oNNcvMy@@}zXCocCx7@z zuh7}mCG#=JftxIMqS}l;e`1f@90rsdHxU@sJ9Qj3tZ-_#sD)fUAAUTc%jD2Uq)Rt& zBuxYhfpwCQbDY)RikjA>nrzA{+7&9&3^C|#br3YHnyi8WiOSRC}- zPPa|U%#52c4ZuEJXowWSBkI1MFq4%{~CL7U9B0nq@2mx8z1L;Y%LRP3T4$QyCdLX!@5M_XYk5zFfu!clco+KhuK>ob|r z-5Zli(q;Fly>6F8p)!rEq@I1;X(m{T!z&EfpVrW8qZ0v7(*e_t39(K>v*0V5BAylh z1CF=W))u{Sq!uKr9<_!X5x6u7GLblI@q){E`44wyE!b19`hPa+I%Gi}NFO4N z?p=eCR0}@|w*VHOw1l$0b9(IYe_?{@pukXJBdwu6&jJ$P6!jIp_0BODeZ@->hJxK$ zZt%kl`(c2sl9rE;P^(yV>kQl2r9_)Gm6Ep3Fg{NvavhA6`t?rfn?Y`yOQ`B!*%Qkn zvpeKHa~_BqZVHZ(_98}DYG@{Uakx+!-CbcBHT3`#?(h^5d}p0?oImo zIT^(rQN#N}0xqZY+z;z!>RFaM!!bX8{Tj32+HRt&7?3Q0>Gp~u9)(^ZK~__ffZBhT zPVsJabD%gW;p&%*bY1*cD|L;l)MO0*aAlmyG4yvi&7IEwO zu!st4z-*O;ep}$H{Ct+ve=8cMrZ}Jb8SJT8Sy@lEGhEjrX}%5q8+E@hu@iBMIGF*l zFpHUqjm92{Dx9cn^lAj=o&_%bmS zfAJs18dnks75d!?(r=`WR0Kl6s>-hu5$#amCNaz?!sn!?wPQ>#J}WyrVQVne>U^7x zS?8IkFZUNtlNi%q{$mA2(f3PIQWXrZUXf#xuuH1M^N;kU;n$1>Z&G!dRerrc7rLJo zTU@t2M&Wm8<`UxRNsGeP)Ro+1kZe@}ToJj6VZzk!7cOW9z0|nbl!pKIlQY%C5n|SZW^LOyrvl>=~E7hLzx0 z(BV`*oh{&`$0S%CT!Kiq62zJ8s{oS-d~rAkB;RmV}0n+qh0 z-?C_GnY4?F`JXU&QiSBp&J3-=;4>~^rJvLyPTws6uEIP?q%)L+)iN=mK0l(3E$SRd zUlh`3I3oC}I*ARlxvd1O5SZS-yK=Gnc!LN_bU$jXFs#Qjzzi!*CzKiiUQ6BpmrC|uR6B`7ni*(vQik}lINr-XS~1|(D-*Onp%_` ze%LKu&vv|e{d(cdw9Inx-H6zQeo_(?3ed&(cSjReyKl%Np`y0Tjt0lZ{jj77`b+L4 zyOVLeb1raBp{}WVjjWLEVQry!(8W(u=2Al-^79oFG!>%XQRaTA@F250%ys{u_s!+r zr)=Yycpw>AX65&V%G&W$Se(;?dfAAi35G2;y)!X90wFf(>0#FoZ7#izt`Qv)$#4E{ z(ToLkd}QaOAv0P?s8S+oejV|>FGdRB- z?lLlea@smL_ls$ryi6yca{R951rxOIIc$Se1<(Rvu1J@fFBl7RItI3G7Z0fEeZ~pp7MKqsM%GD07{iV*P1kV&n^>2v z3fJcnV36r`T9F%Xt`e{*^KNg6e(XtyTDQ!|FLnihH^p2$NwNbJ&#Wt<=XVK2HSZ2s ztFOaL7uSmm3p*ATGO`H>H1+k-BD?5fo54C~y6_cZMUWFCh>A*I$;sUw-#irbHFgir zBip_7bgd$Jl&~5#Vk(;&RtYO6X<$*49KYrMwUpPkVmbEf=qTvWqAKonrtSr0B{}q? zXt&uhVN{g3Alh6WP6o2VvMH<%OSnYAUsPFCvFCet*kGc&4BvWZ?p%WZlM6xQ zLSB6**w`|sXab=rHe|yI8XVSNUb$E!U}*{-kZC7S&5)GjSAa_QCzQ_}%Ihmp{pBkk zYdP7I`>>!C@rog7#aS)e@2}S!|1!Ld%!cpF5#=oQbF{U$OMLqL*?toPx;Sn5t+0^i z)ytnRZe+b-FL7J16(}6@sQpuVX0Hc00&O7P2!l&#&5G13LzZ|(ULR2)(^pi1GG zz&_W0V$MXV!?9aQ1gKPdx9@iI7Z`T@S5#fLTV^BvDCR`Cr?_flbmcd;$EJNc_mI`L zyQ2bpHZ=cVrn;Ahlcj|9PVRr)z3Y(ogsvZ2q_4shB+2FzGY1*36u%<7m4fw8SDuS) zodXTO(S=#Y(Cq_L4g5oY`Qy^t>0@3a&m05i`6dQU-x%)p=OcE4HY;%s($h6#7 zzXvB0*6$N(Jh*Jg%F!pQg!3y``HnHO4}T+fWyKvmdq+^6 zyqg7$8R1BjL%K`1-!3gEbWzNOD9+)0g&<&=dyP#{aju*qCj{>&TpToLbfW|7B>P$n ze#G3d->y@sphyK=7NchM;eA=ml>tx9fbavv_+`W;*R{`fN6HjSlnij*uF`RlXZz&k zSg;+@eX^H!pWGg{tBl+?so)c5JUl$UyLpjzxfl_~YPuI!SG}N5Rfi=_D=5*Gmk1_fCg`QYN>2Hx%!?~WH@UjI}LxeRqX)GM9beHE$pYuGF|AgtTW z<};wGa{?ws^dBz)V-I*FGZtw@m(pikS`duOq|s!33TW@&zvq`mmUD@PaP^sUuWlqt z$lqNZHhs~`_9pT}?G~|Rq^)NTd@jPBD6;Mi+xzx3vFR+;ev6S6AdJ}f#jDVN*iWkQ zP)5OzO1XIzYZ<$FTg+1Y8QJ+R7Q$Z;-vVrput zUt@!P?Sb>_B@Ir796RDn5k10u&4?~M$8~p^_B54-Bj{5&kk-}AE9MeF!kVIwJF|$G z(NyWQTy2G#Ur=DrKd{STcyx1jx6wxvvUyNz`o`h^a{;obaK5=dXgAjPshEdU{4QQW z*wXQIO}c4`grp5NKd1PG8Y*&0`2F4fn{&4#kv4ms_J=E@RQ93gWNmT-_k1u$aIcLc zNSl8RxEAxIme+XD{wBdhkFJ8ACSh9vb^&%HEh7@UG_m z^4na%G-fJe6<=f>Ah@y-Y=oeAztjhG1G^o~1azli;rq!oj%M2wkDt}VKRzgVAdIs9 zWohiA4#09=sNW)ayiTMJpP*Bn7X<-%?i*yjL?d*=QtuU5jS2GIrqa75F)@&6Lf(uQEgWu2VbKJcX*fjB9S}s-vbVa`uc$k z1)P9K`nyFIWm}{EP*_<(d~ESP}%8lO4MbnAH_nhUEpEg#frV#R$dG||HHpd6rt&jXsmj? z{Hxl$1Ht8VSPn0jgEPzs%K6ONS(J_HsF%5M$olwgei`_s zLqL7Z0CCnPZhbsHm=oxA;prfJ9{c8R;hWUw;^NuzUo~C9TSc{qFc|Bqo#uEss}Evo zG_t+5)9U4!f36_-Z4yOGSv(Dq1pj=Sp4AI!jJv z`4wmN%nzgD-*T4SIo(}@Z^jM-;Qx01A$bdHc-SOzAO7V(GTr8h9R#spp0PcrV}Tw( z+1$kK?TSXHXXo6@z#^d>-*xo)vmJRpfc5=wwYiGAI-aTT8Zu|KTF5_yOz#Y`!_B0G zz!e_QD3tjf`V>@n0Odo8#M1gNn(2NR*js^T4=bQk@pmqw6A3Fps{C+uPGd!UW z?0p>|9Q)z5%ko^VuE@;G9zeAJ=i;bKSRPMQH4S{xC-6$B{r+r_AGUa!tqGPt&|<&y zZTIMa+d`-<0Odq@{BDrgq~RWEuYm)bhUdEAw)=|j2DWcN zzy#VmtHrHbM}7)U`%ut!!6p%hETu?XbC`XrUo6;^i;n-%;jy$@`Y6HIV@3{$krh8W zcL~jSzj+~aMwr^DRivDUFW=ZB3;??;?GmXYCUY%q`1wI#^h)n76GZgF2BpkTb}`*T zP)z)w)^^wKZ|G%h0+F!F+{{|7T}XnTGY@S9gMr26^dYrT_=q3JH1OlYdvRoikf)4( z+fWGQE~#^>v{rpDG?UQ15;S^Ho`?$;%csO<`tWt1w6=;!us>9%db{@+6SrZ!o3xCMOFqOo$O(4BN)n{2Bccx%6GK)-PWlkEDn{;FqvsR8BkgPtYmy9b z7iM@Rd}+kEAGkp@|5`Q!5?^6J)-~CRjkyh7;_jMch25K+J{BxMa_0iV1f@?s3nnK+L0XO#UACsGjy> z-m%h}x@Pr6%}xK$rv?tuHUFa1;7{g$h+yX|nNR#?7T7_4?>8iJ)EG86 z$xIir$VfNJ2;wtOIcwXUjZaN+S-{MSx#)EHk-}}ON#Us@^oIus1_BLq2lyJ}H>o~{ zyk$F2^I7sDjTZ{Vg2~AzQvVUPxytq$&!EJ0-R?`(YqCqF|8H4rV8ZxUhx)vc*n^`n6OI4ncWsoIw+cQLpk8alevLcKG% zqVT_r%|ncRn5PF(`m6sxmOI&6?qR{}b8C&hEnxsy<1V>)368~N465{D9B}+>Qlw;* zpoFo-9p)*BkW*pFg0zg00f2kyV4a-kg}v<@2X+b9unomK5D4VQh-TVI5P<;V>5xBD z)}QJX4>|<0{zW<(9^1dZSG+eM2e6^OHd0SatUUv6GZMUUJEP9OIUQaNBaPioU(iWX6eZKD6 z^L#zeWJbRriW=Sn3d3_fqzSUy&s(CFf%C~bb7>I(8E6w}CN18D_=^0PJ|>6&fRB$q zWM#-;iVC|`h9=tt7d~xl#~Mhhm_I$iO{qNxi6d#f2NT7(jE{7NA4FV`TPKhDKQr^i z8)OBj8p_z7SW>t?sQv%d8s8trufMQI{W(k{?l{d(ks>?j!Yybj*eU!%9qbkKFLa-s zZ@(vm7NDEGe3G9Z1@IEENf$w|3;>d@eiUzBP#2x*hm0^RqWZwGV8ZsgYt_!58eSy1 zOViebcefjiT(O$nUj^t15zPwd#Y&8(J+7qgVULSTjjMVJQw=p>$;ru$Who>n=c)c0G*FWh-Q0Kl~?e-XJsA{=iec=8p(RzqI3Um)OfW}He zQDnT=_tY#$JZRBhgmg?P^2b!O*Ilu4dMAH&=}-OfD_@ib3yRA8nC^DQ^&A7d2osES z^dzNwE^?qKy5(1BAyw_AwV(3F5?JYZUgLB0F8$d6QCBb{a113~SsW7n<~Ox?0Y;!6 zGesszrPFrMlZWm1g2EUMN58i67oFZ-AFKJ$N}=S2dmasW9|sa|Ah-Pqzubw8b0T>B z67|&dpIi^=2e`%R6b{xn?2C16GR-Nt1O&buN#}2cuJt+s(B27%f#w(g*YhZ)+9z0+ zsT=0U_~77}_DmHh+SA|*OCQ&gJk2+EFsldX$@zJK$VXbkTj|^>UNO?#yjIDxIB2l* z+%LX|#+FlcT5xD|`!f|N%YQ?yh?V#0p;_LPe@O^yd_mmVV?mY^X)sm(np#FCl2^?B znYY%jZ-=MxZv$A;=9Jb~C{9y9qvI()iO6Q}$2V1o6WmYKt_F;PtTb~yGAsVc}NoyzmGaRt49Sw7fBej4@q7jjh_zuqn?sT2x~ z>h#K{g|7s>YmQ%4E$?Z&K1a;eCZzp&!zTy`bJ^<+%@AAj#P4iv$@x47RhI(ZyNZ}{ znIu%^4@&vK*{423)br8tOzzVuf$2VL0n#r9od^gBi|`H=kSc{dc*$RfOio~?R&SK$ zxc}GlGs_UtZ>jq^N+8SB5K%p8m|a&|8eu62Bp%CG4WsRPzP_0**OdBUeO+Ew&V-oD zKuAk^YU=`MQ|#f0y9;M2(_oY*@-l){9=@@$u_rGev6qWp%ahz97HC!^vP9Tqfd9pY zelP&Cyz2!uTD%W;E9id%+|NZb4{_)sr`YWSKz2r24=Xz(VlEOPt>CGx129QppD1Si zAdg3`*#8Qo?3SZpy$y)TURtEJ55NlU7_uxZGTLMM*o2-`aKrZ!@NdUcr0l$nrxg-P zI}!-R0_Z`IA-%UIy-)?U{QSz6rN96vv+}^3FZ3N223YjjY{!r&Df*_Zx!djF8L%cftm~5i3t? z*@4Vs>9?qoF^Y}7NGv)}yDpw2`BH5-O{RsDb@ zg#x8T`VsEQjQ#WPs@nFm4O>%U8aXf>d-8P&uh$k|=$oiZGA$8` zqYTHtIr=y=-`9^lypSc!cWowT;}xY!$28t3FxJD<%yJ*P*+WlxL8&N*k}1Qm+K7lt zOx#z1g)+1y3OqQipABcPA6mJta9%8))_n;s5D!{0>^59M4o4D=a8-4EWDQ0h7UDChF|DzpzS#V`;OnTAfq*Zmdwn| z)O@g{_<*=7{n<7iN33z`X~s+Y51Q(lTd`W?8ZrEkBNp)d(83B$4L)FMYU-Qulh^R` zS3Su7zU6PTX+PngY@WiBR7~M&Q`-;gdO<~Gi?H~gJl}bx*Mc)+OZxe}dO_NObc+N` zPF7{nCHtem43EXR&{De}36yvtN9<24Y(~D@o#jMeXJvi9^>Cd}3l^Cv0f9BQW&x zuPI&yCGAm%RR~E4V>%FWe9OFK@T4-pP3b0Ai)WcMGbKfCK#u!;eKG>rn~%eWMt(cw z(M#cuwZ5t995E%oL?!_kDeM*lsW zBCkS6tH&&X3EG`g0I33<5@nNcEZd+wKmWPE8{u1k%>8Ur(Wbh!YhG!dWLg3L?l#H_ z_{s+N;Ds>2Tft*C0U+g%C%(`BfB+1TCJQ4T__=Bs3FGyBy#mGWD;vmAU=Df>AP8v= zZpy?Q7^)k0$vVe~x1p#kFOQQ)8@m;h7hFO4EnG@6nBMlq+*WjAZ!3>vU3iZlN14py zn+}gGKe!YpFHnSG-!SZlB+nh6nw6zO{~?zgs;g;eIKZDhnFHwW04I3e03ccAnw75% zM7LvNOUl?+e2eF~3FnUYxxKKbpaZ?X_7f&4XBF{K?rX&bs|p)OJ1qa|ae%c439JVG z0Ne{LdRj@G_Expo;>sI`OD(DLXyC&GZhGev%rCWK*w)C(8+*0uTaYg;=(MM<%@CnZ zR(-E&1AEGXDIS&YzpVOjz*XqdK2H1lzM0Q%&c{^V0D)y{Bw9T}$@LXcM7K;G?v|;c zz*yyX=zF|S`_}n+LkdRO*lNQcE=$2JOT+xA&}G5bXU~ACS1*Pvk^e;p;Uz7C#|b&d zhLINuwu0hDSYYOkS9tM0dfL2ZZn62Hd;~CeJ~4U=cxa{fe03{GJ(*GG1ohc&jk5Y| z5DHSd6e%|;r_$|P3ltK^S?IuI8D6DYN(GYOz$7*d!6S4|>hU640!7fU2yh4WII|3< z)=HVuIib#e;V`mG#sl-DG|n?27$|5(sJ<%%3v+B>+c3rfRH%_HkVZYhc&Q3xHAqbO z23#K%PAo=|Y#dqHP86vqZ}=gBIhT66NfqI~_Gfc;emX$#I86x@eW~Y_nV0d@cEAoK zZ)YSTA{u@DR8}%WzW?|kXJSG%kp{+-l_5t=zVzPnEA7Ff<`_$Gxj8aGWY7S5#=qB| z9(hSNz`qQ3v+cg&y#>Ca9}ogvgy0QH1!M=N^%8QRCmDl+lMn%`+Xa1;IwR#z0<6$e zRjAj&^w|F`HsAD)dBT^@1XXFdXnZqBc_aEOqU2jpRU^v)H`P?R7MP)@n>u|C=eMrP znxePCW7&XY4&{x1ay}nx#c(oG_5^nPCR*Qy#G5#S+xtfb6ww?VkcBWiavG}9Z1+p+ zyV^caPVBLCU#L$_PUcSB!^dMfyezi}5VkW$#g#L5)B`0F5)4+I;}0R-29f9)!=8ShV5);k~&?8-a!{2Yn@)KL2T!Kdi-KBz9HdAs#VDj|sG$grVh!-Mau zRZ4eP8-sKfufb>%PnO@`=!gRa&GOr~Z`|?ZcnfdNyos}J;_XFoaZ}bS#2i8C98-WY zRp#?fV~u5SPMhvRMKP=Iix{^B@?SL`kifuZ|I?ZxTi&n>#R$|2FO6*cZe#p zv`q4>c_N4<4%d(pMz3FhLBfEs-aD;fL!W`CDn8skm!cw5KVx zxYxN?R!ap8RJGv4!8RN6Rzs*4@G(e%C$Zl@kuOhl(H&b-SC`~_*&KB$WtNc6nRhzt z9Mek*L22B&`Cq-gQ%^yT48>ezaP|2n;t9{s6`aPve;yRCy3N{ogtJ_l^ppE`s$n?4 z7+v+OnI^V0$mZMsVFGWy2YxgnD0vO4kt+cr^oQ5?wBO`YC8D~cXVhOG!ih9goM)02 z7Ig8{>oNTN{Ea3V2L}h$-iL-oJV6D*GCNyrehV0hF4h!W%_`?4z!&X*>v!M8Z?@dj zdY&w~8cP!S00E@seG(iOauYpIE7SdvKPF?0Uo-dD+ZhhFB+~lg$b(}y4?SkfOMaXC zYhxhXe}z9he!4M}Rs^G#nJ8#m$JOk);A5tK%6@vb)fi&7#WR&e5E!cmM%Ua{(`~aY zs0B-`X!;j)%|89%H*H98*sWE016U~0w!ulTgsoP8$5ynq%{vVq0P3eae$Yvhe z(6o_US87~9fNk{6(ZGr4#qcS@F8a2RqxZN&iqkaDy;O}-NK*ke=Ew1falH49Gn8>*Kn#vH3J&r%kY&kJfPqk#mzJWZ_u zlLP4rkPI=u#jg<-lsk*?N0IBKr_J;;rd|<8|EFnYcC34-qM{;aW5aab7_4E!;F{4? zgoQ)7@Im#x-aq(?_GxMXI7w{lIfIlm zi5JBmMBR&#q4xIn#%+%Z7fl*bSJuZiEk90+EJ7Y0+Ly~+|GRJ{-3*QZnU*H%DpJiC z@l)iZF0)wM?#GQAIA4)zSKWjb_wOVUT_5R8P^6FPeBk*t%xg_V|E}p8GOygli1>WYN@TQJzC-+vuOR;-ecL3FBjX`jdK(jkLS$( z=GE^u=lAnA53R;ej_-j50Ik1&R)rQAtyRVFs4QFW7Z|U%oei+@e_zA{w=r@H%aK@y z7mH)0$g{~(PBa9A3D1PDHFv7y>qCGCA6OO*@Btb6r26T8(oqqpUc1aPKXflGu);3F3&XK#jUTR)?>Z{?bF?U=R!_;L$BKZ%?^V%9s~e`3rNm5hwxZ^Hu08X8 zh4iU%V4DGiAlxQLMk!t>UkrKLKBM-SAlAwEiMnWL;J4lGvr(A1go=E7TxxKoxjJ4M zVf2=5*8n%OSM@}gO7Cs8iqZS5_W1e9>hQ&m{JZafq>JUr zLclI20H{@QHVTUv#8Iy{lC18I73ep(P{s2iTh$p7JD=fD34i#LA^0wODdH*_g)?33%VE+=Ag3U`c7mj*U(lvR*R z+O5dZ{g`eg^0;yg&#Oay%wNx@NYwY$mlv>FB$oH;bJh@Zu|8ED9>mV#_9?1%`4 zT2FwLPFU{v5LYOxWJt815e}XhBs_$E_<%(5p11J(cO{LxN3b{zPc>b)4eTP6&ppJe zUWSi22cvq0rz=~DKdRHtlNbJRnw<}Szhvnlu=qIAb-v44Ob%r`MLbZ_KlrYm?q^t% zU@v%2QgKSkWf}*9!eeO3bR@BI8WWGDrKP@`9~BzEJaHMN>*ll#;_^2{()tdkrocv0 zohMj}DGx_54tlHPwPa$!%*FudzcT5w+bv74INeA`YTrah@*0~z(jFeX@zUve-}WBC zTjfypAD=g-BTZb=J9})}EnIFwDHrw8*(X<;m=nF*U;h)X%2v=cu|3P6g3dH~o^apH zEIALo%a&p9<&0S(7?&xcc{3pDF(1h#f<x=)d#aIm0gf#pDAqKw zaNX@I$tpqi%27MdtXq~DUXVJ@)kd^!7Ig3f<;=0w!W|P8qIwRkKB-qY0VEm7&nzb7^yj-s}cHk-$dGhNIY|L*S~B2|mkf{&UZK?V+iq#RG!M+Pb>qEW|()=O};1pT^_1JL6BD z-@A52!e1@ld1T^RLEY|tjWI32qk5SM0O>TLiTJk zN!H3%_MJlZ-7sd}dpytky#N32a!tQ$<~#Rt?sGo(Irn`&XWR-6;wHV*|IDE?GdaFz z$~`@Ph=3@TFVU|(`axgG3n<+r#nISw18Qz%YL_fkYM^{ydVsTXh9|9Ow2^1;?PtwE zn~qOAvurGjDV0b2Yfpduy20_0k-y^`65Lj>U%Ugatg8B){k1?Dm&?=ACeM1Hn5DjGZEGfo|HDBa_ z3tSyhjfQ}@)#mt+O-jNCr=H} z<7PHC&sNGBX*m)e>B_i*d~7F2DBDC-9lO9JY5lk1TvcuzLVDpf0`gVn0=duOBNtZd zyc5~)lj3kV{31H9*+HB9?nP?l<>9Ab@yc?6qs$9?vHi{sP}pPFvb_R503FQF^x1C?Pz8X(@IoH9tfM1R zZJxiC7$@_m!F-{Nwl}Yp!q7T^ljo>%Nhp%O!6ODy~el zwSZyU#~_{m^M~&lD?YLJXMVKqKl%KgxrB3ifidjYyMD7$0{+waw?ym8Bu!FU@Pq_m z+EuhRyT|2j3jWGB?$spcEPJfNYfO^jcRFlt{T-|ED7aqIhei@g)idIX?p}IjW^XU; z&#mA&g3@`)`nlR@9+TDYz8YR|{AZzCSmq`x@JG-D=v}7oza-{7QjiG20CrFzSbbiA zS@GnVgek2~EnO)F`ay0`k06cB1Pm42R62s=8g{vRzgW=5j6aH-nrudv3EkZWs=Iw! zATKV#u!qK!J*v!{C#th!iY0I2$*S7Q=QbWhBnkBytyJVx8WDx)yFknn2k%P?m;qy_ zAG*uFs}5@oyyws{Rq^VdSx(OC^=pSqZ<6Sln4%94gE>Y&V(xsRP&q;SOsfNfqQYXa zQWq2egVH~%=ElgV0#xzq#e8QNo$nKFwqdf17eD>Lt632J)z@z~o3he3&xY?tlgFw` zF8LAp@PIb{xoLu&Cm2ccjoedwG#0OocsBQjDoYC*T<{Hv8+f)@np|% z;tp8AH{Z}b4~V9~KL-RQ3yHyH5(69_{~$@boq*YIj#;0WsmDv@Q9`JR37c?mk1WHH z0Jt|k0}6((8A^Z0gANM*`MdidLqi*SdT7_=+10!wZgmcxNEOd4Np~90rNqN~)!9+C z*VM(zHhu0>^AJ6EZI9WH)VIO4XMG{%O3<{*=F@e7aM5A{j8wQJWv`h#@e zTSGREHRJs1YG$x0$2BZ0F3y(}=e7d;6*`Ylb%YbsIdNG?tq|BgI*_yO5D~#cmUAoi zYsn|Yw5i&gpNi~)C?f4XBK`q_FMY%r$ZdiZkWF)Jc#dOj6}lsM_q|m{K7qZ4uApNU=pGoycMLp zs<``ivLXw+I&yfJCIcszEyBq?y3zXA%ut=UcXoaQr?OHg6DZU##PTH@--iyfSrujA z15>wr0kuN-^syaDyr+yMz%Xp<=rCvfBEh%UjePty3Xp#0Us`+L@1l%E>VUnwV15Lv zS-y|f{#%a3W=2Yod+ZkxS8zb@+q8iDD#S z>6-VJLS)~W7Ih2x?(5;Sz-AZjfm_wfBrOXp;WL7HUnFF2v*y@=m`ctB$WdGG3SQ-J(tck9wrBhNi_8>M-cKHOV4*qr58PTipF*E z?XH8J4>50WDzHiD9mECedu(y&*o%~2{Zxo7Dv+c*PVZ%SE!EP}5==Nbxac_|Q-_mv z0BB%mw_dpopwlE?f^|b{qARFy`9Np?#FmF-T)o8`n0Vcwtlzn zg$xNIwiUoZfO8SL6hcO~qC`FE6Jj8rr zZBZWGa{<3YMj)TUT^ZAEV6??-$IEb@`}BMGnrg zYMy{lV1oCvmCEEK(3Gt z*sq1$`CIK0N#q6gramH{Zr>$o`1aS+65Rfs7c!0+ph2C*&_cso;(YHOAa)z(ovpm@ z_xy*uO5c)uuZDvtO_2SR064bYe=lDF8u=9cO@)hg;qTu&;Ku%NwW`<5%IbW0*fwZ|XCf*aq7c?!BJ&vOtzVz2eEhq0|&C0Jaw|hFD3tkM}b=zH^Q2)li1smx`om=?i8A-7|0phsTsb@(@(Pg?Xb&1*(bYfGQ7S z<5V|uvf>3dCPa^6#rPN7L?lGnj#cP;7|WHMqwb)l#lo4+#)HOcqw_?Qzj6lZgVjU%G`*Tf zQo&SsuX*RNPh9d;Qmcn&*#bY@T5x!llynt?m2E|pZS!OkSU=*3h2xrGB}4K46MJVoashAR*wn_RSgiA4xlwN$Ct!zDgPT!gA_#z@9UrEnte&4)VR4pdOK~ z)AaMc&~AmVIa8ugf3)b=%Oi0qm&4qd80DGUhdE<6szDb1B=jIJRz(VD+R41n`Wp_`Jeud(>Z|Cs&siJ)4Lf1HJu9e=K zbb3u)xSX&)bY@dZ?EZ2nD8RscpMS;h!Sg1({ksO=Ox>E+E$VpfgHhA3!z20(YoDw+ ze3yPS_5Q&Be9y4655;H!8k`AP4s@ z3EpG_D~ah0T*GvJ-Lr(cIUl*%PL+cPYGW2~qFI6LD4t1J_MC0p?b42!Z}t-1aLlr{ z)fhweZLBO;phSWnS>MUax8O7i4*2O8y(+DZ6_2JgiHYX+!$U+z>>;&APX^?`bYRlw zcJVN8T4RGd|J~CSe`T}WQ1;@Ma9Y~ZSlveIW%->vASY(=gi4b;)z(Ie+hrp@c**~0 zWPX4u<%}~Zei7Wo!5$u+7L=A_a-)!txUfffSW=mx+dT8GMj3d7%)oaO|Cc~ulsD(5 zMF%7$PvgqlC(h^AJ8KU9rzI4PJxTpH7BZU9Im1z(;v*GMp9W;tc8Hm(7`(BU2_N^@ zF5aS|rynFWD`6hh1+hIX&O_?M-tS5;E%X02!5s=+?XQPd3RHLA|{q%S>AFAE0!7eVmZS06a_9pI5#T3o}00I4R_ByoIh&(;ov4F ztpVcX`icm-$#dC2-zdG#JhQ-25B{k?a>!G9@Ymr_cbb#}FrJuIJ8h?1)8Y^(Y+@z8 zH9pbj@fXC6i$LYTQGsf=@gUwb3KcqNtLnM)+YuZ-{Y$=ALw-M^!FPj*gQ_{q5(p$;Jt z{>w~3*EC2(n7T}vN#k^#nXI%qmRy#-L!<0G@(`Irx>lhjp(~5IU!U|BO_f?~{BAyp zD7TBX`Aj1|Ea`YWV9!z8gxy(ufc=wBx;9OVJ=s9!73YR_zx!5xMhYe{b{tE>w-e4{ z>GG>J-V~8{xvX)z#^*0o;*|0-I*n^$o0X-MmC@_NFoQq59MPF9ZL8IFF17PK_gsDN zT96MyzanC}e55h3#IYwF_{N{t8{Qzq3MuGYKf|C+ni-`xtgM~uU)cz2K`}?n9=))+ zkH)g=$8niIN=t02+5&o!7^U=UN3mVI=lnCP)`doUBJP|ZCx6U#dp)}F0HoM{&s94f zx%e71_z5)V<{d2qyo2}SI9TKJJ9KDI=j}Yt=QBg$N1kn9vP@qYPtN#LS~xj1Nt%7Y zXMgfpQ%*UauF--6^=n1E4ypOoLf3$gs3nsl19!1~cz-}+I(wQeS<-neY zi0fEPof*`w{*)MiM)zz=?=C;V5$A+}Aa7D0h0p@ma1W`su0}&V!ZueCV|cS75B&9LWYkkiY9C~nMff{oi?3-@Z| ziIPFPot{j&URb&>^T&YWki|s>^Ts`|ujy*Qc)bCCtXeG>$Yl|%uZRQp+QC_w7tKEC zhtljty)%Pb!Tv2)BY7tq7hETCNbEw$^HMt{l!_Lu6Mc9J;qvrl%ClmolLOO4Nf<8cCQ7XY)+3HB*|0ok;TJ zjxfd?Ce9stf0HU%RB{0a~T<}}9F5=Tif)KViJF#PBa7t8CNBou3 zvKUO1sFzy&jb8)A|Gl3t2Up{nnO}Y8YJ}kciZhRcLd0;=G32afa%EUzn^ETb? zUOEK@Nl#R11NNYdTwQhhsu*OWLt?3SjIAhf`Pde9kp7_l4pnS%;#c0E{kdXB{6k}% zSIcpkAD<$D=DK{|GlyrJ;mdijVQP*=0vh!pv?n5)Fy9*Y`M9x&8y{}RbgT&a^tm@g zCCfa!ap?;_$o|iX=z9MBjjJ#1EOa!+{*+VDm(f9}3mLnVQ9pknn{p@15m!yn{7&h) zuT81qzOVbJC{*nCb1ELr-W&f=CBV0~Z2_n77v{Lp9|`+`fQoWoluzx75SJC0e{1Z? zZg*VufKAO)8f1MsXp64o#oCZPLvkQif`l0&aVt0xl(nixX1B|xY>6FDhowdHmhmGu z-6pSF?q=2=k$PI~vX7_ZQ>5iwJ&rw)Mxw;YF z8I7DpH?P??zIe24ypWb4lwtkOLN7Zw&;6ZCM_%OD$5fG;z=jgT6Q!P_d^q@!Iw%qi zu7b$Lv$S~^Q+m=rR&-{Cp1}6YY<1UagF3l=#S3tEnhoZ}Zqu$iAM^6MuDtGW^M7|} z%K_7(nW~P5((`+MBz>8>IYEtM&2M59vGr&Upx#^VSt|W&ChPZbU3|%p*24R4M;_93 zjBP(7!K#j?WidA_7;tQJn%v9J*bOigQKBUN(3y>pd!L*MR@2q%}NUcob> zL||v3gKl)R1|+4*S(HoHd!cG7blBUrXI;ULZ_M&);1(Z=QpD~Z;4>o)9CD;fG?4H=$&lr(G=XlsxA13jXnoZmtX&(BiDLpmrk zXv7xJ9it_4awj94RuW|W=9xBqeDyCuV)W$bfi~@Lda2c6{4#9PvF}#(Z;NZ6T_{)n z_Bs+k?SWfCn97x-zMR;J%Z(Y?t8b>SGsEJc0?0Q8hftd-_<%f?&7Y5*baGUeqhPx{Ud z_;?ituH04+-(pY?{X=F6tQDyF1IEMHfBH1rvo@U?q+Vd4yL0>`IIENkK>eN>Zxk!P5r5Gtnj+D`P( zzt;Q;uZX8(!)0(Ik1qVqni3kbbbT7Y3vLk1i)=KnT$vR;HnhE4CZNH<=lMutdTmgc zaQE6L-k*8y(_WW1C){^Ak(43Mf^yt?f?dJSUS_KO^0fQ0KAb1|DsFT;#3(OPiHxiR z&G{#;lGH}ldz^CGlCg`~RQmm&SBP4U%AZ7nBc0lA^6UX+Jz(O6fHFPVP1Y;wK$-#@5ucur-XTC-sNTOM)#%urbx()HfI8N}bORXy2t zw#Nxsn$v?ng?(o90GMsYR^~__2NSKpn7q4$5Uh5S^A^3=hoFg_rn&g?=jrLg^Jsug za0)V1>7VIWwrRezH9x1PVg*IaWW!Z~5WD_a>&n#8+sk-19@7iWU%PYRG1%;0yAw<} z0=?#D9((9%k8_w7gNHn|KxoyyH`yKPd zqGI;R#(9#MFj9>8HbGllf24t_B|Q2#u-4ZRx&8PVe-OsE@+mpPPig+-tRzHsv;uwW z${r^xCGaMkR1H)IG@Gz8KtZa9*4~udV@qJMRiE^Lw*fp@`8~^AaI2gd3_Rmw1F3JOmls!A7S20V~sA zq%1%q2Zkd$MINk!9$k*uBvAg#!d*u;=*yFfRy*NVDcKOcJ7Efh9!&1@v=>blh2Ppb%} zx03$9>IvF#9HohhGlKU8-TIbaV`x=AvBR{u%C2?=s>&1`3^&UakCu7zJ}8~DCTrQ{ z3Q$|L3V$D(y(Ns)<|0{cxRpw=o-_iD&QS3dzte}}Q@1~GE~cm`1`c2=3(Ua+8`M4@ zHK$p>qgx-UTzI|0WPj1aoPHMVNEo6R5P? zo`EmX^H*;l1f63e{zkwuXV>)6FYbrKLm2drL0XB1cEkx_Y6ETVd-60?C11Yk znwq-y;!VA*F=M}HhH`P&k*IylPEt$Bl#j}``rgi@sR34i+HKmIgab$VA zkyW?-UJCcFfI$Wj#6W$4FL!lOOs8&u9-db4l_!DZwcN&6FS>hSBRQO|PCIXRwwLS~ zF&lO3{NsZZOOJ3Dm|!L;XaNlvA67;2%zKa792(yhv`5%TEb_BR)|16*L&Qv7ujAMx z#ZnYb;FMQ%M!Ex{KSm{Mf4y;`YPig$bBrr+f7wo-szMyq-YQ*N)1 zC(ZM8mitcd!fW^egVjd}|9;B{GDG-<%(Neg5`sCfPb6cTbZ(P~$E_EBi$5zPfl)RfNT*3q4JTstD&395Wl4 z*!P3y=_`WL9ajTK3>7D&4p3;@O}ab8TY$>%^P3pw*{-qPMq$C+Bb z&ow0kH|Ne1wt^FntVFwb^DB#_XC0oUJk&KrC{T6s^3kf2;z(usD7VQsu_VDw>Wudv zsEhogTQtMP>fdN?oOq}66HbgA6fZzR$gXLxU2Qx7lc$~20}OrUM8_Al+~%==Ru7+o zmeAi@FGtse2w4YOuczNG?LtT2a=5fv#u{%FSxz>VuY3r_~7o)>9EHaSM_tmRZlz$g`M+mdB$COm(&d9gQ1eOli zsjms#(gvR+IO7gthRN*>%nH@a9`;EG(2+AhM-1_;N(>H6*enj%E25P$IFtf=5Jt{s zQ&hadA-4W7L{UF@2mm!6vWBA;q_I?s+9=~cyl^~;(fyRu_YHyU|MUKWkJ{-xUs6L| z_SHm8t z??3PS-)AsI+Xt|oNhzRE0+_!4jj{v>i#!`{4zxgwgc@uS|LK^s2T8J7NW>{PJ2O!d z(%DQf`IiWcebn_X0-Rxnjxni597IAX=w#4M;&UYBCT|KsUjVbxQGAL#nxI8RZ9J4t zGEICU9!34Xd6F*BZ8|$NoVM;iy9Z{l;A3iVmgDoCx#Q;0XLa&PPCe^UCeIPoc_f|e zTE&rr7q z1(w)_jYUK-`Yk9&CsVxuzuvwUMhm@nHK`OrIsdybiKH%5o?kyJ2! z!YhT`jOn2j<2wba ztS$F>PLAc1(^)>P?I;c{L+PF9Xf@0&O!8vsAnetZVp5~CsOHiPO4SR(dU)>?LgnwZ zH#^*EC)_MBsZ=C+7C`cNltx_e4Tc$6)sE+cQB33YhYK6J*dUiN?8-Sa|IVS_k7XB+ zMJ=Wq){dnjL&{-xGWQ%4n??8--qz?3!xckGDuP(B7?bl?wu2gRIWm+KXYL#rp&bwC zZ1Id9jLEh78X3XWI;l``Q&GoZ(9T;pkQm_w!B!>rBmi6c0v)}+Ic&`e4Rh4Ubl9;k zQ6;BYdyZ`fI69mWg~BZEGi<(_k|3hNR4UNSRFn}Q*hI-(G$zSr0w2$+`Jv!@>iob8 z_Y=V949V`Q@sMkqO);{Cy0iZ{8rT&tZ)qNFGOjVkguGCTrv(~S=AOxb`hG+TAuam) zUQCvveSTA%Dk!9*5wrTS0)& zScgi3jjye(a*x*K{4oO-zRB+0IMu8fF+m#hGgK48A90~=k0(o zjfj#60o(oaZSE#~L>T(ne-WTYm^SLvjKoL=&Oyp#d{`>Z|Mw0z6dmvZAk-KG-zl!d zqm1AhWr+{E>@5{e+qx`(X`;(MPm;(B87sF7BOQO7iUI&no&e?{sFyr%4fOjdQMCC0 z37nK6`IV8ExY!y1IKaAbGk4AX^cj0!PgoRuSmk8;j#fO3!Y(t{RW} zPL5${`FPi2TOm4AD?}BGPIdRBQIaCAm4?qbzbyru&kSlj(xV}7gTbgZib(T48EG(V z0jmah-5%uVKT4=+_XwMKD)~MS%0GK=-P+*8-fjC7V%Ok>VU0W+2%z6`7%Jj;1wowm z%6up#-Fc%lH;8-bxYVcD3Ylf+JUm!>Fu1dU^Qkm6y?>%>^fskhb|@nd5u>Li$C-PW z`}}DWM{rjKrADznhQy&Z(YkAz8mr>SNKf6i{v4;{BMK`%ndj~`#OH{@-WJ(X%~tDU zC>PH=rygF|+Pp2C|>uS0BzLc)d|KXAd54Y z=M=%3K&i6$k&Qt1(k7T`6xR$ZUto4#326(N6X^> ze{}1%-#%i>YgY8}y5K}7uwDf05tD`NVx-$BEe&BaWD{@hQ7QpJSATFwmoC7NkZjPl zc^G|2!hhAL>4vzD$KaKeuKM#mb;p1_b>#aNte1izJ}?d_H2arN0{QOKwBpmZyIar% z>;nWMc!0Y5CqaDlTXgnqShXy#&?{gmvJf*Y1?gjTJnO4I@w-t$K!P}f?{O#)foFje zjU(S^_!ozGYg1`7fOWiYPjrATbglf*p4;W}KF2c^O|`4I@;M^QnlX z{e*FmsT0ZB*2tgZd?m~uf7A#u!(P#VvnHUJ$+*}OYFOajuC!^>@i`Flb7R*B#%^2{ zV7LkQkK&oWrBB4cF!P+n1Z>7dEs3x_MHi$p5R3?qreW9)U*p$V`I|NZc_a4Ow8j-t~~3;rFB|6IE9 z`P`STVK9nU-wcTVv_51)eSKvY_okfE&7F_OL(X~hj6IX@zzVGC)$K}iQDQ?P;H82u zL8Be16SOaskJ9L4Nkut}9t%%rb-h)&01Wj2z^}CAcUxV_wk`(xZgD>P?}4H4XJjoQ zl?S8G=3@py3rZRHi6Xjnz}5$DZgk6s7-u(RH-lm}FfcfW%=@ANcLL;6>WA9hh|{ys+Ti7%kINS(Ok* z-?L_p;HJ9_>`c>Y#O-M$nG90{9+|D%^5uP4U?XZu!lOKd-sL!PT4VgbVge_Z8Zz0g zx8ZQV?Jn_iFS>MW=w7_yfr#2atp==-3b>Cm?^74Amw2~1 zFY^&gIb||#?TT_4CDGs70{)iW+mGkD9+pw+G4+E#P%RC3>o)nLzbH{R|0mNvA&pej zya|cs=W}`R4B!CuT(}IY7yvtDP%n64Bf3g`EO(x}2zV`{cPjO_$wz3YYi>Xp-2dNk z*9q{A85PP!5JMCdcK9k;swvFB{R2_tC(Hkqfe7j;a%lCKq8w-oK7>;N9*IT2$2G#Q+t-y2yM#>@Mtq7!R3heStiPDRnxwJ(_!(gvtu0#be z*;o-+CVV%NG1*wL5wpJic;5p$D+x&GKoJNbSZV7B`Nx@6Rt^6=uL3)jjuGIqJtVc7 zOoW~SIc&Y8K^XyLKzd?>W(p}3gLXSi_3@fuH|K@L1_F1xI`P23F!iSg=$feqeHp8C z!A5CWjijaULSEMTrfA#6emU6kk@KY?U2DT;?mu)DbYfNCxMh{rdleR z8<;AaCfEkyyER!j*rSnu2IcEuz|$(&@$*34`I%vVbu^OAWQI+)$=RJ74VxP|U@3$} zt7i8bNrbYr|9)NMi5uqzVc$fhYdRO!mj=Kp>4$}AS@Ap5Ui92RJW;I*C}gbh8~CHZ zOu852Ucax7?SGx>002lhJZ#qgujnww+q_DCPRhLA8N)w0302^G05eWU0o>cw(W-Om z;lawheyHK~Fwd)C2J0Y%vZv5NjV~a;b)kWQ!2q@*)=qTwlXGhDodb|xAF!&7_-_L* z5E^3428&vcn@mRUirPPznRVbRqVV8qs@_x%1er~j_XzuQIcP994 z#Gfl$cMFfHV!-$%qdd?Wo#H@*pj!45Z2{Y-p}$vtHQ!8yj)B%8`DKBgjX(KzXZZyJ zLtCDDV5x(O_^)VP;FkJ$2>c4gvfV;p`5^J56CxObMFSrh;~|g`W_)m`E@ZNzL!4xl z2^a%?JakzQ$xDBhQMt9=^1QZ%HdI1t7(v_IA#xV%m<44(RU&?%B7PKMb4wR z-23+W`R?w4$l`I;@~r(^#v~t9h^pTwg!!(Ix(Tjy>~fz6+}m#OO1cTRl>U!IU35`t zKqDQ#JoGPb-GO-O)@zix`ywu#f?q4c$i6=~-{VctJ*VvNCSq64*6clLEk`MXBqCmc zKI&B}RNBLP$#07nV_lXDfmmr>Xy%z?80)0U#*cGjnVR68b|DPywy6*!HIJ$yQ|Ua} zb-TKakC||G1fW|~&pCs&HzxTGT0nmD^_~X>zp~@fGAbMY)l-lFYSiZl8@_b9 zxAz_e15gWbe{}{m^b5j8GZ#zj_fJpNIKM>&L$07~8 zR zaGsEYG&g5DmPNZhwR5-+?dwenr{z z?#HImORiD*tz4Y5Eom};w(qH6D=4I47H*fhzVV{YsihH>fY``ts{|%?j2cp!h@9K36&R=%PIeBM2~6BqGfs} zWw9}1fBd-2a54HHGwO@w9&p{HV=B&nMZLwGqm76ZJ-LN2hF0Y$>wE8PqYc4oj=b=j zF&gVlPZps9!opCQL^aUveC zRZpJ@u`OaNgk+whn@4;Mgg9&*hqk{KEPYFLx%Kgv1b>V#do+r70Dn!X(HE+x4UYDn z8mKE?Vn#i&@elaDVpX75(wi^7F4tOYt8rNX7UvjAC{LFZ#aM8Ct$FgGQ;jd_<98 zG(Xr`{xcM59@f2!w=cY&+u|Pfyt(9GJ|gh(a8~GY>$%^QUhe!cPtWNcd&O>C;y=Sf znoA}>(9?K$9^(4`KK&@cRH#XzV-9Z}cElc~fwNHe@xvFsy2)9s6H7n$V1aZVRC4|g4k9FX}F8Vf2v*78j#l#5>J&6f}z<>HWCfa414iEnie9RGM literal 0 HcmV?d00001 diff --git a/sysid/src/main/native/resources/sysid-64.png b/sysid/src/main/native/resources/sysid-64.png new file mode 100644 index 0000000000000000000000000000000000000000..efb193d3cd6405e5b5f7b47f79b145621abecd7f GIT binary patch literal 4502 zcmV;H5ozv;P)dqsf}$)D5-K4i1VRWQ5VBXcqL$P$f4r(nRn|&UICIabbCUO} z-h03A{`PyHz{rLQSm6H50>%STKnx%N&F)VPU;s`5-vaFfVca;50Q?5n07L?Lz;g); zxE|;=gkj!$F|Z!E9|#-bZ@Yl6fxiIz0LKV~-vK<;<5U%pnXrKB+X3J~;6)(a_n;zr zEU~F~p&2y}MVJ;*l!E|HhXcF0lg@@}nl7Eie7&^i^{%?F_gBCf1mTAaAy5E!0PneH z9so`99Fj7Yp-W6b6%mUdii2Fjg{7^T_S#Br6nu@b^qB8SgIlA{20{2CK?nrEYT(a6 zI6!3DBE~QLJ9G&X5k%SW49Ml8qy8$_@()s zY7@~ZvxYBtA0Uj?Wn9?*HkR6po};^gCji?Bg%1eAKmh*i_O9rsFJ{uR^{8~w{eIbI zYRA&nh|Sc7!)5_MrU*e1szDVILr8dJ|6bAD!Q~?#a`VKeo z3D3%2bNyO4)_q7iStO9or6AkIw6{< z-pb%~P<`?Xt{iyVb7(K{$c^K;h9P_{&!~5_n${el-)9 ztVNV5{J!9{+qhYLjEep5;I#UO^tiY*xRGt{|gdkEk+Tl>0uF0 zuATZDmHXcSKpn#GFXu68h{C@DY)x2ztL(7u(b^{MfBVSU3qnr-lYk;X6+LSSsVg@k zQ-t)oL&Jr9&hLD|EAYmR8<{g_4vC40L`Fv9a=9c>PA8R>mDJVMQCeEc?%lhosHl)a zr+zGHkNgvn<5GKRLdE}l!1Zr-p_IdSyCG?Gz`}O|`h*4D{^Q85q~pNdzM2QAy1E*{g(T{O#7#)O}IuWsR?`Q1Y4J=FLMcms40+NORc2?5C zu3X8MEn9{hhC)L_dmU3Ml|1?6lRWm=V*s50=w&Rejeg%rn3WAcelZxz0utWy?-*ce z0FSoFqXFB20qpFP%`K1^f5LE_@#c=z3R(d+d?1|XBkFquqV=jc^+Q6x1r zm7<~|>aJhK?h=SeneDy5JR}sSsGzOVfB-DHHz47MGMpk13uFT%&dK!?-rC+m<^Deb z@X|{!5g#8v{JL4C>N`KsXxOw#GOwE_KBc4HKUayJk^#WSUqW4DP=yEhLIjooB7inw zLJ!AR0KoL=)5*%p8d27(R4V&DmzI{s(xpoQs4F?{cP=b833-I%0WVbrRd|C;bgmPD zy8t3n7orT)`NiXF`3C^luwg^LGZ+j2qA0Rr#R|#f@^)gk-0D6jQxHEl7l7jOpbDRz z`O_P%B9H+Pl{~#y%r{?`JkP9IvqoI^$YcWt@|2Vm@871z8ozVecu6x)6a*%`%OwUP zyb-tRj|B*g@=v$S#=35AoRBbL0D>S42tljWl9Q9;zIVNUaCawU-=BpW4Y~n^x7flt zls}L9mV`lt_W+0jP^iQGtGmuN0M@KogF>MQO7$xa(lnVkaiWyZHu!6RZzXxHE_C3; zOKwG_aPrleTATs#kq5jPXFKeXpY@Jh^dKP zEShB?L2vPe(5LWz01*6V$LX*KG;6^e9usjno&ADy1#%r92zh76m)Pv`#eE6y2f*d< zN2^dt&0bF)ADjlzz>nYB+A0aqqxawoL?-sO`D2FJn5~*#5EjlXGK8zmS<9ZNYU$T3 zJ*_9Z)$9)-R13flKm72c0jRC5m1>2kQU2y=G5OfIzZu!>3L08fe04glCj>)?!jk=` zclI?6=$G6*GpwEd8lsAjY`?g;n5L$tpa8HBV8C5nUF_Yvm%bvBtwVY?r2@jk{3A(t zsFC|J%ILC-z7YDg`Mv;@1GHbi?_6W~X#l27P+_r!Q(TdT)74uOmdqwu8vznytGy7;l%<^;uJFD9 z-t&aR`qGpBwl!)jDXTUEuyyNJ4jno)W*oC=bI~w zG1r_2U~anqB6MPGHQBST6}5E8hAljR$B0Zo95Aot!YM}2S&CfMeM3#$9oV|M=(twO z{{8zIGiD5vCr=J2OLVzhw6?bTIZ>C(#i>)Lc=p+60nks+CS~bU$mB}DR@}MWFXJ#7 znLd3c(}R%~X&F)W>GSt#;2A(=wb_W7G}qf36hx88@oCtsRyu1g zaQN_H+S=NfG-(oAt#;7a_qBhc(a1+1eZ-3|z6e0nv@B9rJcmNXH z3Ou$dm9v$j(S<5K5DX(x`~Cpj0vdpaOgAnO5*hE`s+P&oPndzI)?utTgTY{6$BrFn zG#Yd|9Xg$^mqxf;E?Qbza5|mT*4C1jm&cYZTR47P>iQ%sT+QU=8+uiuO%(<%?)i5B ze)A8J%%9PT%c&*5JQiK3vM45^DJa6zPs?~Ouo7VUQ?H<(IJ0-oUVVX!U;ZbitHs`9 z>FMd@=H`-;lHy$`F&d3rxNw1!Cr?sXSlFG;>c=qU!Jng_IIGvbf{vS4D0t)NxSW#H z+_FJS?!7udpr|7CT%A#wJ=9P)Q~(-xax@iS#)d!k3QYjcE*s62MO2^MPy40(z}n+U zX^gvP711ekkgIyv^&K~>IQy4vINIwFMG>dF2->niOU}KzB8AME6|9*b2mnA5a13eF z6H|Y>jZxF?@mnwGR&yujmU=oHuF-Mx3T9&i=9XGq4m;}T1XS8+wDHM=$BrR1I=?q0sD^uz_Yk;1egerxM&UI z?|s-?B?flc!P94l%}mV?UvlN(+uq*bC!c&mY-}ucyPbF5dB+O@_y~C14Ph42ZnMk5 za)Lca8?Z|*W46=99qm_3s4Y2(Iw}rzWbBA{iMX5&j8*3;+4Cw5XAX30LUS|o=g%iO zIT=wDnLT?pDwWFPIHv&34#wd!^N;Kp&R|M&z8=g(wjQ7JUlwbM|1l=_Nd z6zVV(VOr!$_0Y0HODD~h#auY>9@Ss}7hP@j$mJrx`dJJyQFbm=I@q^wAL;4o13_5k zzMLF*bR-aD0|+kwI|PBJl19Ud97v3XynL{?H_%vejGFKE(9zO>)82)%%L;;k%i)kz z-|4_^vtYM$a;v$P)@$X|`Qihr`7bh~D=JpXm5C#&SK6Yl*H^I?-c|Taoi=sp~hl$xo27+ zJWNKYN+c{)#NkkI@YEa+2RsiY@;gIs3GUbMQ=6X#=nApk_BWs(;rE%p^&5voBHWys`8>~^WfkgLLoOirh{s%*$UK^6?*hq6!^rENj0R(c_fj&A6$ zu*m^-N(EE5@ZGCSGGwxmLlAGb@J?s%eJv9bD_EFbOG#B^$;pyw{ViH}d+|fo(5G!3{xL{9=SdVq^9Jy#ta1li_wd;sWfhuVvRlSX3< z1s7w9iNF_vK_)u0S8TXASYh+M2g0q}1VOfW9sdf1+zy);1Q&_14VcVPz7U4m%;*Ec zjJ_ermDsz620^xY9rJ+6x5MG}giv%jres1wL)OyAuMV}O^@E^Gp6R!xt|tV?5Fm(1 znnn!a!}~q(Ja8;LcFea9n+2D%_uDoy znG#i)-n*ham}3;&VQ{QF=@>tfnZISx^3~}y><)qZ?kpo*ZS=GGU^O$M(zCPLDvR^< zQ!<$Rz%$50dN)^`jxNlmW^XgLk7VgS;9J2b5$YGhP}JUR)pGa;KL|k;-aVE92LWQ{ zEN9Aq5L$4#oP9xP1}1wGa`zh*nLW*6s5Y+-X=iE1dE_z|d4-cpmiv zEc}2F`VxNe;>8>}a>Vny^Mk%OnD=4gIG0QK2KRRQ{>IIwq$0!Rn4DMNyzOc~(D-NI zcb@1ViZVapb8>Pxbm$Q4*RS_{|A~O!91Q@1;s0pn2ZZ1mPe1)M%aLzN)93*l94Duat@+M5K$2&hau-IVaORI2#6#RMMW^7fMU)$tr0VZ z#q6qxF38_~@60d*i0=D-=X~e<-}Z6lrmlXfs;jH3>-Hc31i%7#c>z4Kfk0*e0ssI~ zQuy^&HUKWedm0+#>lpyV!;hI6eyu1BfTRQfBog_0F#tANumM;IKnirb01%!IfFitx z5bzFO4<69TctPjzqbk@K|1`zxyXYA7X^^G9DZCiK$wFJMi*u;1EN-2g4h5z5KCMQ{QUd?kw^q_A-*6k z)DI+udIOKJXy6$Z1-Mxmz+4G7pesKEXi0Mc4+|(1EUJZ|&d~-KYfFJ3WUI2Dq0bt(^08T!~KD^z3 zU`NZm8n7U{5?H}whPw*L^Hv4<@KYY54l08+!MYGFP#vlT>LPSNedK)57zIDk^Fb5* zw8ZIwwj=|v6@J=N3_(Y#5y;OA=?gV@H?gc$PJ)pO@7aTZn031Jl9Gp3G2An;67F@h|5nQ=)1zf#) z72Lgh7u>sd4?KGG2t0oL7(99M1U!BE6ufxx0@D}v1!dG&-w8C~hoT?e?wgprN{#!* z>rHXScKE>*cmKWhe?%)cy^~0Sp@Ev3I=Yb|ZNJPy zM&A(KFpA5{01nG6W@kp}!5hkI#&OBa=rSuSYQ7R1CksJQd^IDw%!)8|Szu}7V(u!w z23@9bIWF-H@DN*UHW!1HTJ9Vc9vwaWc!-cLE5N}gmkK%6PsqwT^8tXY$IulXg*{G!ALtWFjPSz>&w1bn z9pN>d?}V2mSnsGW?q{XowHf>%e~uL<{D6Iv{Ve4UJ3Bi7Gx)(w9ws0uKvQw%Y``#E z9x!Sd0Xb1tpe)V~q(xYOjx0COSC|2mm6d^(7TM908)G)H1@gvL09ZN!usRgX2#5o` z(D}>SH~gNTR-ker-M5oPi*A`^i0bwFuNF|bQ5 zgi5Lgpky-;DQ*U$|?{J)SLCf*!*PSQBfT_{A zCQEf>f`jFhV-jGAi;bEq6BH~r%f^ygAshGwdCrYTj}sDNV`JvJ2m3Kty4YosA@rn! z139Dd$MAV<6z~g{7Ynno&%!GRdIfoDkRK<+!wMQ6!9``A z;hj(*AnqF!j7m_jzXU&|K_=(s=A4grL1~E|LEPQP&(FtQf}o2TPBwa8OnwXxg-P1{ z0Pt%k7LxB3E_22k|KIjuXg#O_KVI-djZB7%)P z{Jyd_V31V?3NzV&7F<8-EARj#C0?MastV-g<$r&?$KsSwxTXxSl>%W-(jeMd7Moks+?0Tg zjSX0`&;l%5whX{N04u%yfcwpS=Z|tGCPg`;9z|xr;4dNzfP`Wo7@rRW)5?KR<~m?n+=#_E4vFwtRviG9 zI{;`p2;-bBFwSWQ;!XSM;v6*3i8^~e zaSLG#RElCCxV}X(Py<}gHpl9MP4RkQQ__5FUArU22*yLkFg7v*J4r@hZ-xojpEVvA z9V%K33JVKCPEHP}E-wYu)zx6bh7F*#wH0jNz8zcB_Vx9FlP6DN@zEcD{4ps$qAGU6 z$;5bPrKdMm1I13JaIG$}`4A9?AEska?xT;#siBPjmj5{obl|1E#V<5qJNaU&!zM!j z*eu(r)m>aeLtQpbRTH~c&j5fP9}p&2XbE+7_3?Fe`x!w!17SAMuQC8N7{TUHRNu#E z@w}-CVCzY_(m=nGAc*R>EOSN0M`y9m@)j~8?V+B5DJeHM2NI|PR2{Vri~C|9SJ$w~ z1dy4;Tv#%tp~$d$WMm{xfH0z?CTa;|23F5XP38jT9h+hGae^ov_kam92ooSPu=Uhb z1;Dl)uTCNG)p7T6ccEpe-YO$?y!yrtBG&vkf{$yc=e%*2An#eU)jKHFDG08v9(rC& zDFpQ_w9FtzVYIPS5GzUAp^h_iHS;911&)a)(^0{ zMzmiW1UCV5AosXt$kjVKXbB>moR&Ddx@vj4x-N$V<^asjnoxb5z|oq6Kp;Rv6ctzt6pn7srn{Xpn%oPPD@Nk zOwPv6V*yV^1rMl24AYm5tRNm$Ns=SG1!>H{5(#{KVBu!^y6~!95UZX(2XatcR#uj; z0=1Y1=@S94bzMv`4Jw@lkcAJEIe~t~I#enu)*1jbpmLRfn4OLr>NuLRk%0>`yoQOT z46BV1RFv|<0h^mG0n~kc{OEMwVTNoZi<70CQhi+|T#J|SGN(gOFw@7!eI+eHI|Dat zUKW&6tFNnq^(#t&6y#_&@O6z|>_#KQ1`wN@n+Ej8t0M_u(F3qY62K}CJx^B}M`jFC za&r~I+DY}xkQ&l~*lI6V*U)iCCI}!bHxF%fOn{1txdilt1DUv|_9BW53=+AyB%nV< z{Q>|xL52ZUSM~4-AgdLLl@5yN>SF>|6d{!=fF;n8c|gZRW(i2==B7-jj}%%_QH<&< z0w;XT`D)=kJyrX7{d}x_24AecyFpZ_HXta#?j`qE2~b2GX+z^?LVdh9)}x`4%`}$= z09TI+VkZ_jj=M_8SZF{88xtJ1v7lg_A*_Br)(#gt=Ki1zxEP^69o0Yy@+k#Ms02uv zMPLS$D*@Q!?lRPMIg}R}Mn^j<0rq2-WMLJVCDgn=;LL>m$jKf|cCQT`+mT|CU)=zp zN#y3{Df5+7B8x{$j))7Rz8BC0lD`K^?l$d}a7A%Z=?=2WJ}#{7~1ayzqijPKaIIyb$`2N!T>Csh;9>~Zucotrlb#4U*FGCtzoK<)>{5AZ5eJWhJPu z$MgBL>(#zJ+o)^S>({Si?_25KuVR{<{ACGq7idk&({l^wpIimqLq)L$<^)iIGVyd> z#m^m98J^?{n$FHY3+iV3#i)eiZZI$hz9z+k1Ai8_B&uPwKng=U0 zY0$QZMtQ&z^&1?(Q3ZfOIZTX+Q5(h4Js=B9Xd0zHragh=vd}%2)s_O#Kz^_#I0`b4 zil2e`^dcZ~6r;li3@8k2hrl?!pMkT-v?5^S`T4ofy_A&!Rt&!*1d|;$;;*F#cX~|I z07hO=P=IkT4-gRjw&-{=y@$_IA~9^51}Nl^o&+36&ZRkCv2u&C{qR)k^0reSxb!+GLSd5&e0YnZBX^L)aW|POj z5qfS46CgBqZbi)Fg(3n`50VonH&ADhl$VEi$H>(&^3FsGH9S%}0qKB9bT*;qppJoc zO@2N`o0~$y(K|b7$SDnAhCp=I^ragMP<4tF&83i;hsvj;kB_3t;H;Gp78N|+3vkHD zVu~Zn&H!acWfOe^@mT*s_UHQ&iBaQ*MAPrNq!e`~3VCPeGWrIn3}6lUn&LWWV#d*t z>M}B*?Cdx?;$ZpI4IugiqXb+B%?v;$3u!(tmxPgTMwI08(*_bW6MVvOJAnM72J$j6 zbh7MIHxTZ%0+v;)J&1Lt1r^TO4y&Oe!~9LQB64H+ zK7uqAI^qHsAbQL)O~aCtjIt(kphSoq3INLl)lpj5 zY5`X}$$16&I3?vfFO?e+mEz>q^*qS`dps2vO3hD}$b?eHF zSpZ!8q9lAO_a0D}()tx-}Vq zRd6u*Oje>Td~E|OKphoRX|WTG9&vzlo5v02z?sR{aMJ870#wj*IWVt=p1vAyzyNR~ zubl)qJc$Vg&cq2KY=%2!AbmOj74+n_WO_L4l3|5R09N>FA%{RO0(2}$`AYDG(S(94 zVBI<+zz-|r^Mg4)2}I}*=yhNPwhG^{W7*pVJp%DuS=~+#sQcj}N3LI-8NF zHXL8|_vv91L?1l^f3gm6diBZON7es212A`-f5ZaOS<5dfDi|BiteAB`vUxBlj47jKP1{NWBcmzTY762K@92_3B zV;66POb??}=mYZR0x3#>fpY=B;aF(Eho2e{m@s^(-LHX(pT`7T;Y3ZD-pNe_b#4Wi z0m0ruPM)@qyB~T0666pLurNqZ-++&IVy6WrK!FNirur_t6`cJF0U(bCm@<$+I-1P4I2UQNJ=yc^_iB~A|;fU5+Ie;DBSbat`OVcT;XK;_;`iJ|i_t^;P=pQ(oPZRN3JUVn;6w-8(A0#qu&7{sp?S%cHq1-x z=xiYeMtB1YDHBzGZjuZ}3BP#Nk>X*akleD9E>MnxL3dO<#ys8toP*@>+OVtA*CZt+ zr(w{LItNZ`mT08VasY)1p_@%12aNb+i(!s`rEvoQ0|!*-8=yf)4;$fvR3;76!Z>jO z39j=9b?7-NG!4X&Rfj)7-&-tjna7*R#B?!}CRC*^7NY5xCpXfBf=n<&K`l8sHCbH= zG7fisY#2v?XJigyCooT`(`-$bgd$irQl3zbSOd{NA%~SZnr$sb*$4zyQ48CqshEW8 zg+yA}5tILx|GOH10|d(vqg*gGPi#h`4`h*KtK?*10300n8fOL@bTx4QH9=Gy2yik2 zQMeCVoS&I~f0MX0U{p{CbA(ucf*2b)Z_En!I-#5~4=|p~2Xn}rKuJjn%!fH+4ceSB z8yA%cMs;04Ft!DheNT)Q4uH*-2-xA?Clxn8EN^V7f$!6Hg!$s7Fn8>V_Gp_+0B&q-y&ZlKWE1(fRd0xg&; z#`bxaw*uMb{aCIT%L}6%@V3)C^_0ihndz_N>v3=joF}m2kZ?xBYV!rrDl`mbsn6keK z{cZ>SX6N9+gW&Y$Eb1Qc8#iuH_c#qaen_uU>ACdR@X8tXjX2!jEe&N}K-Om*d@q3X zjXs1E&v1DsP+BxJV)xPBaJtgagV#rT`?pNe0Q`;Bl%*xX-Q7LhVc(Pw|KpoGZN)GS zBo^(OwvFy~h>pstEz{QfXAgH-(}=%t|1`wy;W+&NC#@ZCLH ze_HLIJ%I7>gwir~15o)i`0nmM=W}ZMsqa$ZIZ7;Nk{RiovMTI*pKv!@h@`V5$0tC*f1`Ihpq7cWB@-2I}DQ3zkKbD7xDbb`aJ65Fh?# z|E&#>;Zxya7Zs?1I=K9VHaJNE_`n+%KPW7iXrvea-!VXeFDgo7##S2|9e*aZhG|Xl$-$>;o@Wwb51m{R@ip7(D!<+5igpIBD8}rsqRv zcM#PFN^jyH49~*X~4M1%t0m4HDC|H!E z*Eqa;xYssn_1`<8z*EqRiXbET`6TM^B<(2eAn8$=!~lg6=m_G?&HtGnm<$iW^R+TF zGhs#qD-_SV9Y>#rfuP`6b3Lm#3IT=h>5fytBm8`bpNVT=7MYwP{d5|L)zi~k8uSn5 zf@UNkfsi_`e0WB}c_gWJjQQ!o&xr@xdk65M~o546}d?#hR6-Kes|6C^&y0p9o1 zz)!`%Qsjj367K&iKhOYJ37Q3kg|zrc_o>N{0Xq17sKciyKlKBU1%G3`>1_ZTcm!J6 zk<)?LNC9;4J-FNZM+`uCJ%i~Oz{kBXt?-!gq3LUpEuXCXo}SPtpz&Kj(}2I3o}NB2 z{O5DQB)5~FkHJIfQ}XGh@9Fs|{1i5T^*)kbKOi{V?`IJa8J@=S;TX(E9iN<^4>$b5 zLY016{3+)G1dq?iep7eBWOyWe3LN$M`N=}q#76_)lQ@k6reFY*o`?;F@F}}s3V2NU z$m`@QV!=p!IQlZz&&s1ba88})ijR4{WJMNc`o71w@BZls#2A}23j8RX!00S?LOg(y^{}MUjJ*8( zEU5a-%&Z(_`2<$+$r*)dO#sG(@j<(v1RfCJdg|@!+%lM4wOBZ@<#OlnnR< zxuZGBkZy5`?=hj9adGJ>Gv0*0C$rJ*GOZ0v>H?&OF!wlf7?1e5uc8@-t$2oEoPmOD zO!?EpLoR+{17Q;s4=;n`P&gC}ZIL!2+KBWI0EGc^-~ST6=T}`Y86SfW3PXKEyDqS! zW8gQXhYI**7a&Q4-Gd>XAJT>o77W56fH)hE2gvf{8YuXkzNc8?bPPmH)D2-ly2<4kbNt;95d;Prf4H{yd2W)^4|_y_Qi8JaGLaAd(zru~*)0ZkCW z2ZpV{H@c(DN?jFBr19&4H$ejwR~+F;3#+7&oSKn={Uj!Xv_?~fmFD4`6&Sqx3N*Li znI*^omRo^cFfrPphnwOGV<6fUd&i13sHl}gGn?R^y&x+^6?=$%&D7HmoB&^|GyZte zggXW5_^ocpK-e4#wNO$v?OZ~04)-M}Q))5Dhto^{pTk2(l;}zzH>{F2Npczvii)x| zvFQ%ho`YLF*7tRFwOD42!rjzU&bY)A&UR7uNvdSfflYaluSr2cM+!Wye930)+3d;l z{RBk1%NBeP0U^?qfRk=!!<`)DLV?Gnm+bCoh7bOs^o``UlBU-@EgPw5FD5Ly8_>wB zBlkUo@9F8ZT{PWG20Fp93v&1-^c$)lX8~^V!iptgfEIpo`@gtTk2f@rUibnylcXhS zsLoXoQc_jdO39*s3>itn>8vR54A#G!qM&1lEIlQ7AWK+~ra`m!6Cp9Frc4-?Bp!?d zOS1H{|0DQjtPPMdu331Np+W2H@EYiQ!r08fjR1dzE=?B`(up|DMJI0gblD;j+Ijku zBD99KAF}bkAcE>jd$@c2M`{6{SC@q$L6D)Ix!FHrU>DZ;%H!f>;~Tx;?!6ic zG=8jw3_uo2$$xEzKx3|WN^?bUu%VuwxfkuafJV<#pJLkQ9UoQX0R^lut^*f*FXx!kuH)RmGIwuVSyPRD^>gCp;SVHNqdT0 z0LBH}f{Y4PaRu0Z3Q;mVe2e>g*>Y^?Q{8R>9<-IwV$zCtrKs3}&#D}pZJtW-~ ztpaNB_qbFW%s_21yOH6E=6V*t)WA+e!b%ap0L#qlPHlQ*HYnQ1j+TfVQ2h{cTLdQ@ zpJ-vA7yC;iv_#_*8C>jt6>te7Q-n zfK0@VjJuycS$f34bO8xw{S;!%_;u*8rn;cVufa@^YC%{BxVd}jnNbrIL6Z`dR5R#C z?DA5^uR6Lap9+%h9^DA6si{O%Jd`#t{{h#eLq#IskJ*6d#m@8bM*mc!{+z zw~Cv37%o7yDcz6R?yuE9(F4?A`35CgCC(TJcMn>M&B#-x>w6>-K4t2|Vy@|Z53Ub- z4^UHsZ6%->0JbovxM1jq5PUqefhmU}=6xt*7sU?@Q)`_5F8mP=U9mt?P_(FlE~s-L zf;W%D-{QATUYMY|3S@lvYa;;6>5+bNHNgV0%{-KJ0p`Nt0Kf~9J{ILIp$4Yt0tBf_ z#>XbFpM@QCj7$)}1`9;Up=bdX1yS+6tjyymiMlD~0)$T)ei;5w;|^K|CgNjZ040LK z@X1pkl-es6CT=N(k}0M7A6k6O`~8mj*G*7A?tv&C5Nl=}AI}lv4ER~-P4EK{=2rB6;C~SRXYy0S@K&+VV=#c}&zLXnz!MA93fIVmWJ=G`%Z zqZU9zH%BGD3V-vit=Ecp*YN&VF`25g!YI zX#F2y(kmk`O!;JP#$!S({GbHCnCG6nu0*%jNM z4xn(ZjV^u}eL;5UoIhNOB03?m7K_j zYLe$a%!=gT8^uW)AS)kN0Qsd=3&N*3pnP<}@z3KQb3~U$>%|<=8_j7Ma1X*9(LO{f zNHIXH>wet<6NW#gegdWYvG~sud!sr%1NgcCTl;5|b%(i*U(di3%nzG=DNdvaTfjwN z_`lKsTAssS$iW{fQWSt?9;zlAJpCPd{Aw&0L{@(R*8OvE_+NEFI2;9-0VtF4i!kN= zQUUblhlx+MeryG`oPs~C27cMQVsr zmQHr^g}b}2!**}l82~%SeDHp35u{CR1v3GTpLM{v_~rQf4s|La3Bl72zHv_6p`_j2 zdlJWYc*D)!;q6F#vIS6QVf=;C&(;Cs;#*>9)aVgzauY;%CiOnX1g7Yop52r#2!g*c zp}_a_V3Pnf2?TfPYNf8*P+MX?#bSVBedT!9)4=1tgL{JU<0=TJya;q4GXQ^L64XwP zL3(;NVWLo`VQiOnQ89XvsWZ_G$>PI5$BGxqtPclZDt5nDg_%Z5n;@<9@L4z3 z1Avl4K@1dNi6qpfZdnz@A+N8hD5Z!F|L{@<)%1#TvCf}b`%n=Sd2p%`<58~r4d*d8Ynv`XmpRAlI?E~wh)IrkS(9W zR!>hO)+lclLME4jBwie8%5TkFN>dhu}L3@;e+gF8o*fz5BH<9e1uFc*jj+*RRFp5qU=;nRdP?TD{G|C7#&`N zgwGh1y#{Cx$+Tq(P6cERkd+q{WM|XwC#O8b)_b&D9e%;U&)^{scozVH z34K6Dn(9!HjV;>X-}9!~=<#zKfO?s-?lZpGNT&==&Iw5+)XvmK z_)B<5i8}(MR&~<2f1N0PhBnnX+0b-7g2u{}8ybHH9!}Ddc%Q;=Ud^?cn(^rfXG2jlg_KoLSX6|5yOo`hqK&Om@n?W>5p@!$0+UZB zje_kHYfN+9NXr3+#mdWvG7EHt(T);VOx4r`27X(5ysc(@O9mYt{e@V=Pi4oOpkv@4 z!owDJ)z6{_q`l&@{f(E~Gz|Q6cqGHFMjI?RrbUK-(nhlWH^31+m4RQl9aQ&cWnW8! zt+j+03{V)kB&-)K+PM2?HK)4Yl@J*dn($LIp%?7mtA91{uLl0rz`q*!R|EfQ;QxXK z3Y;7kaC3;Eyax9|TPtUn(}Ab(FNU$e!|Ld*0r0=%OcUM%k3tD+W+I5MO*>Y=^C}!dxQ8m{-`inO#A^vgg_ImF>qBfX&o_;QrvSdk= z$VwM0Ge7pL{MFY}7xuT>*QnTE-|)3;=vJ5ZrI?tA{qrAPIaAh^`mUnC@saVBq{}g- z&AUhz;?Z0-1_EYkBqea2U`q&0{&8uBW$Ke4s9y%0c(IbVOPg4(jKetxjqtE6||3C!{#LnuV2pzI0M-Lt|x#(Dl+7 z{&^KW^=;eD6W%{4bNeAQctwEg#3I0DldMfz1yooxjIVzcV3^N1yk{5bp7`Lbf_SK? z-gxyHr2EfjS8Zo`aL9Uv?jfO&#-nRR0Az7;RxX&!5 z4@nr`SaAv;h$Y{a3TC>HRW@S&t2uBatKH|)BUB|F{ zE+4-?zv9NNU;mb@5$GHW=-I*D>^@}sNZxWDNg?+DZ)mbZr@c#DN*V8wZ+{DL-pHsG zBuTCq;{oq1MQ^{pxv5P?KSE4UNk*zdNvg`Wym?W!?UqcZDnPLQp%PTa+11b7eMqA8 zmJJ~7-OLvj_ws7&$f}yu9?lalIzbdJ&b}MNOOqn)9yDF4r{>o9o?SRPdKX#77C!JIs$)Kq10fO?{Tln!LlzF7oXQp z-5Rxje#`E}*^5k5*Y8}KRvI25^-7b2+s0sTym~z2*`m*f*7B-0nz^t;`yFF6+A;Wg zi<;HYoA&0*qMQWlV|F*@=^S}Et85cviNe=`i)Yk7^6Bj$M6S|Soq4+Mqn1^c0{*4K7h#w5>VsUH z;u@Ni%Xu?)ahf?wj-3H7SY!H(d{sD>|Cn!b<>kz>3mFHR_Q$x->yfXTRpjFhD?ce^ zXZvDce#c}rl!?_VUgOM5wO$E<&NQGI=62^@QjZz?sjGf3Ep>y`++Lr5{OWG=$%+vB zfQS+g1wFCCH7R4B+X`fEh`mze_xEAC>=tTZb#eN|bs_Uw0+U>37PW6;o)IEr;^S(?r58EmM{lJt80U5f}f8h^!A8eCK-n zg;R6a{=ai-w!Z4={`1wA1j}`)Go1;KeMWK;jEY*9EVYP_kkv4J7kbN}Yel2Y+rwqo zo`=3ndkVHLa9nV@i+Qd57Wf+kiI3}Mz#hE*HiG%!>Yn|(NXc@wjBDn88_5^-d`Zl@ zw9#zYi7Re34Y#=LHjF$xID6lSvS6dxS*D{3kI&3K=vY@#vaQ=lqTJrFc-AAgRF+%Y zE1cf}3aabKc%NCUr%$sNQa8p1hX2wDeuq zJv^r(#*}I;3u@T%+$wn3vu2uRS-f~=>?kG6;H7bW!_hsY1+R)XpIwz==lZ~%7$Q?= zSN7!oiZS*CZWE8I_U`!?IfduUBl3f6)#cZnJ&HH&{4u}QQk}g@MNoNF^0(}h!x`@e z&B7|HZ&wWTaY7GZ%J5ie{u#fE9yxt--MOm6H?KLd-`E||@*~W#P+M-6Z}t7$)+Lp5 zDwIw{Um7|PGdy_8@UCP4L8E;a$w2oiPhMfa%wKJ79QHa!dXypA~efj#+kFGftY)_s2X{DmftFuR5 z%=xqJB6t5Mqv4UAcO{o|JwE;;=C135>-}XrwbV}=|6uBT8RIbW{p}l7f#`PmUGskY z(3nR6kNHI&+oS1Snj{cf%3kx)Q02>3lVSbf!~Oi%Ut4ijS(T0~d%f1+u;Q~T^KJR= zEORwe^*Sudar(;qvawHN8%_7<3o2&{0a8;fP-nO*@X?e-_-)VUz11>f=MP#8v7Wd3 z+|HAl6Vva(bxx;6!hguB*gbmH+3tm``Vzyba2`)n6g4GbW8&CQ^Odo@A7@?X`7qaT zaw>gyta;%2_v&39z?0#_OxHi&+rh~~VCOe?+eZ$arNV+ozLt3jxVmnw^U8T^glyd7-EA3ngfe6;+I+u# zaU|Pf;rBZG)_mmh(YyElPeF-Q`>NHrUbw=@<>5a4*Uh(;MTOpcN&Uo>so%I4O&Nzk zzDVA(-pYCYUwr434b`NL2H0k%tXLhzEUfOqb;zTvt4q7Jt<6%chBdD9zySl-j^(wB z<>9xWh{(VVM^o#tu)zJd@(g+l-||0sF2ert#iN53@up86-@WaBA>sY|5$!tzO~W03 z&CRjct9oak|4s1L=V83gu}&H04h%=*A3834RvS0gKF9M&d|a2;`=z%(M0d8dNbm4C zB&M&gfA-21o_lv#TY7tEI<$T2d%t0^yo-wq%u|cbnjiZ3%iZjIv$h(2U~gBt9pcEo z>y2}S?K?SfKMyXs8manYwq*}{gRGQhf8}4inA8sHL6O`B&Ub5swijPbcpKiKUvfhI z(X7uOE9LEvkA8hrcKo=7pPyg$XOGvfUa^e!o_KO}@J3tIpI7HRJZT2U{z6?7{ymRQ ztykCOXI=f}97EqnU3K}FdC!(xoFCl2Lw)SEdYoNv8QiXK!G#=AoFMXIJLVE26x+ zSCjmKK7i<)obBpmE@Rk2xPc$YS`j?q<*;US_htp%?RF z@zvYm2D@3iNESYqt=O1GZss&+`vk@)G$+4jwHlbE>T%YOL{gTJ2C< zeC%{dMo3Ag=Ml-xn>V{2N{(}VIP`<<88eraxAz>$^pU90dtL0GUa~H8=LSx_1NK!Z z!;XpK5`Ag%+vJ6E64tJe_|e}!zusVhQHt%yfphH2!zK#$OUvGknSE_H8*p6%jF*gU zSa`+0pQ4Q@Q{eb@+`QyJXsGqsGUTcZ7b7pn5@U54-ZZ=r2@ztp~ zEoh-w{&A?+uOQj19)t|?wS4?iVxe;2ByD*_y?o~Vyqe9e(@<~iv}$C zUBhlcf#pA{Z%YJk8F=*MnIWTk+{3ur?!yn>r=5AN>E6TMC2h9I+M2mBb!g?AM@O2z z?Eb5Gx8lf6fxhr_0UOj-9}oy%FIb*%i7m4CTK$@td+w?+5BXhLln^fFec2&oMzSMN z60|ned4Kxek)b1wPnFCZAHSEo>&rU37!9<4Bq0alV_-VE=*o}Cjlj8}PdMJ<#q z=Q!aL!=09!!MkGzowvHoy(RrPJi^BAX3(D;0Uzf}z>ei@kJ}}B?wwpUL#D+Xzr{kH zaHYh=abVt`aSUG#)dNPZy%xF{wC|(t+rRQ|E7!(+eU<%bJGTHQ>D-%9Phh1~gfxGz zTp;malHDMm;E^w`N28uUf8H~=Wy5evxOa}7ikFnUeOu{&eTQ;%U zH|O}@XKp?@(i(ChZso3eLvxq#k-QV(DjPUkPudEZm0Uj@dOvWT_XT2ue=Ea>`@Vze z8-re5i+tGDFXOiVnX}v|936{38)Ps_t!Dmn@X-RnV28Q2C0zwIAL4JkjeD7|d?Q!6 z+oXzVue65fw{PEupPl&XtMl|BV)@JUj$w; zitwL?uSNg<2k-q39U0W`joW+Qmmhj3U=d`91g`(U0w@Y z-_HbT+NE{FKk^>cFm?TCl%8#Mx@qs9xBEno)NFYYrSCNIaPN-7=pRpxv04nDJ$}Z_ zkiA#B@?7ND=+}YHgYSIeR^NPQ-xt6Ya7p?~ed?D7e|}-8)lE;o_a=BGG5UDn=1u7cQ+YP0x#I+TH)K zFXVRkv9smn%IhyFq_8snEl|Z)Z$$b$$eFlu=GxbLoDu?A%M;q1^XDbVOY9*YtM@##Yi+$cw(&uHe^}4Q z(>f;yUZ>qDJYA96x7tuHUH;@;%|~gDuHT={xa_2v=E=gz@Iz#9q4Sx&t9-=R2-X|l zomG2UwFD%7dtMWD%~~YqGl4rU{Lq(x%hKelhi`z%}O6Fov-`ASlUXXpPJ z|72tE2x&Iq&xK26&u=}qs<*Vp?eqREV)ftFrhL64Q)ZO8PI*P{;5=)V!!Zma?gJUD zk|bv(1+_(J0qN1%pc&4h$iDK`&|#VKh1`?Cz&qkq@z*#4F|VtceupI;idf^xo4g~ zPI159{IoRHT`z5J$`xNdQBw^Pw3S$Swi{{RY`=ZEE-7l7*qAu7#eRddTc6DRY+tdX zkteuydCxG`mpl(N+FcX)#>=*<;B4ap;d~=ud4j0gX&$aO1YWt&_GpEe%ilj;*A{bp z2XigCfg|n-4|0+|y~r7zV_gv$5s~(o@K@;hrSHeMJ7)|r+kW39!zFDx!qeQ&Ij2L$ zq`vsbr7cRcY(b~Ae&VxJ?Rt;QYT5+a_E)g}xYg-CYk!{B>T9pRBt9!&kbg$E(dg*6 zy1E@vYqz}MFHzN>b)fUuiF3mQDdWvg?wY_f!jNOt*PRk8kA7ph*fxXz<@bpDJ@ZsT z2CmsE4zX~ZetN2?K$)lM+lQ4NeWWFv(uUlk;isFR=W1!+VDb*GtsJ9wrQM3Y?7u0n zjFV_Os(bAYj3rgv&-acbU*r!btUc$K_~*vF{4*OIE87JB&ib6gUl?>WQacSU_&mU^ z9}K%{pD}$`y8n7)z2of6gAF_Sq-NE`D)JX-5@C1rJS|ktKixR`*|UBHQ)`_|;HLn- zlIJmE8uyE5gTf2Z7iw=kJp^+SBQf*NvH!91{;b~RZ~v|hyf3t3bw<#QE!NM>xrH*n zNOc}*JUhp#X0Jq;&atlwUT5p9Z+Y$?R{1K?cJzaG+C62(l}W^p7mqWXU+!vlH^rDF zB&%Qx=U|H^4CkDVblq-{arowcFgE@gwIrYLLl+&mKHH=5=&KNDX-$66Dt&of+9l$-7sa1mUMV{=x`r)5 zoaB9~P{?Xv2Qe-C(6+i8`~1!gTD21lhvJSsx4F6|J8#2B#s}eJ*Ed`^^LZ!7n~-xw zwhpb=Vpjd#W~^3~{>{|N_x<4weYy9Y6r7)5{`Bcn!E5&UH6k&GJucr5DLCEG!4@6? z75!uWhApAb8&1V=aBlsStiHr7;zSv#T6Ov6NQcpV%V!px9*i}BF|f_kq*H@uUfs0n zka9XapnCbXb1R=v6GyOqq#lwf=KYbl0()ziNPBBGAj0A|8+Ft>~jA%)yd&al^?8ccztZ*)vkx;x?QZo=|Qb%||EG^U)H=`8Pi;VDR33bv8F++iV`)0b=cu0|5ce z`swM4pmHHg#R2~xyL2jg#}e*GEy$O26z_cY>=|!KyJ26$jW{Mj>n?S#*F&FTGFnaz z_rH0v&9@N_SZD_-=1&*-hK!hXgFsuBMS^aLgO6uv$L_CqFe_+RP!In(v*zXPa`)sz zcN$*k-4=Mhhco~5w@xOjqK_+dijUrkXnT4!=-sLpqsLl@glnExcl7N|oH48Wkq8I4 zmc6R3_Pi2vPe*m=URyUeH#W)JSLakPz(3M0q9!Xw40%>9ta7s=ss7?3GwqpUmruY= z!)LB+&UInpKlyG?V~Md9;Yda^cvi_J7!}HXGtnqgL==4dmR?o4!LFL~Dg2Kp{}MeF zttoP#OVgmFX^xAullLOE^-v`a8sSIO1=;3;ZP5kCnbJO9*RFqYbRL+`J@=^<%XR6^ zm#b|YBsaM_+;d`7!Mb~b-LlUZZ^xk2fMw|+VUwwo?SN#`xLnJ*M-V)yWAnAFMWmOI*WxA)Hx zjtW_MS!Az*#De(kV`4R{tw<|hdM3x{x5xc3<7FpVnGap~u%M=Bhm>_IpXm^gP zEldx^?)z|?Tos+Grl@zWUE!#IgDI~S!{f~d^{itLHTb2oMG^A3D=I4sPG1WTXOOyG z!loB6_L1r7mMu>#r2qQxg1zgmw*P^XTck}MqGyZ4PNE>Mr-qpTr~#T%&i}PK6m1UW4dV1koA>LlZO~CiJ$dR z-2=NDeX->wS|hv*zbTDL1hEJZmSoO%FlZHLp5Z!`0mNg+xf^r9@R_w3QW-p$Kfvp`ToKJu2faEkwMIlpkbuzY0y0$zpr zd~DYBrSD&H8O61_$Gb}04_=m=Wj2rC*mkqe`$XduDGVfEK{uL>pk**=#yf*&5U$sKw#aWN;IJ>%koYvjHTG#=O)Tat3yES0itZI(-oEZjl=HSK-HfoH zIsN@}mIUg%x9wGp6jxdHoOD4(>?)_%>zO@9(zPmsdWrFx_wE@0u=I3fMDnY$q=831 zixTo~zWthWcKgDmNu%a{rsXm4QYaBlt@`#3!c=k9O)V4FMnw? zV45N?(Y8I>Qd8)|-7B-_4Y1lS&0t@eG?3jGSj!-8EY@>SU?KZQvmW;SRsNuy1rR!cq{l%2>dT2q> zN5*W1t8OR4BxU8!4zhqvGd6=|X^TUn468SO2Mpyg9zWbDyxD0p?CQQU-Esq^LD5?layjU7qnU%kD9w# zv4Ce!gB>D>1!uGT{FMsj>#c0|GciyJXXXGQJX-u=me-%Cg>Auh*47q!_6LVdg6Qf%`z+BfhbZ&L6=6_mzyiB2Kcr8E*wrXRq$T(apc-YRng-onS`$x zKDzOydTd^LdWzpp1vJO3OpZxfjv6~Q>`2fu91a|=tzEF(K7Q=SXnC4i)OYWF zZo5NntF`Q&oBCl%lDhq-y$u&bsxKU0u}NC@ME2*;pAOwQ&l1N0#ElGRo>}y1*M}|J zdv||$LG)^TtSg(@3)pI=K>YU{xkQkh`Prp)vVZcv*L^3 z*-JA#<)rrYaocSjGxRDRkQJXGOs*YRxs13gg|H;MdbX=$Ar3?FpPJ+>JjTo$?5 z`#HHK3NA{E?^qVxs3|Pu@cHVwao|?lmAm(ByVwJ7N}rFg)7T&ryPFUY=auYX938X3 zC)p#_>g%VN90t;HhF1y|$4c@JKNe?o+VY&Yq<@z;5;0>6V}z)Ux8PHXms zLojN&$y+k3sZCO2w0pZZ)5Fn#)6ExRQr2$pwx}2ew~P;mELJ)EZDz_Q#imN}qdGI1 z7tdn%k3U-a43HuY&*8A=;*=H=h|&{J{65%La5}(aSN^9jZs$uY-R;!%)&JhP-PMXv&41>n{-rM{osUME9 zUb}yPv3C4cfo4Fk0SV0t50s?UL;e{MP5*U7yNWa`^O>U7tQE)^9(bvwZpG zkOyY>l=HW3K78zh5UFh8jIH-RnY3|oD018@e^$bGWOS(C)~IHy3_ru;NIe+Xs`Hjy za*sCr*y)(w#TPI5t_iphFB@GMo;f5$9B{d0UEjpKw+1chI1>inIbDa_ETTvx@3gjF z4he2Qxs4-pmdHyJ;bQf4r~ASA@0hLf-yi;ahP}PLm2cd)`+LSf^S+85k|(tQ#;)8r4$DzvT&Ej_Y~q#ToU^O^56HCn@qv7RbIB zgW1aT(bwq$aS!d`8RqEpOn%Qbqj=gtMQM=&JkvOA3 z*VHndFkJntc~8TJ|5wvhMn%odd99nvv0NJ|O`LwAZuH&RL{AV_x$3eqtkC<4+7 zN(+K0(kU(79g=tR-Fw$!@q@LPb7r5t-+1CZ5@X=8Cny41OwpFff49xLiG>9BBxv&U zla8F{DuA6{+4wY?t(+!o^@LWF51mxVaH^%v0&goLI^0~R({~Gu1dU+ABGSS3uB1dc z7StMzpGKNEUGHHlk*8rm>Iy3^E^e*qlhF_{1l%8JX0t1t?rIo%t^dSahqd%AZY4)U zY7dxZQ>X8B$`;OC5Ci}cx8zI4BI;m5AzPrln-+U|I6~1@{PB2j!1=M#9H~;OYW=la z^FNNg@u^>~bN=`KEXaR9z9vb?k>Gbv&Ooua-{gkuEOJ2(B#F=4@<^sxg4!$_y6%uA z%PZoQLL~IVdR}HG;ADC)*ed$pa+cffghL)_f);=dJIt!HU$zP6ark9`FN?-Yx|%c{ zaWL6KPx{1_cD^m^z4mNmA|E}EMy|)6_>;hvS|ESc$6E@0+&$O<$66GJYvnOj@ynur;X8d9H zJu6LQ=K66|<^ck&vNywVxBhR#i3BzV40&F#)bZZ}2sEFv#3wrX-0aMYgFf=azT7&j z5(3v4S*YLQInk39B631L>R3;my1H#ZNiO6I)ht z{UZIPk!Axo&kGB%P)J7EtIjS7w=>vR@vGs>$~TUi7ZWjZ=3#bTt<5`p>6s5!GY-0j zL4+eP)L)uq<8+if6aBMM-;$t2MzdehnC5d4L(aK7dwn^^Y%0;=S{J1RY3E3Ocb=)p z`by$NE-=6J=SZddv%d}>TJQzi$zP@`MO5ybkkoW;O#An(6Q$xYLVAON4TOr;qa8O0 zvAM4r7Fupaxss)(%Pz-t|Ls4`Rtt6rP=+rRcqtbO;_6pksL*X~ZSDG;PPX15xpnJS z{nd+Vh_^i@i!sV5|B+V@>PAFyahw;^d38Lh7~kz2Jdz5F8D|(i3a21sR$>)@3p-ji zh$gF5RaZxBxr(~^+y1iuy}VAgts`>03v5hQcl<`6WrU=f%9c}Md|m?L0oe+jzJ0vB zX#ghuqv~S~&CAw&4tODhPw02MJM+hrZVpRwT8(RJjw&x#mdqVCpE~(L;*h9qQnEi;(B;beWPJSMp+^5=YPKYZ9%I+aQzPy!VXUbRBjQ5|G5;;(5%0{I@i0eVCavr`tmH1>+9>Z zjprf;e;2RsfwsG%Md#a(p70rQiHBbu@l1^G?klJNG@O0@xYu1Q5E%>s3L&a{Qw!5w z4oyBm_cNd29$~fOb{lh*8KzgSq6j^690^7%VDN~o9DU&Vp4VC&tjM$r^S4+T7QfYfZIF7aa_5 z?ZkKgBqpDk{aqt88ifp&$>X@ z3~cv<-{S2{Pius)K2@MHeg>3Q0Pue6>B8yq`#D!m)8-pAMQ@^5LAe_H=?4sL9hUb_ zsHxMwsNuRZ@-u-w4I0NRqqd^V83R4hK|> z8oc>77H-5o0#cX3+q3r5ugojSzg{URDJ7{ELctY8FGD8OM@`CQn;XtN0YK!ju%m$@ zh5#qffixn8g83^T?uAFYPs37l<2$BeDo0cEYa+_*DIgIsvA+r8GblMZSm#Uj4J8t% z)4+4nkA@cqdDk7K70o}-#sTG)B=aU`mnib%2dpm3plF|q2r3Jl{N0u57YSPvs)pVu zcFsTV2IG|1Pz8TpJnqEX=y>~`$o1ZK6cS81J?w-B;v(l*-2IN!ih;H(x8tLV|BjZr zohpqu#_wCo^+qqK^8EL4A*8IV?D~6zfA1wB7RGk-xhuV7M_~JCI?ou3%jg{(MA;+! z8(={@aF>2yke~gP?M%@#^uXcoi;Yds{8}+wrx->yRr-$mA%aB(T8krI>Mc$V0~{yo6=c*4PB!ahyO>mICmFq44@Tg-JT zdeXHap*}ZHz_#2hj#TN_-MSO3{sz6Wt5tpxy6!&#mLd}gdaRe&^b?xcnVIIF@J9`Z zW7eDUL&t%`rb*lVo87SmE;7unamY1{KZw%JjqH^{$YP_DkOfM1axBUg%?|2h;{d9n5yZuL8`QNP*%nGW{oww=Fb>@`V z)LEiXT%AligH|Sibk4uK-M?b-kGJ{2F|@F&hcff^B>M-M1&lpZ%r!;V;}K;5ebaoj zBLkfz#eW*fi4frqOM3vr0(X<*A#COLsdc8cnRg;zA!_%JONCs;m@U}jdR1mWMEBko z6u|qW4+t!Lm)@XHly9gF<(@@{D5kKwUkMA>Cn9E}k-@f@@)))tb8z5Kvza^H!P_Gti&aBLocKp8aRSY)EmubZ zt4A*Y-yI&{Orp6sYb9va9!co4{^7m*zMVT92g2<(P7fSA=#QUs_|TUYN$#h6hHHGp zq0Z7JykU@@WQs{!G6Ur$6}@j&@dGO%Ul#4?&x zpegk`Gq!FKL#_(yGoBXJ2%2;|X02^DL#K9(D%&oi#^XOO#T9NSb@e+Uv|2{*unV6B zC3lB6`JLDRntr^|SGYI(Zu{ET55lQ7`-H>_sf8<-!k@-++N%=mOyjv@=u0W1Chsp-cSV{Mb#D z1n-f=;kO2TA$P5jsb*+HicjuiY<7;9CKeOV0d-y4VKZEA`ACwy2K==I{M?bo| z=Xr6w8!j6|^Ei@m!4IIU$E)q}cQWD!hs^-x_q@^mD=kN_g41~SoegI_qn8B zSkexwGmBKyj!$3l9Q~ok+myLOnlnRD`^gJhpG6hB5_Grz zD0_SMGDDvAjSY{@aiPEZQ*Eys7QN%SOo&JmJ*X`KZS!7c8X8K>tCaC}hDAi}Y*B`w z9t1rh!aUA4i99>Q>O2*QYxx%zRRiA2-KJWBg&H0E61C=Hi93;nvl>X3K`{HbC(4e& zHS+e23bx_Y&?3#|e4)rGd-_W9Mgw+umzq>{6w7ta=^2-$qLr{C^h!|h9Vq{PG+cNd5R7$J;F9|-F4 zpObC$OeIwGo4#w{e+|og8OX5jqLc}83|gR3#BN(AEbX1%)pSG0lO|Ow8~BwpEYIue zG&>L5XAhzVkqjFu$Fc@9u7(*;*$Q(Zh0xo$PUH@(_7{(RzB>Mm6{%7L+~=O#+wXBhMc!tDMHQS#s)uiTc}vX${Vq38v+`tpjv%Pj zs*n>tjvf3!S*zFkX3MpDhilCyrb5n{&Y!aHwb4Wg!hD#ZgmnpqSjUzHV&~PWsKCmS^Cr$wHZA9PnW4T>KH742zRnxzX2Kb!7k$oCHqi`2ZgH>YRB{qWxomc^Odd7OA7vhj^` z3sIyo(~*z?`JF!1L}D^)K+lrsU@gzczTp+pum~moPv2365-InFAcCKq%-&|)?7Yp9 zUka<;W%0KuO>AuJ?x2PMGwWNoe>k66`ol0=U)SU8YW%>2a4ZmoAHINOKTyd_juqB5 z0Lv<(H0O8d8xyO4{Lx+NPyfhT@cV-m>7W>Wj8}>vGs5!qajT4oLQpuy`nTEeo{YnN z9`6o{l$->S890BE1(t_6lqU%#3<{-!p&RI){OQnOx#FPLzUdsk+LF@}2eh4yqdNOY zs6u|UyD+v|t$Kw9aMX+u1ba1cM`sATC78so~)dpx~JR40b3LeNLqo4|07Zt5pA5rNW24NYxUY zjV5CI%wI3(S39Eyo}QulS5B7%+`g3=Z%%eZ4Uz-3UCce2l5551uq;1tSf7A9G^rpb zs32s)An^vKAW#|&+8qbtS>44sBRG8DbjDV45(pWutE!R@$>$zR8r%>^zd5oeKhZeU zU6R-G)Q1)jNO^At17X2pcd{`P9i9%jX<(coM+LSpeSn#{-0}PUBFD<8i;RT@Lb-Vi zTw@9{h1++Y4*^+trLo7&ZyhCQxM@|wwm{tDY z_E^N3*gsS|ib4M)KR@CUeUD!x_g*x4R<82&RiZ@0c}O%GM+ELejsW6FmRC3w5$q4V z%B{KKdd&ZImvk;Cf7gfE*q9{vPpY5T{_eL3sD6mkfj3f_M=R)dv5=Lkc-j19cf3q4 zCu(h~{gD?^o~4q0dI-+4=`A&MCt%Gz9#=8qMnCar%fcVuYBR;(>Vm6oj@9)+^MFMF z8At&rpeAE;)K5aI|NX?~Tf6Z12@qg1(g)h}(Iy6AB<7g9^|(;NTvB=Z`-fwcu1)1j72?dSf&-EID=y;ddNz`tk!&#!221eLY_(0@0-J%i6 z9mj9q2tr-9^$qCxWu`rIc=X6-Z;8rwj~=EdPYasd#uR>ViRkDX8;HZ1aG<4f0<`^w z)HThNSK6TGH=Wh$;}0qedv3ZlJFG@OHBd3^5Tfx|fPlTW3)7{DREzUuew;2y5oquG z{g$DPa#Gl?$N7P3 zXPgpAZ;sl+eq69}4T=58VvuLZ%@v1Y?iJtL#Vu*Rh8Ul7Hd@fa1&}Fhib_+h3s2Ea z%><*dWGP#L*qqlp-04I?BTo()sVc@YMV!c%dosd0I`W2mrx}@VYjFedxl-&tL3XZU zboh2Xryv4n(iMgExl@*;;TYCJF!eN-%JV)Ii*JvCDtSZQ*3aZ2g|A*|6E>S3f2>@J zL)XUZn4h?Rt8^xf__b^{eyY&T)zaWYp)a0lW<&tM@TVT4WiQPn%%4gh8sPRCRyE9= z9c@&-I9f+dtdrOI=?Mj_88{8pcSK{ZIp4du!lVE|u+BrT6M zp8!!@{>jRIT)5FEUK-Xrw@6wOmOm5t2ew{UsC+cEnXlc+PpxZPB9-IeQPH|Dd9`nY zp`C3lu7t0Q06OHTjfxh=PoFk_V!Uj;cog5b=xp?pkjr(6hpOqIt~Ns z-1VJN#gpT0r@mT!6>v}vh@%wo9(n_W|2-I1mO@C{tVEof4qHL#kao6XhcW^n?v-}k zWFn%XRcB>D=!BAW8R$E4E&-W?*g6Jw*!U0oPf8n270$Ot`ng=XkQiUM!LV-Ga$$Rd zOIobQ>~C%(&kUlkg$Lhfm(?Q`hhuni$U&#Qx+yK&IY&pXO7a{IvDt`oB=+4t_w;-F zdB~dc>MctG?(oRSd`W3}Xt$lsk*|tHpzxvaIc3Hhu220hb0Rs~#UC@xCdJ`~n?e3l zSE0HVD!lOhr@^IEzEyTaX#ME6v6433xqPWx_1CEsX8s|xY9^%N!>xVq;@%O-#sS(9+7(S+g0X+NjX6j%Bf100g@J1U;kyH|npj+VQ&b)hWgin_(F#gQIDk>|+ z)ly6xt2qnSIv77EK2?oDsbYfoo&2k%O)a0qc>WA!17w2mo*XsX5f)@nEnF&a&drxM zwf=&IdApvO^knvRxX0Til32Dt!o0SV6?J3mJFm^dVuLl|g`8P_lU{3Hp_0iH4dl`> zs7lxCAHUp`f#_z=)2L545GzK^cia!o90&Vv6aU~t zn8d$c%TQktAtrL12M*}PlAV4e1gDRX{KIZzoT%5-W}vq6Rl?Jx=L}Ql4mav( zdHB$wx8ou9d8gYYjVuNgY5ivPFL~DsXztSlvqpDt(G;|>><~J^PBX+p5<3&j9CI8M z`_lwnOE&)8AfE7=itavUKsD52!md)l0VChHOF9x6@bqgWi9x8r6 zmza;_$1vcpt7JhBtr<03e$jC4iY{1kmn`e(Qnfc3r!7TlC%ygH{CM0K-iU`voV+Ht z={Us>B@O?oJU89PO)sh}ljQSHNuEOMp&b9)BtT5|?bF#FJ|JXuFB8GQe?*O>0NH#8 z4te^)JAWD+2=@h%^`Fv&-hzq6TX-r;4(NMw(>Lw31|u3 z`Iyg7I~~aH>6KsFiLiFkQCJ6;?Z?G4ts6qK?H`ya=Nm-uJ4j_|)V}Q!1X#85HV!VC z=yX*LuJ0WjziOgOnwnp%p%a;-8@VoTa*RCNaJlTnX7Vu8_?z-6LWCZcD;;m%YO?e* zBeEfNH>REUo_v*Uii0+le*6y4Nai28q@=wCRM~(;X47_L-U@q zkFqKxoeb6s?-yRVrfhFLrJ-Ip`JR`5Mq495#7UU1`mGyPN~>(OGOvem6;BE)hbQHX zPMsT*vz6D*UVMqUuN5GpgmhbywCgnzvFhRil;^J@8eK%;9X{TrNEt@x;PMZvl)LL> zT-%gMPc-yi8p;c1+Mx*?_=y6Ag{w&zf2O2cP5|2Ld726$mQ0?9Cn{?c5hS2}OWg(A z_1nB>jP6KMec@xrs`j3vf0$XE{dr)mzegAFT)NIu;vh(H z!b$MH@A_m1_OX&_FzXCsK;TYhOkOi4l0P-)5Sbviz8es|Ww?>vO^#y%iQVHIlX+U_ zLj1RL7XL#&E;p@w?6Tbjga&bjZ$P*h$3P^ZD?NT6t%M%oXb%+?WyQniauxmVKX)5` zxpHwuf`b4S4BZqQmMTvaGq5v`@IXYRxX$LIcUBMa(Xb?rzvDHf>K8?+o%1Dg|&sv=hZ;e&obp<}bSE4S)x(~8e`TK$`f=$wf z&fPl6lQ`E0OrGJ96;a+vAOet|V|AxoY9_|BZi~-pFP(LQ-#{JHSE~_<2vr;SM=_c| zn}gL$bz@O~PGi=Og%>}XiLYkMlBDQLqj91;^g%9jH_`$hY0WK;$}NtP)+2spga;*Y ziMW5t%x4rL`kB3_;JgD>L5ilXK@!oo795bIAupcYekx3R5sS()Pq44crqeS*8J{+{ zxENa8u|7F@BSjj%=g@1^@x_9bo#LbuK}`yt_XzfVdKhw^w z)}nGb!noU+0)pJ8`GG>VD*{cRVP}ESm`_2d@v)FJjs-I z&?Q4_PxpGbwz06R0`m0!D(GRyezkjetd{S8APgYS35XxbV0p6Op!zfK*8Xz2=UCr| zL5w28y3y=)bLQPk;?uj&1XFqNb5>xWN!WLv7;hIe0AfFIbf~n-LMx~Q1N~)g1OfzW zsTPbrFSlS(md#WjMK5aa9z?0KY-mx~G(yX>`WcknUm{d{`8E$mnQ$UxI60Cd&U~P~ zsjDA)4!w$@9c|ohvrPPnI58z+(cDxebfPya5mRj|ob`Jo{}Vscp`=_~_vS~r=jX0A z>%@T}DSI`q(0E%rKW3~WRe865lY@;1jypuQX-qfLLK7xya6K@{6t9^u-tS7;Ye*A>tcwZeKVMzGl&LX8xHS zTmDQ6VHjnEB#BjfP9ABF2!D|S9mJBAXW#q%`^8JjQeaEYE*(+n0oK;7_D@I z2VUw?+06hQ-hwEl4q21siznWq$0rDd!&|;Q>kY@>|CL8@6j2c3C=>{RvQ<7~?l7yk-3LB#7Kv6uN`0gm zNjR&vuS<<&tIOl5y2Ie^j=yk;!1IVm4rIOmG;w4bku`4gYIPbxxuA1Z=c5`eT00ZdyDyRvzR^SDenSPIvhm; zu>xLWrXXQr&%e&D1@Ejwbj(JT?=j<3o`L%(*xL-FJO6#1 zYDDZ0a%wJ}V3(WZMkx(L`w_#`W?}Ev1#5z!)fpu&ZANbQ>`4qtI24XTgts&h-WTey zfvOxY2qw5W`YMe3Q&=qXLT4}3t3VfUkC&tuNdDRk%_TEawWe7^UA zc79G4O316_#5aFTy*<}TMEPJ#=|xGeaPODBI){7t0{SjEBN8}LNR{k3*J zRnl5>ZN?cT50-#++rE!jV#GN5-UCFgh3V*SqOg6a~kE|laeG+IC9NHjV0_f`Jm3xa{0ElMgHdY5!hz-2wq9w>l2+~cYWjam|)~z51Bw2k{W>Ke6Jf@=Gm{)(7U=`b3F8@vbU2L#p**gr9PEgY2a5QWQX zG8IV*n{#MC`D*Uy#v9e{ye@oeHIK9PkO6IPB3FEX0IXHOeHe)NRo58P6@Uu0h*`uq zR4H7!_z$3%l6m7#4IZp?j^RP{@No)0p7y@}$a_BxHydM}we8}`K{_We{)Q&FHi#(P z`}c~Dp8OswWaUyKr}9h`!6=}32UPZ$XvNo+Q+Zt@IqMECWuYvh4Sjv-)WH?hg4f5F zzTI?kZx}2m$;D|>4iLffvpVdvgoEA=&jGP#W^3+bw58~~x`7_Mm5%K5y7dIvh zj|GRso2$Lq`g5TQ{Cok;0$RVnFODS2=hMMpx6aHYlo7!P8j0svgy;Bh1>0_!>=!2) zR{RXQhzoD57iYI7yIoS(oZs3@l4x}jUo<8>uS}UvJyz5ff&n|tD~@`O?}O#dj(=Ml zvaZHW0{soHcl;h30`dg$6_+aNV|7xC{kJP$_~m_7>(U)*D7TG2!}$Jxrz6`%ys*Aj}M6g08r+G;8<{}M7NMfX9C|i zAo&j$jZVR!7)a*e)#(lg9dzPHLfmybRSH^(9xpI^1bYLQS3IK$8(_JQBxyH)Gm18H{Z1_+7sp!##V9 z;&>TMVLp9m_#lk`F<-n*+bOISUkHF@nl#VeiJO99G`x2#diwPl;c)C@bj9VX*RtgQN=K`j9^VOmejb$k0|WX-M-Iw$>|p-Pb@Of3 z7~JRxn;%8n7CONh2M@*9ZJX0oM6B=l{emtYqCFUh4mll#_ZWXvvN|oQ zs_z=#J`zl0SHWBRm!&h%$x=GWCu;~72!uc1JXM{ zWgJ_*AdRdk#({KGRvTU03lYY)?(e!c1GGTg3PB)@N+d163b*3$b*&cnPuCA?Vr{uF!TGK%hzA^{DLs*d}20q01b~Pw@(0oWlL94JroE7rG;vY8yswa=<^2I@t@w z8l2N*T*SIm|Aax}-@3d-n+qtZbPP9lUI~JZg+R4*RT4=$elMDZ4ZH;uTE z0#XNQ65rCBjjJ&7eRcKp?y8Mba@+Rs?rk`25yp+G12p8e3k_!lQI0#Pj!i8q+Sgxs z6C|#dZP8M`T4eXWH$Vi-xWKU_F7kc>d%?hncSXGS=oTzZrNdXf-#OX3Eioo9AWYu~a|5)a-jVd}Gn@D?e1w zD75Iw-2OmYC*tq+xfQIl_;M znVaktHt+{^)sylCb_wP}Lt%;GC6R0f;vA`bH>L;aZcgvH!MMs#k=LF#6L!uL9%9*F zls>G8R8=&%Wqj)nad5~Ug3_{t!nY|j+R&LHdb2iC?%+6V5AovoplkYyn$-jzc1$E3 zXcolNLut6y)CAC(isrN1v~+YB41?O;3&kHXN(H{F_PqidmftBMk6CX_GOmK`p%-n~wJO z(HmnGO#P=>Sy>)KTH>#AmtR)uz^DPrWXjtKf{*=9%flIC{|Ejb+*aG|CFcY<=8BvE zqUpZ4Gv+HLxmlLb(lXh%3-0K3?z?xD!6galkf5TACW>VrtP&U;V?Djl&^L^ zUZx>j>F~pqgXx!fv5!_2Eh?;t?rX9R)=m`J|8lFyV@N#ivc~b2Y^{D#Fw zy~hX>N}6=5o3s|BuC)I}dE;A2ACfUQLLFuBD1HJjh>gR=LCjSDD|MmlOpqnQ^^a}6 z_;;|^iUHo8l&#GPggQhFlHr7OV(xdh=E3MTen5C29!7xN5SCK5?V_(>fs@FJ&m@1_<815TXObzDs;*U?s> zu1PIiua|bc@E9jsPe&ygLA=K+-O48$vr)j%JyY^z@QOQSj0C6A-lS-2uzs%#H`VF@ zAs>#}S`=nqrrdG8UI;4DOq~bm?I3Xc>0cW;1S1HLZPY0nC{GKkklh-2$24>F8cCDXz10Y}4TM3RdGvo-AoM9fD{?#Gx6NXFXv1IPnvHR3Sy z7|D6!w}2_V5T4A)T+h_%1sTxmJjAfV2qtX1V(4mw1bcYY>z_`4d}*3+i`DRyZs^fa ziqiwWot}m&Zv}wFxqv(R981GVWclADz%-Z + +int main(int argc, char** argv) { + ::testing::InitGoogleTest(&argc, argv); + int ret = RUN_ALL_TESTS(); + return ret; +} diff --git a/sysid/src/test/native/cpp/analysis/AnalysisTypeTest.cpp b/sysid/src/test/native/cpp/analysis/AnalysisTypeTest.cpp new file mode 100644 index 00000000000..0abb2a1e9cc --- /dev/null +++ b/sysid/src/test/native/cpp/analysis/AnalysisTypeTest.cpp @@ -0,0 +1,18 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include + +#include "sysid/analysis/AnalysisType.h" + +TEST(AnalysisTypeTest, FromName) { + EXPECT_EQ(sysid::analysis::kDrivetrain, + sysid::analysis::FromName("Drivetrain")); + EXPECT_EQ(sysid::analysis::kDrivetrainAngular, + sysid::analysis::FromName("Drivetrain (Angular)")); + EXPECT_EQ(sysid::analysis::kElevator, sysid::analysis::FromName("Elevator")); + EXPECT_EQ(sysid::analysis::kArm, sysid::analysis::FromName("Arm")); + EXPECT_EQ(sysid::analysis::kSimple, sysid::analysis::FromName("Simple")); + EXPECT_EQ(sysid::analysis::kSimple, sysid::analysis::FromName("Random")); +} diff --git a/sysid/src/test/native/cpp/analysis/FeedbackAnalysisTest.cpp b/sysid/src/test/native/cpp/analysis/FeedbackAnalysisTest.cpp new file mode 100644 index 00000000000..44f664c800d --- /dev/null +++ b/sysid/src/test/native/cpp/analysis/FeedbackAnalysisTest.cpp @@ -0,0 +1,105 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include + +#include "sysid/analysis/FeedbackAnalysis.h" +#include "sysid/analysis/FeedbackControllerPreset.h" + +TEST(FeedbackAnalysisTest, Velocity1) { + auto Kv = 3.060; + auto Ka = 0.327; + + sysid::LQRParameters params{1, 1.5, 7}; + + auto [Kp, Kd] = sysid::CalculateVelocityFeedbackGains( + sysid::presets::kDefault, params, Kv, Ka); + + EXPECT_NEAR(Kp, 2.11, 0.05); + EXPECT_NEAR(Kd, 0.00, 0.05); +} + +TEST(FeedbackAnalysisTest, Velocity2) { + auto Kv = 0.0693; + auto Ka = 0.1170; + + sysid::LQRParameters params{1, 1.5, 7}; + + auto [Kp, Kd] = sysid::CalculateVelocityFeedbackGains( + sysid::presets::kDefault, params, Kv, Ka); + + EXPECT_NEAR(Kp, 3.11, 0.05); + EXPECT_NEAR(Kd, 0.00, 0.05); +} + +TEST(FeedbackAnalysisTest, VelocityConversion) { + auto Kv = 0.0693; + auto Ka = 0.1170; + + sysid::LQRParameters params{1, 1.5, 7}; + + auto [Kp, Kd] = sysid::CalculateVelocityFeedbackGains( + sysid::presets::kDefault, params, Kv, Ka, 3.0 * 1023); + + // This should have the same Kp as the test above, but scaled by a factor of 3 + // * 1023. + EXPECT_NEAR(Kp, 3.11 / (3 * 1023), 0.005); + EXPECT_NEAR(Kd, 0.00, 0.05); +} + +TEST(FeedbackAnalysisTest, VelocityCTRE) { + auto Kv = 1.97; + auto Ka = 0.179; + + sysid::LQRParameters params{1, 1.5, 7}; + + auto [Kp, Kd] = sysid::CalculateVelocityFeedbackGains( + sysid::presets::kCTRECANCoder, params, Kv, Ka); + + EXPECT_NEAR(Kp, 0.000417, 0.00005); + EXPECT_NEAR(Kd, 0.00, 0.05); +} + +TEST(FeedbackAnalysisTest, VelocityCTREConversion) { + auto Kv = 1.97; + auto Ka = 0.179; + + sysid::LQRParameters params{1, 1.5, 7}; + + auto [Kp, Kd] = sysid::CalculateVelocityFeedbackGains( + sysid::presets::kCTRECANCoder, params, Kv, Ka, 3.0); + + // This should have the same Kp as the test above, but scaled by a factor + // of 3. + EXPECT_NEAR(Kp, 0.000417 / 3, 0.00005); + EXPECT_NEAR(Kd, 0.00, 0.05); +} + +TEST(FeedbackAnalysisTest, VelocityREV) { + auto Kv = 1.97; + auto Ka = 0.179; + + sysid::LQRParameters params{1, 1.5, 7}; + + auto [Kp, Kd] = sysid::CalculateVelocityFeedbackGains( + sysid::presets::kREVNEOBuiltIn, params, Kv, Ka); + + EXPECT_NEAR(Kp, 0.00241, 0.005); + EXPECT_NEAR(Kd, 0.00, 0.05); +} + +TEST(FeedbackAnalysisTest, VelocityREVConversion) { + auto Kv = 1.97; + auto Ka = 0.179; + + sysid::LQRParameters params{1, 1.5, 7}; + + auto [Kp, Kd] = sysid::CalculateVelocityFeedbackGains( + sysid::presets::kREVNEOBuiltIn, params, Kv, Ka, 3.0); + + // This should have the same Kp as the test above, but scaled by a factor + // of 3. + EXPECT_NEAR(Kp, 0.00241 / 3, 0.005); + EXPECT_NEAR(Kd, 0.00, 0.05); +} diff --git a/sysid/src/test/native/cpp/analysis/FeedforwardAnalysisTest.cpp b/sysid/src/test/native/cpp/analysis/FeedforwardAnalysisTest.cpp new file mode 100644 index 00000000000..a52840d620d --- /dev/null +++ b/sysid/src/test/native/cpp/analysis/FeedforwardAnalysisTest.cpp @@ -0,0 +1,251 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include + +#include +#include +#include + +#include "sysid/analysis/AnalysisManager.h" +#include "sysid/analysis/ArmSim.h" +#include "sysid/analysis/ElevatorSim.h" +#include "sysid/analysis/FeedforwardAnalysis.h" +#include "sysid/analysis/SimpleMotorSim.h" + +/** + * Return simulated test data for a given simulation model. + * + * @param Ks Static friction gain. + * @param Kv Velocity gain. + * @param Ka Acceleration gain. + * @param Kg Gravity cosine gain. + */ +template +sysid::Storage CollectData(Model& model) { + constexpr auto kUstep = 0.25_V / 1_s; + constexpr units::volt_t kUmax = 7_V; + constexpr units::second_t T = 5_ms; + constexpr units::second_t kTestDuration = 5_s; + + sysid::Storage storage; + auto& [slowForward, slowBackward, fastForward, fastBackward] = storage; + + // Slow forward test + auto voltage = 0_V; + for (int i = 0; i < (kTestDuration / T).value(); ++i) { + slowForward.emplace_back(sysid::PreparedData{ + i * T, voltage.value(), model.GetPosition(), model.GetVelocity(), T, + model.GetAcceleration(voltage), std::cos(model.GetPosition()), + std::sin(model.GetPosition())}); + + model.Update(voltage, T); + voltage += kUstep * T; + } + + // Slow backward test + model.Reset(); + voltage = 0_V; + for (int i = 0; i < (kTestDuration / T).value(); ++i) { + slowBackward.emplace_back(sysid::PreparedData{ + i * T, voltage.value(), model.GetPosition(), model.GetVelocity(), T, + model.GetAcceleration(voltage), std::cos(model.GetPosition()), + std::sin(model.GetPosition())}); + + model.Update(voltage, T); + voltage -= kUstep * T; + } + + // Fast forward test + model.Reset(); + voltage = 0_V; + for (int i = 0; i < (kTestDuration / T).value(); ++i) { + fastForward.emplace_back(sysid::PreparedData{ + i * T, voltage.value(), model.GetPosition(), model.GetVelocity(), T, + model.GetAcceleration(voltage), std::cos(model.GetPosition()), + std::sin(model.GetPosition())}); + + model.Update(voltage, T); + voltage = kUmax; + } + + // Fast backward test + model.Reset(); + voltage = 0_V; + for (int i = 0; i < (kTestDuration / T).value(); ++i) { + fastBackward.emplace_back(sysid::PreparedData{ + i * T, voltage.value(), model.GetPosition(), model.GetVelocity(), T, + model.GetAcceleration(voltage), std::cos(model.GetPosition()), + std::sin(model.GetPosition())}); + + model.Update(voltage, T); + voltage = -kUmax; + } + + return storage; +} + +TEST(FeedforwardAnalysisTest, Arm1) { + constexpr double Ks = 1.01; + constexpr double Kv = 3.060; + constexpr double Ka = 0.327; + constexpr double Kg = 0.211; + + for (const auto& offset : {-2.0, -1.0, 0.0, 1.0, 2.0}) { + sysid::ArmSim model{Ks, Kv, Ka, Kg, offset}; + auto ff = sysid::CalculateFeedforwardGains(CollectData(model), + sysid::analysis::kArm); + auto& gains = std::get<0>(ff); + + EXPECT_NEAR(gains[0], Ks, 0.003); + EXPECT_NEAR(gains[1], Kv, 0.003); + EXPECT_NEAR(gains[2], Ka, 0.003); + EXPECT_NEAR(gains[3], Kg, 0.003); + EXPECT_NEAR(gains[4], offset, 0.007); + } +} + +TEST(FeedforwardAnalysisTest, Arm2) { + constexpr double Ks = 0.547; + constexpr double Kv = 0.0693; + constexpr double Ka = 0.1170; + constexpr double Kg = 0.122; + + for (const auto& offset : {-2.0, -1.0, 0.0, 1.0, 2.0}) { + sysid::ArmSim model{Ks, Kv, Ka, Kg, offset}; + auto ff = sysid::CalculateFeedforwardGains(CollectData(model), + sysid::analysis::kArm); + auto& gains = std::get<0>(ff); + + EXPECT_NEAR(gains[0], Ks, 0.003); + EXPECT_NEAR(gains[1], Kv, 0.003); + EXPECT_NEAR(gains[2], Ka, 0.003); + EXPECT_NEAR(gains[3], Kg, 0.003); + EXPECT_NEAR(gains[4], offset, 0.007); + } +} + +TEST(FeedforwardAnalysisTest, Drivetrain1) { + constexpr double Ks = 1.01; + constexpr double Kv = 3.060; + constexpr double Ka = 0.327; + + sysid::SimpleMotorSim model{Ks, Kv, Ka}; + auto ff = sysid::CalculateFeedforwardGains(CollectData(model), + sysid::analysis::kDrivetrain); + auto& gains = std::get<0>(ff); + + EXPECT_NEAR(gains[0], Ks, 0.003); + EXPECT_NEAR(gains[1], Kv, 0.003); + EXPECT_NEAR(gains[2], Ka, 0.003); +} + +TEST(FeedforwardAnalysisTest, Drivetrain2) { + constexpr double Ks = 0.547; + constexpr double Kv = 0.0693; + constexpr double Ka = 0.1170; + + sysid::SimpleMotorSim model{Ks, Kv, Ka}; + auto ff = sysid::CalculateFeedforwardGains(CollectData(model), + sysid::analysis::kDrivetrain); + auto& gains = std::get<0>(ff); + + EXPECT_NEAR(gains[0], Ks, 0.003); + EXPECT_NEAR(gains[1], Kv, 0.003); + EXPECT_NEAR(gains[2], Ka, 0.003); +} + +TEST(FeedforwardAnalysisTest, DrivetrainAngular1) { + constexpr double Ks = 1.01; + constexpr double Kv = 3.060; + constexpr double Ka = 0.327; + + sysid::SimpleMotorSim model{Ks, Kv, Ka}; + auto ff = sysid::CalculateFeedforwardGains( + CollectData(model), sysid::analysis::kDrivetrainAngular); + auto& gains = std::get<0>(ff); + + EXPECT_NEAR(gains[0], Ks, 0.003); + EXPECT_NEAR(gains[1], Kv, 0.003); + EXPECT_NEAR(gains[2], Ka, 0.003); +} + +TEST(FeedforwardAnalysisTest, DrivetrainAngular2) { + constexpr double Ks = 0.547; + constexpr double Kv = 0.0693; + constexpr double Ka = 0.1170; + + sysid::SimpleMotorSim model{Ks, Kv, Ka}; + auto ff = sysid::CalculateFeedforwardGains( + CollectData(model), sysid::analysis::kDrivetrainAngular); + auto& gains = std::get<0>(ff); + + EXPECT_NEAR(gains[0], Ks, 0.003); + EXPECT_NEAR(gains[1], Kv, 0.003); + EXPECT_NEAR(gains[2], Ka, 0.003); +} + +TEST(FeedforwardAnalysisTest, Elevator1) { + constexpr double Ks = 1.01; + constexpr double Kv = 3.060; + constexpr double Ka = 0.327; + constexpr double Kg = -0.211; + + sysid::ElevatorSim model{Ks, Kv, Ka, Kg}; + auto ff = sysid::CalculateFeedforwardGains(CollectData(model), + sysid::analysis::kElevator); + auto& gains = std::get<0>(ff); + + EXPECT_NEAR(gains[0], Ks, 0.003); + EXPECT_NEAR(gains[1], Kv, 0.003); + EXPECT_NEAR(gains[2], Ka, 0.003); + EXPECT_NEAR(gains[3], Kg, 0.003); +} + +TEST(FeedforwardAnalysisTest, Elevator2) { + constexpr double Ks = 0.547; + constexpr double Kv = 0.0693; + constexpr double Ka = 0.1170; + constexpr double Kg = -0.122; + + sysid::ElevatorSim model{Ks, Kv, Ka, Kg}; + auto ff = sysid::CalculateFeedforwardGains(CollectData(model), + sysid::analysis::kElevator); + auto& gains = std::get<0>(ff); + + EXPECT_NEAR(gains[0], Ks, 0.003); + EXPECT_NEAR(gains[1], Kv, 0.003); + EXPECT_NEAR(gains[2], Ka, 0.003); + EXPECT_NEAR(gains[3], Kg, 0.003); +} + +TEST(FeedforwardAnalysisTest, Simple1) { + constexpr double Ks = 1.01; + constexpr double Kv = 3.060; + constexpr double Ka = 0.327; + + sysid::SimpleMotorSim model{Ks, Kv, Ka}; + auto ff = sysid::CalculateFeedforwardGains(CollectData(model), + sysid::analysis::kSimple); + auto& gains = std::get<0>(ff); + + EXPECT_NEAR(gains[0], Ks, 0.003); + EXPECT_NEAR(gains[1], Kv, 0.003); + EXPECT_NEAR(gains[2], Ka, 0.003); +} + +TEST(FeedforwardAnalysisTest, Simple2) { + constexpr double Ks = 0.547; + constexpr double Kv = 0.0693; + constexpr double Ka = 0.1170; + + sysid::SimpleMotorSim model{Ks, Kv, Ka}; + auto ff = sysid::CalculateFeedforwardGains(CollectData(model), + sysid::analysis::kSimple); + auto& gains = std::get<0>(ff); + + EXPECT_NEAR(gains[0], Ks, 0.003); + EXPECT_NEAR(gains[1], Kv, 0.003); + EXPECT_NEAR(gains[2], Ka, 0.003); +} diff --git a/sysid/src/test/native/cpp/analysis/FilterTest.cpp b/sysid/src/test/native/cpp/analysis/FilterTest.cpp new file mode 100644 index 00000000000..a7b03492747 --- /dev/null +++ b/sysid/src/test/native/cpp/analysis/FilterTest.cpp @@ -0,0 +1,170 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include +#include +#include + +#include + +#include "sysid/analysis/AnalysisManager.h" +#include "sysid/analysis/FeedforwardAnalysis.h" +#include "sysid/analysis/FilteringUtils.h" +#include "sysid/analysis/Storage.h" + +TEST(FilterTest, MedianFilter) { + std::vector testData{ + sysid::PreparedData{0_s, 0, 0, 0}, sysid::PreparedData{0_s, 0, 0, 1}, + sysid::PreparedData{0_s, 0, 0, 10}, sysid::PreparedData{0_s, 0, 0, 5}, + sysid::PreparedData{0_s, 0, 0, 3}, sysid::PreparedData{0_s, 0, 0, 0}, + sysid::PreparedData{0_s, 0, 0, 1000}, sysid::PreparedData{0_s, 0, 0, 7}, + sysid::PreparedData{0_s, 0, 0, 6}, sysid::PreparedData{0_s, 0, 0, 5}}; + std::vector expectedData{ + sysid::PreparedData{0_s, 0, 0, 0}, sysid::PreparedData{0_s, 0, 0, 1}, + sysid::PreparedData{0_s, 0, 0, 5}, sysid::PreparedData{0_s, 0, 0, 5}, + sysid::PreparedData{0_s, 0, 0, 3}, sysid::PreparedData{0_s, 0, 0, 3}, + sysid::PreparedData{0_s, 0, 0, 7}, sysid::PreparedData{0_s, 0, 0, 7}, + sysid::PreparedData{0_s, 0, 0, 6}, sysid::PreparedData{0_s, 0, 0, 5}}; + + sysid::ApplyMedianFilter(&testData, 3); + EXPECT_EQ(expectedData, testData); +} + +TEST(FilterTest, NoiseFloor) { + std::vector testData = { + {0_s, 1, 2, 3, 5_ms, 0, 0}, {1_s, 1, 2, 3, 5_ms, 1, 0}, + {2_s, 1, 2, 3, 5_ms, 2, 0}, {3_s, 1, 2, 3, 5_ms, 5, 0}, + {4_s, 1, 2, 3, 5_ms, 0.35, 0}, {5_s, 1, 2, 3, 5_ms, 0.15, 0}, + {6_s, 1, 2, 3, 5_ms, 0, 0}, {7_s, 1, 2, 3, 5_ms, 0.02, 0}, + {8_s, 1, 2, 3, 5_ms, 0.01, 0}, {9_s, 1, 2, 3, 5_ms, 0, 0}}; + double noiseFloor = + GetNoiseFloor(testData, 2, [](auto&& pt) { return pt.acceleration; }); + EXPECT_NEAR(0.953, noiseFloor, 0.001); +} + +TEST(FilterTest, StepTrim) { + std::vector testData = { + {0_s, 1, 2, 3, 5_ms, 0, 0}, {1_s, 1, 2, 3, 5_ms, 0.25, 0}, + {2_s, 1, 2, 3, 5_ms, 0.5, 0}, {3_s, 1, 2, 3, 5_ms, 0.45, 0}, + {4_s, 1, 2, 3, 5_ms, 0.35, 0}, {5_s, 1, 2, 3, 5_ms, 0.15, 0}, + {6_s, 1, 2, 3, 5_ms, 0, 0}, {7_s, 1, 2, 3, 5_ms, 0.02, 0}, + {8_s, 1, 2, 3, 5_ms, 0.01, 0}, {9_s, 1, 2, 3, 5_ms, 0, 0}, + }; + + std::vector expectedData = { + {2_s, 1, 2, 3, 5_ms, 0.5, 0}, + {3_s, 1, 2, 3, 5_ms, 0.45, 0}, + {4_s, 1, 2, 3, 5_ms, 0.35, 0}, + {5_s, 1, 2, 3, 5_ms, 0.15, 0}}; + + auto maxTime = 9_s; + auto minTime = maxTime; + + sysid::AnalysisManager::Settings settings; + auto [tempMinTime, positionDelay, velocityDelay] = + sysid::TrimStepVoltageData(&testData, &settings, minTime, maxTime); + minTime = tempMinTime; + + EXPECT_EQ(expectedData[0].acceleration, testData[0].acceleration); + EXPECT_EQ(expectedData.back().acceleration, testData.back().acceleration); + EXPECT_EQ(5, settings.stepTestDuration.value()); + EXPECT_EQ(2, minTime.value()); +} + +template +void AssertCentralResults(F&& f, DfDx&& dfdx, units::second_t h, double min, + double max) { + static_assert(Samples % 2 != 0, "Number of samples must be odd."); + + auto filter = sysid::CentralFiniteDifference(h); + + for (int i = min / h.value(); i < max / h.value(); ++i) { + // Let filter initialize + if (i < static_cast(min / h.value()) + Samples) { + filter.Calculate(f(i * h.value())); + continue; + } + + // For central finite difference, the derivative computed at this point is + // half the window size in the past. + // The order of accuracy is O(h^(N - d)) where N is number of stencil + // points and d is order of derivative + EXPECT_NEAR(dfdx((i - static_cast((Samples - 1) / 2)) * h.value()), + filter.Calculate(f(i * h.value())), + std::pow(h.value(), Samples - Derivative)); + } +} + +/** + * Test central finite difference. + */ +TEST(LinearFilterOutputTest, CentralFiniteDifference) { + constexpr auto h = 5_ms; + + AssertCentralResults<1, 3>( + [](double x) { + // f(x) = x² + return x * x; + }, + [](double x) { + // df/dx = 2x + return 2.0 * x; + }, + h, -20.0, 20.0); + + AssertCentralResults<1, 3>( + [](double x) { + // f(x) = std::sin(x) + return std::sin(x); + }, + [](double x) { + // df/dx = std::cos(x) + return std::cos(x); + }, + h, -20.0, 20.0); + + AssertCentralResults<1, 3>( + [](double x) { + // f(x) = ln(x) + return std::log(x); + }, + [](double x) { + // df/dx = 1 / x + return 1.0 / x; + }, + h, 1.0, 20.0); + + AssertCentralResults<2, 5>( + [](double x) { + // f(x) = x^2 + return x * x; + }, + [](double x) { + // d²f/dx² = 2 + return 2.0; + }, + h, -20.0, 20.0); + + AssertCentralResults<2, 5>( + [](double x) { + // f(x) = std::sin(x) + return std::sin(x); + }, + [](double x) { + // d²f/dx² = -std::sin(x) + return -std::sin(x); + }, + h, -20.0, 20.0); + + AssertCentralResults<2, 5>( + [](double x) { + // f(x) = ln(x) + return std::log(x); + }, + [](double x) { + // d²f/dx² = -1 / x² + return -1.0 / (x * x); + }, + h, 1.0, 20.0); +} diff --git a/sysid/src/test/native/cpp/analysis/OLSTest.cpp b/sysid/src/test/native/cpp/analysis/OLSTest.cpp new file mode 100644 index 00000000000..bf205165a93 --- /dev/null +++ b/sysid/src/test/native/cpp/analysis/OLSTest.cpp @@ -0,0 +1,42 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include + +#include "sysid/analysis/OLS.h" + +TEST(OLSTest, TwoVariablesTwoPoints) { + // (1, 3) and (2, 5). Should produce y = 2x + 1. + Eigen::MatrixXd X{{1.0, 1.0}, {1.0, 2.0}}; + Eigen::VectorXd y{{3.0}, {5.0}}; + + auto [coefficients, cod, rmse] = sysid::OLS(X, y); + EXPECT_EQ(coefficients.size(), 2u); + + EXPECT_NEAR(coefficients[0], 1.0, 0.05); + EXPECT_NEAR(coefficients[1], 2.0, 0.05); + EXPECT_NEAR(cod, 1.0, 1E-4); +} + +TEST(OLSTest, TwoVariablesFivePoints) { + // (2, 4), (3, 5), (5, 7), (7, 10), (9, 15) + // Should produce 1.518x + 0.305. + Eigen::MatrixXd X{{1, 2}, {1, 3}, {1, 5}, {1, 7}, {1, 9}}; + Eigen::VectorXd y{{4}, {5}, {7}, {10}, {15}}; + + auto [coefficients, cod, rmse] = sysid::OLS(X, y); + EXPECT_EQ(coefficients.size(), 2u); + + EXPECT_NEAR(coefficients[0], 0.305, 0.05); + EXPECT_NEAR(coefficients[1], 1.518, 0.05); + EXPECT_NEAR(cod, 0.985, 0.05); +} + +#ifndef NDEBUG +TEST(OLSTest, MalformedData) { + Eigen::MatrixXd X{{1, 2}, {1, 3}, {1, 4}}; + Eigen::VectorXd y{{4}, {5}}; + EXPECT_DEATH(sysid::OLS(X, y), ""); +} +#endif diff --git a/sysid/src/test/native/cpp/analysis/TrackWidthAnalysisTest.cpp b/sysid/src/test/native/cpp/analysis/TrackWidthAnalysisTest.cpp new file mode 100644 index 00000000000..e7b662fe9d0 --- /dev/null +++ b/sysid/src/test/native/cpp/analysis/TrackWidthAnalysisTest.cpp @@ -0,0 +1,12 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include + +#include "sysid/analysis/TrackWidthAnalysis.h" + +TEST(TrackWidthAnalysisTest, Calculate) { + double result = sysid::CalculateTrackWidth(-0.5386, 0.5386, 90_deg); + EXPECT_NEAR(result, 0.6858, 1E-4); +}