From e6ed86954342c0132717184905917d08015984b6 Mon Sep 17 00:00:00 2001 From: treyra Date: Mon, 29 Jul 2024 01:53:39 -0700 Subject: [PATCH] First commit --- .github/workflows/pylint.yml | 46 + .gitignore | 38 + .vscode/launch.json | 28 + .vscode/settings.json | 19 + LICENSE | 5 + failurePy/__init__.py | 0 failurePy/config/binaryFaultModelExample.yaml | 115 ++ .../figure5/binaryAdverseCrashCourse.yaml | 91 ++ .../binaryAdverseCrashCourseBaselines.yaml | 86 ++ .../figure5/binaryProximityOperations.yaml | 75 + .../binaryProximityOperationsBaselines.yaml | 70 + .../figure5/generalAdverseCrashCourse.yaml | 150 ++ .../generalAdverseCrashCourseBaselines.yaml | 151 ++ .../figure5/generalProximityOperations.yaml | 150 ++ .../generalProximityOperationsBaselines.yaml | 151 ++ .../figureS3/binaryRandomCrashCourse.yaml | 75 + .../binaryRandomCrashCourseBaselines.yaml | 70 + .../figureS3/generalRandomCrashCourse.yaml | 118 ++ .../generalRandomCrashCourseBaselines.yaml | 105 ++ .../config/generalFaultModelExample.yaml | 131 ++ failurePy/config/qualitativeExperiment.yaml | 122 ++ failurePy/estimators/__init__.py | 0 failurePy/estimators/beliefInitialization.py | 71 + .../conservativeMarginalizedFilter.py | 98 ++ .../extendedKalmanFilterLinearSensing.py | 183 +++ ...cobianExtendedKalmanFilterLinearSensing.py | 212 +++ failurePy/estimators/generalFaultSampling.py | 254 ++++ failurePy/estimators/kalmanFilter.py | 193 +++ failurePy/estimators/kalmanFilterCommon.py | 143 ++ failurePy/estimators/marginalizedFilter.py | 95 ++ failurePy/estimators/unscentedKalmanFilter.py | 18 + failurePy/load/__init__.py | 0 failurePy/load/estimatorConstructors.py | 238 ++++ failurePy/load/packageLoader.py | 34 + failurePy/load/safetyLoader.py | 264 ++++ failurePy/load/solverConstructors.py | 381 +++++ failurePy/load/systemConstructors.py | 290 ++++ failurePy/load/yamlHardwareLoader.py | 27 + failurePy/load/yamlLoader.py | 570 ++++++++ failurePy/load/yamlLoaderUtilityMethods.py | 281 ++++ failurePy/models/__init__.py | 0 failurePy/models/linearModel.py | 300 ++++ failurePy/models/linearModelGeneralFaults.py | 200 +++ failurePy/models/modelsCommon.py | 72 + failurePy/models/threeDOFGeneralFaultModel.py | 344 +++++ failurePy/models/threeDOFModel.py | 652 +++++++++ failurePy/pipeline.py | 846 +++++++++++ failurePy/realTimePipeline.py | 473 +++++++ failurePy/rewards/__init__.py | 0 failurePy/rewards/safetyConstraint.py | 780 +++++++++++ .../rewards/squareSumFailureBeliefReward.py | 32 + failurePy/solvers/__init__.py | 0 failurePy/solvers/cbf.py | 176 +++ failurePy/solvers/greedy.py | 129 ++ failurePy/solvers/preSpecifiedPolicy.py | 160 +++ failurePy/solvers/randomPolicy.py | 80 ++ failurePy/solvers/realTimeSFEAST.py | 182 +++ failurePy/solvers/sFEAST.py | 587 ++++++++ failurePy/solvers/scp.py | 690 +++++++++ failurePy/utility/__init__.py | 0 failurePy/utility/binaryVisualization.py | 80 ++ failurePy/utility/comb.py | 25 + failurePy/utility/compareData.py | 78 ++ failurePy/utility/computeAlternateReward.py | 155 ++ failurePy/utility/computePartialTrial.py | 193 +++ failurePy/utility/computeSuccessAtEnd.py | 58 + failurePy/utility/dataAnalysisFunctions.py | 937 +++++++++++++ failurePy/utility/legacyPaperCode.py | 43 + failurePy/utility/pipelineHelperMethods.py | 340 +++++ failurePy/utility/reprocessData.py | 341 +++++ failurePy/utility/savedTreeRemover.py | 43 + failurePy/utility/saving.py | 558 ++++++++ failurePy/utility/smoothStep.py | 25 + failurePy/utility/tqdmMultiprocessing.py | 73 + failurePy/visualization/__init__.py | 0 .../visualization/figure5andFigureS3.ipynb | 408 ++++++ failurePy/visualization/figuresS1andS2.ipynb | 358 +++++ .../oneDimensionalBeliefVisulaization.py | 346 +++++ failurePy/visualization/renderBeliefVideo.py | 197 +++ failurePy/visualization/renderPlanarVis.py | 725 ++++++++++ .../renderPlanarVisGeneralFault.py | 449 ++++++ .../visualization/renderPlanarVisWrapper.py | 640 +++++++++ failurePy/visualization/renderSavedRun.py | 52 + failurePy/visualization/videoMaker.py | 108 ++ failurePy/visualization/visualization.py | 1241 +++++++++++++++++ .../visualizationUtilityFunctions.py | 71 + install.sh | 1 + readme.md | 79 ++ setup.py | 26 + 89 files changed, 18501 insertions(+) create mode 100644 .github/workflows/pylint.yml create mode 100644 .gitignore create mode 100644 .vscode/launch.json create mode 100644 .vscode/settings.json create mode 100644 LICENSE create mode 100644 failurePy/__init__.py create mode 100644 failurePy/config/binaryFaultModelExample.yaml create mode 100644 failurePy/config/figure5/binaryAdverseCrashCourse.yaml create mode 100644 failurePy/config/figure5/binaryAdverseCrashCourseBaselines.yaml create mode 100644 failurePy/config/figure5/binaryProximityOperations.yaml create mode 100644 failurePy/config/figure5/binaryProximityOperationsBaselines.yaml create mode 100644 failurePy/config/figure5/generalAdverseCrashCourse.yaml create mode 100644 failurePy/config/figure5/generalAdverseCrashCourseBaselines.yaml create mode 100644 failurePy/config/figure5/generalProximityOperations.yaml create mode 100644 failurePy/config/figure5/generalProximityOperationsBaselines.yaml create mode 100644 failurePy/config/figureS3/binaryRandomCrashCourse.yaml create mode 100644 failurePy/config/figureS3/binaryRandomCrashCourseBaselines.yaml create mode 100644 failurePy/config/figureS3/generalRandomCrashCourse.yaml create mode 100644 failurePy/config/figureS3/generalRandomCrashCourseBaselines.yaml create mode 100644 failurePy/config/generalFaultModelExample.yaml create mode 100644 failurePy/config/qualitativeExperiment.yaml create mode 100644 failurePy/estimators/__init__.py create mode 100644 failurePy/estimators/beliefInitialization.py create mode 100644 failurePy/estimators/conservativeMarginalizedFilter.py create mode 100644 failurePy/estimators/extendedKalmanFilterLinearSensing.py create mode 100644 failurePy/estimators/firstEstimatesJacobianExtendedKalmanFilterLinearSensing.py create mode 100644 failurePy/estimators/generalFaultSampling.py create mode 100644 failurePy/estimators/kalmanFilter.py create mode 100644 failurePy/estimators/kalmanFilterCommon.py create mode 100644 failurePy/estimators/marginalizedFilter.py create mode 100644 failurePy/estimators/unscentedKalmanFilter.py create mode 100644 failurePy/load/__init__.py create mode 100644 failurePy/load/estimatorConstructors.py create mode 100644 failurePy/load/packageLoader.py create mode 100644 failurePy/load/safetyLoader.py create mode 100644 failurePy/load/solverConstructors.py create mode 100644 failurePy/load/systemConstructors.py create mode 100644 failurePy/load/yamlHardwareLoader.py create mode 100644 failurePy/load/yamlLoader.py create mode 100644 failurePy/load/yamlLoaderUtilityMethods.py create mode 100644 failurePy/models/__init__.py create mode 100644 failurePy/models/linearModel.py create mode 100644 failurePy/models/linearModelGeneralFaults.py create mode 100644 failurePy/models/modelsCommon.py create mode 100644 failurePy/models/threeDOFGeneralFaultModel.py create mode 100644 failurePy/models/threeDOFModel.py create mode 100644 failurePy/pipeline.py create mode 100644 failurePy/realTimePipeline.py create mode 100644 failurePy/rewards/__init__.py create mode 100644 failurePy/rewards/safetyConstraint.py create mode 100644 failurePy/rewards/squareSumFailureBeliefReward.py create mode 100644 failurePy/solvers/__init__.py create mode 100644 failurePy/solvers/cbf.py create mode 100644 failurePy/solvers/greedy.py create mode 100644 failurePy/solvers/preSpecifiedPolicy.py create mode 100644 failurePy/solvers/randomPolicy.py create mode 100644 failurePy/solvers/realTimeSFEAST.py create mode 100644 failurePy/solvers/sFEAST.py create mode 100644 failurePy/solvers/scp.py create mode 100644 failurePy/utility/__init__.py create mode 100644 failurePy/utility/binaryVisualization.py create mode 100644 failurePy/utility/comb.py create mode 100644 failurePy/utility/compareData.py create mode 100644 failurePy/utility/computeAlternateReward.py create mode 100644 failurePy/utility/computePartialTrial.py create mode 100644 failurePy/utility/computeSuccessAtEnd.py create mode 100644 failurePy/utility/dataAnalysisFunctions.py create mode 100644 failurePy/utility/legacyPaperCode.py create mode 100644 failurePy/utility/pipelineHelperMethods.py create mode 100644 failurePy/utility/reprocessData.py create mode 100644 failurePy/utility/savedTreeRemover.py create mode 100644 failurePy/utility/saving.py create mode 100644 failurePy/utility/smoothStep.py create mode 100644 failurePy/utility/tqdmMultiprocessing.py create mode 100644 failurePy/visualization/__init__.py create mode 100644 failurePy/visualization/figure5andFigureS3.ipynb create mode 100644 failurePy/visualization/figuresS1andS2.ipynb create mode 100644 failurePy/visualization/oneDimensionalBeliefVisulaization.py create mode 100644 failurePy/visualization/renderBeliefVideo.py create mode 100644 failurePy/visualization/renderPlanarVis.py create mode 100644 failurePy/visualization/renderPlanarVisGeneralFault.py create mode 100644 failurePy/visualization/renderPlanarVisWrapper.py create mode 100644 failurePy/visualization/renderSavedRun.py create mode 100644 failurePy/visualization/videoMaker.py create mode 100644 failurePy/visualization/visualization.py create mode 100644 failurePy/visualization/visualizationUtilityFunctions.py create mode 100644 install.sh create mode 100644 readme.md create mode 100644 setup.py diff --git a/.github/workflows/pylint.yml b/.github/workflows/pylint.yml new file mode 100644 index 0000000..2ebbd15 --- /dev/null +++ b/.github/workflows/pylint.yml @@ -0,0 +1,46 @@ +name: Pylint + +on: [push] + +jobs: + build: + runs-on: ubuntu-20.04 + strategy: + matrix: + python-version: ["3.8"] + steps: + - uses: actions/checkout@v3 + - name: Set up Python ${{ matrix.python-version }} + uses: actions/setup-python@v3 + with: + python-version: ${{ matrix.python-version }} + #Current changes from default are: camelCase (preference), line length 100 -> 200 (wide monitors and preference), + #Regex to make variable names 3-40 characters, gives hint + #Removed i,j,k,ex,Run,_ as good names. Added dt and ax, as they are widely used and universal in python. + #import-error disabled (since running on github we assume the user will set up their environment) + #too-many-arguments disabled for now (consider refactoring later to have more compact parameter passing, currently think it is fine) + #Same with too-many-function-args + #too-many-locals disabled for now (consider refactoring later along with less arguments, as the lead to each other. Currently think it is fine) + #ignored-argument-names used as a hack for dummy arguments for now. + - name: Install dependencies and configure + run: | + python -m pip install --upgrade pip + pip install pylint + pylint --generate-rcfile > ~/.pylintrc + sed -i 's/snake_case/camelCase/g' ~/.pylintrc + sed -i 's/max-line-length=100/max-line-length=200/g' ~/.pylintrc + sed -i 's/good-names-rgxs=/good-names-rgxs=[a-z_][a-z0-9_]{2,40}/g' ~/.pylintrc + sed -i 's/include-naming-hint=no/include-naming-hint=yes/g' ~/.pylintrc + sed -i 's/good-names=i,/good-names=dt,ax,iii,/g' ~/.pylintrc + sed -i 's/ j,/ jjj,/g' ~/.pylintrc + sed -i 's/ k,/ kkk,/g' ~/.pylintrc + sed -i 's/ ex,/ exx,/g' ~/.pylintrc + sed -i 's/ Run,/ run,/g' ~/.pylintrc + sed -i 's/ _/ iii/g' ~/.pylintrc + sed -i 's/ j,/ jjj,/g' ~/.pylintrc + sed -i 's/bad-names=/bad-names=i,j,k,/g' ~/.pylintrc + sed -i 's/disable=/disable=import-error,too-many-arguments,too-many-function-args,too-many-locals,duplicate-code,/g' ~/.pylintrc + sed -i 's/ignored-argument-names=_.*|^ignored_|^unused_/ignored-argument-names=_.*|^ignored_|^unused_|dummy/g' ~/.pylintrc + - name: Analyzing the code with pylint + run: | + pylint $(git ls-files '*.py') diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..d958a36 --- /dev/null +++ b/.gitignore @@ -0,0 +1,38 @@ +SavedData/* +*/SavedData/* + +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +installNoiseTesting.sh +*.swp +failurePy/utility/CalibrationData/* +*checkpoint.ipynb +failurePy/utility/test.ipynb +failurePy/visualization/.ipynb_checkpoints/FTC Paper Visualization-checkpoint.ipynb + +failurePy/visualization/*.pdf +failurePy.egg-info/* +dFailurePy.egg-info/* +.config/config.yml +.config/hosts.yml +failurePy/.DS_Store +failurePy/.config/config.yml +failurePy/.config/hosts.yml +SavedData/* +*/SavedData/* + +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +installNoiseTesting.sh +*.swp +failurePy/utility/CalibrationData/* +*checkpoint.ipynb +failurePy/utility/test.ipynb +failurePy/visualization/.ipynb_checkpoints/FTC Paper Visualization-checkpoint.ipynb + +failurePy/visualization/*.pdf +failurePy.egg-info/* +dFailurePy.egg-info/* +*.DS_Store diff --git a/.vscode/launch.json b/.vscode/launch.json new file mode 100644 index 0000000..0e90b38 --- /dev/null +++ b/.vscode/launch.json @@ -0,0 +1,28 @@ +{ + // Use IntelliSense to learn about possible attributes. + // Hover to view descriptions of existing attributes. + // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 + "version": "0.2.0", + "configurations": [ + { + "name": "Python: Pipeline", + "type": "python", + "request": "launch", + "program": "failurePy/pipeline.py", + "justMyCode": false, + //"cwd": "failurePy", + "args": [ + //"--configFilePath", + "./failurePy/config/safetyNonLinearModelTest4.yaml" + ] + } + //{ + // "name": "Python: Remove Tree Data", + // "type": "python", + // "request": "launch", + // "program": "utility/savedTreeRemover.py", + // "justMyCode": false, + // "cwd": "failurePy" + //} + ] +} diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 0000000..16920b0 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,19 @@ +{ + "python.analysis.diagnosticSeverityOverrides": { //Disable rerportMissingImports, as VS Code seems to miss local imports (and because using VS code in windows and conda env in WSL seems to be cause missed imports too) + "reportMissingImports": "none", + "reportMissingModuleSource": "none", + "todohighlight.keywords": [ + "DEBUG:", + ], + }, + "cSpell.words": [ + "argnames", + "edgecolor", + "fejekf", + "fejkalman", + "fontsize""horizontalalignment", + "Labbe", + "pcov" + ], + "python.REPL.enableREPLSmartSend": false +} diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..c530270 --- /dev/null +++ b/LICENSE @@ -0,0 +1,5 @@ +Copyright 2024 James Ragan. + +The data and code here are for personal and educational use only and provided without warranty; written permission from the authors is required for further use. Please cite our work when the article is published. + +FilterPy library adapted under MIT license, copyright 2014-2018 Roger R Labbe Jr. Full license in readme.md located here http://github.com/rlabbe/filterpy diff --git a/failurePy/__init__.py b/failurePy/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/failurePy/config/binaryFaultModelExample.yaml b/failurePy/config/binaryFaultModelExample.yaml new file mode 100644 index 0000000..009d2ae --- /dev/null +++ b/failurePy/config/binaryFaultModelExample.yaml @@ -0,0 +1,115 @@ +#Example showing our binary fault model under an averse fault like the simulations shown in our paper. +#Initiate experiment by running "python pipeline.py ./config/binaryFaultModelExample.yaml" in the failurePy directory +nSimulationsPerTree: #This is a list of simulation levels to run + - 200 + +nTrialsPerPoint: 1 #How many times to repeat each experiment configuration + +dim: 3 +linear: False +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: .4 +discretization: .125 +dt: 1 + +numWheels: 2 +providedFailure: #1 indicates nominal, 0 indicates failure + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 0 + - 0 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 # Actions are selected randomly, but same for every trial + +#Not letting simulation break early to enforce safety over full experiment +diagnosisThreshold: 1.1 +nMaxComponentFailures: 3 + +initialState: + - 0 + - 0 + - 0 #Giving 10 time steps until collision + - -1 + - 0 + - 0 + - 0 + - 0 + +nExperimentSteps: 15 #Didn't see any noticeable changes with more time steps, so less to run faster + +solverFList: + - sFEAST + #- cbf #Baseline methods, to use, note "nSimulationsPerTree" must be 1 + #- greedy + #- scp + +estimator: marginalizedFilter +physicalStateSubEstimator: ekf #Required sub filter if using marginal filter +reward: squareSumFailureBeliefReward + +safetyMethod: safetyConstrainedReward +safetyFunctionEvaluation: chebyshev +allowableFailureChance: .10 +safetyFunction: worstCase +safetyConstraints: #Should be nested list, constraint, and parameters + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + #- - circularSafeZoneConstraint + # - - 30 #Radius (Currently safe zone - s/c radius) + # - - 0 #center x + # - 0 #center y + #Square constraint, normal matrix, offset + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 + +saveDirectoryPath: binaryExample +clobber: True #Overwrites data when true! + +nMaxPossibleFailures: 40 + +#Plotting config +plottingExtent: 30 +resolution: 100 + +generalFaultFlag: False + +particleResampleType: gaussian +particleResampleCheck: never +particleInitializationFunction: biasedRandomRedundant #Biased to 1/2 chance to be nominal, biases repeated x5 + +saveTreeFlag: True #Visualizes the tree search, but this must be disabled when running more than one trial, as it produces a lot of data + +multiprocessingFlag: False #To enable multiprocessing (useful when running any trials per point), type a number to represent how many CPU cores should NOT be used by failurePy. Note this can have undefined behavior if more cores are provided than trials are run +discountFactor: 1 diff --git a/failurePy/config/figure5/binaryAdverseCrashCourse.yaml b/failurePy/config/figure5/binaryAdverseCrashCourse.yaml new file mode 100644 index 0000000..36b8681 --- /dev/null +++ b/failurePy/config/figure5/binaryAdverseCrashCourse.yaml @@ -0,0 +1,91 @@ +nSimulationsPerTree: + - 0 + #- 20 + - 80 + - 200 + - 600 + #- 1000 + - 2000 +nTrialsPerPoint: 1 +dim: 3 +linear: false +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: 0.4 +discretization: 0.125 +dt: 1 +nExperimentSteps: 15 +saveTrajectory: true +providedFailure: + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 0 + - 0 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 +diagnosisThreshold: 1.9 +nMaxComponentFailures: 3 +initialState: + - 0 + - 0 + - 0 + - -1 + - 0 + - 0 + - 0 + - 0 +solverFList: + - SFEAST +estimator: marginalizedFilter +physicalStateSubEstimator: ekf +reward: squareSumFailureBeliefReward +safetyMethod: safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev +allowableFailureChance: 0.1 +safetyFunction: worstCase +safetyConstraints: + - - circularObstacleConstraint + - - 10 + - - 0 + - -20 + - - linearSafeZoneConstraint + - - - - 1 + - 0 + - - -1 + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 + - 25 + - 25 + - 25 +saveDirectoryPath: figure5/binaryAdverseCrashCourse +clobber: false +nMaxPossibleFailures: 40 +saveTreeFlag: false +multiprocessingFlag: 10 +plottingExtent: 30 +resolution: 400 +hardwareEmulationFlag: false +filterDivergenceHandlingMethod: acceptDiagnosisBeforeNan +discountFactor: 1 diff --git a/failurePy/config/figure5/binaryAdverseCrashCourseBaselines.yaml b/failurePy/config/figure5/binaryAdverseCrashCourseBaselines.yaml new file mode 100644 index 0000000..f7ba8e2 --- /dev/null +++ b/failurePy/config/figure5/binaryAdverseCrashCourseBaselines.yaml @@ -0,0 +1,86 @@ +nSimulationsPerTree: + - 1 +nTrialsPerPoint: 1000 +dim: 3 +linear: false +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: 0.4 +discretization: 0.125 +dt: 1 +nExperimentSteps: 15 +saveTrajectory: true +providedFailure: + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 0 + - 0 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 +diagnosisThreshold: 1.9 +nMaxComponentFailures: 3 +initialState: + - 0 + - 0 + - 0 + - -1 + - 0 + - 0 + - 0 + - 0 +solverFList: + - cbf + - greedy + - scp +estimator: marginalizedFilter +physicalStateSubEstimator: ekf +reward: squareSumFailureBeliefReward +safetyMethod: safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev +allowableFailureChance: 0.1 +safetyFunction: worstCase +safetyConstraints: + - - circularObstacleConstraint + - - 10 + - - 0 + - -20 + - - linearSafeZoneConstraint + - - - - 1 + - 0 + - - -1 + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 + - 25 + - 25 + - 25 +saveDirectoryPath: figure5/binaryAdverseCrashCourseBaselines +clobber: false +nMaxPossibleFailures: 40 +saveTreeFlag: false +multiprocessingFlag: 112 +plottingExtent: 30 +resolution: 400 +hardwareEmulationFlag: false +filterDivergenceHandlingMethod: acceptDiagnosisBeforeNan diff --git a/failurePy/config/figure5/binaryProximityOperations.yaml b/failurePy/config/figure5/binaryProximityOperations.yaml new file mode 100644 index 0000000..31ee1e4 --- /dev/null +++ b/failurePy/config/figure5/binaryProximityOperations.yaml @@ -0,0 +1,75 @@ +nSimulationsPerTree: + - 0 + #- 20 + - 80 + - 200 + - 600 + #- 1000 + - 2000 +nTrialsPerPoint: 1000 +dim: 3 +linear: false +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: 0.4 +discretization: 0.125 +dt: 1 +nExperimentSteps: 15 +saveTrajectory: true +providedFailure: null +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 +diagnosisThreshold: 1.9 +nMaxComponentFailures: 3 +initialState: + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 +solverFList: + - SFEAST +estimator: marginalizedFilter +physicalStateSubEstimator: ekf +reward: squareSumFailureBeliefReward +safetyMethod: safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev +allowableFailureChance: 0.1 +safetyFunction: worstCase +safetyConstraints: + - - circularObstacleConstraint + - - 10 + - - 0 + - -20 + - - linearSafeZoneConstraint + - - - - 1 + - 0 + - - -1 + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 + - 25 + - 25 + - 25 +saveDirectoryPath: figure5/binaryProximityOperations +clobber: false +nMaxPossibleFailures: 40 +saveTreeFlag: false +multiprocessingFlag: 10 +plottingExtent: 30 +resolution: 400 +hardwareEmulationFlag: false +filterDivergenceHandlingMethod: acceptDiagnosisBeforeNan +discountFactor: 1 diff --git a/failurePy/config/figure5/binaryProximityOperationsBaselines.yaml b/failurePy/config/figure5/binaryProximityOperationsBaselines.yaml new file mode 100644 index 0000000..a087788 --- /dev/null +++ b/failurePy/config/figure5/binaryProximityOperationsBaselines.yaml @@ -0,0 +1,70 @@ +nSimulationsPerTree: + - 1 +nTrialsPerPoint: 1000 +dim: 3 +linear: false +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: 0.4 +discretization: 0.125 +dt: 1 +nExperimentSteps: 15 +saveTrajectory: true +providedFailure: null +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 +diagnosisThreshold: 1.9 +nMaxComponentFailures: 3 +initialState: + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 +solverFList: + - cbf + - greedy + - scp +estimator: marginalizedFilter +physicalStateSubEstimator: ekf +reward: squareSumFailureBeliefReward +safetyMethod: safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev +allowableFailureChance: 0.1 +safetyFunction: worstCase +safetyConstraints: + - - circularObstacleConstraint + - - 10 + - - 0 + - -20 + - - linearSafeZoneConstraint + - - - - 1 + - 0 + - - -1 + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 + - 25 + - 25 + - 25 +saveDirectoryPath: figure5/binaryProximityOperationsBaselines +clobber: false +nMaxPossibleFailures: 40 +saveTreeFlag: false +multiprocessingFlag: 33 +plottingExtent: 30 +resolution: 400 +hardwareEmulationFlag: false +filterDivergenceHandlingMethod: acceptDiagnosisBeforeNan diff --git a/failurePy/config/figure5/generalAdverseCrashCourse.yaml b/failurePy/config/figure5/generalAdverseCrashCourse.yaml new file mode 100644 index 0000000..0f329ca --- /dev/null +++ b/failurePy/config/figure5/generalAdverseCrashCourse.yaml @@ -0,0 +1,150 @@ +nSimulationsPerTree: + - 0 + #- 20 #Not plotting + #- 50 + - 80 + #- 100 + - 200 + #- 400 + - 600 + #- 1000 #Not Plotting + - 2000 + #- 4000 + #- 1 +nTrialsPerPoint: 1000 + +dim: 3 +linear: False #This means we just take our simple linear model +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: .4 +discretization: .125 +dt: 1 + +numWheels: 2 +providedFailure: #Note 0 is good now, 1 bad + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 + - 0.8 #Double +y failure, mostly failed + - 0.8 + - 0 + - 0 #End of actuator Degradation + - 0 + - 0 + - 0 + - 0 + - .1 #Double -y bias + - .1 + - 0 + - 0 + - 0 + - 0 #End of actuator bias + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 #End of sensor degradation + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 + +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 # For now actions are selected randomly, but same for every trial + +#Not letting it break early to enforce safety over full experiment +diagnosisThreshold: 1.1 +nMaxComponentFailures: 3 + +#initialState: #Roughly what I'm trying to do in sim (note, we're going to have to define a coordinate system in s/c sim so comet is consistently placed) +# - 4 +# - -0.5 +# - 0 +# - 0 +# - 0 +# - 0 + +initialState: + - 0 + - 0 + - 0 #Giving 10 time steps + - -1 + - 0 + - 0 + - 0 + - 0 + +nExperimentSteps: 15 #Didn't see any noticeable changes with more time steps, so less to run faster + +saveTrajectory: True #Think we'll just always have this as true + +solverFList: + - SFEAST + #- cbf + #- greedy + #- scp + +estimator: marginalizedFilter +physicalStateSubEstimator: ekf #Required sub filter if using marginal filter +reward: squareSumFailureBeliefReward + +safetyMethod: safetyConstrainedReward #safetyOff #safetyPenalizedReward #safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev #probabilisticAlpha #Testing non-proven safety +allowableFailureChance: .10 +safetyFunction: worstCase +safetyConstraints: #Should be nested list, constraint, and parameters + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + #- - circularSafeZoneConstraint + # - - 30 #Radius (Currently safe zone - s/c radius) + # - - 0 #center x + # - 0 #center y + #Square constraint, normal matrix, offset + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 + +saveDirectoryPath: figure5/generalAdverseCrashCourse +clobber: False + +nMaxPossibleFailures: 40 + +#Plotting config +plottingExtent: 30 +resolution: 100 + +generalFaultFlag: True + +particleResampleType: gaussian +particleResampleCheck: never +particleInitializationFunction: biasedRandomRedundant #Biased to 1/2 chance to be nominal, biases repeated x5 + +saveTreeFlag: False + +multiprocessingFlag: 10 +discountFactor: 1 diff --git a/failurePy/config/figure5/generalAdverseCrashCourseBaselines.yaml b/failurePy/config/figure5/generalAdverseCrashCourseBaselines.yaml new file mode 100644 index 0000000..2f1daf7 --- /dev/null +++ b/failurePy/config/figure5/generalAdverseCrashCourseBaselines.yaml @@ -0,0 +1,151 @@ +#Yaml file to test the linear model experiment parameter loading + +nSimulationsPerTree: + #- 0 + #- 20 + ##- 50 + #- 80 + ##- 100 + #- 200 + ##- 400 + #- 600 + #- 1000 + #- 2000 + ##- 4000 + - 1 +nTrialsPerPoint: 1000 + +dim: 3 +linear: False #This means we just take our simple linear model +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: .4 +discretization: .125 +dt: 1 + +numWheels: 2 +providedFailure: #Note 0 is good now, 1 bad + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 + - 0.8 #Double +y failure, mostly failed + - 0.8 + - 0 + - 0 #End of actuator Degradation + - 0 + - 0 + - 0 + - 0 + - .1 #Double -y bias + - .1 + - 0 + - 0 + - 0 + - 0 #End of actuator bias + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 #End of sensor degradation + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 + +maxNumActions: 20 +rngKeysOffset: 100 +actionRNGSeed: 0 # For now actions are selected randomly, but same for every trial + +#Not letting it break early to enforce safety over full experiment +diagnosisThreshold: 1.1 +nMaxComponentFailures: 3 + +#initialState: #Roughly what I'm trying to do in sim (note, we're going to have to define a coordinate system in s/c sim so comet is consistently placed) +# - 4 +# - -0.5 +# - 0 +# - 0 +# - 0 +# - 0 + +initialState: + - 0 + - 0 + - 0 #Giving 10 time steps + - -1 + - 0 + - 0 + - 0 + - 0 + +nExperimentSteps: 15 #Didn't see any noticeable changes with more time steps, so less to run faster + +saveTrajectory: True #Think we'll just always have this as true + +solverFList: + #- POMCPMF + - cbf + - greedy + - scp + +estimator: marginalizedFilter +physicalStateSubEstimator: ekf #Required sub filter if using marginal filter +reward: squareSumFailureBeliefReward + +safetyMethod: safetyConstrainedReward #safetyOff #safetyPenalizedReward #safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev #probabilisticAlpha #Testing non-proven safety +allowableFailureChance: .10 +safetyFunction: worstCase +safetyConstraints: #Should be nested list, constraint, and parameters + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + #- - circularSafeZoneConstraint + # - - 30 #Radius (Currently safe zone - s/c radius) + # - - 0 #center x + # - 0 #center y + #Square constraint, normal matrix, offset + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 + +saveDirectoryPath: figure5/generalAdverseCrashCourseBaselines +clobber: False + +nMaxPossibleFailures: 40 + +#Plotting config +plottingExtent: 30 +resolution: 100 + +generalFaultFlag: True + +particleResampleType: gaussian +particleResampleCheck: never +particleInitializationFunction: biasedRandomRedundant #Biased to 1/2 chance to be nominal, biases repeated x5 + +saveTreeFlag: False + +multiprocessingFlag: 28 diff --git a/failurePy/config/figure5/generalProximityOperations.yaml b/failurePy/config/figure5/generalProximityOperations.yaml new file mode 100644 index 0000000..d0a157e --- /dev/null +++ b/failurePy/config/figure5/generalProximityOperations.yaml @@ -0,0 +1,150 @@ +nSimulationsPerTree: + - 0 + #- 20 #Not plotting + #- 50 + - 80 + #- 100 + - 200 + #- 400 + - 600 + #- 1000 #Not Plotting + - 2000 + #- 4000 + #- 1 +nTrialsPerPoint: 1000 + +dim: 3 +linear: False #This means we just take our simple linear model +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: .4 +discretization: .125 +dt: 1 + +#numWheels: 2 +#providedFailure: #Note 0 is good now, 1 bad +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 +# - 0.8 #Double +y failure, mostly failed +# - 0.8 +# - 0 +# - 0 #End of actuator Degradation +# - 0 +# - 0 +# - 0 +# - 0 +# - .1 #Double -y bias +# - .1 +# - 0 +# - 0 +# - 0 +# - 0 #End of actuator bias +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 #End of sensor degradation +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 + +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 # For now actions are selected randomly, but same for every trial + +#Not letting it break early to enforce safety over full experiment +diagnosisThreshold: 1.1 +nMaxComponentFailures: 3 + +#initialState: #Roughly what I'm trying to do in sim (note, we're going to have to define a coordinate system in s/c sim so comet is consistently placed) +# - 4 +# - -0.5 +# - 0 +# - 0 +# - 0 +# - 0 + +#initialState: +# - 0 +# - 0 +# - 0 #Giving 10 time steps +# - -1 +# - 0 +# - 0 +# - 0 +# - 0 + +nExperimentSteps: 15 #Didn't see any noticeable changes with more time steps, so less to run faster + +saveTrajectory: True #Think we'll just always have this as true + +solverFList: + - SFEAST + #- cbf + #- greedy + #- scp + +estimator: marginalizedFilter +physicalStateSubEstimator: ekf #Required sub filter if using marginal filter +reward: squareSumFailureBeliefReward + +safetyMethod: safetyConstrainedReward #safetyOff #safetyPenalizedReward #safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev #probabilisticAlpha #Testing non-proven safety +allowableFailureChance: .10 +safetyFunction: worstCase +safetyConstraints: #Should be nested list, constraint, and parameters + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + #- - circularSafeZoneConstraint + # - - 30 #Radius (Currently safe zone - s/c radius) + # - - 0 #center x + # - 0 #center y + #Square constraint, normal matrix, offset + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 + +saveDirectoryPath: figure5/generalProximityOperations +clobber: False + +nMaxPossibleFailures: 40 + +#Plotting config +plottingExtent: 30 +resolution: 100 + +generalFaultFlag: True + +particleResampleType: gaussian +particleResampleCheck: never +particleInitializationFunction: biasedRandomRedundant #Biased to 1/2 chance to be nominal, biases repeated x5 + +saveTreeFlag: False + +multiprocessingFlag: 10 +discountFactor: 1 diff --git a/failurePy/config/figure5/generalProximityOperationsBaselines.yaml b/failurePy/config/figure5/generalProximityOperationsBaselines.yaml new file mode 100644 index 0000000..a71adca --- /dev/null +++ b/failurePy/config/figure5/generalProximityOperationsBaselines.yaml @@ -0,0 +1,151 @@ +#Yaml file to test the linear model experiment parameter loading + +nSimulationsPerTree: + #- 0 + #- 20 + ##- 50 + #- 80 + ##- 100 + #- 200 + ##- 400 + #- 600 + #- 1000 + #- 2000 + ##- 4000 + - 1 +nTrialsPerPoint: 1000 + +dim: 3 +linear: False #This means we just take our simple linear model +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: .4 +discretization: .125 +dt: 1 + +#numWheels: 2 +#providedFailure: #Note 0 is good now, 1 bad +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 +# - 0.8 #Double +y failure, mostly failed +# - 0.8 +# - 0 +# - 0 #End of actuator Degradation +# - 0 +# - 0 +# - 0 +# - 0 +# - .1 #Double -y bias +# - .1 +# - 0 +# - 0 +# - 0 +# - 0 #End of actuator bias +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 #End of sensor degradation +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 +# - 0 + +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 # For now actions are selected randomly, but same for every trial + +#Not letting it break early to enforce safety over full experiment +diagnosisThreshold: 1.1 +nMaxComponentFailures: 3 + +#initialState: #Roughly what I'm trying to do in sim (note, we're going to have to define a coordinate system in s/c sim so comet is consistently placed) +# - 4 +# - -0.5 +# - 0 +# - 0 +# - 0 +# - 0 + +#initialState: +# - 0 +# - 0 +# - 0 #Giving 10 time steps +# - -1 +# - 0 +# - 0 +# - 0 +# - 0 + +nExperimentSteps: 15 #Didn't see any noticeable changes with more time steps, so less to run faster + +saveTrajectory: True #Think we'll just always have this as true + +solverFList: + #- POMCPMF + - cbf + - greedy + - scp + +estimator: marginalizedFilter +physicalStateSubEstimator: ekf #Required sub filter if using marginal filter +reward: squareSumFailureBeliefReward + +safetyMethod: safetyConstrainedReward #safetyOff #safetyPenalizedReward #safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev #probabilisticAlpha #Testing non-proven safety +allowableFailureChance: .10 +safetyFunction: worstCase +safetyConstraints: #Should be nested list, constraint, and parameters + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + #- - circularSafeZoneConstraint + # - - 30 #Radius (Currently safe zone - s/c radius) + # - - 0 #center x + # - 0 #center y + #Square constraint, normal matrix, offset + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 + +saveDirectoryPath: figure5/generalProximityOperationsBaselines +clobber: False + +nMaxPossibleFailures: 40 + +#Plotting config +plottingExtent: 30 +resolution: 100 + +generalFaultFlag: True + +particleResampleType: gaussian +particleResampleCheck: never +particleInitializationFunction: biasedRandomRedundant #Biased to 1/2 chance to be nominal, biases repeated x5 + +saveTreeFlag: False + +multiprocessingFlag: 28 diff --git a/failurePy/config/figureS3/binaryRandomCrashCourse.yaml b/failurePy/config/figureS3/binaryRandomCrashCourse.yaml new file mode 100644 index 0000000..173c7e5 --- /dev/null +++ b/failurePy/config/figureS3/binaryRandomCrashCourse.yaml @@ -0,0 +1,75 @@ +nSimulationsPerTree: + - 0 + #- 20 + - 80 + - 200 + - 600 + #- 1000 + - 2000 +nTrialsPerPoint: 1000 +dim: 3 +linear: false +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: 0.4 +discretization: 0.125 +dt: 1 +nExperimentSteps: 15 +saveTrajectory: true +providedFailure: Null +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 +diagnosisThreshold: 1.9 +nMaxComponentFailures: 3 +initialState: + - 0 + - 0 + - 0 + - -1 + - 0 + - 0 + - 0 + - 0 +solverFList: + - SFEAST +estimator: marginalizedFilter +physicalStateSubEstimator: ekf +reward: squareSumFailureBeliefReward +safetyMethod: safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev +allowableFailureChance: 0.1 +safetyFunction: worstCase +safetyConstraints: + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 +saveDirectoryPath: figureS3/binaryRandomCrashCourse +clobber: false +nMaxPossibleFailures: 40 +saveTreeFlag: false +multiprocessingFlag: 10 +plottingExtent: 30 +resolution: 400 +hardwareEmulationFlag: false +filterDivergenceHandlingMethod: acceptDiagnosisBeforeNan +discountFactor: 1 diff --git a/failurePy/config/figureS3/binaryRandomCrashCourseBaselines.yaml b/failurePy/config/figureS3/binaryRandomCrashCourseBaselines.yaml new file mode 100644 index 0000000..6d6deb9 --- /dev/null +++ b/failurePy/config/figureS3/binaryRandomCrashCourseBaselines.yaml @@ -0,0 +1,70 @@ +nSimulationsPerTree: + - 1 +nTrialsPerPoint: 1000 +dim: 3 +linear: false +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: 0.4 +discretization: 0.125 +dt: 1 +nExperimentSteps: 15 +saveTrajectory: true +providedFailure: Null +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 +diagnosisThreshold: 1.9 +nMaxComponentFailures: 3 +initialState: + - 0 + - 0 + - 0 + - -1 + - 0 + - 0 + - 0 + - 0 +solverFList: + - cbf + - greedy + - scp +estimator: marginalizedFilter +physicalStateSubEstimator: ekf +reward: squareSumFailureBeliefReward +safetyMethod: safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev +allowableFailureChance: 0.1 +safetyFunction: worstCase +safetyConstraints: + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 +saveDirectoryPath: figureS3/binaryRandomCrashCourseBaselines +clobber: false +nMaxPossibleFailures: 40 +saveTreeFlag: false +multiprocessingFlag: 10 +plottingExtent: 30 +resolution: 400 +hardwareEmulationFlag: false +filterDivergenceHandlingMethod: acceptDiagnosisBeforeNan diff --git a/failurePy/config/figureS3/generalRandomCrashCourse.yaml b/failurePy/config/figureS3/generalRandomCrashCourse.yaml new file mode 100644 index 0000000..860220e --- /dev/null +++ b/failurePy/config/figureS3/generalRandomCrashCourse.yaml @@ -0,0 +1,118 @@ +nSimulationsPerTree: + - 0 + #- 20 #Not plotting + #- 50 + - 80 + #- 100 + - 200 + #- 400 + - 600 + #- 1000 #Not Plotting + - 2000 + #- 4000 + #- 1 +nTrialsPerPoint: 1000 + +dim: 3 +linear: False #This means we just take our simple linear model +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: .4 +discretization: .125 +dt: 1 + +numWheels: 2 +providedFailure: Null + +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 # For now actions are selected randomly, but same for every trial + +#Not letting it break early to enforce safety over full experiment +diagnosisThreshold: 1.1 +nMaxComponentFailures: 3 + +#initialState: #Roughly what I'm trying to do in sim (note, we're going to have to define a coordinate system in s/c sim so comet is consistently placed) +# - 4 +# - -0.5 +# - 0 +# - 0 +# - 0 +# - 0 + +initialState: + - 0 + - 0 + - 0 #Giving 10 time steps + - -1 + - 0 + - 0 + - 0 + - 0 + +nExperimentSteps: 15 #Didn't see any noticeable changes with more time steps, so less to run faster + +saveTrajectory: True #Think we'll just always have this as true + +solverFList: + - SFEAST + #- cbf + #- greedy + #- scp + +estimator: marginalizedFilter +physicalStateSubEstimator: ekf #Required sub filter if using marginal filter +reward: squareSumFailureBeliefReward + +safetyMethod: safetyConstrainedReward #safetyOff #safetyPenalizedReward #safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev #probabilisticAlpha #Testing non-proven safety +allowableFailureChance: .10 +safetyFunction: worstCase +safetyConstraints: #Should be nested list, constraint, and parameters + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + #- - circularSafeZoneConstraint + # - - 30 #Radius (Currently safe zone - s/c radius) + # - - 0 #center x + # - 0 #center y + #Square constraint, normal matrix, offset + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 + +saveDirectoryPath: figureS3/generalRandomCrashCourse +clobber: False + +nMaxPossibleFailures: 40 + +#Plotting config +plottingExtent: 30 +resolution: 100 + +generalFaultFlag: True + +particleResampleType: gaussian +particleResampleCheck: never +particleInitializationFunction: biasedRandomRedundant #Biased to 1/2 chance to be nominal, biases repeated x5 + +saveTreeFlag: False + +multiprocessingFlag: 10 +discountFactor: 1 diff --git a/failurePy/config/figureS3/generalRandomCrashCourseBaselines.yaml b/failurePy/config/figureS3/generalRandomCrashCourseBaselines.yaml new file mode 100644 index 0000000..e2730eb --- /dev/null +++ b/failurePy/config/figureS3/generalRandomCrashCourseBaselines.yaml @@ -0,0 +1,105 @@ +nSimulationsPerTree: + - 1 +nTrialsPerPoint: 1000 + +dim: 3 +linear: False #This means we just take our simple linear model +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: .4 +discretization: .125 +dt: 1 + +numWheels: 2 +providedFailure: Null + +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 # For now actions are selected randomly, but same for every trial + +#Not letting it break early to enforce safety over full experiment +diagnosisThreshold: 1.1 +nMaxComponentFailures: 3 + +#initialState: #Roughly what I'm trying to do in sim (note, we're going to have to define a coordinate system in s/c sim so comet is consistently placed) +# - 4 +# - -0.5 +# - 0 +# - 0 +# - 0 +# - 0 + +initialState: + - 0 + - 0 + - 0 #Giving 10 time steps + - -1 + - 0 + - 0 + - 0 + - 0 + +nExperimentSteps: 15 #Didn't see any noticeable changes with more time steps, so less to run faster + +saveTrajectory: True #Think we'll just always have this as true + +solverFList: + - cbf + - greedy + - scp + +estimator: marginalizedFilter +physicalStateSubEstimator: ekf #Required sub filter if using marginal filter +reward: squareSumFailureBeliefReward + +safetyMethod: safetyConstrainedReward #safetyOff #safetyPenalizedReward #safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev #probabilisticAlpha #Testing non-proven safety +allowableFailureChance: .10 +safetyFunction: worstCase +safetyConstraints: #Should be nested list, constraint, and parameters + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + #- - circularSafeZoneConstraint + # - - 30 #Radius (Currently safe zone - s/c radius) + # - - 0 #center x + # - 0 #center y + #Square constraint, normal matrix, offset + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 + +saveDirectoryPath: figureS3/generalRandomCrashCourseBaselines +clobber: False + +nMaxPossibleFailures: 40 + +#Plotting config +plottingExtent: 30 +resolution: 100 + +generalFaultFlag: True + +particleResampleType: gaussian +particleResampleCheck: never +particleInitializationFunction: biasedRandomRedundant #Biased to 1/2 chance to be nominal, biases repeated x5 + +saveTreeFlag: False + +multiprocessingFlag: 10 diff --git a/failurePy/config/generalFaultModelExample.yaml b/failurePy/config/generalFaultModelExample.yaml new file mode 100644 index 0000000..079f2bb --- /dev/null +++ b/failurePy/config/generalFaultModelExample.yaml @@ -0,0 +1,131 @@ +#Example showing our general fault model under an averse fault like the simulations shown in our paper. +#Initiate experiment by running "python pipeline.py ./config/generalFaultModelExample.yaml" in the failurePy directory +nSimulationsPerTree: #This is a list of simulation levels to run + - 200 + +nTrialsPerPoint: 1 #How many times to repeat each experiment configuration + +dim: 3 +linear: False +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: .4 +discretization: .125 +dt: 1 + +numWheels: 2 +providedFailure: #Note 0 is nominal, 1 completely degraded or biased + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 + - 0.8 #Double +y failure, mostly failed + - 0.8 + - 0 + - 0 #End of actuator Degradation + - 0 + - 0 + - 0 + - 0 + - .1 #Double -y bias + - .1 + - 0 + - 0 + - 0 + - 0 #End of actuator bias + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 #End of sensor degradation + - 0 + - 0 + - 0 + - 0 + - 0 + - 0 + +maxNumActions: 20 +rngKeysOffset: 0 +actionRNGSeed: 0 # Actions are selected randomly, but same for every trial + +#Not letting simulation break early to enforce safety over full experiment +diagnosisThreshold: 1.1 +nMaxComponentFailures: 3 + +initialState: + - 0 + - 0 + - 0 #Giving 10 time steps until collision + - -1 + - 0 + - 0 + - 0 + - 0 + +nExperimentSteps: 15 #Didn't see any noticeable changes with more time steps, so less to run faster + +solverFList: + - sFEAST + #- cbf #Baseline methods, to use, note "nSimulationsPerTree" must be 1 + #- greedy + #- scp + +estimator: marginalizedFilter +physicalStateSubEstimator: ekf #Required sub filter if using marginal filter +reward: squareSumFailureBeliefReward + +safetyMethod: safetyConstrainedReward +safetyFunctionEvaluation: chebyshev +allowableFailureChance: .10 +safetyFunction: worstCase +safetyConstraints: #Should be nested list, constraint, and parameters + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + #- - circularSafeZoneConstraint + # - - 30 #Radius (Currently safe zone - s/c radius) + # - - 0 #center x + # - 0 #center y + #Square constraint, normal matrix, offset + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 + +saveDirectoryPath: generalExample +clobber: True #Overwrites data when true! + +nMaxPossibleFailures: 40 + +#Plotting config +plottingExtent: 30 +resolution: 100 + +generalFaultFlag: True + +particleResampleType: gaussian +particleResampleCheck: never +particleInitializationFunction: biasedRandomRedundant #Biased to 1/2 chance to be nominal, biases repeated x5 + +saveTreeFlag: True #Visualizes the tree search, but this must be disabled when running more than one trial, as it produces a lot of data + +multiprocessingFlag: False #To enable multiprocessing (useful when running any trials per point), type a number to represent how many CPU cores should NOT be used by failurePy. Note this can have undefined behavior if more cores are provided than trials are run +discountFactor: 1 diff --git a/failurePy/config/qualitativeExperiment.yaml b/failurePy/config/qualitativeExperiment.yaml new file mode 100644 index 0000000..6cc2b28 --- /dev/null +++ b/failurePy/config/qualitativeExperiment.yaml @@ -0,0 +1,122 @@ +nSimulationsPerTree: + #- 0 + #- 20 + #- 50 + #- 80 + #- 100 + - 200 + #- 400 + #- 600 + #- 1000 + #- 2000 + ##- 4000 +nTrialsPerPoint: 1 + +dim: 3 +linear: False #This means we just take our simple linear model +spacecraftMass: 1 +spacecraftMoment: 4 +sigmaW: + - 0.2 + - 0.2 + - 0.01 +sigmaV: .4 +discretization: .125 +dt: 1 + +nExperimentSteps: 15 +saveTrajectory: True #Think we'll just always have this as true +#providedFailure: Null +providedFailure: + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 0 #Double +y failure + - 0 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + - 1 + +maxNumActions: 20 +rngKeysOffset: 1 +actionRNGSeed: 0 # For now actions are selected randomly, but same for every trial + +#Not letting it break early to enforce safety over full experiment +diagnosisThreshold: 1.1 +nMaxComponentFailures: 3 + +#initialState: #Roughly what I'm trying to do in sim (note, we're going to have to define a coordinate system in s/c sim so comet is consistently placed) +# - 4 +# - -0.5 +# - 0 +# - 0 +# - 0 +# - 0 + +initialState: + - 0 + - 0 + - 0 #Giving 10 time steps + - -2 + - 0 + - 0 + - 0 + - 0 + +solverFList: + - SFEAST + +estimator: marginalizedFilter +physicalStateSubEstimator: ekf #Required sub filter if using marginal filter + +reward: squareSumFailureBeliefReward + +safetyMethod: safetyConstrainedReward #safetyOff #safetyPenalizedReward #safetyConstrainedReward +penalty: 0 +safetyFunctionEvaluation: chebyshev #probabilisticAlpha #Testing non-proven safety +allowableFailureChance: .90 +safetyFunction: worstCase +safetyConstraints: #Should be nested list, constraint, and parameters + - - circularObstacleConstraint + - - 10 #Radius (Currently obstacle + s/c radius) + - - 0 #center x + - -20 #center y + - - linearSafeZoneConstraint #Of form Ax - b < 0, need all to be satisfied. Here is is a 60x60 rect around origin + - - - - 1 #First row of A matrix, should be external normals + - 0 + - - -1 #next row of A matrix + - 0 + - - 0 + - 1 + - - 0 + - -1 + - - 25 #First offset + - 25 + - 25 + - 25 + +saveDirectoryPath: safetyOnVisualization +clobber: True + +nMaxPossibleFailures: 40 + +saveTreeFlag: True + +#0 or false to disable +multiprocessingFlag: False + +#Plotting config +plottingExtent: 30 +resolution: 400 + +#Test flag to allow for different behavior when emulating hardware (lowers real noise vs. expected) +hardwareEmulationFlag: False +discountFactor: 1 diff --git a/failurePy/estimators/__init__.py b/failurePy/estimators/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/failurePy/estimators/beliefInitialization.py b/failurePy/estimators/beliefInitialization.py new file mode 100644 index 0000000..e855a45 --- /dev/null +++ b/failurePy/estimators/beliefInitialization.py @@ -0,0 +1,71 @@ +""" +File of belief initialization functions. Currently tailored to each type of belief that needs to be initialized +""" + +import jax.numpy as jnp + +def uniformFailureBeliefMarginalizedKalman(initialPhysicalState,possibleFailures,initialUncertainty=.001): + """ + Creates the initial beliefTuple as narrowly distributed in physical belief about the origin, + and uniform in failure belief. Only valid for marginalized filter with kalman filter + + Parameters + ---------- + initialPhysicalState : array, shape(numState) + Initial state the belief is centered around + possibleFailures : array, shape(nMaxPossibleFailures,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + initialUncertainty : float (default=.001) + Initial state uncertainty magnitude, if any + + + Returns + ------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + """ + + #Make failure weights array + failureWeights = jnp.ones(len(possibleFailures))/len(possibleFailures) + filters = [] + for iFailure in range(len(possibleFailures)): # pylint: disable=unused-variable + #Initialize to small (non-zero) diagonal covariance. Needs to be PD! + #We are using a convention where the filter is a n+1xn array, where the filter[0] = mean, filter[1:] = covariance! + filters.append(jnp.vstack((initialPhysicalState,initialUncertainty* jnp.eye(len(initialPhysicalState))))) + + return (failureWeights,jnp.array(filters)) + + +def uniformFailureBeliefMarginalizedFEJKalman(initialPhysicalState,possibleFailures): + """ + Creates the initial beliefTuple as narrowly distributed in physical belief about the origin, + and uniform in failure belief. Only valid for marginalized filter with FEJ kalman filter, as adds extra row to the end + + Parameters + ---------- + possibleFailures : array, shape(nMaxPossibleFailures,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + + Returns + ------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + """ + + #Make failure weights array + failureWeights = jnp.ones(len(possibleFailures))/len(possibleFailures) + filters = [] + for iFailure in range(len(possibleFailures)): # pylint: disable=unused-variable + #Initialize to small (non-zero) diagonal covariance. Needs to be PD! + #We are using a convention where the filter is a n+1xn array, where the filter[0] = mean, filter[1:-1] = covariance, filter[-1] = previousPredictedMean (only for this filter) + filters.append(jnp.vstack((initialPhysicalState,.001* jnp.eye(len(initialPhysicalState)),initialPhysicalState))) + + return (failureWeights,jnp.array(filters)) diff --git a/failurePy/estimators/conservativeMarginalizedFilter.py b/failurePy/estimators/conservativeMarginalizedFilter.py new file mode 100644 index 0000000..6066b9a --- /dev/null +++ b/failurePy/estimators/conservativeMarginalizedFilter.py @@ -0,0 +1,98 @@ +""" +Implements the marginalized filter, agnostic to the physical state estimator. Uses a conservative factor to limit speed of failure weight updates +""" + +from functools import partial +import jax +import jax.numpy as jnp + +@partial(jax.jit, static_argnames=['systemF','physicalStateSubEstimatorF','physicalStateJacobianF']) #Big slow down to compile, esp with EKF (2 min!) +def updateMarginalizedFilterEstimate(action,observation,previousBeliefTuple,possibleFailures,systemF,systemParametersTuple,physicalStateSubEstimatorF,physicalStateJacobianF,updateRate=.25): + """ + Function that propagates and updates the marginalized filter, given physical state estimator + + Parameters + ---------- + action : array, shape(numAct) + Action taken + observation : array, shape(numSenors) + Observation received + previousBeliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + Contents are in order: + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + controlTransitionMatrix : array, shape(numState,numAct) + State Transition matrix resulting from constant control input + sensingMatrix : array, shape(numSen, numState) + C matrix + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + physicalStateSubEstimatorF : function + Function to update all of the conditional position filters + updateRate : float (default=.25) + Rate at which failure weights are updated (1 being normal filter update rate). Similar to a learning rate in SGD + + Returns + ------- + updatedBeliefTuple : tuple + The tuple consists of an updated array of weights over possibleFailures and corresponding conditional filters + """ + + #Get previous failure weights, filters + perviousFailureWeights = previousBeliefTuple[0] + previousFilters = previousBeliefTuple[1] + + #Get new filters + updatedFilters,relativeLikelihoods = physicalStateSubEstimatorF(action,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF) + + #print("relativeLikelihoods") + #print(relativeLikelihoods) + + #Update failure weights + updatedFailureWeights = updateFailureWeights(relativeLikelihoods,perviousFailureWeights,updateRate) + #print("updatedFailureWeights") + #print(updatedFailureWeights) + #error + return (updatedFailureWeights,updatedFilters) + +def updateFailureWeights(relativeLikelihoods,perviousFailureWeights,updateRate): + """ + Function that updates the failure weights of the marginalized filter via a Bayesian update + + Parameters + ---------- + relativeLikelihoods : array, shape(maxPossibleFailures) + Relative likelihood of each observation given the action taken and the previous (conditional) physical state filters + previousFailureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure before this update. Sorted to match possibleFailures + updateRate : float + Rate at which failure weights are updated (1 being normal filter update rate). Similar to a learning rate in SGD + + Returns + ------- + updatedFailureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure after this update + """ + + #Create new failure weights + #updatedFailureWeights = updateRate * jnp.multiply(relativeLikelihoods,perviousFailureWeights) + (1-updateRate) * perviousFailureWeights + + #Normalize + #return updatedFailureWeights/jnp.sum(updatedFailureWeights) + + updatedFailureWeights = jnp.multiply(relativeLikelihoods,perviousFailureWeights) + + return updateRate * updatedFailureWeights/jnp.sum(updatedFailureWeights) + (1-updateRate) * perviousFailureWeights diff --git a/failurePy/estimators/extendedKalmanFilterLinearSensing.py b/failurePy/estimators/extendedKalmanFilterLinearSensing.py new file mode 100644 index 0000000..ce08b63 --- /dev/null +++ b/failurePy/estimators/extendedKalmanFilterLinearSensing.py @@ -0,0 +1,183 @@ +""" +Extended kalman filter on non-linear dynamics and linear sensing + +Adapts the FilterPy library. +http://github.com/rlabbe/filterpy + +Documentation at: +https://filterpy.readthedocs.org + +FilterPy library is licensed under an MIT license. See the readme.MD file +for more information. + +Copyright 2014-2018 Roger R Labbe Jr. +""" + +#from functools import partial Unused unless this is ever used outside of marginal filter +import jax +import jax.numpy as jnp + +from failurePy.estimators.kalmanFilter import updateFilter + +#0/1 realization +from failurePy.models.linearModel import getRealizedNominalMeasurement as linearGetRealizedNominalMeasurementF +#General realization +from failurePy.models.linearModelGeneralFaults import getRealizedNominalMeasurement as linearGeneralFaultsGetRealizedNominalMeasurementF + +#Don't need to jit or vmap unless using it separately from marginal filter! currently we are not. +#If we need to, use from functools import partial to make functions static args: @partial(jax.jit, static_argnames=['n'])) +#@partial(jax.jit, static_argnames=['systemF']) #yse with vmap from calling function, otherwise compiling takes too long (2 mins!). Only need if called outside marginal filter. +def predictAndUpdateAll(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF, + getRealizedNominalMeasurementF=linearGetRealizedNominalMeasurementF): + """ + Function that propagates and updates the Kalman filter given a nonlinear system and relevant parameters. + Only works for MULTIVARIATE (ie, state and observation 2 or higher dimensions) cases + + Parameters + ---------- + nominalAction : array, shape(numAct) + Action taken before failures are considered (this is handled in systemF) + observation : array, shape(numSenors) + Observation received + previousFilters : array + Array of previous filters, each element is an array representing mean and covariance + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. + systemParametersTuple : tuple + Needed parameters for systemF to simulate forward + Contents are in order (for s/c rotations): + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + getRealizedNominalMeasurementF : function + Function used to realize the nominal measurement given a failure particle + + Returns + ------- + updatedFilters : array + Array of updated Kalman filters + relativeLikelihoods : array, shape(maxPossibleFailures) + The relative likelihood of the observation (for failure weight updating) + """ + + #Unpack systemParametersTuple here + sensingMatrix = systemParametersTuple[-4] + measurementNoiseMatrixR = systemParametersTuple[-1] + + #We will use vmap to vectorize our updates. This provides another 30% speed up over non-vectorized performance (using filter arrays) + + #Don't need to get realized actions, as this will happen in systemF + + batchPredictFilter = jax.vmap(predictNonLinear,in_axes=[0, None, 0, None, None,None]) + predictedMeans, predictedCovariancePs = batchPredictFilter(previousFilters, nominalAction, possibleFailures, systemF,systemParametersTuple,physicalStateJacobianF ) + + #Create the sensing matrices for all failures + batchPredictedMeasurements = jax.vmap(getRealizedNominalMeasurementF, in_axes=[0,0, None]) + predictedObservations = batchPredictedMeasurements(predictedMeans,possibleFailures,sensingMatrix) + + #Now get the updated filters and relative likelihoods + #Note this is re-using the linear update, as we assume linear measurements + batchPredictAndUpdateFilter = jax.vmap(updateFilter, in_axes=[0, 0, 0, None, None, None]) + updatedFilters,relativeLikelihoods = batchPredictAndUpdateFilter(predictedMeans, predictedCovariancePs,predictedObservations,observation,sensingMatrix,measurementNoiseMatrixR) + + return (updatedFilters,relativeLikelihoods) + +def makeGeneralFaultExtendedKalmanFilter(): + """ + Constructor that makes the general fault version using the alternate control transition matrix + and sensing matrix functions + """ + def predictAndUpdateAllGeneral(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF): + return predictAndUpdateAll(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF, + getRealizedNominalMeasurementF=linearGeneralFaultsGetRealizedNominalMeasurementF) + return predictAndUpdateAllGeneral + +def predictNonLinear(previousFilter,nominalAction,failureState,systemF,systemParametersTuple,physicalStateJacobianF): + """ + Function that propagates and updates the Kalman filter + + Parameters + ---------- + previousFilter : array, shape(numState+1,numState) + The rows consists of the pervious mean and covariance of the filter + previousMean : array, shape(numState) + The previous estimate of the physical state + perviousCovarianceP : array, shape(numState,numState) + The previous covariance estimate of the physical state + nominalAction : array, shape(numAct) + Action taken before failures are considered (this is handled in systemF) + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Needed parameters for systemF to simulate forward + Contents are in order (for s/c rotations): + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + reactionWheelMoment : array, shape(numWheels,numWheels) + Jw, The moment of inertia for each reaction wheel (default is the same for all wheels) + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + + Returns + ------- + predictedMean : array, shape(numState) + The predicted estimate of the physical state + predictedCovarianceP : array, shape(numState,numState) + The predicted covariance estimate of the physical state + """ + + #Get old values + #We are using a convention where the filter is a n+1xn array, where the filter[0] = mean, filter[1:] = covariance! + previousMean = previousFilter[0] + perviousCovarianceP = previousFilter[1:] + + covarianceQ = systemParametersTuple[-2] + + #Noise free propagation, so set rng to default since it doesn't matter + rngKey = jax.random.PRNGKey(0) + + #Propagate system forward to estimate mean (Don't use the other return values of systemF + predictedMean, dummy, dummy = systemF(previousMean,failureState,nominalAction,rngKey,systemParametersTuple,noisyPropagationBooleanInt=0) + #Get jacobian for current state. + jacobian = physicalStateJacobianF(physicalState=previousMean,failureState=failureState,nominalAction=nominalAction,systemParametersTuple=systemParametersTuple) + + #Propagate covariance with jacobian + predictedCovarianceP = jnp.matmul(jnp.matmul(jacobian, perviousCovarianceP), jnp.transpose(jacobian)) + covarianceQ + + return predictedMean, predictedCovarianceP diff --git a/failurePy/estimators/firstEstimatesJacobianExtendedKalmanFilterLinearSensing.py b/failurePy/estimators/firstEstimatesJacobianExtendedKalmanFilterLinearSensing.py new file mode 100644 index 0000000..ae29129 --- /dev/null +++ b/failurePy/estimators/firstEstimatesJacobianExtendedKalmanFilterLinearSensing.py @@ -0,0 +1,212 @@ +""" +Extended kalman filter on non-linear dynamics and linear sensing. +Uses first estimates Jacobian method to try to reduce estimator inconsistency +https://link.springer.com/chapter/10.1007/978-3-642-00196-3_43 + +Adapts the FilterPy library. +http://github.com/rlabbe/filterpy + +Documentation at: +https://filterpy.readthedocs.org + +FilterPy library is licensed under an MIT license. See the readme.MD file +for more information. + +Copyright 2014-2018 Roger R Labbe Jr. +""" + +import jax +#from functools import partial Unused unless this is ever used outside of marginal filter +import jax.numpy as jnp + +from jax.random import multivariate_normal as multivariateNormal +from failurePy.estimators.kalmanFilter import updateFilter +#0/1 realization +from failurePy.models.linearModel import getRealizedNominalMeasurement as linearGetRealizedNominalMeasurementF +#General realization +from failurePy.models.linearModelGeneralFaults import getRealizedNominalMeasurement as linearGeneralFaultsGetRealizedNominalMeasurementF + + + +#Don't need to jit or vmap unless using it separately from marginal filter! currently we are not. +#If we need to, use from functools import partial to make functions static args: @partial(jax.jit, static_argnames=['n'])) +#@partial(jax.jit, static_argnames=['systemF']) #yse with vmap from calling function, otherwise compiling takes too long (2 mins!). Only need if called outside marginal filter. +def predictAndUpdateAll(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF, + getRealizedNominalMeasurementF=linearGetRealizedNominalMeasurementF): + """ + Function that propagates and updates the Kalman filter given a nonlinear system and relevant parameters. + Only works for MULTIVARIATE (ie, state and observation 2 or higher dimensions) cases + + Parameters + ---------- + nominalAction : array, shape(numAct) + Action taken before failures are considered (this is handled in systemF) + observation : array, shape(numSenors) + Observation received + previousFilters : array + Array of previous filters, each element is an array representing mean and covariance + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. + systemParametersTuple : tuple + Needed parameters for systemF to simulate forward + Contents are in order (for s/c rotations): + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + + Returns + ------- + updatedFilters : array + Array of updated Kalman filters + relativeLikelihoods : array, shape(maxPossibleFailures) + The relative likelihood of the observation (for failure weight updating) + """ + + #Unpack systemParametersTuple here + sensingMatrix = systemParametersTuple[-4] + measurementNoiseMatrixR = systemParametersTuple[-1] + + #We will use vmap to vectorize our updates. This provides another 30% speed up over non-vectorized performance (using filter arrays) + + #Don't need to get realized actions, as this will happen in systemF + #Slightly different prediction using previous mean + batchPredictFilter = jax.vmap(predictNonLinearFEJ,in_axes=[0, None, 0, None, None,None]) + predictedMeans, predictedCovariancePs = batchPredictFilter(previousFilters, nominalAction, possibleFailures, systemF,systemParametersTuple,physicalStateJacobianF ) + + #Create the sensing matrices for all failures + batchPredictedMeasurements = jax.vmap(getRealizedNominalMeasurementF, in_axes=[0,0, None]) + predictedObservations = batchPredictedMeasurements(predictedMeans,possibleFailures,sensingMatrix) + + #Now get the updated filters and relative likelihoods + #Note this is re-using the linear update, as we assume linear measurements + batchPredictAndUpdateFilter = jax.vmap(updateFilter, in_axes=[0, 0, 0, None, None, None]) + updatedFilters,relativeLikelihoods = batchPredictAndUpdateFilter(predictedMeans, predictedCovariancePs,predictedObservations,observation,sensingMatrix,measurementNoiseMatrixR) + + return (updatedFilters,relativeLikelihoods) + +def makeGeneralFaultFEJExtendedKalmanFilter(): + """ + Constructor that makes the general fault version using the alternate control transition matrix + and sensing matrix functions + """ + def predictAndUpdateAllGeneral(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF): + return predictAndUpdateAll(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF, + getRealizedNominalMeasurementF=linearGeneralFaultsGetRealizedNominalMeasurementF) + return predictAndUpdateAllGeneral + +def predictNonLinearFEJ(previousFilter,nominalAction,failureState,systemF,systemParametersTuple,physicalStateJacobianF): + """ + Function that propagates and updates the Kalman filter + + Parameters + ---------- + previousFilter : array + The array rows consists of: + previousMean : array, shape(numState) + The previous estimate of the physical state + previousPredictedMean : array, shape(numState) + The previous estimate of the physical state, BEFORE the measurement update. This follows the FEJ-EKF introduced in: https://doi.org/10.1109%2FROBOT.2008.4543252 + perviousCovarianceP : array, shape(numState,numState) + The previous covariance estimate of the physical state + nominalAction : array, shape(numAct) + Action taken before failures are considered (this is handled in systemF) + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Needed parameters for systemF to simulate forward + Contents are in order (for s/c rotations): + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + reactionWheelMoment : array, shape(numWheels,numWheels) + Jw, The moment of inertia for each reaction wheel (default is the same for all wheels) + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + + Returns + ------- + predictedMean : array, shape(numState) + The predicted estimate of the physical state + predictedCovarianceP : array, shape(numState,numState) + The predicted covariance estimate of the physical state + """ + + #Get old values + #We are using a convention where the filter is a n+1xn array, where the filter[0] = mean, filter[1:-1] = covariance, filter[-1] = previousPredictedMean (only this filter) + previousMean = previousFilter[0] + perviousCovarianceP = previousFilter[1:-1] + previousPredictedMean = previousFilter[-1] #(only this filter) + + covarianceQ = systemParametersTuple[-2] + + #Noise free propagation, so set rng to default since it doesn't matter + rngKey = jax.random.PRNGKey(0) + + #Propagate system forward to estimate mean (Don't use the other return values of systemF + predictedMean, dummy, dummy = systemF(previousMean,failureState,nominalAction,rngKey,systemParametersTuple,noisyPropagationBooleanInt=0) + #Get jacobian for current state. + jacobian = physicalStateJacobianF(physicalState=previousPredictedMean,failureState=failureState,nominalAction=nominalAction,systemParametersTuple=systemParametersTuple) + + #Propagate covariance with jacobian + predictedCovarianceP = jnp.matmul(jnp.matmul(jacobian, perviousCovarianceP), jnp.transpose(jacobian)) + covarianceQ + + return predictedMean, predictedCovarianceP + +#Used in POMCP to sample a physical state (and Monte Carlo belief propagation) +def sampleFromFilter(filterToSample,rngKey): + """ + Returns random sample of the state using the current estimate and covariance estimate. DOES NOT return estimate (in general) + + Parameters + ---------- + filterToSample : tuple + mean : array, shape(numState) + The estimate of the physical state + covarianceP : array, shape(numState,numState) + The covariance estimate of the physical state + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + + Returns + ------- + x : array, shape(len(xHat)) + Sample of state + """ + + #We are using a convention where the filter is a n+1xn array, where the filter[0] = mean, filter[1:-1] = covariance, filter[-1] = previousPredictedMean (only this filter) + return multivariateNormal(rngKey, filterToSample[0], filterToSample[1:-1]) #Different for this filter b/ of the first estimates diff --git a/failurePy/estimators/generalFaultSampling.py b/failurePy/estimators/generalFaultSampling.py new file mode 100644 index 0000000..86f7622 --- /dev/null +++ b/failurePy/estimators/generalFaultSampling.py @@ -0,0 +1,254 @@ +""" +Module of functions that sample in fault space for new particles and check resampling conditions. + +Also includes initialization functions + +Not fully implemented yet +""" + +#Still under development pylint: skip-file +from functools import partial + +import jax +import jax.random as jaxRandom +import jax.numpy as jnp + +#Do we need to saturate the Gaussian at 0/1? I think so, could this cause issues? Unsure. +@partial(jax.jit, static_argnames=['timeStepK','estimatorF','systemF','physicalStateSubEstimatorF','physicalStateJacobianF','singleParticleResampleMethodF']) +def failureParticleResample(beliefTuple,timeStepK,estimatorF,initialBelief,actionHistory,observationHistory,systemF,systemParametersTuple, + physicalStateSubEstimatorF,physicalStateJacobianF,rngKey, sigma=.1,singleParticleResampleMethodF=None): + """ + Takes in a belief and performs a weighted resample based on gaussian noise. + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(numFailureParticlesP) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + possibleFailureParticles : array, shape(nMaxPossibleFailures,2*numAct+2*numSen) + Array of the current failure particles (locations in fault space, effectively). Belief failure weights are are over these possibilities + timeStepK : int + How many time steps from initial the states we need to propagate filters forward to catch up to current time + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + initialBelief : array + The initial belief state of our estimator. ASSUMPTION: All particles start with uniform probability and the same initial state estimate. + We are only interested in these 2 components of the initial belief. + TODO: Relax this assumption + actionHistory : tuple + Tuple of actions taken to fast-forward filters + observationHistory : tuple + Tuple of actions taken to fast-forward filters + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + physicalStateSubEstimatorF : function + Function to update all of the conditional position filters + physicalStateJacobianF : function + Jacobian of the model for use in estimating. Can be none if physicalStateSubEstimatorF doesn't need it. + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + sigma : float (default=.1) + The sigma on the resampling. Should be provided when constructed if a different value is desired + singleParticleResampleMethodF : function (default=None) + Function to perform resampling with. Should be provided when constructed + + Returns + ------- + resampledFailureParticles : array, shape(nMaxPossibleFailures,2*numAct+2*numSen) + Array of the updated failure particles (locations in fault space, effectively). Belief failure weights are are over these possibilities + updatedBeliefTuple : tuple + The tuple consists of an updated array of weights over possibleFailures and corresponding conditional filters + """ + + resampledFailureParticles = resampledFailureParticlesJitHelper(beliefTuple,singleParticleResampleMethodF,sigma,rngKey) + + #Now rebuild filters with the update particles. USE THE ESTIMATOR FUNCTION + updatedBeliefTuple = initialBelief #Note this could have the failure particles provided, but the base estimatorF doesn't use these anyways + for iPastTimeStep in range(timeStepK): + updatedBeliefTuple = estimatorF(actionHistory[iPastTimeStep],observationHistory[iPastTimeStep],updatedBeliefTuple,resampledFailureParticles,systemF,systemParametersTuple,physicalStateSubEstimatorF,physicalStateJacobianF) + + #Combine into one tuple (mostly for saving the changing particles) + return updatedBeliefTuple + (resampledFailureParticles, ) + +@partial(jax.jit, static_argnames=['singleParticleResampleMethodF']) +def resampledFailureParticlesJitHelper(beliefTuple,singleParticleResampleMethodF,sigma,rngKey): + """ + Helper that can jit without needing to know timeStepK + """ + + failureWeights = beliefTuple[0] + possibleFailureParticles = beliefTuple[2] + + numFailureParticlesP = len(failureWeights) + failureIdxs = jnp.arange(numFailureParticlesP) + rngKey,rngSubKey = jaxRandom.split(rngKey) + #Sample with replacement from our particles. This will lead to some particle extinction. + # #IDEA! WHAT IF THE DIFFUSION SIZE IS THE INVERSE OF THE FAILURE WEIGHT? UNLIKELY PARTICLES MOVE MORE? NO PARTICLE EXTINCTION? NEED TO READ PAPERS!!! + # This idea would probably lead to more likely to search uncovered space, though it is a little hard to conceptualize + #More ideas: Some sort of probability gradient? Is this too strong of a convergence? + + #Use choices to select the particles + particlesToResampleIdxs = jaxRandom.choice(rngSubKey,failureIdxs,shape=(numFailureParticlesP,),p=failureWeights,replace=True) + + #Parallelize the diffusion step + batchGaussianDiffusion = jax.vmap(singleParticleResampleMethodF,in_axes=[0,None,0]) #IDEA!!! We can swap this line out! Get polymorphic behavior! (Can specify re-sample method) + batchRngKeys = jaxRandom.split(rngKey,num=numFailureParticlesP) + covariance = sigma * jnp.eye(len(possibleFailureParticles[0])) + + resampledFailureParticles = batchGaussianDiffusion(possibleFailureParticles[particlesToResampleIdxs],covariance,batchRngKeys) + + return resampledFailureParticles + + +def makeFailureParticleResampleF(singleParticleResampleMethodF,sigma=.1): + """ + Constructor for failureParticleResample functions. Binds resample method and sigma + """ + def failureParticleResampleF(beliefTuple,timeStepK,estimatorF,initialFilters,actionHistory,observationHistory,systemF,systemParametersTuple, + physicalStateSubEstimatorF,physicalStateJacobianF,rngKey): + return failureParticleResample(beliefTuple,timeStepK,estimatorF,initialFilters,actionHistory,observationHistory,systemF,systemParametersTuple, + physicalStateSubEstimatorF,physicalStateJacobianF,rngKey, sigma,singleParticleResampleMethodF) + return failureParticleResampleF + + + + +def gaussianDiffusion(failureParticle,covariance,rngKey,clipMin=0,clipMax=1): + """ + vmap helper for gaussianDiffusionResample + """ + + particle = jaxRandom.multivariate_normal(rngKey,failureParticle,covariance) + return jnp.clip(particle,clipMin,clipMax) + + + + + + +@jax.jit +def maxRatioResampleCheck(beliefTuple,threshold): + """ + Takes in a belief and checks if highest versus lowest weight is above a threshold + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(numFailureParticlesP) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + threshold : float + maximum ratio that can exist between max and min particle weights + + Returns + ------- + resampleFlag : boolean + Whether the maxRatio threshold is exceeded + """ + + weights = beliefTuple[0] + maxWeight = jnp.max(weights) + minWeight = jnp.min(weights) + return maxWeight/minWeight > threshold + + #NEED TO INCORPORATE CONVERGENCE INTO REWARD: Tree needs to see how "close" the particles are together. Need to maybe add regularization or something like that + #to make the tree avoid overfitting, or otherwise guarantee we don't converge to local minimum? Stabilizing noise probably has a role here + +def makeMaxRatioResampleCheck(threshold): + """ + Makes maxRatioResampleCheck for given threshold + """ + + def failureParticleResampleCheckF(beliefTuple): + return maxRatioResampleCheck(beliefTuple,threshold) + return failureParticleResampleCheckF + +def effectiveNumberOfParticlesResampleCheck(thresholdPercent = .66): + """ + Uses the condition suggested here: https://ieeexplore.ieee.org/abstract/document/5546308 + """ + pass + +def neverResampleCheck(beliefTuple): + """ + Dummy function that never performs resampling (for static particle testing) + """ + + return False + + +def randomInitialFailureParticles(numFailureParticles, numAct,numSen,rngKey,dummyProvidedFailure): + """ + Simple way of initializing the failure particles by randomly sampling belief space. + """ + numFallibleComponents = numAct + numSen + #Each has degradation and bias + return jaxRandom.uniform(rngKey,shape=(numFailureParticles,2*numFallibleComponents)) + +def biasedRandomInitialFailureParticles(numFailureParticles, numAct,numSen,rngKey,dummyProvidedFailure): + """ + Simple way of initializing the failure particles by randomly sampling belief space and biasing towards nominal + """ + + numFallibleComponents = numAct + numSen + #Each has degradation and bias, but bias these towards 0, 1/2 chance of being nominal + scaledFailureParticles = 2* jaxRandom.uniform(rngKey,shape=(numFailureParticles,2*numFallibleComponents)) + scaledFailureParticles -= 1 + return jnp.clip(scaledFailureParticles,a_min=0,a_max=1) + +def biasedRandomInitialFailureParticlesRedundantBiases(numFailureParticles, numAct,numSen,rngKey,providedFailure): + """ + Simple way of initializing the failure particles by randomly sampling belief space and biasing towards nominal + + Also ensures the act/sen biases are repeated 5x times + """ + numFallibleComponents = numAct + numSen + #Each has degradation and bias, but bias these towards 0, 1/2 chance of being nominal + scaledFailureParticles = 2* jaxRandom.uniform(rngKey,shape=(numFailureParticles,2*numFallibleComponents)) + scaledFailureParticles -= 1 + failureParticles = jnp.clip(scaledFailureParticles,a_min=0,a_max=1) + + #Add provided failure to the list + if providedFailure is not None: + failureParticles = failureParticles.at[0].set(providedFailure) + + #For validating + #jnp.set_printoptions(threshold=jnp.inf) + #jnp.set_printoptions(linewidth=jnp.inf) + + #Now make each bias have 5x redundancy + numDiffBiases = int(numFailureParticles/5) + for iFailureParticle in range(numFailureParticles-numDiffBiases): + failureParticles = failureParticles.at[iFailureParticle+numDiffBiases,numAct:2*numAct].set(failureParticles[iFailureParticle % numDiffBiases,numAct:2*numAct]) + failureParticles = failureParticles.at[iFailureParticle+numDiffBiases,2*numAct+numSen:2*numAct+2*numSen].set(failureParticles[iFailureParticle % numDiffBiases,2*numAct+numSen:2*numAct+2*numSen]) + #print(failureParticles[iFailureParticle+numDiffBiases]) For validating + + return failureParticles + + +@jax.jit +def binaryToDegradationFaults(binaryTrueFaultParticle,rngKey): + """ + Takes a binary fault in, and changes it to randomly degraded fault on the components identified as failed. + + Note we are using the old convention here of 1 = nominal, 0 = completely degraded. THESE FAULTS SHOULD BE USED WITH THE OLD DYNAMICS MODEL + + Parameters + ---------- + binaryTrueFaultParticle : array, shape(numAct+numSen) + A fault particle with a 0/1 for each particle, with 1=nominal, 0=totally failed. + """ + + #Only need to do this every now and then, so I this computation is fast enough + randomDegradations = jaxRandom.uniform(rngKey,shape=(len(binaryTrueFaultParticle),)) #Create random vals between 0 and 1 + #Only affect components with current fault state = 0 + return jnp.where(binaryTrueFaultParticle == 1, 1, randomDegradations) + +#def specifiedInitialFailureParticles() diff --git a/failurePy/estimators/kalmanFilter.py b/failurePy/estimators/kalmanFilter.py new file mode 100644 index 0000000..5eef68f --- /dev/null +++ b/failurePy/estimators/kalmanFilter.py @@ -0,0 +1,193 @@ +""" +Adapts the FilterPy library. +http://github.com/rlabbe/filterpy + +Documentation at: +https://filterpy.readthedocs.org + +FilterPy library is licensed under an MIT license. See the readme.MD file +for more information. + +Copyright 2014-2018 Roger R Labbe Jr. +""" + +import jax +#from functools import partial Unused unless this is ever used outside of marginal filter +import jax.numpy as jnp +from failurePy.estimators.kalmanFilterCommon import updateMultiDimensional, computeRelativeLikelihood +#0/1 realization +from failurePy.models.linearModel import getRealizedAction as linearGetRealizedActionF +from failurePy.models.linearModel import getRealizedNominalMeasurement as linearGetRealizedNominalMeasurementF +#General realization +from failurePy.models.linearModelGeneralFaults import getRealizedAction as linearGeneralFaultsGetRealizedActionF +from failurePy.models.linearModelGeneralFaults import getRealizedNominalMeasurement as linearGeneralFaultsGetRealizedNominalMeasurementF + + +#Using default control realization and sensing realizations, makes more backwards compatible. BUT! We must have this function after those methods now, or otherwise +#we would need to import ourselves, which is bad form. +#Don't need to jit unless using it separately from marginal filter! currently we are not +#@partial(jax.jit, static_argnames=['systemF']) #Only a major speed up for many trials! Otherwise compiling takes too long +def predictAndUpdateAll(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF,# pylint: disable=unused-argument + getRealizedActionF=linearGetRealizedActionF,getRealizedNominalMeasurementF=linearGetRealizedNominalMeasurementF): + """ + Function that propagates and updates the Kalman filter given a LINEAR system and relevant parameters. + Only works for MULTIVARIATE (ie, state and observation 2 or higher dimensions) cases + + Parameters + ---------- + nominalAction : array, shape(numAct) + Action taken before failures are considered (this is handled in by the controlTransitionMatrices) + observation : array, shape(numSenors) + Observation received + previousFilters : array + Array of previous filters, each element is an array representing mean and covariance + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel). Model must be linear + Contents are in order: + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + + controlTransitionMatrix : array, shape(numState,numAct) + State Transition matrix resulting from constant control input + sensingMatrix : array, shape(numSen, numState) + C matrix + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + physicalStateJacobianF : function + Jacobian of the model for use in estimating. Not used here, but provided to make compatible with marginal filter + getRealizedActionF : function + Function used to realize the action given a failure particle + getRealizedNominalMeasurementF : function + Function used to realize the nominal measurement given a failure particle + + Returns + ------- + updatedFilters : array + Array of updated Kalman filters + relativeLikelihoods : array, shape(maxPossibleFailures) + The relative likelihood of the observation (for failure weight updating) + """ + #Unpack systemParametersTuple here + stateTransitionMatrix = systemParametersTuple[0] + controlTransitionMatrix = systemParametersTuple[1] + sensingMatrix = systemParametersTuple[2] + #Get noise covariance matrices + processNoiseMatrixQ = systemParametersTuple[3] + measurementNoiseMatrixR = systemParametersTuple[4] + + #We will use vmap to vectorize our updates. This provides another 30% speed up over non-vectorized performance (using filter arrays) + + #Get the realized actions for each filter (no longer looking at transition matrices, cause can get this directly) + batchRealizeActions = jax.vmap(getRealizedActionF, in_axes=[0, None]) + realizedActions = batchRealizeActions(possibleFailures,nominalAction) + + batchPredictFilter = jax.vmap(predict,in_axes=[0, None, None, 0, None]) + predictedMeans, predictedCovariancePs = batchPredictFilter(previousFilters, stateTransitionMatrix, processNoiseMatrixQ, realizedActions, controlTransitionMatrix) + + #Create the sensing matrices for all failures + batchPredictedMeasurements = jax.vmap(getRealizedNominalMeasurementF, in_axes=[0,0, None]) + predictedObservations = batchPredictedMeasurements(predictedMeans,possibleFailures,sensingMatrix) + + #Now get the updated filters and relative likelihoods + batchPredictAndUpdateFilter = jax.vmap(updateFilter, in_axes=[0, 0, 0, None, None, None]) + updatedFilters,relativeLikelihoods = batchPredictAndUpdateFilter(predictedMeans, predictedCovariancePs,predictedObservations,observation,sensingMatrix,measurementNoiseMatrixR) + + return (updatedFilters,relativeLikelihoods) + +def makeGeneralFaultKalmanFilter(): + """ + Constructor that makes the general fault version using the alternate control transition matrix + and sensing matrix functions + """ + def predictAndUpdateAllGeneral(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF): + return predictAndUpdateAll(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF, + getRealizedActionF=linearGeneralFaultsGetRealizedActionF,getRealizedNominalMeasurementF=linearGeneralFaultsGetRealizedNominalMeasurementF) + return predictAndUpdateAllGeneral + + +def updateFilter(predictedMean, predictedCovarianceP,predictedObservation,observation,sensingMatrix,measurementNoiseMatrixR): + """ + Function that propagates and updates the Kalman filter given a LINEAR system and relevant parameters + + Parameters + ---------- + realizedAction : array, shape(numAct) + Action taken (after fault applied) + observation : array, shape(numSenors) + Observation received + previousFilter : array + The tuple consists of the pervious mean and covariance of the filter + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + controlTransitionMatrix : array, shape(numState,numAct) + Maps constant control input to change in state + sensingMatrix : array, shape(numSen,numState) + Measurement function (conditioned on failure) + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + + Returns + ------- + updatedFilter : array + Array of the updated Kalman filter + relativeLikelihood : float + The relative likelihood of the observation (for failure weight updating) + """ + + #Relative likelihood of observation (we need this for failure weighting) + relativeLikelihood = computeRelativeLikelihood(observation,predictedObservation, predictedCovarianceP,sensingMatrix,measurementNoiseMatrixR) + + #Innovate with new measurement + updatedMean,updatedCovarianceP = updateMultiDimensional(predictedMean,predictedCovarianceP,predictedObservation,observation,measurementNoiseMatrixR,sensingMatrix) + + #Stack into a single object and return (so we don't need to re-assign later. This might already be optimized when jitted, doesn't make much of a change) + return jnp.vstack((updatedMean,updatedCovarianceP)),relativeLikelihood + +#Original FilterPy method, re-written to match our conventions alpha discarded as we don't use memory here +def predict(previousFilter, stateTransitionMatrix, processNoiseMatrixQ, realizedAction, controlTransitionMatrix): #alpha=1.): # pylint: disable=invalid-name + """ + Predict next state (prior) using the Kalman filter state propagation + equations. + + Parameters + ---------- + previousFilter : array, shape(numState+1,numState) + The rows consists of the pervious mean and covariance of the filter + previousMean : array, shape(numState) + Previous mean estimate + perviousCovarianceP : array, shape(numState,numState) + Previous covariance estimate + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + realizedAction : array, shape(numAct) + Action taken (after fault applied) + controlTransitionMatrix : array, shape(numState,numAct) + Maps constant control input to change in state + + Returns + ------- + predictedMean : array, shape(numState) + Prior state estimate vector + predictedCovarianceP : array, shape(numState,numState) + Prior covariance matrix + """ + + #processNoiseMatrixQ *= 1.5 + + #Get old values + #We are using a convention where the filter is a n+1xn array, where the filter[0] = mean, filter[1:] = covariance! + previousMean = previousFilter[0] + perviousCovarianceP = previousFilter[1:] + + predictedMean = jnp.matmul(stateTransitionMatrix, previousMean) + jnp.matmul(controlTransitionMatrix, realizedAction) + predictedCovarianceP = jnp.matmul(jnp.matmul(stateTransitionMatrix, perviousCovarianceP), jnp.transpose(stateTransitionMatrix)) + processNoiseMatrixQ + + return predictedMean, predictedCovarianceP diff --git a/failurePy/estimators/kalmanFilterCommon.py b/failurePy/estimators/kalmanFilterCommon.py new file mode 100644 index 0000000..94c7ae3 --- /dev/null +++ b/failurePy/estimators/kalmanFilterCommon.py @@ -0,0 +1,143 @@ +""" +Common functions used in the kalman filter classes, to avoid repeated code + +Adapts the FilterPy library. +http://github.com/rlabbe/filterpy + +Documentation at: +https://filterpy.readthedocs.org + +FilterPy library is licensed under an MIT license. See the readme.MD file +for more information. + +Copyright 2014-2018 Roger R Labbe Jr. +""" + +from jax.random import multivariate_normal as multivariateNormal +from jax.scipy.stats.multivariate_normal import pdf as multivariateNormalPDF +import jax.numpy as jnp + + + +#Future idea: square root form of filter to force P to remain PD? + +def updateMultiDimensional(predictedMean, predictedCovarianceP, predictedObservation, observation, covarianceR, sensingMatrix): + """ + Updates the kalman filter given an new observation. Uses the more numerically stable Joseph form + + This now ONLY WORKS FOR the multidimensional case. + + Parameters + ---------- + + predictedMean : array, shape(numState) + The predicted estimate of the physical state + predictedCovarianceP : array, shape(numState,numState) + The previous covariance estimate of the physical state + observation : array, shape(numSenors) + Observation received + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + sensingMatrix : array, shape(numSen, numState) + C matrix + + Returns + ------- + + x : numpy.array + Posterior state estimate vector + + P : numpy.array + Posterior covariance matrix + """ + + #Increasing R as stabilizing noise, from of regularization effectively + #covarianceR *= 1.2 + + #predictedObservation = jnp.matmul(sensingMatrix, predictedMean) + + # error (residual) between measurement and prediction + residual = observation - predictedObservation + + #Compute this only once + covariancePSensingMatrixTrans = jnp.matmul(predictedCovarianceP,sensingMatrix.T) + + # project system uncertainty into measurement space + intermediateGainS = jnp.matmul(sensingMatrix, covariancePSensingMatrixTrans) + covarianceR + + + # map system uncertainty into kalman gain ONLY WORKS FOR MULTIDIMENSIONAL CASE + + kalmanGainK = jnp.matmul(covariancePSensingMatrixTrans, jnp.linalg.inv(intermediateGainS)) + + + # predict new x with residual scaled by the kalman gain + updatedMean = predictedMean + jnp.matmul(kalmanGainK, residual) + + #Use joseph form for covariance propagation to ensure numerical stability + # P = (I-KH)P(I-KH)' + KRK' instead of shorter but unstable P = (I-KH)P + identityMinusKH = jnp.eye(len(predictedMean)) - jnp.matmul(kalmanGainK, sensingMatrix) + + updatedCovarianceP = jnp.matmul(jnp.matmul(identityMinusKH, predictedCovarianceP),identityMinusKH.T) + jnp.matmul(jnp.matmul(kalmanGainK,covarianceR),kalmanGainK.T) + + #Stabilizing noise, + #updatedCovarianceP *= 1.5 + + return updatedMean, updatedCovarianceP + + +#Don't think we need to jit since only called from jitted functions +def computeRelativeLikelihood(observation,predictedObservation, predictedCovarianceP,sensingMatrix,measurementNoiseMatrixR): + """ + Function that gives the relative likelihood of an observation for the given filter. + + Parameters + ---------- + observation : array, shape(numSen) + The observation to get relative likelihood of + predictedMean : array, shape(numState) + The mean of the physical state estimate + predictedCovarianceP : array, shape(numState,numState) + The covariance of the physical state estimate + sensingMatrix : array, shape(numSen, numState) + C matrix + measurementNoiseMatrixR : array, shape(numSen,numSen) + Covariance of the sensing noise. + discretization : float (default=None) + + Returns + ------- + relativeLikelihood : float + Relative likelihood of this observation + """ + + #Get the mean of our posterior + #predictedObservation = jnp.matmul(sensingMatrix,predictedMean) + #Get covariance of our posterior + measurementCovariance = jnp.matmul(sensingMatrix,jnp.matmul(predictedCovarianceP,sensingMatrix.T)) + measurementNoiseMatrixR + #Get relative likelihood + return multivariateNormalPDF(x=observation, mean=predictedObservation, cov=measurementCovariance) + +#Used in POMCP to sample a physical state (and Monte Carlo belief propagation) +def sampleFromFilter(filterToSample,rngKey): + """ + Returns random sample of the state using the current estimate and covariance estimate. DOES NOT return estimate (in general) + + Parameters + ---------- + filterToSample : tuple + mean : array, shape(numState) + The estimate of the physical state + covarianceP : array, shape(numState,numState) + The covariance estimate of the physical state + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + + Returns + ------- + x : array, shape(len(xHat)) + Sample of state + """ + + #We are using a convention where the filter is a n+1xn array, where the filter[0] = mean, filter[1:] = covariance! + return multivariateNormal(rngKey, filterToSample[0], filterToSample[1:]) diff --git a/failurePy/estimators/marginalizedFilter.py b/failurePy/estimators/marginalizedFilter.py new file mode 100644 index 0000000..cb5caf1 --- /dev/null +++ b/failurePy/estimators/marginalizedFilter.py @@ -0,0 +1,95 @@ +""" +Implements the marginalized filter, agnostic to the physical state estimator +""" +from functools import partial +import jax +import jax.numpy as jnp + + +#jit (we can use from functools import partial to make functions static args! @partial(jax.jit, static_argnames=['n'])) +@partial(jax.jit, static_argnames=['systemF','physicalStateSubEstimatorF','physicalStateJacobianF']) #Big slow down to compile, esp with EKF (2 min!) +def updateMarginalizedFilterEstimate(action,observation,previousBeliefTuple,possibleFailures,systemF,systemParametersTuple,physicalStateSubEstimatorF,physicalStateJacobianF): + """ + Function that propagates and updates the marginalized filter, given physical state estimator + + Parameters + ---------- + action : array, shape(numAct) + Action taken + observation : array, shape(numSenors) + Observation received + previousBeliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + Contents are in order: + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + Future optimization: + controlTransitionMatrix : array, shape(numState,numAct) + State Transition matrix resulting from constant control input + sensingMatrix : array, shape(numSen, numState) + C matrix + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + physicalStateSubEstimatorF : function + Function to update all of the conditional position filters + physicalStateJacobianF : function + Jacobian of the model for use in estimating. Can be none if physicalStateSubEstimatorF doesn't need it. + + Returns + ------- + updatedBeliefTuple : tuple + The tuple consists of an updated array of weights over possibleFailures and corresponding conditional filters + """ + + + #Get previous failure weights, filters + perviousFailureWeights = previousBeliefTuple[0] + previousFilters = previousBeliefTuple[1] + + #Get new filters + updatedFilters,relativeLikelihoods = physicalStateSubEstimatorF(action,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF) + + #print("relativeLikelihoods") + #print(relativeLikelihoods) + + #Update failure weights + updatedFailureWeights = updateFailureWeights(relativeLikelihoods,perviousFailureWeights) + #print("updatedFailureWeights") + #print(updatedFailureWeights) + #error + return (updatedFailureWeights,updatedFilters) + +def updateFailureWeights(relativeLikelihoods,perviousFailureWeights): + """ + Function that updates the failure weights of the marginalized filter via a Bayesian update + + Parameters + ---------- + relativeLikelihoods : array, shape(maxPossibleFailures) + Relative likelihood of each observation given the action taken and the previous (conditional) physical state filters + previousFailureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure before this update. Sorted to match possibleFailures + + Returns + ------- + updatedFailureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure after this update + """ + + #Create new failure weights. Adding stabilizing noise + updatedFailureWeights = jnp.multiply(relativeLikelihoods,perviousFailureWeights) + + #Normalize + return updatedFailureWeights/jnp.sum(updatedFailureWeights) diff --git a/failurePy/estimators/unscentedKalmanFilter.py b/failurePy/estimators/unscentedKalmanFilter.py new file mode 100644 index 0000000..c0a4ed0 --- /dev/null +++ b/failurePy/estimators/unscentedKalmanFilter.py @@ -0,0 +1,18 @@ +""" +Unscented kalman filter on non-linear dynamics and linear sensing. +Unscented propagation preserves higher moments of the uncertainty posterior than the standard EKF +KNOWN BUG: Update is currently numerically unstable + +Adapts the FilterPy library. +http://github.com/rlabbe/filterpy + +Documentation at: +https://filterpy.readthedocs.org + +FilterPy library is licensed under an MIT license. See the readme.MD file +for more information. + +Copyright 2014-2018 Roger R Labbe Jr. +""" +#Currently not a development priority pylint: skip-file +raise NotImplementedError diff --git a/failurePy/load/__init__.py b/failurePy/load/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/failurePy/load/estimatorConstructors.py b/failurePy/load/estimatorConstructors.py new file mode 100644 index 0000000..ea68b44 --- /dev/null +++ b/failurePy/load/estimatorConstructors.py @@ -0,0 +1,238 @@ +""" +Module for loading and constructing each estimator +""" + +from failurePy.load.yamlLoaderUtilityMethods import loadOptionalParameter, loadRequiredParameter, raiseIncompatibleSpecifications, raiseSpecificationNotFoundError + +#We do a lot of conditional importing to only load in the models, solvers, estimators as needed, and bind them to shared names to pass back to pipeline. +#We could change this to be done in sub modules, or import everything and conditionally bind the names, but we'd be importing a lot more than we need to. Maybe look into manifests? +# pylint: disable=import-outside-toplevel +def loadEstimatorAndBelief(inputDict,linear,numState,generalFaultFlag,silent): + """ + Load the proper estimator function and return it + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + linear : boolean + Whether the system is linear or not + numState : int + Number of states + silent : Boolean + If true, will not print anything out while loading + + Returns + ------- + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Physical state estimator for use with the marginal filter, if any + physicalStateSubEstimatorSampleF : function + Function that can sample a physical state from the sub estimator + beliefInitializationF : function + Function that creates the initial belief + """ + + estimatorFString = loadRequiredParameter("estimator",inputDict) + estimatorFString = ''.join(estimatorFString.lower().split()) #String processing, caps and spaces don't matter + if estimatorFString in ("marginalizedFilter".lower(), "marginalFilter".lower(), "marginalized", "marginal"): + #Import the marginalized filter + from failurePy.estimators.marginalizedFilter import updateMarginalizedFilterEstimate as estimatorF + elif estimatorFString in ("conservativeMarginalizedFilter".lower(), "conservativeMarginalFilter".lower(), + "conservativeMarginalized".lower(), "conservativeMarginal".lower()): + #Import the conservative marginalized filter + #Check for a different updateRate + updateRate = loadOptionalParameter("updateRate",inputDict,.25,silent=silent) + from failurePy.estimators.conservativeMarginalizedFilter import updateMarginalizedFilterEstimate as estimatorFUnWrapped + #Wrap with specified updateRate + def estimatorF(action,observation,previousBeliefTuple,possibleFailures,systemF,systemParametersTuple,physicalStateSubEstimatorF,physicalStateJacobianF): + return estimatorFUnWrapped(action,observation,previousBeliefTuple,possibleFailures,systemF,systemParametersTuple,physicalStateSubEstimatorF, + physicalStateJacobianF,updateRate=updateRate) + else: + raiseSpecificationNotFoundError(estimatorFString,"estimator") + + #Now always look for physicalStateSubEstimator, although only marginalized filters will use it, as it won't hurt anything + if "physicalStateSubEstimator" in inputDict: + physicalStateSubEstimatorF,physicalStateSubEstimatorSampleF,beliefInitializationF = loadPhysicalStateSubEstimator(inputDict,linear,numState,generalFaultFlag,silent=silent) + else: + specificationNotProvided = \ + "No specification for required parameter physicalStateSubEstimator provided. (When using the marginalized filter, the sub filter is required)" + raise ValueError(specificationNotProvided) + + return (estimatorF,physicalStateSubEstimatorF,physicalStateSubEstimatorSampleF,beliefInitializationF) + +def loadPhysicalStateSubEstimator(inputDict,linear,numState,generalFaultFlag,silent): #Lots of estimators. pylint: disable=too-many-branches + """ + Load the proper sub estimator function and return it + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + linear : boolean + Whether the system is linear or not + numState : int + Number of states + silent : Boolean + If true, will not print anything out while loading + + Returns + ------- + physicalStateSubEstimatorF : function + Physical state estimator for use with the marginal filter, if any + physicalStateSubEstimatorSampleF : function + Function that can sample a physical state from the sub estimator + beliefInitializationF : function + Function that creates the initial belief + """ + subEstimatorFString = ''.join(inputDict["physicalStateSubEstimator"].lower().split()) #String processing, caps and spaces don't matter + #Load in the filters. + #NOTE many shared components, but some are different, so need to check the type of filter and import the appropriate methods + #KF + if subEstimatorFString in ("kalmanFilter".lower(), "kalman", "kf"): + #Check that the system is linear + if not linear: + raiseIncompatibleSpecifications("A Kalman filter","a nonlinear system") + #Import estimator + if generalFaultFlag: + from failurePy.estimators.kalmanFilter import makeGeneralFaultKalmanFilter + physicalStateSubEstimatorF = makeGeneralFaultKalmanFilter() + else: + from failurePy.estimators.kalmanFilter import predictAndUpdateAll as physicalStateSubEstimatorF + from failurePy.estimators.kalmanFilterCommon import sampleFromFilter as physicalStateSubEstimatorSampleF + #initialize to uniform belief for now + from failurePy.estimators.beliefInitialization import uniformFailureBeliefMarginalizedKalman as beliefInitializationF + #EKF + elif subEstimatorFString in ("extendedKalmanFilter".lower(), "extendedKalman".lower(), "ekf"): + #Check that the system is nonlinear + if linear: + raiseIncompatibleSpecifications("An extended Kalman filter","a linear system") + + #Import estimator + if generalFaultFlag: + from failurePy.estimators.extendedKalmanFilterLinearSensing import makeGeneralFaultExtendedKalmanFilter + physicalStateSubEstimatorF = makeGeneralFaultExtendedKalmanFilter() + else: + from failurePy.estimators.extendedKalmanFilterLinearSensing import predictAndUpdateAll as physicalStateSubEstimatorF + from failurePy.estimators.kalmanFilterCommon import sampleFromFilter as physicalStateSubEstimatorSampleF + #initialize to uniform belief for now + from failurePy.estimators.beliefInitialization import uniformFailureBeliefMarginalizedKalman as beliefInitializationF + #FEJ-EKF + elif subEstimatorFString in {"firstEstimatesJacobianExtendedKalmanFilter".lower(), "firstEstimatesJacobianExtendedKalman".lower(), "firstEstimatesExtendedKalman".lower(), + "fejExtendedKalmanFilter".lower(),"fejkalman","fejekf"}: + #Check that the system is nonlinear + if linear: + raiseIncompatibleSpecifications("An extended Kalman filter","a nonlinear system") + + #Import estimator. Note it uses a different sampleFromFilter, as needs to modify for the first estimates + if generalFaultFlag: + from failurePy.estimators.firstEstimatesJacobianExtendedKalmanFilterLinearSensing import makeGeneralFaultFEJExtendedKalmanFilter + physicalStateSubEstimatorF = makeGeneralFaultFEJExtendedKalmanFilter() + else: + from failurePy.estimators.firstEstimatesJacobianExtendedKalmanFilterLinearSensing import predictAndUpdateAll as physicalStateSubEstimatorF + from failurePy.estimators.firstEstimatesJacobianExtendedKalmanFilterLinearSensing import sampleFromFilter as physicalStateSubEstimatorSampleF + #initialize to uniform belief for now + from failurePy.estimators.beliefInitialization import uniformFailureBeliefMarginalizedFEJKalman as beliefInitializationF + #UKF + elif subEstimatorFString in {"unscentedKalmanFilter".lower(), "unscentedKalman".lower(), "unscented","ukf"}: + #Import estimator + from failurePy.estimators.unscentedKalmanFilter import predictAndUpdateAll as physicalStateSubEstimatorFUnWrapped + from failurePy.estimators.unscentedKalmanFilter import createWeights + #We need to wrap up the Estimator parameters tuple here, so we don't need to worry about it later when calling it! + #We'll use a nested function. Note that since we only define this once, with no looping, we shouldn't need to worry about late closing bindings + #But if we were to modify the values of that tuple at any point, this could introduce hard to spot errors. + alpha = loadOptionalParameter("alpha",inputDict,.001,silent=silent) + beta = loadOptionalParameter("beta",inputDict,2,silent=silent) + kappa = loadOptionalParameter("kappa",inputDict,0,silent=silent) + meanWeights,covarianceWeights = createWeights(alpha,beta,kappa,numState) + filterParametersTuple = (alpha,kappa,meanWeights,covarianceWeights) #beta isn't needed anymore + #Define physicalStateSubEstimatorF to be unscented estimator, with the weighting parameters fixed + def physicalStateSubEstimatorF(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF): + return physicalStateSubEstimatorFUnWrapped(nominalAction,observation,previousFilters,possibleFailures,systemF,systemParametersTuple,physicalStateJacobianF,filterParametersTuple) + + from failurePy.estimators.kalmanFilterCommon import sampleFromFilter as physicalStateSubEstimatorSampleF + #initialize to uniform belief for now + from failurePy.estimators.beliefInitialization import uniformFailureBeliefMarginalizedKalman as beliefInitializationF + + else: + raiseSpecificationNotFoundError(subEstimatorFString,"physicalStateSubEstimator") + + return physicalStateSubEstimatorF,physicalStateSubEstimatorSampleF,beliefInitializationF #Will load or raise errors. pylint: disable=possibly-used-before-assignment + + +def loadFaultParticleMethods(inputDict,silent): + """ + Load the functions for updating sampling particles from fault space + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + silent : Boolean + If true, will not print anything out while loading + + Returns + ------- + failureParticleResampleF : function + Function that resamples the particles when needed + failureParticleResampleCheckF : function + Function that determines if resampling is needed + failureParticleInitializationF : function + Function that creates the initial failure particles + """ + + #Will check if we are in the general true fault in initial set or general true fault not in initial set case. Defaulting to in set to match experiment history + trueFaultInInitialParticlesFlag = loadOptionalParameter("trueFaultInInitialParticleSetFlag",inputDict,True,alternativeString="trueFaultKnownFlag", silent=silent) + + #Assumed that if we called this, we are using the general fault model, so some parameters are required. + #Exception to this is if we want the hybrid binary/general fault, in which case initialization is all that matters + particleInitializationMethodString = loadRequiredParameter("particleInitializationFunction",inputDict,alternativeString="particleInitializationMethod") + particleInitializationMethodString = ''.join(particleInitializationMethodString.lower().split()) #String processing, caps and spaces don't matter + + if particleInitializationMethodString in ("random", "randomInitialParticles".lower(),"randomInitialFailureParticles".lower()): + from failurePy.estimators.generalFaultSampling import randomInitialFailureParticles as failureParticleInitializationF + elif particleInitializationMethodString in ("biased","randomBiased".lower(), "randomBiasedInitialParticles".lower(),"randomBiasedInitialFailureParticles".lower(), + "biasedRandom".lower(), "biasedRandomInitialParticles".lower(),"biasedRandomInitialFailureParticles".lower()): + from failurePy.estimators.generalFaultSampling import biasedRandomInitialFailureParticles as failureParticleInitializationF + elif particleInitializationMethodString in ("biasedRedundant","randomBiasedRedundant".lower(), "randomBiasedRedundantInitialParticles".lower(), + "randomBiasedRedundantInitialFailureParticles".lower(),"biasedRandomRedundant".lower(), + "biasedRandomRedundantInitialParticles".lower(),"biasedRandomRedundantInitialFailureParticles".lower()): + + from failurePy.estimators.generalFaultSampling import biasedRandomInitialFailureParticlesRedundantBiases as failureParticleInitializationF + elif particleInitializationMethodString in ("hybrid", "binaryToDegradationFaults".lower(),"binaryDegradation".lower(),"binary"): + from failurePy.estimators.generalFaultSampling import binaryToDegradationFaults as failureParticleInitializationF + #Don't need the other parameters in this case! + return None, None, failureParticleInitializationF, trueFaultInInitialParticlesFlag + else: + raiseSpecificationNotFoundError(particleInitializationMethodString,"particle resample method") + + + particleResampleTypeString = loadRequiredParameter("particleResampleType",inputDict,alternativeString="particleResampleMethod") + particleResampleTypeString = ''.join(particleResampleTypeString.lower().split()) #String processing, caps and spaces don't matter + + if particleResampleTypeString in ("gaussian", "gaussianDiffusion".lower()): + from failurePy.estimators.generalFaultSampling import gaussianDiffusion as singleParticleResampleMethodF + faultParticleSampleSigma = loadOptionalParameter("faultParticleSampleSigma",inputDict,defaultValue=.1,silent=silent) + from failurePy.estimators.generalFaultSampling import makeFailureParticleResampleF + failureParticleResampleF = makeFailureParticleResampleF(singleParticleResampleMethodF,faultParticleSampleSigma) + + else: + raiseSpecificationNotFoundError(particleResampleTypeString,"particle resample method") + + particleResampleCheckString = loadRequiredParameter("particleResampleCheck",inputDict,alternativeString="particleResampleCondition") + particleResampleCheckString = ''.join(particleResampleCheckString.lower().split()) #String processing, caps and spaces don't matter + + + if particleResampleCheckString in ("ratio", "maxRatio".lower(),"maxRatioCheck".lower(),"maxRatioResampleCheck".lower()): + from failurePy.estimators.generalFaultSampling import makeMaxRatioResampleCheck as makeFailureParticleResampleCheckF + threshold = loadOptionalParameter("failureParticleResampleThreshold",inputDict,10) + failureParticleResampleCheckF = makeFailureParticleResampleCheckF(threshold) + + elif particleResampleCheckString in ("never", "neverSample".lower(), "noSample".lower(), "none"): + from failurePy.estimators.generalFaultSampling import neverResampleCheck as failureParticleResampleCheckF + + else: + raiseSpecificationNotFoundError(particleResampleCheckString,"particle resample condition") + + return failureParticleResampleF, failureParticleResampleCheckF, failureParticleInitializationF, trueFaultInInitialParticlesFlag #Will load or raise errors. pylint: disable=possibly-used-before-assignment diff --git a/failurePy/load/packageLoader.py b/failurePy/load/packageLoader.py new file mode 100644 index 0000000..62330d5 --- /dev/null +++ b/failurePy/load/packageLoader.py @@ -0,0 +1,34 @@ +""" +Module with methods for loading files from the package submodules +""" + +import sys +import importlib.resources as packageResources + +#import yaml + +#Guard against importing this with python < 3.9. +# Only this module has issues, so we are doing this instead of setting a package requirement +if sys.version_info < (3,9): + raise ValueError("Loading of package files is not supported for python < 3.9") + + +def getPackageSubDirectoryPath(package,subDirectory): + """ + Helper function to load the files of a specified package to make them available to the program. + This is in it's own function so we don't need to guard on python version in more than one spot + + Parameters + ---------- + package : python package + The package to load the files from + subDirectory : string + The subDirectory of the package we want a path too. + + Returns + ------- + packageSubDirectoryPath : string + Path to the package's subDirectory + """ + + return packageResources.files(package).joinpath(subDirectory) # pylint: disable=no-member diff --git a/failurePy/load/safetyLoader.py b/failurePy/load/safetyLoader.py new file mode 100644 index 0000000..1ed1a76 --- /dev/null +++ b/failurePy/load/safetyLoader.py @@ -0,0 +1,264 @@ +""" +Module to handle loading safety as part of the reward, as there a lot of configurable options. +""" + +#We do a lot of conditional importing to only load in the models, solvers, estimators as needed, and bind them to shared names to pass back to pipeline. +#We could change this to be done in sub modules, or import everything and conditionally bind the names, but we'd be importing a lot more than we need to. Maybe look into manifests? +# pylint: disable=import-outside-toplevel +import jax.numpy as jnp + +#Import all of the possible constraints, as it'll be messy to import them while looping through +from failurePy.rewards.safetyConstraint import makeCircularObstacleConstraintF,makeCircularSafeZoneConstraintF,makeLinearObstacleConstraintF,makeLinearSafeZoneConstraintF +from failurePy.load.yamlLoaderUtilityMethods import loadOptionalParameter, raiseSpecificationNotFoundError + +def loadSafetyConstrainedReward(inputDict,rewardF,physicalStateSubEstimatorSampleF,nMaxDepth=4,mSamples=100): + """ + Top-level method for loading the safety constrained rewards. + Specificity done in sub-methods + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + rewardF : function + Reward function that should accept a beliefTuple and an rngKey as arguments. + This reward should give positive rewards, as safety violations will return as 0 (no reward) + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + nMaxDepth : int (default=4) + Maximum depth of the tree. This is the horizon we need to be safe over (can't be safe over a longer horizon, as we don't search over it) + mSamples : int (default=100) + The number of samples to take to approximately evaluate the safety condition at each belief + + Returns + ------- + safetyConstrainedReward : function + Reward function to evaluate the beliefs with, with safety constraints enforced + safetyFunctionF : functions + Function that allows us to check the safety of a physicalState directly, useful for plotting or ground truth checking. + """ + + from failurePy.rewards.safetyConstraint import makeSafetyConstrainedReward as safetyConstrainedRewardFactoryF + + safetyFunctionEvaluationF, safetyFunctionF = loadSafetyModulatedRewardComponents(inputDict,physicalStateSubEstimatorSampleF,mSamples) + + return safetyConstrainedRewardFactoryF(rewardF,safetyFunctionEvaluationF,nMaxDepth), safetyFunctionF + +def loadSafetyPenalizedReward(inputDict,rewardF,physicalStateSubEstimatorSampleF, penalty=1): + """ + Top-level method for loading the safety penalized rewards. + Specificity done in sub-methods + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + rewardF : function + Reward function that should accept a beliefTuple and an rngKey as arguments. + This reward should give positive rewards, as safety violations will return as 0 (no reward) + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + penalty : float (default=1) + This is how big the penalty to the reward is. + + Returns + ------- + safetyConstrainedReward : function + Reward function to evaluate the beliefs with, with safety constraints enforced + safetyFunctionF : functions + Function that allows us to check the safety of a physicalState directly, useful for plotting or ground truth checking. + """ + + from failurePy.rewards.safetyConstraint import makeSafetyPenalizedReward as makeSafetyPenalizedRewardFactoryF + + safetyFunctionEvaluationF, safetyFunctionF = loadSafetyModulatedRewardComponents(inputDict,physicalStateSubEstimatorSampleF) + + return makeSafetyPenalizedRewardFactoryF(rewardF,safetyFunctionEvaluationF,penalty), safetyFunctionF + + +def loadSafetyModulatedRewardComponents(inputDict,physicalStateSubEstimatorSampleF,numSamples=100): + """ + Top-level method for loading the rewards that depend on the safety criteria. + Specificity done in sub-methods + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + numSamples : int (default=100) + The number of samples to take to approximately evaluate the safety condition at each belief + + Returns + ------- + safetyFunctionEvaluationF : functions + Method of checking the safety constraints + safetyFunctionF : functions + Function that allows us to check the safety of a physicalState directly, useful for plotting or ground truth checking. + """ + + #Load method for evaluating safety constraints + safetyFunctionEvaluationFactoryF = loadSafetyFunctionEvaluationF(inputDict) + + #Load type of safety constraints (inequality, etc.) + safetyFunctionFactoryF = loadSafetyFunctionF(inputDict) + + #Load the constraint functions + constraintFTuple = loadConstraintFunctionTuple(inputDict) + + #Now build up the constrained reward function + safetyFunctionF = safetyFunctionFactoryF(constraintFTuple) + + #Load allowable failure chance + allowableFailureChance = loadOptionalParameter("allowableFailureChance",inputDict,defaultValue=.05) + + safetyFunctionEvaluationF = safetyFunctionEvaluationFactoryF(safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples,allowableFailureChance) + + return safetyFunctionEvaluationF,safetyFunctionF + + +def loadSafetyFunctionEvaluationF(inputDict): + """ + Sub method to load safetyFunctionEvaluationF + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + + Returns + ------- + safetyFunctionEvaluationF : function + Function that implements a method to evaluate the safety constraints + """ + #Load how to check the safety constraints + if "safetyFunctionEvaluation" in inputDict: + #Need to interpret reward function + safetyConstraintFString = ''.join(inputDict["safetyFunctionEvaluation"].lower().split()) #String processing + if safetyConstraintFString in ("probabilisticSafetyConstraint".lower(), "probSafetyConstraint".lower(), "probabilistic", "probabilisticSafety".lower(), + "probabilisticSafetyFunction".lower(), "probSafetyFunction".lower(), "probabilisticSafetyFunctionEvaluation".lower()): + from failurePy.rewards.safetyConstraint import makeProbabilisticSafetyFunctionEvaluation as safetyFunctionEvaluationFactoryF + elif safetyConstraintFString in ("chebyshevInequalitySafetyFunction".lower(), "chebyshevIneqSafetyFunction".lower(), + "chebyshevSafetyFunction".lower(),"chebyshevInequalitySafetyConstraint".lower(), + "chebyshevIneqSafetyConstraint".lower(),"chebyshevSafetyConstraint".lower(),"chebyshevInequality".lower(), + "chebyshevIneq".lower(),"chebyshev","chebyshevInequalitySafetyFunctionEvaluation".lower()): + from failurePy.rewards.safetyConstraint import makeChebyshevIneqSafetyFunctionEvaluation as safetyFunctionEvaluationFactoryF + elif safetyConstraintFString in ("probabilisticAlphaSafetyFunctionEvaluation".lower(),"probabilisticAlpha".lower()): + from failurePy.rewards.safetyConstraint import makeProbabilisticAlphaSafetyFunctionEvaluation as safetyFunctionEvaluationFactoryF + elif safetyConstraintFString in ("filterMeansSafetyConstraint".lower(), "meansSafetyConstraint".lower(),"meanSafetyConstraint".lower(), + "filterMeansSafety".lower(), "meansSafety".lower(),"meanSafety".lower()): + raise NotImplementedError + else: #This is invalid + raiseSpecificationNotFoundError(safetyConstraintFString,"safetyFunctionEvaluation") + + else: + #Default behavior + print("Defaulting to probabilistic safety constraint") + from failurePy.rewards.safetyConstraint import makeProbabilisticSafetyFunctionEvaluation as safetyFunctionEvaluationFactoryF + + return safetyFunctionEvaluationFactoryF #Will load or raise errors. pylint: disable=possibly-used-before-assignment + +def loadSafetyFunctionF(inputDict): + """ + Sub method to load safetyFunctionF + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + + Returns + ------- + safetyFunctionF : function + A function that implements the specified type of safety constraints. + Evaluates the provided safety constraints against the type of condition (inequality, etc.) + """ + + #Load the constraints condition type (may remove later if we don't implement other types) + if "safetyFunction" in inputDict: + safetyFunctionFString = ''.join(inputDict["safetyFunction"].lower().split()) #String processing + if safetyFunctionFString in ("booleanInequalitySafetyFunction".lower(),"booleanSafetyFunction".lower(),"booleanInequalitySafety".lower(), + "inequalitySafetyFunction".lower(), "inequalitySafetyConstraint".lower(), "inequalitySafety".lower(), + "booleanSafety".lower(),"boolean","inequality","inequalitySafetyConstraintCondition".lower(),): + from failurePy.rewards.safetyConstraint import makeBooleanInequalitySafetyFunctionF as safetyFunctionFactoryF + elif safetyFunctionFString in ("worstCaseInequalitySafetyFunction".lower(), "worstInequalitySafetyFunction".lower(), + "worstCaseInequalitySafety".lower(),"worstInequalitySafety".lower(),"worstCaseInequality".lower(), + "worstInequality".lower(),"worstCase".lower(),"worst"): + from failurePy.rewards.safetyConstraint import makeWorstInequalitySafetyFunctionF as safetyFunctionFactoryF + else: + #This is invalid + raiseSpecificationNotFoundError(safetyFunctionFString,"safetyFunction") + else: + #Default behavior + print("Defaulting to inequality safety constraint conditions") + from failurePy.rewards.safetyConstraint import makeBooleanInequalitySafetyFunctionF as safetyFunctionFactoryF + + return safetyFunctionFactoryF #Will load or raise errors. pylint: disable=possibly-used-before-assignment + +def loadConstraintFunctionTuple(inputDict): + """ + Sub method to load constraintFTuple + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + + Returns + ------- + constraintFTuple : tuple + A function that implements the specified type of safety constraints. + Evaluates the provided safety constraints against the type of condition (inequality, etc.) + """ + + #Load the constraints condition type (may remove later if we don't implement other types) + if "safetyConstraints" in inputDict: + #Get list of specified constraints + safetyConstraintsList = inputDict["safetyConstraints"] + #Loop through and interpret each + constraintFList = [] + #Label indexes + constraintNameIdx = 0 + constraintParamsIdx = 1 + for safetyConstraint in safetyConstraintsList: + + constraintName = ''.join(safetyConstraint[constraintNameIdx].lower().split()) #String processing + #Obstacle Constraint + if constraintName in ("circularObstacleConstraint".lower(),"circularObstacle".lower()): + radius = safetyConstraint[constraintParamsIdx][0] + center = jnp.array(safetyConstraint[constraintParamsIdx][1]) + #Get constraint function from function factory. + constraintFList.append(makeCircularObstacleConstraintF(radius,center)) + #Safe zone constraint + elif constraintName in ("circularSafeZoneConstraint".lower(),"circularSafeZone".lower(),"circularSafe".lower()): + radius = safetyConstraint[constraintParamsIdx][0] + center = jnp.array(safetyConstraint[constraintParamsIdx][1]) + #Get constraint function from function factory. + constraintFList.append(makeCircularSafeZoneConstraintF(radius,center)) + #Linear obstacle constraint + elif constraintName in ("linearObstacleConstraint".lower(),"linearObstacle".lower()): + normalMatrix = jnp.array(safetyConstraint[constraintParamsIdx][0]) + offsetVector = jnp.array(safetyConstraint[constraintParamsIdx][1]) + #Get constraint function from function factory. + constraintFList.append(makeLinearObstacleConstraintF(normalMatrix,offsetVector)) + #Linear safe zone constraint + elif constraintName in ("linearSafeZoneConstraint".lower(),"linearSafeZone".lower(),"linearSafe".lower()): + normalMatrix = jnp.array(safetyConstraint[constraintParamsIdx][0]) + offsetVector = jnp.array(safetyConstraint[constraintParamsIdx][1]) + #Get constraint function from function factory. + constraintFList.append(makeLinearSafeZoneConstraintF(normalMatrix,offsetVector)) + #No match + else: + constraintNotImplemented=f"Specified constraint {safetyConstraint[constraintNameIdx]} is currently not implemented" + raise NotImplementedError(constraintNotImplemented) + + else: + #Default behavior + print("Defaulting to radius 10 safe zone centered at the origin") + + #Get constraint function from function factory. + constraintFList = [makeCircularSafeZoneConstraintF(10,jnp.array([0,0]))] + + #Cast to a hashable form then return (for jitting). Lists aren't hashable because they are mutable. + return tuple(constraintFList) diff --git a/failurePy/load/solverConstructors.py b/failurePy/load/solverConstructors.py new file mode 100644 index 0000000..5467114 --- /dev/null +++ b/failurePy/load/solverConstructors.py @@ -0,0 +1,381 @@ +""" +Module to build solvers such as sFEAST and others +""" + +import jax.numpy as jnp +import jax.random as jaxRandom + +from failurePy.load.yamlLoaderUtilityMethods import loadOptionalParameter, loadRequiredParameter, raiseIncompatibleSpecifications, raiseSpecificationNotFoundError + +#We do a lot of conditional importing to only load in the models, solvers, estimators as needed, and bind them to shared names to pass back to pipeline. +#We could change this to be done in sub modules, or import everything and conditionally bind the names, but we'd be importing a lot more than we need to. Maybe look into manifests? +# pylint: disable=import-outside-toplevel +def loadSolvers(inputDict,systemParametersTuple,dim,linear,legacyPaperCodeFlag,safetyFunctionF,silent): + """ + Load the specified solver function(s) and return them, along with need parameters + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + dim : int + Number of dimensions + linear : boolean + Whether the system is linear or not + legacyPaperCodeFlag : boolean + Flag to generate available actions using the same logic as the old v1 code for the original paper + safetyFunctionF : function + Function used to evaluate safety of a physical state. Only used by the cbf solver, as that does not use the rewardF to determine safety + silent : Boolean + If true, will not print anything out while loading + + Returns + ------- + solverFList : list + List of solver functions to try + solverParametersTuplesList : list + List of solver parameters needed. Contents of each tuple are: + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action + discretization : float + Discretization level or scheme + maxSimulationTime : float + Max simulation time (can be infinite). NOTE: Currently implemented by breaking loop after EXCEEDING time, NOT a hard cap + explorationParameter : float + Weighting on exploration vs. exploitation + nMaxDepth : int + Max depth of the tree + discountFactor : float + Discount on future rewards, should be in range [0,1] + solverNamesList : list + List of names of solvers, for data logging + """ + #Check for parameters first + solverFStringList = loadRequiredParameter("solverFList",inputDict) + #requiredParameterCheck("solverParametersListsList") + #requiredParameterCheck("solverNames") + + #Get common parameters + if linear: + influenceMatrixIdx = 2 + influenceMatrix = systemParametersTuple[influenceMatrixIdx] + numAct = len(influenceMatrix[0]) + elif dim == 3: + positionInfluenceMatrixIdx = 0 + reactionWheelInfluenceMatrixIdx = 2 + influenceMatrix = systemParametersTuple[positionInfluenceMatrixIdx] + numAct = len(influenceMatrix[0]) + len(systemParametersTuple[reactionWheelInfluenceMatrixIdx]) + else: + raise NotImplementedError + maxNumActions = loadOptionalParameter("maxNumActions",inputDict,defaultValue=min(20,numAct**2),silent=silent) + specifiedActions = loadOptionalParameter("specifiedActions",inputDict,defaultValue=None,silent=silent) + + #Create action list (shared by solvers) + actionRNGSeed = loadOptionalParameter("actionRNGSeed",inputDict,defaultValue=0,silent=silent) + actionRNGKey = jaxRandom.PRNGKey(actionRNGSeed) + if legacyPaperCodeFlag: + from failurePy.utility.legacyPaperCode import makeAvailableActions as legacyMakeAvailableActions + #Note this always returns actions of size 1, as the paper did, and ignores the maxNumActions flag + availableActions = legacyMakeAvailableActions(numAct,influenceMatrix) + print(f"legacyPaperCodeFlag set to True, overriding available actions configuration. ({len(availableActions)} total available actions)") + else: + availableActions = makeAvailableActions(maxNumActions,numAct,actionRNGKey,specifiedActions) + + #Loop through and add solvers to list + solverFList,solverParametersTuplesList,solverNamesList = loadEachSolver(solverFStringList,inputDict,availableActions,silent,safetyFunctionF) + + + + return solverFList,solverParametersTuplesList,solverNamesList + +def loadEachSolver(solverFStringList,inputDict,availableActions,silent,safetyFunctionF): + """ + Helper method to load each solver one at a time. + """ + + solverFList = [] + solverParametersTuplesList = [] + solverNamesList = [] + + + for solverFString in solverFStringList: + if solverFString.lower() in ("SFEAST".lower(), "s-FEAST".lower()): + from failurePy.solvers.sFEAST import solveForNextAction as SFEASTSolverF + solverFList.append(SFEASTSolverF) + + loadSFEASTParametersAndAppend(inputDict, solverParametersTuplesList, availableActions,silent=silent) + + #Add name to list + solverNamesList.append("SFEAST") + + elif solverFString.lower() == "preSpecified".lower(): + from failurePy.solvers.preSpecifiedPolicy import PreSpecifiedPolicy + + #Instantiate object, then pass method as the "solver" + preSpecifiedPolicyInstance = PreSpecifiedPolicy() + solverFList.append(preSpecifiedPolicyInstance.takeNextAction) + + #No parameters needed, but availableActions needed for compatibility with pipeline, which expects access to the null action + solverParametersTuplesList.append((availableActions,)) + + #Add name to list + solverNamesList.append("PreSpecified") + elif solverFString.lower() == "realTimeSFEAST".lower(): + from failurePy.solvers.realTimeSFEAST import solveForNextAction as realTimeSFEASTSolverF + solverFList.append(realTimeSFEASTSolverF) + + loadSFEASTParametersAndAppend(inputDict, solverParametersTuplesList, availableActions,silent=silent) + + #Add name to list + solverNamesList.append("realTimeSFEAST") + #cbf solver + elif solverFString.lower() in ("cbf", "controlBarrierFunction".lower()): + from failurePy.solvers.cbf import solveForNextAction as cbfSolverF + solverFList.append(cbfSolverF) + + numActuators = len(availableActions[0]) + solverParametersTuplesList.append((numActuators,safetyFunctionF)) + #Add name to list + solverNamesList.append("cbf") + elif solverFString.lower() == "greedy": + from failurePy.solvers.greedy import solveForNextAction as greedySolverF + solverFList.append(greedySolverF) + + loadGreedyParametersAndAppend(inputDict, solverParametersTuplesList, availableActions,silent=silent) + + #Add name to list + solverNamesList.append("greedy") + elif solverFString.lower() == "scp": + from failurePy.solvers.scp import solveForNextAction as scpSolverF + solverFList.append(scpSolverF) + + loadScpParametersAndAppend(inputDict,solverParametersTuplesList,availableActions,safetyFunctionF,silent=silent) + + solverNamesList.append("scp") + else: + raiseSpecificationNotFoundError(solverFString,"solver") + + return solverFList,solverParametersTuplesList,solverNamesList + +def loadSFEASTParametersAndAppend(inputDict, solverParametersTuplesList, availableActions, silent): + """ + Sub method to load all the SFEAST parameters + """ + discretization = loadOptionalParameter("discretization",inputDict,defaultValue=1,silent=silent) + maxSimulationTime, explorationParameter,nMaxDepth,discountFactor = loadCommonParameters(inputDict,silent) + + #Add to list of parameters + solverParametersTuplesList.append((availableActions,discretization,maxSimulationTime,explorationParameter,nMaxDepth,discountFactor)) + +def loadGreedyParametersAndAppend(inputDict, solverParametersTuplesList, availableActions,silent): + """ + Sub method to load all the greedy parameters + """ + discretization = loadOptionalParameter("discretization",inputDict,defaultValue=1,silent=silent) + + #Add to list of parameters + solverParametersTuplesList.append((availableActions,discretization)) + +def loadScpParametersAndAppend(inputDict, solverParametersTuplesList, availableActions, safetyFunctionF, silent): + """ + Sub method to load all the scp parameters + """ + + numAct = len(availableActions[0]) + horizon = loadOptionalParameter("nMaxDepth",inputDict,defaultValue=4,silent=silent) + actuationLimit = jnp.max(availableActions) + + #Add to list of parameters + solverParametersTuplesList.append((numAct,safetyFunctionF,horizon,actuationLimit)) + +def loadCommonParameters(inputDict,silent): + "Sum method to load common solver parameters" + + maxSimulationTime = loadOptionalParameter("maxSimulationTime",inputDict,defaultValue=jnp.inf,silent=silent) + explorationParameter = loadOptionalParameter("explorationParameter",inputDict,defaultValue=1.2,silent=silent) + nMaxDepth = loadOptionalParameter("nMaxDepth",inputDict,defaultValue=4,silent=silent) + discountFactor = loadOptionalParameter("discountFactor",inputDict,defaultValue=.9,silent=silent) + + return maxSimulationTime, explorationParameter,nMaxDepth,discountFactor + +def makeAvailableActions(numActions,numAct,rngKey,specifiedActions=None): + """ + Generate the actions the solvers will be allowed to consider. + No longer scaled by testActuation size, now always 0 or 1, where 1 = full on for duration + + Parameters + ---------- + numActions : int + Number of actions that should be generated + numAct : int + The number of actuators there are + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + specifiedActions : list or string (default=None) + Optionally provided default actions from the yaml file + + Returns + ------- + availableActions : array, shape(numActions,numAct) + Array of actions that can be taken. First action is always null action + """ + + availableActions = jnp.zeros((numActions,numAct)) + + #Check for pre-specified actions and set the last x actions to them, then generate less random ones + numSpecifiedActions = 0 + if specifiedActions is not None: + #Check if it was a string, as this is a specific type + if isinstance(specifiedActions,str): + specifiedActionString = ''.join(specifiedActions.lower().split()) + if specifiedActionString in ("redundantXY".lower(),"redundantPosition".lower(),"redundantTranslation".lower()): + specifiedActions = redundantXYActions(numAct) + elif specifiedActionString in ("redundantXYT".lower(),"redundant".lower()): + specifiedActions = redundantXYTActions(numAct) + else: + specifiedActionStringNotImplemented = f"The specified actions given by {specifiedActions} are not currently implemented." + raise NotImplementedError(specifiedActionStringNotImplemented) + #Treat as an array + else: + raise NotImplementedError + + numSpecifiedActions = len(specifiedActions) + availableActions = availableActions.at[-numSpecifiedActions:].set(specifiedActions) + + #Check if all actions already specified (-1 because can specify 0 as first action by providing numActions-1) + if numSpecifiedActions >= numActions - 1: + return availableActions + + if numActions-numSpecifiedActions < 2**numAct: + actionIdxes = jnp.array([0]) + #Force us to generate an array without 0 in it. Hacky, but should work + while 0 in actionIdxes: + rngKey, rngSubKey = jaxRandom.split(rngKey) # have to split in loop, or would infinite loop since key won't be updated + actionIdxes = jaxRandom.choice(rngSubKey, 2**numAct, (numActions-1-numSpecifiedActions,),replace=False) + else: + actionIdxes = jnp.arange(1,2**numAct) + + + + #Generate actions (first action is null action) + for iAction, actionIdx in enumerate(actionIdxes): + action = [] + for jActuator in range(numAct): + #Generate combinatorially (binary number encoding) + action.append((int(actionIdx/(2**(jActuator)))%2)) #Order of operations matters here! + availableActions = availableActions.at[iAction+1].set(jnp.array(action)) + + return availableActions + +def redundantXYActions(numAct): + """ + Method that returns actions such that thrusters in each direction are both fired + + Parameters + ---------- + numAct : int + How many actuators we have. + We assume actuators are redundant in pairs and there are 8, so this is just to check. + + Returns + ------- + specifiedActions : array + Array of the specified actions to take. + + """ + + if numAct !=8: + raiseIncompatibleSpecifications("Specified actions redundantXYActions","not exactly 8 actuators") + + return jnp.array([[1,1,0,0,0,0,0,0], + [0,0,1,1,0,0,0,0], + [0,0,0,0,1,1,0,0], + [0,0,0,0,0,0,1,1],]) + +def redundantXYTActions(numAct): + """ + Method that returns actions such that thrusters in each direction are both fired + and pure rotation actuations are fired + + Parameters + ---------- + numAct : int + How many actuators we have. + We assume actuators are redundant in pairs and there are 8, so this is just to check. + + Returns + ------- + specifiedActions : array + Array of the specified actions to take. + + """ + + if numAct !=8: + raiseIncompatibleSpecifications("Specified actions redundantXYTActions","not exactly 8 actuators") + + return jnp.array([[1,1,0,0,0,0,0,0], + [0,0,1,1,0,0,0,0], + [0,0,0,0,1,1,0,0], + [0,0,0,0,0,0,1,1], + [1,0,1,0,0,0,0,0], + [0,1,0,1,0,0,0,0], + [0,0,0,0,1,0,1,0], + [0,0,0,0,0,1,0,1],]) + +def makeDistributedAvailableActions(maxNumActions,rngKey,specifiedActions,graphEdges): #Will fix when fully implemented pylint: disable=unused-argument + """ + Generate the actions the solvers will be allowed to consider in the distributed setting. + Here each action is an agent to point to and ping, including recursively. Need to multiplex recursive actions + + Parameters + ---------- + numActions : int + Number of actions that should be generated + numAct : int + The number of actuators there are + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + specifiedActions : list or string (default=None) + Optionally provided default actions from the yaml file + + Returns + ------- + availableActions : array, shape(numActions,numAct) + Array of actions that can be taken. First action is always null action + """ + + #Currently not implemented, returning None + import warnings + warnings.warn("makeDistributedAvailableActions isn't implemented, only random distributed actions will work.") + + #Get num agents by knowing every agent has at least one edge so will be listed in edges + numAgents = len(jnp.unique(graphEdges)) #Flattens so is counting number of different entries = number of nodes! + + + #Return possible pointings to make the agents move randomly + #Will for now generate a random 100 actions from the edges + + availableActions = [] + for iAction in range(100):# pylint: disable=unused-variable + #Generate a random new pointing + action = jnp.zeros(numAgents) + rngKey, rngSubKey = jaxRandom.split(rngKey) + numReorientations = jaxRandom.randint(rngSubKey,shape=(),minval=1,maxval=numAgents) + #Draw random edges as the reorientation + for jReorientation in range(numReorientations): # pylint: disable=unused-variable + rngKey, rngSubKey = jaxRandom.split(rngKey) + edge = jaxRandom.choice(rngSubKey,graphEdges) + + rngKey, rngSubKey = jaxRandom.split(rngKey) + #Pick which agent is turning and which is the target + actingVertex = jaxRandom.choice(rngSubKey,jnp.array([0,1])) + actingAgent = edge[actingVertex] + targetAgent = edge[1-actingVertex] + #Have the actor point at the target (yes this can overwrite, that's okay) + action = action.at[actingAgent-1].set(targetAgent) #Need to zero index to select agent in action + availableActions.append(action) + + + return jnp.array(availableActions) diff --git a/failurePy/load/systemConstructors.py b/failurePy/load/systemConstructors.py new file mode 100644 index 0000000..158fef2 --- /dev/null +++ b/failurePy/load/systemConstructors.py @@ -0,0 +1,290 @@ +""" +Module for loading and constructing each system +""" + +import os + +import numbers + +import jax.numpy as jnp +from jax.scipy.linalg import block_diag as blockDiag + +from failurePy.load.yamlLoaderUtilityMethods import checkParameter, loadOptionalParameter, loadRequiredParameter, raiseIncompatibleSpecifications, getInputDict, raiseSpecificationNotFoundError + +#We do a lot of conditional importing to only load in the models, solvers, estimators as needed, and bind them to shared names to pass back to pipeline. +#We could change this to be done in sub modules, or import everything and conditionally bind the names, but we'd be importing a lot more than we need to. Maybe look into manifests? +# pylint: disable=import-outside-toplevel +def loadAndBuildSingleAgentSystem(inputDict,providedFailure,generalFaultFlag,silent): + """ + Load which type of system we're running and initializes appropriately + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + providedFailure : array, shape(numAct+numSen) (default=None) + Provided failure (if any) to have each trial use. Here for consistency checking + generalFaultFlag : Boolean + If we are using general fault model or not + silent : Boolean + If true, will not print anything out while loading + + Returns + ------- + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + dim : int + Number of dimensions + linear : boolean + Whether the system is linear or not + dt : float + The time between time steps of the experiment + sigmaW : float or array + Standard deviation representing the process noise. + sigmaV : float or array + Standard deviation representing the sensor noise. + numAct : int + Number of actuators this system has + """ + + #Get the dimensions (2 or less = linear system) + dim = loadRequiredParameter("dim", inputDict) + + #Check for linear flag + #Determine default + if dim<=3: + default = True + defaultMessage = "linear system as dim <= 3." + else: + default = False + defaultMessage = "non-linear system as dim > 3." + + linear = loadOptionalParameter("linear",inputDict,default,defaultMessage,silent=silent) + #Check for consistency (only inconsistent if user specified values don't match) + if not linear and dim <=2: + raiseIncompatibleSpecifications("dim <=2","a non-linear system") + if linear and dim > 3: + raiseIncompatibleSpecifications("dim > 3","a linear system") + + #Start list, will cast to a tuple (to be immutable) + systemParametersList = [] + + #Get shared parameters + numAct = loadOptionalParameter("numAct",inputDict,None,"model default of 2 per direction",silent=silent) + numSen = loadOptionalParameter("numSen",inputDict,None,"model default of 2 per axis",silent=silent) + #dt is pretty universal, so making an exception for it + dt = loadOptionalParameter("dt",inputDict,1,silent=silent) # pylint: disable=invalid-name + + #Make linear or non linear system + if linear: + systemParametersList, systemF, physicalStateJacobianF, sensingMatrix, numAct, numSen = importLinearSystem(inputDict,systemParametersList,dt,dim,numAct,numSen,generalFaultFlag,silent=silent) + numWheels = 0 #Just to avoid possible referencing this when it isn't set + elif dim == 3: + systemParametersList, systemF, physicalStateJacobianF, sensingMatrix, numWheels, numAct, numSen = importThreeDofSystem(inputDict,systemParametersList,dt,numAct, + numSen,generalFaultFlag,silent=silent) + else: + raise NotImplementedError + + #Consistency check for the provided failure (if all provided) + if providedFailure is not None: + if generalFaultFlag and len(providedFailure) != 2*(numAct+numSen): + raiseIncompatibleSpecifications(f"A provided general failure of length {len(providedFailure)}", + f"{numAct} actuators and {numSen} sensors (expected length {2*(numAct+numSen)})") + elif not generalFaultFlag and len(providedFailure) != numAct+numSen: + raiseIncompatibleSpecifications(f"A provided failure of length {len(providedFailure)}", + f"{numAct} actuators and {numSen} sensors (expected length {(numAct+numSen)}") + + #Currently all noise handled the same time + covarianceQ, diagCovarianceR, sigmaW, sigmaV = loadNoise(inputDict,linear,dim,dt,sensingMatrix,numWheels) + + #Keep only the covariance matrices in systemParameters + #Trying to enable hardware emulation + if "hardwareEmulationFlag" in inputDict and inputDict["hardwareEmulationFlag"]: + raise NotImplementedError #THIS DOESN'T WORK! The estimator gets the same Q!!!!! (so converge too fast) + #systemParametersList.append(.02*covarianceQ) + #systemParametersList.append(jnp.diag(.1*diagCovarianceR)) + + systemParametersList.append(covarianceQ) + systemParametersList.append(jnp.diag(diagCovarianceR)) + + return systemF,tuple(systemParametersList), physicalStateJacobianF, dim, linear, dt, sigmaW, sigmaV, numAct + +def importLinearSystem(inputDict,systemParametersList,dt,dim,numAct,numSen,generalFaultFlag,silent): #dt is pretty universal, so making an exception for it, pylint: disable=invalid-name + """ + Sub method to import the linear system + """ + #General or original fault model + if generalFaultFlag: + from failurePy.models.linearModelGeneralFaults import simulateSystemWrapper as systemF + else: + from failurePy.models.linearModel import simulateSystemWrapper as systemF + from failurePy.models.linearModel import makeDynamicsMatrix, makeInfluenceMatrix, makeSensingMatrix, makeStateTransitionMatrices + + physicalStateJacobianF = None + + #Make systemParametersList + ########################## + #Make the base matrices + + #Get s/c mass for scaling influence matrices + spacecraftMass = loadOptionalParameter("spacecraftMass",inputDict,defaultValue=1,silent=silent) + + #Make dynamics and influence matrices + dynamicsMatrix = makeDynamicsMatrix(dim) + influenceMatrix = makeInfluenceMatrix(dim,spacecraftMass,numAct) + numAct = len(influenceMatrix[0]) + #Make sensing matrices + sensingMatrix = makeSensingMatrix(dim,numSen) + numSen = len(sensingMatrix) + + stateTransitionMatrix,controlTransitionMatrix = makeStateTransitionMatrices(dynamicsMatrix,dt,influenceMatrix) + systemParametersList.append(stateTransitionMatrix) + systemParametersList.append(controlTransitionMatrix) + systemParametersList.append(sensingMatrix) + + return systemParametersList, systemF, physicalStateJacobianF, sensingMatrix, numAct, numSen + +def importThreeDofSystem(inputDict,systemParametersList,dt,numAct,numSen,generalFaultFlag,silent): #dt is pretty universal, so making an exception for it, pylint: disable=invalid-name + """ + Sub method to import the 3DOF system + """ + #General or original fault model + if generalFaultFlag: + from failurePy.models.threeDOFGeneralFaultModel import simulateSystemWrapper as systemF + from failurePy.models.threeDOFGeneralFaultModel import dynamicsJacobianWrapper as physicalStateJacobianF + else: + from failurePy.models.threeDOFModel import simulateSystemWrapper as systemF + from failurePy.models.threeDOFModel import dynamicsJacobianWrapper as physicalStateJacobianF + from failurePy.models.threeDOFModel import makeInfluenceMatrices, makeSensingMatrix, makeCalibratedInfluenceMatricesNoWheels + + #Need to check for calibrated parameters or use model + if checkParameter("positionInfluenceMatrix",inputDict) and checkParameter("rotationInfluenceMatrix",inputDict) and checkParameter("reactionWheelInfluenceMatrix",inputDict): + positionInfluenceMatrix = loadRequiredParameter("positionInfluenceMatrix",inputDict) + rotationInfluenceMatrix = loadRequiredParameter("rotationInfluenceMatrix",inputDict) + reactionWheelInfluenceMatrix = loadRequiredParameter("reactionWheelInfluenceMatrix",inputDict) + numWheels = len(reactionWheelInfluenceMatrix) + + elif checkParameter("positionInfluenceMatrix",inputDict) or checkParameter("rotationInfluenceMatrix",inputDict) or checkParameter("reactionWheelInfluenceMatrix",inputDict): + incompatibleSpecifications = "If any calibrated influence matrices are provided, all arrays must be provided. Mixing modeled and calibrated behavior currently unsupported" + raise ValueError(incompatibleSpecifications) + + elif checkParameter("positionInfluence",inputDict) and checkParameter("rotationInfluence",inputDict): + positionInfluence = loadRequiredParameter("positionInfluence",inputDict) + rotationInfluence = loadRequiredParameter("rotationInfluence",inputDict) + positionInfluenceMatrix, rotationInfluenceMatrix = makeCalibratedInfluenceMatricesNoWheels(positionInfluence,rotationInfluence) + #OVERRIDES numWheels + numWheels = 0 + reactionWheelInfluenceMatrix = jnp.ones(numWheels) + elif checkParameter("positionInfluence",inputDict) and checkParameter("rotationInfluence",inputDict) and checkParameter("reactionWheelInfluence",inputDict): + raise NotImplementedError + + elif checkParameter("positionInfluence",inputDict) or checkParameter("rotationInfluence",inputDict) or checkParameter("reactionWheelInfluence",inputDict): + incompatibleSpecifications = "positionInfluence and rotationInfluence must be supplied together and with reactionWheelInfluence. " +\ + "Mixing modeled and calibrated behavior currently unsupported" + raise ValueError(incompatibleSpecifications) + + else: + #Get s/c mass for scaling influence matrices + spacecraftMass = loadOptionalParameter("spacecraftMass",inputDict,defaultValue=1,silent=silent) + + #Get s/c inertia for scaling influence matrices + spacecraftMoment = loadOptionalParameter("spacecraftMoment",inputDict,defaultValue=1,silent=silent) + + #Get num wheels + numWheels = loadOptionalParameter("numWheels",inputDict,2,silent=silent) + + #Get lever arms + leverArm = loadOptionalParameter("thrusterLeverArm",inputDict,.4,silent=silent) + + #Get wheel inertia for influence + reactionWheelMoment = loadOptionalParameter("reactionWheelMoment",inputDict,defaultValue=None, defaultMessage=".05 kg m^2 per wheel",silent=silent) + if isinstance(reactionWheelMoment, numbers.Number): + reactionWheelMoment = reactionWheelMoment*jnp.ones(numWheels) + + #Make the actuation and sensing matrices + positionInfluenceMatrix, rotationInfluenceMatrix, reactionWheelInfluenceMatrix = makeInfluenceMatrices(spacecraftMass,spacecraftMoment,leverArm,numWheels,numAct,reactionWheelMoment) + + numAct = len(positionInfluenceMatrix[0]) + len(reactionWheelInfluenceMatrix) + + sensingMatrix = makeSensingMatrix(numWheels,numSen) + numSen = len(sensingMatrix) + + #Check for errors (note if calibrated matrices given, we won't enter here by construction) + if len(reactionWheelInfluenceMatrix) != numWheels: + raiseIncompatibleSpecifications(f"{numWheels} reaction wheels",f"reactionWheelMoment array of length {len(reactionWheelMoment)}") + + positionCoefficientOfFriction = loadOptionalParameter("positionCoefficientOfFriction",inputDict,0,silent=silent) + rotationalCoefficientOfFriction = loadOptionalParameter("rotationalCoefficientOfFriction",inputDict,0,silent=silent) + + systemParametersList.append(positionInfluenceMatrix) + systemParametersList.append(rotationInfluenceMatrix) + systemParametersList.append(reactionWheelInfluenceMatrix) + systemParametersList.append(positionCoefficientOfFriction) + systemParametersList.append(rotationalCoefficientOfFriction) + systemParametersList.append(sensingMatrix) + systemParametersList.append(dt) + + return systemParametersList, systemF, physicalStateJacobianF, sensingMatrix, numWheels, numAct, numSen + +def loadNoise(inputDict,linear,dim,dt,sensingMatrix,numWheels): #dt is pretty universal, so making an exception for it, pylint: disable=invalid-name + """ + Sub method to load the noise parameters + + Checks if there is a single sigma value + Produce block diagonal process noise to match model from Bar-Shalom. "Estimation with Applications To Tracking and Navigation". John Wiley & Sons, 2001. Page 270. + Notice power spectral density = variance here + """ + if "sigma" in inputDict: + sigma = inputDict["sigma"] + #We think of our noise in terms of sigmaW and sigmaV, so set them to be the same explicitly + sigmaW = sigma + sigmaV = sigma + covarianceQBlock = sigmaW**2*jnp.array([[(dt**3)/3, (dt**2)/2], + [(dt**2)/2, dt ]]) #We'll assume same block for each dimension + covarianceQ = jnp.kron(jnp.eye(dim,dtype=int),covarianceQBlock) + #Measurement noise assumed to be independent + diagCovarianceR = sigmaV**2*jnp.ones(len(sensingMatrix)) + elif "sigmaW" in inputDict and "sigmaV" in inputDict: + sigmaW = inputDict["sigmaW"] + sigmaV = inputDict["sigmaV"] + #Check if given array or scalar + if isinstance(sigmaW, numbers.Number): + covarianceQBlock = sigmaW**2*jnp.array([[(dt**3)/3, (dt**2)/2], + [(dt**2)/2, dt ]]) #We'll assume same block for each dimension + #Stack covarianceQBlock into block matrix + covarianceQ = jnp.kron(jnp.eye(dim,dtype=int),covarianceQBlock) + #Otherwise assume it's an array + elif len(sigmaW) == dim: + covarianceQBlocks = [] + for iDim in range(dim): + covarianceQBlocks.append(sigmaW[iDim]**2*jnp.array([[(dt**3)/3, (dt**2)/2], + [(dt**2)/2, dt ]])) + #Make covariance out of blocks (unpack first) + covarianceQ = blockDiag(*covarianceQBlocks) + else: + #Currently not checking + notImplemented = "Setting more complicated process noises than per dimensions is currently not supported." + raise NotImplementedError(notImplemented) + + if isinstance(sigmaV, numbers.Number): + diagCovarianceR = sigmaV**2*jnp.ones(len(sensingMatrix)) + #Otherwise assume it's an array, return only first value for save directories + else: + sigmaV = jnp.array(sigmaV) + if len(sigmaV) != len(sensingMatrix): + raiseIncompatibleSpecifications(f"sigmaV with length {len(sigmaV)}",f"a system with {len(sensingMatrix)} sensors") + else: + diagCovarianceR = jnp.square(sigmaV) + else: + specificationNotProvided = "No specification for required parameter sigma (or sigmaW AND sigmaV) provided." + raise ValueError(specificationNotProvided) + + #Need to add noise for wheels (will make infinitesimal, needs to be non zero though for estimation) + if not linear: + wheelCovarianceQ = jnp.diag(.001* jnp.ones(numWheels)) + covarianceQ = blockDiag(covarianceQ,wheelCovarianceQ) + return covarianceQ, diagCovarianceR, sigmaW, sigmaV #Will load or raise errors. pylint: disable=possibly-used-before-assignment diff --git a/failurePy/load/yamlHardwareLoader.py b/failurePy/load/yamlHardwareLoader.py new file mode 100644 index 0000000..7edf480 --- /dev/null +++ b/failurePy/load/yamlHardwareLoader.py @@ -0,0 +1,27 @@ +""" +Methods for loading the experiment parameters from a yaml file that are specific to hardware emulation +Future TODO: could add more robust input checking/sanitizing, currently assuming user will do this correctly, but typos in the yamls could lead to weird behavior. +""" + +from failurePy.load.yamlLoaderUtilityMethods import getInputDict, loadOptionalParameter + + +def loadRealTimeParams(configFilePath): + """ + Loads hardware emulation experiment parameters from a .yaml file + + Parameters + ---------- + configFilePath : String + Absolute path to the config file for the experiment + + Returns + ------- + initialAction : array, len(numAct) + Initial action to take (zeros if none provided) + """ + inputDict = getInputDict(configFilePath) + + initialAction = loadOptionalParameter("initialAction",inputDict,None) + + return initialAction diff --git a/failurePy/load/yamlLoader.py b/failurePy/load/yamlLoader.py new file mode 100644 index 0000000..bf843a9 --- /dev/null +++ b/failurePy/load/yamlLoader.py @@ -0,0 +1,570 @@ +""" +Collection of methods for loading the experiment parameters from a yaml file +Future TODO: could add more robust input checking/sanitizing, currently assuming user will do this correctly, but typos in the yamls could lead to weird behavior. +""" +import numbers +import multiprocessing as mp #For setting up multiprocessing + +import jax.numpy as jnp +from failurePy.load.yamlLoaderUtilityMethods import getInputDict, loadOptionalParameter, loadRequiredParameter, raiseIncompatibleSpecifications +from failurePy.load.yamlLoaderUtilityMethods import checkExperimentParametersConsistency, checkParameter, raiseSpecificationNotFoundError +from failurePy.load.safetyLoader import loadSafetyConstrainedReward #, loadSafetyPenalizedReward #Not used by current proof +from failurePy.load.systemConstructors import loadAndBuildSingleAgentSystem +from failurePy.load.solverConstructors import loadSolvers +from failurePy.load.estimatorConstructors import loadEstimatorAndBelief, loadFaultParticleMethods + + +#We do a lot of conditional importing to only load in the models, solvers, estimators as needed, and bind them to shared names to pass back to pipeline. +#We could change this to be done in sub modules, or import everything and conditionally bind the names, but we'd be importing a lot more than we need to. Maybe look into manifests? +# pylint: disable=import-outside-toplevel +def loadExperimentParamsFromYaml(configFilePath,extraData=False): + """ + Loads experiment parameters from a .yaml file. Wraps loadExperimentParams + """ + inputDict = getInputDict(configFilePath) + return loadExperimentParams(inputDict,extraData) + +def loadExperimentParams(inputDict,extraData=False,silent=False): + """ + Loads experiment parameters from an input dict. + + Parameters + ---------- + configFilePath : String + Absolute path to the config file for the experiment + extraData : Boolean + If true, return additional variables used to build the models and solvers + but not needed by pipeline. Used for easier set up of ROS models + silent : Boolean + If true, will not print anything out while loading + + Returns + ------- + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + The contents should be as follows: + nSimulationsPerTreeList : list, len(numTrials) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + dt : float + The time between time steps of the experiment + nExperimentSteps : int + How many time steps are in the experiment + nTrialsPerPoint : int + The number of repeated experiments per configuration. + diagnosisThreshold : float + Level of the reward to consider high enough to return an answer. + rngKeysOffset : int + Offset to the initial PRNG used in generating the initial failure states and randomness in the trials. + This is added to the trial number to allow for different experiments to be preformed + initialState : array, shape(numState) + Initial state if any provided. + nMaxComponentFailures : int + Maximum number of simultaneous failures of components that can be considered + nMaxPossibleFailures : int + Maximum number of possible failures to consider. If larger than the number of possible unique failures, all possibilities are considered + providedFailure : array, shape(numAct+numSen) (default=None) + Provided failure (if any) to have each trial use + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + solverFList : list + List of solver functions to try + solverParametersTuplesList : list + List of tuples of solver parameters. Included action list, failure scenarios + solverNamesList: list + List of names of solvers, for data logging + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Physical state estimator for use with the marginal filter, if any + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + beliefInitializationF : function + Function that creates the initial belief + rewardF : function + Reward function to evaluate the beliefs with + safetyFunctionF : functions + None if no safetyMethod specified. Function that allows us to check the safety of a physicalState directly, useful for plotting or ground truth checking. + multiprocessingFlag : int + Wether to use multi-processing (if number is set other than 0) or not (if False/0) + saveTreeFlag : boolean + Whether to save the tree or not (it can be quite large, so if not visualizing, it is best to set this to false) + numWarmStart : int (default=0) + Checks if we should run the solver a few times to compile first, and if so how many. Only does so on first trial. Currently only implemented for non-multiprocessing + clobber : boolean + Wether to overwrite existing data or not + plottingBounds : array, shape(2,2) (default=None) + Bounds of the plotting axis + resolution : int (default=200) + How high of a resolution the safe zone should be drawn in when showing the safety function. + virtualConfigDictList : list + List of input dictionaries for each subExperiment when multiprocessing + networkFlag : bool + Whether we are in a distributed network or not + generalFaultDict : dict + If we are using a general fault model this is a dictionary with the following values. Otherwise it is None + failureParticleResampleF : function + Function that resamples the particles when needed + failureParticleResampleCheckF : function + Function that determines if resampling is needed + failureParticleInitializationF : function + Function that creates the initial failure particles + filterDivergenceHandlingMethod : string + How to handle if the filter diverges mid trial. None if it should not be. + saveDirectoryPath : str + String of the path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + Can now specify an absolute path, auto determined one is always relative + extraDataDict : dict + Only provided of extraData is True. Contains: + linear : boolean + If experiment system is linear or not + dim : int + Number of dimensions the system has + sigmaW : float or array + Standard deviation representing the process noise. + sigmaV : float or array + Standard deviation representing the sensor noise. + (maybe more later) + """ + + #Top level configurations + nSimulationsPerTreeList, multiprocessingFlag,saveTreeFlag, legacyPaperCodeFlag, clobber, mergeData, numWarmStart = loadTopLevelSpecifications(inputDict,silent) + + nExperimentSteps,nTrialsPerPoint,diagnosisThreshold,rngKeysOffset, initialState,filterDivergenceHandlingMethod = loadTrialParams(inputDict,legacyPaperCodeFlag,silent) + + nMaxComponentFailures,nMaxFailureParticles,providedFailure = loadFailureParams(inputDict, legacyPaperCodeFlag,silent) + + #Check if we are using general faults. + if generalFaultFlag := loadOptionalParameter("generalFaultFlag",inputDict,False,alternativeString="generalFaults",silent=silent): + failureParticleResampleF, failureParticleResampleCheckF, failureParticleInitializationF, trueFaultInInitialParticlesFlag = loadFaultParticleMethods(inputDict,silent) + generalFaultDict = {"failureParticleResampleF": failureParticleResampleF, "failureParticleResampleCheckF":failureParticleResampleCheckF, + "failureParticleInitializationF":failureParticleInitializationF, "trueFaultInInitialParticlesFlag": trueFaultInInitialParticlesFlag} + #Hybrid edge case uses the OLD fault method (no bias... could do this later?) + if failureParticleResampleF is None: + generalFaultFlag = False + else: + generalFaultDict = None + + #Check if multi agent or single agent (default) + networkFlag = loadOptionalParameter("networkArchitecture",inputDict,defaultValue=False,silent=True) + if networkFlag: #communication network + futureCapability = "The distributed version of s-FEAST is intended future work, but is not currently implemented" + raise NotImplementedError(futureCapability) + + #Single agent otherwise + else: + #Load dimensions and linearity, from this construct system parameters. dt is pretty universal, so making an exception for it + systemF, systemParametersTuple, physicalStateJacobianF, dim, linear, dt, sigmaW, sigmaV, numAct= loadAndBuildSingleAgentSystem(inputDict,providedFailure,generalFaultFlag,silent) # pylint: disable=invalid-name + + #To get the number of states, this is length of covariance matrix, which is the -2 element of the systemParametersTuple + covarianceQ = systemParametersTuple[-2] + numState = len(covarianceQ) + + #Load estimator and belief initialization function + estimatorF,physicalStateSubEstimatorF,physicalStateSubEstimatorSampleF, beliefInitializationF = loadEstimatorAndBelief(inputDict,linear,numState,generalFaultFlag,silent=silent) + + #Load reward function + rewardF, safetyFunctionF = loadRewardF(inputDict,physicalStateSubEstimatorSampleF,silent) + + #Load the solver(s) to run, and return parameters needed. Names are used for data logging + solverFList, solverParametersTuplesList, solverNamesList = loadSolvers(inputDict,systemParametersTuple,dim,linear,legacyPaperCodeFlag,safetyFunctionF,silent) + + + #Load plotting parameters (these are all optional and silent) + plottingBounds, resolution = loadPlottingParameters(inputDict) #Already silent + + experimentParamsDict = { + "nSimulationsPerTreeList": nSimulationsPerTreeList, + "dt": dt, + "nExperimentSteps": nExperimentSteps, + "nTrialsPerPoint": nTrialsPerPoint, + "diagnosisThreshold" : diagnosisThreshold, + "rngKeysOffset": rngKeysOffset, + "initialState": initialState, + "nMaxComponentFailures": nMaxComponentFailures, + "nMaxFailureParticles": nMaxFailureParticles, + "providedFailure": providedFailure, + "systemF": systemF, + "systemParametersTuple": systemParametersTuple, + "solverFList": solverFList, + "solverParametersTuplesList": solverParametersTuplesList, + "solverNamesList": solverNamesList, + "estimatorF": estimatorF, + "physicalStateSubEstimatorF": physicalStateSubEstimatorF, + "physicalStateJacobianF" : physicalStateJacobianF, + "physicalStateSubEstimatorSampleF": physicalStateSubEstimatorSampleF, + "beliefInitializationF": beliefInitializationF, + "rewardF": rewardF, + "safetyFunctionF": safetyFunctionF, + "multiprocessingFlag" : multiprocessingFlag, + "saveTreeFlag" : saveTreeFlag, + "numWarmStart" : numWarmStart, + "clobber" : clobber, + "mergeData" : mergeData, + "plottingBounds": plottingBounds, + "resolution": resolution, + "networkFlag": networkFlag, + "generalFaultDict": generalFaultDict, + "filterDivergenceHandlingMethod": filterDivergenceHandlingMethod + } + + + + #Check for consistency (this will be added as new conflicts are found) + checkExperimentParametersConsistency(experimentParamsDict,dim,numAct) + + #Added extra field for processing + if multiprocessingFlag: + experimentParamsDict["virtualConfigDictList"] = getMultiprocessingVirtualConfigAndExperimentParams(inputDict, nTrialsPerPoint, rngKeysOffset) + + #Make the saved directory path. Checks if the folder already exists, and if so, if the experiments are compatible + relativeSaveDirectoryPath = makeOrLoadSaveDirectoryPath(inputDict,experimentParamsDict,dim,linear,sigmaW, sigmaV,silent=silent) + + if extraData: + if checkParameter("networkArchitecture",inputDict): + raise NotImplementedError + extraDataDict ={ + "linear" : linear, + "dim" : dim, + "sigmaW" : sigmaW, + "sigmaV" : sigmaV, + } + return experimentParamsDict,relativeSaveDirectoryPath, extraDataDict + + return experimentParamsDict,relativeSaveDirectoryPath + +def getMultiprocessingVirtualConfigAndExperimentParams(inputDict, nTrialsPerPoint, rngKeysOffset): + """ + Packages up "virtual" config files and the needed experiment parameters to set up the data output + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + nTrialsPerPoint : int + The number of repeated experiments per configuration. + rngKeysOffset : int + Offset to the initial PRNG used in generating the initial failure states and randomness in the trials. This is added to the trial number to allow for different experiments to be preformed + + Returns + ------- + subExperimentsInputDictList : list + List of "virtual" config file values to use for each sub experiment Next: pass in to yaml load (use wrapper for file vs dit input) wrapper in pipeline too for running, hook into that + """ + numProcesses = int(mp.cpu_count() - inputDict["multiprocessingFlag"]) #When multiprocessingFlag != 0, should be num of left over cores (TODO: too overloaded?) + #Stop further recursions! + inputDict["multiprocessingFlag"] = False + + #We need to handle rounding errors + numSeedsPerProcess = int(nTrialsPerPoint/numProcesses) + numProcessesWithExtraTrial = jnp.mod(nTrialsPerPoint,numProcesses) + #Create experiment params dict for each trial + subExperimentsInputDictList =[] + #Determine rngKeysOffsets per process + #rngKeyOffsetList = [] + #numTrialsList = [] + rngKeyOffset = rngKeysOffset + for iProcess in range(numProcesses): + subExperimentParamsDict = inputDict.copy() + #Add current offset + subExperimentParamsDict["rngKeysOffset"] = rngKeyOffset + #Adjust offset for next process + rngKeyOffset += numSeedsPerProcess + if iProcess < numProcessesWithExtraTrial: + rngKeyOffset += 1 + subExperimentParamsDict["nTrialsPerPoint"] = numSeedsPerProcess+1 + else: + subExperimentParamsDict["nTrialsPerPoint"] = numSeedsPerProcess + subExperimentsInputDictList.append(subExperimentParamsDict) + return subExperimentsInputDictList + +def loadTopLevelSpecifications(inputDict,silent): + """ + Load limits on simulations per tree and simulation time + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + + Returns + ------- + nSimulationsPerTreeList : list, len(numTrials) + List of the number of simulations to try, if just one value, wrapped as list. This is now a list and not an array, as we want to access the bare integers + multiprocessingFlag : int + Wether to use multi-processing (if number is set other than 0) or not (if False/0) + saveTreeFlag : boolean + Whether to save the tree or not (it can be quite large, so if not visualizing, it is best to set this to false) + legacyPaperCodeFlag : boolean + Flag to set parameters using the same logic as the old v1 code for the original paper + clobber : boolean + Wether to overwrite existing data or not + numWarmStart : int (default=0) + Checks if we should run the solver a few times to compile first, and if so how many. Only does so on first trial. Currently only implemented for non-multiprocessing + """ + nSimulationsPerTreeList = list(loadRequiredParameter("nSimulationsPerTree",inputDict)) + + multiprocessingFlag = loadOptionalParameter("multiprocessingFlag",inputDict,False,silent=silent) + + saveTreeFlag = loadOptionalParameter("saveTreeFlag",inputDict,False,silent=silent) + + legacyPaperCodeFlag = loadOptionalParameter("legacyPaperCodeFlag",inputDict,False,silent=silent) + + clobber = loadOptionalParameter("clobber",inputDict,False,silent=True) + + mergeData = loadOptionalParameter("mergeData",inputDict,False,silent=True) + + #Not implemented yet + if mergeData: + #Merging data isn't implemented yet + mergingDataNotSupported = "Merging existing data with new experiments is currently not supported" + raise NotImplementedError(mergingDataNotSupported) + + numWarmStart = loadOptionalParameter("numWarmStart",inputDict,0,silent=True) + + return nSimulationsPerTreeList,multiprocessingFlag,saveTreeFlag,legacyPaperCodeFlag, clobber, mergeData, numWarmStart + +def loadTrialParams(inputDict, legacyPaperCodeFlag,silent): + """ + Load parameters to set up and run the various trials + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + legacyPaperCodeFlag : boolean + Flag to set parameters using the same logic as the old v1 code for the original paper + + Returns + ------- + nExperimentSteps : int + How many time steps are in the experiment + nTrialsPerPoint : int + The number of repeated experiments per configuration. + diagnosisThreshold : float + Level of the reward to consider high enough to return an answer. + rngKeysOffset : int + Offset to the initial PRNG used in generating the initial failure states and randomness in the trials. This is added to the trial number to allow for different experiments to be preformed + initialState : array, shape(numState) + Initial state if any provided. + """ + nExperimentSteps = loadOptionalParameter("nExperimentSteps",inputDict,20,silent=silent) + + nTrialsPerPoint = loadOptionalParameter("nTrialsPerPoint",inputDict,1, "1 trial per solver and computation limit",silent=silent) + + diagnosisThreshold = loadOptionalParameter("diagnosisThreshold",inputDict,.9,silent=silent) + + #Check if we should set using paper draft logic + if legacyPaperCodeFlag: + #Check if this is different than what the user specified + if diagnosisThreshold != .81: + print("legacyPaperCodeFlag set to True, overriding diagnosisThreshold setting to be .81") + diagnosisThreshold = .81 + + rngKeysOffset = loadOptionalParameter("rngKeysOffset",inputDict,0,silent=silent) + + #Need to check for None first, then convert to an array, otherwise we get an empty array + initialState = loadOptionalParameter("initialState",inputDict,None,silent=silent) + if initialState is not None: + initialState = jnp.array(initialState) + + filterDivergenceHandlingMethod = loadOptionalParameter("filterDivergenceHandlingMethod",inputDict,None,silent=silent) + + return nExperimentSteps,nTrialsPerPoint,diagnosisThreshold,rngKeysOffset, initialState,filterDivergenceHandlingMethod + +def loadFailureParams(inputDict, legacyPaperCodeFlag,silent): + """ + Load parameters related to the set of failures we are considering + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + legacyPaperCodeFlag : boolean + Flag to set max possible failures using the same logic as the old v1 code for the original paper + + Returns + ------- + nMaxComponentFailures : int + Maximum number of simultaneous failures of components that can be considered + nMaxPossibleFailures : int + Maximum number of possible failures to consider. If larger than the number of possible unique failures, all possibilities are considered + providedFailure : array, shape(numAct+numSen) (default=None) + Provided failure (if any) to have each trial use + """ + nMaxComponentFailures = loadOptionalParameter("nMaxComponentFailures",inputDict,3,silent=silent) + + nMaxPossibleFailures = loadOptionalParameter("nMaxPossibleFailures",inputDict,40,silent=silent) + + #Check if we should set using paper draft logic + if legacyPaperCodeFlag: + #Check if this is different than what the user specified + if nMaxPossibleFailures != 42: + print("legacyPaperCodeFlag set to True, overriding nMaxPossibleFailures setting to be 42") + nMaxPossibleFailures = 42 + if nMaxComponentFailures != 3: + print("legacyPaperCodeFlag set to True, overriding nMaxComponentFailures setting to be 3") + nMaxComponentFailures = 3 + + providedFailure = loadOptionalParameter("providedFailure",inputDict,None,silent=silent) + + if providedFailure is not None: + providedFailure = jnp.array(providedFailure) + #Check all 0-1 + if jnp.max(providedFailure) > 1 or jnp.min(providedFailure) < 0: + raiseIncompatibleSpecifications(f"provided failure {providedFailure}", "Fault/degradation/bias limits of [0,1]") + + return nMaxComponentFailures,nMaxPossibleFailures,providedFailure + +def loadRewardF(inputDict,physicalStateSubEstimatorSampleF,silent): + """ + Load the proper reward function and return it + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + + Returns + ------- + rewardF : function + Reward function to evaluate the beliefs with + safetyFunctionF : functions + None if no safetyMethod specified. Function that allows us to check the safety of a physicalState directly, useful for plotting or ground truth checking. + """ + if "reward" in inputDict: + #Need to interpret reward function + rewardFString = ''.join(inputDict["reward"].lower().split()) #String processing + if rewardFString in ("squareSumFailureBeliefReward".lower(), "squaredFailureBeliefReward".lower(), "squareSumFailureBelief".lower(), "squaredFailureBelief".lower()): + from failurePy.rewards.squareSumFailureBeliefReward import squareSumFailureBeliefReward + #Check if there is a safety method specified + if "safetyMethod" in inputDict: + safetyMethodString = ''.join(inputDict["safetyMethod"].lower().split()) #String processing + #HACK to vary M + if "varyM" in inputDict: + rewardFs = [] + nSimulationsPerTreeList = list(loadRequiredParameter("nSimulationsPerTree",inputDict)) + for mSamples in nSimulationsPerTreeList: + nMaxDepth = loadOptionalParameter("nMaxDepth",inputDict,defaultValue=4,silent=silent) + rewardFs.append(loadSafetyConstrainedReward(inputDict,squareSumFailureBeliefReward,physicalStateSubEstimatorSampleF,nMaxDepth,mSamples=mSamples)) + return rewardFs, None + + #Basic safety modulated reward, gives reward unless constraints violated, then gives 0 + if safetyMethodString in ("safetyConstrainedReward".lower(),"safetyReward".lower(),"safetyConstrained".lower(),"safetyConstraint".lower(),"safety"): + #Need solver depth to calculate r_0 (can only plan safety over a horizon) + nMaxDepth = loadOptionalParameter("nMaxDepth",inputDict,defaultValue=4,silent=silent) + return loadSafetyConstrainedReward(inputDict,squareSumFailureBeliefReward,physicalStateSubEstimatorSampleF,nMaxDepth) + #Penalized reward, gives a stronger penalty if constraint violated, not just 0 + if safetyMethodString in ("safetyPenalizedReward".lower(),"safetyPenalty".lower(),"safetyPenalized".lower()): + #Not supported by proof + raiseIncompatibleSpecifications(safetyMethodString,"current safety proof") + #penalty = loadOptionalParameter("penalty",inputDict,1) + #return loadSafetyPenalizedReward(inputDict,squareSumFailureBeliefReward,physicalStateSubEstimatorSampleF,penalty) + #Safety filter off, but computes safe region for plotting + if safetyMethodString in ("safetyConstrainedRewardOff".lower(),"safetyRewardOff".lower(),"safetyConstrainedOff".lower(),"safetyConstraintOff".lower(),"safetyOff".lower()): + dummySafetyReward, safetyFunctionF = loadSafetyConstrainedReward(inputDict,squareSumFailureBeliefReward,physicalStateSubEstimatorSampleF) + return squareSumFailureBeliefReward, safetyFunctionF + #This is invalid + raiseSpecificationNotFoundError(safetyMethodString,"safetyMethod") + + return squareSumFailureBeliefReward, None + #This is invalid + raiseSpecificationNotFoundError(rewardFString,"reward") + + #Default behavior + print("Defaulting to squared sum of failure belief reward function") + from failurePy.rewards.squareSumFailureBeliefReward import squareSumFailureBeliefReward + return squareSumFailureBeliefReward, None + +def makeOrLoadSaveDirectoryPath(inputDict,experimentParamsDict,dim,linear, sigmaW, sigmaV, silent): + """ + Function to auto generate save directory path (or load it if provided) + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + dim : int + Number of dimensions + linear : boolean + Whether the system is linear or not + sigmaW : float or array + Standard deviation representing the process noise. If an array, only first value is used for default directory + sigmaV : float or array + Standard deviation representing the sensor noise. If an array, only first value is used for default directory + + Returns + ------- + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + """ + saveDirectoryPath = "" + + #Autogenerate path + #Linearity + if linear: + saveDirectoryPath+="Linear" + elif linear is None: #Set to None if networked + saveDirectoryPath+="Network" + else: + saveDirectoryPath+="Non-Linear" + + #Dimensionality + saveDirectoryPath+=f"_{dim}DOF" + + #Append solver list + for solverName in experimentParamsDict["solverNamesList"]: + saveDirectoryPath+="_" + saveDirectoryPath+=solverName + #Append noise + #First need to see if we need to get the first value out. If not a float, assume it is an array + if not sigmaW is None and not isinstance(sigmaW, numbers.Number): + sigmaW = sigmaW[0] + if not sigmaV is None and not isinstance(sigmaV, numbers.Number): + sigmaV = sigmaV[0] + if not (sigmaW is None or sigmaV is None): + saveDirectoryPath += f"_sigmaW_{sigmaW:.1f}_sigmaV_{sigmaV:.1f}" + #See if a path was provided + saveDirectoryPath = loadOptionalParameter("saveDirectoryPath",inputDict,saveDirectoryPath,silent=silent) + #Check if absolute + if saveDirectoryPath[0] == "/": + return saveDirectoryPath + + #Add relative start to the front of the path + saveDirectoryPath = "SavedData/" + saveDirectoryPath #Relative path! + #Return relative path (as we don't want to rely on necessarily python running in the directory above SavedData) + return saveDirectoryPath + #return os.path.join(os.getcwd(), saveDirectoryPath) #Join path to make abs path + +def loadPlottingParameters(inputDict): + """ + Function to load in optional plotting parameters. Loads silently + + Parameters + ---------- + inputDict : dict + Contains the configuration parameters from the .yaml file + + Returns + ------- + plottingBounds : array, shape(2,2) (default=None) + Bounds of the axis + resolution : int (default=200) + How high of a resolution the safe zone should be drawn in. + """ + plottingExtent = loadOptionalParameter("plottingExtent",inputDict,None,silent=True) + #Always a square plot + if plottingExtent is not None: + plottingBounds = jnp.array([[-plottingExtent,plottingExtent],[-plottingExtent,plottingExtent]]) + else: + plottingBounds = None + resolution = loadOptionalParameter("resolution",inputDict,200,silent=True) + return plottingBounds,resolution diff --git a/failurePy/load/yamlLoaderUtilityMethods.py b/failurePy/load/yamlLoaderUtilityMethods.py new file mode 100644 index 0000000..b8b0337 --- /dev/null +++ b/failurePy/load/yamlLoaderUtilityMethods.py @@ -0,0 +1,281 @@ +""" +Additional methods used in yaml loader that don't load any other files +""" + +from pathlib import Path #Starting to use path capabilities +import yaml + +#Import functions for comparison +from failurePy.models.threeDOFModel import simulateSystemWrapper as threeDOFSystemF +from failurePy.models.threeDOFGeneralFaultModel import simulateSystemWrapper as threeDOFGeneralFaultSystemF +from failurePy.solvers.preSpecifiedPolicy import PreSpecifiedPolicy + +def getInputDict(configFilePath): + """ + Helper method that gets the input dict from the configuration file path. + Checks for duplicate key errors and converts "None" to None. + + Parameters + ---------- + configFilePath : string + Relative path to the config file to be used + + Returns + ------- + inputDict : dict + The contents of the yaml file parsed to a dictionary. + """ + #Open file (use Path to make this compatible with our package imports) + return loadUniqueKeyYaml(Path(configFilePath),"configuration file") + +def loadUniqueKeyYaml(yamlFile,fileDescriptionString): + """ + Helper method that loads a specified yaml file + + Parameters + ---------- + yamlFile : File object + File to open yaml from + fileDescriptionString : string + Description of file for more useful failure message + + Returns + ------- + loadedDict : dict + The contents of the yaml file parsed to a dictionary. + """ + + #Open file + with yamlFile.open('r',encoding="UTF-8") as inputFile: + try: + inputDict = yaml.load(inputFile,UniqueKeyLoader) + #Set "None" to None + checkDictForNone(inputDict) + + except AssertionError as yamlError: #Check if any key provided twice + duplicateKey = f"Error duplicate keys occur in the {fileDescriptionString}. To avoid undefined behavior, remove duplicate keys" + raise KeyError(duplicateKey) from yamlError + + return inputDict + +def checkDictForNone(inputDict): + """ + Method that modifies a dictionary in place to change any "None" to None type. + + Parameters + ---------- + inputDict : dict + Dictionary to iterate through + """ + + for key in inputDict: + if isinstance(inputDict[key],str): + if inputDict[key].lower() == "none": + inputDict[key] = None + +def checkParameter(parameterString,inputDict): + """ + Returns if the parameterString is a valid dict key + """ + return parameterString in inputDict + +def loadOptionalParameter(parameterString,inputDict,defaultValue, defaultMessage=None,silent=False,alternativeString=None): + """ + Loads specified parameter, replacing it with the default value if it is not specified. + Will inform user (can be configured) unless silent is set to True + + Alternative string allows for a different key name (used by stealthAttackPy for clearer variable names) + """ + if not parameterString in inputDict: + if alternativeString in inputDict: + return inputDict[alternativeString] + + if defaultMessage is None: + defaultMessage = str(defaultValue) + if not silent: + print(f"No specification for optional parameter {parameterString} provided. Defaulting to {defaultMessage}.") + return defaultValue + return inputDict[parameterString] + +def loadRequiredParameter(parameterString,inputDict,alternativeString=None): + """ + Tries to load a required parameter, will raise an exception if it is not found + """ + if not parameterString in inputDict: + #Allow for alternative name + if not alternativeString in inputDict: + requiredParameterNotFound(parameterString) + #This will always raise, so no return needed + return inputDict[alternativeString] + return inputDict[parameterString] + +def requiredParameterNotFound(parameterString): + """ + Raises an exception informing the user if a required parameter is missing. + """ + specificationNotProvided = f"No specification for required parameter {parameterString} provided." + raise ValueError(specificationNotProvided) + +def raiseIncompatibleSpecifications(incompatibleSpecification1,incompatibleSpecification2,extraText=None): + """ + Raises an exception informing the user if two specifications are incompatible. + """ + if extraText is not None: + incompatibleSpecifications = f"{incompatibleSpecification1} is incompatible with {incompatibleSpecification2}. {extraText}" + else: + incompatibleSpecifications = f"{incompatibleSpecification1} is incompatible with {incompatibleSpecification2}." + raise ValueError(incompatibleSpecifications) + +def checkExperimentParametersConsistency(experimentParamsDict, dim, numAct): + """ + Method that checks for known inconsistencies in the experimentParameters. + This method will be expanded as more inconsistencies are identified. + Raises error with inconsistent parameters when identified + + Parameters + ---------- + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + The contents should be as follows: + nSimulationsPerTreeList : list, len(numTrials) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + dt : float + The time between time steps of the experiment + nExperimentSteps : int + How many time steps are in the experiment + nTrialsPerPoint : int + The number of repeated experiments per configuration. + diagnosisThreshold : float + Level of the reward to consider high enough to return an answer. + rngKeysOffset : int + Offset to the initial PRNG used in generating the initial failure states and randomness in the trials. + This is added to the trial number to allow for different experiments to be preformed + initialState : array, shape(numState) + Initial state if any provided. + nMaxComponentFailures : int + Maximum number of simultaneous failures of components that can be considered + nMaxPossibleFailures : int + Maximum number of possible failures to consider. If larger than the number of possible unique failures, all possibilities are considered + providedFailure : array, shape(numAct+numSen) (default=None) + Provided failure (if any) to have each trial use + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + solverFList : list + List of solver functions to try + solverParametersTuplesList : list + List of tuples of solver parameters. Included action list, failure scenarios + solverNamesList: list + List of names of solvers, for data logging + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Physical state estimator for use with the marginal filter, if any + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + beliefInitializationF : function + Function that creates the initial belief + rewardF : function + Reward function to evaluate the beliefs with + safetyFunctionF : functions + None if no safetyMethod specified. Function that allows us to check the safety of a physicalState directly, useful for plotting or ground truth checking. + multiprocessingFlag : boolean + Wether to use multi-processing or not + saveTreeFlag : boolean + Whether to save the tree or not (it can be quite large, so if not visualizing, it is best to set this to false) + clobber : boolean + Wether to overwrite existing data or not + plottingBounds : array, shape(2,2) (default=None) + Bounds of the plotting axis + resolution : int (default=200) + How high of a resolution the safe zone should be drawn in when showing the safety function. + dim : int + Number of dimensions + """ + #Validate solver names list length and solverFList length match + if len(experimentParamsDict["solverFList"]) != len(experimentParamsDict["solverNamesList"]): + raiseIncompatibleSpecifications(f"{len(experimentParamsDict['solverFList'])} solver functions", f"{len(experimentParamsDict['solverNamesList'])} solver names") + + #Initial State validation TODO: Add network validation + if experimentParamsDict["initialState"] is not None and dim is not None: #No dim for network system + initialState = experimentParamsDict["initialState"] + #Check it matches system dimensions + if len(initialState) != 2*dim: + #Only raise if not 3DOF, as that has extra states from reaction wheels + if experimentParamsDict["systemF"] is not threeDOFSystemF and experimentParamsDict["systemF"] is not threeDOFGeneralFaultSystemF: + raiseIncompatibleSpecifications(f"dim: {dim}", f"initialState length of {len(initialState)}") + #Check it matches covarianceQ (if not, probably not accounting for numWheels). covarianceQ is always second from back of systemParametersTuple + covarianceQIdx = -2 + covarianceQ = experimentParamsDict["systemParametersTuple"][covarianceQIdx] + if len(initialState) != len(covarianceQ): + #Raise error, just check which one, 3DOF or otherwise + if experimentParamsDict["systemF"] is threeDOFSystemF: + reactionWheelInfluenceMatrixIdx = 2 + raiseIncompatibleSpecifications(f"initialState length of: {len(initialState)}", f"initial covarianceQ length of: {len(covarianceQ)}", + f"Check that initial states were provided for each of the {len(experimentParamsDict['systemParametersTuple'][reactionWheelInfluenceMatrixIdx])} reaction wheels.") + raiseIncompatibleSpecifications(f"initialState length of: {len(initialState)}", f"initial covarianceQ length of: {len(covarianceQ)}", + "Check that initial states were provided for each state.") + + #Check saveTreeFlag on when > 1 trials per point (lots of data) + if experimentParamsDict["saveTreeFlag"]: + if experimentParamsDict["nTrialsPerPoint"] > 1: + raiseIncompatibleSpecifications("Saving each tree search", + f">1 nTrialsPerPoint per point (currently {experimentParamsDict['nTrialsPerPoint']}). Too much data is generated.") + + solverNamesList = experimentParamsDict["solverNamesList"] + + #Check pre specified policy errors (a little hard to debug) + if "PreSpecified" in solverNamesList: + #Make a new one and check the action length! Since it is hard coded! + preSpecifiedSolver = PreSpecifiedPolicy() + numActionsPreSpecified = len(preSpecifiedSolver.actionList[0]) + if numAct != numActionsPreSpecified: + raiseIncompatibleSpecifications(f"Model {experimentParamsDict['systemF']} with {numAct} actions", + f"Pre specified action policy with {numActionsPreSpecified} actions specified per time step") + + #Check for baseline policies and nSimulationsPerTreeList that isn't [1] + if "cbf" in solverNamesList or "greedy" in solverNamesList or "scp" in solverNamesList: + if experimentParamsDict["nSimulationsPerTreeList"] != [1]: + raiseIncompatibleSpecifications("Using any baseline solvers", f"nSimulationsPerTreeList that is not [1] (received {experimentParamsDict['nSimulationsPerTreeList']})") + + + #Potential noise inconsistency to check + #sigmaW = jnp.array(sigmaW) + #if len(sigmaW) != dim*2: + # raiseIncompatibleSpecifications("sigmaW with length {}".format(len(sigmaW)),"a system with {} states".format(len(dynamicsMatrix))) + #else: + # diagCovarianceQ = jnp.square(sigmaW) + +#Can't change number of ancestors, as this is a 3rd party package +class UniqueKeyLoader(yaml.SafeLoader): # pylint: disable=too-many-ancestors,too-few-public-methods + """ + Yaml loader specification that checks if there are duplicate keys and raises and assertion error if this fails. + Inherits from SafeLoader, which protects against data injection by limiting evaluation of code. + """ + + def construct_mapping(self, node, deep=False): #Override, so can't enforce naming convention. pylint: disable=invalid-name + """ + Overrides yaml.constructor.SafeConstructor + + Creates the mapping for loading the yaml file in. + This is an overwrite of the base package behavior, so be vary careful making changes + """ + mapping = [] + #Not removing unused argument or changing name to make mapping to the base method clearer. + for key_node, value_node in node.value: # pylint: disable=unused-variable,invalid-name + key = self.construct_object(key_node, deep=deep) + assert key not in mapping + mapping.append(key) + return super().construct_mapping(node, deep) + + +def raiseSpecificationNotFoundError(specification,parameter="parameter"): + """ + Method that raises error when the given specification not found in range of possible models/solvers/estimators/etc. + """ + specificationNotFound= f"Specified {parameter}, {specification}, does not exist or is not currently implemented." + raise ValueError(specificationNotFound) diff --git a/failurePy/models/__init__.py b/failurePy/models/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/failurePy/models/linearModel.py b/failurePy/models/linearModel.py new file mode 100644 index 0000000..1ac8da9 --- /dev/null +++ b/failurePy/models/linearModel.py @@ -0,0 +1,300 @@ +""" +Linear dynamics and observing model + +Currently implemented in a non-OOP approach to allow for JIT compiling +""" + +import math +import jax +import jax.numpy as jnp +from jax import random as jaxRandom +from failurePy.models.modelsCommon import observationModel, makeSingleAxisSensingMatrix + +@jax.jit +def simulateSystemWrapper(physicalState,failureState,action,rngKey,systemParametersTuple,noisyPropagationBooleanInt=1): + """ + Wrapper for the linear model system, so all the systems look the same up to a systemParametersTuple which is unique to each system + Currently no error checking!! + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + action : array, shape(numAct) + Current action to take + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + systemParametersTuple : tuple + Contents are in order: + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + + controlTransitionMatrix : array, shape(numState,numAct) + State Transition matrix resulting from constant control input + sensingMatrix : array, shape(numSen, numState) + C matrix + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + noisyPropagationBooleanInt : int (default=1) + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + Returns + ------- + nextPhysicalState : array, shape(numState) + Next physical state of the model + nextFailureState : array, shape(numAct+numSen) + Failure afflicting the s/c (unchanging by this model) + nextObservation : array, shape(numSenors) + Next observation of the model + """ + + return simulateSystem(physicalState,failureState, action, systemParametersTuple[0], + systemParametersTuple[1],systemParametersTuple[2], + systemParametersTuple[3],systemParametersTuple[4], rngKey, noisyPropagationBooleanInt) + +def simulateSystem(physicalState,failureState, action, stateTransitionMatrix,controlTransitionMatrix,sensingMatrix,covarianceQ,covarianceR, rngKey, noisyPropagationBooleanInt=1): + """ + Iterates the model forward one time step dt based on the action chosen and generates resulting observation + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + action : array, shape(numAct) + Current action to take + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + + controlTransitionMatrix : array, shape(numState,numAct) + State Transition matrix resulting from constant control input + sensingMatrix : array, shape(numSen, numState) + C matrix + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + noisyPropagationBooleanInt : int + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextPhysicalState : array, shape(numState) + Next physical state of the model + nextFailureState : array, shape(numAct+numSen) + Failure afflicting the s/c (unchanging by this model) + nextObservation : array, shape(numSenors) + Next observation of the model + """ + + #Split rngKey for two different noise processes. These keys are consumed on use! So we need to split first + rngKey, rngSubKey = jaxRandom.split(rngKey) + + #First we note that by assumption, the failure state doesn't change, so only propagate the physical state + nextPhysicalState = propagateDynamics(physicalState,failureState,action,stateTransitionMatrix,controlTransitionMatrix,covarianceQ,rngSubKey,noisyPropagationBooleanInt) + + nextObservation = observationModel(nextPhysicalState,failureState,sensingMatrix,getRealizedNominalMeasurement,covarianceR,rngKey,noisyPropagationBooleanInt) + + return (nextPhysicalState,failureState,nextObservation) + + +def propagateDynamics(physicalState,failureState,action,stateTransitionMatrix,controlTransitionMatrix,covarianceQ,rngKey,noisyPropagationBooleanInt): + """ + Iterates the dynamics forward a time step + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + action : array, shape(numAct) + Current action to take (constant) + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + controlTransitionMatrix : array, shape(numState,numAct) + State Transition matrix resulting from constant control input + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + noisyPropagationBooleanInt : int + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextState : tuple (nextPhysicalState, nextPhi) + Next state of the model + """ + + realizedAction = getRealizedAction(failureState,action) + + #Create Noise + dynamicsNoise = jaxRandom.multivariate_normal(rngKey,jnp.zeros(len(physicalState)), covarianceQ) + + #Convolute the state (solution to forced first order diff eq) + nominalNextState = jnp.matmul(stateTransitionMatrix,physicalState) + \ + jnp.matmul(controlTransitionMatrix,realizedAction) + return nominalNextState + noisyPropagationBooleanInt * dynamicsNoise #when noisyPropagationBooleanInt is 0, noise is zeroed out! + +def getRealizedAction(failureState,action): + """ + Helper method to apply failure and get realized action + """ + numAct = len(action) + + #Create failure Matrix on the actuators Phi_B + actuatorFailureMatrix = jnp.diag(failureState[0:numAct]) + + realizedAction = jnp.matmul(actuatorFailureMatrix,action) + + return realizedAction + +def getRealizedNominalMeasurement(physicalState,failureState,sensingMatrix): + """ + Helper method to apply failure and get realized observation + """ + #Make matrix of sensor failures Phi_C + sensorFailureMatrix = jnp.diag(failureState[-len(sensingMatrix):]) + + #Compute the probability of seeing the observation + #This is a Gaussian around the mean value (given failures) + nominalMeasurement = jnp.matmul(sensorFailureMatrix,jnp.matmul(sensingMatrix,physicalState)) + + return nominalMeasurement + +def makeDynamicsMatrix(dim): + """ + Make the dynamics matrix of the model + + Parameters + ---------- + dim : int + Number of dimensions in the model + + Returns + ------- + dynamicsMatrix : array, shape(numState,numState) + A matrix + """ + + singleAxisDynamicsMatrix = jnp.array([[0,1], + [0,0]]) + + return jnp.kron(jnp.eye(dim,dtype=int),singleAxisDynamicsMatrix) + +def makeInfluenceMatrix(dim,spacecraftMass,numAct=None): + """ + Make the influence matrix of the model + + Parameters + ---------- + dim : int + Number of dimensions in the model + systemMass : float + Mass of s/c + numAct : int (default=None) + Number of actuators affecting the model. By default we assume 2 in each axis (+/-) + The number of actuators will be rounded (down) to the nearest value that can be evenly distributed among each axis (ie, divided by dim*2) + + Returns + ------- + influenceMatrix : array, shape(numState,numAct) + B matrix + """ + + #Default behavior + if numAct is None: + singleAxisInfluenceMatrix = jnp.array([[0,0,0,0], + [-1,-1,1,1]]) + #We assume a symmetric distribution of the actuators, round down to achieve + else: + numActPerDirection = int(numAct/(dim*2)) + singleAxisInfluenceMatrix = jnp.zeros((2,2*numActPerDirection)) + #Set half actuators as negative, half as positive + singleAxisInfluenceMatrix = singleAxisInfluenceMatrix.at[1,:numActPerDirection].set(-1) + singleAxisInfluenceMatrix = singleAxisInfluenceMatrix.at[1,numActPerDirection:].set(1) + + return jnp.kron(jnp.eye(dim,dtype=int),singleAxisInfluenceMatrix/spacecraftMass) #Divide by s/c mass to scale influence! + + +def makeSensingMatrix(dim,numSen=None): + """ + Make the sensing matrix of the model + + Parameters + ---------- + dim : int + Number of dimensions in the model + numSen : int (default=None) + Number of sensors measuring the model. By default we assume 2 in each dimension + The number of sensors will be rounded (down) to the nearest value that can be evenly distributed among each dimension + We further assume no direct sensing of velocities + Returns + ------- + sensingMatrix : array, shape(numSen,numState) + C matrix + """ + + singleAxisSensingMatrix = makeSingleAxisSensingMatrix(dim, numSen) + + return jnp.kron(jnp.eye(dim,dtype=int),singleAxisSensingMatrix) + + +def makeStateTransitionMatrices(dynamicsMatrix,dt,influenceMatrix): #dt is pretty universal, so making an exception for it pylint: disable=invalid-name + """ + Function that makes the state transition matrix and it's integral, assuming + A is nilpotent and the dimension is less than or equal to 12 (as otherwise we won't be able to compute explicitly) + This is true for the double integrator systems we are considering. More sophisticated methods can be used for other systems + + Parameters + ---------- + dynamicsMatrix : array, shape(numState,numState) + A matrix + dt : float + The time between time steps of the experiment + + Returns Matrices + ------- + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + controlTransitionMatrix : array, shape(numState,numAct) + State Transition matrix resulting from constant control input + """ + + #Explicitly exponentiate the matrix using a Taylor matrix and relying on nilpotence + dynamicsMatrixPowers = [jnp.eye(jnp.shape(dynamicsMatrix)[0]),dynamicsMatrix] + + for iMultiplications in range(13): + dynamicsMatrixPower = jnp.matmul(dynamicsMatrixPowers[iMultiplications+1],dynamicsMatrix) + #Check if we have hit the zero matrix + if jnp.all(dynamicsMatrixPower == 0): + break + dynamicsMatrixPowers.append(dynamicsMatrixPower) + if iMultiplications > 11: + raise ValueError("dynamics matrix (A matrix) not sufficiently nilpotent (A^12 !=0)") + #Create the state transition matrix and it's derivative + stateTransitionMatrix = jnp.zeros(jnp.shape(dynamicsMatrix)) + stateTransitionMatrixIntegral = jnp.zeros(jnp.shape(dynamicsMatrix)) + + for iMatrixPowerMinusOne,dynamicsMatrixPower in enumerate(dynamicsMatrixPowers): + #Taylor series for matrix exponential + stateTransitionMatrix = stateTransitionMatrix + dynamicsMatrixPower * dt**iMatrixPowerMinusOne/math.factorial(iMatrixPowerMinusOne) + #Now we compute the integration of the state transition matrix, as if we have this + #we can compute the next state, leveraging invariance of Amat, B, and the control input + #Integrated taylor series (note we want integral of e^(-A tau), hence sign) + stateTransitionMatrixIntegral = stateTransitionMatrixIntegral + dynamicsMatrixPower * (-1)**iMatrixPowerMinusOne * (dt)**(iMatrixPowerMinusOne+1)/math.factorial(iMatrixPowerMinusOne+1) + + controlTransitionMatrix = jnp.matmul(stateTransitionMatrix,jnp.matmul(\ + stateTransitionMatrixIntegral,influenceMatrix)) + + return (stateTransitionMatrix,controlTransitionMatrix) diff --git a/failurePy/models/linearModelGeneralFaults.py b/failurePy/models/linearModelGeneralFaults.py new file mode 100644 index 0000000..8be0c9c --- /dev/null +++ b/failurePy/models/linearModelGeneralFaults.py @@ -0,0 +1,200 @@ +""" +Linear dynamics and observing model + +Currently implemented in a non-OOP approach to allow for JIT compiling +""" +import jax +import jax.numpy as jnp +from jax import random as jaxRandom +from failurePy.models.modelsCommon import observationModel + + +@jax.jit +def simulateSystemWrapper(physicalState,failureState,action,rngKey,systemParametersTuple,noisyPropagationBooleanInt=1): + """ + Wrapper for the linear model system, so all the systems look the same up to a systemParametersTuple which is unique to each system + Currently no error checking!! + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(2*numAct+2*numSen) + Failure afflicting the s/c. Now includes constant biases and notation change. 1 = failed, 0 = nominal + action : array, shape(numAct) + Current action to take + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + systemParametersTuple : tuple + Contents are in order: + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + + controlTransitionMatrix : array, shape(numState,numAct) + State Transition matrix resulting from constant control input + sensingMatrix : array, shape(numSen, numState) + C matrix + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + noisyPropagationBooleanInt : int (default=1) + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + Returns + ------- + nextPhysicalState : array, shape(numState) + Next physical state of the model + nextFailureState : array, shape(numAct+numSen) + Failure afflicting the s/c (unchanging by this model) + nextObservation : array, shape(numSenors) + Next observation of the model + """ + + return simulateSystem(physicalState,failureState, action, systemParametersTuple[0], + systemParametersTuple[1],systemParametersTuple[2], + systemParametersTuple[3],systemParametersTuple[4], rngKey, noisyPropagationBooleanInt) + +def simulateSystem(physicalState,failureState, action, stateTransitionMatrix,controlTransitionMatrix,sensingMatrix,covarianceQ,covarianceR, rngKey, noisyPropagationBooleanInt=1): + """ + Iterates the model forward one time step dt based on the action chosen and generates resulting observation + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(2*numAct+2*numSen) + Failure afflicting the s/c. Now includes constant biases and notation change. 1 = failed, 0 = nominal + action : array, shape(numAct) + Current action to take + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + + controlTransitionMatrix : array, shape(numState,numAct) + State Transition matrix resulting from constant control input + sensingMatrix : array, shape(numSen, numState) + C matrix + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + noisyPropagationBooleanInt : int + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextPhysicalState : array, shape(numState) + Next physical state of the model + nextFailureState : array, shape(numAct+numSen) + Failure afflicting the s/c (unchanging by this model) + nextObservation : array, shape(numSenors) + Next observation of the model + """ + + #Split rngKey for two different noise processes. These keys are consumed on use! So we need to split first + rngKey, rngSubKey = jaxRandom.split(rngKey) + + #First we note that by assumption, the failure state doesn't change, so only propagate the physical state + nextPhysicalState = propagateDynamics(physicalState,failureState,action,stateTransitionMatrix,controlTransitionMatrix,covarianceQ,rngSubKey,noisyPropagationBooleanInt) + + nextObservation = observationModel(nextPhysicalState,failureState,sensingMatrix,getRealizedNominalMeasurement,covarianceR,rngKey,noisyPropagationBooleanInt) + + return (nextPhysicalState,failureState,nextObservation) + + +def propagateDynamics(physicalState,failureState,action,stateTransitionMatrix,controlTransitionMatrix,covarianceQ,rngKey,noisyPropagationBooleanInt): + """ + Iterates the dynamics forward a time step + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(2*numAct+2*numSen) + Failure afflicting the s/c. Now includes constant biases and notation change. 1 = failed, 0 = nominal + action : array, shape(numAct) + Current action to take (constant) + stateTransitionMatrix : array, shape(numState,numState) + State transition matrix from previous state to the next state. This depends on dt, and should be recreated if dt changes + controlTransitionMatrix : array, shape(numState,numAct) + State Transition matrix resulting from constant control input + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + noisyPropagationBooleanInt : int + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextState : tuple (nextPhysicalState, nextPhi) + Next state of the model + """ + + realizedAction = getRealizedAction(failureState,action) + + #Create Noise + dynamicsNoise = jaxRandom.multivariate_normal(rngKey,jnp.zeros(len(physicalState)), covarianceQ) + + #Convolute the state (solution to forced first order diff eq) + nominalNextState = jnp.matmul(stateTransitionMatrix,physicalState) + \ + jnp.matmul(controlTransitionMatrix,realizedAction) + return nominalNextState + noisyPropagationBooleanInt * dynamicsNoise #when noisyPropagationBooleanInt is 0, noise is zeroed out! + +def getRealizedAction(failureState,action): + """ + Helper method to apply failure and get realized action + + Uses general fault model + """ + + numAct = len(action) + + #Create degradation Matrix on the actuators Phi_B. Note notation is now x_k = A x_{k-1} + B u_k + B [-Phi_B Phi_x] [u_k, 1s]^T + w_k + actuatorDegradationMatrix = jnp.diag(1-failureState[0:numAct]) + + #Create bias. Note we are assuming positive bias for these actuators, since we assume thrusters where negative bias doesn't make a lot of sense. + actuatorBias = failureState[numAct:2*numAct] + + #Apply degradation and bias to the actuation. Note because we assume 0/1 actuation, this all scales cleanly. + realizedAction = jnp.matmul(actuatorDegradationMatrix,action) + actuatorBias + + return realizedAction + +def getRealizedNominalMeasurement(physicalState,failureState,sensingMatrix): + """ + Helper method to apply failure and get realized observation + + Uses a general observation model, subject to biases and partial degradation + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + sensingMatrix : array, shape(numSen, numState) + C matrix + + Returns + ------- + nominalMeasurement : array, shape(numSenors) + Nominal next observation of the model + """ + + numSen = len(sensingMatrix) + + #Make matrix of sensor failures Phi_C + sensorDegradationMatrix = jnp.diag(1-failureState[-numSen:]) + + sensorBias = failureState[-2*numSen:-numSen] + + #Compute the probability of seeing the observation + #This is a Gaussian around the mean value (given failures) + nominalMeasurement = jnp.matmul(sensorDegradationMatrix,jnp.matmul(sensingMatrix,physicalState)) + sensorBias + + return nominalMeasurement diff --git a/failurePy/models/modelsCommon.py b/failurePy/models/modelsCommon.py new file mode 100644 index 0000000..85c52bf --- /dev/null +++ b/failurePy/models/modelsCommon.py @@ -0,0 +1,72 @@ +""" +Module containing methods common to more than one model. +""" + +import jax.numpy as jnp +from jax import random as jaxRandom + +def observationModel(physicalState,failureState,sensingMatrix,getRealizedNominalMeasurementF,covarianceR,rngKey,noisyPropagationBooleanInt): + """ + Generates observations for most all models, subject to the models nominal measurement model. + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + sensingMatrix : array, shape(numSen, numState) + C matrix + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + noisyPropagationBooleanInt : int + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextObservation : array, shape(numSenors) + Next observation of the model + """ + + nominalMeasurement = getRealizedNominalMeasurementF(physicalState,failureState,sensingMatrix) + + #Add Gaussian noise + sensingNoise = jaxRandom.multivariate_normal(rngKey,jnp.zeros(len(sensingMatrix)), covarianceR) #rng.normal(0,self.sigma_v,size=len(mean)) + + return nominalMeasurement + noisyPropagationBooleanInt * sensingNoise #when noisyPropagationBooleanInt is 0, noise is zeroed out! + + +def makeSingleAxisSensingMatrix(dim,numSen=None): + """ + Make the redundant single axis sensing matrix of the model. + This is for models that assume redundant sensing on each degree of freedom + + Parameters + ---------- + dim : int + Number of dimensions in the model + numSen : int (default=None) + Number of sensors measuring the model. By default we assume 2 in each dimension + The number of sensors will be rounded (down) to the nearest value that can be evenly distributed among each dimension + We further assume no direct sensing of velocities + Returns + ------- + singleAxisSensingMatrix : array, shape(numSen,2) + Repeated Block of C matrix + """ + + #Default behavior + if numSen is None: + singleAxisSensingMatrix = jnp.array([[1,0], + [1,0]]) + #We assume a symmetric distribution of the actuators, round down to achieve + else: + numSenPerAxis = int(numSen/(dim)) + singleAxisSensingMatrix = jnp.zeros((numSenPerAxis,2)) + #Set to observe the base state (not derivative in each axis) + singleAxisSensingMatrix = singleAxisSensingMatrix.at[:,0].set(1) + + return singleAxisSensingMatrix diff --git a/failurePy/models/threeDOFGeneralFaultModel.py b/failurePy/models/threeDOFGeneralFaultModel.py new file mode 100644 index 0000000..c4ef9ad --- /dev/null +++ b/failurePy/models/threeDOFGeneralFaultModel.py @@ -0,0 +1,344 @@ +""" +Non-linear planar dynamics and observing model, using general fault model + +Currently implemented in a non-OOP approach to allow for JIT compiling +""" + +import jax +import jax.numpy as jnp +from jax import random as jaxRandom +from failurePy.models.modelsCommon import observationModel +from failurePy.models.linearModelGeneralFaults import getRealizedNominalMeasurement, getRealizedAction +from failurePy.models.threeDOFModel import rk4, thetaRotationMatrixDerivative +from failurePy.models.threeDOFModel import actionDynamicsJacobian as baseActionDynamicsJacobian + +@jax.jit #Slight speed up, not the main slow down it appears (already jitting somewhere?) +def simulateSystemWrapper(physicalState,failureState,action,rngKey,systemParametersTuple,noisyPropagationBooleanInt=1): + """ + Wrapper for the 3DOF model system, so all the systems look the same up to a systemParametersList which is unique to each system + Currently no error checking!! + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(2*numAct+2*numSen) + Failure afflicting the s/c. Now includes constant biases and notation change. 1 = failed, 0 = nominal + action : array, shape(numAct) + Current action to take + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + systemParametersTuple : tuple + Contents are in order: + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + noisyPropagationBooleanInt : int (default=1) + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextPhysicalState : array, shape(numState) + Next physical state of the model + nextFailureState : array, shape(numAct+numSen) + Failure afflicting the s/c (unchanging by this model) + nextObservation : array, shape(numSenors) + Next observation of the model + """ + + return simulateSystem(physicalState,failureState, action, systemParametersTuple[0], systemParametersTuple[1], + systemParametersTuple[2], systemParametersTuple[3], systemParametersTuple[4], systemParametersTuple[5], + systemParametersTuple[6],systemParametersTuple[7],systemParametersTuple[8], + rngKey, noisyPropagationBooleanInt=noisyPropagationBooleanInt) + +#dt is pretty universal, so making an exception for it +def simulateSystem(physicalState,failureState, action,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix,positionCoefficientOfFriction, # pylint: disable=invalid-name + rotationalCoefficientOfFriction,sensingMatrix, dt, covarianceQ,covarianceR, rngKey, noisyPropagationBooleanInt=1): + """ + Iterates the model forward one time step dt based on the action chosen and generates resulting observation + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(2*numAct+2*numSen) + Failure afflicting the s/c. Now includes constant biases and notation change. 1 = failed, 0 = nominal + action : array, shape(numAct) + Current action to take + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + noisyPropagationBooleanInt : int + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextPhysicalState : array, shape(numState) + Next physical state of the model + nextFailureState : array, shape(numAct+numSen) + Failure afflicting the s/c (unchanging by this model) + nextObservation : array, shape(numSenors) + Next observation of the model + """ + + #Split rngKey for two different noise processes. These keys are consumed on use! So we need to split first + rngKey, rngSubKey = jaxRandom.split(rngKey) + + #First we note that by assumption, the failure state doesn't change, so only propagate the physical state + nextPhysicalState = propagateDynamics(physicalState,failureState,action,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix, + positionCoefficientOfFriction,rotationalCoefficientOfFriction,covarianceQ, dt, rngSubKey,noisyPropagationBooleanInt) + + nextObservation = observationModel(nextPhysicalState,failureState,sensingMatrix,getRealizedNominalMeasurement,covarianceR,rngKey,noisyPropagationBooleanInt) + + return (nextPhysicalState,failureState,nextObservation) + +#dt is pretty universal, so making an exception for it +def propagateDynamics(physicalState,failureState,action,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix,positionCoefficientOfFriction, # pylint: disable=invalid-name + rotationalCoefficientOfFriction,covarianceQ, dt, rngKey,noisyPropagationBooleanInt): + """ + Iterates the dynamics forward a time step + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate. physicalState = [x, vx, y, vy, theta, omega, w1, w2, ...] + Where w1, w2 ... are the speeds of the wheels (if any, determined by length of the state vector) + failureState : array, shape(2*numAct+2*numSen) + Failure afflicting the s/c. Now includes constant biases and notation change. 1 = failed, 0 = nominal + action : array, shape(numAct) + Current action to take (constant) + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + dt : float + The time between time steps of the experiment + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + noisyPropagationBooleanInt : int + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextState : tuple (nextPhysicalState, nextPhi) + Next state of the model + """ + + realizedAction = getRealizedAction(failureState,action) + + #Create Noise + dynamicsNoise = jaxRandom.multivariate_normal(rngKey,jnp.zeros(len(physicalState)), covarianceQ) + + #Use an rk4 solver for good enough accuracy (I think) that can be jitted + nominalNextState = rk4(physicalState,realizedAction,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix,positionCoefficientOfFriction,rotationalCoefficientOfFriction, dt) + + return nominalNextState + noisyPropagationBooleanInt * dynamicsNoise #when noisyPropagationBooleanInt is 0, noise is zeroed out! + +def actionDynamicsJacobian(physicalState,failureState,systemParametersTuple): + """ + The jacobian of the dynamics with respect to the control input. + Used by the scp solver + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(2*numAct+2*numSen) + Failure afflicting the s/c. Now includes constant biases and notation change. 1 = failed, 0 = nominal + action : array, shape(numAct) + Current action to take + systemParametersTuple : tuple + Contents are in order: + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + + Returns + ------- + jacobianMatrix : array(numState,numAct) + Derivative of the each element of the dynamics with respect to each element of the state + """ + + #Only difference between this implementation and previous is failure convention change, so pass in adjusted failure + # (note we don't need to remove bias, as the previous implementation only considers first numAct failures) + + return baseActionDynamicsJacobian(physicalState,1-failureState,systemParametersTuple) + +@jax.jit +def dynamicsJacobianWrapper(physicalState,failureState, nominalAction,systemParametersTuple): + """ + Wrapper for the 3DOF model system, so all the systems look the same up to a systemParametersList which is unique to each system + Currently no error checking!! + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(2*numAct+2*numSen) + Failure afflicting the s/c. Now includes constant biases and notation change. 1 = failed, 0 = nominal + action : array, shape(numAct) + Current action to take + systemParametersTuple : tuple + Contents are in order: + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + + Returns + ------- + jacobianMatrix : array(numState,numState) + Derivative of the each element of the dynamics with respect to each element of the state + """ + + #Return the jacobian after pulling out the needed parameters (skip those unneeded) + return dynamicsJacobian(physicalState, failureState, nominalAction, systemParametersTuple[0], systemParametersTuple[2],systemParametersTuple[3],systemParametersTuple[4]) + +def dynamicsJacobian(physicalState, failureState, nominalAction, positionInfluenceMatrix,reactionWheelInfluenceMatrix,positionCoefficientOfFriction,rotationalCoefficientOfFriction): + """ + Compute the Jacobian of the dynamics at the given state + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate. physicalState = [x, vx, y, vy, theta, omega, w1, w2, ...] + Where w1, w2 ... are the speeds of the wheels (if any, determined by length of the state vector) + failureState : array, shape(2*numAct+2*numSen) + Failure afflicting the s/c. Now includes constant biases and notation change. 1 = failed, 0 = nominal + nominalAction : array, shape(numAct) + Current action to take before applying the failure (constant) + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + + Returns + ------- + jacobianMatrix : array(numState,numState) + Derivative of the each element of the dynamics with respect to each element of the state + """ + + idxVx = 1 + idxVy = 3 + idxTheta = 4 + idxOmega = 5 + + #Get action after faults applied + realizedAction = getRealizedAction(failureState,nominalAction) + + numThrusters = len(positionInfluenceMatrix[0]) + numWheels = len(reactionWheelInfluenceMatrix) + + #Get rotation matrix derivative + theta = physicalState[4] + rotationMatrixDerivative = thetaRotationMatrixDerivative(theta) + + #Construct jacobianMatrix + + #Velocity derivatives with theta (only nonlinear term in 3DOF) + jacobianMatrixSpatialVelDTheta = jnp.matmul(rotationMatrixDerivative,jnp.matmul(positionInfluenceMatrix,realizedAction[0:numThrusters])) + + #First 4x4 corner is just the original A matrix from 2DOF (Need friction coefficients!) + singleAxisDynamicsMatrix = jnp.array([[0,1], + [0,-positionCoefficientOfFriction]]) + jacobianSpatialPosVelDPosVel = jnp.kron(jnp.eye(2,dtype=int),singleAxisDynamicsMatrix) + + #First 4 rows + jacobianSpatialPosVel = jnp.concatenate((jacobianSpatialPosVelDPosVel,jnp.zeros((4,2+numWheels))),axis=1) + #Set velocity derivatives explicitly + jacobianSpatialPosVel = jacobianSpatialPosVel.at[idxVx,idxTheta].set(jacobianMatrixSpatialVelDTheta[0]) + jacobianSpatialPosVel = jacobianSpatialPosVel.at[idxVy,idxTheta].set(jacobianMatrixSpatialVelDTheta[1]) + + #Remaining rows (only non zero is theta derivative (and friction coefficient!), will set that explicitly) + jacobianMatrix = jnp.concatenate((jacobianSpatialPosVel,jnp.zeros((2+numWheels,6+numWheels)))) + jacobianMatrix = jacobianMatrix.at[idxTheta,idxOmega].set(1) + jacobianMatrix = jacobianMatrix.at[idxOmega,idxOmega].set(-rotationalCoefficientOfFriction) + + + return jacobianMatrix diff --git a/failurePy/models/threeDOFModel.py b/failurePy/models/threeDOFModel.py new file mode 100644 index 0000000..ee24220 --- /dev/null +++ b/failurePy/models/threeDOFModel.py @@ -0,0 +1,652 @@ +""" +Non-linear planar dynamics and observing model + +Currently implemented in a non-OOP approach to allow for JIT compiling +""" + +import jax +import jax.numpy as jnp +from jax import random as jaxRandom +from failurePy.models.modelsCommon import observationModel, makeSingleAxisSensingMatrix +from failurePy.models.linearModel import getRealizedAction, getRealizedNominalMeasurement + +@jax.jit #Slight speed up, not the main slow down it appears (already jitting somewhere?) +def simulateSystemWrapper(physicalState,failureState,action,rngKey,systemParametersTuple,noisyPropagationBooleanInt=1): + """ + Wrapper for the 3DOF model system, so all the systems look the same up to a systemParametersList which is unique to each system + Currently no error checking!! + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + action : array, shape(numAct) + Current action to take + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + systemParametersTuple : tuple + Contents are in order: + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + noisyPropagationBooleanInt : int (default=1) + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextPhysicalState : array, shape(numState) + Next physical state of the model + nextFailureState : array, shape(numAct+numSen) + Failure afflicting the s/c (unchanging by this model) + nextObservation : array, shape(numSenors) + Next observation of the model + """ + + return simulateSystem(physicalState,failureState, action, systemParametersTuple[0], systemParametersTuple[1], + systemParametersTuple[2], systemParametersTuple[3], systemParametersTuple[4], systemParametersTuple[5], + systemParametersTuple[6],systemParametersTuple[7],systemParametersTuple[8], + rngKey, noisyPropagationBooleanInt=noisyPropagationBooleanInt) + +#dt is pretty universal, so making an exception for it +def simulateSystem(physicalState,failureState, action,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix,positionCoefficientOfFriction, # pylint: disable=invalid-name + rotationalCoefficientOfFriction,sensingMatrix, dt, covarianceQ,covarianceR, rngKey, noisyPropagationBooleanInt=1): + """ + Iterates the model forward one time step dt based on the action chosen and generates resulting observation + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + action : array, shape(numAct) + Current action to take + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + noisyPropagationBooleanInt : int + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextPhysicalState : array, shape(numState) + Next physical state of the model + nextFailureState : array, shape(numAct+numSen) + Failure afflicting the s/c (unchanging by this model) + nextObservation : array, shape(numSenors) + Next observation of the model + """ + + #Split rngKey for two different noise processes. These keys are consumed on use! So we need to split first + rngKey, rngSubKey = jaxRandom.split(rngKey) + + #First we note that by assumption, the failure state doesn't change, so only propagate the physical state + nextPhysicalState = propagateDynamics(physicalState,failureState,action,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix, + positionCoefficientOfFriction,rotationalCoefficientOfFriction,covarianceQ, dt, rngSubKey,noisyPropagationBooleanInt) + + nextObservation = observationModel(nextPhysicalState,failureState,sensingMatrix,getRealizedNominalMeasurement, + covarianceR,rngKey,noisyPropagationBooleanInt) + + return (nextPhysicalState,failureState,nextObservation) + +#dt is pretty universal, so making an exception for it +def propagateDynamics(physicalState,failureState,action,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix,positionCoefficientOfFriction, # pylint: disable=invalid-name + rotationalCoefficientOfFriction,covarianceQ, dt, rngKey,noisyPropagationBooleanInt): + """ + Iterates the dynamics forward a time step + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate. physicalState = [x, vx, y, vy, theta, omega, w1, w2, ...] + Where w1, w2 ... are the speeds of the wheels (if any, determined by length of the state vector) + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + action : array, shape(numAct) + Current action to take (constant) + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + dt : float + The time between time steps of the experiment + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + noisyPropagationBooleanInt : int + When 0, noise free propagation is used. Should be 1 or 0 for defined behavior! + + + Returns + ------- + nextState : tuple (nextPhysicalState, nextPhi) + Next state of the model + """ + + #Apply to the actuation + realizedAction = getRealizedAction(failureState,action) + + #Create Noise + dynamicsNoise = jaxRandom.multivariate_normal(rngKey,jnp.zeros(len(physicalState)), covarianceQ) + + #Use an rk4 solver for good enough accuracy (I think) that can be jitted + nominalNextState = rk4(physicalState,realizedAction,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix,positionCoefficientOfFriction,rotationalCoefficientOfFriction, dt) + + return nominalNextState + noisyPropagationBooleanInt * dynamicsNoise #when noisyPropagationBooleanInt is 0, noise is zeroed out! + +def rk4(physicalState,realizedAction,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix,positionCoefficientOfFriction,rotationalCoefficientOfFriction, dt): #dt is pretty universal, so making an exception for it pylint: disable=invalid-name + """ + Use an rk4 approximator to accurately propagate the non-linear dynamics + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate. physicalState = [x, vx, y, vy, theta, omega, w1, w2, ...] + Where w1, w2 ... are the speeds of the wheels (if any, determined by length of the state vector) + realizedAction : array, shape(numAct) + Current action to take after applying the failure (constant) + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + dt : float + The time between time steps of the experiment + + Returns + ------- + + """ + + #RK4 algorithm is y_{n+1} = y_n + 1/6 (k_1 + 2k_2 + 3k_3 + k_4)dt + #We'll compute each intermediate step (note no time dependence in dynamics!) + #Since these are local math variables, we will make an exception to the naming convention + + k1 = dynamicsDerivatives(physicalState,realizedAction,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix, # pylint: disable=invalid-name + positionCoefficientOfFriction,rotationalCoefficientOfFriction) + + k2 = dynamicsDerivatives(dt/2 *k1 + physicalState,realizedAction,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix, # pylint: disable=invalid-name + positionCoefficientOfFriction,rotationalCoefficientOfFriction) + + k3 = dynamicsDerivatives(dt/2 *k2 + physicalState,realizedAction,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix, # pylint: disable=invalid-name + positionCoefficientOfFriction,rotationalCoefficientOfFriction) + + k4 = dynamicsDerivatives(dt * k3 + physicalState,realizedAction,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix, # pylint: disable=invalid-name + positionCoefficientOfFriction,rotationalCoefficientOfFriction) + + return physicalState + 1/6 * (k1 + 2* k2 + 2* k3 + k4) * dt + +def dynamicsDerivatives(physicalState,realizedAction,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix,positionCoefficientOfFriction,rotationalCoefficientOfFriction): + """ + Computes the dynamics derivatives at this time step + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate. physicalState = [x, vx, y, vy, theta, omega, w1, w2, ...] + Where w1, w2 ... are the speeds of the wheels (if any, determined by length of the state vector) + realizedAction : array, shape(numAct) + Current action to take after applying the failure (constant) + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + + Returns + ------- + stateDerivatives : array(numState) + Derivative of each state for the given inputs + """ + + #NOTE u is inertial, tau is body + + numThrusters = len(positionInfluenceMatrix[0]) + + #Get velocities + velocityX = physicalState[1] + velocityY = physicalState[3] + angularVelocityOmega = physicalState[5] + + #Get rotation matrix + theta = physicalState[4] + rotationMatrix = thetaRotationMatrix(theta) + + + #Because things are non-linear, we compute the derivatives for spatial, angular and wheel states separately, to make the math easier to follow. + # This isn't as critical for the 3DOF model, but will make generalizing easier + inertialSpatialAccelerations = jnp.matmul(rotationMatrix,jnp.matmul(positionInfluenceMatrix,realizedAction[0:numThrusters])) #Already scaled influence by mass. + accelerationX = inertialSpatialAccelerations[0] - positionCoefficientOfFriction*velocityX #USING ASSUMPTION FRICTION IS THE SAME IN EACH AXIS. If we don't, need to do this before rotation + #This friction force is to capture average residual friction in our spacecraft simulator, so can be somewhat orientation dependent + accelerationY = inertialSpatialAccelerations[1] - positionCoefficientOfFriction*velocityY + + #Note that since there is only one axis, reactionWheelInfluenceMatrix is a vector + #Torque (in body frame) due to thrusters and RW (note - sign is due to Newton's third law, torque is opposite of acceleration) wheels are listed last in the action + #Already scaled by moment #NOTE: We don't want to do this for higher dimensions, it's a matrix (maybe we still can?) + bodyAngularAcceleration = -rotationalCoefficientOfFriction*angularVelocityOmega + ( + jnp.matmul(rotationInfluenceMatrix,realizedAction[0:numThrusters])+jnp.matmul(-reactionWheelInfluenceMatrix,realizedAction[numThrusters:])) + + #This should be positive, b/ torque is opposite of wheel speed change + wheelAccelerations = realizedAction[numThrusters:] + + #Derivative is [vx, ax, vy, ay, omega, alpha, w1dot, w2dot] + stateDerivativesMinusWheels = jnp.array([velocityX,accelerationX,velocityY,accelerationY,angularVelocityOmega,bodyAngularAcceleration]) + + return jnp.concatenate((stateDerivativesMinusWheels,wheelAccelerations)) + +def actionDynamicsJacobian(physicalState,failureState,systemParametersTuple): + """ + The jacobian of the dynamics with respect to the control input. + Used by the scp solver + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + action : array, shape(numAct) + Current action to take + systemParametersTuple : tuple + Contents are in order: + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + + Returns + ------- + jacobianMatrix : array(numState,numAct) + Derivative of the each element of the dynamics with respect to each element of the state + """ + + #Get needed system parameters + positionInfluenceMatrix = systemParametersTuple[0] + rotationInfluenceMatrix = systemParametersTuple[1] + reactionWheelInfluenceMatrix = systemParametersTuple[2] + + numThrusters = len(positionInfluenceMatrix[0]) + numWheels = len(reactionWheelInfluenceMatrix) + + #Get rotation matrix + theta = physicalState[4] + rotationMatrix = thetaRotationMatrix(theta) + + #Set up output + jacobianMatrix = jnp.zeros((6+numWheels,numThrusters+numWheels)) #Wheels are tracked! (Maybe arguably shouldn't, it's for compatibility with future multi-axis rotation) + #print(jnp.shape(jacobianMatrix),numThrusters,numWheels) + + #Dynamics are all linear in control, but not in state, so need to factor that in + # RTheta * Bp * phi_B[thrusters] -> 2 x numThrusters (we left out spatial states here) + inertialSpatialAccelerationInfluence = jnp.matmul(rotationMatrix,jnp.matmul(positionInfluenceMatrix,jnp.diag(failureState[0:numThrusters]))) + #Br * phi_B[thrusters] -> 1 x numThrusters + bodyAngularAccelerationThrusterInfluence = jnp.matmul(rotationInfluenceMatrix,jnp.diag(failureState[0:numThrusters])) + #(G*Jw) * phi_B[thrusters] -> 1x numWheels + bodyAngularAccelerationWheelInfluence = jnp.matmul(-reactionWheelInfluenceMatrix,jnp.diag(failureState[numThrusters:numThrusters+numWheels])) + + #Spatial portions, state is x, vx, y, vy, theta, omega + jacobianMatrix = jacobianMatrix.at[1,0:numThrusters].set(inertialSpatialAccelerationInfluence[0,:]) + jacobianMatrix = jacobianMatrix.at[3,0:numThrusters].set(inertialSpatialAccelerationInfluence[1,:]) + #Angular portions + jacobianMatrix = jacobianMatrix.at[5,0:numThrusters].set(bodyAngularAccelerationThrusterInfluence) + jacobianMatrix = jacobianMatrix.at[5,numThrusters:].set(bodyAngularAccelerationWheelInfluence) + #Wheel influence + jacobianMatrix = jacobianMatrix.at[6:,numThrusters:].set(jnp.eye(numWheels)) + + return jacobianMatrix + +@jax.jit +def dynamicsJacobianWrapper(physicalState,failureState, nominalAction,systemParametersTuple): + """ + Wrapper for the 3DOF model system, so all the systems look the same up to a systemParametersList which is unique to each system + Currently no error checking!! + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + action : array, shape(numAct) + Current action to take + systemParametersTuple : tuple + Contents are in order: + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + + Returns + ------- + jacobianMatrix : array(numState,numState) + Derivative of the each element of the dynamics with respect to each element of the state + """ + + #Return the jacobian after pulling out the needed parameters (skip those unneeded) + return dynamicsJacobian(physicalState, failureState, nominalAction, systemParametersTuple[0], systemParametersTuple[2],systemParametersTuple[3],systemParametersTuple[4]) + +def dynamicsJacobian(physicalState, failureState, nominalAction, positionInfluenceMatrix,reactionWheelInfluenceMatrix,positionCoefficientOfFriction,rotationalCoefficientOfFriction): + """ + Compute the Jacobian of the dynamics at the given state + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state of the system to propagate. physicalState = [x, vx, y, vy, theta, omega, w1, w2, ...] + Where w1, w2 ... are the speeds of the wheels (if any, determined by length of the state vector) + failureState : array, shape(numAct+numSen) + Failure afflicting the s/c + nominalAction : array, shape(numAct) + Current action to take before applying the failure (constant) + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + + Returns + ------- + jacobianMatrix : array(numState,numState) + Derivative of the each element of the dynamics with respect to each element of the state + """ + + idxVx = 1 + idxVy = 3 + idxTheta = 4 + idxOmega = 5 + + #Create failure Matrix on the actuators Phi_B + actuatorFailureMatrix = jnp.diag(failureState[0:len(positionInfluenceMatrix[0])+len(reactionWheelInfluenceMatrix)]) + + #Apply to the actuation + realizedAction = jnp.matmul(actuatorFailureMatrix,nominalAction) + + numThrusters = len(positionInfluenceMatrix[0]) + numWheels = len(reactionWheelInfluenceMatrix) + + #Get rotation matrix derivative + theta = physicalState[4] + rotationMatrixDerivative = thetaRotationMatrixDerivative(theta) + + #Construct jacobianMatrix + + #Velocity derivatives with theta (only nonlinear term in 3DOF) + jacobianMatrixSpatialVelDTheta = jnp.matmul(rotationMatrixDerivative,jnp.matmul(positionInfluenceMatrix,realizedAction[0:numThrusters])) + + #First 4x4 corner is just the original A matrix from 2DOF (Need friction coefficients!) + singleAxisDynamicsMatrix = jnp.array([[0,1], + [0,-positionCoefficientOfFriction]]) + jacobianSpatialPosVelDPosVel = jnp.kron(jnp.eye(2,dtype=int),singleAxisDynamicsMatrix) + + #First 4 rows + jacobianSpatialPosVel = jnp.concatenate((jacobianSpatialPosVelDPosVel,jnp.zeros((4,2+numWheels))),axis=1) + #Set velocity derivatives explicitly + jacobianSpatialPosVel = jacobianSpatialPosVel.at[idxVx,idxTheta].set(jacobianMatrixSpatialVelDTheta[0]) + jacobianSpatialPosVel = jacobianSpatialPosVel.at[idxVy,idxTheta].set(jacobianMatrixSpatialVelDTheta[1]) + + #Remaining rows (only non zero is theta derivative (and friction coefficient!), will set that explicitly) + jacobianMatrix = jnp.concatenate((jacobianSpatialPosVel,jnp.zeros((2+numWheels,6+numWheels)))) + jacobianMatrix = jacobianMatrix.at[idxTheta,idxOmega].set(1) + jacobianMatrix = jacobianMatrix.at[idxOmega,idxOmega].set(-rotationalCoefficientOfFriction) + + + return jacobianMatrix + + +def makeInfluenceMatrices(spacecraftMass,systemMoment,leverArm,numWheels,numAct=None,reactionWheelMoment=None): + """ + Make the influence matrix of the model, scaled by inertia and moment + + Parameters + ---------- + systemMass : float + Mass of s/c + leverArm : float + Distance from thrusters to center of mass in each axis, in m (assumed to be uniform for now) + numWheels : int + Number of wheels present + numAct : int (default=None) + Number of actuators affecting the model. By default we assume 2 in each axis (+/-) + The number of actuators will be rounded (down) to the nearest value that can be evenly distributed among each axis (ie, divided by dim*2) + reactionWheelMoment : array, shape(numWheels) (default=None) + Moment of each reaction wheel affecting the model. By default we assume a uniform value of .05 for each + + Returns + ------- + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + """ + + dim = 2 #Always 2 positional dimensions and one rotational + + #Default behavior + if numAct is None: + numAct = 8 + singleAxisInfluenceMatrix = jnp.array([[-1,-1,1,1]]) #NOTE: We now just consider the effects on velocity, don't handle position terms to make stacking up easier later. + #We assume a symmetric distribution of the actuators, round down to achieve + else: + numActPerDirection = int(numAct/(dim*2)) + singleAxisInfluenceMatrix = jnp.zeros((1,2*numActPerDirection)) + #Set half actuators as negative, half as positive + singleAxisInfluenceMatrix = singleAxisInfluenceMatrix.at[0,:numActPerDirection].set(-1) + singleAxisInfluenceMatrix = singleAxisInfluenceMatrix.at[0,numActPerDirection:].set(1) + + positionInfluenceMatrix = jnp.kron(jnp.eye(dim,dtype=int),singleAxisInfluenceMatrix/spacecraftMass) + + #We will alternate the torque of each actuator + rotationInfluenceMatrix = leverArm/systemMoment * jnp.ones(numAct) + for iActuator in range(numAct): + if iActuator % 2 == 1: + rotationInfluenceMatrix = rotationInfluenceMatrix.at[iActuator].set(-1 * leverArm/systemMoment) + + #All reaction wheels are aligned with the z-axis, so G is identity + if reactionWheelMoment is None: + reactionWheelInfluenceMatrix = .05/systemMoment*jnp.ones(numWheels) + else: + reactionWheelInfluenceMatrix = reactionWheelMoment/systemMoment + + return positionInfluenceMatrix, rotationInfluenceMatrix, reactionWheelInfluenceMatrix + +def makeCalibratedInfluenceMatricesNoWheels(positionInfluence,rotationInfluence): + + """ + Makes the positionInfluenceMatrix and rotationInfluenceMatrix for given thruster position and rotation influence + + Parameters + ---------- + positionInfluence : float + Ratio of thrust/mass for each thruster + rotationInfluence : float + Ratio of torque/moment of inertia for each thruster + + Returns + ------- + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + """ + + dim = 2 #Always 2 positional dimensions and one rotational + numAct = 8 + singleAxisInfluenceMatrix = positionInfluence * jnp.array([[-1,-1,1,1]]) #NOTE: We now just consider the effects on velocity, don't handle position terms to make stacking up easier later. + + positionInfluenceMatrix = jnp.kron(jnp.eye(dim,dtype=int),singleAxisInfluenceMatrix) + + #We will alternate the torque of each actuator + rotationInfluenceMatrix = rotationInfluence * jnp.ones(numAct) + for iActuator in range(numAct): + if iActuator % 2 == 1: + rotationInfluenceMatrix = rotationInfluenceMatrix.at[iActuator].set(-rotationInfluence) + + return positionInfluenceMatrix,rotationInfluenceMatrix + +def makeSensingMatrix(numWheels, numSen=None): + """ + Make the sensing matrix of the model + + Parameters + ---------- + numWheels : int + Number of reaction wheels. Part of the state, but we don't sense this directly (for now) + numSen : int (default=None) + Number of sensors measuring the model. By default we assume 2 in each dimension + The number of sensors will be rounded (down) to the nearest value that can be evenly distributed among each dimension + We further assume no direct sensing of velocities + Returns + ------- + sensingMatrix : array, shape(numSen,numState) + C matrix + """ + + dim = 3 + + singleAxisSensingMatrix = makeSingleAxisSensingMatrix(dim, numSen) + + sensingMatrixMinusWheels = jnp.kron(jnp.eye(dim,dtype=int),singleAxisSensingMatrix) + #Need to add zeros for the wheel states + + return jnp.concatenate((sensingMatrixMinusWheels, jnp.zeros((len(sensingMatrixMinusWheels),numWheels))),axis=1) + +def thetaRotationMatrix(theta): + """ + Function that returns the 2D rotation matrix from theta used + for a matrix multiplication to transform from the inertial + to body frames + + Parameters + ---------- + theta : float + angle in radians of the s/c's rotation + + Returns + ------- + thetaRotationMatrix : array, shape(2,2) + Rotation matrix from inertial to body frame + """ + + return jnp.array([[jnp.cos(theta),-jnp.sin(theta)], + [jnp.sin(theta), jnp.cos(theta)]]) + +def thetaRotationMatrixDerivative(theta): + """ + Function that returns the derivative with respect to theta + 2D rotation matrix from theta used for a matrix multiplication + to transform from the inertial to body frames + + Parameters + ---------- + theta : float + angle in radians of the s/c's rotation + + Returns + ------- + thetaRotationMatrixDerivative : array, shape(2,2) + Rotation matrix from inertial to body frame + """ + + return jnp.array([[-jnp.sin(theta),-jnp.cos(theta)], + [ jnp.cos(theta),-jnp.sin(theta)]]) diff --git a/failurePy/pipeline.py b/failurePy/pipeline.py new file mode 100644 index 0000000..a4978ee --- /dev/null +++ b/failurePy/pipeline.py @@ -0,0 +1,846 @@ +""" +Main file for setting up, running, and logging data for experiments +""" +import os +import time +#import pickle +import argparse +#Multiprocessing components to make things run faster +import multiprocessing as mp +from queue import Empty #Can't get this directly from mp.Queue +import numpy as onp #Following Jax conventions +import multiprocess.context as ctx +import jax.numpy as jnp + +import jax +from jax import random as jaxRandom +from tqdm import tqdm +#failurePy imports, these need to be installed by pip to work`` +from failurePy.load.yamlLoader import loadExperimentParamsFromYaml, loadExperimentParams +from failurePy.utility.saving import checkSaveDirectoryPathMakeIfNeeded, processDataAverages, checkIfDataExists,makeTrialResultDict,setUpDataOutput,saveTrialResult,getTrialDataPath #,saveMetaData +from failurePy.visualization.renderPlanarVisWrapper import visualizeFirstTrajectory +from failurePy.solvers.randomPolicy import solveForNextAction as randomPolicyF +from failurePy.solvers.randomPolicy import distributedSolveForNextAction as distributedRandomPolicyF +from failurePy.utility.tqdmMultiprocessing import initializeTqdm +from failurePy.utility.pipelineHelperMethods import getExperimentParameters, generateAllPossibleFailures, checkFailureIsValid, diagnoseFailure +from failurePy.estimators.generalFaultSampling import binaryToDegradationFaults #Check fault initialization method +from failurePy.utility.computeAlternateReward import computeSquareSumFailureBeliefRewardAlternativeThroughout + + +def main(configFilePath, saveData=True, visualizeFirstTrajectoryFlag=True): + """ + Main method of the code sets up, runs, logs and cleans up experiment + + Parameters + ---------- + configFilePath : String + Relative path to the config file for the experiment + saveData : boolean (default=True) + Over-rides data saving behavior when False to not write out any data, avoiding potential overwrite when testing or profiling + visualizeFirstTrajectory : boolean (default=True) + Whether to visualize the first experiment result or not + """ + + + #First load in the experiment parameters. These determine the save path, so this is returned as well + experimentParamsDict, saveDirectoryPath = loadExperimentParamsFromYaml(configFilePath) #We won't use extra data here pylint: disable=unbalanced-tuple-unpacking + + #Make absolute save directory if it isn't already + if not saveDirectoryPath[0] == "/": + saveDirectoryPath = os.path.join(os.getcwd(),saveDirectoryPath) + + #Check if save directory is clean + checkSaveDirectoryPathMakeIfNeeded(saveDirectoryPath,experimentParamsDict) + + #Setup data output + setUpDataOutput(saveDirectoryPath, experimentParamsDict, configFilePath) + + #Check for multiprocessing. If so, we will recurse into sub processes + if experimentParamsDict["multiprocessingFlag"]: + runMultiprocessingSubExperiments(experimentParamsDict["virtualConfigDictList"],saveDirectoryPath, + nTrialsPerPoint=experimentParamsDict["nTrialsPerPoint"],numExperiments=len(experimentParamsDict["nSimulationsPerTreeList"])) + else: + runExperimentsAndLog(experimentParamsDict,saveDirectoryPath,saveData) + + #Log data (potentially do something with a return code at a later date?) + processDataAverages(saveDirectoryPath,experimentParamsDict) + + computeSquareSumFailureBeliefRewardAlternativeThroughout(saveDirectoryPath,force=True) + + if visualizeFirstTrajectoryFlag: + #Display, only if asked (never multiprocessing) + visualize(experimentParamsDict,saveDirectoryPath) + +def runMultiprocessingSubExperiments(virtualConfigDictList,saveDirectoryPath,nTrialsPerPoint,numExperiments): + """ + Splits the experiments to run into many sub experiments for parallelization using multiprocessing. + Each sub experiment has a virtual configuration dictionary, that can be passed to yamlLoader to get the needed parameters, + it has already been configured for the number of cores desired. + + virtualConfigDictList : list + Each member of the list contains the configuration parameters for their sub-experiment. This is the same information + we would get from the config file, but multiprocessing is set to False, and the rngKeysOffset and nTrialsPerPoint are + adjusted to split the load across cores + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + Now using pickle to save the data in it's original dictionary format, rather than creating directories for each data type saved + totalTrials : int + Total number of trials that we are doing across all processes + """ + + #Get number of cores available, always leave specified number free (in multiprocessing flag!) + numProcesses = len(virtualConfigDictList) + + #Limit CPU cores to numProcesses! (To share better on servers) + cpuMask = range(numProcesses) + os.sched_setaffinity(os.getpid(), cpuMask) + + #Make progress bar and queue + tqdmQueue = mp.Queue() #Infinite Queue + tqdmProcess = mp.Process(target=multiprocessingTqdmUpdater,args=(tqdmQueue,nTrialsPerPoint,numExperiments),daemon=True) #Incase we ctrl+c (should still kill them but can't hurt) + tqdmProcess.start() + + #And multiprocess! + processList = [] + for iProcess in range(numProcesses): + #Make progress bar (only first process gets a real one, rest are None) (daemon incase we ctrl+c (should still kill them but can't hurt)) + process = mp.Process(target=multiprocessingMain,args=(virtualConfigDictList[iProcess],saveDirectoryPath,tqdmQueue),daemon=True) + process.start() + processList.append(process) + + for process in processList: + process.join() + + #No need to track progress + tqdmProcess.join() + +def multiprocessingTqdmUpdater(tqdmQueue,nTrialsPerPoint,numExperiments): + """ + Helper function that updates the tqdm progress bar + """ + + progressBar = initializeTqdm(nTrialsPerPoint) + experiment = 0 + trial = 0 + numExtraUpdates = 0 + + while experiment < numExperiments: + #Listening loop + while trial < nTrialsPerPoint: + #Get all progress counts that are available, then the exception breaks us out + numUpdates = 0 + try: + while True: + numUpdates += tqdmQueue.get_nowait() + except Empty: + #This is our indication that we have all the updates, so update now! + trial += numUpdates + #Check if any processes went on to the next experiment already (note this is approximate) + if trial > nTrialsPerPoint: + numExtraUpdates = trial - nTrialsPerPoint + numUpdates = numUpdates-numExtraUpdates + + progressBar.update(numUpdates) + #Sleep a little to avoid wasting too much effort listening + time.sleep(.1) #Don't need updates more than every 10th of a second + + #Make next manual bar for next experiment + progressBar = initializeTqdm(nTrialsPerPoint) + #Add any extra updates + progressBar.update(numExtraUpdates) + trial = numExtraUpdates + experiment += 1 + +def multiprocessingMain(virtualInputDict,saveDirectoryPath,tqdmQueue=None, disableTqdm=True): + """ + Helper function that loads the experimentParamsDict and runs all of the experiments and trials. + + Parameters + ---------- + virtualInputDict : dict + Contains the configuration parameters for this sub-experiment. This is the same information we would + get from the config file, but multiprocessing is set to False, and the rngKeysOffset and nTrialsPerPoint are adjusted + to split the load across cores + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + Now using pickle to save the data in it's original dictionary format, rather than creating directories for each data type saved + tqdmQueue : multiprocessing queue (default=None) + Queue object to send progress updates through, should be provided unless disableTqdm is set to False + disableTqdm : boolean (default=True) + Replaces tqdm with custom tqdmQueue object if the tqdmQueue is provided + """ + #Get the experiments parameters. We won't use the relative save directory path, as we will use the one for the full experiment + experimentParamsDict, dummyRelativeSaveDirectoryPath = loadExperimentParams(virtualInputDict,silent=True) #We won't use extra data here pylint: disable=unbalanced-tuple-unpacking + #And run! We always save data + runExperimentsAndLog(experimentParamsDict,saveDirectoryPath,saveData=True, #Always save data + disableTqdm=disableTqdm, tqdmQueue=tqdmQueue) + + +def runExperimentsAndLog(experimentParamsDict,saveDirectoryPath,saveData=True,disableTqdm=False, tqdmQueue=None,): + """ + Method that contains the main experiment loop. + To avoid memory leaks, we log the results of each trial as they are produced + + Parameters + ---------- + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + The contents should be as follows: + nSimulationsPerTreeList : list, len(numTrials) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + dt : float + The time between time steps of the experiment + nExperimentSteps : int + How many time steps are in the experiment + nTrialsPerPoint : int + The number of repeated trials per configuration. + nMaxComponentFailures : int + Maximum number of simultaneous failures of components that can be considered + nMaxFailureParticles : int + Maximum number of failure particles to consider at once. If larger than the number of possible unique failures, all possibilities are considered + providedFailure : array, shape(numAct+numSen) (default=None) + Provided failure (if any) to have each trial use + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + solverFList : list + List of solver functions to try + solverParametersTuplesList : list + List of tuples of solver parameters. Included action list, failure scenarios + solverNamesList: list + List of names of solvers, for data logging + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Physical state estimator for use with the marginal filter, if any + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + beliefInitializationF : function + Function that creates the initial belief + rewardF : function + Reward function to evaluate the beliefs with + rngKeysOffset : int + Offset to the initial PRNG used in generating the initial failure states and randomness in the trials. + This is added to the trial number to allow for different trials to be preformed + multiprocessingFlag : int + Wether to use multi-processing (if number is set other than 0) or not (if False/0) + saveTreeFlag : boolean + Whether to save the tree or not (it can be quite large, so if not visualizing, it is best to set this to false) + numWarmStart : int (default=0) + Checks if we should run the solver a few times to compile first, and if so how many. Only does so on first trial. Currently only implemented for non-multiprocessing + clobber : boolean + Wether to overwrite existing data or not + plottingBounds : array, shape(2,2) (default=None) + Bounds of the plotting axis + resolution : int (default=200) + How high of a resolution the safe zone should be drawn in when showing the safety function. + virtualConfigDictList : list + List of input dictionaries for each subExperiment when multiprocessing + networkFlag : bool + Whether we are in a distributed network or not + generalFaultDict : dict + If we are using a general fault model this is a dictionary with the following values. Otherwise it is None + failureParticleResampleF : function + Function that resamples the particles when needed + failureParticleResampleCheckF : function + Function that determines if resampling is needed + failureParticleInitializationF : function + Function that creates the initial failure particles + filterDivergenceHandlingMethod : string + How to handle if the filter diverges mid trial. None if it should not be. + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + Now using pickle to save the data in it's original dictionary format, rather than creating directories for each data type saved + saveData : boolean (default=True) + Over-rides data saving behavior when False to not write out any data, avoiding potential overwrite when testing or profiling + disableTqdm : boolean (default=False) + When true, turns off tqdm bar for a manual bar. tqdmQueue should be provided + tqdmQueue : queue (default=None) + Queue to pass updates to the manual progress bar + """ + #Get basic parameters of the system + numState, numAct, numSen, numNFailures, numWarmStart, numAgents = getExperimentParameters(experimentParamsDict) + + #Loop over solvers + for iSolver in range(len(experimentParamsDict["solverFList"])): + + #Loop over nSimulationsPerTrees + for nSimulationsPerTree in experimentParamsDict["nSimulationsPerTreeList"]: + + #Loop over trials + for jTrial in tqdm(range(experimentParamsDict["nTrialsPerPoint"]),disable=disableTqdm): + #Only warm start first trial + warmStart = 0 if jTrial != 0 else numWarmStart + #Eventually might allow us to have data already existing + if experimentParamsDict["mergeData"] and checkIfDataExists(getTrialDataPath(saveDirectoryPath, experimentParamsDict["solverNamesList"][iSolver], nSimulationsPerTree, jTrial)): + raise NotImplementedError("Merging is not implemented at this time") + #continue #Don't overwrite + initializeRunAndSaveTrial(experimentParamsDict,numState, numAct, numSen,numNFailures,saveDirectoryPath,nSimulationsPerTree, + iSolver,jTrial+experimentParamsDict["rngKeysOffset"],saveData,numWarmStart=warmStart,numAgents=numAgents) + #Manual multiprocessing bar + if disableTqdm: + tqdmQueue.put_nowait(1) + +def initializeRunAndSaveTrial(experimentParamsDict,numState, numAct, numSen,numNFailures,saveDirectoryPath,nSimulationsPerTree,iSolver,rngSeed, + saveData=True,numWarmStart=0,numAgents=1): + """ + Helper method that performs the initialize, run and saving for each trial, to enable parallelization + + Parameters + ---------- + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + numState : int + Number of states + numAct : int + Number of actuators + numSen : int + Number of sensors + numNFailures : array, shape(nMaxComponentFailures+1) + Number of failure combinations for each level of failed components + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + iSolver : int + Index of the solver being run + rngSeed : int + Index of the trial being run (plus offset) + saveData : boolean (default=True) + Over-rides data saving behavior when False to not write out any data, avoiding potential overwrite when testing or profiling + numWarmStart : int (default=0) + Checks if we should run the solver a few times to compile first, and if so how many. Only does so on first trial. Currently only implemented for non-multiprocessing + numAgents : int (default=1) + How many agents are present (distinguishes single from multi-agent) + """ + + #Set random policy whenever nSimulationsPerTree = 0 + if nSimulationsPerTree == 0: + if numAgents == 1: + solverF = randomPolicyF + else: + solverF = distributedRandomPolicyF + else: + solverF = experimentParamsDict["solverFList"][iSolver] + + #Make initial rngKey and split + rngKey = jaxRandom.PRNGKey(rngSeed) + rngKey,rngSubKey = jaxRandom.split(rngKey) + initializationDict, initialFailureParticles = initializeTrial(numState, numAct, numSen, + experimentParamsDict["providedFailure"],numNFailures, + experimentParamsDict["nMaxFailureParticles"],experimentParamsDict["beliefInitializationF"], + experimentParamsDict["rewardF"],experimentParamsDict["generalFaultDict"],rngSubKey, + initialState=experimentParamsDict["initialState"],numAgents=numAgents) + #print("Trial initialized") + #Run trial + if numAgents == 1: + runTrialF = runSingleAgentTrial + else: + runTrialF = runNetworkTrial + trialResultDict = runTrialF(initializationDict,nSimulationsPerTree,experimentParamsDict["nExperimentSteps"], + experimentParamsDict["systemF"],experimentParamsDict["systemParametersTuple"], + solverF,experimentParamsDict["solverParametersTuplesList"][iSolver],#Get the list of solver params corresponding to this solver + experimentParamsDict["estimatorF"],experimentParamsDict["physicalStateSubEstimatorF"],experimentParamsDict["physicalStateJacobianF"], + experimentParamsDict["physicalStateSubEstimatorSampleF"],experimentParamsDict["rewardF"],initialFailureParticles,experimentParamsDict["generalFaultDict"], + experimentParamsDict["diagnosisThreshold"],experimentParamsDict["filterDivergenceHandlingMethod"], experimentParamsDict["saveTreeFlag"], + rngKey, numWarmStart=numWarmStart) #pass in PRNG key for this trial + #Future TODO: make computeSuccessAtEnd configurable! + #print("Trial run") + #Save this result directly (if turned on) + if saveData: + saveTrialResult(saveDirectoryPath, experimentParamsDict["solverNamesList"][iSolver], nSimulationsPerTree, rngSeed, trialResultDict) + +def runSingleAgentTrial(initializationDict,nSimulationsPerTree,nExperimentSteps,systemF,systemParametersTuple,solverF,solverParametersTuple,estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,rewardF,initialFailureParticles, generalFaultDict, diagnosisThreshold,filterDivergenceHandlingMethod, + saveTreeFlag, rngKey, computeSuccessAtEnd=False,computeSafetyAtEnd=True, numWarmStart=0): #These last two parameters currently hardcoded TODO. # pylint: disable=too-many-branches + """ + Method that runs one trial of a given system and solver, from given initialization + + Parameters + ---------- + initializationDict : dict + Initial physical state, failure state, beliefTuple, reward + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + nExperimentSteps : int + How many time steps are in the experiment + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + solverF : function + Solver function to select next action with + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Physical state estimator for use with the marginal filter, if any + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + rewardF : function + Reward function to evaluate the beliefs with + solverParametersTuple : tuple + List of solver parameters needed. Contents are: + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action + discretization : float + Discretization level or scheme + maxSimulationTime : float + Max simulation time (can be infinite). NOTE: Currently implemented by breaking loop after EXCEEDING time, NOT a hard cap + explorationParameter : float + Weighting on exploration vs. exploitation + nMaxDepth : int + Max depth of the tree + discountFactor : float + Discount on future rewards, should be in range [0,1] + initialFailureParticles : array, shape(nMaxFailureParticles,numAct+numSen) + List of (initial) possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + These may change if the estimator allows for re-sampling the fault particles + generalFaultDict : dict + If we are using a general fault model this is a dictionary with the following values. Otherwise it is None + failureParticleResampleF : function + Function that resamples the particles when needed + failureParticleResampleCheckF : function + Function that determines if resampling is needed + failureParticleInitializationF : function + Function that creates the initial failure particles + diagnosisThreshold : float + Level of the reward to consider high enough to return an answer. + Overload: If set to a value above 1, use diagnosisThreshold-1 for evaluating filter divergences (if appropriate) + filterDivergenceHandlingMethod : string + How to handle if the filter diverges mid trial. None if it should not be. + saveTreeFlag : boolean + Whether to save the tree or not (it can be quite large, so if not visualizing, it is best to set this to false) + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + computeSuccessAtEnd : boolean + Checks if we should assign nan or not if ends without converging (ie, for safety where we don't want to break early) + computeSafetyAtEnd : boolean + Checks if we should evaluate safety of the trial at the end (to avoid needing to do it later), supersedes computeSuccessAtEnd, which may be removed, as it also checks this. + numWarmStart : int (default=0) + Checks if we should run the solver a few times to compile first, and if so how many. Only does so on first trial. Currently only implemented for non-multiprocessing + + Returns + ------- + trialResultsDict : dict + dict containing: + physicalStateList : list + List of the (realized) physical states of the system + failureStateList : list + List of the (unchanging) true failure state + beliefList : list + List of the beliefs at each time step (time steps determined by nExperimentSteps and dt, which is currently set in the system model) + rewardList : list + List of the rewards at each time step + actionList : list + List of the actions taken at each time step + treeList: list + List of the tree data at each time step. Each element is a tuple with the nodeList and the valuesRewardsVisitsArray for the tree + initialFailureParticles : array, shape(nMaxFailureParticles,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + + """ + physicalStateList,failureStateList,beliefList,actionList,observationList,treeList,rewards = setUpTrialOutputs(initializationDict,nExperimentSteps,saveTreeFlag) + + #Warm start by running the solver a few times to compile everything + if numWarmStart: + print("Warm start") + for dummyIndex in range(numWarmStart): + #Still use rng keys so burn ins are different + rngKey, rngSubKey = jaxRandom.split(rngKey) + solverF(beliefList[-1],solverParametersTuple,initialFailureParticles,systemF,systemParametersTuple,rewardF,estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngSubKey) + print("Warm start done") + + #Get time for logging later + wctStartTime = time.time() + success = 0 #Will be set to 1 if returns the correct failure + currentFailureParticles = initialFailureParticles #Updated by general fault model + + #for timeStep in tqdm(range(nExperimentSteps)): #Used to eyeball wall clock time + for timeStep in range(nExperimentSteps): + #Reaches here + #Compute action to take + rngKey, rngSubKey = jaxRandom.split(rngKey) #Keys are consumed on use, so keep splitting rngKey first to avoid consumption + nextAction,tree = solverF(beliefList[-1],solverParametersTuple,currentFailureParticles,systemF,systemParametersTuple,rewardF,estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngSubKey) + + #Simulate system forward + rngKey, rngSubKey = jaxRandom.split(rngKey) #Keys are consumed on use, so keep splitting rngKey first to avoid consumption + nextPhysicalState,nextFailureState,nextObservation = systemF(physicalStateList[-1],failureStateList[-1],nextAction,rngSubKey,systemParametersTuple) + #print("Ground Truth, state, failure, obs") + #print(nextPhysicalState,nextFailureState,nextObservation) + #err, some reach this, not all? + #Update beliefs + nextBelief = estimatorF(nextAction,nextObservation,beliefList[-1],currentFailureParticles,systemF,systemParametersTuple,physicalStateSubEstimatorF,physicalStateJacobianF) + + #NOTE: This is a future feature that is not used yet + #Check resample condition for general faults (hybrid case means resample could be none. Still thinking about best way here) + if generalFaultDict and generalFaultDict["failureParticleResampleCheckF"] and generalFaultDict["failureParticleResampleCheckF"](nextBelief): + #Resample based on given function + sampleRngKey, rngSubKey = jaxRandom.split(sampleRngKey) + #Here we expect the tuple to have the current failure particles included + actionHistory = tuple(actionList) + (nextAction,) + observationHistory = tuple(observationList) + (nextObservation,) + #print(actionHistory) + #print(observationHistory) + print(timeStep) + nextBelief = generalFaultDict["failureParticleResampleF"](nextBelief+(currentFailureParticles,),timeStep,estimatorF,beliefList[0],actionHistory, + observationHistory, systemF,systemParametersTuple,physicalStateSubEstimatorF,physicalStateJacobianF,rngSubKey) + currentFailureParticles = nextBelief[2] + #Does not reach here + #Evaluate Reward, we now allow for probabilistic rewards (usually b/ of safety constraint) + rngKey, rngSubKey = jaxRandom.split(rngKey) + appendTimeStepToTrialResults(physicalStateList,nextPhysicalState,failureStateList,nextFailureState,beliefList,nextBelief, + rewards,rewardF,rngSubKey,actionList,nextAction,observationList,nextObservation,timeStep,saveTreeFlag,tree,treeList) + + #We will let it break here, if want to use jit, have to get more creative? + #Check if reward over threshold + if rewards[timeStep+1] > diagnosisThreshold: + success = terminateEarly(nextBelief,currentFailureParticles,nextFailureState,timeStep,nExperimentSteps,rewards,saveTreeFlag,treeList) + break + #Check for filter divergence (can do it here, as will fix it before the next action) + if jnp.isnan(rewards[timeStep+1]) and filterDivergenceHandlingMethod: + handleFilterDivergence(filterDivergenceHandlingMethod,rewards,timeStep,diagnosisThreshold,beliefList) + + #Set success to nan if we don't converge. Rationale here is this allows us to check for this later, and then count as a failure (or not) as desired. + #In python else is only entered if we DON'T break + else: + if computeSuccessAtEnd and not computeSafetyAtEnd: #Avoid computing twice + diagnosis = diagnoseFailure(nextBelief,currentFailureParticles) + #If the last reward is nan, we diverged so this is always a failure + if not jnp.isnan(rewards[-1]) and jnp.all(diagnosis == nextFailureState): + success = 1 + else: + success = jnp.nan + + #If we want to give credit for being right but not confident, use this instead + ##In python else is only entered if we DON'T break. We want to check for success if we time out still! (useful in the case of safety where we can't break early) + #else: + # diagnosis = diagnoseFailure(nextBelief,currentFailureParticles) + # if jnp.all(diagnosis == nextFailureState): + # success = 1 + # else: + # success = jnp.nan + + #return results! + return makeTrialResultDict(physicalStateList,failureStateList,beliefList,rewards,actionList,initialFailureParticles,success,timeStep,wctStartTime,saveTreeFlag,treeList,computeSafetyAtEnd) + +def runNetworkTrial(initializationDict,nSimulationsPerTree,nExperimentSteps,systemF,systemParametersTuple,solverF,solverParametersTuple,estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,rewardF,initialFailureParticles, generalFaultDict, diagnosisThreshold,filterDivergenceHandlingMethod, + saveTreeFlag, rngKey, computeSuccessAtEnd=False,computeSafetyAtEnd=True, numWarmStart=0): # pylint: disable=unused-argument + """ + Networked systems runner + """ + futureCapability = "The distributed version of s-FEAST is intended future work, but is not currently implemented" + raise NotImplementedError(futureCapability) + +def handleFilterDivergence(filterDivergenceHandlingMethod,rewards,timeStep,diagnosisThreshold,beliefList): + """ + Method to handle filter divergence if needed. + """ + failureWeightsIdx = 0 + filtersIdx = 1 + if filterDivergenceHandlingMethod == "acceptDiagnosisBeforeNan": + #Check if we are above the threshold we set for accepting the diagnosis if needed (otherwise, let filter diverge, we failed) + if rewards[timeStep] > diagnosisThreshold-1: + print(f"Over confidence threshold {diagnosisThreshold-1}") + #Set *failure* belief to our diagnosis + diagnosisIdx = jnp.argmax(beliefList[timeStep][failureWeightsIdx]) + diagnosis = jnp.zeros(len(beliefList[timeStep][failureWeightsIdx])) + diagnosis = diagnosis.at[diagnosisIdx].set(1) + beliefList[timeStep+1] = (diagnosis,beliefList[timeStep+1][filtersIdx]) #Note this won't handle general fault particles, TODO + else: + print(f"Under confidence threshold {diagnosisThreshold-1}, will diverge") + else: + unrecognizedFilterDivergenceHandlingMethod = f"The filter divergence handling method {filterDivergenceHandlingMethod} is not recognized or implemented." + raise ValueError(unrecognizedFilterDivergenceHandlingMethod) + +def setUpTrialOutputs(initializationDict,nExperimentSteps,saveTreeFlag): + """ + Helper method to set up trials for running + """ + + #Initialize data to be returned + physicalStateList = [initializationDict["physicalState"]] + failureStateList = [initializationDict["failureState"]] + beliefList = [initializationDict["beliefTuple"]] + actionList = [initializationDict["firstAction"]] + observationList = [initializationDict["firstObservation"]] + #breaks if using solver w/0 action list like cbf: actionList = [solverParametersTuple[idxAvailableActionList][idxNullAction]] #First action in the list of available actions is null action + treeList = None + if saveTreeFlag: #Only save tree if told to + treeList = [] #We will add None to end, b/ tree thinkings about next action from current state + + #we'll use onp arrays for flexibility and to make processing later easier for the data we want to average + rewards = onp.zeros(nExperimentSteps+1) + rewards[0] = initializationDict["reward"] + + return physicalStateList,failureStateList,beliefList,actionList,observationList,treeList,rewards + +def appendTimeStepToTrialResults(physicalStateList,nextPhysicalState,failureStateList,nextFailureState,beliefList,nextBelief, + rewards,rewardF,rngKey,actionList,nextAction,observationList,nextObservation,timeStep,saveTreeFlag,tree,treeList): + """ + Helper function that appends all the data for a time step to the trial results + """ + + #Evaluate Reward, we now allow for probabilistic rewards (usually b/ of safety constraint) + nextReward = rewardF(nextBelief,rngKey) + + #Add everything to our data lists + physicalStateList.append(nextPhysicalState) + failureStateList.append(nextFailureState) #Potential optimization: only save this once? Doesn't change by assumption. Leaving since it is small compared to rest of data + beliefList.append(nextBelief) + rewards[timeStep+1] = nextReward + actionList.append(nextAction) + observationList.append(nextObservation) + #Only save tree if told to, as it is very large compared to the other data + if saveTreeFlag: + treeList.append(tree) + +#Future TODO: Need to adjust for general fault with changing failure particles, currently not supported +def terminateEarly(nextBelief,currentFailureParticles,nextFailureState,timeStep,nExperimentSteps,rewards,saveTreeFlag,treeList): + """ + Helper method handling early termination. + """ + #Now add None to the end of the trees (if saving the tree) + if saveTreeFlag: #Only save tree if told to + treeList.append(None) + diagnosis = diagnoseFailure(nextBelief,currentFailureParticles) #Future TODO: Need to adjust for general fault with changing failure particles + if jnp.all(diagnosis == nextFailureState): + success = 1 + else: + success = 0 + + # Check if we terminated early, get extra reward if so. NOTE: it gets the extra reward EVEN if the answer is wrong. + # The reasoning here is that the POMDP has no way of knowing "correctness" and the POMDP reward is only on convergence, so this should only be on convergence + if timeStep < nExperimentSteps - 1: + rewards[timeStep+2:] = 1 #Set to max reward + return success + +#Can't jit while there is a if statement. +def initializeTrial(numState, numAct, numSen,providedFailure,numNFailures,nMaxFailureParticles,beliefInitializationF,rewardF,generalFaultDict,rngKey,# pylint: disable=too-many-branches + initialState=None,initialUncertainty=.001,numAgents=1): + """ + Method that creates the initial physical and failure state, beliefTuple and reward. Also generates the possible failures. + Both true and possible failures are randomized, currently nothing else is. + + Parameters + ---------- + numState : int + Number of states + numAct : int + Number of actuators + numSen : int + Number of sensors + providedFailure : array, shape(numAct+numSen) (default=None) + Provided failure (if any) to have each trial use + numNFailures : array, shape(nMaxComponentFailures+1) + Number of failure combinations for each level of failed components + nMaxFailureParticles : int + Maximum number of possible failures to consider at once. If larger than the number of possible unique failures, all possibilities are considered + beliefInitializationF : function + Function that creates the initial belief + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Physical state estimator for use with the marginal filter, if any + rewardF : function + Reward function to evaluate the beliefs with + generalFaultDict : dict + If we are using a general fault model this is a dictionary with the following values. Otherwise it is None + failureParticleResampleF : function + Function that resamples the particles when needed + failureParticleResampleCheckF : function + Function that determines if resampling is needed + failureParticleInitializationF : function + Function that creates the initial failure particles + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + initialState : array, shape(numState) (default=None) + Initial state if any provided. If not, defaults to origin. + initialUncertainty : float (default=.001) + Initial state uncertainty magnitude, if any + numAgents : int (default=1) + How many agents are present (distinguishes single from multi-agent which is currently not supported) + + Returns + ------- + initializationDict : dict + Initial physical state, failure state, beliefTuple, reward, firstAction (=0), firstObservation (=0) + initialFailureParticles : array, shape(nMaxFailureParticles,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + """ + + #enumerated fault case. hybridFaultFlag is checked again later. This is written so if the first condition is true (generalFaultDict is None) + #Then hybridFaultFlag is None or False. If the second condition is true (necessitates first is false), then hybridFaultFlag is True + #If both are false, hybridFaultFlag is False. + if (hybridFaultFlag := generalFaultDict) is None or (hybridFaultFlag := generalFaultDict["failureParticleInitializationF"] == binaryToDegradationFaults): #pylint: disable=comparison-with-callable + #Generate possible failures (THIS ONLY APPLIES TO ENUMERATED BINARY FAULTS!) + ######################################### + #First compute total possible number + nFailureCombs = jnp.sum(numNFailures) + rngKey,rngSubKey = jaxRandom.split(rngKey) + if nMaxFailureParticles < nFailureCombs: + #Really slow when there is a large number of possible failures, so will just randomly generate if too large (and assume repeats odds are low so regen easily) + if nFailureCombs > 10000: + while True: + initialFailureParticlesIdxes = jaxRandom.randint(rngSubKey, minval=0, maxval=nFailureCombs, shape=(nMaxFailureParticles,)) + dummyVals, counts = jnp.unique(initialFailureParticlesIdxes,return_counts=True) + if jnp.max(counts) == 1: + break + else: + #Returns un ordered! So don't need to randomly pick from these, can always take the first. + initialFailureParticlesIdxes = jaxRandom.choice(rngSubKey, nFailureCombs, (nMaxFailureParticles,),replace=False) + else: + #Need to scramble, because taking first idex as true failure + initialFailureParticlesIdxes = jaxRandom.permutation(rngSubKey, jnp.arange(nFailureCombs,dtype=int)) + #Now generate the possible failures + initialFailureParticles = generateAllPossibleFailures(numAct,numSen,numNFailures,initialFailureParticlesIdxes,numAgents) + + #Only validate single agent failures for now + if numAgents==1: + #Validate that the system is solvable (ie, no double sensing failure, as then we can't solve at all) + for iFailure,possibleFailure in enumerate(initialFailureParticles): + #Check if not valid and update NOTE: can get duplicate failures, not observed to be an issue + newFailureIfNeeded = checkFailureIsValid(possibleFailure,numSen) + if newFailureIfNeeded is not None: + initialFailureParticles = initialFailureParticles.at[iFailure].set(newFailureIfNeeded) + + + #General Fault Case + else: + #Start with totally general case where every component could be partially broken, determined by failureParticleInitializationF, which + #could be biased to nominal components. + #Future TODO: Configure to use nMaxComponentFailures? + rngKey,rngSubKey = jaxRandom.split(rngKey) + #nMaxFailureParticles is the number of particles we start with. numFallibleComponents = numAct+numSen + initialFailureParticles = generalFaultDict["failureParticleInitializationF"](nMaxFailureParticles, numAct,numSen,rngSubKey,providedFailure) + + + #Add in the providedFailure if we didn't generate it (replaces first failure always, since this is random, this is fine) + #In either case, always select the first failure (no loss of generality), unless general fault with the initial failure not in the failure particles + #NOTE: (WARNING) if we ever try to learn, need to be careful not to learn that the first failure is always the answer + if providedFailure is not None: + failureState = providedFailure + + if generalFaultDict is None or generalFaultDict["trueFaultInInitialParticlesFlag"]: + #This checks if any array matches (will fail in general case almost certainly, and almost always in 0/1) + #If it does, then we already have a particle for the general case and shouldn't add a duplicate + if not jnp.any(jnp.all(providedFailure == initialFailureParticles,axis=1)): + initialFailureParticles = initialFailureParticles.at[0].set(providedFailure) + #We're done, as now true fault is in the initial particle set + #In the general fault case where we don't want the initial fault in the particle set, we're done + + #Incase with no provided failure where we want the true fault in the initial particle set, this is all we need to do. + elif generalFaultDict is None or generalFaultDict["trueFaultInInitialParticlesFlag"]: + failureState = initialFailureParticles[0] + + #Finally, in this case, in general fault not in initial particle set + else: + #Fault isn't known in general! + rngKey,rngSubKey = jaxRandom.split(rngKey) + failureState = generalFaultDict["failureParticleInitializationF"](2, numAct+numSen,rngSubKey)[0] + + #Finally, check if 0/1 true fault or degradation is present + if hybridFaultFlag: + rngKey,rngSubKey = jaxRandom.split(rngKey) + failureState = generalFaultDict["failureParticleInitializationF"](failureState,rngSubKey) + + + + #Create Initial state + ##################################### + initializationDict = {} + + #Set default physical state if one isn't provided + if initialState is not None: + if len(initialState) != numState: + inconsistentInitialState = f"The provided initial state ({initialState}) is inconsistent with the expected number of states ({numState})" + raise ValueError(inconsistentInitialState) + initializationDict["physicalState"] = initialState + else: + initializationDict["physicalState"] = jnp.zeros(numState) + + initializationDict["failureState"] = failureState + + #Create Belief #Future addition TODO, add ability for adversarial or other initial priors + #print(initializationDict["physicalState"]) + initializationDict["beliefTuple"] = beliefInitializationF(initializationDict["physicalState"],initialFailureParticles,initialUncertainty) + + #Generate Initial reward, we now allow for probabilistic rewards (usually b/ of safety constraint). + # Don't need to split because last use of this key + initializationDict["reward"] = rewardF(initializationDict["beliefTuple"],rngKey) + + initializationDict["firstAction"] = jnp.zeros(numAct) + initializationDict["firstObservation"] = jnp.zeros(numSen) + + return initializationDict, initialFailureParticles + +def visualize(experimentParamsDict,saveDirectoryPath): + """ + Visualizes + + Parameters + ---------- + experimentParams : dict + Relevant parameters are: + nSimulationsPerTreeList : list, len(numTrials) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + dt : float + The time between time steps of the experiment + solverNamesList: list + List of names of solvers, for data logging + networkFlag : bool + Whether we are in a distributed network or not + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + """ + + outputFilePath = os.path.join(saveDirectoryPath,"render.pdf") + if experimentParamsDict["networkFlag"]: + futureCapability = "The distributed version of s-FEAST is intended future work, but is not currently implemented" + raise NotImplementedError(futureCapability) + else: + visualizeFirstTrajectory(saveDirectoryPath,experimentParamsDict,outputFilePath) + +def getCommandLineArgs(): + """ + Helper function to parse command line arguments + """ + + #Add --noSave argument for testing code w/o potentially overwriting data + parser = argparse.ArgumentParser(description='Generate and process data for given trial configurations') + parser.add_argument('configFilePath',help='Relative (or absolute) path to the config file') + parser.add_argument('--noSave', dest='save', action='store_false', default=True, + help='Flag to disable saving data') + commandLineArgs = parser.parse_args() + return commandLineArgs + +def setUpMultiPRocessing(): + """ + Helper function to setup multiprocessing + """ + #JAX is internally threaded, so if we do any multi-processing, need to set it to spawn new processes + mp.set_start_method('forkserver') + ctx._force_start_method('forkserver') #Recommended by JAX, but should look at a better way in the future. pylint: disable=protected-access + + +#Entry point to code, called by "python pipeline.py" +if __name__ == '__main__': + COMMAND_LINE_ARGS_INPUT = getCommandLineArgs() + setUpMultiPRocessing() + #Debug turn off jit + #with jax.disable_jit(): + # with jax.default_device(jax.devices("cpu")[0]): + # jax.config.update("jax_debug_nans", True) + # main(COMMAND_LINE_ARGS_INPUT.configFilePath,COMMAND_LINE_ARGS_INPUT.save) + #Context manager that disables GPU (faster in current s-FEAST algorithm) This is the proper way to do this now, setting GPU to be invisible raises an error + with jax.default_device(jax.devices("cpu")[0]): + main(COMMAND_LINE_ARGS_INPUT.configFilePath,COMMAND_LINE_ARGS_INPUT.save) diff --git a/failurePy/realTimePipeline.py b/failurePy/realTimePipeline.py new file mode 100644 index 0000000..f9009e8 --- /dev/null +++ b/failurePy/realTimePipeline.py @@ -0,0 +1,473 @@ +""" +Main file for setting up, running, and logging data for experiments simulated to run in real-time. +Similar to pipeline, and future work is to reduce/eliminate redundancy, for now ignoring. + +Currently only supports binary faults! + +Imports as much as possible from pipeline.py +""" +# pylint: disable=duplicate-code +import os +import time +import inspect + +#Multiprocessing components to make things run faster (implement later) +#from itertools import repeat +#import multiprocessing as mp +import numpy as onp #Following Jax conventions + +import jax.numpy as jnp +#import jax +#from functools import partial +from jax import random as jaxRandom +from tqdm import tqdm + +#failurePy imports, these need to be installed by pip to work +from failurePy.load.yamlLoader import loadExperimentParamsFromYaml +from failurePy.load.yamlHardwareLoader import loadRealTimeParams +from failurePy.load.yamlLoaderUtilityMethods import raiseIncompatibleSpecifications +from failurePy.utility.saving import checkSaveDirectoryPathMakeIfNeeded, processDataAverages, checkIfDataExists,setUpDataOutput,saveTrialResult,makeTrialResultDict,getTrialDataPath #,saveMetaData +from failurePy.solvers.randomPolicy import solveForNextAction as randomPolicyF +#For determining system type +from failurePy.pipeline import visualize, initializeTrial, getCommandLineArgs, setUpMultiPRocessing,terminateEarly +from failurePy.utility.pipelineHelperMethods import getExperimentParameters, diagnoseFailure + + +def main(configFilePath, saveData=True, visualizeFirstTrajectoryFlag=True): + """ + Main method of the code sets up, runs, logs and cleans up experiment + + Parameters + ---------- + configFilePath : String + Relative path to the config file for the experiment + saveData : boolean (default=True) + Over-rides data saving behavior when False to not write out any data, avoiding potential overwrite when testing or profiling + visualizeFirstTrajectory : boolean (default=True) + Whether to visualize the first experiment result or not + """ + + #Cuda not installed on Jimmy desktop + #Toggle CUDA (GPU) off + os.environ['CUDA_VISIBLE_DEVICES'] = '-1' + + #First load in the experiment parameters. These determine the save path, so this is returned as well + experimentParamsDict, saveDirectoryPath = loadExperimentParamsFromYaml(configFilePath) #We won't use extra data here pylint: disable=unbalanced-tuple-unpacking + + #Make absolute save directory if it isn't already + if not saveDirectoryPath[0] == "/": + saveDirectoryPath = os.path.join(os.getcwd(),saveDirectoryPath) + + #Check for compatibility, real-time solver is different + checkRealTimeSolverCompatibility(experimentParamsDict) + + #Get initial action (if any). Loading here instead of in loadExperimentParams as this is only for real-time implementations + initialAction = loadRealTimeParams(configFilePath) + + #Check if save directory is clean + checkSaveDirectoryPathMakeIfNeeded(saveDirectoryPath,experimentParamsDict) + + #Setup data output + setUpDataOutput(saveDirectoryPath, experimentParamsDict, configFilePath) + + #Next run experiment + runExperimentsAndLog(experimentParamsDict,initialAction,saveDirectoryPath,saveData) + + #Log data (potentially do something with a return code at a later date?) + processDataAverages(saveDirectoryPath,experimentParamsDict) + + if visualizeFirstTrajectoryFlag: + #Clean up / display + visualize(experimentParamsDict,saveDirectoryPath) + +def runExperimentsAndLog(experimentParamsDict,initialAction,saveDirectoryPath,saveData=True): + """ + Method that contains the main experiment loop. + To avoid memory leaks, we log the results of each trial as they are produced + + Parameters + ---------- + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + The contents should be as follows: + nSimulationsPerTreeList : list, len(numTrials) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + dt : float + The time between time steps of the experiment + nExperimentSteps : int + How many time steps are in the experiment + nTrialsPerPoint : int + The number of repeated trials per configuration. + nMaxComponentFailures : int + Maximum number of simultaneous failures of components that can be considered + nMaxPossibleFailures : int + Maximum number of possible failures to consider. If larger than the number of possible unique failures, all possibilities are considered + providedFailure : array, shape(numAct+numSen) (default=None) + Provided failure (if any) to have each trial use + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + solverFList : list + List of solver functions to try + solverParametersTuplesList : list + List of tuples of solver parameters. Included action list, failure scenarios + solverNamesList: list + List of names of solvers, for data logging + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Physical state estimator for use with the marginal filter, if any + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + beliefInitializationF : function + Function that creates the initial belief + rewardF : function + Reward function to evaluate the beliefs with + rngKeysOffset : int + Offset to the initial PRNG used in generating the initial failure states and randomness in the trials. + This is added to the trial number to allow for different trials to be preformed + multiprocessingFlag : int + Wether to use multi-processing (if number is set other than 0) or not (if False/0) + saveTreeFlag : boolean + Whether to save the tree or not (it can be quite large, so if not visualizing, it is best to set this to false) + numWarmStart : int (default=0) + Checks if we should run the solver a few times to compile first, and if so how many. Only does so on first trial. Currently only implemented for non-multiprocessing + initialAction : array, len(numAct) + Initial action to take (zeros if none provided) + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + Now using pickle to save the data in it's original dictionary format, rather than creating directories for each data type saved + saveData : boolean (default=True) + Over-rides data saving behavior when False to not write out any data, avoiding potential overwrite when testing or profiling + """ + + #Get basic parameters of the system + numState, numAct, numSen, numNFailures, numWarmStart, numAgents = getExperimentParameters(experimentParamsDict) + + if numAgents > 1: + realtimeMultiAgent = "Real time distributed systems are not currently supported" + raise NotImplementedError(realtimeMultiAgent) + + #Validate initial action + if initialAction is not None: + if len(initialAction) != numAct: + raiseIncompatibleSpecifications(f"initialAction: {initialAction}",f"numAct: {numAct}") + else: + initialAction = jnp.zeros(numAct) + + #Loop over solvers + for iSolver in range(len(experimentParamsDict["solverFList"])): + + #Loop over nSimulationsPerTrees + for nSimulationsPerTree in experimentParamsDict["nSimulationsPerTreeList"]: + + #Check if we're multiprocessing (Speed up for parallelizing over solvers and experiments seems minimal) + #This relies on the processes only being spawned at opening of pool, so we don't need to recompile every time, otherwise its a major slow down. + if experimentParamsDict["multiprocessingFlag"]: + raise NotImplementedError("Not Implemented for real time pipeline yet") + + #else: #Will implement multiprocessing later + #Loop over trials + for jTrial in tqdm(range(experimentParamsDict["nTrialsPerPoint"])): + #Only warm start first trial + if numWarmStart and jTrial != 0: + warmStart=0 + else: + warmStart=numWarmStart + #Now allowing to have data already existing + if experimentParamsDict["mergeData"] and checkIfDataExists(getTrialDataPath(saveDirectoryPath, experimentParamsDict["solverNamesList"][iSolver], nSimulationsPerTree, jTrial)): + continue #Don't overwrite + initializeRunAndSaveTrial(experimentParamsDict,initialAction,numState, numAct, numSen,numNFailures,saveDirectoryPath,nSimulationsPerTree, + iSolver,jTrial+experimentParamsDict["rngKeysOffset"],saveData,numWarmStart=warmStart) + + +#def initializeRunAndSaveTrialWrapper(args): +# """ +# Wrapper of initializeRunAndSaveTrial that allows for all the args to be passed as one iterable for multiprocessing +# """ +# +# initializeRunAndSaveTrial(*args) + + +def initializeRunAndSaveTrial(experimentParamsDict,initialAction,numState, numAct, numSen,numNFailures,saveDirectoryPath,nSimulationsPerTree,iSolver,rngSeed, + saveData=True,numWarmStart=0): + """ + Helper method that performs the initialize, run and saving for each trial, to enable parallelization + + Parameters + ---------- + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + initialAction : array, len(numAct) + Initial action to take (zeros if none provided) + numState : int + Number of states + numAct : int + Number of actuators + numSen : int + Number of sensors + numNFailures : array, shape(nMaxComponentFailures+1) + Number of failure combinations for each level of failed components + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + iSolver : int + Index of the solver being run + rngSeed : int + Index of the trial being run (plus offset) + saveData : boolean (default=True) + Over-rides data saving behavior when False to not write out any data, avoiding potential overwrite when testing or profiling + numWarmStart : int (default=0) + Checks if we should run the solver a few times to compile first, and if so how many. Only does so on first trial. Currently only implemented for non-multiprocessing + """ + + #Set random policy whenever nSimulationsPerTree = 0 + if nSimulationsPerTree == 0: + solverF = randomPolicyF + else: + solverF = experimentParamsDict["solverFList"][iSolver] + + #Make initial rngKey and split + rngKey = jaxRandom.PRNGKey(rngSeed) + rngKey,rngSubKey = jaxRandom.split(rngKey) + initializationDict, possibleFailures = initializeTrial(numState, numAct, numSen, + experimentParamsDict["providedFailure"],numNFailures, + experimentParamsDict["nMaxPossibleFailures"],experimentParamsDict["beliefInitializationF"], + experimentParamsDict["rewardF"], + None, #No generalFualt dict + rngSubKey,initialState=experimentParamsDict["initialState"]) + + initializationDict["initialAction"] = initialAction + + #Run trial + trialResultDict = runTrial(initializationDict,nSimulationsPerTree,experimentParamsDict["nExperimentSteps"], + experimentParamsDict["systemF"],experimentParamsDict["systemParametersTuple"], + solverF,experimentParamsDict["solverParametersTuplesList"][iSolver],#Get the list of solver params corresponding to this solver + experimentParamsDict["estimatorF"],experimentParamsDict["physicalStateSubEstimatorF"],experimentParamsDict["physicalStateJacobianF"], + experimentParamsDict["physicalStateSubEstimatorSampleF"],experimentParamsDict["rewardF"],possibleFailures, + experimentParamsDict["diagnosisThreshold"], experimentParamsDict["saveTreeFlag"], rngKey, numWarmStart=numWarmStart) #pass in PRNG key for this trial + #Future TODO: make computeSuccessAtEnd configurable! + + #Save this result directly (if turned on) + if saveData: + saveTrialResult(saveDirectoryPath, experimentParamsDict["solverNamesList"][iSolver], nSimulationsPerTree, rngSeed, trialResultDict) + + +#Add leap frogging actions +def runTrial(initializationDict,nSimulationsPerTree,nExperimentSteps,systemF,systemParametersTuple,solverF,solverParametersTuple,estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,rewardF,possibleFailures, diagnosisThreshold, + saveTreeFlag, rngKey, computeSuccessAtEnd=False, numWarmStart=0): # pylint: disable too-many-branches + """ + Method that runs one trial of a given system and solver, from given initialization. + Runs in simulated real-time, so plans next action while current action is running. + + Parameters + ---------- + initializationDict : dict + Initial physical state, failure state, beliefTuple, reward + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + nExperimentSteps : int + How many time steps are in the experiment + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + solverF : function + Solver function to select next action with + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Physical state estimator for use with the marginal filter, if any + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + rewardF : function + Reward function to evaluate the beliefs with + solverParametersTuple : tuple + List of solver parameters needed. Contents are: + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action + discretization : float + Discretization level or scheme + maxSimulationTime : float + Max simulation time (can be infinite). NOTE: Currently implemented by breaking loop after EXCEEDING time, NOT a hard cap + explorationParameter : float + Weighting on exploration vs. exploitation + nMaxDepth : int + Max depth of the tree + discountFactor : float + Discount on future rewards, should be in range [0,1] + possibleFailures : array, shape(nMaxPossibleFailures,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + diagnosisThreshold : float + Level of the reward to consider high enough to return an answer. + saveTreeFlag : boolean + Whether to save the tree or not (it can be quite large, so if not visualizing, it is best to set this to false) + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + computeSuccessAtEnd : boolean + Checks if we should assign nan or not if ends without converging (ie, for safety where we don't want to break early) + numWarmStart : int (default=0) + Checks if we should run the solver a few times to compile first, and if so how many. Only does so on first trial. Currently only implemented for non-multiprocessing + + Returns + ------- + trialResultsDict : dict + dict containing: + physicalStateList : list + List of the (realized) physical states of the system + failureStateList : list + List of the (unchanging) true failure state + beliefList : list + List of the beliefs at each time step (time steps determined by nExperimentSteps and dt, which is currently set in the system model) + rewardList : list + List of the rewards at each time step + actionList : list + List of the actions taken at each time step + treeList: list + List of the tree data at each time step. Each element is a tuple with the nodeList and the valuesRewardsVisitsArray for the tree + possibleFailures : array, shape(nMaxPossibleFailures,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + + """ + + #Explicitly define indexes of parameters we'll get later for clarity + idxAvailableActionList = 0 + idxNullAction = 0 + + #Initialize data to be returned + physicalStateList = [initializationDict["physicalState"]] + failureStateList = [initializationDict["failureState"]] + beliefList = [initializationDict["beliefTuple"]] + actionList = [initializationDict["initialAction"]] #Now can have a pre specified action + treeList = None #Only save tree if told to + if saveTreeFlag: + treeList = [] #We will add None to end, b/ tree thinkings about next action from current state + + #we'll use onp arrays for flexibility and to make processing later easier for the data we want to average + rewards = onp.zeros(nExperimentSteps+1) + rewards[0] = initializationDict["reward"] + + + #Warm start by running the solver a few times to compile everything + if numWarmStart: + print("Warm start") + warmStartSolverParametersTuple = solverParametersTuple[0:2] + (jnp.inf,) + solverParametersTuple[3:] + for dummyIndex in range(numWarmStart): + #Still use rng keys so burn ins are different + rngKey, rngSubKey = jaxRandom.split(rngKey) + #Set max sim time to inf for warm starts + solverF(beliefList[-1],warmStartSolverParametersTuple,possibleFailures,systemF,systemParametersTuple,rewardF,estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree, + rngKey,currentAction=actionList[-1]) + print("Warm start done") + + #Get time for logging later + wctStartTime = time.time() + success = 0 #Will be set to 1 if returns the correct failure + #for timeStep in tqdm(range(nExperimentSteps)): #Used to eyeball wall clock time + for timeStep in range(nExperimentSteps): + #Compute NEXT action to take + rngKey, rngSubKey = jaxRandom.split(rngKey) #Keys are consumed on use, so keep splitting rngKey first to avoid consumption + nextAction,tree = solverF(beliefList[-1],solverParametersTuple,possibleFailures,systemF,systemParametersTuple,rewardF,estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree, + rngSubKey,currentAction=actionList[-1]) + + #Simulate system forward using CURRENT action + rngKey, rngSubKey = jaxRandom.split(rngKey) #Keys are consumed on use, so keep splitting rngKey first to avoid consumption + nextPhysicalState,nextFailureState,nextObservation = systemF(physicalStateList[-1],failureStateList[-1],actionList[-1],rngSubKey,systemParametersTuple) + #print("Ground Truth, state, failure, obs") + #print(nextPhysicalState,nextFailureState,nextObservation) + + #Update beliefs + nextBelief = estimatorF(actionList[-1],nextObservation,beliefList[-1],possibleFailures,systemF,systemParametersTuple,physicalStateSubEstimatorF,physicalStateJacobianF) + #Evaluate Reward, we now allow for probabilistic rewards (usually b/ of safety constraint) + rngKey, rngSubKey = jaxRandom.split(rngKey) + nextReward = rewardF(nextBelief,rngSubKey) + + #Add everything to our data lists + physicalStateList.append(nextPhysicalState) + failureStateList.append(nextFailureState) #Potential optimization: only save this once? Doesn't change by assumption. Leaving since it is small compared to rest of data + beliefList.append(nextBelief) + rewards[timeStep+1] = nextReward + if saveTreeFlag: #Only save tree if told to + treeList.append(tree) + + #We will let it break here, if want to use jit, have to get more creative? + #Check if reward over threshold + if nextReward > diagnosisThreshold: + success = terminateEarly(nextBelief,possibleFailures,nextFailureState,timeStep,nExperimentSteps,rewards,saveTreeFlag,treeList) + break + + #Didn't break, so need next action (if below iteration count, otherwise breaking anyways and will apply null action) + if timeStep+1 < nExperimentSteps: + #Save NEXT action to apply next time (it'll be the current action next loop) + actionList.append(nextAction) + + #Set success to nan if we don't converge. Rational here is this allows us to check for this later, and then count as a failure (or not) as desired. + #In python else is only entered if we DON'T break + else: + if computeSuccessAtEnd: + diagnosis = diagnoseFailure(nextBelief,possibleFailures) + if jnp.all(diagnosis == nextFailureState): + success = 1 + else: + success = jnp.nan + + #If we want to give credit for being right but not confident, use this instead + ##In python else is only entered if we DON'T break. We want to check for success if we time out still! (useful in the case of safety where we can't break early) + #else: + # diagnosis = diagnoseFailure(nextBelief,possibleFailures) + # if jnp.all(diagnosis == nextFailureState): + # success = 1 + # else: + # success = jnp.nan + + #Don't take the last action when we break, do nothing instead. + # (technically last computation is wasted, but on hardware this is accurate (won't know we don't need it before hand) and if we time out it's okay) + actionList.append(solverParametersTuple[idxAvailableActionList][idxNullAction]) + + #return results! + return makeTrialResultDict(physicalStateList,failureStateList,beliefList,rewards,actionList,possibleFailures,success,timeStep,wctStartTime,saveTreeFlag,treeList) + +def checkRealTimeSolverCompatibility(experimentParamsDict): + """ + Method that checks for known inconsistencies in the experimentParameters with real-time simulation + This method will be expanded as more inconsistencies are identified. + Raises error with inconsistent parameters when identified + + Parameters + ---------- + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + """ + + #Check solver is real-time, take in extra parameter + solverFList = experimentParamsDict["solverFList"] + for solverF in solverFList: + methodSignature = inspect.signature(solverF) + if not "currentAction" in methodSignature.parameters: + raiseIncompatibleSpecifications(str(solverF),"real-time simulation framework, as it does not accept a currentAction parameter.") + + +#Entry point to code, called by "python pipeline.py" +if __name__ == '__main__': + + COMMAND_LINE_ARGS_INPUT = getCommandLineArgs() + setUpMultiPRocessing() + + ##Debug turn off jit + #import jax + #with jax.disable_jit(): + # from jax.config import config + # config.update("jax_debug_nans", True) + # main(commandLineArgs.configFilePath,commandLineArgs.save) + + main(COMMAND_LINE_ARGS_INPUT.configFilePath,COMMAND_LINE_ARGS_INPUT.save) diff --git a/failurePy/rewards/__init__.py b/failurePy/rewards/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/failurePy/rewards/safetyConstraint.py b/failurePy/rewards/safetyConstraint.py new file mode 100644 index 0000000..9213716 --- /dev/null +++ b/failurePy/rewards/safetyConstraint.py @@ -0,0 +1,780 @@ +""" +Module that implements safety constraints as modifications for the tree reward function +""" +from functools import partial + +import jax +import jax.numpy as jnp +from jax import random as jaxRandom + +@partial(jax.jit, static_argnames=['rewardF','safetyFunctionEvaluationF']) +def safetyConstrainedReward(beliefTuple,rngKey,rewardF,safetyFunctionEvaluationF,safetyRewardR0): + """ + Takes in a belief and gives a reward unless it violates the safety constraint. + + Method used by s-FEAST in our paper + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness (for some safety constraints) + rewardF : function + Reward function that should accept a beliefTuple and an rngKey as arguments. + This reward should give positive rewards, as safety violations will return as 0 (no reward) + safetyFunctionEvaluationF : function + Safety constraint function that should accept a beliefTuple and an rngKey as arguments. + Should return a boolean value of True (1) if we are safe or False (0) if we violated the constraint + safetyRewardR0 : float + r0. Constant that guarantees any safe trajectory has a higher reward than any unsafe trajectory + + Returns + ------- + reward : float + Reward for how certain we are. Note this will always be 0-1 because + the belief distribution is a probability distribution + """ + + #Returns 0 if we violate the constraint, as safetyFunctionEvaluationF returns a boolean value + return safetyFunctionEvaluationF(beliefTuple,rngKey) * (safetyRewardR0 + (1-safetyRewardR0) * rewardF(beliefTuple)) #the rewardF under this will not be probabilistic + +def makeSafetyConstrainedReward(rewardF,safetyFunctionEvaluationF,nMaxDepth): + """ + Function factory to make probabilisticSafetyFunctionEvaluation functions. + We shouldn't run into late binding problems here, but I think this is easier to read + + Parameters + ---------- + rewardF : function + Reward function that should accept a beliefTuple and an rngKey as arguments. + This reward should give positive rewards, as safety violations will return as 0 (no reward) + safetyFunctionEvaluationF : function + Safety constraint function that should accept a beliefTuple and an rngKey as arguments. + Should return a boolean value of True (1) if we are safe or False (0) if we violated the constraint + nMaxDepth : int + Maximum depth of the tree. This is the horizon we need to be safe over (can't be safe over a longer horizon, as we don't search over it) + + Returns + ------- + safetyConstrainedRewardF : function + Wrapper around makeSafetyConstrainedReward with the specified rewardF,safetyConstraintF + """ + def safetyConstrainedRewardF(beliefTuple,rngKey): + safetyRewardR0 = nMaxDepth/(nMaxDepth+1) + return safetyConstrainedReward(beliefTuple,rngKey,rewardF,safetyFunctionEvaluationF,safetyRewardR0) + return safetyConstrainedRewardF + +@partial(jax.jit, static_argnames=['rewardF','safetyFunctionEvaluationF']) +def safetyPenalizedReward(beliefTuple,rngKey,rewardF,safetyFunctionEvaluationF,penalty=1): + """ + Takes in a belief and gives a reward unless it violates the safety constraint. + If the constraint is violated it also assigns a penalty + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness (for some safety constraints) + rewardF : function + Reward function that should accept a beliefTuple and an rngKey as arguments. + This reward should give positive rewards, as safety violations will return as 0 (no reward) + safetyFunctionEvaluationF : function + Safety constraint function that should accept a beliefTuple and an rngKey as arguments. + Should return a boolean value of True (1) if we are safe or False (0) if we violated the constraint + penalty : float (default=1) + This is how big the penalty to the reward is. + + Returns + ------- + reward : float + Reward for how certain we are. Note this will always be 0-1 because + the belief distribution is a probability distribution + """ + + safetyFlag = safetyFunctionEvaluationF(beliefTuple,rngKey) + + #Compute penalty (note it is zeroed out if the safeFlag return from safetyFunctionEvaluationF is 1) and return it instead of safetyFlag=0 + return -penalty * (1-safetyFlag) + safetyFlag * rewardF(beliefTuple) #the rewardF under this will not be probabilistic + +def makeSafetyPenalizedReward(rewardF,safetyFunctionEvaluationF,penalty=1): + """ + Function factory to make probabilisticSafetyFunctionEvaluation functions. + We shouldn't run into late binding problems here, but I think this is easier to read + + Parameters + ---------- + rewardF : function + Reward function that should accept a beliefTuple and an rngKey as arguments. + This reward should give positive rewards, as safety violations will return as 0 (no reward) + safetyFunctionEvaluationF : function + Safety constraint function that should accept a beliefTuple and an rngKey as arguments. + Should return a boolean value of True (1) if we are safe or False (0) if we violated the constraint + penalty : float (default=1) + This is how big the penalty to the reward is. + + Returns + ------- + safetyPenalizedRewardF : function + Wrapper around makeSafetyPenalizedReward with the specified rewardF,safetyConstraintF + """ + def safetyPenalizedRewardF(beliefTuple,rngKey): + return safetyPenalizedReward(beliefTuple,rngKey,rewardF,safetyFunctionEvaluationF,penalty) + return safetyPenalizedRewardF + +def filterMeansSafetyFunctionEvaluation(beliefTuple,rngKey,safetyFunctionF): + """ + Function that defines a safety constraint based on the means of the belief tuple filters. + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness (for some safety constraints) + safetyFunctionF : function + Function that represents the conditions the physical state must satisfy for safety. + Must accept a physical state as an input. + """ + raise NotImplementedError + +#Jitting: numSamples needs to be a static argument (prettySure) +@partial(jax.jit, static_argnames=['safetyFunctionF','physicalStateSubEstimatorSampleF','numSamples']) +def probabilisticAlphaSafetyFunctionEvaluation(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples=100,alpha=.95): + """ + Function that evaluates a safety constraint based using samples from the belief to determine if the belief is alpha safe. + At high number of samples, acts as "ground truth" of alpha-safety of a belief + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness (for some safety constraints) + safetyFunctionF : function + Function that represents the conditions the physical state must satisfy for safety. + Must accept a physical state as an input. + physicalStateSubEstimatorSampleF : function + Samples the physical state from the belief + numSamples : int (default=100) + Number of samples to be drawn + alpha : float (default) + Threshold for safety. ie samples must have % safety > alpha + + Returns + ------- + safeFlag : boolean + 1 if safety constraints satisfied, 0 if not + """ + + batchSafetyReturn = batchSampleSafetyHelperMethod(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples) + #Dealing with non-boolean returns, because Chebyshev uses non-boolean returns and we want to be compatible + #Negative return is safe! #Not used in our paper, we instead set to 0 in a different function + batchSafetyReturn = - jnp.sign(batchSafetyReturn) + + #Now determine if we are above the threshold (alpha) percentage of safe samples + safetyPercent = jnp.sum(batchSafetyReturn)/numSamples + safetyFlag = jnp.sign(safetyPercent-alpha) #Check if safetyPercent > alpha + #Deal with possibility of equality (okay) and sign being negative + safetyFlag = jnp.sign(.5*safetyFlag +.5) + + return safetyFlag + +def makeProbabilisticAlphaSafetyFunctionEvaluation(safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples=100,alpha=.95): + """ + Function factory to make probabilisticAlphaSafetyFunctionEvaluation functions. + We shouldn't run into late binding problems here, but I think this is easier to read + + Parameters + ---------- + safetyFunctionF : function + Function that represents the conditions the physical state must satisfy for safety. + Must accept a physical state as an input. + physicalStateSubEstimatorSampleF : function + Samples the physical state from the belief + numSamples : int (default=100) + Number of samples to be drawn + alpha : float (default) + Threshold for safety. ie samples must have % safety > alpha + + Returns + ------- + probabilisticSafetyFunctionEvaluationF : function + Wrapper around probabilisticSafetyFunctionEvaluation with the specified safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples + """ + def probabilisticAlphaSafetyFunctionEvaluationF(beliefTuple,rngKey): + return probabilisticAlphaSafetyFunctionEvaluation(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples,alpha) + return probabilisticAlphaSafetyFunctionEvaluationF + +#Jitting: numSamples needs to be a static argument (prettySure, actually not) +@partial(jax.jit, static_argnames=['safetyFunctionF','physicalStateSubEstimatorSampleF','numSamples']) +def probabilisticSafetyFunctionEvaluation(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples=100): + """ + Function that evaluates a safety constraint based using samples from the belief. + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness (for some safety constraints) + safetyFunctionF : function + Function that represents the conditions the physical state must satisfy for safety. + Must accept a physical state as an input. + physicalStateSubEstimatorSampleF : function + Samples the physical state from the belief + numSamples : int (default=100) + Number of samples that must successfully be drawn without violation + + Returns + ------- + safeFlag : boolean + 1 if safety constraints satisfied, 0 if not + """ + + batchSafetyReturn = batchSampleSafetyHelperMethod(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples) + + #Implicitly assuming that we are using the boolean safety function here + #If all pass, each safeFlag will still be 1. Any failure sets this to zero + return jnp.prod(batchSafetyReturn) + +def batchSampleSafetyHelperMethod(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples): + """ + Helper method that does the batch sampling for the sample based safety methods + """ + + #Check specified number of samples #vmapping this for speed ups (especially on compile side) >10x faster!! + #First create the keys for each sample + batchRngKeys = jaxRandom.split(rngKey,num=numSamples) + #vmap the helper function. Only rng keys change + batchSampleSafety = jax.vmap(probabilisticSafetyFunctionEvaluationVMapHelper, in_axes=[None,0,None,None]) + return batchSampleSafety(beliefTuple,batchRngKeys,safetyFunctionF,physicalStateSubEstimatorSampleF) + + + +def probabilisticSafetyFunctionEvaluationVMapHelper(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF): + """ + Helper function for parallelizing the loop in probabilisticSafetyFunctionEvaluation for faster compilation + """ + #Sample a state from the belief + failureWeightsIdx = 0 + filtersIdx = 1 + + #Pick failure from possible, weighted by current belief + rngKey,rngSubKey = jaxRandom.split(rngKey) #Make rngSubKey, as consumed on use + failureIdx = jaxRandom.choice(rngSubKey,len(beliefTuple[failureWeightsIdx]),p=beliefTuple[failureWeightsIdx]) + + #Now use the filter to sample x. Use rngKey here, as don't need to split it again + physicalStateSample = physicalStateSubEstimatorSampleF(beliefTuple[filtersIdx][failureIdx],rngKey) + + return safetyFunctionF(physicalStateSample) + +def makeProbabilisticSafetyFunctionEvaluation(safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples=100): + """ + Function factory to make probabilisticSafetyFunctionEvaluation functions. + We shouldn't run into late binding problems here, but I think this is easier to read + + Parameters + ---------- + safetyFunctionF : function + Function that represents the conditions the physical state must satisfy for safety. + Must accept a physical state as an input. + physicalStateSubEstimatorSampleF : function + Samples the physical state from the belief + numSamples : int (default=100) + Number of samples that must successfully be drawn without violation + + Returns + ------- + probabilisticSafetyFunctionEvaluationF : function + Wrapper around probabilisticSafetyFunctionEvaluation with the specified safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples + """ + def probabilisticSafetyFunctionEvaluationF(beliefTuple,rngKey): + return probabilisticSafetyFunctionEvaluation(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples) + return probabilisticSafetyFunctionEvaluationF + +@partial(jax.jit, static_argnames=['safetyFunctionF','physicalStateSubEstimatorSampleF','numSamples']) +def chebyshevIneqSafetyFunctionEvaluation(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples=100,allowableFailureChance=.05): + """ + Function that evaluates a safety constraint based using samples from the belief. Uses sample based Chebyshev inequality bound from Kaban 2012 + to place an upper bound on the chance of safety inequalities being violated + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness (for some safety constraints) + safetyFunctionF : function + Function that represents the conditions the physical state must satisfy for safety. + Must accept a physical state as an input. + For this method, using the worstCaseSafetyFunction will work best (enforced in function factory) + In the future other methods may be added, but they must all return strictly negative values when the function is safe, and positive otherwise + physicalStateSubEstimatorSampleF : function + Samples the physical state from the belief + numSamples : int (default=100) + Number of samples that must successfully be drawn without violation + allowableFailureChance : float (default=.05) + Maximum allowable failure chance (safety chance = 1-allowableFailureChance = alpha) + + Returns + ------- + safeFlag : boolean + 1 if safety condition satisfied, 0 if not + """ + + batchSafetyReturn = batchSampleSafetyHelperMethod(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples) + + #Now we need to compute the statistics to get the bound + + safetySampleMean = jnp.mean(batchSafetyReturn) #Note if this is not negative, we're already unsafe. + safetySampleVariance = jnp.var(batchSafetyReturn,ddof=1) #ddof =1 gives us 1/(N-1), which we needed for an unbiased estimate + + #We want to bound the probability of the safety function giving a positive (unsafe) return. + # To use Chebyshev, we need to represent this in terms of standard deviations from the mean + #Use definition of sample std from Kaban 2012 + safetySampleStd = jnp.sqrt((numSamples+1)/numSamples * safetySampleVariance) #We re-square later, but need this to check sampleStdsUntilUnsafe>=1 condition + #How many standard deviations until we're at 0? Note we're assuming safetySampleMean < 0. This we'll check for explicitly later when returning + sampleStdsUntilUnsafe = -safetySampleMean/safetySampleStd + + #ASSUMPTIONS: numSamples>=2 (enforced in function factory), sampleStdsUntilUnsafe>=1 + unsafeProbabilityBound = jnp.floor((numSamples+1)/numSamples * ((numSamples-1)/sampleStdsUntilUnsafe**2 +1)) / (numSamples+1) + + #Now we need to determine if unsafeProbabilityBound > allowableFailureChance or if sampleStdsUntilUnsafe < 1, as in either case our bound has failed + # unsafeProbabilityBound > allowableFailureChance + boundPassed = jnp.sign(allowableFailureChance - unsafeProbabilityBound) #This needs to be 1, not 0 or -1 + # sampleStdsUntilUnsafe < 1 + assumptionsPassed = jnp.sign(sampleStdsUntilUnsafe - 1) #This is okay to be zero + #Check all three conditions passed. boundPassed != -1, boundPassed != 0, assumptionsPassed != -1 + safeFlag = (.5 + .5*boundPassed) * jnp.abs(boundPassed) * (.5 + .5*assumptionsPassed) + + return safeFlag + +def makeChebyshevIneqSafetyFunctionEvaluation(safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples=100,allowableFailureChance=.05): + """ + Function factory to make chebyshevIneqSafetyFunctionEvaluation functions. + We shouldn't run into late binding problems here, but I think this is easier to read + + Parameters + ---------- + safetyFunctionF : function + Function that represents the conditions the physical state must satisfy for safety. + Must accept a physical state as an input. + physicalStateSubEstimatorSampleF : function + Samples the physical state from the belief + numSamples : int (default=100) + Number of samples that must successfully be drawn without violation + allowableFailureChance : float (default=.05) + Maximum allowable failure chance (safety chance = 1-allowableFailureChance) + + Returns + ------- + chebyshevIneqSafetyFunctionEvaluationF : function + Wrapper around probabilisticSafetyFunctionEvaluation with the specified safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples + """ + + #Check to ensure valid construction so our assumptions hold/make sense + if allowableFailureChance <= 0: + invalidSpecification = "The allowableFailureChance must be greater than 0 for the Chebyshev bound to have meaning" + raise ValueError(invalidSpecification) + if numSamples < 2: + invalidSpecification = "The numSamples must be greater than or equal to 2 for the Chebyshev bound to be valid" + raise ValueError(invalidSpecification) + #Check the safety function is compatible (booleanInequalitySafetyFunction for example doesn't work well here ) + #This feels a little ugly, thinking if there is a better way to do it. + if not safetyFunctionF.__name__ in ("worstCaseSafetyFunctionF"): + invalidSpecification = "Using the safety function {safetyFunctionF.__name__} is invalid for the Chebyshev bound evaluation method." + raise ValueError(invalidSpecification) + + def chebyshevIneqSafetyFunctionEvaluationF(beliefTuple,rngKey): + return chebyshevIneqSafetyFunctionEvaluation(beliefTuple,rngKey,safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples,allowableFailureChance) + return chebyshevIneqSafetyFunctionEvaluationF + +#IDEA: The spacecraft can clip through the obstacle with this formulation, b/ we only check the position at discrete time steps. Would it make sense +#to add a variation that is aware of the time step and velocity and checks for collision this way? Additional complexity=slower, but would be more accurate. +@partial(jax.jit, static_argnames=['inequalityConstraintFTuple']) +def booleanInequalitySafetyFunction(physicalState,inequalityConstraintFTuple): + """ + Function that defines a safety constraint based on specified inequality constraints. + These don't need to be convex as we aren't doing optimization, just checking. + May need to have convex constraints if trying to check safety of a gaussian exactly or something like this. + Equality constraints omitted because these aren't usually found for safety. Also, achieving these exactly may be infeasible + + Parameters + ---------- + physicalState : array, shape(numState) + Physical state of the system to evaluate constraints against + inequalityConstraintFTuple : tuple + Tuple of inequality constraints to evaluate. These should all be < 0 when safety is satisfied. + Strict inequality assumed because: 1) equality can be considered collision. 2) ease of implementation + + Returns + ------- + safeFlag : boolean + 1 if safety constraints satisfied, 0 if not + """ + + #Will set to 0 if we ever aren't safe + safeFlag = 1 + + #We can't vmap this, because vmap only works over arrays, not tuples (and not of functions) + for inequalityConstraintF in inequalityConstraintFTuple: + #If constraint < 0, we are safe. + inequalityConstraintReturnValSign = jnp.sign(inequalityConstraintF(physicalState)) + #Check for > 0 (positive) AND check for = 0, as both are bad + inequalityConstraintSatisfied = (.5 - .5 *inequalityConstraintReturnValSign) * jnp.abs(inequalityConstraintReturnValSign) + safeFlag = safeFlag*inequalityConstraintSatisfied + + #If all pass, each safeFlag will still be 1. Any failure sets this to zero + return safeFlag #jnp.prod(batchSafetyReturn) + +#Can't vmap over tuples or functions +#def inequalitySafetyFunctionVMapHelper(physicalState,inequalityConstraintF): +# """ +# Helper function for parallelizing the loop in probabilisticSafetyFunctionEvaluation for faster compilation +# """ +# #If constraint < 0, we are safe. +# inequalityConstraintReturnValSign = jnp.sign(inequalityConstraintF(physicalState)) +# #Check for > 0 (positive) AND check for = 0, as both are bad +# inequalityConstraintSatisfied = (.5 - .5 *inequalityConstraintReturnValSign) * jnp.abs(inequalityConstraintReturnValSign) +# return inequalityConstraintSatisfied + + + +def makeBooleanInequalitySafetyFunctionF(inequalityConstraintFTuple): + """ + Function factory to make inequalitySafetyFunction functions. + We shouldn't run into late binding problems here, but I think this is easier to read + + Parameters + ---------- + inequalityConstraintFTuple : tuple + Tuple of inequality constraints to evaluate. These should all be < 0 when safety is satisfied. + Strict inequality assumed because: 1) equality can be considered collision. 2) ease of implementation + + Returns + ------- + booleanInequalitySafetyFunctionF : function + Wrapper around booleanInequalitySafetyFunction with the specified constraint tuple + """ + def inequalitySafetyFunctionF(physicalState): + return booleanInequalitySafetyFunction(physicalState,inequalityConstraintFTuple) + return inequalitySafetyFunctionF + +@partial(jax.jit, static_argnames=['inequalityConstraintFTuple']) +def worstCaseSafetyFunction(physicalState,inequalityConstraintFTuple): + """ + Function that returns the worst case (largest) safety constraint value. + + Parameters + ---------- + physicalState : array, shape(numState) + Physical state of the system to evaluate constraints against + inequalityConstraintFTuple : tuple + Tuple of inequality constraints to evaluate. These should all be < 0 when safety is satisfied. + Strict inequality assumed because: 1) equality can be considered collision. 2) ease of implementation + + Returns + ------- + worstCaseSafetyValue : float + Largest safety constraint value. We assume < 0 is safe. + """ + + #Set to best case (negative infinity) + worstCaseSafetyValue = - jnp.inf + + #We can't vmap this, because vmap only works over arrays, not tuples (and not of functions) + for inequalityConstraintF in inequalityConstraintFTuple: + #If constraint < 0, we are safe. We can accept multiple returns in an array + inequalityConstraintReturn = inequalityConstraintF(physicalState) + + #Keep largest value + inequalityConstraintValues = jnp.append(inequalityConstraintReturn,worstCaseSafetyValue) + worstCaseSafetyValue = jnp.max(inequalityConstraintValues) + + return worstCaseSafetyValue + +def makeWorstInequalitySafetyFunctionF(inequalityConstraintFTuple): + """ + Function factory to make worstCaseSafetyFunction functions. + We shouldn't run into late binding problems here, but I think this is easier to read + + Parameters + ---------- + inequalityConstraintFTuple : tuple + Tuple of inequality constraints to evaluate. These should all be < 0 when safety is satisfied. + Strict inequality assumed because: 1) equality can be considered collision. 2) ease of implementation + + Returns + ------- + worstCaseSafetyFunctionF : function + Wrapper around worstCaseSafetyFunction with the specified constraintTuple + """ + def worstCaseSafetyFunctionF(physicalState): + return worstCaseSafetyFunction(physicalState,inequalityConstraintFTuple) + return worstCaseSafetyFunctionF + +@jax.jit +def circularObstacleConstraint(physicalState,radiusObstaclePlusRadiusSpacecraft,center): + """ + Function that enforces a circular obstacle constraint. + + Parameters + ---------- + physicalState : array, shape(numState) + Physical state of the system to evaluate constraints against. + NOTE: Assumed to be a double integrator state, so for example, we have x, vx, y, vy, ... + Only the position for each dimension (x,y,...) will be used to determine collision. + The first len(center) dimensions will be checked for collision, in the same order + radiusObstaclePlusRadiusSpacecraft : float + Radius of obstacle AND the spacecraft. This is because this is the closest the centers can come to each other. + center : array, shape(numDimensionsObstacle) + The center of the obstacle. Length of this will be used to determine how many dimensions to check + + Returns + ------- + constraintReturn : int + If 0 or greater, constraint is violated. + """ + #Get the positions out of the physical state + positionSpaceCraft = getImplicitPositionSpaceCraftToCompare(physicalState,center) + + #If within radius, positive, so violated + return radiusObstaclePlusRadiusSpacecraft - jnp.linalg.norm(center-positionSpaceCraft) + +def makeCircularObstacleConstraintF(radiusObstaclePlusRadiusSpacecraft,center): + """ + Function factory to make circularObstacleConstraint functions. + This is needed because of python's late binding. If multiple constraints are defined in a loop, only the last set of variables will be used. + + Parameters + ---------- + radiusObstaclePlusRadiusSpacecraft : float + Radius of obstacle AND the spacecraft. This is because this is the closest the centers can come to each other. + center : array, shape(numDimensionsObstacle) + The center of the obstacle. Length of this will be used to determine how many dimensions to check + + Returns + ------- + circularObstacleConstraintF : function + Wrapper around circularObstacleConstraint with the specified radiusObstaclePlusRadiusSpacecraft,center + """ + def circularObstacleConstraintF(physicalState): + return circularObstacleConstraint(physicalState,radiusObstaclePlusRadiusSpacecraft,center) + return circularObstacleConstraintF + +@jax.jit +def circularSafeZoneConstraint(physicalState,radiusSafeZoneMinusRadiusSpacecraft,center): + """ + Function that enforces a circular safe zone constraint. + + Parameters + ---------- + physicalState : array, shape(numState) + Physical state of the system to evaluate constraints against. + NOTE: Assumed to be a double integrator state, so for example, we have x, vx, y, vy, ... + Only the position for each dimension (x,y,...) will be used to determine collision. + The first len(center) dimensions will be checked for collision, in the same order + radiusSafeZoneMinusRadiusSpacecraft : float + Radius of safe zone MINUS the spacecraft. This is because this is the closest the spacecraft center can come the edge of the safe zone. + center : array, shape(numDimensionsObstacle) + The center of the safe zone. Length of this will be used to determine how many dimensions to check + + Returns + ------- + constraintReturn : int + If 0 or greater, constraint is violated. + """ + #Get the positions out of the physical state + positionSpaceCraft = getImplicitPositionSpaceCraftToCompare(physicalState,center) + + #If outside radius, positive, so violated + return jnp.linalg.norm(center-positionSpaceCraft) - radiusSafeZoneMinusRadiusSpacecraft + +def makeCircularSafeZoneConstraintF(radiusSafeZoneMinusRadiusSpacecraft,center): + """ + Function factory to make circularSafeZoneConstraint functions. + This is needed because of python's late binding. If multiple constraints are defined in a loop, only the last set of variables will be used. + + Parameters + ---------- + radiusSafeZoneMinusRadiusSpacecraft : float + Radius of obstacle minus the spacecraft. This is because this is the farthest the centers can be from each other. + center : array, shape(numDimensionsObstacle) + The center of the obstacle. Length of this will be used to determine how many dimensions to check + + Returns + ------- + circularSafeZoneConstraintF : function + Wrapper around circularSafeZoneConstraint with the specified radiusSafeZoneMinusRadiusSpacecraft,center + """ + def circularSafeZoneConstraintF(physicalState): + return circularSafeZoneConstraint(physicalState,radiusSafeZoneMinusRadiusSpacecraft,center) + return circularSafeZoneConstraintF + +#Too much avoiding repeated code? #Don't need to jit as never called outside jitted methods +def getImplicitPositionSpaceCraftToCompare(physicalState,constraintPositionState): + """ + Gets the dimensions of the spacecraft's position that are relevant to a constraint we are evaluating + + Parameters + ---------- + physicalState : array, shape(numState) + Physical state of the system to evaluate constraints against. + NOTE: Assumed to be a double integrator state, so for example, we have x, vx, y, vy, ... + Only the position for each dimension (x,y,...) will be used to determine collision. + The first len(center) dimensions will be checked for collision, in the same order + constraintPositionState : array, shape(numState) + Physical state of the constraint to compare with the physical state. + + Returns + ------- + positionSpaceCraft : array, shape(numDimensionsObstacle) + The relevant position of the SpaceCraft to evaluate the constraint against + """ + + numDimensionsObstacle = len(constraintPositionState) + #Get the positions out of the physical state + return physicalState[0:2*numDimensionsObstacle:2] + +@jax.jit +def linearObstacleConstraint(physicalState,normalMatrix,offsetVector): + """ + Function that enforces a (convex) linear obstacle constraints on the position. + Defined as Ax - b < 0 for each constraint. To be outside the obstacle, one constraint must be satisfied. + so return the best case (most negative or min) from each line + + + Parameters + ---------- + physicalState : array, shape(numState) + Physical state of the system to evaluate constraints against. + NOTE: Assumed to be a double integrator state, so for example, we have x, vx, y, vy, ... + Only the position for each dimension (x,y,...) will be used to determine collision. + The first len(center) dimensions will be checked for collision, in the same order + normalMatrix : array, shape(numConstraints,numDimensionsObstacle) + A Matrix defining the normal vector of each constraint + offsetVector : array, shape(numConstraints) + b Vector defining the offset from the origin of each constraint + + Returns + ------- + worstConstraint : float + If 0 or greater, at least one constraint is violated. + """ + #Get the positions out of the physical state + positionSpaceCraft = getImplicitPositionSpaceCraftToCompare(physicalState,normalMatrix[0]) + + constraintEvaluation = jnp.matmul(normalMatrix, positionSpaceCraft) - offsetVector + + #If outside of obstacle, at least one of these will be negative. Only when all are positive are we in violation + return jnp.min(constraintEvaluation) + +def makeLinearObstacleConstraintF(normalMatrix,offsetVector): + """ + Function factory to make circularSafeZoneConstraint functions. + This is needed because of python's late binding. If multiple constraints are defined in a loop, only the last set of variables will be used. + + Parameters + ---------- + normalMatrix : array, shape(numConstraints,numDimensionsObstacle) + A Matrix defining the normal vector of each constraint + offsetVector : array, shape(numConstraints) + b Vector defining the offset from the origin of each constraint + + Returns + ------- + circularSafeZoneConstraintF : function + Wrapper around circularSafeZoneConstraint with the specified radiusObstaclePlusRadiusSpacecraft,center + """ + def linearObstacleConstraintF(physicalState): + return linearObstacleConstraint(physicalState,normalMatrix,offsetVector) + return linearObstacleConstraintF + +@jax.jit +def linearSafeZoneConstraint(physicalState,normalMatrix,offsetVector): + """ + Function that enforces a (convex) composition of linear safe zone constraints on the position. + Defined as Ax - b < 0 for each constraint. We require every constraint is satisfied for safety, + so return the worst case (most positive or max) from each line + + + Parameters + ---------- + physicalState : array, shape(numState) + Physical state of the system to evaluate constraints against. + NOTE: Assumed to be a double integrator state, so for example, we have x, vx, y, vy, ... + Only the position for each dimension (x,y,...) will be used to determine collision. + The first len(center) dimensions will be checked for collision, in the same order + normalMatrix : array, shape(numConstraints,numDimensionsObstacle) + A Matrix defining the normal vector of each constraint + offsetVector : array, shape(numConstraints) + b Vector defining the offset from the origin of each constraint + + Returns + ------- + worstConstraint : float + If 0 or greater, at least one constraint is violated. + """ + #Get the positions out of the physical state + positionSpaceCraft = getImplicitPositionSpaceCraftToCompare(physicalState,normalMatrix[0]) + + constraintEvaluation = jnp.matmul(normalMatrix, positionSpaceCraft) - offsetVector + + #If outside on any constraint, we are in violation, so require all negative + return jnp.max(constraintEvaluation) + +def makeLinearSafeZoneConstraintF(normalMatrix,offsetVector): + """ + Function factory to make circularSafeZoneConstraint functions. + This is needed because of python's late binding. If multiple constraints are defined in a loop, only the last set of variables will be used. + + Parameters + ---------- + normalMatrix : array, shape(numConstraints,numDimensionsObstacle) + A Matrix defining the normal vector of each constraint + offsetVector : array, shape(numConstraints) + b Vector defining the offset from the origin of each constraint + + Returns + ------- + circularSafeZoneConstraintF : function + Wrapper around circularSafeZoneConstraint with the specified radiusObstaclePlusRadiusSpacecraft,center + """ + def linearSafeZoneConstraintF(physicalState): + return linearSafeZoneConstraint(physicalState,normalMatrix,offsetVector) + return linearSafeZoneConstraintF + + + +#Scratch ideas: +#Obstacle defined by radius: +#g(x) = radius**2 - 2norm(xCenter-xPos)**2. If within radius, 2norm**2 < radius**, so positive, so violated + + +#Add and Multiplication check on -1/1: .5 - .5*testVal (0 if testVal=1, 1 if testVal=-1) diff --git a/failurePy/rewards/squareSumFailureBeliefReward.py b/failurePy/rewards/squareSumFailureBeliefReward.py new file mode 100644 index 0000000..c06295e --- /dev/null +++ b/failurePy/rewards/squareSumFailureBeliefReward.py @@ -0,0 +1,32 @@ +""" +Simple reward function that is the square sum over the failure beliefs +""" + +import jax.numpy as jnp +import jax + +@jax.jit +def squareSumFailureBeliefReward(beliefTuple,rngKey=None): #pylint: disable=unused-argument + """ + Reward on the certainty of the failure belief, or the L2 norm of the failure belief + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + rngKey : JAX PRNG key (default=None) + Unused here, included for compatibility with the safety filters + + Returns + ------- + reward : float + Reward for how certain we are. Note this will always be 0-1 because + the belief distribution is a probability distribution + """ + + failureWeights = beliefTuple[0] + return jnp.sum(jnp.square(failureWeights)) diff --git a/failurePy/solvers/__init__.py b/failurePy/solvers/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/failurePy/solvers/cbf.py b/failurePy/solvers/cbf.py new file mode 100644 index 0000000..82a39ca --- /dev/null +++ b/failurePy/solvers/cbf.py @@ -0,0 +1,176 @@ +""" +Simple implementation of a control barrier function based solver for safety. +""" + +import jax.numpy as jnp +from jax import random as jaxRandom +import numpy as onp #Following Jax conventions to be explicit about which implementation of numpy we use +from scipy.optimize import minimize, Bounds + + + +#Usually doesn't do anything, going to just take a brute force approach and see how well that works +def solveForNextAction(beliefTuple,solverParametersTuple,possibleFailures,systemF,systemParametersTuple,rewardF,estimatorF, # pylint: disable=unused-argument + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngKey): # pylint: disable=unused-argument + """ + Function that takes in the current belief tuple, parameters, possible failures and system to determine the next best action to take. + Uses the SFEAST algorithm + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + solverParametersTuple : tuple + List of solver parameters needed. Contents are: + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action + discretization : float + Discretization level or scheme + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + Abstracted for the system function + rewardF : function + Reward function to evaluate the beliefs with + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Function to update all of the conditional position filters + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + + Returns + ------- + action : array, shape(numAct) + Action to take next + rootNode : BeliefNode + Root node of the tree that is now expanded to amount requested (N trajectories) + """ + + #Unpack + numActuators,safetyFunctionF = unpackSolverParameters(solverParametersTuple) + + + #We sample over possible actions that might satisfy cbf + + #Outline of function. + # Compute ML failure. In event of a tie (such as at initial state), select randomly + # Sample within actuation limits (thinking setting any actuator to +/- 5 m/s^2 influence, since empirically, velocity usually below 10m/s^2 + # Compute nominal next state given the most likely failure + # see if satisfies hcbf(next state) > hcbf(current state), hcbf = h * (10-||v||) -> safe + velocity bounded + # If fails bound, keep if violation is less than previous best. Resample up to 100 times + # Use smallest violation if failed to find an action that satisfies the bound. + # Actually, just set hcbf to h, and progressively widen a until we find one that works or until we have widened 100 times. + + + #Get ML failure + failureWeights = beliefTuple[0] + + #When cbf fails to solve, large actions can have the EKF diverge, leading to nans. For now just going to side step this by selecting randomly + if jnp.isnan(failureWeights[0]): + mostLikelyFailuresIdx = jaxRandom.randint(rngKey,shape=(1,),minval=0,maxval=len(failureWeights))[0] + else: + mostLikelyFailuresIdxes = jnp.argwhere(failureWeights == jnp.amax(failureWeights)) + #Dealing with possible ties/lack there of + if len(mostLikelyFailuresIdxes) > 1: + #Pick random most likely failure and assume this to be the dynamics + mostLikelyFailuresIdx = jaxRandom.choice(rngKey,mostLikelyFailuresIdxes)[0] + else: + mostLikelyFailuresIdx = mostLikelyFailuresIdxes[0,0] + + mostLikelyFailure = possibleFailures[mostLikelyFailuresIdx] + #Need to assume a state. Idea, propagate posterior of this failure and require up to 2 sigma (95%!) to be safe? + # Downside: why not just use full failure and propagate action? Maybe we should? Could re-use our chebyshev bound? With random observations/noise? + + #Best plan so far, select action, simulate 100 times on state/failure sampled from initial belief, evaluate average hcbf as approximate hcbf, check if + + #Now get ML state (first row of associated filter) + assumedState = beliefTuple[1][mostLikelyFailuresIdx,0] + + cbfConstraintWrapperF = makeCbfConstraintWrapper(assumedState, mostLikelyFailure, systemF, systemParametersTuple, safetyFunctionF) + + initialActionGuess = onp.zeros(numActuators) #When this is feasible, it's always the solution + actuationBounds = Bounds(lb=-10,ub=10) + + #print(mostLikelyFailuresIdx) + #print(mostLikelyFailure,"mostLikelyFailure") + #print(assumedState,"assumedState") + #print(initialActionGuess,"initialActionGuess") + + #Solve as non-linear program (note that this is probably not optimized, hoping it can solve well enough numerically without needing to optimize) + # x is the optimal solution + solution = minimize(minControlObjective, initialActionGuess, constraints={'type': 'ineq', 'fun': cbfConstraintWrapperF},bounds=actuationBounds) + action = solution['x'] + #print(solution['success'],solution['message']) + #Map negative controls to opposite thruster + for iThruster in range(8): + if action[iThruster] < 0: + #Influence matrices are: -1,-1,1,1 per axis, 1,-1,1,-1,... for rotation + #Map to new thruster + thrusterOppositeMap = (3,2,1,0,7,6,5,4) + idxNewThruster = thrusterOppositeMap[iThruster] + action[idxNewThruster] -= action[iThruster] #Note sign, since action is negative at this idx + action[iThruster] = 0 + #for iActuator in range(10): + # #Zero out controls close to 0 (just for vis) + # if action[iActuator] < 1e-3: + # action[iActuator] = 0 + #print(-safetyFunctionF(assumedState),action,cbfConstraintWrapperF(solution['x'])) + return action, None #No tree to return + + +def makeCbfConstraintWrapper(assumedState, mostLikelyFailure, systemF, systemParametersTuple, safetyFunctionF): + """ + Constructor that wraps up the constraints for the cbf so that we can pass to optimizer. + """ + def cbfConstraintWrapper(action): + return cbfConstraint(action,assumedState, mostLikelyFailure, systemF, systemParametersTuple, safetyFunctionF) + + return cbfConstraintWrapper + +def minControlObjective(action): + """ + Minimizes ||u||^2 + """ + return onp.linalg.norm(action,ord=2) + +def cbfConstraint(action, physicalState, failureState, systemF, systemParametersTuple, safetyFunctionF): + """ + Determines the cbf value at this action, given the current state, system dynamics, and safety function + """ + + #rngKey not used, because noisyPropagationBooleanInt = 0, so just hand it basic one + rngKey = jaxRandom.PRNGKey(0) + nominalNextPhysicalState,dummyNextFailureState,dummyNextObservation = systemF(physicalState,failureState,action,rngKey,systemParametersTuple,noisyPropagationBooleanInt=0) + + #Evaluate the value of the safety function (this is h), Note minus sign convention, as cbf literature has h=>0 safe, but optimizers want constraints <=0, but our safety already has <0 safe + + sigmaW = .4 #Hard coded for now + + #CBF with alpha = 0 (gamma = 1), as this is the least restrictive + #Adding distance, so that it needs to be in 90% confidence (relative to linear noise sigmaW) + return -safetyFunctionF(nominalNextPhysicalState) - 1.28155*sigmaW#If h>0, this should be -safetyFunctionF + +def unpackSolverParameters(solverParametersTuple): + """ + Helper method to unpack parameters for readability + """ + + #Get solver parameters + numActuators = solverParametersTuple[0] + safetyFunctionF = solverParametersTuple[1] + + return numActuators,safetyFunctionF diff --git a/failurePy/solvers/greedy.py b/failurePy/solvers/greedy.py new file mode 100644 index 0000000..e3fb45e --- /dev/null +++ b/failurePy/solvers/greedy.py @@ -0,0 +1,129 @@ +""" +one-step greedy algorithm that finds the next best action after trying them all to a depth of 1. +""" + +import jax.numpy as jnp +from jax import random as jaxRandom +#from failurePy.solvers.sFEAST import BeliefNode +from failurePy.solvers.sFEAST import simulateHelperFunction + + +#Could jit, but probably no need to for speed. +def solveForNextAction(beliefTuple,solverParametersTuple,possibleFailures,systemF,systemParametersTuple,rewardF,estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngKey): # pylint: disable=unused-argument + """ + Function that takes in the current belief tuple, parameters, possible failures and system to determine the next best action to take. + Uses the SFEAST algorithm + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + solverParametersTuple : tuple + List of solver parameters needed. Contents are: + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action + discretization : float + Discretization level or scheme + maxSimulationTime : float + Max simulation time (can be infinite). NOTE: Currently implemented by breaking loop after EXCEEDING time, NOT a hard cap + explorationParameter : float + Weighting on exploration vs. exploitation + nMaxDepth : int + Max depth of the tree + discountFactor : float + Discount on future rewards, should be in range [0,1] + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + Abstracted for the system function + rewardF : function + Reward function to evaluate the beliefs with + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Function to update all of the conditional position filters + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + + Returns + ------- + action : array, shape(numAct) + Action to take next + rootNode : BeliefNode + Root node of the tree that is now expanded to amount requested (N trajectories) + """ + + #Unpack + availableActions,discretization = unpackSolverParameters(solverParametersTuple) + + #We perform a greedy search over possible futures. Create the root node (no observation used to get here) + #We now allow for probabilistic rewards (usually b/ of safety constraint) + #Unused here in greedy + #rngKey, rngSubKey = jaxRandom.split(rngKey) + #rootNode = BeliefNode(None,rewardF(beliefTuple,rngSubKey),beliefTuple,availableActions) + + #Rewards + rewards = jnp.zeros(len(availableActions)) + + #Try every action and save reward + for iAction, action in enumerate(availableActions): + #Since already chose action, will use the simulate sub methods directly + rngKey,rngSubKey = jaxRandom.split(rngKey) #Make rngSubKey, as consumed on use + nextObservation = simulateHelperFunction(action,possibleFailures,beliefTuple,systemF,systemParametersTuple,physicalStateSubEstimatorSampleF,discretization,rngSubKey) + + #Now see if this observation is any of the existing children of the decision node, or make new node. Get reward + #We now allow for probabilistic rewards (usually b/ of safety constraint) + rngKey, rngSubKey = jaxRandom.split(rngKey) + #Update belief tuple + nextBeliefTuple = estimatorF(action,nextObservation,beliefTuple,possibleFailures,systemF,systemParametersTuple,physicalStateSubEstimatorF,physicalStateJacobianF) + #We now allow for probabilistic rewards (usually b/ of safety constraint) + rewards= rewards.at[iAction].set(rewardF(nextBeliefTuple,rngKey)) + + #And done, don't look any further! + + #Need to return best reward! (No tree to return) + #Rarely the EKF diverges, leading to nans. For now just going to side step this by selecting randomly + if jnp.isnan(rewards[0]): + bestRewardIdx = jaxRandom.randint(rngKey,shape=(1,),minval=0,maxval=len(rewards))[0] + else: + + + bestRewardsIdxes = jnp.argwhere(rewards == jnp.amax(rewards)) + #print(len(bestRewardsIdxes),bestRewardsIdxes) + #Dealing with possible ties, split randomly (probably not going to have any here..,) + #print(bestRewardsIdxes) + #print(rewards) + if len(bestRewardsIdxes) > 1: + #Pick random most likely failure and assume this to be the dynamics + bestRewardIdx = jaxRandom.choice(rngKey,bestRewardsIdxes)[0] + else: + bestRewardIdx = bestRewardsIdxes[0,0] + + #print(bestRewardIdx) + + return availableActions[bestRewardIdx], None + +def unpackSolverParameters(solverParametersTuple): + """ + Helper method to unpack parameters for readability + """ + + #Get solver parameters + availableActions = solverParametersTuple[0] + discretization = solverParametersTuple[1] + + return availableActions,discretization diff --git a/failurePy/solvers/preSpecifiedPolicy.py b/failurePy/solvers/preSpecifiedPolicy.py new file mode 100644 index 0000000..fd3f0b2 --- /dev/null +++ b/failurePy/solvers/preSpecifiedPolicy.py @@ -0,0 +1,160 @@ +""" +Debug policy module +""" +import jax.numpy as jnp + +#Debug class, so disable much of pylint +class PreSpecifiedPolicy: # pylint: disable=too-few-public-methods + """ + Debug policy, uses class object to deterministically apply a set of specified actions + """ + def __init__(self, actionList=None): + """ + Create the pre-specified list of actions to take + + Parameters + ---------- + actionList : List (default=None) + List of actions to take, if any. If not provided hard-coded default used + """ + + if actionList is None: + #actionList = [] + ##1D pre-specified + #actionList = [ jnp.array([1,1,0,0]), + # jnp.array([0,0,0,1]), + # jnp.array([0,0,1,0]), + # jnp.array([0,0,1,1]), + # jnp.array([1,1,0,0]), + # jnp.array([0,1,0,0]), + # jnp.array([1,0,0,0]), + # jnp.array([1,1,0,0]), + # jnp.array([0,1,0,0]), + # jnp.array([0,0,1,0]), + # jnp.array([0,0,1,1]), + # jnp.array([0,0,1,1]), + # jnp.array([1,1,0,0]), + # jnp.array([1,1,0,0]), + # jnp.array([1,1,0,0]), + # ] + + + #Sequential test + #actionList = [ jnp.array([1,0,0,0,0,0,0,0,0,0]), + # jnp.array([0,1,0,0,0,0,0,0,0,0]), + # jnp.array([0,0,1,0,0,0,0,0,0,0]), + # jnp.array([0,0,0,1,0,0,0,0,0,0]), + # jnp.array([0,0,0,0,1,0,0,0,0,0]), + # jnp.array([0,0,0,0,0,1,0,0,0,0]), + # jnp.array([0,0,0,0,0,0,1,0,0,0]), + # jnp.array([0,0,0,0,0,0,0,1,0,0]), + # jnp.array([0,0,0,0,0,0,0,0,1,0]), + # jnp.array([0,0,0,0,0,0,0,0,0,1]), + # ] + + #All rotations (if no failures of course) + actionList = [ jnp.array([1,0,1,0,0,0,0,0,0,0]), + jnp.array([1,0,1,0,0,0,0,0,0,0]), + jnp.array([0,0,0,0,0,0,0,0,0,0]), + jnp.array([0,0,0,0,0,0,0,0,0,0]), + jnp.array([0,1,0,1,0,0,0,0,0,0]), + jnp.array([0,1,0,1,0,0,0,0,0,0]), + jnp.array([0,0,0,0,0,0,0,0,0,0]), + jnp.array([0,0,0,0,0,0,0,0,0,0]), + jnp.array([0,0,0,0,1,0,1,0,0,0]), + jnp.array([0,0,0,0,1,0,1,0,0,0]), + jnp.array([0,0,0,0,0,0,0,0,0,0]), + jnp.array([0,0,0,0,0,0,0,0,0,0]), + jnp.array([0,0,0,0,0,1,0,1,0,0]), + jnp.array([0,0,0,0,0,1,0,1,0,0]), + jnp.array([0,0,0,0,0,0,0,0,0,0]), + jnp.array([0,0,0,0,0,0,0,0,0,0]), + jnp.array([0,0,0,0,0,0,0,0,1,1]), + jnp.array([0,0,0,0,0,0,0,0,1,1]), + jnp.array([0,0,0,0,0,0,0,0,-1,-1]), + jnp.array([0,0,0,0,0,0,0,0,-1,-1]), + ] + #Tom's actuation idea + # actionList = [Action(.1* np.array([1,1,1,1,1,1,1,1,50,50])), + # Action(.1* np.array([1,1,1,1,1,1,1,1,50,50])), + # Action(.1* np.array([1,1,1,1,1,1,1,1,50,50])), + # Action(.1* np.array([1,0,0,0,0,0,0,0,0,0])), + # Action(.1* np.array([0,1,0,0,0,0,0,0,0,0])), + # Action(.1* np.array([0,0,1,0,0,0,0,0,0,0])), + # Action(.1* np.array([0,0,0,1,0,0,0,0,0,0])), + # Action(.1* np.array([0,0,0,0,1,0,0,0,0,0])), + # Action(.1* np.array([0,0,0,0,0,1,0,0,0,0])), + # Action(.1* np.array([0,0,0,0,0,0,1,0,0,0])), + # Action(.1* np.array([0,0,0,0,0,0,0,1,0,0])), + # Action(.1* np.array([0,0,0,0,0,0,0,0,50,0])), + # Action(.1* np.array([0,0,0,0,0,0,0,0,0,50])), + # ] + + self.actionList = actionList + self.tree = {():None} + + #Made to be compatible, so all arguments ignored + def takeNextAction(self,beliefTuple,solverParametersTuple,possibleFailures,systemF,systemParametersTuple,rewardF,estimatorF, # pylint: disable=unused-argument + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngKey): # pylint: disable=unused-argument + """ + Compatible with SFEAST, but pre determined result + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + solverParametersTuple : tuple + List of solver parameters needed. None needed, but availableActions included for completeness + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Tuple of system parameters needed + Abstracted for the system function + rewardF : function + Reward function to evaluate the beliefs with + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + + Returns + ------- + action : array, shape(numAct) + Action to take next + rootNode : None + No belief node for random policy + """ + + return self._takeNextAction() + + def _takeNextAction(self): + """ + Internal action method, takes no arguments + """ + + if len(self.actionList) > 0: + + action = self.actionList.pop(0) + else: + #HACK to allow repeated actions + self.__init__() # pylint: disable=unnecessary-dunder-call + action, dummyRootNode = self._takeNextAction() + ##action = jnp.array([0,0,0,0,0,0,0,0,0,0]) + #noMoreSpecifiedActions = "Ran out of pre-specified actions." + #raise IndexError(noMoreSpecifiedActions) + + return action,None diff --git a/failurePy/solvers/randomPolicy.py b/failurePy/solvers/randomPolicy.py new file mode 100644 index 0000000..d6be0a4 --- /dev/null +++ b/failurePy/solvers/randomPolicy.py @@ -0,0 +1,80 @@ +""" +Default random policy baseline +""" + +from jax import random as jaxRandom + +#Made to be compatible with distributed solvers, so many unused arguments here +def distributedSolveForNextAction(beliefTuple,solverParametersTuple,possibleFailures,systemF,systemParametersTuple,rewardF,estimatorF, # pylint: disable=unused-argument + physicalStateSubEstimatorF,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngKey): # pylint: disable=unused-argument + """ + Compatible with d-SFEAST, but random result + """ + + return solveForNextAction(beliefTuple,solverParametersTuple,possibleFailures,systemF,systemParametersTuple,rewardF,estimatorF, + physicalStateSubEstimatorF,None,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngKey) + + +#Made to be compatible with SFEAST, so many unused arguments here +def solveForNextAction(beliefTuple,solverParametersTuple,possibleFailures,systemF,systemParametersTuple,rewardF,estimatorF, # pylint: disable=unused-argument + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngKey): # pylint: disable=unused-argument + """ + Compatible with SFEAST, but random result + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + solverParametersTuple : tuple + List of solver parameters needed. Contents are: + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action. + discretization : float + Discretization level or scheme + maxSimulationTime : float + Max simulation time (can be infinite). NOTE: Currently implemented by breaking loop after EXCEEDING time, NOT a hard cap + explorationParameter : float + Weighting on exploration vs. exploitation + nMaxDepth : int + Max depth of the tree + discountFactor : float + Discount on future rewards, should be in range [0,1] + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Tuple of system parameters needed + Abstracted for the system function + rewardF : function + Reward function to evaluate the beliefs with + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + + Returns + ------- + action : array, shape(numAct) + Action to take next + rootNode : None + No belief node for random policy + """ + #errRandom NEED TO ADD VALIDATION ON NUM TRIALS PER POINT FOR BASELINES + availableActions = solverParametersTuple[0] + + #Store action so we can print while debugging + action = jaxRandom.choice(rngKey,availableActions) + #print(action) + + return action,None diff --git a/failurePy/solvers/realTimeSFEAST.py b/failurePy/solvers/realTimeSFEAST.py new file mode 100644 index 0000000..f60f681 --- /dev/null +++ b/failurePy/solvers/realTimeSFEAST.py @@ -0,0 +1,182 @@ +""" +POMCP Algorithm adapted to carry the updated belief state forward instead of the approximation, +as this is what our reward is conditioned on. Uses a marginalized filter to do so. + +Goal of this implementation is to be purely functional, to allow for jitting of the algorithm. +Currently the tree has to be represented as objects, but there are ideas to do this with arrays instead. + +This version is designed for real-time use, meaning that the action active on the system while +the tree search is running is incorporated in the tree search +""" + +import time +from tqdm import tqdm +import jax +import jax.numpy as jnp +from jax import random as jaxRandom +from failurePy.solvers.sFEAST import BeliefNode, simulateHelperFunction, simulate, unpackSolverParameters,getNextBeliefNodeAndReward #Re-used methods + + +def solveForNextAction(beliefTuple, solverParametersTuple, possibleFailures, systemF, systemParametersTuple, rewardF, estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngKey,currentAction=None): + """ + Function that takes in the current belief tuple, parameters, possible failures and system to determine the next best action to take. + This action is dependant on the observation seen after this tree search terminates. + Therefore, only the rootNode (beliefNode) is returned from this function, and the best action is extracted once the solver knows the real observation + Uses the SFEAST algorithm in real-time + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + solverParametersTuple : tuple + List of solver parameters needed. Contents are: + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action + discretization : float + Discretization level or scheme + maxSimulationTime : float + Max simulation time (can be infinite). NOTE: Currently implemented by breaking loop after EXCEEDING time, NOT a hard cap + explorationParameter : float + Weighting on exploration vs. exploitation + nMaxDepth : int + Max depth of the tree + discountFactor : float + Discount on future rewards, should be in range [0,1] + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + Abstracted for the system function + rewardF : function + Reward function to evaluate the beliefs with + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Function to update all of the conditional position filters + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + currentAction : array, shape(numAct) (default=None) + Action that is active while the tree search is running. The first action that is automatically taken in the tree search. + If unspecified, assumed to be the null action + + Returns + ------- + action : array, shape(numAct) + Action to take next + rootNode : BeliefNode + Root node of the tree that is now expanded to amount requested (N trajectories) + + """ + + #Unpack + startTime,availableActions,discretization,maxSimulationTime,explorationParameter,nMaxDepth,discountFactor = unpackSolverParameters(solverParametersTuple) + + if currentAction is None: + currentAction = availableActions[0] + #We now allow for probabilistic rewards (usually b/ of safety constraint) + rngKey, rngSubKey = jaxRandom.split(rngKey) + #Need to check if a default action that was NOT part of the normal action set was used (ie, Tom's idea) + if jnp.any(jnp.all(currentAction != availableActions,axis=1)): + augmentedAvailableActions = jnp.zeros((len(availableActions)+1,len(availableActions[0]))) + augmentedAvailableActions = augmentedAvailableActions.at[:len(availableActions),:].set(availableActions) + augmentedAvailableActions = augmentedAvailableActions.at[len(availableActions),:].set(currentAction) + # root node, no observation to get here, just the belief + rootNode = BeliefNode(None, rewardF(beliefTuple,rngSubKey), beliefTuple, augmentedAvailableActions) + #will return array, takes first (should be only) value of that array. Need first 0 to get the device array, second to pop the integer out + actionIdx = jnp.where((augmentedAvailableActions == currentAction).all(axis=1))[0][0] + else: + # root node, no observation to get here, just the belief + rootNode = BeliefNode(None, rewardF(beliefTuple,rngSubKey), beliefTuple, availableActions) + + #What's different here from standard POMCP is that the first action is prescribed (BUT, we DON'T know what the observation is going to be still) + #Search for actionIdx that matches the prescribed action + #Will return array, takes first (should be only) value of that array. Need first 0 to get the device array, second to pop the integer out + actionIdx = jnp.where((availableActions == currentAction).all(axis=1))[0][0] + decisionNode = rootNode.children[actionIdx] + + + # search until time-out or use all simulations + for iSimulation in tqdm(range(nSimulationsPerTree)): # pylint: disable=unused-variable + #for iSimulation in range(nSimulationsPerTree): # pylint: disable=unused-variable + + #Time out + if (time.time() - startTime ) > maxSimulationTime: + print("Timeout") + break + #make rngSubKey, as consumed on use + rngKey, rngSubKey = jaxRandom.split(rngKey) + + #Need to sim first observation before working down the tree. Don't really care about the reward here + nextObservation = simulateHelperFunction(currentAction, possibleFailures, beliefTuple, systemF, systemParametersTuple,physicalStateSubEstimatorSampleF,discretization,rngSubKey) + + #Now see if this observation is any of the existing children of the decision node, or make new node. + #We get reward, but we don't need it here at the outer loop + rngKey, rngSubKey = jaxRandom.split(rngKey) + dummyReward, nextBeliefNode = getNextBeliefNodeAndReward(availableActions, possibleFailures, systemF, systemParametersTuple, rewardF, estimatorF, physicalStateSubEstimatorF, + physicalStateJacobianF, beliefTuple, currentAction, decisionNode, nextObservation,rngSubKey) + + #make rngSubKey, as consumed on use (as we loop and will use rngKey a again) + rngKey, rngSubKey = jaxRandom.split(rngKey) + + #Simulate forward (don't use the reward) + dummyDiscountedReward = simulate(nextBeliefNode,nMaxDepth,discretization,explorationParameter, + availableActions,possibleFailures,systemF,systemParametersTuple,discountFactor, + rewardF,estimatorF,physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF, + depth=0,rngKey=rngSubKey) # Choose depth to be zero, since the previous cycle was just applying previously selected action + #Simulate returns the discounted reward, currently we don't use if for anything + + #Now need to get the next action to take. We will get the best actions for each possible next observation considered, then weight by the likelihood of each observation + action = availableActions[getWeightedBestActionIdx(decisionNode.children,rngKey)] + + return action, rootNode + + +#This uses best action instead of most visited, departure from POMCP, but I think this is better (avoids degeneracies when not every node is visited, likely here because of observation sampling) +#When the number of visits is high, they converge to the same value, so this only matters in the case of limited simulations (like when running in real-time) +def getWeightedBestActionIdx(beliefNodesList,rngKey): + """ + Helper function to sample from the best actions of each belief node, weighted by visits to the belief nodes + + Parameters + ---------- + beliefNodesList : list + List of belief nodes to chose best actions from + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + + Returns + ------- + bestActionIdx : int + Index of the action to take next, sampled from the belief nodes' best actions weighted by visits + """ + + bestActionIdxes = jnp.zeros(len(beliefNodesList)) + nVisitsArray = jnp.zeros(len(beliefNodesList)) + + for iBeliefNode, beliefNode in enumerate(beliefNodesList): + #rngKey is needed incase we tie on zero visits + rngKey, rngSubKey = jaxRandom.split(rngKey) + bestActionIdxes = bestActionIdxes.at[iBeliefNode].set(beliefNode.getBestActionIdx(rngKey=rngSubKey)) + nVisitsArray = nVisitsArray.at[iBeliefNode].set(beliefNode.nVisits) + + return int(getWeightedBestActionIdxHelperFunction(rngKey,bestActionIdxes,nVisitsArray)) + +@jax.jit +def getWeightedBestActionIdxHelperFunction(rngKey,bestActionIdxes,nVisitsArray): + """ + jittable helper function + """ + return jaxRandom.choice(rngKey,bestActionIdxes,p=nVisitsArray/jnp.sum(nVisitsArray)) diff --git a/failurePy/solvers/sFEAST.py b/failurePy/solvers/sFEAST.py new file mode 100644 index 0000000..3f0f578 --- /dev/null +++ b/failurePy/solvers/sFEAST.py @@ -0,0 +1,587 @@ +""" +POMCP Algorithm adapted to carry the updated belief state forward instead of the approximation, +as this is what our reward is conditioned on. Uses a marginalized filter to do so. + +Goal of this implementation is to be purely functional, to allow for jitting of the algorithm. +Currently the tree has to be represented as objects, but there are ideas to do this with arrays instead. +""" +import time +from functools import partial +import jax +import jax.numpy as jnp +from jax import random as jaxRandom +import numpy as onp #Following Jax conventions to be explicit about which implementation of numpy we use + +#But feels like if we aren't jitting, we are wasting memory with device arrays? helper methods seem to fix + +#Previously used list (*not* dict!) of nodes, coupled with (mutable) dict in decision nodes mapping to child belief nodes +#Idea is that this will allow for rapid traversal down the tree without needing to explicitly store the histories (just need to know what child to go to, and make and and new node when needed) +#Ideas for speed ups, lists instead of dicts for nodes? Immutable nodes? Store history in separate list so don't need mutable dicts in decision nodes? ... + +#Can't jit because of logic flow + + +def solveForNextAction(beliefTuple,solverParametersTuple,possibleFailures,systemF,systemParametersTuple,rewardF,estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngKey): + """ + Function that takes in the current belief tuple, parameters, possible failures and system to determine the next best action to take. + Uses the SFEAST algorithm + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + solverParametersTuple : tuple + List of solver parameters needed. Contents are: + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action + discretization : float + Discretization level or scheme + maxSimulationTime : float + Max simulation time (can be infinite). NOTE: Currently implemented by breaking loop after EXCEEDING time, NOT a hard cap + explorationParameter : float + Weighting on exploration vs. exploitation + nMaxDepth : int + Max depth of the tree + discountFactor : float + Discount on future rewards, should be in range [0,1] + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + Abstracted for the system function + rewardF : function + Reward function to evaluate the beliefs with + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Function to update all of the conditional position filters + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + + Returns + ------- + action : array, shape(numAct) + Action to take next + rootNode : BeliefNode + Root node of the tree that is now expanded to amount requested (N trajectories) + """ + + #Unpack + startTime,availableActions,discretization,maxSimulationTime,explorationParameter,nMaxDepth,discountFactor = unpackSolverParameters(solverParametersTuple) + + + #We perform a tree search over possible futures. Create the root node (no observation used to get here) + #We now allow for probabilistic rewards (usually b/ of safety constraint) + rngKey, rngSubKey = jaxRandom.split(rngKey) + rootNode = BeliefNode(None,rewardF(beliefTuple,rngSubKey),beliefTuple,availableActions) + + #Make array of rng keys, to avoid needing to split every loop (in GPU mode this might cause some hanging as we wait for a dispatch) + rngKeys = jaxRandom.split(rngKey,num=nSimulationsPerTree) + + #Now search repeatedly until we either time out or use all of our simulations NOTE: Time out is NOT immediate + #for iSimulation in tqdm(range(nSimulationsPerTree)): + for iSimulation in range(nSimulationsPerTree): + #Time out + if (time.time() - startTime) > maxSimulationTime: + print("Timeout") + break + #No longer used + ##Make rngSubKey, as consumed on use + #rngKey,rngSubKey = jaxRandom.split(rngKey) + dummyDiscountedReward = simulate(rootNode, nMaxDepth,discretization,explorationParameter, + availableActions,possibleFailures,systemF,systemParametersTuple,discountFactor, + rewardF,estimatorF,physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF, + depth=0,rngKey=rngKeys[iSimulation]) #Get rngKey from precomputed array + #Simulate returns the discounted reward, currently we don't use if for anything + + #Now select child action that we expect to give us the best value. Do so by having no exploration term + #NOTE: This will return an untried action if nSimulationsPerTree < maxNumActions. This behavior is undefined! + return availableActions[rootNode.getBestActionIdx(0)],rootNode + + +#Don't think I can, have to check if a belief node exists. Look into further, might be able to jit higher level or otherwise combine with previous method to make this work? +#Currently using a helper function to jit what we can do. +def simulate(rootNode, nMaxDepth,discretization,explorationParameter,availableActions,possibleFailures,systemF,systemParametersTuple, + discountFactor,rewardF,estimatorF,physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,depth,rngKey): + """ + Recursively simulates the system out to a horizon, branching and/or creating new nodes according to POMCP value function + Returns new versions of most past parameters + + Parameters + --------- + rootNode : BeliefNode + Node to expand out from + nMaxDepth : int + Max depth of the tree + discretization : float + Discretization level or scheme + explorationParameter : float + Weighting on exploration vs. exploitation + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + Abstracted for the system function + discountFactor : float + Discount on future rewards, should be in range [0,1] + rewardF : function + Reward function to evaluate the beliefs with + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Function to update all of the conditional position filters + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + depth : int + Depth of the tree so far + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + + Returns + ------- + discountedReward : float + Discounted reward for the sequence of actions taken + """ + + + #return if we've hit the bottom of the recursion stack + if depth > nMaxDepth: + return 0 + + #Get belief at this node + beliefTuple = rootNode.beliefTuple + + #Update visits at this belief + + #Select the action to take + rngKey,rngSubKey = jaxRandom.split(rngKey) #Make rngSubKey, as consumed on use. Used for randomly returning if multiple actions haven't been trying + actionIdx = rootNode.getBestActionIdx(explorationParameter,rngSubKey) + action = availableActions[actionIdx] + decisionNode = rootNode.children[actionIdx] + + rngKey,rngSubKey = jaxRandom.split(rngKey) #Make rngSubKey, as consumed on use + nextObservation = simulateHelperFunction(action,possibleFailures,beliefTuple,systemF,systemParametersTuple,physicalStateSubEstimatorSampleF,discretization,rngSubKey) + #End block to jit + + #Now see if this observation is any of the existing children of the decision node, or make new node. Get reward + #We now allow for probabilistic rewards (usually b/ of safety constraint) + rngKey, rngSubKey = jaxRandom.split(rngKey) + reward, nextBeliefNode = getNextBeliefNodeAndReward(availableActions, possibleFailures, systemF, systemParametersTuple, rewardF, estimatorF, + physicalStateSubEstimatorF, physicalStateJacobianF, beliefTuple, action, decisionNode, nextObservation,rngSubKey) + + ##THIS ISN'T NEEDED ANYMORE.... and isn't used in the safety proof. Need to re-run? + ##Safety early return + #if reward<=0: #If we violate safety constraints, the reward is set to 0 (or a negative penalty) + # maxReward=1 #Always true at time of writing, in future if we want to allow rewards to be greater than 1, + # return reward - maxReward * depth #subtracts off max possible reward from previous states on this trajectory, ensuring it is negative overall + # #So any unsafe trajectory is automatically worse than any safe one. + + #Simulate forward and collect future reward + futureReward = simulate(nextBeliefNode,nMaxDepth,discretization,explorationParameter, + availableActions,possibleFailures,systemF,systemParametersTuple,discountFactor, + rewardF,estimatorF,physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF, + depth=depth+1,rngKey=rngKey) #Don't need to split key since we don't re-use it or loop + + #Get discounted reward for future beliefs + reward = reward + futureReward*discountFactor + + #Update visit at this root node and chosen decision node by 1 NOTE: THIS IS A CHANGE FROM V1, WHICH UPDATED THE BELIEF NODE, BEFORE THE ACTION WAS PICKED + rootNode.nVisits += 1 + decisionNode.nVisits += 1 + + #Update value of the decision node + decisionNode.value += (reward-decisionNode.value)/decisionNode.nVisits + + return reward + +def getNextBeliefNodeAndReward(availableActions, possibleFailures, systemF, systemParametersTuple, rewardF, estimatorF, physicalStateSubEstimatorF, + physicalStateJacobianF, beliefTuple, action, decisionNode, nextObservation,rngKey): + """ + Helper method to get look through the existing belief nodes, creating a new one as needed, to match the new observation. + + Returns the next belief node and the corresponding reward. + """ + observationIdx = decisionNode.getIdxOfBeliefChild(nextObservation) + + #Check if this is a new observation! + if observationIdx == -1: + #Add to the decision node's children a new belief node! + #Update belief tuple + nextBeliefTuple = estimatorF(action,nextObservation,beliefTuple,possibleFailures,systemF,systemParametersTuple,physicalStateSubEstimatorF,physicalStateJacobianF) + #We now allow for probabilistic rewards (usually b/ of safety constraint) + reward = rewardF(nextBeliefTuple,rngKey) + + nextBeliefNode = BeliefNode(nextObservation,reward,nextBeliefTuple,availableActions) + decisionNode.children.append(nextBeliefNode) + + else: + #Get the belief node + nextBeliefNode = decisionNode.children[observationIdx] + reward = nextBeliefNode.reward + return reward,nextBeliefNode + +#MASSIVE speed up, 2.5x faster (leverages the filter arrays) +@partial(jax.jit, static_argnames=['systemF','physicalStateSubEstimatorSampleF']) +def simulateHelperFunction(action,possibleFailures,beliefTuple,systemF,systemParametersTuple,physicalStateSubEstimatorSampleF,discretization,rngKey): + """ + Performs the simulation step of POMCP in a compiled fashion + + Parameters + ---------- + values : array, shape(len(availableActions)) + Values of each possible action's decision node. + visits : array, shape(len(availableActions)) + Visits to each possible action's decision node. + explorationParameter : float + Weighting on exploration vs. exploitation + nVisitsParent : int + Number of visits to the parent belief node + + Returns + ------- + actionIdx : int + Index of the action to take. Since decisionNodeIdxes is sorted the same as availableActions, this corresponds to the index of decisionNodeIdxes that gives the node index of the decision node. + """ + + failureWeightsIdx = 0 + filtersIdx = 1 + + #Pick failure from possible, weighted by current belief + rngKey,rngSubKey = jaxRandom.split(rngKey) #Make rngSubKey, as consumed on use + failureIdx = jaxRandom.choice(rngSubKey,len(possibleFailures),p=beliefTuple[failureWeightsIdx]) + failureStateSample = possibleFailures[failureIdx] + + #Now use the filter to sample x + rngKey,rngSubKey = jaxRandom.split(rngKey) #Make rngSubKey, as consumed on use + physicalStateSample = physicalStateSubEstimatorSampleF(beliefTuple[filtersIdx][failureIdx],rngSubKey) + #IDEA: Make filters a 3D array. 1st axis, filter, 2nd and 3rd are concatenated array of mean AND covariance. Sub index later! + + #Now simulate the action forward + rngKey,rngSubKey = jaxRandom.split(rngKey) #Make rngSubKey, as consumed on use + dummy,dummy,nextObservation = systemF(physicalStateSample,failureStateSample,action,rngSubKey,systemParametersTuple) #We don't care about next physical state or the next failure state + + #Discretize the observation + discretizationArray = jax.vmap(discretize, in_axes=[0, None]) + nextObservation = discretizationArray(nextObservation,discretization) + return nextObservation + +@jax.jit +def selectBestActionIndex(values,visits,explorationParameter,nVisitsParent,): + """ + Choses best action to take according to the POMCP value function + + Parameters + ---------- + values : array, shape(len(availableActions)) + Values of each possible action's decision node. + visits : array, shape(len(availableActions)) + Visits to each possible action's decision node. + explorationParameter : float + Weighting on exploration vs. exploitation + nVisitsParent : int + Number of visits to the parent belief node + + Returns + ------- + actionIdx : int + Index of the action to take. Since decisionNodeIdxes is sorted the same as availableActions, this corresponds to the index of decisionNodeIdxes that gives the node index of the decision node. + """ + + #Get values using auto vectorization (note nVisitsParent and exploration parameter are not batched) + batchValue = jax.vmap(pomcpValueFunction, in_axes=[None, 0, 0, None]) + pomcpValues = batchValue(nVisitsParent,visits,values,explorationParameter) + + #Get argmax and return. If there is an exact tie, biases to earlier actions. Because rewards probably aren't exactly the same, not a concern + return jnp.argmax(pomcpValues) + +def pomcpValueFunction(nVisitsParent,nVisitsChild,value,explorationParameter): + """ + Compute the POMCP value function + + Parameters + ---------- + nVisitsParent : int + Number of visits to the parent node so far + nVisitsChild : int + Number of visits to the child node so far (if zero returns inf) + value : float + The average value of the child node so far + explorationParameter : float + Weighting on exploration vs. exploitation + + Returns + ------- + augmentedValue : float + The average value of the child node so far augmented by the exploration term + """ + + #Use where to avoid divide by zero error but remain jittable! + # NOTE: Since we now select zero visit nodes *before* calling pomcpValueFunction, this is probably outdated + # Since it's a public method though, I think it is wise to have this a guard + return jnp.where(nVisitsChild == 0, jnp.inf, value + explorationParameter * jnp.sqrt(jnp.log(nVisitsParent)/nVisitsChild)) + + + +def discretize(value,discretization): + """ + Function to discretize the value to specified level + + Parameters + ---------- + value : float + Value to be discretized + discretization : float + Discretization size + + Returns + ------- + discreteValue : float + Discretized value + """ + + return discretization * jnp.round(value/discretization) + +#UNUSED +#@jax.jit +def hashableRepresentation(array): + """ + Method that turns an array to a format that is hashable. + + Parameters + ---------- + array : array + Array to turn to a hashable representation + + Returns + ------- + hashableRepresentation : hashable + Hashable object that represents the array + """ + + return array.tobytes() + +@jax.jit +def nextObservationInNode(nextObservation,decisionNodeObservationList): + """ + UNUSED, one way to check membership + + Parameters + ---------- + nextObservation : array, shape(numSen) + The observation observed after taking the action at this decision node + decisionNodeObservationList : list + List of observations seen after taking the action of this decision node. + + Returns + ------- + nextObservationInNode : boolean + Whether nextObservation has already been seen (in decisionNodeObservationList) as a result of the action of this decision node + """ + for observation in decisionNodeObservationList: + if jnp.array_equal(observation,nextObservation): + return True + + return False + +def unpackSolverParameters(solverParametersTuple): + """ + Helper method to unpack parameters for readability + """ + #Get start time (for timeout based execution) + startTime = time.time() + + #Get solver parameters + availableActions = solverParametersTuple[0] + discretization = solverParametersTuple[1] + maxSimulationTime = solverParametersTuple[2] + explorationParameter = solverParametersTuple[3] + nMaxDepth = solverParametersTuple[4] + discountFactor = solverParametersTuple[5] + return startTime,availableActions,discretization,maxSimulationTime,explorationParameter,nMaxDepth,discountFactor + +#Adding back in class for stateful computation, tree structure seems unnaturally difficult to work out with out when it can grow arbitrarily, will revisit +class Node: #Base class, we're creating a data structure so we don't need public methods here. pylint: disable=too-few-public-methods + """ + Class representing a Node of the tree search. Parent of decision and belief nodes + """ + + def __init__(self): + """ + Create a node of the tree + """ + self.nVisits = 0.0 #Number of visits to this node + #self.value = 0.0 # average reward + self.children = [] + + +class BeliefNode(Node): + """ + Class representing a belief node in the tree search + """ + + def __init__(self, observation, reward, beliefTuple, availableActions): + """ + Create a belief node of the tree + + Parameters + ---------- + observation : array, shape(numSen) + The observation that led to this belief node (used to map back to this belief node) + reward : float + Value of the belief at this node (according to confidence metric) + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + availableActions : array, shape(maxNumActions,numAct) + Array of actions that can be taken. First action is always null action. + """ + super().__init__() + + self.observation = observation + self.reward = reward + self.availableActions = availableActions + self.beliefTuple = beliefTuple + + #Make children actions. NOTE: We DON'T need to explicitly track the action in the decision nodes, + # as lists are ordered! The index of the node in children is the index of the action in availableActions + for iAction in range(len(availableActions)): #pylint: disable=unused-variable + self.children.append(DecisionNode()) + + def getBestActionIdx(self, explorationParameter=0.0, rngKey=None): + """ + Returns the action with the best (augmented) value function + + Parameters + ---------- + explorationParameter : float (default = 0) + Weighting on exploration vs. exploitation. If 0, no exploration, value function is not augmented. + rngKey : JAX PRNG key (default=None) + Key for the PRNG, to be used to create pseudorandomness. Note, MUST be provided if any actions are untried + + Returns + ------- + actionIdx : int + Index of the action to take. Since decisionNodeIdxes is sorted the same as availableActions, + this corresponds to the index of decisionNodeIdxes that gives the node index of the decision node. + """ + + #Get the values and visits to each child (use numpy for mutability then convert to jax) + values = onp.zeros(len(self.availableActions)) + visits = onp.zeros(len(self.availableActions)) + #Iterate over the children and add to the list + for iChild, child in enumerate(self.children): + values[iChild] = child.value + visits[iChild] = child.nVisits + + values = jnp.array(values) + visits = jnp.array(visits) + + #Check if any have zero visits, if so return one of those randomly. Seems to cause about a 25% slow down in POMCP speed, but much better performance. 63 sims/s vs 85 sims/s + #Jitting recovers almost all of the speed 83 sims/s, 85 sims/s, with improved performance. + if jnp.any(visits == 0): + numZero = int(len(visits) - jnp.count_nonzero(visits)) + return getRandomZeroVisitsIdxHelperFunction(rngKey,visits,numZero) + + #jitted POMCP value function + return selectBestActionIndex(values,visits,explorationParameter,self.nVisits,) + + def getMostVisitedAction(self): + """ + Returns the action that was selected the most + + Returns + ------- + bestAction : array, shape(numAct) + Action to take next based on POMCP value function + """ + #Iterate over every child node + mostVisitedActionIdx = None #Strictly I don't think this line is needed + mostVisits = -1*jnp.inf + for iChild, child in enumerate(self.children): + visits = child.nVisits + if visits > mostVisits: + mostVisits = visits + mostVisitedActionIdx = iChild + + return self.availableActions[mostVisitedActionIdx] + +@partial(jax.jit, static_argnames=['numZero']) +def getRandomZeroVisitsIdxHelperFunction(rngKey,visits,numZero): + """ + Helper function to randomly select an idex from the decision nodes with zero visits + + Parameters + ---------- + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + visits : array, shape(len(availableActions)) + Visits to each possible action's decision node. + numZero : int + Number of zero visit actions + + Return + ------ + indexAction : int + Index of the action that hasn't been visited to try + """ + #jnp.asarray(visits == 0).nonzero() finds sets elements to 1 if visits == 0, 0 if not, and then returns the indices of the nonzero elements, in a tuple, so access it (since 1D) + return jaxRandom.choice(rngKey,jnp.asarray(visits == 0).nonzero(size=numZero)[0]) + +class DecisionNode(Node): #We're creating a data structure so we don't need many public methods here. pylint: disable=too-few-public-methods + """ + Class representing a decision node in the tree search + """ + + def __init__(self): + """ + Create a decision node of the tree + """ + super().__init__() + + #Initially we have no idea of the value + self.value = 0 + + def getIdxOfBeliefChild(self, observation): + """ + Method to determine if this observation has been seen before from this decision node, and return the resulting child if so + + Parameters + ---------- + observation : array, shape(numSen) + The observation seen from this decision node + + Returns + ------- + beliefChildIdx : int + Index of the child this observation corresponds to. -1 if no child matches + """ + + #Loop through children + for iChild, child in enumerate(self.children): + if jnp.all(child.observation == observation): + return iChild + + #If we fail to find it, new child! + return -1 diff --git a/failurePy/solvers/scp.py b/failurePy/solvers/scp.py new file mode 100644 index 0000000..c40f93b --- /dev/null +++ b/failurePy/solvers/scp.py @@ -0,0 +1,690 @@ +""" +Sequential Convex Programming (SCP) Baseline. + +Adapted from an implementation originally authored by Ben Riviere +""" +#Baselines were not developed to coding style +# pylint:skip-file + +import jax.numpy as jnp +from jax import random as jaxRandom +import numpy as onp +import cvxpy as cp + +#import plotter +#from controllers.controller import Controller +#from util import make_interp + +#Hack to make this work, not generally applicable +from failurePy.models.threeDOFModel import dynamicsDerivatives as threeDOFDynamicDerivatives +from failurePy.models.threeDOFModel import actionDynamicsJacobian as threeDOFActionDynamicsJacobian + + +def solveForNextAction(beliefTuple,solverParametersTuple,possibleFailures,systemF,systemParametersTuple,rewardF,estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,nSimulationsPerTree,rngKey): + """ + Function that takes in the current belief tuple, parameters, possible failures and system to determine the next best action to take. + Uses the SFEAST algorithm + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + solverParametersTuple : tuple + List of solver parameters needed. Contents are: + numActuators : int + + safetyFunctionF : float + + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + systemF : function + Function reference of the system to call to run experiment. Not used here, but provided to make compatible with marginal filter + systemParametersTuple : tuple + Tuple of system parameters needed. See the model being used for details. (ie, linearModel) + Abstracted for the system function + rewardF : function + Reward function to evaluate the beliefs with + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Function to update all of the conditional position filters + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + nSimulationsPerTree : int + Number of max simulations per tree for the solver to search + rngKey : JAX PRNG key + Key for the PRNG, to be used to create pseudorandomness + + Returns + ------- + action : array, shape(numAct) + Action to take next + rootNode : BeliefNode + Root node of the tree that is now expanded to amount requested (N trajectories) + """ + + #Unpack + safetyFunctionF,numAct,horizon, actuationLimit = unpackSolverParameters(solverParametersTuple) + + + #We sample over possible actions that might satisfy cbf + + #Outline of function. + # Compute ML failure. In event of a tie (such as at initial state), select randomly + # Sample within actuation limits (thinking setting any actuator to +/- 5 m/s^2 influence, since empirically, velocity usually below 10m/s^2 + # Compute nominal next state given the most likely failure + # see if satisfies hcbf(next state) > hcbf(current state), hcbf = h * (10-||v||) -> safe + velocity bounded + # If fails bound, keep if violation is less than previous best. Resample up to 100 times + # Use smallest violation if failed to find an action that satisfies the bound. + # Actually, just set hcbf to h, and progressively widen a until we find one that works or until we have widened 100 times. + + + #Get ML failure + failureWeights = beliefTuple[0] + + mostLikelyFailuresIdxes = jnp.argwhere(failureWeights == jnp.amax(failureWeights)) + #print(len(mostLikelyFailuresIdxes),mostLikelyFailuresIdxes) + #Dealing with possible ties/lack there of + if len(mostLikelyFailuresIdxes) > 1: + #Pick random most likely failure and assume this to be the dynamics + mostLikelyFailuresIdx = jaxRandom.choice(rngKey,mostLikelyFailuresIdxes)[0] + #When there are nans (estimator has diverged), the length will be zero, so we'll just pick a failure at random again + #Using isnan over len(mostLikelyFailuresIdxes) == 0, as we dont' want to ignore a different sort of error + elif jnp.isnan(jnp.amax(failureWeights)): + mostLikelyFailuresIdx = jaxRandom.choice(rngKey,jnp.arange(len(failureWeights))) + else: + mostLikelyFailuresIdx = mostLikelyFailuresIdxes[0,0] + + mostLikelyFailure = possibleFailures[mostLikelyFailuresIdx] + #Need to assume a state. Idea, propagate posterior of this failure and require up to 2 sigma (95%!) to be safe? + # Downside: why not just use full failure and propagate action? Maybe we should? Could re-use our chebyshev bound? With random observations/noise? + + #Best plan so far, select action, simulate 100 times on state/failure sampled from initial belief, evaluate average hcbf as approximate hcbf, check if + + #Now get ML state (first row of associated filter) + assumedState = beliefTuple[1][mostLikelyFailuresIdx,0] + + action = scpSolveForNextAction(assumedState,mostLikelyFailure, systemF, systemParametersTuple, safetyFunctionF,physicalStateJacobianF,numAct,horizon,actuationLimit) + return action, None #No tree to return + +def scpSolveForNextAction(assumedState,mostLikelyFailure, systemF,systemParametersTuple, safetyFunctionF,physicalStateJacobianF,numAct,horizon,actuationLimit): + """ + Re-implementation of the scp solver to re-solve at every time step. Not constrained on the terminal state + + """ + + #No goal state + xSolution, uSolution, tSolution, scpPlotInfo = solveFiniteHorizonSafeOptControlProb(assumedState, 0, mostLikelyFailure, systemF, systemParametersTuple, safetyFunctionF,physicalStateJacobianF,numAct,horizon,actuationLimit) + #Now always returning valid control, but it might be empty + #if xSolution is None: + # return onp.nan * onp.array(numAct) + + #self.scp_plot_info = scpPlotInfo + #if self.debugPlotFlag: self.plot_scp(scpPlotInfo) + return uSolution[0] + + +# finite horizon terminal constraint optimal control problem: FHTCOCP +def solveFiniteHorizonSafeOptControlProb(x0, t0, mostLikelyFailure, systemF, systemParametersTuple, safetyFunctionF,physicalStateJacobianF,numAct,horizon,actuationLimit, eta=2, verbose=False): + """ + Solve the scp problem + + Parameters + ---------- + x0 : array, shape(numStates) + Initial condition + t0 : float + Initial time + systemParametersTuple : tuple + Tuple of system parameters needed. Assumed to be 3DOF nonlinear system + Contents are in order: + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + + Returns + ------- + + """ + + dt = systemParametersTuple[6] + + tSolution = onp.arange(t0, horizon, dt) + nonLinearCorrectionFlag = False + + #Guess unforced trajectory + xReference, uReference = initialNoForceGuess(tSolution, x0, numAct,mostLikelyFailure,systemF,systemParametersTuple) + xSolutionsList = [xReference] + uSolutionsList = [uReference] + virtualControlMagnitudeList = [] + xDifferenceList = [] + status = "running" + maxNumIter = 20 + #Start with no virtual control, since initial guess shouldn't need it + #print(onp.shape(xReference),onp.shape(uReference),onp.shape(x0)) + if verbose: + print("xRef: ",xReference) + print("uRef: ",uReference) + virtualControl = onp.zeros((len(tSolution),len(x0))) + for k in range(maxNumIter): + if verbose: + print("scp iter: {}/{}".format(k, maxNumIter)) + xSolution, uSolution, virtualControl, dummyTimeSolution = solveLinearizedFiniteHorizonOptControlProb(x0, xReference, uReference, tSolution, eta,systemParametersTuple,actuationLimit,mostLikelyFailure, safetyFunctionF,physicalStateJacobianF,horizon,virtualControl) + if xSolution is None: + status = "failed" + if verbose: + print("scp status: ",status) + print("nextAction: ", uSolution[0]) + break + if nonLinearCorrectionFlag: + xSolution, uSolution = scpRollout(x0, tSolution, uSolution) + if is_converged(xSolution, xReference): + status = "solved" + xDifference = onp.linalg.norm(onp.array(xSolution) - onp.array(xReference), axis=1) + virtualControlMagnitude = onp.linalg.norm(onp.array(virtualControl), axis=1) + xReference, uReference = xSolution, uSolution + #eta = beta * eta + xSolutionsList.append(xReference) + uSolutionsList.append(uReference) + virtualControlMagnitudeList.append(virtualControlMagnitude) + xDifferenceList.append(xDifference) + if status in ["failed","solved"]: + if verbose: + print("scp status: ",status) + print("nextAction: ", uSolution[0]) + break + scp_plot_info = { + "x0" : x0, + "xd" : onp.nan, + "ts" : tSolution, + "xss" : xSolutionsList, + "uss" : uSolutionsList, + "exss" : xDifferenceList, + "vss" : virtualControlMagnitudeList, + } + return xSolution, uSolution, tSolution, scp_plot_info + +def initialNoForceGuess(tSolution, x0, numAct,mostLikelyFailure,systemF,systemParametersTuple): + """ + Makes initial guess of the solution by applying provided control sequences + or modeling as a straight line with no forcing + + Parameters + ---------- + tSolution : float + Time steps the solution should be defined along + x0 : array, shape(numStates) + Initial state + xGoal : array, shape(numStates) + Desired end state + + Returns + ------- + xReference : array, + """ + + # guess (0) straight line, (1) unforced trajectory + # Either way, will put zeros as the reference control + uZero = onp.zeros(numAct) + + K = len(tSolution) + + uReference = [uZero for dummyIdx in range(K)] + xReference, dummyControls = scpRollout(x0, tSolution, uReference,mostLikelyFailure,systemF,systemParametersTuple) + return onp.array(xReference), onp.array(uReference) + +def is_converged(xSolution, xReference): + scale = 1 + tolerance = 1e-2 + scaled_abs_errors = [onp.abs(scale*x - \ + scale*xbar) for (x,xbar) in zip(xSolution, xReference)] + scaled_abs_errors_arr = onp.array(scaled_abs_errors) # nt x n x 1 + return not (onp.sum(scaled_abs_errors_arr > tolerance) > 0) + +# linearized finite horizon terminal constraint optimal control problem: LFHTCOCP +def solveLinearizedFiniteHorizonOptControlProb(x0, xReference, uReference, tSolution, eta,systemParametersTuple,actuationLimit,mostLikelyFailure, safetyFunctionF,physicalStateJacobianF,horizon, virtualControl = None, verbose=False): + """ + Set up and solve cvxpy problem + + Parameters + ---------- + systemParametersTuple : tuple + Tuple of system parameters needed. Assumed to be 3DOF nonlinear system + Contents are in order: + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + """ + + dt = systemParametersTuple[6] + lambdaV = 1 + #set to 1.28155*sigmaW, as this would be 90% threshold if all uncertainty was due to sigmaW + safetyBuffer = 2*1.28155*systemParametersTuple[-2][0,0] #Will take x sigma + + K = len(tSolution) + xSolutionCp = cp.Variable((K, len(x0))) + uSolutionCp = cp.Variable((K, len(uReference[0]))) + virtualControlSolutionCp = cp.Variable((K, len(x0))) # virtual control + + #Warm start to use reference as feasible solution + xSolutionCp.value = xReference + uSolutionCp.value = uReference + if virtualControl is not None: + virtualControlSolutionCp.value = virtualControl + else: + #Might be redundant, but being clear here what the warm start is + virtualControlSolutionCp.value = onp.zeros((K,len(x0))) + + circularObstacleRadius = 10 + circularObstaclePosition = onp.array([0,-20]) + linearSafeZoneNormalMatrix = onp.array([[1,0],[-1,0],[0,1],[0,-1]]) + linearSafeZoneOffsets = onp.array([25,25,25,25]) + + # s cvx + constraints = [] + for k in range(K-1): + # dynamics (virtual control) + A_k, B_k, C_k = singleTaylorExpansion(xReference[k], uReference[k],systemParametersTuple,mostLikelyFailure,physicalStateJacobianF) + Xdot_k = A_k @ xSolutionCp[k,:] + B_k @ uSolutionCp[k,:] + C_k + virtualControlSolutionCp[k,:] + constraints.append( + xSolutionCp[k+1,:] == eulerStep(xSolutionCp[k,:], Xdot_k, dt)) + # trust region + deltaX = cp.norm(xSolutionCp[k,:]-xReference[k,:]) + deltaU = cp.norm(uSolutionCp[k,:]-uReference[k,:]) + constraints.append(deltaX + deltaU <= eta) + # state space (None) + # control space + constraints.append(uSolutionCp[k,:] <= actuationLimit) + constraints.append(uSolutionCp[k,:] >= 0) + + # Safety, buffer is hyperparameter (set to 1.28155*sigmaW, as this would be 90% threshold if all uncertainty was due to sigmaW) + constraints.append(convexifiedCircularObstacleConstraint(xSolutionCp[k,:],xReference[k,:],circularObstacleRadius,circularObstaclePosition) <= -safetyBuffer) + constraints.append(linearSafeZoneConstraint(xSolutionCp[k,:],linearSafeZoneNormalMatrix,linearSafeZoneOffsets) <= -safetyBuffer) + + # initial/terminal constraints + constraints.append(xSolutionCp[0,:] == x0) + #constraints.append(xSolutionCp[-1,:] == xGoal) #unconstrained terminal state + #constraints.append(uSolutionCp[-1,:] == onp.zeros(len(uReference[0]))) + + # augmented cost function + objective = cp.Minimize(cp.sum_squares(uSolutionCp) + lambdaV * cp.norm(virtualControlSolutionCp)) + # objective = cp.Minimize(cp.sum_squares(Vs)) + # objective = cp.Minimize(cp.sum_squares(Us)) + + cvxPyProb = cp.Problem(objective, constraints) + try: + sol = cvxPyProb.solve(solver=cp.CVXOPT, warm_start=True, verbose=verbose) + # sol = prob.solve(solver=cp.GUROBI) + # sol = prob.solve(solver=cp.MOSEK, verbose=True) + if cvxPyProb.status in ["optimal"]: #Is this necessary? Think this might fail now that we removed squeezes + xSolution = xSolutionCp.value + uSolution = uSolutionCp.value + virtualControlSolution = virtualControlSolutionCp.value + #xSolution = [xSolutionCp[k,:][:,onp.newaxis] for k in range(xSolutionCp.shape[0])] + #uSolution = [uSolutionCp[k,:][:,onp.newaxis] for k in range(uSolutionCp.shape[0])] + #vSolution = [virtualControlSolutionCp[k,:][:,onp.newaxis] for k in range(virtualControlSolutionCp.shape[0])] + return xSolution, uSolution, virtualControlSolution, tSolution + else: + if verbose: + print("scp cvx failed to solve, maximizing obstacle safety instead") + print("prob.status: ", cvxPyProb.status) + print("x0: ", x0) + #print("last x: ",xSolutionCp.value) + #print("last u: ", uSolutionCp.value) + #print("last virtualU: ", virtualControlSolutionCp.value) + # print("xbars: ", xbars) + # print("ubars: ", ubars) + # print("ts: ", ts) + except cp.error.SolverError as e: + if verbose: + print("error", e) + #Don't want to return None, as that will just lead to a less helpful error. Will raise instead + #raise ValueError("Solver failed to run") from e + print("scp cvx failed to solve, maximizing obstacle safety instead") + + + + #Try again, maximizing the safety of each time step instead. + # scvx + constraints = [] + for k in range(K-1): + # dynamics (virtual control) + A_k, B_k, C_k = singleTaylorExpansion(xReference[k], uReference[k],systemParametersTuple,mostLikelyFailure,physicalStateJacobianF) + Xdot_k = A_k @ xSolutionCp[k,:] + B_k @ uSolutionCp[k,:] + C_k + virtualControlSolutionCp[k,:] + constraints.append( + xSolutionCp[k+1,:] == eulerStep(xSolutionCp[k,:], Xdot_k, dt)) + # trust region + deltaX = cp.norm(xSolutionCp[k,:]-xReference[k,:]) + deltaU = cp.norm(uSolutionCp[k,:]-uReference[k,:]) + constraints.append(deltaX + deltaU <= eta) + # state space (None) + # control space + constraints.append(uSolutionCp[k,:] <= actuationLimit) + constraints.append(uSolutionCp[k,:] >= 0) + + # Safety, buffer is hyperparameter (set to 1.28155*sigmaW, as this would be 90% threshold if all uncertainty was due to sigmaW) + # Now obstacle is the objective, not a constraint + constraints.append(linearSafeZoneConstraint(xSolutionCp[k,:],linearSafeZoneNormalMatrix,linearSafeZoneOffsets) <= -safetyBuffer) + + # initial/terminal constraints + constraints.append(xSolutionCp[0,:] == x0) + #constraints.append(xSolutionCp[-1,:] == xGoal) #unconstrained terminal state + #constraints.append(uSolutionCp[-1,:] == onp.zeros(len(uReference[0]))) + + # augmented cost function + objective = cp.Minimize(convexifiedCircularObstacleConstraint(xSolutionCp[k,:],xReference[k,:],circularObstacleRadius,circularObstaclePosition) + + lambdaV * cp.norm(virtualControlSolutionCp)) + # objective = cp.Minimize(cp.sum_squares(Vs)) + # objective = cp.Minimize(cp.sum_squares(Us)) + + cvxPyProb = cp.Problem(objective, constraints) + try: + sol = cvxPyProb.solve(solver=cp.CVXOPT, warm_start=True, verbose=verbose) + # sol = prob.solve(solver=cp.GUROBI) + # sol = prob.solve(solver=cp.MOSEK, verbose=True) + if cvxPyProb.status in ["optimal"]: #Is this necessary? Think this might fail now that we removed squeezes + xSolution = xSolutionCp.value + uSolution = uSolutionCp.value + virtualControlSolution = virtualControlSolutionCp.value + #xSolution = [xSolutionCp[k,:][:,onp.newaxis] for k in range(xSolutionCp.shape[0])] + #uSolution = [uSolutionCp[k,:][:,onp.newaxis] for k in range(uSolutionCp.shape[0])] + #vSolution = [virtualControlSolutionCp[k,:][:,onp.newaxis] for k in range(virtualControlSolutionCp.shape[0])] + return xSolution, uSolution, virtualControlSolution, tSolution + except cp.error.SolverError as e: + if verbose: print("error", e) + + if verbose: print("Trying maximizing safe zone safety.") + + + #Finally try solving with obstacle as constraint, and safety zone as objective + + # scvx + constraints = [] + for k in range(K-1): + # dynamics (virtual control) + A_k, B_k, C_k = singleTaylorExpansion(xReference[k], uReference[k],systemParametersTuple,mostLikelyFailure,physicalStateJacobianF) + Xdot_k = A_k @ xSolutionCp[k,:] + B_k @ uSolutionCp[k,:] + C_k + virtualControlSolutionCp[k,:] + constraints.append( + xSolutionCp[k+1,:] == eulerStep(xSolutionCp[k,:], Xdot_k, dt)) + # trust region + deltaX = cp.norm(xSolutionCp[k,:]-xReference[k,:]) + deltaU = cp.norm(uSolutionCp[k,:]-uReference[k,:]) + constraints.append(deltaX + deltaU <= eta) + # state space (None) + # control space + constraints.append(uSolutionCp[k,:] <= actuationLimit) + constraints.append(uSolutionCp[k,:] >= 0) + + # Safety, buffer is hyperparameter (set to 1.28155*sigmaW, as this would be 90% threshold if all uncertainty was due to sigmaW) + # Now obstacle is the objective, not a constraint + constraints.append(convexifiedCircularObstacleConstraint(xSolutionCp[k,:],xReference[k,:],circularObstacleRadius,circularObstaclePosition) <= -safetyBuffer) + #constraints.append(linearSafeZoneConstraint(xSolutionCp[k,:],linearSafeZoneNormalMatrix,linearSafeZoneOffsets) <= -safetyBuffer) + + # initial/terminal constraints + constraints.append(xSolutionCp[0,:] == x0) + #constraints.append(xSolutionCp[-1,:] == xGoal) #unconstrained terminal state + #constraints.append(uSolutionCp[-1,:] == onp.zeros(len(uReference[0]))) + + # augmented cost function + objective = cp.Maximize(cp.sum(linearSafeZoneConstraint(xSolutionCp[k,:],linearSafeZoneNormalMatrix,linearSafeZoneOffsets)) + - lambdaV * cp.norm(virtualControlSolutionCp)) + # objective = cp.Minimize(cp.sum_squares(Vs)) + # objective = cp.Minimize(cp.sum_squares(Us)) + + cvxPyProb = cp.Problem(objective, constraints) + try: + sol = cvxPyProb.solve(solver=cp.CVXOPT, warm_start=True, verbose=verbose) + # sol = prob.solve(solver=cp.GUROBI) + # sol = prob.solve(solver=cp.MOSEK, verbose=True) + except cp.error.SolverError as e: + if verbose: print("error", e) + #Don't want to return None, as that will just lead to a less helpful error. Will raise instead + if verbose: print("Giving up and keeping uReference") + + if cvxPyProb.status in ["optimal"]: #Is this necessary? Think this might fail now that we removed squeezes + xSolution = xSolutionCp.value + uSolution = uSolutionCp.value + virtualControlSolution = virtualControlSolutionCp.value + #xSolution = [xSolutionCp[k,:][:,onp.newaxis] for k in range(xSolutionCp.shape[0])] + #uSolution = [uSolutionCp[k,:][:,onp.newaxis] for k in range(uSolutionCp.shape[0])] + #vSolution = [virtualControlSolutionCp[k,:][:,onp.newaxis] for k in range(virtualControlSolutionCp.shape[0])] + return xSolution, uSolution, virtualControlSolution, tSolution + else: + #Give up and return the reference control and nones + return None, uReference, None, None + + +def convexifiedCircularObstacleConstraint(physicalState,physicalStateRef,radiusObstaclePlusRadiusSpacecraft,center): + """ + Function that enforces a circular obstacle constraint. + + Parameters + ---------- + physicalState : array, shape(numState) + Physical state of the system to evaluate constraints against. + NOTE: Assumed to be a double integrator state, so for example, we have x, vx, y, vy, ... + Only the position for each dimension (x,y,...) will be used to determine collision. + The first len(center) dimensions will be checked for collision, in the same order + radiusObstaclePlusRadiusSpacecraft : float + Radius of obstacle AND the spacecraft. This is because this is the closest the centers can come to each other. + center : array, shape(numDimensionsObstacle) + The center of the obstacle. Length of this will be used to determine how many dimensions to check + + Returns + ------- + constraintReturn : int + If 0 or greater, constraint is violated. + """ + #Get the positions out of the physical state + positionSpaceCraft = getLinearPositionSpaceCraft(physicalState) + positionSpaceCraftRef = getLinearPositionSpaceCraft(physicalStateRef) + + #Convexified constraint + return radiusObstaclePlusRadiusSpacecraft*cp.norm(positionSpaceCraftRef-center) - (positionSpaceCraftRef-center).T @ (positionSpaceCraft - center) + #Non-convex + ##If within radius, positive, so violated + #return radiusObstaclePlusRadiusSpacecraft - cp.norm(center-positionSpaceCraft) + +def getLinearPositionSpaceCraft(physicalState): + """ + Gets the dimensions of the spacecraft's position that are relevant to a constraint we are evaluating, which is on linear position + Assumes 2 wheels, 2 linear axes, and 1 rotation axis + + Parameters + ---------- + physicalState : array, shape(numState) + Physical state of the system to evaluate constraints against. + NOTE: Assumed to be a double integrator state, so for example, we have x, vx, y, vy, ... + Only the position for each dimension (x,y,...) will be used to determine collision. + The first len(center) dimensions will be checked for collision, in the same order + + Returns + ------- + positionSpaceCraft : array, shape(numDimensionsObstacle) + The relevant position of the SpaceCraft to evaluate the constraint against + """ + + pickOutLinearPositionMatrix = onp.array([[1,0,0,0,0,0,0,0], + [0,0,1,0,0,0,0,0]]) + #For hardware w/o wheels. TODO: make this configurable + #pickOutLinearPositionMatrix = onp.array([[1,0,0,0,0,0], + # [0,0,1,0,0,0]]) + + return pickOutLinearPositionMatrix @ physicalState #Need to use @ for cvxpy + + +def linearSafeZoneConstraint(physicalState,normalMatrix,offsetVector): + """ + Function that enforces a (convex) composition of linear safe zone constraints on the position. + Defined as Ax - b < 0 for each constraint. We require every constraint is satisfied for safety, + so return the worst case (most positive or max) from each line + + + Parameters + ---------- + physicalState : array, shape(numState) + Physical state of the system to evaluate constraints against. + NOTE: Assumed to be a double integrator state, so for example, we have x, vx, y, vy, ... + Only the position for each dimension (x,y,...) will be used to determine collision. + The first len(center) dimensions will be checked for collision, in the same order + normalMatrix : array, shape(numConstraints,numDimensionsObstacle) + A Matrix defining the normal vector of each constraint + offsetVector : array, shape(numConstraints) + b Vector defining the offset from the origin of each constraint + + Returns + ------- + worstConstraint : float + If 0 or greater, at least one constraint is violated. + """ + #Get the positions out of the physical state + positionSpaceCraft = getLinearPositionSpaceCraft(physicalState) + + constraintEvaluation = normalMatrix @ positionSpaceCraft - offsetVector + + #If outside safe zone, one of these will be positive + return constraintEvaluation + + + +def singleTaylorExpansion(xReference, uReference,systemParametersTuple,mostLikelyFailure,physicalStateJacobianF): + """ + Taylor expansion of the dynamics + A = jacobian of the dynamics with respect to x, at xReference, uReference + B = jacobian of the dynamics with respect to u, at xReference, uReference + C = difference between non-linear and linearized dynamics. xdot = f(x,u) = Ax + Bu + C. Used for "virtual control" to provide a non-linear correction, I think. + + Parameters + ---------- + systemParametersTuple : tuple + Tuple of system parameters needed. Assumed to be 3DOF nonlinear system + Contents are in order: + positionInfluenceMatrix : array, shape(2, numThrusters) + Bp matrix. Influence of the thrusters on the position scaled by mass. We choose to break these out so we can deal with rotation of body frame + rotationInfluenceMatrix : array, shape(numThrusters) + Br matrix. Influence of the thrusters on the rotation scaled by moment. We choose to break these out so we can deal with rotation of body frame + reactionWheelInfluenceMatrix : array, shape(numWheels) + G*Jw matrix. Influence of reaction wheels on the rotation (they don't affect position). We choose to break these out so we can deal with rotation of body frame and stored momentum. + For 3DOF this is just the ones array + positionCoefficientOfFriction : float + Coefficient of friction that would be in the Ap matrix. Each axis is assumed to be the same coefficient of friction + rotationalCoefficientOfFriction : float + Coefficient of friction that would be in the Ar matrix. Since this can vary independent of the position coefficient (for example, based on pad spacing) as it yields a torque, + we report it separately. We could instead deal with the lever arms, but this is easier and more robust + sensingMatrix : array, shape(numSen, numState) + C matrix + dt : float + The time between time steps of the experiment + covarianceQ : array, shape(numState,numState) + Covariance of the dynamics noise. + covarianceR : array, shape(numSen,numSen) + Covariance of the sensing noise. + + """ + #print(onp.shape(xReference),onp.shape(mostLikelyFailure),onp.shape(uReference)) + A = physicalStateJacobianF(xReference,mostLikelyFailure, uReference,systemParametersTuple) + B = threeDOFActionDynamicsJacobian(xReference,mostLikelyFailure,systemParametersTuple) + numAct = len(uReference) + realizedAction = jnp.matmul(jnp.diag(mostLikelyFailure[0:numAct]),uReference) + positionInfluenceMatrix = systemParametersTuple[0] + rotationInfluenceMatrix = systemParametersTuple[1] + reactionWheelInfluenceMatrix = systemParametersTuple[2] + + C = threeDOFDynamicDerivatives(xReference,realizedAction,positionInfluenceMatrix,rotationInfluenceMatrix,reactionWheelInfluenceMatrix,0,0)\ + - A @ xReference\ + - B @ uReference + return onp.array(A), onp.array(B), onp.array(C) + +def eulerStep(X_k, Xdot_k, dt): + """ + Forward Euler approximation of system dynamics + """ + + X_kp1 = X_k + Xdot_k * dt + return X_kp1 + +def scpRollout(x0, tSolution, uSequence,mostLikelyFailure,systemF,systemParametersTuple): + """ + Rolls out the sequence of controls provided + + Parameters + ---------- + x0 : array, shape(numStates) + Initial state + tSolution : array, shape(numTimeSteps) + Times steps to roll out at + uSequence : array, shape(numTimeSteps,numActuators) + Controls to apply at each timeStep + + Returns + ------- + xSolution : array, shape(numTimeSteps,numStates) + Resulting sequence of states from the control sequence and initial conditions + uSequence : array, shape(numTimeSteps,numActuators) + Controls to apply at each timeStep + """ + # xs = [x0] + # for k, t in enumerate(ts[0:-1]): + for kTimeStep, t in enumerate(tSolution): + if kTimeStep == 0: + xSolution = [x0] + else: + #Nominal propagation, so dummy key + rngKey = jaxRandom.PRNGKey(0) + nextPhysicalState,dummyFailureState,dummyNextObservation = systemF(xSolution[-1],mostLikelyFailure,uSequence[kTimeStep-1],rngKey,systemParametersTuple,noisyPropagationBooleanInt=0) + xSolution.append(nextPhysicalState) + return onp.array(xSolution), uSequence + +def unpackSolverParameters(solverParametersTuple): + """ + Helper method to unpack parameters for readability + """ + + #Get solver parameters + numAct = solverParametersTuple[0] + safetyFunctionF = solverParametersTuple[1] + horizon = solverParametersTuple[2] + actuationLimit = solverParametersTuple[3] + + return safetyFunctionF,numAct,horizon, actuationLimit diff --git a/failurePy/utility/__init__.py b/failurePy/utility/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/failurePy/utility/binaryVisualization.py b/failurePy/utility/binaryVisualization.py new file mode 100644 index 0000000..f410bcc --- /dev/null +++ b/failurePy/utility/binaryVisualization.py @@ -0,0 +1,80 @@ +""" +File with useful functions for visualizing and understanding bit manipulation in python, especially since it only mimics C integers +""" + +import numpy as onp + +def displayTwosComp(intValue, nBits): + """ + Displays the value in twos complement notation for an integer (which python mimics when doing bitwise operations), with the specified number of bits + """ + print(getTwosCompString(intValue, nBits)) + +#Adapted from https://stackoverflow.com/questions/1604464/twos-complement-in-python to display easier +def getTwosCompString(intValue, nBits): + """ + Compute the 2's complement of intValue. Recall the nBits INCLUDES the sign bit, so we will fake it in display + + Checks bit limits, which is a bit of a slow down but displays -1 right now. + """ + if (intValue > 2**(nBits-1) -1) or (intValue < - (2**(nBits-1)) ): + print(f"Int {intValue} outside number of range of values for a signed int given the specified nBits {- (2**(nBits-1)) } - {2**(nBits-1) -1}, behavior is undefined") + + #Doesn't work with jax... just going to avoid binary ops here, this isn't speed critical + ##Check for issues with bit limits + #atBitLimitFlag = False + #print(type(intValue), nBits) + #if nBits >=8: + # if isinstance(intValue, (onp.int8,jnp.int8)): + # if nBits > 8: + # print(f"nBits is greater than the size of the integer (8 bit), errors will occur with negative numbers") + # else: + # atBitLimitFlag = True + #elif nBits >=16: + # print("Should be here") + # if isinstance(intValue, (onp.int16,jnp.int16)): + # if nBits > 16: + # print(f"nBits is greater than the size of the integer (16 bit), errors will occur with negative numbers") + # else: + # atBitLimitFlag = True + #elif nBits >=32: + # if isinstance(intValue, (onp.int32,jnp.int32)): + # if nBits > 32: + # print(f"nBits is greater than the size of the integer (32 bit), errors will occur with negative numbers") + # else: + # atBitLimitFlag = True + #elif nBits >=64: + # if isinstance(intValue, (onp.int64,jnp.int64)): + # if nBits > 64: + # print(f"nBits is greater than the size of the integer (64 bit), errors will occur with negative numbers") + # else: + # atBitLimitFlag = True + digits = nBits+2 + if intValue < 0: + #MSB is the sign bit, and need to watch out for overflow, so just add half at a time + #We will fake the sign bit + intValue = 2**(nBits-2) + intValue + intValue = 2**(nBits-2) + intValue + #This also doesn't work because jax (and maybe numpy too) casts down to the smaller int size, and 2**nBits is outside of that! + #intValue = 2**nBits + intValue + #This doesn't work if at limit of integer, so will just non binary op version + #intValue = (1 << nBits) + intValue + returnString = format(intValue,f'#0{digits}b') + #Fake the sign bit + return returnString[:2] +'1' + returnString[3:] + + if (intValue & (1 << (nBits - 1))) != 0: + # If sign bit is set. + # compute negative value. + intValue = intValue - (1 << nBits) + + return format(intValue,f'#0{digits}b') + +def displayVectorTwosComp(intArray, nBits): + """ + Displays an integer array in twos complement notation + """ + outputList = [] + for intValue in intArray: + outputList.append(getTwosCompString(intValue, nBits)) + print(onp.array(outputList)) diff --git a/failurePy/utility/comb.py b/failurePy/utility/comb.py new file mode 100644 index 0000000..9d02d0b --- /dev/null +++ b/failurePy/utility/comb.py @@ -0,0 +1,25 @@ +""" +Simple combinatorial implementation that should be integer exact +""" + +import math + +#Math expression so allowing single letter names +def comb(n,k): # pylint: disable=disallowed-name,invalid-name + """ + N choose k + + Parameters + ---------- + N : int + Number of items to choose from + k : int + Number of items to choose + + Returns + ------- + nChooseK : int + Number of combinations of k items from N totalW + """ + + return math.factorial(n)/(math.factorial(k)*math.factorial(n-k)) diff --git a/failurePy/utility/compareData.py b/failurePy/utility/compareData.py new file mode 100644 index 0000000..55dc17d --- /dev/null +++ b/failurePy/utility/compareData.py @@ -0,0 +1,78 @@ +""" +File that has functions for comparing data between test results + +""" + +import os +import subprocess +from tqdm import tqdm + +def checkIfResultsAreConsistent(absoluteExperimentSavedDataDirectory1,absoluteExperimentSavedDataDirectory2): + """ + Method that checks if the data in two saved experiment directories math. + Useful for checking if two versions of the simulation pipeline are interchangeable + Note checks at the experiment level directly + """ + + #Check if trial nums match + trials1 = next(os.walk(absoluteExperimentSavedDataDirectory1))[1] + trials2 = next(os.walk(absoluteExperimentSavedDataDirectory2))[1] + consistent = True + + #Only check one way + print(f"Checking consistency of the trials found in {absoluteExperimentSavedDataDirectory1} with those found in {absoluteExperimentSavedDataDirectory2}") + if len(trials1) != len(trials2): + if len(trials1) > len(trials2): + print(f"{absoluteExperimentSavedDataDirectory1} has more trials than {absoluteExperimentSavedDataDirectory2}") + consistent = False + else: + print(f"{absoluteExperimentSavedDataDirectory1} has less trials than {absoluteExperimentSavedDataDirectory2}") + consistent = False + for trial in tqdm(trials1): + #Check if the same trial is in trials2 + if not trial in trials2: + print(f"Trial {trial} in {absoluteExperimentSavedDataDirectory1} not found in {absoluteExperimentSavedDataDirectory2}") + consistent = False + continue + try: + dataDict1StringPath = os.path.join(absoluteExperimentSavedDataDirectory1,trial,"trialData.txt") + with open(dataDict1StringPath, "rb") as trialDataFile: + data1DictString = trialDataFile.read() + #Check if data is in 2, then check data + try: + data2DictStringPath = os.path.join(absoluteExperimentSavedDataDirectory2,trial,"trialData.txt") + with open(data2DictStringPath, "rb") as trialDataFile: + data2DictString = trialDataFile.read() + #Iterate through all the stuff in the dict + if data1DictString[:-20] != data2DictString[:-20]: #Hack to ignore wall clock time data + print(f"Trial {trial}'s data in {absoluteExperimentSavedDataDirectory1} and {absoluteExperimentSavedDataDirectory2} is inconsistent") + #print(git.diff("--no-index",data1DictString,data2DictString)) + #gitOutput = subprocess.Popen([f"git diff --no-index {dataDict1StringPath} {data2DictStringPath}"], cwd=os.getcwd(), stdout=subprocess.PIPE) + #NOTE shell=True is unsafe in general (if dataDict1StringPath or dataDict3StringPath are provided by arbitrary, malicious inputs) but safe here since we control input + with subprocess.Popen([f"git diff --no-index {dataDict1StringPath} {data2DictStringPath}"], shell=True, stdout=subprocess.PIPE) as gitOutput: + while gitOutput.poll() is None: #Loop until terminated + print(gitOutput.stdout.readline()) + consistent = False + + except FileNotFoundError: + print(f"Trial {trial} in {absoluteExperimentSavedDataDirectory1} has data, but no data exists in {absoluteExperimentSavedDataDirectory2}") + consistent = False + except FileNotFoundError: + try: + #Just checking if we can read the second file, not going to use it + data2DictStringPath = os.path.join(absoluteExperimentSavedDataDirectory2,trial,"trialData.txt") + with open(data2DictStringPath, "rb") as trialDataFile: + dummyData2DictString = trialDataFile.read() + print(f"Trial {trial} in {absoluteExperimentSavedDataDirectory1} does not have any data, but data does exist in {absoluteExperimentSavedDataDirectory2}") + consistent = False + except FileNotFoundError: + pass #consistent at least if they both don't have it + + if consistent: + print("All data is consistent!") + + +if __name__ == "__main__": + EXPERIMENT_SAVED_DATA_PATH_1 = "/home/ragan/CaltechVersionFailurePy/probabilistic_planning_v2/failurePy/SavedData/linearSafetyMultiTest/SFEAST/200" + EXPERIMENT_SAVED_DATA_PATH_2 = "/home/ragan/CaltechVersionFailurePy/probabilistic_planning_v2/failurePy/SavedData/linearSafetyTest3/SFEAST/200" + checkIfResultsAreConsistent(EXPERIMENT_SAVED_DATA_PATH_1,EXPERIMENT_SAVED_DATA_PATH_2) diff --git a/failurePy/utility/computeAlternateReward.py b/failurePy/utility/computeAlternateReward.py new file mode 100644 index 0000000..93d2361 --- /dev/null +++ b/failurePy/utility/computeAlternateReward.py @@ -0,0 +1,155 @@ +"""" +Function to compute a different reward metric given the trial data. Uses the fact the beliefs are saved to reprocess +""" + +import os +#from functools import partial +import pickle +import numpy as onp + +from tqdm import tqdm +#import jax +import jax.numpy as jnp + +from failurePy.utility.reprocessData import confirmDataDeletion, reprocessTrialDataDicts +from failurePy.rewards.squareSumFailureBeliefReward import squareSumFailureBeliefReward + + +#@partial(jax.jit, static_argnames=['rewardF']) +def computeAlternateReward(trialResultsDict, rewardF): + """ + Computes the new reward given a trialDataDict. Currently doesn't support approximate chance constraint evaluation + """ + + beliefList = trialResultsDict["beliefList"] + + altRewards = onp.zeros(len(beliefList)) + for iReward, belief in enumerate(beliefList): + altRewards[iReward] = rewardF(belief) + + trialResultsDict["altRewards"] = altRewards + + return trialResultsDict + + +def makeAlternativeRewardReprocessor(rewardF): + """ + Constructor for making reprocessing function. Doing this to fit into reprocessData modular design + """ + + def alternativeRewardReprocessorF(trialResultsDict): + return computeAlternateReward(trialResultsDict, rewardF) + + return alternativeRewardReprocessorF + + +def processAlternativeRewardsAverages(saveDirectoryAbsolutePath): + """ + Adds alternative rewards averages to existing data averages + + Parameters + ---------- + saveDirectoryAbsolutePath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + """ + + #Get all the solvers using os walk + solverNamesList = next(os.walk(saveDirectoryAbsolutePath))[1] + #Get the experiments (different number of trials) + solverDirectoryPath = os.path.join(saveDirectoryAbsolutePath, solverNamesList[0]) + #Using numpy to cast strings to ints then to jax + nSimulationsPerTrees = jnp.array(onp.array(next(os.walk(solverDirectoryPath))[1], dtype=onp.int32)) + #And get number of simulations per point + nSimPath = os.path.join(solverDirectoryPath, str(nSimulationsPerTrees[0])) + trialRandomSeeds = next(os.walk(nSimPath))[1] + nTrialsPerPoint = len(trialRandomSeeds) + #Get number of time steps + trialDataPath = os.path.join(nSimPath, str(trialRandomSeeds[0]), "trialData.dict") + with open(trialDataPath, "rb") as trialDataFile: + trialDataDict = pickle.load(trialDataFile) + numTimeSteps = len(trialDataDict["altRewards"]) + + #Now we can loop + for solverName in solverNamesList: + solverDirectoryPath = os.path.join(saveDirectoryAbsolutePath, solverName) + + #Loop through each number of sims per tree + for nSimulationsPerTree in nSimulationsPerTrees: + nSimPath = os.path.join(solverDirectoryPath, str(nSimulationsPerTree)) + #Array to average over (use onp for mutability later when plotting or otherwise) + avgAltRewards = onp.zeros(numTimeSteps) + varAltRewards = onp.zeros(numTimeSteps) + #Not going to include points where the reward diverged in variance calculation + numNonNans = onp.zeros(numTimeSteps) + #Loop through each trial (Might be inefficient? Will check later) + try: + for trialRandomSeed in tqdm(trialRandomSeeds): + trialDataPath = os.path.join(nSimPath, str(trialRandomSeed), "trialData.dict") + with open(trialDataPath, "rb") as trialDataFile: + trialDataDict = pickle.load(trialDataFile) + #Check for nans + trialDataDict["altRewards"][onp.isnan(trialDataDict["altRewards"])] = 0 + avgAltRewards = onp.add(avgAltRewards, trialDataDict["altRewards"]) + #Use fact reward is only zero if we just set it to 0 because of nan, otherwise strictly positive + numNonNans = onp.add(numNonNans, onp.sign(trialDataDict["altRewards"])) + except ValueError as arrayError: + tooManyAltRewards = f"too many alt rewards found in {trialDataPath}" + raise ValueError(tooManyAltRewards) from arrayError + #Average for this experiment + avgAltRewards = avgAltRewards / nTrialsPerPoint + + #Compute variance as well (need to already know the average rewards, so have to loop again) + + for trialRandomSeed in tqdm(trialRandomSeeds): + trialDataPath = os.path.join(nSimPath, str(trialRandomSeed), "trialData.dict") + with open(trialDataPath, "rb") as trialDataFile: + trialDataDict = pickle.load(trialDataFile) + #Check for nans, in this case, we set them to the *average* (so variance isn't effected, since already taking the skipped ones into account) + trialDataDict["altRewards"][onp.isnan(trialDataDict["altRewards"])] = avgAltRewards[onp.isnan(trialDataDict["altRewards"])] + + #Only update variance if not nan (as will be 0 if it was nan) + varAltRewards = onp.add(varAltRewards,onp.square(jnp.subtract(trialDataDict["altRewards"], avgAltRewards)),) + + #Add to average data dict and save + experimentAvgDataPath = os.path.join(nSimPath, "averageData.dict") + with open(experimentAvgDataPath, "rb") as experimentAvgDataFile: + experimentAvgDataDict = pickle.load(experimentAvgDataFile) + experimentAvgDataDict["avgAltRewards"] = avgAltRewards + experimentAvgDataDict["varAltRewards"] = onp.divide(varAltRewards, numNonNans - 1) #Each time step could have different non-nans + + with open(experimentAvgDataPath, "wb") as experimentAvgDataFile: + experimentAvgDataDict = pickle.dump(experimentAvgDataDict, experimentAvgDataFile) + + +def computeAlternativeRewardsThroughout(absoluteSavedDataPath, alternativeRewardReprocessorF, force=False): + """ + Computes alternative reward based on the last belief in the specified directory, and also logs the first time the system becomes unsafe + + Parameters + ---------- + absoluteSavedDataPath : string + Absolute path to directory where we will recompute success based on the last belief + """ + + if force or confirmDataDeletion(absoluteSavedDataPath, "any previous alternative reward"): + reprocessTrialDataDicts(absoluteSavedDataPath, alternativeRewardReprocessorF) + + #Add altRewards to the averages. + processAlternativeRewardsAverages(absoluteSavedDataPath) + else: + print("The alternate rewards will not be updated") + + +def computeSquareSumFailureBeliefRewardAlternativeThroughout(absoluteSavedDataPath,force=False): + """ + Computes alternative reward as squareSumFailureBeliefReward + """ + + computeAlternativeRewardsThroughout(absoluteSavedDataPath,alternativeRewardReprocessorF=makeAlternativeRewardReprocessor(squareSumFailureBeliefReward),force=force) + + +if __name__ == "__main__": + SAVED_DATA_DIRECTORY = None #SET TO THE DIRECTORY YOU WISH TO COMPUTE THE ALTERNATIVE REWARD IN + + + computeSquareSumFailureBeliefRewardAlternativeThroughout(SAVED_DATA_DIRECTORY,force=True) diff --git a/failurePy/utility/computePartialTrial.py b/failurePy/utility/computePartialTrial.py new file mode 100644 index 0000000..67fe4f6 --- /dev/null +++ b/failurePy/utility/computePartialTrial.py @@ -0,0 +1,193 @@ +""" +Module for considering only a sub part of a trial, useful for reprocessing the extended trials in to shorter experiments + +Will also support changing handling of fault divergence and re-running trials as needed +""" +import os +import pickle +import multiprocessing as mp + +import jax.numpy as jnp + +from failurePy.pipeline import multiprocessingMain, setUpMultiPRocessing +from failurePy.utility.pipelineHelperMethods import diagnoseFailure +from failurePy.utility.reprocessData import reprocessDataAverages, runNewExperimentsWithOldData +from failurePy.utility.computeAlternateReward import computeSquareSumFailureBeliefRewardAlternativeThroughout + + + +def computeAllPartialTrials(originalExperimentAbsoluteSavedDataPath,newExperimentAbsoluteSavedDataPath, subHorizonTimeSteps, reRunFilterDivergence=True, + reRunDivergenceHandlingMethod="acceptDiagnosisBeforeNan"): + """ + Looks at existing (and already safety processed) trials to consider first subHorizonTimeSteps (plus initial condition). + + Recomputes success based on the last belief in the specified directory, and also logs the first time the system becomes unsafe + + Parameters + ---------- + absoluteSavedDataPath : string + Absolute path to directory where we will recompute success based on the last belief + """ + + computePartialTrialF=makeComputePartialTrialF(subHorizonTimeSteps, reRunFilterDivergence) +# + #Updates to the experiment parameters dict to save + inputUpdateDict = {} + inputUpdateDict["saveDirectoryPath"] = newExperimentAbsoluteSavedDataPath + inputUpdateDict["filterDivergenceHandlingMethod"] = reRunDivergenceHandlingMethod + inputUpdateDict["diagnosisThreshold"] = 1.9 #Overloaded so we accept if we are above 1.9-1 .9 confidence when we diverge. Adding to configs of extended exp (since it doesn't chance anything) + inputUpdateDict["nExperimentSteps"] = subHorizonTimeSteps +# +# + returnCode = runNewExperimentsWithOldData(originalExperimentAbsoluteSavedDataPath, computePartialTrialF, + newExperimentAbsoluteSavedDataPath=newExperimentAbsoluteSavedDataPath,inputUpdateDict=inputUpdateDict) +# + if returnCode == -1: + #Aborted + return + + #Recompute the averages using the saved config file! + #Need to do this first as the alt rewards assumes this exists + reprocessDataAverages(os.path.join(newExperimentAbsoluteSavedDataPath, "config.yaml")) #Abs path in the config files + + #Recompute last free colli + + #Compute alt rewards here! Since we already got the success (and are assuming safety was already computed on the full trials)\ + computeSquareSumFailureBeliefRewardAlternativeThroughout(newExperimentAbsoluteSavedDataPath,force=True) + + +def makeComputePartialTrialF(subHorizonTimeSteps, reRunFilterDivergence): + """ + Constructor for partial trail runner + """ + def computePartialTrialF(trialDataPath,experimentParamsDict,newExperimentAbsoluteSavedDataPath): + return computePartialTrial(trialDataPath,experimentParamsDict,newExperimentAbsoluteSavedDataPath, subHorizonTimeSteps, reRunFilterDivergence) + return computePartialTrialF + +def computePartialTrial(trialDataPath,inputDict,newExperimentAbsoluteSavedDataPath, subHorizonTimeSteps, reRunFilterDivergence=True): + """ + Abridges Trial to just the horizon requested. If the filter has diverged at this point, re-runs the trial using + method to deal with the divergence + + Parameters + ---------- + trialDataPath : string + Path to trial data, useful because it contains the rng seed used for this trial + inputDict + Yaml load of experiment parameters + newExperimentAbsoluteSavedDataPath : string + Absolute path to directory where we should save modified (or rerun) trailData.dict files. + subHorizonTimeSteps : int + The number of time steps in this re-processed dict (should be saved to new location to avoid loosing data!) + reRunFilterDivergence : Boolean (default=True) + If true, will re-run any trials where the filter diverges before the end of the time period + """ + + #Load dictionary + with open(trialDataPath, "rb") as trialDataFile: + trialResultsDict = pickle.load(trialDataFile) + #Reprocess! (And Rerun if needed) + + #Need to get relative path. Could probably be more efficient by just using string ops directly + dictNameAndPathTuple = os.path.split(trialDataPath) + trialNameAndPathTuple = os.path.split(dictNameAndPathTuple[0]) + subExpNameAndPathTuple = os.path.split(trialNameAndPathTuple[0]) + solverNameAndPathTuple = os.path.split(subExpNameAndPathTuple[0]) + #expNameAndPathTuple = os.path.split(solverNameAndPathTuple[0]) + #New path + newTrialDataPath = os.path.join(newExperimentAbsoluteSavedDataPath,solverNameAndPathTuple[1], + subExpNameAndPathTuple[1],trialNameAndPathTuple[1],dictNameAndPathTuple[1]) + + + + #First check if filter diverged at end of desired horizon + if jnp.isnan(trialResultsDict["rewards"][subHorizonTimeSteps+1]) and reRunFilterDivergence: + #Should we dispatch this as a sub process??? No collision with other processes + #Handle with new method, will call pipeline with modified config + #will modify experiment parameters a little and hand to pipeline's running method + inputDict["nSimulationsPerTree"] = [int(subExpNameAndPathTuple[1])] + inputDict["nTrialsPerPoint"] = 1 + inputDict["multiprocessingFlag"] = False #Shouldn't matter here + inputDict["rngKeysOffset"] = int(trialNameAndPathTuple[1]) + print(f"Re Running {inputDict['nSimulationsPerTree']} {inputDict['rngKeysOffset']}") + #NOT using multiprocessingQueue + process = mp.Process(target=multiprocessingMain,args=(inputDict,newExperimentAbsoluteSavedDataPath,None,False),daemon=True) + #All seem to die, not sure why + #process = mp.Process(target=runExperimentsAndLog,args=(experimentParamsDict,newExperimentAbsoluteSavedDataPath,True),daemon=True) + return process #Dict will be saved when this ends, calling method handles process joining + #runExperimentsAndLog(experimentParamsDict,newExperimentAbsoluteSavedDataPath,True) + #return None + + #Otherwise, abridging existing data + + #Abridge, first check it isn't already shorter due to early termination + originalHorizonTimeStepsPlusOne = len(trialResultsDict["physicalStateList"]) + if originalHorizonTimeStepsPlusOne < subHorizonTimeSteps+1: + trialResultsDict["rewards"] = trialResultsDict["rewards"][subHorizonTimeSteps+1:] + return trialResultsDict + for key in trialResultsDict.keys(): + if key in ("success", "wallClockTime"): + #Will update at the end or assume average is still good + continue + if key == "steps":#This is the nominal time steps (not including the +1 for the initial time steps. Consider it transitions only) + trialResultsDict[key] = subHorizonTimeSteps + elif key == "lastBelievedCollisionFreeTStep": + #Need to check if this is after new end + trialResultsDict[key] = min(trialResultsDict[key],subHorizonTimeSteps) + else: + #print(key) want everything up to our sub horizon (+1) + trialResultsDict[key] = trialResultsDict[key][:subHorizonTimeSteps+1] + + #Update success of trials + trialResultsDict = updateSuccessStatusOfTrialDataDict(trialResultsDict) + + rewards = trialResultsDict["rewards"] + #Loop through and see when we become unsafe (die and stay dead logic) + lastBelievedCollisionFreeTStep = -1 + for reward in rewards: + if reward == 0: + break + lastBelievedCollisionFreeTStep += 1 + trialResultsDict["lastBelievedCollisionFreeTStep"] = lastBelievedCollisionFreeTStep + with open(newTrialDataPath,'wb') as trialDataFile: + pickle.dump(trialResultsDict,trialDataFile) + #And update human readable copy + trialDataTextPath = os.path.splitext(newTrialDataPath)[0]+'.txt' + with open(trialDataTextPath, "w",encoding="UTF-8") as textFile: + textFile.write(str(trialResultsDict)) + + #Now we don't need to return anything, dict is saved + return None # No process + +def updateSuccessStatusOfTrialDataDict(trialResultsDict): + """ + Recomputes success based on the last belief of this trial + + Parameters + ---------- + trialResultsDict : dict + trial data we will recompute the success on + """ + + #Get the beliefList last entry and true failure + lastBelief = trialResultsDict["beliefList"][-1] + failure = trialResultsDict["failureStateList"][-1] + + #Get predicted failure + diagnosis = diagnoseFailure(lastBelief, trialResultsDict["possibleFailures"]) + + if jnp.all(diagnosis == failure): + trialResultsDict["success"] = 1 + else: + trialResultsDict["success"] = 0 + + return trialResultsDict + + +if __name__ == "__main__": + setUpMultiPRocessing() #THIS IS ESSENTIAL TO AVOID HANGING! + SAVED_DATA_DIRECTORY = None #SET TO THE DIRECTORY OF THE ORIGINAL EXPERIMENT YOU WANT TO TAKE A PARTIAL TRIAL FROM + + NEW_DATA_DIRECTORY = None #SET TO THE DIRECTORY YOU WISH TO SAVE THE OUTPUT DATA TO + + computeAllPartialTrials(originalExperimentAbsoluteSavedDataPath=SAVED_DATA_DIRECTORY,newExperimentAbsoluteSavedDataPath=NEW_DATA_DIRECTORY, subHorizonTimeSteps=15) diff --git a/failurePy/utility/computeSuccessAtEnd.py b/failurePy/utility/computeSuccessAtEnd.py new file mode 100644 index 0000000..4f9c80f --- /dev/null +++ b/failurePy/utility/computeSuccessAtEnd.py @@ -0,0 +1,58 @@ +""" +Function that processes data and gives a success code of 1 to any trial where the most likely final failure scenario is correct (matches the true underlying failure) + +Intended for experiments where terminating early is inappropriate/not checked for (like safety), but where the success code was set to nan for not terminating by mistake + +WARNING! Deletes data (as we will no longer be able to distinguish if the experiment terminated early or not, although this could be recovered if we know what the threshold was) +""" + +import os + +from failurePy.utility.reprocessData import reprocessDataAverages, confirmDataDeletion, reprocessTrialDataDicts +from failurePy.utility.saving import updateSuccessStatusAndSafetyOfTrialDataDict, updateSuccessStatusOfTrialDataDict + +def updateSuccessStatus(absoluteSavedDataPath): + """ + Recomputes success based on the last belief in the specified directory + + Parameters + ---------- + absoluteSavedDataPath : string + Absolute path to directory where we will recompute success based on the last belief + """ + + #Guard on user confirmation + if confirmDataDeletion(absoluteSavedDataPath, "early termination success"): + reprocessTrialDataDicts(absoluteSavedDataPath, updateSuccessStatusOfTrialDataDict) + + #Recompute the averages using the saved config file! + reprocessDataAverages(os.path.join(absoluteSavedDataPath, "config.yaml"),os.path.dirname(os.path.dirname(absoluteSavedDataPath))) + else: + print("The success statuses will not be updated") + + +def updateSuccessStatusAndSafetyThroughout(absoluteSavedDataPath,force=False): + """ + Recomputes success based on the last belief in the specified directory, and also logs the first time the system becomes unsafe + + Parameters + ---------- + absoluteSavedDataPath : string + Absolute path to directory where we will recompute success based on the last belief + """ + #Guard on user confirmation + if force or confirmDataDeletion(absoluteSavedDataPath, "early termination success"): + reprocessTrialDataDicts(absoluteSavedDataPath, updateSuccessStatusAndSafetyOfTrialDataDict) + + #Recompute the averages using the saved config file! + reprocessDataAverages(os.path.join(absoluteSavedDataPath, "config.yaml"),os.path.dirname(os.path.dirname(absoluteSavedDataPath))) + else: + print("The success statuses will not be updated") + +if __name__ == "__main__": + + SAVED_DATA_DIRECTORY = None #SET TO THE DIRECTORY YOU WISH TO COMPUTE THE SUCCESS AT THE END OF + + + #updateSuccessStatus(SAVED_DATA_DIRECTORY) + updateSuccessStatusAndSafetyThroughout(SAVED_DATA_DIRECTORY, force=True) diff --git a/failurePy/utility/dataAnalysisFunctions.py b/failurePy/utility/dataAnalysisFunctions.py new file mode 100644 index 0000000..e7e3044 --- /dev/null +++ b/failurePy/utility/dataAnalysisFunctions.py @@ -0,0 +1,937 @@ +""" +Module containing various functions for post processing data, such as performing safety metric analysis +""" + + +import os + +import pickle +from tqdm import tqdm +import numpy as onp +import matplotlib.pyplot as plt + +import jax.random as jaxRandom + +from failurePy.load.yamlLoaderUtilityMethods import getInputDict +from failurePy.load.safetyLoader import loadSafetyModulatedRewardComponents +from failurePy.load.systemConstructors import loadAndBuildSingleAgentSystem +from failurePy.load.yamlLoader import loadEstimatorAndBelief +from failurePy.rewards.safetyConstraint import makeProbabilisticAlphaSafetyFunctionEvaluation + +# Data loader for reward plotting + + +def loadDataSummaryFromSaveDirectory(savedDataDirPath, experimentName,solverNames,cumulativeFlag=False,baselineExpName=None,altRewardFlag=True,): #Alt way to plot only some experimentIndexes=None): + """ + Method to load saved data that is reused by several functions + + This is an alternate method from loadDataSummary in failurePy.visualization.visualization + due data location being required parameter, both provide same returns. + + Parameters + ---------- + savedDataDirPath : str + Absolute path of the saved data. + experimentName : str + Name of the experiment (top level saved data directory) + solverNames : list + List of the names of each solver that was used + cumulativeFlag : boolean (default=False) + If true, plot the cumulative reward + baselineExpName : str (default=None) + If provided, loads in additional solver experiments that are all baselines (1 nSim per tree, always 1) + altRewardFlag : str (default=False) + If true, looks for alternative reward data instead of the default. Incompatible with cumulative sum currently. Does not check for existence first + + Returns + ------- + nSimulationsPerTrees : array, shape(numNSimulationsPerTrees) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + nTrialsPerPoint : int + The number of repeated trials per configuration. + avgRewards : array, shape(numSolvers,numNSimulationsPerTrees,numExperimentSteps+1) + The average rewards for each solver and number of simulations per tree, for each time step (including initial time) + avgSuccessRates : array, shape(numSolvers,numNSimulationsPerTrees) + The average success rate for each solver and number of simulations per tree + avgWallClockTimes : array, shape(numSolvers,numNSimulationsPerTrees) + The average time for each solver and number of simulations per tree + avgSteps : array, shape(numSolvers,numNSimulationsPerTrees) + The average steps for each solver and number of simulations per tree + sigmaRewards : array, shape(numSolvers,numNSimulationsPerTrees) + The 1 sigma bounds for the rewards + """ + + #First we need to collect the data + experimentDataDirPath = os.path.join(savedDataDirPath,experimentName) + + #Check if there is a baseline directory to load from too + if baselineExpName is not None: + baselineExperimentDataDirPath = os.path.join(savedDataDirPath,baselineExpName) + baselineSolverNames = next(os.walk(baselineExperimentDataDirPath))[1] + #Hack to sort baselines consistently (will format when plotting legend) + if "greedy" in baselineSolverNames and "cbf" in baselineSolverNames and "scp" in baselineSolverNames: + baselineSolverNames = ["greedy", "cbf", "scp"] + + + numBaselines = len(baselineSolverNames) + solverNames += baselineSolverNames #Updates solverNames by reference! + else: + numBaselines = 0 + + #We take for granted that the number of simulations per trees is the same for each solver, as is the number of trials per point. If this is None, haven't found them yet + nSimulationsPerTrees = None + nTrialsPerPoint = None + + for iSolver, solverName in enumerate(solverNames): + solverDirectoryPath = getSolverDirectoryPath(iSolver,solverNames,numBaselines,baselineExperimentDataDirPath,experimentDataDirPath,solverName) + + if nSimulationsPerTrees is None: + nSimulationsPerTrees = getNSimulationsPerTrees(solverDirectoryPath) + + for jNSimsPerTreeExperiment, nSimulationsPerTree in enumerate(nSimulationsPerTrees): + #Initialize average data arrays if we haven't yet + if nTrialsPerPoint is None: + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + nTrialsPerPoint = len(onp.array(next(os.walk(nSimPath))[1])) + + #Load first data dict + experimentAverageDataDict = loadExperimentAverageDataDict(nSimPath) + + #Now initialize the average data now that we know the number of experiments + avgRewards = onp.zeros((len(solverNames),len(nSimulationsPerTrees),len(experimentAverageDataDict["avgRewards"]))) + avgSuccessRates = onp.zeros((len(solverNames),len(nSimulationsPerTrees))) + avgWallClockTimes = onp.zeros((len(solverNames),len(nSimulationsPerTrees))) + avgSteps = onp.zeros((len(solverNames),len(nSimulationsPerTrees))) + sigmaRewards = onp.zeros((len(solverNames),len(nSimulationsPerTrees),len(experimentAverageDataDict["avgRewards"]))) + #Baselines load a little different (SUPER HACKY) + elif iSolver > 0 and jNSimsPerTreeExperiment == 0: + nSimPath = os.path.join(solverDirectoryPath,str(1)) #Always 1 for baselines + experimentAverageDataDict = loadExperimentAverageDataDict(nSimPath) + #Fill baselines with nans for other "num sims per tre" SUPER HACKY here, just trying to quickly plot. + elif iSolver > 0: + avgSuccessRates[iSolver,jNSimsPerTreeExperiment] += onp.nan + avgWallClockTimes[iSolver,jNSimsPerTreeExperiment] += onp.nan + avgSteps[iSolver,jNSimsPerTreeExperiment] += onp.nan + avgRewards[iSolver,jNSimsPerTreeExperiment] += onp.nan + sigmaRewards[iSolver,jNSimsPerTreeExperiment] += onp.nan + continue #Don't load anything + #Otherwise just load + else: + #Load data dict + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + experimentAverageDataDict = loadExperimentAverageDataDict(nSimPath) + + + #print(experimentAverageDataDict) + + #In either case, get data + loadExperimentAverageData(experimentAverageDataDict,avgSuccessRates,avgWallClockTimes,avgSteps,avgRewards,sigmaRewards,cumulativeFlag, + altRewardFlag,iSolver,jNSimsPerTreeExperiment) + + return nSimulationsPerTrees, nTrialsPerPoint, avgRewards, avgSuccessRates, avgWallClockTimes, avgSteps, sigmaRewards + +def getSolverDirectoryPath(iSolver,solverNames,numBaselines,baselineExperimentDataDirPath,experimentDataDirPath,solverName): + """ + Helper method to generate solver path + """ + if iSolver >= len(solverNames) - numBaselines: + solverDirectoryPath = os.path.join(baselineExperimentDataDirPath,solverName) + else: + solverDirectoryPath = os.path.join(experimentDataDirPath,solverName) + + if not os.path.exists(solverDirectoryPath): + raise FileNotFoundError(f"Directory {solverDirectoryPath} not found, check if the correct save directory and experiment are given") + + return solverDirectoryPath + +def getNSimulationsPerTrees(solverDirectoryPath): + """ + Helper method to load NSimulations per trees from folder names + """ + #Get nSimulationsPerTrees using os.walk to read the directory names + nSimulationsPerTrees = onp.array(next(os.walk(solverDirectoryPath))[1]) + nSimulationsPerTrees = nSimulationsPerTrees.astype(int) + nSimulationsPerTrees = onp.sort(nSimulationsPerTrees) + return nSimulationsPerTrees + +def getTrialNumbers(nSimPath): + """ + Helper method to load nTrialsPerPoint from the folders present + """ + #Get nTrialsPerPoint + trialNumbers = onp.array(next(os.walk(nSimPath))[1]) + nTrialsPerPoint = len(trialNumbers) + #Sorts the trial numbers so we have consistency (incase that matters) + return onp.sort(trialNumbers),nTrialsPerPoint + +def loadExperimentAverageDataDict(experimentPath): + """ + Helper method to load average data from a given experiment path + """ + + experimentDataPath = os.path.join(experimentPath,"averageData.dict") + with open(experimentDataPath,'rb') as experimentDataFile: + experimentAverageDataDict = pickle.load(experimentDataFile) + return experimentAverageDataDict + +def loadTrialDataDict(trialPath): + """ + Helper method to load trial data dict + """ + trialDataPath = os.path.join(trialPath, "trialData.dict") + with open(trialDataPath, "rb") as trialDataFile: + trialDataDict = pickle.load(trialDataFile) + return trialDataDict + + +def loadExperimentAverageData(experimentAverageDataDict,avgSuccessRates,avgWallClockTimes,avgSteps,avgRewards,sigmaRewards,cumulativeFlag, + altRewardFlag,iSolver,jNSimsPerTreeExperiment): + """ + Helper method to load the data for a given trial, and make adjustments if needed + """ + + avgSuccessRates[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["avgSuccessRate"] + avgWallClockTimes[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["avgWallClockTime"] + avgSteps[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["avgSteps"] + if cumulativeFlag: + #If EKF diverged = failure (also need to make sure success set to 0) + experimentAverageDataDict["cumulativeAvgRewards"][onp.isnan(experimentAverageDataDict["cumulativeAvgRewards"])] = 0 + + avgRewards[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["cumulativeAvgRewards"] + sigmaRewards[iSolver,jNSimsPerTreeExperiment] = onp.sqrt(experimentAverageDataDict["cumulativeVarRewards"]) + elif altRewardFlag: + #If EKF diverged = failure (also need to make sure success set to 0) + experimentAverageDataDict["avgAltRewards"][onp.isnan(experimentAverageDataDict["avgAltRewards"])] = 0 + + avgRewards[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["avgAltRewards"] + sigmaRewards[iSolver,jNSimsPerTreeExperiment] = onp.sqrt(experimentAverageDataDict["varAltRewards"]) + else: + #If EKF diverged = failure (also need to make sure success set to 0) + experimentAverageDataDict["avgRewards"][onp.isnan(experimentAverageDataDict["avgRewards"])] = 0 + + avgRewards[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["avgRewards"] + sigmaRewards[iSolver,jNSimsPerTreeExperiment] = onp.sqrt(experimentAverageDataDict["varRewards"]) + +def trialSuccessRatesAndFaultSpaceErrors(savedDataDirAbsolutePath, experimentName,solverNames,perTimeStep=False,faultDistances=False,stride=10, #pylint: disable=too-many-branches,too-many-statements + clearCache=False): #Letting this be a do everything method, and conditionally create arrays pylint: disable=too-many-branches,too-many-statements,too-many-nested-blocks,possibly-used-before-assignment + """ + Finds the success rates (correct diagnoses at the end) as well as the fault space distances for each trial + """ + #First we need to collect the data + experimentDataDirAbsolutePath = os.path.join(savedDataDirAbsolutePath,experimentName) + + #Check for caches + if cacheDict := getFaultSpaceErrorCache(experimentDataDirAbsolutePath, perTimeStep, stride, clearCache): + return cacheDict + + nSimulationsPerTrees = None + nTrialsPerPoint = None + + for iSolver, solverName in enumerate(solverNames): #pylint: disable=too-many-nested-blocks + solverDirectoryPath = getSolverDirectoryPath(iSolver,solverNames,numBaselines=0,baselineExperimentDataDirPath=None,experimentDataDirPath=experimentDataDirAbsolutePath,solverName=solverName) + + if nSimulationsPerTrees is None: + nSimulationsPerTrees = getNSimulationsPerTrees(solverDirectoryPath) + + for jNSimsPerTreeExperiment, nSimulationsPerTree in enumerate(nSimulationsPerTrees): + #Initialize average data arrays if we haven't yet + if nTrialsPerPoint is None: + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + trialNumbers, nTrialsPerPoint = getTrialNumbers(nSimPath) + #Now initialize the data now that we know the number of experiments + if perTimeStep: + kTrialPath = os.path.join(nSimPath, str(trialNumbers[0])) + trialDataDict = loadTrialDataDict(kTrialPath) + numExperimentTimeSteps = len(trialDataDict["beliefList"]) + numTimeStepsToAnalyze = min(int(numExperimentTimeSteps/stride) + 1, numExperimentTimeSteps) # Only add one when stride !=1 + diagnosisSuccess = onp.zeros((len(solverNames),len(nSimulationsPerTrees),nTrialsPerPoint,numTimeStepsToAnalyze)) + diagnosisErrors = onp.zeros((len(solverNames),len(nSimulationsPerTrees),nTrialsPerPoint,numTimeStepsToAnalyze)) + diagnosisConfidences = onp.zeros((len(solverNames),len(nSimulationsPerTrees),nTrialsPerPoint,numTimeStepsToAnalyze)) + if faultDistances: #Kind of expensive to compute, lots of looping + avgFaultDistances = onp.zeros((len(solverNames),len(nSimulationsPerTrees),nTrialsPerPoint,numTimeStepsToAnalyze)) + minFaultDistances = onp.zeros((len(solverNames),len(nSimulationsPerTrees),nTrialsPerPoint,numTimeStepsToAnalyze)) + else: + avgFaultDistances = None + minFaultDistances = None + + else: + diagnosisSuccess = onp.zeros((len(solverNames),len(nSimulationsPerTrees),nTrialsPerPoint)) + diagnosisErrors = onp.zeros((len(solverNames),len(nSimulationsPerTrees),nTrialsPerPoint)) + diagnosisConfidences = onp.zeros((len(solverNames),len(nSimulationsPerTrees),nTrialsPerPoint)) + if faultDistances: #Kind of expensive to compute, lots of looping + avgFaultDistances = onp.zeros((len(solverNames),len(nSimulationsPerTrees),nTrialsPerPoint)) + minFaultDistances = onp.zeros((len(solverNames),len(nSimulationsPerTrees),nTrialsPerPoint)) + else: + avgFaultDistances = None + minFaultDistances = None + #Load data for each trial + for kTrial,trialNumber in tqdm(enumerate(trialNumbers)): + kTrialPath = os.path.join(nSimPath, str(trialNumber)) + trialDataDict = loadTrialDataDict(kTrialPath) + if perTimeStep: + failureParticles = trialDataDict["possibleFailures"] #Initial possible failures + trueFault = trialDataDict["failureStateList"][0] #Assumed unchanging + jAnalysisStep = 0 + for iTimeStep in range(numExperimentTimeSteps): + #Check if we re-weighted + if len(trialDataDict["beliefList"][iTimeStep]) == 3: + failureParticles = trialDataDict["beliefList"][iTimeStep][2] + #Check if we should analyze this point + if iTimeStep % stride != 0: + continue + #Fix zero looking right because all equal weight + if iTimeStep == 0: + #Kinda hacky, but should work without loss of generality + # Just set diagnosis to second particles, as this is randomly selected, so should average out + faultWeights = onp.array([0,1]) + else: + faultWeights = trialDataDict["beliefList"][iTimeStep][0] #Fault weights are 0th position in the belief tuple + + #Get the metrics + diagnosis = failureParticles[onp.argmax(faultWeights)] + #We assume the failure state doesn't change, but taking last to be general incase this changes + diagnosisErrors[iSolver,jNSimsPerTreeExperiment,kTrial,jAnalysisStep] = onp.linalg.norm(trueFault - diagnosis) #pylint: disable=possibly-used-before-assignment + diagnosisSuccess[iSolver,jNSimsPerTreeExperiment,kTrial,jAnalysisStep] = (diagnosisErrors[iSolver,jNSimsPerTreeExperiment,kTrial,jAnalysisStep] < .01) #pylint: disable=possibly-used-before-assignment + diagnosisConfidences[iSolver,jNSimsPerTreeExperiment,kTrial,jAnalysisStep] = onp.max(faultWeights) #pylint: disable=possibly-used-before-assignment + if faultDistances: #Kind of expensive to compute, lots of looping + avgFaultDistance = 0 + minFaultDistance = onp.inf + for faultParticle in failureParticles: + faultDistance = onp.linalg.norm(faultParticle-trueFault) + avgFaultDistance += faultDistance + if 0 < faultDistance < minFaultDistance: + minFaultDistance = faultDistance + #Note when one of the particle is the true particle, this will be lower than when none are + avgFaultDistances[iSolver,jNSimsPerTreeExperiment,kTrial,jAnalysisStep] = avgFaultDistance/(len(failureParticles)) #pylint: disable=possibly-used-before-assignment + minFaultDistances[iSolver,jNSimsPerTreeExperiment,kTrial,jAnalysisStep] = minFaultDistance #pylint: disable=possibly-used-before-assignment + jAnalysisStep += 1 + + else: + #If we re-sample the failure particles, these are included in the belief tuple as the 2 index, so check for these, + # otherwise use possible failures, the initial failure particles + #Loop backwards! + for iTimeStep in range(len(trialDataDict["beliefList"])): + if len(trialDataDict["beliefList"][-iTimeStep-1]) == 3: + failureParticles = trialDataDict["beliefList"][-iTimeStep-1][2] + break + #In python else is only entered if we DON'T break + else: + failureParticles = trialDataDict["possibleFailures"] + + #While converging to the first fault indicates correct diagnosis when the fault is in the failure state, since we have access to the fault directly, will use general case + #Will consider a distance of <.01 in fault space as converged + #The diagnosis is the most likely fault in the final belief + faultWeights = trialDataDict["beliefList"][-1][0] #Fault weights are 0th position in the belief tuple + diagnosis = failureParticles[onp.argmax(faultWeights)] + #We assume the failure state doesn't change, but taking last to be general incase this changes + diagnosisErrors[iSolver,jNSimsPerTreeExperiment,kTrial] = onp.linalg.norm((trueFault := trialDataDict["failureStateList"][-1]) - diagnosis) + diagnosisSuccess[iSolver,jNSimsPerTreeExperiment,kTrial] = (diagnosisErrors[iSolver,jNSimsPerTreeExperiment,kTrial] < .01) + diagnosisConfidences[iSolver,jNSimsPerTreeExperiment,kTrial] = onp.max(faultWeights) + if faultDistances: #Kind of expensive to compute, lots of looping + avgFaultDistance = 0 + minFaultDistance = onp.inf + for faultParticle in failureParticles: + faultDistance = onp.linalg.norm(faultParticle-trueFault) + avgFaultDistance += faultDistance + if 0 < faultDistance < minFaultDistance: + minFaultDistance = faultDistance + #Note when one of the particle is the true particle, this will be lower than when none are + avgFaultDistances[iSolver,jNSimsPerTreeExperiment,kTrial] = avgFaultDistance/(len(failureParticles)) + minFaultDistances[iSolver,jNSimsPerTreeExperiment,kTrial] = minFaultDistance + + #Cache data so we only need to do this once + faultDataDict = makeFaultDataDict(diagnosisSuccess,diagnosisErrors,diagnosisConfidences,avgFaultDistances, minFaultDistances,stride) + if perTimeStep: + cacheData(experimentDataDirAbsolutePath, faultDataDict, cacheName="faultSpaceErrorPerTimeStepDataCache.dict") + else: + cacheData(experimentDataDirAbsolutePath, faultDataDict, cacheName="faultSpaceFinalErrorDataCache.dict") + + return faultDataDict + +def makeFaultDataDict(diagnosisSuccess,diagnosisErrors,diagnosisConfidences,avgFaultDistances, minFaultDistances,stride): + """ + Makes a dictionary of the computed data for caching and to return + """ + return {"diagnosisSuccess": diagnosisSuccess, + "diagnosisErrors": diagnosisErrors, + "diagnosisConfidences": diagnosisConfidences, + "avgFaultDistances": avgFaultDistances, + "minFaultDistances": minFaultDistances, + "stride": stride} #only matters on per time step data + +def getFaultSpaceErrorCache(experimentDataDirAbsolutePath, perTimeStep, stride, clearCachedData=False): # pylint: disable=too-many-nested-blocks + """ + Checks for already existing safety data cache + """ + if not clearCachedData: # pylint: disable=too-many-nested-blocks + try: + if perTimeStep: + faultSpaceErrorCachePath = getCachePath(experimentDataDirAbsolutePath, "faultSpaceErrorPerTimeStepDataCache.dict") + else: + faultSpaceErrorCachePath = getCachePath(experimentDataDirAbsolutePath, "faultSpaceFinalErrorDataCache.dict") + with open(faultSpaceErrorCachePath, "rb") as safetyCacheFile: + cacheDict = pickle.load(safetyCacheFile) + #Check if we are consistent on per time step or not + # Check consistency in time scale (only applies if we are per time step) + if perTimeStep and cacheDict["stride"] != stride: + #Okay if we can get subset of date with this stride. + # This is the case if the current stride is larger than the cached one and is divided evenly by the caches one + if stride % cacheDict["stride"] == 0: + #In this case, get the sub set + cacheStride = int(stride / cacheDict["stride"]) + for key in cacheDict.keys(): + if key == "stride" or cacheDict[key] is None: + continue + cacheDict[key] = cacheDict[key][:,:,:,::cacheStride] + else: + mismatchedCache = (f"Cache at {faultSpaceErrorCachePath} has an inconsistent stride ({cacheDict['stride']})" + + f" than the provided stride {stride}. Use a compatible stride or set clearCachedData to True") + raise ValueError(mismatchedCache) + except FileNotFoundError: + cacheDict = None + else: + cacheDict = None + return cacheDict + +def plotComparisonMetricsAvgsAlongTime(savedDataDirPath, experimentNameRoot,solverNames,dataAnalysisF,metricStr,stride=10,clearCache=False): + """ + Function that plots several experiments against each other that all share the same experimentNameRoot. + Takes in one of these functions as the analysis function, and plots one of their average metrics along experiment time + + Assumes same size time step (and should have same time length for best comparison) + """ + print("Loading Experiments") + #First we need to find all matching experiments + savedExperiments = next(os.walk(savedDataDirPath))[1] #Get all experiment folder strings + comparisonExperiments = [] + print("Looking for matches") + for savedExperiment in tqdm(savedExperiments): + if savedExperiment.startswith(experimentNameRoot): + comparisonExperiments.append(savedExperiment) + + if len(comparisonExperiments) == 0: + noExperimentsFound = f"No experiments found matching {experimentNameRoot} in {savedDataDirPath}." + raise FileNotFoundError(noExperimentsFound) + print("Getting comparison data") + #Get data + comparisonData = [] + maxNumTimeSteps = 0 + experimentLabels = [] + for experimentName in tqdm(comparisonExperiments): + dataAnalysisFReturnDict = dataAnalysisF(savedDataDirPath,experimentName,solverNames,perTimeStep=True,stride=stride,clearCache=clearCache) + if not metricStr in dataAnalysisFReturnDict.keys(): + selectedMetricIdxToLarge = f"The selected metricStr {metricStr} is not in the metrics provided by {dataAnalysisF} ({dataAnalysisFReturnDict.keys()})" + raise ValueError(selectedMetricIdxToLarge) + comparisonData.append(dataAnalysisFReturnDict[metricStr]) + + if len(comparisonData[-1]) > 1 or len(comparisonData[-1][0]) >1: + tooManyVariables = f"Currently can only compare with one solver and one nSimsPerTree. Received {len(comparisonData[-1])} and {len(comparisonData[-1][0])}" + raise ValueError(tooManyVariables) + comparisonData[-1] = comparisonData[-1][0,0] + + maxNumTimeSteps = max(maxNumTimeSteps, len(comparisonData[-1][0])) + experimentLabels.append(experimentName[len(experimentNameRoot):]) + + + #Finally plot + dummyFig, ax = plt.subplots(nrows=1,ncols=1,figsize=(15,10)) + timeSteps = onp.arange(maxNumTimeSteps) * stride + legendHandles = [] + for iExperiment, data in enumerate(comparisonData): + handle, = ax.plot(timeSteps,onp.average(data,axis=0),label=experimentLabels[iExperiment]) + legendHandles.append(handle) + ax.legend(handles=legendHandles) + + plt.show() + +def plotMetricsBySimLevelAvgsAlongTime(savedDataDirPath, experimentName,solverNames,dataAnalysisF,metricStr,stride=10,clearCache=False): + """ + Function that plots the different planning levels as a function of time. + Takes in one of these functions as the analysis function, and plots one of their average metrics along experiment time + + Assumes same size time step (and should have same time length for best comparison) + """ + + + #Get data + numTimeSteps = 0 + dataAnalysisFReturnDict = dataAnalysisF(savedDataDirPath,experimentName,solverNames,perTimeStep=True,stride=stride,clearCache=clearCache) + if not metricStr in dataAnalysisFReturnDict.keys(): + selectedMetricIdxToLarge = f"The selected metricStr {metricStr} is not in the metrics provided by {dataAnalysisF} ({dataAnalysisFReturnDict.keys()})" + raise ValueError(selectedMetricIdxToLarge) + comparisonData = dataAnalysisFReturnDict[metricStr] + + if len(comparisonData) > 1: + tooManyVariables = f"Currently can only simulation levels with one solver. Received {len(comparisonData)}" + raise ValueError(tooManyVariables) + comparisonData = comparisonData[0] + + numTimeSteps = len(comparisonData[0,0]) + + + solverDirectoryPath = getSolverDirectoryPath(0,solverNames,numBaselines=0,baselineExperimentDataDirPath=None, + experimentDataDirPath=os.path.join(savedDataDirPath,experimentName), + solverName=solverNames[0]) + + nSimulationsPerTrees = getNSimulationsPerTrees(solverDirectoryPath) + + #Finally plot + dummyFig, ax = plt.subplots(nrows=1,ncols=1,figsize=(15,10)) + timeSteps = onp.arange(numTimeSteps) * stride + legendHandles = [] + for iNumSimulationsPerTree in tqdm(range(len(comparisonData))): + handle, = ax.plot(timeSteps,onp.average(comparisonData[iNumSimulationsPerTree],axis=0),label=f"N = {nSimulationsPerTrees[iNumSimulationsPerTree]}") + legendHandles.append(handle) + ax.legend(handles=legendHandles) + + plt.show() + + +# Compute safety metrics across experiment results. +# We will leverage the fact that the only way to get a reward = 0 is if the belief was determined to be unsafe + + +# First need to load data (This is a pretty manual function so disabling pylint) +def loadAndComputeSafetyData(experimentDataDirAbsolutePath, solverNamesList, dieAndStayDead=True, + sampleBeliefFlag=False, cacheName="safetyDataCache", clearCachedData=False, recomputeLastCollisionFree=False,requestedTSteps=None): + """ + Returns safety metrics for plotting + """ + # Need to load safety constraint evaluation to evaluate if belief is safe or not. + # Actually we don't! We can leverage reward = 0 only when the belief was evaluated not to be alpha-safe (could look into whether it is overestimated... sure!) + + # Check for cached data. Then we don't need to recompute (might need to recompute missing data) + cacheDict = getSafetyCache(experimentDataDirAbsolutePath, cacheName, dieAndStayDead, clearCachedData) + + if sampleBeliefFlag: + safetyFunctionEvaluationF, safetyFunctionF, alphaSafetyFunctionEvaluationF = loadExactAndSampleSafetyFunctionF(experimentDataDirAbsolutePath, returnAlphaSafetyFunctionEvaluationF=True) + else: + safetyFunctionEvaluationF, safetyFunctionF = loadExactAndSampleSafetyFunctionF(experimentDataDirAbsolutePath) # pylint: disable=unbalanced-tuple-unpacking + alphaSafetyFunctionEvaluationF = None + initialized = False + # Returning as a dict now + safetyDataDict = {} + #Variables which will be replaced when we first loop through + nSimulationsPerTrees = None + partialCache = None + nTrialsPerPoint = None + trialNumbers = None + + rngKey = jaxRandom.PRNGKey(0) + + # Loop through solvers + for iSolver, solverName in enumerate(solverNamesList): + solverDirectoryPath = os.path.join(experimentDataDirAbsolutePath, solverName) + if not os.path.exists(solverDirectoryPath): + raise FileNotFoundError("Directory not found, check if the correct save directory and experiment are given") + + if nSimulationsPerTrees is None: + safetyDataDict["nSimulationsPerTrees"] = getNSimulationsPerTrees(solverDirectoryPath) + + # Check for consistency one more time, then assume cache matches + partialCache, returnFlag, sampleBeliefFlag = checkAndApplyCache(cacheDict,safetyDataDict,experimentDataDirAbsolutePath, + recomputeLastCollisionFree,sampleBeliefFlag) + #If cache already has all the data, just return it + if returnFlag: + return returnRequestedDataDictRange(cacheDict, requestedTSteps) + + for jNSimsPerTreeExperiment, nSimulationsPerTree in enumerate(safetyDataDict["nSimulationsPerTrees"]): + print(f"Computing safety for N = {nSimulationsPerTree}") + nSimPath = os.path.join(solverDirectoryPath, str(nSimulationsPerTree)) + # Initialize average data arrays if we haven't yet, since determining safetyDataDict["nSimulationsPerTrees"] programmatically + if nTrialsPerPoint is None: + # Get nTrialsPerPoint + trialNumbers, nTrialsPerPoint = getTrialNumbers(nSimPath) + + for kTrial, trialNumber in tqdm(enumerate(trialNumbers)): + kTrialPath = os.path.join(nSimPath, str(trialNumber)) + trialDataDict = loadTrialDataDict(kTrialPath) + + # Set up outputs if needed + if not initialized: + numTimeSteps = len(trialDataDict["beliefList"]) + initializeSafetyDataDict(safetyDataDict,partialCache,numTimeSteps,len(solverNamesList),nTrialsPerPoint,recomputeLastCollisionFree) + initialized = True + + # In any case, get data + physicalStateList = trialDataDict["physicalStateList"] + beliefList = trialDataDict["beliefList"] + rewards = trialDataDict["rewards"] + # If EKF diverged = failure (also need to make sure success set to 0) + rewards[onp.isnan(rewards)] = 0 + # Old name, not as informative + # lastBelievedCollisionFreeTStep = trialDataDict["lastCollisionFreeTStep"] + lastBelievedCollisionFreeTStep = trialDataDict["lastBelievedCollisionFreeTStep"] + + #Loop over each time step (all saved in safetyDataDict, so no returns) + safetyAtEachTimeStep(safetyDataDict,iSolver,jNSimsPerTreeExperiment,kTrial,numTimeSteps,partialCache, + dieAndStayDead,physicalStateList,beliefList,rewards,safetyFunctionF,safetyFunctionEvaluationF, + alphaSafetyFunctionEvaluationF,sampleBeliefFlag,rngKey) + + #Compute averages and trial wide data + safetyOverTrial(safetyDataDict,iSolver,jNSimsPerTreeExperiment,kTrial,partialCache,sampleBeliefFlag,recomputeLastCollisionFree,lastBelievedCollisionFreeTStep) + + # Average collision free-ness + if not partialCache or recomputeLastCollisionFree: + safetyDataDict["avgBelievedLastCollisionFreeTSteps"][iSolver, jNSimsPerTreeExperiment] = onp.average( + safetyDataDict["lastBelievedCollisionFreeTSteps"][iSolver, jNSimsPerTreeExperiment, :]) + safetyDataDict["avgTrueLastCollisionFreeTSteps"][iSolver, jNSimsPerTreeExperiment] = onp.average( + safetyDataDict["lastTrueCollisionFreeTSteps"][iSolver, jNSimsPerTreeExperiment, :]) + + # Useful to know + safetyDataDict["numTimeSteps"] = numTimeSteps + + # To determine if this cache matches later + safetyDataDict["dieAndStayDead"] = dieAndStayDead + cacheData(experimentDataDirAbsolutePath, safetyDataDict, cacheName) + return returnRequestedDataDictRange(safetyDataDict, requestedTSteps) + +def returnRequestedDataDictRange(safetyDataDict, requestedTSteps): + """ + Helper function that only returns some time steps if a shorter range is requested + """ + + + #Allow for only considering some of the data + if requestedTSteps is not None: + timeStepsInData = len(safetyDataDict["empiricalSafetyValues"][0,0,0]) + if timeStepsInData > requestedTSteps: + for key in safetyDataDict.keys(): + if len(onp.shape(safetyDataDict[key]))>3 and not "totals" in key.lower(): #Totals sums over all time steps + safetyDataDict[key] = safetyDataDict[key][:,:,:,:requestedTSteps+1] + elif key == "numTimeSteps": + safetyDataDict[key] = requestedTSteps+1 + + elif timeStepsInData < requestedTSteps: + tooManyTimeStepsRequested = f"Saved data only has {timeStepsInData} time steps. {requestedTSteps} requested" + raise ValueError(tooManyTimeStepsRequested) + + return safetyDataDict + +def checkAndApplyCache(cacheDict,safetyDataDict,experimentDataDirAbsolutePath,recomputeLastCollisionFree,sampleBeliefFlag): + """ + Helper method that inspects what type of cache we have + """ + + if cacheDict is not None: + if not onp.all(safetyDataDict["nSimulationsPerTrees"] == cacheDict["nSimulationsPerTrees"]): + mismatchedCache = (f"Safety cache under {experimentDataDirAbsolutePath} has different value of nSimulationsPerTrees ({safetyDataDict['nSimulationsPerTrees']}) " + + "than the computed value, indicating a change in the data. Use a different cache name or set clearCachedData to True") + raise ValueError(mismatchedCache) + + # Check if we need to do anything, if true assume all values present, so no need to compute anything + # (if sampleBeliefFlag = False, then we don't care about missing info) + returnFlag = not recomputeLastCollisionFree and ("beliefAlphaSafetyValues" in cacheDict or not sampleBeliefFlag) + + + if "beliefAlphaSafetyValues" in cacheDict or not sampleBeliefFlag: + partialCache = True + sampleBeliefFlag = False # Only need to recompute last collision free times + safetyDataDict = cacheDict + else: + # Only need to do the belief sampling (may make this more complicated later?) + partialCache = True + safetyDataDict = cacheDict + else: + partialCache = False + returnFlag = False + + return partialCache, returnFlag, sampleBeliefFlag + +def safetyAtEachTimeStep(safetyDataDict,iSolver,jNSimsPerTreeExperiment,kTrial,numTimeSteps,partialCache, + dieAndStayDead,physicalStateList,beliefList,rewards,safetyFunctionF,safetyFunctionEvaluationF, + alphaSafetyFunctionEvaluationF,sampleBeliefFlag,rngKey): + """ + Helper method that performs the safety analysis at each time step + """ + # Safety at each point (May need to vectorize this...) Note, t=0 is initialization so should always be safe + for mTimeStep in range(numTimeSteps): + if not partialCache: + # Check if we crashed before + if dieAndStayDead and mTimeStep > 0: + estimatedAlive = safetyDataDict["empiricalSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, mTimeStep - 1] + trulyAlive = safetyDataDict["trueSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, mTimeStep - 1] + nInfAlive = safetyDataDict["nInfSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, mTimeStep - 1] + + # Check for false life. + if estimatedAlive != trulyAlive: + if estimatedAlive > trulyAlive: + safetyDataDict["empiricalFalsePositives"][iSolver,jNSimsPerTreeExperiment,kTrial,mTimeStep,1,] = 1 + else: + safetyDataDict["empiricalFalseNegatives"][iSolver,jNSimsPerTreeExperiment,kTrial,mTimeStep,1,] = 1 + if nInfAlive != trulyAlive: + if nInfAlive > trulyAlive: + safetyDataDict["nInfFalsePositives"][iSolver,jNSimsPerTreeExperiment,kTrial, mTimeStep,1,] = 1 + else: + safetyDataDict["nInfFalseNegatives"][iSolver,jNSimsPerTreeExperiment,kTrial,mTimeStep,1,] = 1 + + else: + estimatedAlive = 1 + trulyAlive = 1 + nInfAlive = 1 + + # Safe unless reward = 0 ! (And not already dead) + estimatedSafety = onp.sign(rewards[mTimeStep]) + safetyDataDict["empiricalSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, mTimeStep] = estimatedSafety * estimatedAlive + # Can check true safety (negative return is safe, positive or zero is unsafe!) + trueSafetyFUnctionSign = onp.sign(safetyFunctionF(physicalStateList[mTimeStep])) + trueSafety = (0.5 - 0.5 * trueSafetyFUnctionSign) * onp.abs(trueSafetyFUnctionSign) + safetyDataDict["trueSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, mTimeStep] = trueSafety * trulyAlive + # Can approximate nInf by letting it go to high value (will try with N=1000 here) + rngKey, rngSubKey = jaxRandom.split(rngKey) + nInfSafety = safetyFunctionEvaluationF(beliefList[mTimeStep], rngSubKey) + safetyDataDict["nInfSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, mTimeStep] = nInfSafety * nInfAlive + + # Check for false +/- + falsePositiveNegativeCheck(safetyDataDict,estimatedSafety,nInfSafety,trueSafety,iSolver,jNSimsPerTreeExperiment,kTrial, mTimeStep) + + # Always do this part, partial cache or no. + # Assuming this might be expensive, seems to be a 1/2 slow down (but 2000 samples may be excessive) This and nInf are probably main costs. + if sampleBeliefFlag: + sampleBeliefAlphaSafety(safetyDataDict,dieAndStayDead,trulyAlive,alphaSafetyFunctionEvaluationF,beliefList,trueSafety,iSolver,jNSimsPerTreeExperiment,kTrial, mTimeStep, rngKey) + +def falsePositiveNegativeCheck(safetyDataDict,estimatedSafety,nInfSafety,trueSafety,iSolver,jNSimsPerTreeExperiment,kTrial,mTimeStep): + """ + Helper function to compute false +/- + """ + if estimatedSafety != trueSafety: + if estimatedSafety > trueSafety: + safetyDataDict["empiricalFalsePositives"][iSolver,jNSimsPerTreeExperiment,kTrial, mTimeStep,0,] = 1 + else: + safetyDataDict["empiricalFalseNegatives"][iSolver,jNSimsPerTreeExperiment, kTrial,mTimeStep, 0,] = 1 + if nInfSafety != trueSafety: + if nInfSafety > trueSafety: + safetyDataDict["nInfFalsePositives"][iSolver,jNSimsPerTreeExperiment,kTrial,mTimeStep,0,] = 1 + else: + safetyDataDict["nInfFalseNegatives"][iSolver,jNSimsPerTreeExperiment,kTrial,mTimeStep,0,] = 1 + +def sampleBeliefAlphaSafety(safetyDataDict,dieAndStayDead,trulyAlive,alphaSafetyFunctionEvaluationF,beliefList,trueSafety,iSolver,jNSimsPerTreeExperiment,kTrial, mTimeStep, rngKey): + """ + Helper method that computes the safety estimate we get by just sampling from the belief a specified number of times (1000 by hard coding) + """ + if dieAndStayDead and mTimeStep > 0: + alphaAlive = safetyDataDict["beliefAlphaSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, mTimeStep - 1] + # False life? + if alphaAlive != trulyAlive: + if alphaAlive > trulyAlive: + safetyDataDict["beliefAlphaFalsePositives"][iSolver,jNSimsPerTreeExperiment,kTrial,mTimeStep,1,] = 1 + else: + safetyDataDict["beliefAlphaFalseNegatives"][iSolver,jNSimsPerTreeExperiment,kTrial,mTimeStep,1,] = 1 + else: + alphaAlive = 1 + + beliefAlphaSafety = alphaSafetyFunctionEvaluationF( beliefList[mTimeStep], rngKey) + # print(trueSafety,beliefAlphaSafety,alphaAlive) + safetyDataDict["beliefAlphaSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, mTimeStep] = beliefAlphaSafety * alphaAlive + # false +/- + if beliefAlphaSafety != trueSafety: + if beliefAlphaSafety > trueSafety: + safetyDataDict["beliefAlphaFalsePositives"][iSolver,jNSimsPerTreeExperiment,kTrial,mTimeStep,0,] = 1 + else: + safetyDataDict["beliefAlphaFalseNegatives"][iSolver,jNSimsPerTreeExperiment,kTrial,mTimeStep,0,] = 1 + + +def safetyOverTrial(safetyDataDict,iSolver,jNSimsPerTreeExperiment,kTrial,partialCache,sampleBeliefFlag,recomputeLastCollisionFree,lastBelievedCollisionFreeTStep): + """ + Helper method that performs the safety analysis for the trial as a whole + """ + # Totals and Averages + if not partialCache: + safetyDataDict["empiricalFalsePositivesTotals"][ iSolver, jNSimsPerTreeExperiment, kTrial] = onp.sum( + safetyDataDict["empiricalFalsePositives"][iSolver, jNSimsPerTreeExperiment, kTrial, :, :],axis=0,) + safetyDataDict["empiricalFalseNegativesTotals"][iSolver, jNSimsPerTreeExperiment, kTrial] = onp.sum( + safetyDataDict["empiricalFalseNegatives"][iSolver, jNSimsPerTreeExperiment, kTrial, :, :],axis=0,) + + safetyDataDict["nInfFalseNegativesTotals"][iSolver, jNSimsPerTreeExperiment, kTrial] = onp.sum( + safetyDataDict["nInfFalseNegatives"][iSolver, jNSimsPerTreeExperiment, kTrial, :, :],axis=0,) + safetyDataDict["nInfFalsePositivesTotals"][iSolver, jNSimsPerTreeExperiment, kTrial] = onp.sum( + safetyDataDict["nInfFalsePositives"][iSolver, jNSimsPerTreeExperiment, kTrial, :, :],axis=0,) + + safetyDataDict["avgEmpSafety"][iSolver, jNSimsPerTreeExperiment, kTrial] = onp.average( + safetyDataDict["empiricalSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, :]) + safetyDataDict["avgTrueSafety"][iSolver, jNSimsPerTreeExperiment, kTrial] = onp.average( + safetyDataDict["trueSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, :]) + safetyDataDict["avgNInfSafety"][iSolver, jNSimsPerTreeExperiment, kTrial] = onp.average( + safetyDataDict["nInfSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, :]) + + # Collision free + if not partialCache or recomputeLastCollisionFree: + # print("believed",lastBelievedCollisionFreeTStep) + safetyDataDict["lastBelievedCollisionFreeTSteps"][iSolver, jNSimsPerTreeExperiment, kTrial] = lastBelievedCollisionFreeTStep + lastTrueCollisionFreeTStep = -1 + for trueSafetyValue in safetyDataDict["trueSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial]: + if trueSafetyValue == 0: + # print("true",lastTrueCollisionFreeTStep) + break + lastTrueCollisionFreeTStep += 1 + safetyDataDict["lastTrueCollisionFreeTSteps"][iSolver, jNSimsPerTreeExperiment, kTrial] = lastTrueCollisionFreeTStep + + if sampleBeliefFlag: + safetyDataDict["beliefAlphaFalseNegativesTotals"][iSolver, jNSimsPerTreeExperiment, kTrial] = onp.sum( + safetyDataDict["beliefAlphaFalseNegatives"][ iSolver, jNSimsPerTreeExperiment, kTrial, :, :],axis=0,) + safetyDataDict["beliefAlphaFalsePositivesTotals"][iSolver, jNSimsPerTreeExperiment, kTrial] = onp.sum( + safetyDataDict["beliefAlphaFalsePositives"][iSolver, jNSimsPerTreeExperiment, kTrial, :, :],axis=0, ) + + safetyDataDict["avgBeliefAlphaSafety"][iSolver, jNSimsPerTreeExperiment, kTrial] = onp.average( + safetyDataDict["beliefAlphaSafetyValues"][iSolver, jNSimsPerTreeExperiment, kTrial, :]) + +def initializeSafetyDataDict(safetyDataDict,partialCache,numTimeSteps,numSolvers,nTrialsPerPoint,recomputeLastCollisionFree): + """ + Helper method to create all the output arrays + """ + if not partialCache: + + numNSimulationsPerTree = len(safetyDataDict["nSimulationsPerTrees"]) + + # Now initialize the data now that we know the number of experiments + safetyDataDict["empiricalSafetyValues"] = onp.zeros((numSolvers,numNSimulationsPerTree,nTrialsPerPoint,numTimeSteps,)) + safetyDataDict["avgEmpSafety"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint)) + safetyDataDict["trueSafetyValues"] = onp.zeros((numSolvers, numNSimulationsPerTree,nTrialsPerPoint,numTimeSteps,)) + safetyDataDict["avgTrueSafety"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint)) + + safetyDataDict["nInfSafetyValues"] = onp.zeros((numSolvers,numNSimulationsPerTree,nTrialsPerPoint,numTimeSteps,)) + safetyDataDict["avgNInfSafety"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint)) + + safetyDataDict["empiricalFalseNegatives"] = onp.zeros((numSolvers,numNSimulationsPerTree,nTrialsPerPoint,numTimeSteps,2,)) + safetyDataDict["empiricalFalsePositives"] = onp.zeros((numSolvers,numNSimulationsPerTree,nTrialsPerPoint,numTimeSteps,2,)) + + safetyDataDict["empiricalFalseNegativesTotals"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint, 2)) + safetyDataDict["empiricalFalsePositivesTotals"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint, 2)) + + safetyDataDict["nInfFalseNegatives"] = onp.zeros((numSolvers,numNSimulationsPerTree,nTrialsPerPoint,numTimeSteps,2,)) + safetyDataDict["nInfFalsePositives"] = onp.zeros((numSolvers,numNSimulationsPerTree,nTrialsPerPoint,numTimeSteps,2,)) + + safetyDataDict["nInfFalseNegativesTotals"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint, 2)) + safetyDataDict["nInfFalsePositivesTotals"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint, 2)) + # Calculate for new run or specified recompute + if not partialCache or recomputeLastCollisionFree: + safetyDataDict["lastBelievedCollisionFreeTSteps"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint)) + safetyDataDict["avgBelievedLastCollisionFreeTSteps"] = onp.zeros((numSolvers, numNSimulationsPerTree)) + + safetyDataDict["lastTrueCollisionFreeTSteps"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint)) + safetyDataDict["avgTrueLastCollisionFreeTSteps"] = onp.zeros((numSolvers, numNSimulationsPerTree)) + # Do this always partial cached or no cache + + safetyDataDict["beliefAlphaSafetyValues"] = onp.zeros((numSolvers,numNSimulationsPerTree,nTrialsPerPoint,numTimeSteps,)) + safetyDataDict["avgBeliefAlphaSafety"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint)) + + safetyDataDict["beliefAlphaFalsePositives"] = onp.zeros((numSolvers,numNSimulationsPerTree,nTrialsPerPoint,numTimeSteps,2,)) + safetyDataDict["beliefAlphaFalseNegatives"] = onp.zeros((numSolvers,numNSimulationsPerTree,nTrialsPerPoint,numTimeSteps,2,)) + + safetyDataDict["beliefAlphaFalseNegativesTotals"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint, 2)) + safetyDataDict["beliefAlphaFalsePositivesTotals"] = onp.zeros((numSolvers, numNSimulationsPerTree, nTrialsPerPoint, 2)) + +def getSafetyCache(experimentDataDirAbsolutePath, cacheName="safetyDataCache", dieAndStayDead=True, clearCachedData=False): + """ + Checks for already existing safety data cache + """ + if not clearCachedData: + try: + safetyCachePath = getCachePath(experimentDataDirAbsolutePath, cacheName) + with open(safetyCachePath, "rb") as safetyCacheFile: + cacheDict = pickle.load(safetyCacheFile) + # Check consistency + if cacheDict["dieAndStayDead"] != dieAndStayDead: + mismatchedCache = (f"Cache at {safetyCachePath} has different value of dieAndStayDead ({not dieAndStayDead})" + + " than the provided value. Use a different cache name or set clearCachedData to True") + raise ValueError(mismatchedCache) + except FileNotFoundError: + cacheDict = None + else: + cacheDict = None + return cacheDict + +def cacheData(experimentDataDirAbsolutePath, dataDict, cacheName=None): + """ + Saves analyzed data to save time re-loading it + """ + cachePath = getCachePath(experimentDataDirAbsolutePath, cacheName) + + with open(cachePath, "wb") as cacheFile: + pickle.dump(dataDict, cacheFile) + + +def getCachePath(experimentDataDirAbsolutePath, cacheName="safetyDataCache"): + """ + Creates path for cache file. Default is safety cache + """ + + return os.path.join(experimentDataDirAbsolutePath, f"{cacheName}.dict") + + + +def loadExactAndSampleSafetyFunctionF(experimentDataDirAbsolutePath, returnAlphaSafetyFunctionEvaluationF=False): + """ + Returns the sample-based safety function evaluation method. + """ + + configFilePath = os.path.join(experimentDataDirAbsolutePath, "config.yaml") + + inputDict = getInputDict(configFilePath) + + # Could be more efficient getting components here, but seems okay for now + silent = True + dummySystemF,systemParametersTuple,dummyPhysicalStateJacobianF,dummyDim,linear,dummyDt,dummySigmaW,dummySigmaV, dummyNumAct = loadAndBuildSingleAgentSystem( + inputDict, providedFailure=None,generalFaultFlag=False, silent=silent) #Even if we have general fault system, don't need it for safety analysis, as systemParametersTuple isn't affected + + + # To get the number of states, this is length of covariance matrix, which is the -2 element of the systemParametersTuple + covarianceQ = systemParametersTuple[-2] + numState = len(covarianceQ) + + # Load estimator and belief initialization function + dummyEstimatorF,dummyPhysicalStateSubEstimatorF,physicalStateSubEstimatorSampleF, dummyBeliefInitializationF = loadEstimatorAndBelief( + inputDict, linear, numState=numState, generalFaultFlag=False, silent=silent)#Even if we have general fault system, don't need it for safety analysis, + # as physicalStateSubEstimatorSampleF isn't affected + + # Going to approximate infinite samples by an order of magnitude higher, to justify claim that we are close. + safetyFunctionEvaluationF, safetyFunctionF = loadSafetyModulatedRewardComponents( + inputDict, physicalStateSubEstimatorSampleF, numSamples=1000) + + if returnAlphaSafetyFunctionEvaluationF: + alphaSafetyFunctionEvaluationF = makeProbabilisticAlphaSafetyFunctionEvaluation(safetyFunctionF,physicalStateSubEstimatorSampleF,numSamples=2000,alpha=0.95,) + return (safetyFunctionEvaluationF,safetyFunctionF,alphaSafetyFunctionEvaluationF,) + + return safetyFunctionEvaluationF, safetyFunctionF + + +def getActions(experimentDataDirPath, solverName, lastTimeStep=None): + """ + Method for getting the actions a solver takes throughout the course of the experiment for each trial + + Useful for comparing how aggressive a solver is + """ + + solverDirectoryPath = os.path.join(experimentDataDirPath, solverName) + nSimulationsPerTrees = getNSimulationsPerTrees(solverDirectoryPath) + nSimPath = os.path.join(solverDirectoryPath, str(nSimulationsPerTrees[0])) + # Initialize average data arrays + # Get nTrialsPerPoint + trialNumbers, nTrialsPerPoint = getTrialNumbers(nSimPath) + kTrialPath = os.path.join(nSimPath, str(trialNumbers[0])) + trialDataDict = loadTrialDataDict(kTrialPath) + # Get number of experiment steps + numTimeSteps = len(trialDataDict["actionList"]) + # Want to be able to cap to shorter length if specified + if lastTimeStep is not None and lastTimeStep < numTimeSteps - 1: + numTimeSteps = lastTimeStep + 1 + + actions = onp.zeros((len(nSimulationsPerTrees),nTrialsPerPoint,numTimeSteps,len(trialDataDict["actionList"][0]),)) + numActiveActuators = onp.zeros((len(nSimulationsPerTrees), nTrialsPerPoint, numTimeSteps)) + + # Now loop through and process + for jNSimsPerTreeExperiment, nSimulationsPerTree in enumerate(nSimulationsPerTrees): + print(nSimulationsPerTree) + # if nSimulationsPerTree < 200: + # continue + nSimPath = os.path.join(solverDirectoryPath, str(nSimulationsPerTree)) + + for kTrial, trialNumber in tqdm(enumerate(trialNumbers)): + kTrialPath = os.path.join(nSimPath, str(trialNumber)) + trialDataDict = loadTrialDataDict(kTrialPath) + + actions[jNSimsPerTreeExperiment, kTrial] = onp.array(trialDataDict["actionList"][:numTimeSteps]) + numActiveActuators[jNSimsPerTreeExperiment, kTrial] = onp.sum(actions[jNSimsPerTreeExperiment, kTrial], axis=1) + + return actions, numActiveActuators diff --git a/failurePy/utility/legacyPaperCode.py b/failurePy/utility/legacyPaperCode.py new file mode 100644 index 0000000..862eb05 --- /dev/null +++ b/failurePy/utility/legacyPaperCode.py @@ -0,0 +1,43 @@ +""" +File containing relevant legacy code from the first draft of the paper to reproduce results as needed +""" +# pylint: skip-file + +import jax.numpy as jnp + +def makeAvailableActions(numAct,influenceMatrix): + """ + Generate the actions the solvers will be allowed to consider. Uses paper first draft code + + Parameters + ---------- + numAct : int + The number of actuators there are + influenceMatrix : array, shape(numState, numAct) + B matrix + + Returns + ------- + availableActions : array, shape(numActions,numAct) + Array of actions that can be taken. First action is always null action + + """ + + #Create list of every permutation of actions + #Note this list is generated by converting every number from 0 to numAct^2 to binary + availableActions = [] + #explicitly add 0 action (if optimal, we shouldn't do this, not really true if we're waiting) + availableActions.append(jnp.zeros(numAct)) + for i in range(2**(numAct)): + action = [] + for j in range(numAct): + action.append(int(i/2**(j))%2) + action = jnp.array(action) + #Only allow 3 or fewer thrusters to fire + if jnp.sum(action) <= 3: + #Check if the action does anything + if not jnp.all(jnp.matmul(influenceMatrix,action)==0): + availableActions.append(action) + + + return jnp.array(availableActions) diff --git a/failurePy/utility/pipelineHelperMethods.py b/failurePy/utility/pipelineHelperMethods.py new file mode 100644 index 0000000..6c61db1 --- /dev/null +++ b/failurePy/utility/pipelineHelperMethods.py @@ -0,0 +1,340 @@ +""" +Module of helper methods called by pipeline.py +""" + +import warnings + +import jax.numpy as jnp + +from failurePy.utility.comb import comb +from failurePy.models.linearModel import simulateSystemWrapper as linearSystemF +from failurePy.models.linearModelGeneralFaults import simulateSystemWrapper as linearSystemGeneralF +from failurePy.models.threeDOFModel import simulateSystemWrapper as threeDOFSystemF +from failurePy.models.threeDOFGeneralFaultModel import simulateSystemWrapper as threeDOFSystemGeneralF + +def getExperimentParameters(experimentParamsDict): + """ + Helper function to get common parameters for each experiment + """ + numState, numAct, numSen, numAgents = getDimensions(experimentParamsDict["systemF"],experimentParamsDict["systemParametersTuple"],experimentParamsDict["networkFlag"]) + + numNFailures = getNumNFailures(experimentParamsDict["nMaxComponentFailures"],numAct,numSen,numAgents=numAgents) + + numWarmStart = experimentParamsDict["numWarmStart"] + + return numState, numAct, numSen, numNFailures, numWarmStart, numAgents + +#Conditioning on value of numAct and numSens isn't ideal, but that probably won't change, so could be fine +#Low priority because this is only run once per trial, also need to figure out jitting failureCombinationGenerator first +def generateAllPossibleFailures(numAct,numSen,numNFailures,possibleFailuresIdxes,numAgents=1): + """ + Method that creates the possible failures + + Parameters + ---------- + numAct : int + Number of actuators + numSen : int + Number of sensors + numNFailures : array, shape(nMaxComponentFailures+1) + Number of failure combinations for each level of failed components + possibleFailuresIdxes : array, shape(nMaxPossibleFailures) + The indexes of each failure to generate + numAgents : int (default=1) + How many agents are present (distinguishes single from multi-agent) + + Returns + ------- + possibleFailures : array, shape(nMaxPossibleFailures,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + """ + #Note we will squeeze at end, so if numAgents=1, we will remove that axis + numFallibleComponents = numAct+numSen + possibleFailures = jnp.zeros((len(possibleFailuresIdxes),numAgents,numFallibleComponents)) + for iFailure,possibleFailuresIdx in enumerate(possibleFailuresIdxes): + possibleFailure = failureCombinationGenerator(numAgents*numAct,numAgents*numSen,numNFailures,possibleFailuresIdx) + #If more than one agent, need to divide the failure across them to parallel process later + #If one agent, this will get flattened + for jAgent in range(numAgents): + #NEED TO TAKE INTO CONSIDERATION THAT SENSOR FAILURES ARE GENERATED AT THE END + # Otherwise, nominal sensing flag is broken. TEST THIS + actuatorFailure = possibleFailure[jAgent*numAct:(jAgent+1)*numAct] + #Ugly, but negative indexing fails when the index is -0 + sensorFailure = possibleFailure[len(possibleFailure)-(jAgent+1)*numSen:len(possibleFailure)-jAgent*numSen] + possibleFailures = possibleFailures.at[iFailure,jAgent].set(jnp.concatenate((actuatorFailure,sensorFailure))) + #Remove numAgents axis if numAgents = 1. Catch value error if numAgents !=1 + try: + possibleFailures = jnp.squeeze(possibleFailures,axis=1) + except ValueError: + pass #Just return the original array then! + + return possibleFailures #Remove numAgents axis if numAgents=1 + +#but could maybe lead to low memory implementation (store int instead of array) +#Or just jit allowing failureIdx to be conditional? Doesn't seem very efficient though +#Low priority because this is only run once per trial +def failureCombinationGenerator(numAct,numSen,numNFailures,failureIdx): + """ + Method that generates a failure given the number of components that can fail, max failures, and which failure index to consider. + + Parameters + ---------- + numAct : int + Number of actuators + numSen : int + Number of sensors + numNFailures : array, shape(nMaxComponentFailures+1) + Number of failure combinations for each level of failed components + failureIdx : int + Index of the failure in the lexicographic ordering of the failures. This order is defined as lower numbers of failures occurring first, and within + the same number of failures, failures corresponding to smaller binary numbers occurring first. + + Returns + ------- + failure : array, shape(numAct+numSen) + The failure state corresponding to the failureIdx + """ + + #Create nominal failure state (no failures), we'll modify as needed + failure = jnp.ones(numAct+numSen) + + #Find where failureIdx is relative to the total number of failures, and branch + #failureIdx runs sequentially over all combinations, starting from 0 failures + if failureIdx == 0: + return failure + + if failureIdx < numNFailures[1] + 1: + failure = failure.at[failureIdx-1].set(0) + return failure + + #For more than one failure, we use failure combination generator + #Loop through number of total failures > 2 + for numTotalComponentFailures in jnp.arange(2,len(numNFailures)): + #Count all possible failures up to and including this numTotalComponentFailures + # The failureIndexLimit is the last index with numTotalComponentFailures) + failureIndexLimit = 0 + for iComponentFailureCount in range(numTotalComponentFailures+1): + failureIndexLimit += numNFailures[iComponentFailureCount] + #If the failure index is below this, we know how many failures we need! + #Else, loop further, as we need more component failures! + if failureIdx < failureIndexLimit: + #note reverseLexicographicIdx is failureIdx - numNFailures of previous totals, which is failureIdx-failureIndexLimit + numNFailures[numTotalComponentFailures] + return failureCombinationFromLexicographicOrder(numAct,numSen,numTotalComponentFailures,failureIdx-failureIndexLimit + numNFailures[numTotalComponentFailures]) + #If failureIdx is improperly set above totalPossibleFailures, just return everything failed + return jnp.zeros(numAct+numSen) + +#but could maybe lead to low memory implementation (store int instead of array) +#Low priority because this is only run once per trial +def failureCombinationFromLexicographicOrder(numAct,numSen,numFailures,reverseLexicographicIdx): + """ + Adapts the algorithm from: https://math.stackexchange.com/questions/1368526/fast-way-to-get-a-combination-given-its-position-in-reverse-lexicographic-or/1368570#1368570 + + Parameters + ---------- + numAct : int + Number of actuators + numSen : int + Number of sensors + numFailures : int + Number of failures to return + failureIdx : int + Index of the failure in the lexicographic ordering of the failures (for this number of failures!). + This order is defined as lower numbers of failures occurring first, and within + the same number of failures, failures corresponding to smaller binary numbers occurring first. + + Returns + ------- + failure : array, shape(numAct+numSen) + The failure state corresponding to the reverseLexicographicIdx for this numFailures + """ + #Create nominal failure state (no failures), we'll modify as needed + #Since sensors are always last, we only set them as failed if there are enough possible combinations before rolling over + failure = jnp.ones(numAct+numSen) + #Loop through the bits in reverse order (MSB first, right side of array) + for iBit in reversed(range(numAct+numSen)): + #Compute combinatorial value, or zero if this doesn't make sense (choosing more than we have, which would through an error) + if iBit >= numFailures >=0: + combinatorialPlaceValue = comb(iBit,numFailures) + else: + combinatorialPlaceValue = 0 + #Check if we should set a failure + if reverseLexicographicIdx >= combinatorialPlaceValue: + #If so, decrease the index value + reverseLexicographicIdx = reverseLexicographicIdx - combinatorialPlaceValue + failure = failure.at[iBit].set(0) + #Decrease the number of failures left to set + numFailures = numFailures - 1 + return failure + +def getNumNFailures(nMaxComponentFailures,numAct,numSen,nominalSensing=False,numAgents=1): + """ + Computes the number of failures for each level of simultaneous failures + + Parameters + ---------- + nMaxComponentFailures : int + Max number of simultaneous failures + numAct : int + Number of actuators + num Sen : int + Number of sensors + nominalSensing : boolean (default=False) + If true, no sensor failures will be generated. Achieved by limiting combinations considered, + and noting that sensors are always last in the failure array. + numAgents : int (default=1) + How many agents are present (distinguishes single from multi-agent) + + Returns + ------- + numNFailures : array, shape(nMaxComponentFailures+1) + Number of combinations of failures for each level of simultaneous failures + """ + + #Guard against too high an nMaxComponentFailures + if not nominalSensing: + numFallibleComponents = (numAct+numSen)*numAgents + else: + numFallibleComponents = numAct*numAgents + if nMaxComponentFailures > numFallibleComponents: + nMaxComponentFailuresTooHigh = f"{nMaxComponentFailures} maximum component failures exceeds the number of fallible components ({numFallibleComponents})!" + warnings.warn(nMaxComponentFailuresTooHigh) + nMaxComponentFailures = numFallibleComponents + + #Get numbers of failures + numNFailures = jnp.ones(nMaxComponentFailures+1) + numNFailures = numNFailures.at[1].set(numFallibleComponents) + for iComponentsFailed in range(nMaxComponentFailures-1): #Faster to just set it (I think for 0 and 1 failures) + numNFailures = numNFailures.at[iComponentsFailed+2].set(comb(numFallibleComponents,iComponentsFailed+2)) + + return numNFailures + +def checkFailureIsValid(failure,numSen): + """ + Checks for double sensor failures, as these can't be solved. (Assumes redundant sensing) + + Parameters + ---------- + failure : array, shape(numAct+numSen) + The failure state to validate + numSen : int + Number of sensors + + Returns + ------- + newFailureIfNeeded : array, shape(numAct+numSen) + The failure state with no double sensor failures if needed, otherwise returns None + """ + + #Check to see if double sensing makes sense. Even number of sensors, needed + if not numSen % 2 == 0: + return None + # Flag for multiple failures on an axis + oneSensorFailedFlag = False + newFailureIfNeeded = None + + #Checking for two sensors failed on the same axis, as this is impossible to solve + for iSen in range(numSen): + #New axis, reset + if iSen % 2 == 0: + oneSensorFailedFlag = False + #This sensor is failed. Backwards indexing! Watch for off by one errors! + if failure[-iSen-1] == 0: + #Already had a sensor failed this axis! + if oneSensorFailedFlag: + #Remove this sensor failure. Need to make a new failure if we haven't yet + if newFailureIfNeeded: + newFailureIfNeeded = newFailureIfNeeded.at[-iSen-1].set(1) + else: + newFailureIfNeeded = failure.at[-iSen-1].set(1) + else: + oneSensorFailedFlag = True + return newFailureIfNeeded + +def getDimensions(systemF,systemParametersTuple,networkFlag): + """ + Method that gets the dimensions of the system + + Parameters + ---------- + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple containing all system parameters. Relevant parameters are given below (for linear system): + influenceMatrix : array, shape(numState, numAct) + B matrix + sensingMatrix : array, shape(numSen, numState) + C matrix Future + networkFlag : bool + Whether we are in a distributed network or not + + Returns + ------- + numState : int + Number of states + numAct : int + Number of actuators + numSen : int + Number of sensors + numAgents : int + Number of agents in system (distributed vs single agent) + """ + covarianceRIdx = -1 + #Need to determine system type here + if systemF is linearSystemF or systemF is linearSystemGeneralF: + #Get size of physical state and num actuators and sensors + influenceMatrixIdx = 2 + + + numState = len(systemParametersTuple[influenceMatrixIdx]) + numAgents = 1 + numAct = len(systemParametersTuple[influenceMatrixIdx][0]) + numSen = len(systemParametersTuple[covarianceRIdx]) + elif systemF is threeDOFSystemF or systemF is threeDOFSystemGeneralF: + positionInfluenceMatrixIdx = 0 + reactionWheelInfluenceMatrixIdx = 2 + + + numState = 6 + len(systemParametersTuple[reactionWheelInfluenceMatrixIdx]) #Need to add in the wheels to the state + numAct = len(systemParametersTuple[positionInfluenceMatrixIdx][0]) + len(systemParametersTuple[reactionWheelInfluenceMatrixIdx]) #Wheels count as actuators + numSen = len(systemParametersTuple[covarianceRIdx]) + numAgents = 1 + elif networkFlag: + nodePositionsIdx = -1 + numState = len(systemParametersTuple[nodePositionsIdx]) + numAgents = numState + numAct = 3 #hg, lg, act + numSen = 1 #sen + else: + systemDimensionsNotDefined = f"system function {systemF} does not yet have defined dimensions." + raise NotImplementedError(systemDimensionsNotDefined) + + return numState,numAct,numSen,numAgents + + +def diagnoseFailure(beliefTuple,currentFailureParticles): + """ + Returns the failure diagnosis. + + Known issue. If the failure weights are all nan (such as if the EKF diverged). Then argmax will return 0, and we will erroneously diagnose the correct failure. + Currently addressed in pipeline as well as saving. Saving is so that reprocessed experiments can fix this. + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxFailureParticles) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state + currentFailureParticles : array, shape(nMaxFailureParticles,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + + Returns + ------- + diagnosis : array, shape(numAct+numSen) + Failure believed to be afflicting the s/c + """ + failureWeightsIdx = 0 + failureIdx = jnp.argmax(beliefTuple[failureWeightsIdx]) + + return currentFailureParticles[failureIdx] diff --git a/failurePy/utility/reprocessData.py b/failurePy/utility/reprocessData.py new file mode 100644 index 0000000..34e2e9f --- /dev/null +++ b/failurePy/utility/reprocessData.py @@ -0,0 +1,341 @@ +""" +File for regenerating the average data from the results +""" +import os +import sys +import pickle +from tqdm import tqdm +import yaml + +from failurePy.load.yamlLoader import loadExperimentParams,loadExperimentParamsFromYaml +from failurePy.load.yamlLoaderUtilityMethods import getInputDict +from failurePy.utility.saving import processDataAverages, checkSaveDirectoryPathMakeIfNeeded, setUpDataOutput + + +def reprocessDataAverages(configFilePath,absolutePathAboveSavedData=None): + """ + Reprocesses the specified directory by recomputing the averages + """ + + #Get experiment params and save path + experimentParamsDict, saveDirectoryPath = loadExperimentParamsFromYaml(configFilePath) # pylint: disable=unbalanced-tuple-unpacking + #print(experimentParamsDict["nExperimentSteps"]) + configSaveDirectoryAbsoluteFlag = bool(saveDirectoryPath[0] == "/") + + if configSaveDirectoryAbsoluteFlag: + print(saveDirectoryPath) + processDataAverages(saveDirectoryPath, experimentParamsDict,) + else: + #Override if needed + #savePath = "" + print(saveDirectoryPath) + processDataAverages(os.path.join(absolutePathAboveSavedData,saveDirectoryPath), experimentParamsDict,) + +def reprocessTrialDataDicts(absoluteSavedDataPath,dictReprocessF): + """ + Looks for all trialData.dict files in this directory and its subdirectories, then passes them to the + specified reprocessing method. The changed dictionary overwrites the original file. + + Parameters + ---------- + absoluteSavedDataPath : string + Absolute path to directory where we should look for and modify trailData.dict files. + dictReprocessF : function + Function to reprocess the trial data + """ + + pbar = tqdm(total=getNumberOfTrials(absoluteSavedDataPath)) + + #Use os.walk to search through every file here for saved data dictionaries + for path, dummyDirectories, files in os.walk(absoluteSavedDataPath): + #Look at each file here for saved data dictionary + for file in files: + #Found a dictionary to re-compute the successFlag for + if file == "trialData.dict": + #Load dictionary + trialDataPath = os.path.join(path,"trialData.dict") + with open(trialDataPath, "rb") as trialDataFile: + trialResultsDict = pickle.load(trialDataFile) + #Reprocess! + reprocessedTrialDataDict = dictReprocessF(trialResultsDict) + #Guard against returning None (since that will destroy all the data) + if reprocessedTrialDataDict is None: + invalidTrialDataDict = "trialDataDict is None. Check that the updated data was returned" + raise ValueError(invalidTrialDataDict) + #Save again + with open(trialDataPath,'wb') as trialDataFile: + pickle.dump(reprocessedTrialDataDict,trialDataFile) + #And update human readable copy + trialDataTextPath = os.path.splitext(trialDataPath)[0]+'.txt' + with open(trialDataTextPath, "w",encoding="UTF-8") as textFile: + textFile.write(str(reprocessedTrialDataDict)) + #Update progress + pbar.update(1) + pbar.close() + +def runNewExperimentsWithOldData(absoluteSavedDataPath,reprocessOrRunNewExpF,newExperimentAbsoluteSavedDataPath,inputUpdateDict): + """ + Looks for all trialData.dict files in this directory and its subdirectories, then passes them to the + specified reprocessing method. The changed dictionary overwrites the original file. + + Parameters + ---------- + absoluteSavedDataPath : string + Absolute path to directory where we should look for and modify trailData.dict files. + dictReprocessF : function + Function to reprocess the trial data + newExperimentAbsoluteSavedDataPath : string + Absolute path to directory where we should save modified (or rerun) trailData.dict files. + """ + + + dummyDict = {"mergeData":False,"clobber":False} + try: + checkSaveDirectoryPathMakeIfNeeded(newExperimentAbsoluteSavedDataPath,dummyDict) + except FileExistsError: + print(f"Data already exists at {newExperimentAbsoluteSavedDataPath}! Overwrite?") + if not confirmDataDeletion(newExperimentAbsoluteSavedDataPath,data="ALL DATA"): + print("Aborting") + return -1 + dummyDict["clobber"] = True + checkSaveDirectoryPathMakeIfNeeded(newExperimentAbsoluteSavedDataPath,dummyDict) + + #This config file is the original experiments config + configFilePath = os.path.join(absoluteSavedDataPath, "config.yaml") + #Load raw yaml input + inputDict = getInputDict(configFilePath) + + #Make changes, and dump in new directory, won't be sorted, but will ensure the saved config is right + inputDict.update(inputUpdateDict) + yamlContent = yaml.dump(inputDict, sort_keys=False, default_flow_style = False, allow_unicode = True, encoding = None) + newConfigFilePath = os.path.join(newExperimentAbsoluteSavedDataPath, "config.yaml") + with open(newConfigFilePath, "w", encoding="utf-8") as configFile: + configFile.write(yamlContent) + #Overwrite if anything existed before, there shouldn't be + configFile.truncate() + #print(inputDict.keys()) + + experimentParamsDict, dummySaveDirectoryRelativePath = loadExperimentParams(inputDict) # pylint: disable=unbalanced-tuple-unpacking + setUpDataOutput(newExperimentAbsoluteSavedDataPath, experimentParamsDict, configFilePath) + + + pbar = tqdm(total=getNumberOfTrials(absoluteSavedDataPath)) + + processList = [] + + #Limit CPU cores to numProcesses! (To share better on servers) + cpuMask = range(100) + os.sched_setaffinity(os.getpid(), cpuMask) + #Use os.walk to search through every file here for saved data dictionaries + for path, dummyDirectories, files in os.walk(absoluteSavedDataPath): + #Look at each file here for saved data dictionary + for file in files: + #Found a dictionary to re-compute the successFlag for + if file == "trialData.dict": + trialDataPath = os.path.join(path,"trialData.dict") + #Check if we have a detached process + processReturn =reprocessOrRunNewExpF(trialDataPath,inputDict,newExperimentAbsoluteSavedDataPath) + if processReturn is not None: + processReturn.start() + if len(processList) <= 99: + processList.append(processReturn) + print(processReturn.is_alive(),processReturn.exitcode) + else: #This will be the 100th running, since it is started already + appendAndWaitUntilAProcessEnds(processReturn,processList,pbar) + + continue #Don't update the pbar, we'll do that when popping processes + #Update progress + pbar.update(1) + + #Join all processes! + for process in processList: + print(process.is_alive(),process.exitcode) + process.join() + pbar.update(1) + + pbar.close() + + return 0 + +def appendAndWaitUntilAProcessEnds(process,processList,pbar): + """ + Method that checks for finished process and joins then pops them. + Will not return until this is done + """ + + atLeastOneProcessEnded = False + processList.append(process) + + #Loop until we are done + while not atLeastOneProcessEnded: + #Go from the back to make popping work better + #We know there are 100 processes, as we ended up in here + for iProcess in range(99,0,-1): + #Check each for 10 ms. + processList[iProcess].join(.01) + #If joined, it has ended + if processList[iProcess].exitcode is not None: + processList.pop(iProcess) + atLeastOneProcessEnded = True + pbar.update(1) + + +def confirmDataDeletion(directory,data="data"): + """ + Confirms with the user before starting process that could delete data. + + Parameters + ---------- + directory : string + Path where the data will be deleted from. + data : string (default="data") + The specific data that can be removed + + Returns + ------- + confirmation : boolean + True if the user confirms, False otherwise. + """ + + sys.stdout.write(f"WARNING: This script can PERMANENTLY delete {data} in {directory}. Proceed [y/N]?") + choice = input().lower() + if choice in {"yes","y","ye"}: + return True + return False + +def getNumberOfTrials(absoluteSavedDataPath): + """ + Finds the total number of trials in the saved data + """ + + firstSolver = getSubFolders(absoluteSavedDataPath)[0] + numSolvers = getNumberOfFoldersInDirectory(absoluteSavedDataPath) + + firstSolverDirectoryPath = os.path.join(absoluteSavedDataPath,firstSolver) + firstNSimsPerTreeExperiment = getSubFolders(firstSolverDirectoryPath)[0] + numNSimsPerTreeExperiments = getNumberOfFoldersInDirectory(firstSolverDirectoryPath) + + firstNSimsPerTreeExperimentPath = os.path.join(firstSolverDirectoryPath,firstNSimsPerTreeExperiment) + numTrialsPerPoint = getNumberOfFoldersInDirectory(firstNSimsPerTreeExperimentPath) + + return numSolvers*numNSimsPerTreeExperiments*numTrialsPerPoint + +def getSubFolders(directory): + """ + Returns the names of the folders in a directory + """ + + return next(os.walk(directory))[1] + +def getNumberOfFoldersInDirectory(directory): + """ + Returns the number of sub folders in a directory + """ + return len(getSubFolders(directory)) +#Fixing a too-large tuple so will have a long method. +def reformatCache(experimentDataDirAbsolutePath,dieAndStayDead): # pylint: disable=too-many-statements + """ + Translates from original pickle cache to dictionary based cache. Shouldn't be needed anymore + """ + #newSafetyCachePath = os.path.join(experimentDataDirAbsolutePath,"safetyDataCache.dict") + oldSafetyCachePath = os.path.join(experimentDataDirAbsolutePath,"safetyTupleCache.pickle") + #load + with open(oldSafetyCachePath,'rb') as oldCache: + safetyTuple = pickle.load(oldCache) + empiricalSafetyValuesIdx = 0 + avgEmpSafetyIdx = 1 + trueSafetyValuesIdx = 2 + avgTrueSafetyIdx = 3 + nInfSafetyValuesIdx = 4 + avgNInfSafetyIdx = 5 + empiricalFalseNegativesIdx = 6 + empiricalFalsePositivesIdx = 7 + empiricalFalseNegativesTotalsIdx = 8 + empiricalFalsePositivesTotalsIdx = 9 + nInfFalsePositivesIdx = 10 + nInfFalseNegativesIdx = 11 + nInfFalseNegativesTotalsIdx = 12 + nInfFalsePositivesTotalsIdx = 13 + nSimulationsPerTreesIdx = 14 + lastBelievedCollisionFreeTStepsIdx = 15 + avgBelievedLastCollisionFreeTStepsIdx = 16 + lastTrueCollisionFreeTStepIdx = 17 + avgBelievedLastCollisionFreeTStepsIdx = 18 + beliefAlphaSafetyIdx = 19 + avgBeliefAlphaSafetyIdx = 20 + beliefAlphaFalsePositivesIdx = 21 + beliefAlphaFalseNegativesIdx = 22 + + beliefAlphaFalseNegativesTotalsIdx = 23 + beliefAlphaFalsePositivesTotalsIdx = 24 + #Convert to dict + safetyDataDict = {} + safetyDataDict["empiricalSafetyValues"] = safetyTuple[empiricalSafetyValuesIdx] + safetyDataDict["avgEmpSafety"] = safetyTuple[avgEmpSafetyIdx] + + safetyDataDict["trueSafetyValues"] = safetyTuple[trueSafetyValuesIdx] + safetyDataDict["avgTrueSafety"] = safetyTuple[avgTrueSafetyIdx] + + safetyDataDict["nInfSafetyValues"] = safetyTuple[nInfSafetyValuesIdx] + safetyDataDict["avgNInfSafety"] = safetyTuple[avgNInfSafetyIdx] + + safetyDataDict["empiricalFalseNegatives"] = safetyTuple[empiricalFalseNegativesIdx] + safetyDataDict["empiricalFalsePositives"] = safetyTuple[empiricalFalsePositivesIdx] + + safetyDataDict["empiricalFalseNegativesTotals"] = safetyTuple[empiricalFalseNegativesTotalsIdx] + safetyDataDict["empiricalFalsePositivesTotals"] = safetyTuple[empiricalFalsePositivesTotalsIdx] + + safetyDataDict["nInfFalseNegatives"] = safetyTuple[nInfFalsePositivesIdx] + safetyDataDict["nInfFalsePositives"] = safetyTuple[nInfFalseNegativesIdx] + + safetyDataDict["nInfFalseNegativesTotals"] = safetyTuple[nInfFalseNegativesTotalsIdx] + safetyDataDict["nInfFalsePositivesTotals"] = safetyTuple[nInfFalsePositivesTotalsIdx] + + safetyDataDict["lastBelievedCollisionFreeTSteps"] = safetyTuple[lastBelievedCollisionFreeTStepsIdx] + safetyDataDict["avgBelievedLastCollisionFreeTSteps"] = safetyTuple[avgBelievedLastCollisionFreeTStepsIdx] + + safetyDataDict["lastTrueCollisionFreeTSteps"] = safetyTuple[lastTrueCollisionFreeTStepIdx] + safetyDataDict["avgTrueLastCollisionFreeTSteps"] = safetyTuple[avgBelievedLastCollisionFreeTStepsIdx] #note wrong! + + safetyDataDict["beliefAlphaSafetyValues"] = safetyTuple[beliefAlphaSafetyIdx] + safetyDataDict["avgBeliefAlphaSafety"] = safetyTuple[avgBeliefAlphaSafetyIdx] + + safetyDataDict["beliefAlphaFalsePositives"] = safetyTuple[beliefAlphaFalsePositivesIdx] + safetyDataDict["beliefAlphaFalseNegatives"] = safetyTuple[beliefAlphaFalseNegativesIdx] + + safetyDataDict["beliefAlphaFalseNegativesTotals"] = safetyTuple[beliefAlphaFalseNegativesTotalsIdx] + safetyDataDict["beliefAlphaFalsePositivesTotals"] = safetyTuple[beliefAlphaFalsePositivesTotalsIdx] + + safetyDataDict["nSimulationsPerTrees"] = safetyTuple[nSimulationsPerTreesIdx] + safetyDataDict["numTimeSteps"] = len(safetyTuple[0][0,0,0]) + + #To determine if this cache matches later + safetyDataDict["dieAndStayDead"] = dieAndStayDead + + #Save this + cacheData(experimentDataDirAbsolutePath,safetyDataDict) + +def cacheData(experimentDataDirAbsolutePath,safetyDataDict,cacheName=None): + """ + Saves safety data to save time re-loading it + """ + safetyCachePath = getCachePath(experimentDataDirAbsolutePath,cacheName) + + with open(safetyCachePath,'wb') as safetyCacheFile: + pickle.dump(safetyDataDict,safetyCacheFile) + +def getCachePath(experimentDataDirAbsolutePath,cacheName=None): + """ + Creates path for cache file + """ + if cacheName is not None: + return os.path.join(experimentDataDirAbsolutePath,f"{cacheName}.dict") + return os.path.join(experimentDataDirAbsolutePath,"safetyDataCache.dict") + + +if __name__ == "__main__": + #CONFIG_FILE_PATH = "../config/chebyshevSafetyLinearModelTest.yaml" + #reprocessDataAverages(CONFIG_FILE_PATH,os.path.dirname(os.getcwd())) + + SAVED_DATA_DIRECTORY = "/mnt/i/jplFeastSavedData/SavedData/nonLinearSafetyTestTrueCrashScenario10s90Confidence1000LowSigma" + reprocessDataAverages(os.path.join(SAVED_DATA_DIRECTORY,"config.yaml"),os.path.dirname(os.path.dirname(SAVED_DATA_DIRECTORY))) diff --git a/failurePy/utility/savedTreeRemover.py b/failurePy/utility/savedTreeRemover.py new file mode 100644 index 0000000..24affcc --- /dev/null +++ b/failurePy/utility/savedTreeRemover.py @@ -0,0 +1,43 @@ +""" +Script that removes the tree from saved data dictionaries for data compression. Useful when accidentally starting a run with saveTreeFlag=True + +WARNING! PERMANENTLY DELETES DATA +""" + +from failurePy.utility.reprocessData import confirmDataDeletion, reprocessTrialDataDicts + +def removeSavedTree(absoluteSavedDataPath): + """ + Removes saved tree data from the specified directory + + Parameters + ---------- + absoluteSavedDataPath : string + Absolute path to directory where the tree data will be deleted from. + """ + + #Guard on user confirmation + if confirmDataDeletion(absoluteSavedDataPath,"saved tree data"): + reprocessTrialDataDicts(absoluteSavedDataPath,removeSavedTreeFromTrialDataDict) + + else: + print("Saved Tree Data will not be removed") + +def removeSavedTreeFromTrialDataDict(trialResultsDict): + """ + Removes saved tree data from the specified dictionary + + Parameters + ---------- + trialResultsDict : dict + trial data we will remove the saved tree from + """ + + #Look if it has a tree (no need to overwrite if it doesn't have it) + if "treeList" in trialResultsDict: + trialResultsDict.pop("treeList") + return trialResultsDict + +if __name__ == "__main__": + SAVED_DATA_DIRECTORY = None #SET TO THE DIRECTORY YOU WISH TO DELETE TREE DATA FROM + removeSavedTree(SAVED_DATA_DIRECTORY) diff --git a/failurePy/utility/saving.py b/failurePy/utility/saving.py new file mode 100644 index 0000000..37e1dcb --- /dev/null +++ b/failurePy/utility/saving.py @@ -0,0 +1,558 @@ +""" +File for the functions need for saving the data +""" + +import os +import time + +import shutil +from importlib.metadata import version +import datetime +from hashlib import md5 +from inspect import getsource + +#import sys +import pickle +import errno +import numpy as onp +from tqdm import tqdm +import yaml + +import jax.numpy as jnp + + +#FailurePy files for hashing to verify version +from failurePy.estimators import extendedKalmanFilterLinearSensing, kalmanFilter,kalmanFilterCommon, marginalizedFilter +from failurePy.utility.pipelineHelperMethods import diagnoseFailure + + +def processDataAverages(saveDirectoryAbsolutePath, experimentParamsDict,): + """ + Logs data for future analysis + + Parameters + ---------- + saveDirectoryAbsolutePath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + Relevant contents as follows: + nSimulationsPerTreeList : list, len(numTrials) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + dt : float + The time between time steps of the experiment + nExperimentSteps : int + How many time steps are in the experiment + nTrialsPerPoint : int + The number of repeated trials per configuration. + nMaxComponentFailures : int + Maximum number of simultaneous failures of components that can be considered + nMaxPossibleFailures : int + Maximum number of possible failures to consider. If larger than the number of possible unique failures, all possibilities are considered + providedFailure : array, shape(numAct+numSen) (default=None) + Provided failure (if any) to have each trial use + systemF : function + Function reference of the system to call to run experiment + systemParametersTuple : tuple + Tuple of system parameters needed + solverFList : list + List of solver functions to try + solverParametersListsList : list + List of lists of solver parameters. Included action list, failure scenarios + solverNamesList: list + List of names of solvers, for data logging + estimatorF : function + Estimator function to update the beliefs with. Takes batch of filters + physicalStateSubEstimatorF : function + Physical state estimator for use with the marginal filter, if any + physicalStateJacobianF : function + Jacobian of the model for use in estimating. + physicalStateSubEstimatorSampleF : function + Samples from the belief corresponding to this estimator + beliefInitializationF : function + Function that creates the initial belief + rewardF : function + Reward function to evaluate the beliefs with + rngKeysOffset : int + Offset to the initial PRNG used in generating the initial failure states and randomness in the trials. This is added to the trial number to allow for different trials to be preformed + multiprocessingFlag : boolean + Wether to use multi-processing or not + saveTreeFlag : boolean + Whether to save the tree or not (it can be quite large, so if not visualizing, it is best to set this to false) + clobber : boolean + Wether to overwrite existing data or not + """ + + + #Loop through solvers + for solverName in experimentParamsDict["solverNamesList"]: + solverDirectoryPath = os.path.join(saveDirectoryAbsolutePath,solverName) + + #Loop through each number of sims per tree + for nSimulationsPerTree in experimentParamsDict["nSimulationsPerTreeList"]: + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + + #Make arrays to average quantities over. We use numpy here because speed isn't a priority and flexibility is nice + avgRewards = onp.zeros(experimentParamsDict["nExperimentSteps"]+1) #Need to add one because we track initial reward too! + cumulativeAvgRewards = onp.zeros(experimentParamsDict["nExperimentSteps"]+1) #Need to add one because we track initial reward too! + avgSuccessRate = 0 + avgWallClockTime = 0 + avgSteps = 0 + #Also take the variance! + varRewards = onp.zeros(experimentParamsDict["nExperimentSteps"]+1) #Need to add one because we track initial reward too! + cumulativeVarRewards = onp.zeros(experimentParamsDict["nExperimentSteps"]+1) #Need to add one because we track initial reward too! + varWallClockTime = 0 + + #Loop through each trial (Might be inefficient? Will check later) + for nTrial in tqdm(range(experimentParamsDict["nTrialsPerPoint"])): + nTrialPath = os.path.join(nSimPath,str(nTrial+experimentParamsDict["rngKeysOffset"])) #Make directory according to the rngKeyUSed + + #Load in trial results (pickled) + trialDataPath = os.path.join(nTrialPath,"trialData.dict") + with open(trialDataPath, "rb") as trialDataFile: + trialResultsDict = pickle.load(trialDataFile) + + #Deal with nans, which can occur when the EKF goes unstable. We will treat these as 0 reward, and set success to zero for this trial + trialRewards = trialResultsDict["rewards"] + if onp.isnan(trialRewards[-1]): + trialRewards[onp.isnan(trialRewards)] = 0 + trialResultsDict["success"] = 0 + + #Add quantities to the average totals + avgRewards = onp.add(avgRewards,trialResultsDict["rewards"]) + cumulativeAvgRewards = onp.add(cumulativeAvgRewards,onp.cumsum(trialResultsDict["rewards"])) + #Might set success rate to nan if we don't want to count failing to converge against alg, so check for this + if not onp.isnan(trialResultsDict["success"]): + avgSuccessRate += trialResultsDict["success"] + avgWallClockTime += trialResultsDict["wallClockTime"] + avgSteps += trialResultsDict["steps"] + + avgRewards = avgRewards/experimentParamsDict["nTrialsPerPoint"] + cumulativeAvgRewards = cumulativeAvgRewards/experimentParamsDict["nTrialsPerPoint"] + avgWallClockTime = avgWallClockTime/experimentParamsDict["nTrialsPerPoint"] + + #Compute variance as well (need to already know the average rewards, so have to loop again) + for nTrial in tqdm(range(experimentParamsDict["nTrialsPerPoint"])): + nTrialPath = os.path.join(nSimPath,str(nTrial+experimentParamsDict["rngKeysOffset"])) #Make directory according to the rngKeyUSed + + #Load in trial results (pickled) + trialDataPath = os.path.join(nTrialPath,"trialData.dict") + with open(trialDataPath, "rb") as trialDataFile: + trialResultsDict = pickle.load(trialDataFile) + + varRewards = onp.add(varRewards, onp.square(onp.subtract(trialResultsDict["rewards"],avgRewards))) + cumulativeVarRewards = onp.add(cumulativeVarRewards, onp.square(onp.subtract(onp.cumsum(trialResultsDict["rewards"]),cumulativeAvgRewards))) + varWallClockTime += (trialResultsDict["wallClockTime"] - avgWallClockTime)**2 + + #Take average + experimentAverageDataDict = { + "avgRewards" : avgRewards, + "cumulativeAvgRewards": cumulativeAvgRewards, + "avgSuccessRate" : avgSuccessRate/experimentParamsDict["nTrialsPerPoint"], + "avgWallClockTime" : avgWallClockTime, + "avgSteps" : avgSteps/experimentParamsDict["nTrialsPerPoint"], + "varRewards" : varRewards/(experimentParamsDict["nTrialsPerPoint"]-1), + "cumulativeVarRewards" : cumulativeVarRewards/(experimentParamsDict["nTrialsPerPoint"]-1), + "varWallClockTime" : onp.float64(varWallClockTime)/(experimentParamsDict["nTrialsPerPoint"]-1), #Guarding against divide by zero + } + + #And save averages + #For now just pickle dump the full dictionary, consider more sophisticated saving later + + experimentDataPath = os.path.join(nSimPath,"averageData.dict") + with open(experimentDataPath,'wb') as experimentDataFile: + pickle.dump(experimentAverageDataDict,experimentDataFile) + + + + + +def saveMetaData(saveDirectoryPath,experimentParamsDict): + """ + Saves meta data for the experiment + + Parameters + ---------- + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + """ + + + #Make yaml file + metaData = makeMetaData(experimentParamsDict) + + #Write to file + with open(os.path.join(saveDirectoryPath,"metaData.yaml"), "w", encoding = "utf-8") as metaDataFile: + metaDataFile.write(metaData) + #Overwrite if anything existed before (we checked with user already!) + metaDataFile.truncate() + +def copyConfigFileIfNeeded(saveDirectoryAbsolutePath,configFilePath): + """ + Saves meta data for the experiment by copying config file. Doesn't copy if paths are the same + + Parameters + ---------- + saveDirectoryAbsolutePath + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + configFilePath : String + Relative (or absolute) path to the config file for the experiment + """ + + saveConfigFilePath = os.path.join(saveDirectoryAbsolutePath,"config.yaml") + + #Don't copy if a file already exists + if os.path.exists(saveConfigFilePath): + return + try : + shutil.copyfile(configFilePath,saveConfigFilePath) + except shutil.SameFileError: + pass #Don't need to do anything here, as we are saving the data to the folder the config already exists in + +def saveFailurePyVersion(saveDirectoryAbsolutePath): + """ + Saves the current failurePy version, to make future experiments more readily reproducible. + + Parameters + ---------- + saveDirectoryAbsolutePath + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + """ + + versionFilePath = os.path.join(saveDirectoryAbsolutePath,"version.txt") + + with open(versionFilePath, 'w',encoding="UTF-8") as versionFile: + versionFile.write(version('failurePy')) #NEED TO MAKE SURE PIP UPDATES VERSION NUMBER, it won't be default in the -e format unless you manually re-install + #Add time stamp as well + versionFile.write(" " + str(datetime.datetime.now())) + versionFile.write("\n\n") + versionFile.write(getEstimatorsHash()) + +def getEstimatorsHash(): + """ + Method that provides hash of the estimation methods, to identify if they have changed (useful when testing different estimation ideas in hard code) + + Hardcoded now for repeatability + """ + #Start hash + estimatorHash = md5() + estimatorHash.update(getsource(extendedKalmanFilterLinearSensing).encode(encoding = 'UTF-8')) + estimatorHash.update(getsource(kalmanFilter).encode(encoding = 'UTF-8')) + estimatorHash.update(getsource(kalmanFilterCommon).encode(encoding = 'UTF-8')) + estimatorHash.update(getsource(marginalizedFilter).encode(encoding = 'UTF-8')) + return estimatorHash.hexdigest() + +def makeMetaData(experimentParamsDict): + """ + Function that makes meta data file from the experimentParamsDict + + Parameters + ---------- + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + + Returns + ------- + metaDataString : str + String of all the meta data + """ + + return yaml.dump(experimentParamsDict, sort_keys=False) + +def checkIfDataExists(dataPath): + """ + Function that checks if data exists at the specified path + + Parameters + ---------- + dataPath : string + Absolute path to data to check for. + + Returns + ------- + dataExistsFlag : boolean + True if data exists + """ + + return os.path.isfile(dataPath) + + + + +def checkSaveDirectoryPathMakeIfNeeded(saveDirectoryAbsolutePath,experimentParamsDict): + """ + Checks if the directory exists, making it if not, and prompting the user if it already exists and is incompatible with + the current experiment + + Parameters + ---------- + saveDirectoryAbsolutePath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + """ + + #Now we check if any data exists (by checking the meta data) + if os.path.exists(saveDirectoryAbsolutePath): + #Merge with existing data (this is blind for now) + if experimentParamsDict["mergeData"]: + return #Don't touch existing data + + #Check for clobber param + if experimentParamsDict["clobber"]: + shutil.rmtree(saveDirectoryAbsolutePath) + else: + #Check if there is anything other than config.yaml + itemsInSaveDirectory = os.listdir(saveDirectoryAbsolutePath) + for item in itemsInSaveDirectory: + #This should only trigger in the case that we are saving in the directory the config file exists. + if not os.path.isfile(os.path.join(saveDirectoryAbsolutePath,item)) or not item == "config.yaml": + dataExists = f"Data ({item}) already exists at {saveDirectoryAbsolutePath}! To overwrite, set to true in the config yaml file." + raise FileExistsError(dataExists) + + + #Now check for the folders to exist and make them if not + makeDirectoryAndParents(saveDirectoryAbsolutePath) + + +def makeDirectoryAndParents(saveDirectoryPath): + """ + Recursively makes directory, making parents as needed + + Parameters + ---------- + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + """ + + #Check if the directory exists + if os.path.exists(saveDirectoryPath): + return + + #Split off the parent path to check it + parentPath = saveDirectoryPath.rsplit("/",1) + + #Check if the path used \\ instead. + if parentPath[0] == saveDirectoryPath: + parentPath = saveDirectoryPath.rsplit("\\",1) + + #If we still failed to split, we don't have a parent. Otherwise let's check that it exists or make it + if parentPath[0] != saveDirectoryPath: + makeDirectoryAndParents(parentPath[0]) + print(f"Making {saveDirectoryPath}") + #Now make this directory + os.mkdir(saveDirectoryPath) + +def checkOrMakeDirectory(saveDirectoryPath,subDirectory): + """ + Makes subdirectory (if it doesn't exist) in the saveDirectoryPath + + Parameters + ---------- + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + subDirectory : str + String of the subdirectory to make. Should NOT have further subDirectories under it. + + Returns + ------- + subDirectoryPath : str + Path to the new directory, or None if it failed + returnCode : int + Flag on the result of the operation. Possible values: + 2 : Directory already exists + 1 : Nominal success + -1 : Failed to make directory because it already exists. + -2 : subDirectory has further sub directories (\\ ir / characters in the string) + """ + if "\\" in subDirectory or "/" in subDirectory: + return None, -2 + + subDirectoryPath = os.path.join(saveDirectoryPath,subDirectory) + if os.path.exists(subDirectoryPath): + return subDirectoryPath, 2 + + #Attempt to make the directory + try: + os.mkdir(subDirectoryPath) + return subDirectoryPath, 1 + #Catches directory already exists error. Raises if it is a different OSError (like out of space or permission denied) + except OSError as exc: + + if exc.errno != errno.EEXIST: + raise #Re-raises the exception + return None, -1 + +def makeTrialResultDict(physicalStateList,failureStateList,beliefList,rewards,actionList,initialFailureParticles,success,timeStep,wctStartTime,saveTreeFlag,treeList,computeSafetyAtEnd=False): + """ + Helper function that makes the trial result dictionary + (since it has a lot of members and to minimize repeat code) + """ + trialResultsDict = {"physicalStateList" : physicalStateList, + "failureStateList" : failureStateList, + "beliefList" : beliefList, + "rewards" : rewards, + "actionList" : actionList, + "possibleFailures" : initialFailureParticles, #Not changing name for backwards compatibility issue, should be okay because general faults will not be using this + "success" : success, + #0 indexed to 1 index on experiment time (NOTE the length of all of our lists is timeStep + 2) + "steps": timeStep+1, #Assuming nExperimentSteps is > 0, pylint: disable=undefined-loop-variable + "wallClockTime" : (time.time()-wctStartTime)/(timeStep+1)} #Assuming nExperimentSteps is > 0, pylint: disable=undefined-loop-variable + + if computeSafetyAtEnd: + trialResultsDict = updateSuccessStatusAndSafetyOfTrialDataDict(trialResultsDict) + + #Now add None to the end of the trees (if saving the tree) + if saveTreeFlag: #Only save tree if told to + treeList.append(None) + trialResultsDict["treeList"] = treeList + return trialResultsDict + +def updateSuccessStatusAndSafetyOfTrialDataDict(trialResultsDict): + """ + Recomputes success based on the last belief of this trial using sub method and also + computes when the system is first unsafe. + + Parameters + ---------- + trialResultsDict : dict + trial data we will recompute the success on + """ + + #Update success of trials + trialResultsDict = updateSuccessStatusOfTrialDataDict(trialResultsDict) + + rewards = trialResultsDict["rewards"] + #Loop through and see when we become unsafe (die and stay dead logic) + lastBelievedCollisionFreeTStep = -1 + for reward in rewards: + if reward == 0: + break + lastBelievedCollisionFreeTStep += 1 + trialResultsDict["lastBelievedCollisionFreeTStep"] = lastBelievedCollisionFreeTStep + return trialResultsDict + + +def updateSuccessStatusOfTrialDataDict(trialResultsDict): + """ + Recomputes success based on the last belief of this trial + + Parameters + ---------- + trialResultsDict : dict + trial data we will recompute the success on + """ + + #Get the beliefList last entry and true failure + lastBelief = trialResultsDict["beliefList"][-1] + failure = trialResultsDict["failureStateList"][-1] + + #Get predicted failure + diagnosis = diagnoseFailure(lastBelief, trialResultsDict["possibleFailures"]) + + if jnp.all(diagnosis == failure): + trialResultsDict["success"] = 1 + + return trialResultsDict + +def setUpDataOutput(saveDirectoryPath, experimentParamsDict, configFilePath): + """ + Creates directories for logging data + + Parameters + ---------- + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + experimentParamsDict : dict + Dictionary containing all the relevant experiment parameters. + Relevant parameters: + nSimulationsPerTreeList : list, len(numTrials) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + nTrialsPerPoint : int + The number of repeated trials per configuration. + solverNamesList: list + List of names of solvers, for data logging + rngKeysOffset : int + Offset to the initial PRNG used in generating the initial failure states and randomness in the trials. + This is added to the trial number to allow for different trials to be preformed + configFilePath : String + Relative path to the config file for the experiment + """ + + #Copy original config file over. Don't copy if they are already the same + copyConfigFileIfNeeded(saveDirectoryPath,configFilePath) + #Save version (this will make repeating experiments easier) + saveFailurePyVersion(saveDirectoryPath) + + #Loop through each solver + for solverName in experimentParamsDict["solverNamesList"]: + #Check if the directory exists already (in case of merging compatible data ) + #Otherwise make directory (returnCode for future handling of existing directories. + #Returns -1 if it fails, -2 if it fails due to SolverName having / or \\ in it, shouldn't happen) + solverDirectoryPath,returnCode = checkOrMakeDirectory(saveDirectoryPath,solverName) + if not returnCode == 1: + unexpectedDirectoryReturn = f"Checking the directory {solverDirectoryPath} gave an unexpected result, error code {returnCode}. Error handling not implemented yet" + raise NotImplementedError(unexpectedDirectoryReturn) #Not trying to handle anything complicated yet. + + #Loop through each number of sims per tree we try and make sub folders for each + for nSimulationsPerTree in experimentParamsDict["nSimulationsPerTreeList"]: + #Check if the directory exists already (in case of merging compatible data ) + #Otherwise make directory (returnCode for future handling of existing directories. Returns -1 if it fails, -2 if it fails due to SolverName having / or \\ in it, shouldn't happen) + nSimPath,returnCode = checkOrMakeDirectory(solverDirectoryPath,str(nSimulationsPerTree)) + if not returnCode == 1: + unexpectedDirectoryReturn = f"Checking the directory {solverDirectoryPath} gave an unexpected result, error code {returnCode}. Error handling not implemented yet" + raise NotImplementedError(unexpectedDirectoryReturn) #Not trying to handle anything complicated yet. + + #Now we create folders for each trial (Might be inefficient? Will check later) + for nTrial in range(experimentParamsDict["nTrialsPerPoint"]): + #Check if the directory exists already (in case of merging compatible data ) + #Otherwise make directory (returnCode for future handling of existing directories. Returns -1 if it fails, -2 if it fails due to SolverName having / or \\ in it, shouldn't happen) + dummyNTrialPath,returnCode = checkOrMakeDirectory(nSimPath,str(nTrial+experimentParamsDict["rngKeysOffset"])) #Make directory according to the rngKeyUSed + if not returnCode == 1: + unexpectedDirectoryReturn = f"Checking the directory {nSimPath} gave an unexpected result, error code {returnCode}. Error handling not implemented yet" + raise NotImplementedError(unexpectedDirectoryReturn) #Not trying to handle anything complicated yet. + #We are now as low down as we need to go + #We're done pre-allocating + +def saveTrialResult(saveDirectoryPath, solverName, nSimulationsPerTree, nTrial,trialResultDict): + """ + Method that saves a single experiment result + + Parameters + ---------- + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + solverName : str + Names of solver to log under + nSimulationsPerTree : int + Number of simulations per tree to log under + nTrial : int + Trial number to log under (rng seed used) + """ + #Save the data to the pre-created directories (made when setUpDataOutput is called) + + trialDataPath = getTrialDataPath(saveDirectoryPath, solverName, nSimulationsPerTree, nTrial) + + with open(trialDataPath,'wb') as trialDataFile: + pickle.dump(trialResultDict,trialDataFile) + + #Dump as text file for human readability (trialDataPath ends in .dict, change to .txt) + trialDataTextPath = os.path.splitext(trialDataPath)[0] + ".txt" + with open(trialDataTextPath, "w",encoding="UTF-8") as textFile: + textFile.write(str(trialResultDict)) + +def getTrialDataPath(saveDirectoryPath, solverName, nSimulationsPerTree, nTrial): + """ + Helper function that makes path to save trialDataDict at + """ + + solverDirectoryPath = os.path.join(saveDirectoryPath,solverName) + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + nTrialPath = os.path.join(nSimPath,str(nTrial)) #Make directory according to the rngKeyUSed + + #For now just pickle dump the full dictionary, consider more sophisticated saving later + return os.path.join(nTrialPath,"trialData.dict") diff --git a/failurePy/utility/smoothStep.py b/failurePy/utility/smoothStep.py new file mode 100644 index 0000000..29c9eb3 --- /dev/null +++ b/failurePy/utility/smoothStep.py @@ -0,0 +1,25 @@ +""" +Module to create a smooth step function. + +May be extended to have several useful functions in the future/jax implementations +""" + +from scipy.special import comb +import numpy as onp + + +#Credit: Jonas Adler on stackoverflow for the implementation +def smoothStep(xVal, xMin=0, xMax=1, maxDerivative=1): + """ + Smoothly interpolates between xMin and xMax, with the first + maxDerivatives being continuous + """ + xVal = onp.clip((xVal - xMin) / (xMax - xMin), 0, 1) + + result = 0 + for nDerivative in range(0, maxDerivative + 1): + result += comb(maxDerivative + nDerivative, nDerivative) * comb(2 * maxDerivative + 1, maxDerivative - nDerivative) * (-xVal) ** nDerivative + + result *= xVal ** (maxDerivative + 1) + + return result diff --git a/failurePy/utility/tqdmMultiprocessing.py b/failurePy/utility/tqdmMultiprocessing.py new file mode 100644 index 0000000..e3c61b1 --- /dev/null +++ b/failurePy/utility/tqdmMultiprocessing.py @@ -0,0 +1,73 @@ +""" +File with functions for using tqdm with multiprocessing or recursion to give interpretable results. +""" + +from queue import Empty #Can't get this directly from mp.Queue +from tqdm import tqdm + +def initializeProcessTqdm(rank,total): + """ + Initializes the progress bar for each process. Only does so if at the top level or in the first process. + + Parameters + ---------- + rank : int + Level or the process call, 0 if top level for first process + total : int + Total number of steps the bar should be tracking + + Returns + ------- + progressBar : tqdmProgressBar + Progress bar object to be updated + """ + progressBar = None + if rank == 0: + progressBar = initializeTqdm(total=total) + return progressBar + +def initializeTqdm(total): + """ + Initializes the progress bar. + + Parameters + ---------- + total : int + Total number of steps the bar should be tracking + + Returns + ------- + progressBar : tqdmProgressBar + Progress bar object to be updated + """ + + return tqdm(total=total) + + +def updateTqdmMultiProcess(processID,totalPerWorker,queueObject,progressBar): + """ + Updates the progress bar, by either updating the display (top level or first process) + or putting the an update into the queue for the first process to update + Only needed by the multiprocessing methods + + Parameters + ---------- + processID : int + Number representing the process call, 0 if top level for first process + total : int + Total number of steps the bar should be tracking + queue : multiprocessing queue + Queue object to send progress updates through + progressBar : tqdmProgressBar + Progress bar object to be updated + """ + if processID == 0: + count = totalPerWorker + try: + while True: + count += queueObject.get_nowait() + except Empty: + pass + progressBar.update(count) + else: + queueObject.put_nowait(totalPerWorker) diff --git a/failurePy/visualization/__init__.py b/failurePy/visualization/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/failurePy/visualization/figure5andFigureS3.ipynb b/failurePy/visualization/figure5andFigureS3.ipynb new file mode 100644 index 0000000..58bca03 --- /dev/null +++ b/failurePy/visualization/figure5andFigureS3.ipynb @@ -0,0 +1,408 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 42, + "metadata": {}, + "outputs": [ + { + "data": { + "text/html": [ + "" + ], + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "\"\"\"\n", + "This notebook generates the Figure 5 of our paper\n", + "\"\"\"\n", + "\n", + "from IPython.display import display, HTML\n", + "display(HTML(\"\"))\n", + "import numpy as onp\n", + "#Ignore matplotlib warnings'\n", + "import warnings\n", + "warnings.filterwarnings( \"ignore\", module = r\"matplotlib\\..*\" )\n", + "\n", + "\n", + "from failurePy.visualization.visualization import plotDataRewardStd\n", + "\n", + "#Get data processing tools (now in a module to avoid code re-use)\n", + "\n", + "from failurePy.utility.dataAnalysisFunctions import loadAndComputeSafetyData\n", + "\n", + "#Get plotting methods (now in a module for better structure)\n", + "from failurePy.visualization.visualization import plotTrueSafetyOursVsBaselines" + ] + }, + { + "cell_type": "code", + "execution_count": 28, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Binary Easy\n", + "plotDataRewardStd(\"figure5/binaryProximityOperations\",[\"SFEAST\"],.4,successRateAdjustmentFlag=True,systemName=\"Average Reward for Each Policy\",tSteps=15,\n", + " baselineExpName=\"figure5/binaryProximityOperationsBaselines\")" + ] + }, + { + "cell_type": "code", + "execution_count": 29, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Binary Easy.\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figure5/binaryProximityOperations\"\n", + "fixedSafetyData = loadAndComputeSafetyData(experimentPath,[\"SFEAST\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False)\n", + "\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figure5/binaryProximityOperationsBaselines\"\n", + "Baselines = loadAndComputeSafetyData(experimentPath,[\"greedy\",\"cbf\",\"scp\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False)\n", + "\n", + "timeSteps = onp.arange(fixedSafetyData[\"numTimeSteps\"])\n", + "\n", + "\n", + "plotTrueSafetyOursVsBaselines(timeSteps,fixedSafetyData[\"trueSafetyValues\"],Baselines[\"trueSafetyValues\"],[\"s-FEAST\",\"Greedy\",\"CBF\",\"SCP\"],fixedSafetyData[\"nSimulationsPerTrees\"],figTitleExpName=None,#In paper will label with caption figTitleExpName=\"Crash Course Under Worst Case Failure\",\n", + " threshold=.9)" + ] + }, + { + "cell_type": "code", + "execution_count": 30, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAACoYAAAZ9CAYAAADmU3b1AAAAOXRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjguMiwgaHR0cHM6Ly9tYXRwbG90bGliLm9yZy8g+/7EAAAACXBIWXMAAD2EAAA9hAHVrK90AAEAAElEQVR4nOzdd3RU5dbH8V9CGiT0ItJD711aaAEURZEmRUAQpNqu2LtYwF6vFenSRFQQAdFIE6R3pErvLZR0EnLeP3jhWiDzTOacmUn4ftaate7Ffc7eM5k5Z8o++wmwLMsSAAAAAAAAAAAAAAAAAAAAsrxAXxcAAAAAAAAAAAAAAAAAAAAAe9AYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAAAAAAAAAACQTdAYCgAAAAAAAAAAAAAAAAAAkE3QGAoAAAAAAAAAAAAAAAAAAJBN0BgKAAAAAAAAAIANWrZsqYCAgAxvZcqU8XWZfmP79u368ssv9fDDD6tt27aqUaOGbrjhBkVERCgoKMjlYxkQEODruwAA2cq+ffuMjr3Dhw/3dalAtjd8+HCj1+O+fftszVumTBmXOVu2bGlrTgAA4IwgXxcAAAAAAAAAAACuD7t27dKYMWM0ZcoUHTx40NflAAAAAAAAZEs0hgIAAAAAAAAAAEcdOXJETz31lKZOnaqLFy/6uhwAAAAAAIBsjcZQAAAA+J0uXbrou+++M47v27evxo8f71xBAAD4gNPL4wYHBys0NFShoaHKmzevihQpoiJFiqh06dKqXLmyqlSporp16ypv3ryO1gEAyP6+/fZbDRgwQGfPnvV1KYCx4cOH6+WXX/Z1GR7h+xIg+9i9e7dSU1Md2XdAQICCgoIUFham0NBQ5cmTRyEhIY7kAgAAgPfQGAoAAAC/curUKc2ePdutbWbMmKGPP/5YERERDlUFAED2k5qaqtTUVMXHx+v06dPas2fPv2ICAwNVo0YNtWzZUl26dFFUVJQCAwN9UC0AIKv6+OOP9fDDD8uyLF+XAgBAltW6dWvt37/fa/kKFCigG264QZGRkapataqqVaumxo0bq1KlSl6rAQAAAJ6hMRQAAAB+ZdKkSW5f/Z6QkKDp06erf//+DlUFAMD1KT09XRs3btTGjRv14YcfqlixYho0aJCGDh2qIkWK+Lo8AICfmzFjBk2hAABkQbGxsYqNjdW2bds0d+7cK/9etGhRtWnTRj169NAtt9yi4OBgH1YJAACAjDDiAQAAAH5l3LhxXt0OAACYO3LkiIYPH65SpUrpqaeeUlxcnK9LAgD4qcOHD2vAgAE0hQIAkI0cO3ZMkyZN0h133KEbb7xRL774ok6ePOnrsgAAAHAVNIYCAADAb6xdu1abNm3K1LZLly7Vrl27bK4IAABcTUpKit566y1VrFhR8+bN83U5AAA/9MQTT+jcuXO+LgMAADjk9OnTevXVV1W6dGkNHz5cycnJvi4JAAAAf8FS8gAAAPAbnk79HDdunEaOHGlTNQAAwJVjx47p9ttv1zPPPKMRI0b4uhwAgJ/Yvn27vv76a+P4kJAQtWvXTg0aNFCNGjWUP39+5c2bV0FB/IQBAIC/S0pK0ssvv6xJkyZpypQpatCgga9LAgAAgGgMBQAAgJ9ISUnRlClTPNrHxIkT9dprrykwkMH4AAB4i2VZGjlypE6dOqXPP/9cAQEBvi4JAOBjo0ePVnp6ulHskCFD9Morr6hw4cIOVwUAAJy0e/duNWvWTP/97381aNAgX5cDAABw3eMXcwAAAPiFmTNn6syZMx7t4/Dhw/r5559tqggAALhj1KhRevLJJ31dBgDAD0ybNs0o7vXXX9dnn31GUygAANnEhQsXNHjwYL399tu+LgUAAOC6x8RQAAAA+AVPl5G/bOzYsbr11ltt2RcAAFnBAw88oAcffNDt7eLi4nT27FmdPXtWR48e1apVq7Ry5Ur9+eefma7lnXfeUf369dW9e/dM7wMAkLVt2bJFhw8fdhnXoEEDPfXUU16oCAAAeNuTTz6p3Llza8iQIb4uBQAA4LpFYygAAAB87tChQ/rll19s2dcPP/yg2NhYFShQwJb9AQDg7woVKqTKlSvbtr/Dhw/rs88+05dffqkTJ064vf3999+v1q1bq1ChQrbVBADIOpYuXWoUN2TIEAUEBDhcDeAdlmX5ugQAkCT17dtX48ePd3u7+Ph4xcbGKjY2VocPH9ayZcv022+/afXq1UpJSclULQ8//LBq1KihqKioTG0P39i3b5+vSwAAADZhKXkAAAD43IQJE5Senu4y7uabb3YZk5KSoilTpthRFgAA16XixYvrtdde04EDBzR8+HDlyJHDre1jY2P1zDPPOFQdAMDfbd682SiuQ4cODlcCAABMRUREqFSpUqpdu7Zuv/12jRw5Ur/99puOHDmiV155RYULF3Z7n6mpqerdu7eSkpIcqBgAAACu0BgKAAAAnzO5ir1w4cIaP368goODXcbatSw9AADXs9DQUL300ktavHixihUr5ta2EyZM0MGDBx2qDADgz3bs2OEypkSJEqzyAABAFlCgQAG98MIL2r9/v/7zn/+4vf2+ffs0YsQIByoDAACAKzSGAgAAwKeWLFmiP//802Vcjx49VKxYMd16660uY9etW6dNmzbZUR4AANe9qKgozZ07VxEREcbbpKam6qOPPnKwKgCAvzpy5IjLmAoVKnihEgAAYJecOXPqgw8+0PTp05U7d263tn3//fd1+vRphyoDAADAtdAYCgAAAJ8aO3asUVyfPn0kSX379rV1vwAAwLVatWppypQpbm0zbdo0WZblUEUAAH918uRJlzF58uTxQiUAAMBuXbt21fTp05UjRw7jbRITE/XJJ584WBUAAACuhsZQAAAA+Ex8fLxmzJjhMq5q1aqqX7++JKl9+/bKnz+/y20mT56s1NRUj2sEAACXtG/fXrfffrtx/KFDh7Rq1SoHKwIA+KOEhASXMe5MoQYAAP7l1ltv1ZtvvunWNlzEDwAA4H00hgIAAMBnpk+fbvSj4T333HPlf4eEhKhHjx4utzl16pRmz57tUX0AAODvXnrpJbfiFy5c6FAlAAB/lZKS4jImKCjIC5UAAACnPPbYY2rYsKFx/P79+7VmzRoHKwIAAMA/0RgKAAAAnzG5UjwwMFC9e/f+279dXlbelXHjxmWqLgAAcHU33XSTWz/+rVy50sFqAAD+KD093dclAAAAL3jxxRfdip8zZ45DlQAAAOBqaAwFAACAT+zatUvLli1zGdeyZUuVKFHib//WqFEjVaxY0eW2P/30k44dO5bpGgHARFpammJjY3XgwAHt3r1bJ06cUHJysq/LAhwTHR1tHLthwwbnCgEAAAAA+Ey7du1Uq1Yt4/gVK1Y4WA0AAAD+ifVaAAAA4BMm00Kla08H7dOnj55//vkMt01LS9PEiRP15JNPul0f/ENSUpISEhKUkJCg1NRU5cyZU+Hh4cqdO7dy5Mjh6/K8Ijk5WUuWLNHatWu1c+dO7dixQ8eOHVN8fLzi4+N14cIF5cqVS7lz51aRIkVUsmRJjR07VoUKFfJKfampqTpz5oySk5OVkpKi4OBghYWFKWfOnMqbN69XavAmy7K0bt06/fzzz/r999+1fft27d27VxcvXvxXbHh4uKpWrapq1aqpQYMGat++/b8a3a8HFy5cuPI6TkpKUlhY2JXnbEhIiK/LQya0bNlSb7zxhlHsoUOHdPHiRb8+ZnOugZ0sy9LZs2eVmJio5ORkWZalnDlzKmfOnMqdO7eCg4N9XaJP7N69W4sWLdK2bdu0Y8cO7dmzR+fOnVN8fLwSEhIUFBSk8PBw5c+fX8WKFVOPHj00dOhQ2+vYvHmzfvnlF23atEnbtm3T4cOHFRcXp4SEhCt/o7x586pcuXKqWrWqatasqVtuuUVFihSxvRZkTWlpaVeet0lJSQoJCVF4eLgiIiIUGhrq6/K8Ki4uTgsXLtTGjRu1Y8cO7dixQydPnrzyOeXixYtXzqdFixZViRIl9P333/u6bPjQxYsXdebMGSUlJSklJUWBgYFXzpF58uRRYOD1OcsmNTVV8fHxSkpKUmJiokJCQpQnT55s9140MTFRMTExWrt2rbZs2aIdO3bozJkzOn/+/JXPieHh4brxxhsVGRmpatWqKSoqSlFRUcqTJ4+vy0cG2rVrp40bNxrFrlq1yuFqri49Pf3KZ76EhATlyJFD4eHhCg8PV65cuXxSE7wjLS1NCQkJSkxMVGJionLkyHHlGHu9fjYDAFxfaAwFAACA1128eFETJ050GRceHq4uXbpc9b/dc889euGFF2RZVob7GDdunK2Noenp6Ro5cqTS0tJcxj7wwAMqXLiwbbk9NXfuXKMvYBs0aKB27dp5oaL/iY+P18qVK/X7779r/fr12rt3r/bs2aPz589fNT4oKEilSpVSZGSkateurSZNmqhp06Y+/9E+ICDAZUzfvn01fvz4DGNSUlI0ffp0TZo0SUuWLHE5fTIuLk5xcXE6cuSINmzYoPj4eFsbQ1NSUrRp0yZt2rRJmzdv1p9//qk9e/bo8OHD1/wbSVJoaKiKFSumEiVKqEaNGqpbt64aNmyo6tWr21abtxw9elSjR4/Wl19+qYMHDxptk5CQoNWrV2v16tUaP3687r//ftWrV09DhgxRnz59MmyKPH78uHr16uUyR58+fa7ZQO9taWlp2rBhg5YtW6bVq1dr9+7d2rt3r44fP37V+ICAABUtWlSRkZGqWrWqoqKi1LRpU5UvX97LlcNd7kyESUtL09GjR/2iKTqrnWuSkpL05ptvuoxr2bKlWrZs6VgdEydO1J49e4xiK1eurB49ejhWS0xMjJYuXZphTEBAgJ599lnHf+Tbs2ePNmzYoE2bNl1pdNy/f79OnTp11YsFLtdWpEgRFS9eXBUqVFDdunVVr149NWnSRDlz5nS0XlPDhw/Xyy+/7DJu7969KlOmTIYx27dv1+eff64ff/xRu3fvzjA2LS1NycnJOn36tP78809FRkba1hh68OBBffHFFxo/frwOHz58zbjLzWxHjx7V9u3bryx1GhgYqAYNGqhnz57q37+/wsPDbakL/m/Pnj1aunSpli1bduVioMOHDys9Pf2q8YULF1bZsmVVoUIFNWrUSM2aNVP16tV93uy2b98+RUZGuox76aWXNHz48Axj4uPjNWHCBH399ddavny5y8/F586d07lz53To0CGtWbPGnbKRRaWlpemPP/7Qxo0btXnzZu3atUt79+7VwYMHdfbs2Wt+hxMcHKwbb7xRxYsXV7Vq1VSnTh01aNBAdevW9flryC6JiYlas2aNVq5cqXXr1mnv3r3av3+/jh8/fs3HJVeuXCpSpIiqVKmiqlWrqkqVKqpZs6bq1q2bJZpGLcvS7NmzNXr0aMXExCgpKemasZcb9k6cOKGNGzdq5syZkqSwsDDddtttuu+++3T77bd7qXK4Izo6Wq+//rpRbGxsrM6ePat8+fI5Vs+pU6e0bNkyLV26VJs3b77yPv3ChQtXjc+dO7ciIyNVrlw51a9fX02bNlWDBg0UFhbmWI3+rkyZMtq/f3+GMS1atNCiRYu8U5CBCxcuaP369Vq5cqXWrFlz5e9+5MiRa753CwsLU6FChVS5cuUrx9jq1aurQYMGHl/I/OOPP6p9+/Yu46pWrao//vjDo1x2OnjwoMqUKXPNx+yysLAwHTlyRPnz5/dSZQCATLMAAAAAL5szZ44lyeWtd+/eGe4nOjraaD/Lly+3tf527doZ5X333XdtzeupChUqGNU9e/Zsr9Rz5swZa+zYsVbbtm2toKAgo9oyugUGBlotWrSwPv30U+v8+fNeuQ//ZFJn3759r7l9YmKi9fLLL1tFihTx6LHYu3evR/cjJSXFWrBggfX0009bUVFRVmhoqMd/n7/eSpQoYQ0aNMhatmyZR3V6w9mzZ62nnnrKCgsLs/UxKFasmPXZZ59Z6enpV827d+9eo/289NJL3n1A/uHChQvWjz/+aN1zzz1Wnjx5bHlsqlatag0fPtzat2+fT++bPzB9zLz9PLhw4YJbf9PNmzd7tb6/yurnmlKlSrmsqX379o7lv3jxolWgQAHjx6dkyZKO1WJZltWmTRuXNVSqVMmR3Dt27LA++ugjq1OnTh6fp/95y5kzp3XbbbdZY8eOtRITEx2p39RLL71kVHNG7zVWrFhh3XzzzVZAQECmH5OM3i+ZOnbsmDVgwAArR44ctv2tChQoYL388stWUlLSNfO2aNHC5X5Kly7t8f3zBdP3J964OXXu27lzpzV8+HCrUqVKttRZtGhR6+GHH7ZWrFjhSL0m7HhfGRsbaw0bNszj93tZjekxMSveN7ukpaVZy5cvt4YPH261atXKCg8Pt/W1XqhQIat3797WTz/9dM3PTv7s5MmT1qhRo6xbb73VCgkJse1xyZcvn9WlSxfriy++sPbv329rzXZ9Fp06dapVpUoVW58PtWvXtmJiYmy9v1lJ6dKljR4nO95HuSMhIcGt930bNmywvYbTp09bn332mdW8eXOP3oNevuXKlcvq0aOHNWvWLOvChQu212vKjvfmmWHyXGvRooWtOTPj/Pnz1uTJk63OnTtbuXLlsu1YEx4ebrVr18764IMPrO3bt2eqtosXLxq/Zn/77TebH5nMe/HFF41qvueee3xdKgDA0PX7aRUAAAA+c9dddxl9wfDzzz9nuJ9x48YZ7WfgwIG21j99+nSjvDVr1rQ1ryeWLVtmVHPRokWt1NRUR2s5cOCA9Z///Mf2H4z+esuXL5/1zDPPWKdOnXL0vvyTSW3X+oJ+zpw5VmRkpC33PzNfCJ8/f96aMmWK1aVLF0f/Nld7nUyZMsUvf+SbP3++VbRoUUfvf4sWLazdu3f/K7e/N4bGxcVZ7777rlW8eHHHHpugoCCrd+/e1tatW31yH/2B6WPli+dB7ty5jetbuXKl1+vLLueae++912UdefLksdLS0hzJv3btWrcfl507dzpSS3JyspUzZ06X+e+//35b8qWnp1vLli2zHn30UdvOz6bPqyeeeMI6ffq0LffDXZ78+BwbG2sNGjTIlh/jPW1o+Pzzz906Trl7q1Sp0jUvcKEx1Ds3u899a9eutTp37mzL8/dat8aNG1tz5syxtW4Tnr6vnDBhglW4cGFbHoOshsbQq0tKSrJmzZpl9enTx8qfP7/XXvflypWzPvnkE8e/s7DD5s2brf79+9t+keXVbgEBAVarVq2sadOmWSkpKR7X7ukxY9++fVbbtm0dvc8DBgzI8CKN7MpfG0Mty7Ly5ctn/Pf76aefbMt7+PBha9iwYbY2Bf7zVrp0aevTTz+1kpOTbavbFI2hV7d3717rkUcecfT9/l9vN910k/Xll19a8fHxbtX52muvGe3fX5os09LSrBIlShjV7E/NrACAjGWP9RcAAACQZZw+fVo//PCDy7jixYurdevWGcbcddddypUrl8t9ff311xkuV+WuO++8UwUKFHAZt2nTJm3YsMG2vJ6YMGGCUVyvXr0UFBTkSA3x8fF6/PHHVa5cOX344YdKSEhwJI8knT17Vq+//roqVaqkMWPGXHNZNn9gWZaeeeYZ3X777dq7d6/Xc8+dO1c9evRQkSJF1LNnT3377beO/m3+adOmTerZs6caNGig1atXey1vRi7/TW699VYdO3bM0VyLFy9W/fr1tWzZMkfz2MWyLI0ePVplypTRY489luGSvJ5KS0vTpEmTVKtWLT355JNefV7Ctdy5cxvHXmvJPidkt3ONq/dCknT+/HnHjp+//vqr29vExMQ4UIn0+++/G72fa9WqlUd5du3apeeee05lypRRVFSU3nvvPa+en8+ePau33377ynPYn9/D/NXWrVtVv359jRo1yqc1x8XFqVu3bhoyZIji4uIcy7Njxw41b95cn3/+uWM54B2nT5/Wvffeq3r16um7775z9Pm7fPly3X777YqOjtbOnTsdy2OXlJQU9e3bV3379tXJkyd9XQ78wG+//aYBAwbohhtuUIcOHTRx4kSdOXPGa/l3796tBx54QNWqVdP8+fO9ltcdBw8e1N13360aNWpo7NixSklJcTynZVlasGCBevTooeLFi2vMmDGO57yWn376STVr1nT87zN69Gi1aNFCx48fdzQPzBUqVMg41o7PaGlpaXrjjTdUvnx5vf/++0pMTPR4n9eyf/9+3X///apSpYrfHnuuF6dPn9YDDzyg8uXL64MPPnD0/f5frV69WgMHDtSNN96o1157zXi7++67T8HBwS7jZsyY4dXz6bXMmzdPhw4dchlXtWpVNW3a1AsVAQDsQGMoAAAAvGry5MlGDSK9evVSYGDGb1cjIiLUuXNnl/s6f/68vv32W+MaXQkNDVWPHj2MYk0bMp2UnJys6dOnG8X27dvXkRrmzZunqlWr6t1331VqaqojOa7m9OnTGjBggG677TadPn3aa3lNpaSkqHPnznrjjTd8kv/06dO6/fbb9fXXXys5OdknNVy2Zs0aRUVF6Y033vBpQ0lqaqruuecer9Zx5swZtWnTxqhp3pd27typqKgoDRw40Kuvp9TUVL399tuqVauWNm3a5LW8yNi5c+eMY91pIvVEdjzXmDY5ZqaB08SCBQvc3saXtQQGBio6OtqjPMOGDdPIkSN14MABj/bjqbNnz+qRRx7RLbfcoqNHj/q0FldiYmLUuHFj7dmzx6d1nDp1Sq1atdI333zjlXwXL17U0KFD9fzzz3slH+z3ww8/qHLlyl7/zLZo0SLVrFlT7733nlfzuuPMmTNq3bq1Jk6c6OtS4Eduu+02jRkzRufPn/dpHTt37tRtt92mYcOGefUCpIxYlqW33npLlStX1rRp03xWx6lTp/Tbb7/5JPcnn3yiO+64w2vPj1WrVunmm2/2i2YqSAULFjSO9fTi/R07dqhevXp65plnbB0E4MrevXt16623qm/fvo42ouLqxo8fr4oVK+rTTz/VxYsXfVJDXFycWxdCFi1aVJ06dXIZl5SUpK+++sqT0mwxatQoo7hBgwY5XAkAwE40hgIAAMCrxo0bZxTXp08fW+NM85oybaCcMmWK0tLSbM3trlmzZuns2bMu4+rWrasaNWrYmjs9PV0vvPCCbr/9dh08eNDWfbtj/vz5qlevnrZs2eKzGv7Jsiz16dNHM2fO9HUpfiM1NVXPPPOM+vTp45PXTXp6unr27KnJkyd7PXdycrK6d++ulStXej23ie+++0433XSTli9f7rMadu/erUaNGhk3usM5KSkpbk15yZs3r4PVZO9zTbFixVSlShWXcU5M6UxNTc1UY8HChQuVnp5uez0mDae1a9c2muqelcTExKhRo0Z+O11w1apV6tixo8+bhE6dOqXmzZtrzZo1Xs89YsQIv27ww79ZlqVXX31VHTt21KlTp3xSQ0pKih577DH17t3bq00tJpKTk3XnnXdmmYn2uD5ZlqUPPvhAt99+u+Lj431ay4kTJ9S2bVs99dRT122z2CeffKIHH3zQ681amzdvVseOHX3WJIb/cedvEBAQkOk8c+bMUYMGDXx60ejEiRMVFRXl8wvJrhfx8fHq3bu3+vXrp9jYWF+X47YhQ4YYxX355ZcOV5Kxw4cPa+7cuS7jwsLCjH+PAQD4BxpDAQAA4DXr1683Wlq9Tp06qlatmtE+W7dureLFi7uMW7hwofbt22e0TxMNGjRQ1apVXcadOHFC8+bNsy1vZphOwLn33nttzZuSkqKOHTvqtdde84tlUPfv36+WLVtq/fr1vi5FkvT444/T4HYNkyZNUteuXR1pLMrIsGHDNGPGDK/m/Kvk5GR16NDB735cGDFihLp06eLzph/p0hSFu+++W+PHj/d1Kdc1d5to8uXL50whuj7ONSZTQ5cvX257Y9GKFSsytcxjbGys0fs9d8TFxWn16tUu41q3bm1rXn9x4MABNW3aVDt27PB1KX+zZ88e3XHHHbYsB+qJy01s27Zt81kNTzzxhGbPnu2z/DBnWZYGDx6sF1980S/OG5MnT1bbtm19/jr6q969e2vp0qW+LgMwEhMTozZt2visIXP79u2qV6+efvnlF5/k9wdTp07VQw895LP8S5Ys0auvvuqz/LjEnc+IuXLlylSOiRMn6s477/SL7yY2bNighg0b+u3FW9nF0aNH1aRJE59cwG2X6OhoVa5c2WXcli1bfHox9pgxY4wavO+66y7lz5/fCxUBAOwS5OsCAAAAcP2we1qodGnJ0N69e+vNN9/MMM6yLI0fP17Dhw833rcrffv21VNPPeUybsKECWrfvr1ted1x7Ngx/fzzzy7jgoODdffdd9uWNykpSR06dPC7H0dOnz6t1q1b6/fffzf6Us4p8+bNM5osFRISogYNGqhZs2aqVKmSypQpo9y5cys0NFQJCQk6d+6cduzYoU2bNmn+/Pl+11DoiZkzZ+qJJ57Qu+++65V848aN00cffeT2doGBgWrRooVuueUW1atXT5UqVVL+/PmVK1cuJSUl6ezZs9q1a5c2bNigX375RTExMRkucX38+HH1799fo0eP9uTu2OaFF17Qa6+95usy/iY9PV39+/dXaGiorcctmFu7dq1xbIECBRxrDL1ezjWtW7fWJ598kmFMSkqKli5dqptvvtnjfJd5siT8r7/+qrp169pWy+LFi40mSWfXxlBJOnnypNq3b68VK1b4xVTU9PR09e7dWydPnnQZW6JECbVo0UL169dXuXLlVLhwYYWHh+vixYuKi4vT0aNHr/wQunjx4gzPk1fTr1+/TP2ImiNHDjVu3FitWrVS1apVVbJkSeXOnftKXXv27NGWLVv0yy+/aOPGjRnuKz09XX379tXWrVvdrgPe9eCDD/p8ItM//fbbb7rjjjs0Z86cTDfL2OWzzz7Tt99+6zIuV65catKkiaKiolShQgWVKlVKERERCg4OVnx8vM6cOaPt27drw4YN+umnn3TixAkvVI/r1cqVK9W3b19Nnz7do0mE7lq7dq1uvfVWn00e9gcbNmxQv379XDba586dW02bNlXjxo1VoUIFlSxZUuHh4QoODlZCQoIOHTqkbdu2afHixVq4cKHbK4iMGDFCd999typVquTJ3YEHTp8+bRwbHh7u9v6nTp2qfv36ef0C4owcO3ZM0dHRWrx4scqXL+/rcrKdvXv3qk2bNtqzZ4+vS/HYkCFD9Mgjj7iMGzVqlBo3bux8Qf+Qnp6usWPHGsWyjDwAZD00hgIAAMArLly4oClTpriMCwoKUs+ePd3ad58+fVw2hkqXGjRfeukl234o6N27t5599lmXV9POnj1bsbGxPvkRf9KkSUZX+95xxx0qVKiQLTkvXryozp07Z6pRJyQkRM2bN1dUVJTq1KmjyMhIFStWTOHh4QoNDVViYqJOnz6tPXv2aM2aNVq4cKHLRrt/OnPmjNq3b69Vq1b55ArnM2fOaMCAARnGlCtXTo899pi6d+/u8nnz1yag5cuX6/XXX7f9x7DAwEBVqVJF9erVU8WKFVWpUiUVK1ZMRYoUUcGCBRUaGqqwsDAlJibq3LlzOn/+vE6ePKmNGzdq3bp1WrNmTaaWVn7vvfcUFRWlzp0723p//mnXrl1uTzgJDQ3VAw88oP/85z8qVarUVWMiIiIUERGhEiVKKDo6WsOGDdOJEyf0+eef65133lFcXNxVt/v11181ZswYt++H3UaMGJGpptCAgADVrl1brVq1Ut26dVWhQgWVKFFCefLkUVhYmC5cuKBz585p37592rx5s5YsWaIff/xRZ8+eNc5hWZb69++v8uXL66abbnK7Rnhm0aJFxrF16tRxpIbr6VzTsmVLBQYGuvwR9Ndff/WbxtCYmBg98cQTXq0lODhYzZo1sy2nKzfccINuuukmVa1aVRUrVlRkZKSKFCmiIkWKKGfOnAoLC5NlWTp37tyV244dO7R27VqtW7dOK1eudHvK665du3Tvvffqhx9+cOhemXv77bczbMbMkSOHevXqpcGDB6tJkyYu99etWzdJ0rlz5zR69GjjJptx48Zp2rRpZkX/v3z58mnYsGEaNGiQihYtes24vz6fdu7cqY8//lhffPGFLly4cNX4M2fO6IEHHnCrlqymTJkyRlM2Td6L9u3b1+sTwN966y19+umnmdq2bt26ateunRo2bKjKlSurcOHCioiI+NuFQOvXr9dPP/2UqaamRYsWqX///m4/n+20Z88evfPOOxnG1K5dW48++qg6d+7ssrHntttuk3Sp2SAmJkYjRoywrVb4r4CAAJUrV07169dXpUqVVKlSJZUoUUJFihRRoUKFFBYWprCwMKWkpFz57BgbG6tNmzZp3bp1WrdundauXev2RN8ZM2bo/fff16OPPurQPfu77du36+abb9aZM2cytX3BggXVokULRUVFqUqVKipbtqwKFSp0pVkyOTlZcXFxOnLkiA4ePKg//vhDmzZt0tKlS3X48GGb703mxMfHq3v37kpJSblmTOPGjTVs2DC1b99eYWFh14xr0KCBJOm5557TyZMn9cEHH+iDDz4wngSblpamxx9/nOndPnL27Nlrfr9xNSYrP/3VsmXL1Ldv30w1hZYuXVrt2rVTy5YtVaVKFRUvXvzKhUDnz5/X3r17r1wI9NNPP+ncuXNu7f/IkSNq166dVq9erbx587pdH67u+PHjatWqVaZX/8qdO7eaNWumqKgo1ahRQ5GRkSpatOiVz/zJyclKSEjQ0aNHdejQIW3dulWbN2/W0qVLHWlE7du3r5555hmXn/+mT5+uDz74wOvPpfnz52v//v0u46pUqeLVz9wAAJtYAAAAgBdMnz7dkuTydvvtt2dq//Xr1zfa/6+//mrr/br11luN8n7yySe25jVVvXp1o/pmzZplW86HH37YKOdfb7Vq1bJGjRplnT9/3u18p0+ftl577TWrYMGCbuVs3769bff5Mnfv9z9v4eHh1kcffWSlpqbaXtvVnDx58pq1VK1a1Xr00Uetn376yYqLi/M419atW60nnnjCuuGGG9x6TIoWLWrFxsbacG+vrUmTJm7V1LhxY2v37t0e5Tx27Jh1++23XzNHcHCwUS0vvfSSPQ/CP3z77bdWQECA23+rl19+2Tp48KDb+VJSUqyJEydaVapUcStniRIlrLNnzzrwCPgH08fBqefBtdSsWdO4tieffNKRGq63c029evVc5qpfv74tuSzLsuLj442PQ1e75cqVy0pJSbGtnho1arjM2axZM1tyXevYnC9fPuvuu++2xo4da+3fv9/jPOfOnbO++OILq1GjRm4/vlOmTLHhnl7dSy+9lOm/++VbixYtrB07djhW42V79uyxIiIi3KqtV69e1smTJzOdc9euXVaLFi0yzBEeHu6yjtKlS9v3QPghk79F3759vVrTggULrBw5crj1fAkICLB69uxpbdiwwa1chw8ftp555hkrZ86cbr9+3n33Xdvv+969ez1+XRcqVMiaPHmylZ6ebnt9/sydY+L14FrHtzJlylhDhw61vv/+e1s+u+3bt896+eWXrcjISLeep7ly5bL+/PNPG+5pxk6cOGGVLVvW7ddRQECA1bFjR2vu3LkefebftWuX9d5771nNmze/6mc2T4+vpseMjI5xZcqUsX788UeP6ti5c6dVq1Yttx7jTZs2eZTT35UuXdovz7EzZ8506+8UHx9vvO9jx45ZxYoVc/v11qhRI2vOnDnWxYsXjXPFx8dbn3/+uVW8eHG38915552OnCNNz0N79+61Na/Jc61Fixa25rwsMTHRatCggdt/A0lWy5YtrRkzZliJiYmZzn/o0CHr888/t2677TYrKCjItvvdr18/o/vw8ccfZ7r2zOrYsaNRbe+//77XawMAeO76+LQKAAAAnzNtoPz6668ztf+PPvrIaP+9e/e29X5NmzbNKG+DBg1szWti7dq1RrUVLlzYunDhgi05J06c6NYXdsWKFbO+/vprW748PXXqlNWnTx+38k+cONGGe/0/mfnS8vKtQoUK1s6dO22tx5V/NoYWL17cev75560tW7Y4ljMhIcF6/PHHr/rl6rVujzzyiGP1TJ482a2/U//+/W1r3E1PT7defPFFj543TjQEbt261aip5fItLCzMeu2116yEhASPc6emplpvvvmmFRIS4tbfJLvy5fPgWn799Ve3nqPz5s2zvYbr8Vzz5JNPuswTGBhoWyP93LlzPTo2SbIWLVpkSy3Hjx83alQfPny4Lfn+2hgaEhJi9ejRw5o9e7atja7/NGvWLKtkyZLGj+2NN95oJSUlOVKLp42hw4cP91rjWKdOnYzrCgwMtD777DNb8qalpVmPPvqoR48TjaHebVo5d+6c200l5cqVs5YvX+5R3v3791vR0dFu5Q0KCnK7EdUVTxtDGzZsaB07dszWmrIKGkP/7q+fEQoUKGA98sgj1sqVKx3Ll5qaar3xxhtWrly5jP8OHTt2dKwey7r0Ga5Vq1Zuv45atWrlyOfsvXv3Wi+99NLfLsD0VmPotW4dOnSwzp07Z8v9O3funFsNYvfdd58tef2VvzaG/uc//zH+GxUrVsytfWd0Qe3VbhEREda4ceM8ej8aHx9vPfTQQ24/950YCnA9NoaaNlD+9VanTh1r2bJlttdy7Ngx65133vnbhQqZvd+rVq0yui+1atWy9T64cuTIEaPvaMPCwqzTp097tTYAgD2uj0+rAAAA8KlDhw5ZgYGBLr9gyJcvX6Z/5D558qTRZKucOXPa9gW1ZVlWUlKSlS9fPqMvdrZt22ZbXhOm09Tsaro7dOiQlTdvXuMv7bp06WKdOXPGltx/9fnnnxtPAypQoICtNbj7xeXlW/Xq1a1Tp07ZVoepy42hTZo0sb777jsrLS3Na7k3bNhgPGUlZ86cjvwYnZKS4lYjzsCBAx1pdnnttdcy/dyxuyEwLS3NatiwoXH+atWqOXJsW758uVW4cGHjOhYvXmx7Df7AV8+DjLialPfXW9GiRW0/rlyv55r58+cb5fruu+9suX+PP/54hnlKlSpllSpVKsOYF154wZZaTC/C+e2332zJd/vtt1uFCxe2XnvtNev48eO27NNEXFyc1bdvX+Pn9ocffuhIHZ40hn7++eeO1HQ1CxcuNK4rMDDQmjx5su01vPDCC5l+rGgM9W7TygMPPODW3+eWW26x7TNjWlqaNWzYMLfyN2zY0K0JZ6540uTVqlUrj6ZuZXU0hv5deHi4Vb16dWv8+PGOXaBwNXv27DFeJSYgIMD25uq/+vDDD916DYWGhlpffPGFY/VclpycbI0ePdqKjIz0aWNo//79bf/MfPz4cato0aJG+fPkyWMlJyfbmt+f+GNjaFpamlsTdN1p3v7mm2/cfn9l5/cT06ZNc2sVhTx58lhHjhyxLb9lXX+NobNmzXLrbx4QEGC9/PLLjn+fmZaWZn3zzTdWjRo1PLrfdevWNbpfTl508U8jRowwqqlXr15eqwkAYK/r49MqAAAAfGrkyJFGXzAMHDjQozwdOnQwymP3l/KDBw82yvv000/bmjcjFy5csAoVKmRUl10/mtxxxx3GX9w99dRTjk6TmjZtmlEzsiTrueeesy2vO19eXr7deOON1qFDh2yrwR0JCQnWggULfJLbsi79wFOpUiWv/50uGzNmjPHfKTo62rZJoVdzzz33ZOr5Y3dD4DvvvGOcu3Xr1plaktvUH3/8Ydwc2rRpU8fq8CVfPQ+uxd1JnY8++qjtNVyv55qEhASjSboPPPCALfetTp06Gebp37+/de+992YY06RJE1tqGThwoMv7HR4ebtv08wULFvi0Ccq0gaxkyZK2No5dltnG0BdffNH2WjLStGlT49pGjBjhWB29e/fO1ONFY6j3mlY2bNhgfKyWZLVr186RpqJnnnnGrefIl19+aVvuzDZ5Va9e3dH3elkBjaF/N3fuXK9Nhf6n+Ph442O/U80re/bsyXD59H/eChQo4PHkYXdduHDBWrdunUf7yOwxo2PHjo49P2bMmGFcxw8//OBIDf7AHxtD3f2M+OabbxrtNykpya0l3SMjI60DBw7Yfv9+/PFHt1a8sfv4cz01hp49e/Zv049d3cLCwrz+ek9PT7dWrVqV6e2//PJLo/vmrenH6enpf5uGmtFtyZIlXqkJAGC/6+PTKgAAAHyqQoUKRl8weDrp6dtvvzXK06hRI5vu2SXLly83yluiRAlHfsC/mpkzZxrVZNfyNL/88ovxF3dONApdzVtvvWVUT0REhG1L4Zg+BpdvAQEBVkxMjC25s6rdu3dbefLkcflY2d0Ak56eblWtWtXo75QvXz7Hm3fj4uKMf+T5683OhsDTp08b/S2kS42Ydiwd78pvv/1mvKz8/PnzHa/H23zxPLiW33//3QoNDTWuKTQ01NqzZ4+tNVzv55rmzZu7zFO5cmWP79OpU6dcLt0+efJk66uvvsowJigoyJaGIpMJRLfeeqvHefxFenq61b59e6Pn1S+//GJ7/sw0hrZs2dJr73Ety7JWrlxpXFvbtm0drSUpKcmqWLGi248ZjaHea1rp0qWL8d+lZs2aVlxcnGO19OjRw7iWyMhI2y5KykyTV86cOR1Z9jqr8WSKsj/cnJia7kuxsbFGKz7YvVLMZT179jR+7PPly2etXbvW9hq8ITPHjPLlyzveSG66ssX999/vaB2+5G+NoWlpaVblypXdeq5s3brVaN///e9/jfeZO3duR89Zn332mXEtgYGB1o4dO2zLfT01hj777LPGj3NISIg1d+5cW/N7Q3x8vNEKKOHh4V65OMd0ZZIqVao4XgsAwDmBAgAAABy0dOlS7dq1y2VcZGSkoqKiPMp1xx13qECBAi7jVqxYoe3bt3uU668aNWqkypUru4w7dOiQfv31V9vyZmTChAlGcffee68t+Z5//nmjuFtvvVVvv/22LTldeeKJJ3TLLbe4jIuPj9fEiRO9UNG/9e3bV61bt/ZJbn9RtmxZvfXWWy7jDh48qMWLF9uWd+nSpdq6datR7MiRI1W8eHHbcl9NRESEPv74Y0dzuPLmm2/q/PnzLuNKlCihb7/9Vrly5XK8pqZNm+qll14yiv30008drub69fPPP+vOO+9USkqK8TaPPvqoIiMjba3jej/XmJwvtm/frsOHD3uUZ+HChbIsK8OYVq1aqVWrVhnGpKWleXzc3rdvn/bs2eMyLjudSwMCAjR69GjlyZPHZexXX33lhYoyFhwcrFGjRikw0HtfM7///vtGcbly5dIXX3zhaC1hYWEaM2aMozmQedu2bdN3331nFJszZ05Nnz5dERERjtUzZswYlStXzih27969mjRpkmO1uPLUU0+pWrVqPssPXE3+/Pn15ZdfuoxLSkrSt99+a2vuDRs2aOrUqUaxgYGBmjp1qurWrWtrDf5s1KhRyp07t6M5Hn74YaO4pUuXOloH/ufRRx916/vVqlWrqkqVKi7jUlNT3fo89/HHHzt6zhoyZIh69OhhFJuenq6RI0c6Vkt2dfToUX3wwQfG8f/973912223OVeQQ8LDw3XPPfe4jEtISNDkyZMdr2fUqFFGcQMHDnS4EgCAk2gMBQAAgKPGjh1rFHfPPfcoICDAo1whISHGX9SZ1mWqb9++RnGmDZueOH36tObMmeMyLjg4WL169fI43/z587Vy5UqXcfny5dO4ceO82jjw2WefKTg42GWcyY9LdgsNDdWIESO8ntcf3XfffSpbtqzLuHnz5tmW0/RHvbJly2rAgAG25c3IHXfc4XGDfGbFxsYaN6aOHj1aRYoUcbii/3nqqadUqVIll3Fz5szRkSNHvFDR9SMxMVFPP/20br31Vp06dcp4uxIlSujZZ5+1tRbONebNj55ehOJq+2rVqqlo0aIqVqyYyx92na7lsuzUGCpJRYoU0SOPPOIy7qeffnLZxOu0IUOGqEKFCl7LFx8fr1mzZhnFPvzwwypdurTDFV26iKFTp06O54H7PvvsM+PXyMsvv2z0fsMTuXLl0ujRo43jfXXR0A033KAnnnjCJ7kBV9q2bavmzZu7jLPzs6N06SI60+PJM888o1tvvdXW/P6sffv2io6OdjxP586djS5O3LJlixISEhyv53o3duxYffTRR25tM3jwYKO42bNn68CBA0ax7dq1U58+fdyqIzP++9//qmDBgkaxU6dOVWxsrMMVZS8fffSREhMTjWJ79eqlQYMGOVyRc4YMGWIU5/R31SdOnNAPP/zgMi40NNT4dw8AgH+iMRQAAACOSUhI0DfffGMUa9eXeKb7+eqrr3Tx4kVbckqXGltNmlC+//57xcXF2Zb3aqZOnaoLFy64jLvttttUuHBhj/N9/vnnRnGvvvqqihYt6nE+d5QtW1b9+/d3Gbd161Zt3rzZCxX9T8+ePVWsWDGv5vRXQUFBRn+nmJgYW/Klp6drxowZRrGPPPKIUcOXXXz1I/xXX31l9CV8ly5d1LZtWy9U9D85cuTQ8OHDXcalpaXZPhnoerV//349/fTTKlmypFs/gkuXml5mzZpl+8Q1zjVSgwYNjB5Xp5sx27Rpc+V/u2rI9EZjaMGCBVW7dm2P8vijAQMGuLxo6sSJE15///JXgYGBGjZsmFdzzpw5U0lJSS7jcuXK5dVz6ssvv+y1XDCTmppqfCFQmTJl9J///Mfhii5p2bKl7rzzTqPYtWvX6o8//nC4on+7//77vTIZHsgsk4agBQsW2HbxxMmTJ42nD1eoUEEvvPCCLXmziueee84recLCwowuBkpPT7d1lSD8nWVZeuONN9xuzMufP7/uu+8+o1jTlRZy5Mihd955x606MqtQoULGz/ULFy4YvwfBpfdspgMcChQo4NZkUX9UrVo1owsc1q1bpzVr1jhWx7hx45Samuoy7q677jJaoQ0A4L9oDAUAAIBjpk+frvj4eJdxTZo0MV5Sz5WGDRsaTXo5duyYrRMkihcv/rdGiWtJTEw0bpbNLG8uI3/s2DH9+OOPLuNKlCjhs2VnHnzwQaO4uXPnOlzJ35lOSrhetGvXzmXMhg0bjI4prqxbt04nT550GZczZ06vTJ74qzvuuEMlSpTwak7JbBJBQECAUYOmE+666y6jZj9vv479xalTp7R9+3a3b2vWrFFMTIxmzJih//73v+rdu7fKlSunMmXK6M0333R7yklgYKAmTZpk+7KZnGsuCQ4OVrNmzVzGedKMeejQIe3atSvDmL/+IO/qx/ktW7boxIkTma5n4cKFLmOio6M9njrvj0qWLKkaNWq4jPPlcqm33HKLIiMjvZpz5syZRnHdu3f36g+YNWrUUNOmTb2WD67Nnz/feNr1s88+q5CQEIcr+p9XXnnFOParr75ysJJ/CwwMZLlQ+L3bbrvN5bn/9OnT2rZtmy35xo8fb3TxrXRpsmhoaKgtebOC6tWrq2HDhl7L16RJE6M4GkOdceDAAd1555165pln3L7Y/oUXXlB4eLjLuNjYWOPPTN27dzdamt4u999/v/FFiN4+f2dlM2fONP7M+Pzzz6tQoUIOV+Q8X08NtSzLeIp9Vp7OCgC4hMZQAAAAOGbcuHFGcXY3Xpnuz7Q+U6aNlk4uJ79161ajq4kLFSqkO+64w+N806dPV1pamsu4QYMG+ezHkerVq6tmzZou4+bPn++Fai4pVaqUGjRo4LV8WUGtWrUUFhaWYYxlWbZMTTJpNJIuLVOYN29ej/O5I0eOHOrcubNXc27atMnocY2Ojlb16tW9UNG/BQUFqVu3bi7jFi1apJSUFC9U5F8++eQTValSxe3bTTfdpJtvvlldu3bVww8/rMmTJ2vPnj2ZqiF37tz6/vvvHVlOmXPN/5hMSTp8+LB27NiRqf27airNkSOHWrRoceX/t2zZMsOJ6ZZlZbpR9Y8//tCxY8dcxrVq1SpT+88KTBotfDkxtGvXrl7NZ1mWFi1aZBRrxwVQ7urXr5/Xc+LaTJtK8ufPr969eztczd/VqlXLqNFf8v5FL1FRUbrxxhu9mhNwV4ECBVS+fHmXcXadI01Xm6hWrZo6duxoS86swuQzmp1Mp8SbLkMOM+vXr9c999yjcuXKGV2w9081a9bUQw89ZBQbExNjNMVQkvE+7RIaGmp88cSqVauML1C53pkeYwsVKpRtLrLv0qWL0SpeU6dOteUC+X9asGCB/vzzT5dxlStXNppuCgDwbzSGAgAAwBF//vmnfvvtN5dxoaGh6t69u625TZd1nz17tq1f0nXs2NGoiey3337T3r17bcv7V6ZNp3fffbcty2PPmTPHKK5v374e5/KEyTTKNWvW2LbUnCsmE06uN4GBgSpTpozLODt+3FuyZIlRnOkyn3br0KGDV/Nlp9dxcnKyT5ukrlcVK1bUihUrHHvNZKfnqKfnGpPGUCnzU0NdbXfTTTcpT548V/5/vnz5VK9ePZ/UcpnpY5IVmUzU9+Ux77bbbvNqvk2bNun06dMu4woVKqSoqCgvVPR37du3V44cObyeF1f3yy+/GMV1795dOXPmdLiaf+vfv79R3ObNm3X8+HGHq/kfk3MZ4A+8dY48ceKEVq9ebRR7//33X3ef89u2bevVfBUqVDCK82RifXZw7ty5TK0osXbtWv3yyy+aPn263nvvPd1111264YYbVLduXU2aNMnoYr1/ioiI0NSpUxUUFGQUb3r+rly5sho1auR2PZ4yPX97coHc9SQtLU0///yzUWy/fv2UK1cuhyvyjpCQEN13330u4+Li4jR16lTb85tOImWKPABkDzSGAgAAwBGm0zjbt2+vfPny2Zq7ZMmSatmypcu41NRUTZo0yba8OXPmNJqWYFmWJk6caFveyy5evGh8f+yYopSYmKjFixe7jKtZs6ZKlSrlcT5PmHxZHBcX53L5XLuYTgi63pg0Vu/evdvjPBs3bjSK89VV8Y0bNzb+0cQOJpOoAgMDdfvtt3uhmmszXaJw3bp1DleCy/Lly6e3335bmzdvVtWqVR3Jwbnm72rVqmW0dJ5TzZhXa8J01ZjpZGNoiRIlVLFixUztPyvw1nkxM8qXL+/1qYIrV640irv55pt90qBZuHBh1a9f3+t58W+HDh0ymoIkyZFJ1ybuvPNO4/d7ptPu7cDnFGQV3jpHzp8/3+iinuDgYNsvevZ3ISEhqlOnjldzFi9e3Cjuem8MnTlzZqZWlKhfv75uueUWde/eXY899pi+/fZbjx7LHDlyaOLEiW59VjQ95/nq/F2mTBnj5703z99Z1fLly3X27Fmj2HvuucfZYrxs0KBBRoMtRo0aZWveU6dO6fvvv3cZFxoa6vOLbwEA9qAxFAAAALZLT083bny0exl5d/frq+XkJ06caPt0ypiYGB05csRlXI0aNVS3bl2P861cudJoyWZ/mORlsryv5L2pW66mq12vXC0lL0lHjx71KMf58+d18OBBl3FFihQxmkLjhJw5c6pWrVpeyZWSkmLUaFOrVi0VLFjQCxVdW758+Ywa/5gY6rxKlSppxIgR+vPPP/X4448rJCTEsVyca/4uICDA6OKXhQsXKj093a19b9++3eX7iDZt2vzr31w99vv27dOePXvcquXixYtGDcH+8Hd3ksl58cSJE7p48aIXqvk7X7yX2bJli1FckyZNHK7k2ho3buyz3Pgf04tEQkND1aJFC4eruboCBQoYTzrz1kUvAQEBXm/yAjLLG58dJWnFihVGcc2aNfP55yVvq1Klii0r0bgjLCxMERERLuMSEhK8UA0ykiNHDn311VduNXCeP3/euKH71ltvzWxpHjO9aJaLVl0zPcaWLVtWNWrUcLga74qMjDSaurxmzRpt2LDBtrzjx4/XhQsXXMZ16dLlujuvAUB25b0RJAAAALhu/Pzzzzp06JDLuMKFCzv2RV6XLl30wAMPuPwyeNOmTVq3bp0tjZLSpR+iK1asqJ07d2YYt2fPHi1dutTWiSymy8jbdbWv6Rec/jA5qUSJEgoICHDZjHvgwAHHawkODlb58uUdz+OEixcv6o8//tDmzZu1a9cu7dq1S0ePHtWpU6d06tQpJSYm6sKFC0pJSXG7IcmUpz/ubd++3SiuWrVqHuXxVPXq1bV27VrH82zZskWpqaku4/zhdSxdmgjt6nXqjdfx9eypp57SiBEjvDaNj3PNv7Vu3VozZszIMObMmTNav369W817riZ05syZ86pNb1FRUQoNDc2wgffXX39V2bJljWtZs2aNzp075zLOHxpDjxw5orVr1145L+7fv1+nTp3SyZMndf78eaWkpCglJSVTS2+aSE9P14kTJ7w+vbNKlSpezSeZN4bedNNNDldybQ0aNPBZbvyPaQP+TTfdpNDQUIerubaoqCgtXbrUZdymTZu8UI1UunTpbLNEqy/YfeFnVmdZlnbu3KkNGzZcOUceOXJEJ0+e1KlTp5SQkKCUlBRduHDBsQsc7GgMNf1M5g/vSbytTJkyPsmbK1cuxcfHZxhjcmEZnJM/f35NmjRJ7dq1c2s70/N3cHCwT9/vRUVFGcX98ccfSk9PN5oKeb263o+xQ4cO1bx581zGjRo1Sp9++qktOUePHm0UN2jQIFvyAQB8j8ZQAAAA2M50CmePHj0cmy4QERGhzp0766uvvnIZO27cONsaQ6VL00qff/55l3ETJkywrTH0/Pnzmjlzpsu4oKAg9e7d25acps06Ti0v7I7g4GDly5dPZ86cyTDOpKHZUyVLlvTqMuGe2rVrl3744QfNnTtXq1atcvkDjNNc/Q1dMf0bV6pUyaM8nvJW/qz0OpYuTXJ1xRuv4+vZm2++qe+++06ff/65WrVq5Xi+rPQc9da5xvRHsZiYGFsbQ5s2bXrVBqqcOXOqSZMmGS6VGBMTo4EDB9pWy2XeeA7+0/nz5/XTTz9p9uzZWrx4sdEUaqedOXPG642h7jT62sV0glTlypUdruTafP3+AZdkhSZiybyR2FvT0H3xukb2cujQIc2ePVs//vijli9f7vFnN095mj89Pd24Mdu0USw7KVasmE/ymjT00xjqO82aNdOECRMUGRnp9ram5+/q1asrZ86cbu/fLqbn78TERO3evVsVKlRwuKKsa/369UZx2fUY265dO5UsWdLlZ8rJkyfrnXfe8fgCnsWLF2vHjh0u4ypVquSzqfoAAPtxiQoAAABsFRsbq1mzZhnFOrWM/GWmkzGnTJli65fGffr0Mboa/JtvvlFSUpItOadPn260r7Zt2+qGG26wJee2bduM4nw1ReKfTL40Pn78uON12PX4Oyk5OVnjx49Xw4YNVbFiRT3++ONasGCBz5tCL9fmiWPHjhnFmSxZ7iRv5ed1jMzYtWuXWrdurUcffdSx6cCX8Rz9twoVKqhkyZIu40ybK6VLjQ+LFi3KMCajhlRXzaoLFy50a5LaggULXMZUqlRJxYsXN96np1asWKE+ffrohhtuUPfu3TVp0iS/aAqVPD83ZoYv3s+YnMMLFy6svHnzeqGaq6tYsaLPcuN/9u/fbxTnyyZid/IfPXrUsanDf5UVPqfA/1y8eFHffvut2rRpo1KlSun+++/X3Llzfd4UKnl+fjx69KjxdzbZbYljEyZLujvB5Ps2pz+j4N9KliypCRMmaMmSJZlqCpWyzvm7QIECKly4sFEsK5pcm2VZ2rdvn1Fsdj3G5siRw2gy5/nz5zVt2jSP840aNcoozp2LOgEA/o/GUAAAANjKtMmyatWqji/7Gh0dbdQ44U4zq4mSJUsaTbA6f/68vv/+e1tymi4jf++999qST5JxM0T+/PkVEBDg89uRI0dc1pqYmOjpw+JSoUKFHM+RWRcvXtTo0aNVoUIF9evXT6tWrfJ1Sf/i6Y97pg1Zpl/yO8Vb+U1fx506dfL5azggIEBTpkxxWas3Xse45P3331fHjh0dncjDuebqTN5nLF261Phvs379epcNHG3atLnmf3PVGHry5EnjiVvJyclatmyZyzhvLSe4bt06tW3bVo0bN9ZXX33lkyZMV3xRk7ffz5w6dUoXLlxwGeftyan/FBER4bNGGfyP6fLRvm7krVChglGDk2VZtiyJ7Yo/f06Bf/r2229VvXp13XXXXfr111/dugjEGzw9P5pOeb/hhhtUoEABj3JlRWFhYb4uAX6gXr16Gj9+vHbv3u3xAICscv6WzKfEm3w+vF6dOHHC6P29JFWpUsXhanxnwIABRiuqmTZ1XktsbKy+/fZbl3GhoaHGwzYAAFkDjaEAAACw1dixY43i7rnnHocruTRFoFevXkax48aNszW3aQOmaUNnRnbv3q2lS5e6jCtQoIDuvPNOj/NJl35gOXXqlC378id2TXDNiC+Xu8rIrl271LRpUw0cONCvl+JOTU31aHvTqacFCxb0KI+nvPXDvD//rTPLG69jf/PSSy/JsizjW1JSkk6cOKHdu3crJiZG7777rnr16qV8+fK5nXv27Nnq3r27I5PMONdcm0lTZFJSkpYvX260P1fTRfPnz686depc87/fdNNNypMnj0c5Lvv999+NGjmcbgy9cOGCnnrqKd100036+eefHc3lKU/PjZnh7fczp0+fNorz9YUd/lLD9c60scTXjcTBwcHG7zm90Vjir59T4H+OHTumO+64Q3fddZe2b9/u63KuydPzo+kFSt6cYO5PTBrbkf2EhoaqWbNmeuWVV7Rjxw6tWbNGffv2NWpscyWrnL/dqYHG0GszPcYWKFAgW79HKVq0qDp06OAybuXKlcYXW17NxIkTjS4c7dy5MxcLAUA2w7t2AAAA2Gbjxo1av369y7jAwED17t3bCxWZLyf/888/6/Dhw7bl7dSpk8sGCUmKiYnxOO/EiRON4nr06KGQkBCPcl1muhx3VuONiVuhoaGO53DX7NmzVadOHa1YscLXpbjk6RQa07+xr6efeCu/N6ZPeZs/TvPzN2FhYSpcuLDKli17ZUn4SZMm6fjx45o5c6YaNGjg1v5mzZqlIUOG2F4n55prM22KNG3GdBUXHR2d4Y//OXLkUIsWLbxSi3TpvWR0dLTR/jLj+PHjatq0qd56660ssRSpLya0efv9jGlDtS+XkfenGq5nSUlJxtOSixQp4nA1rpku33727FlnC5F/fk6B/1m5cqVq1qypOXPm+LoUx8XGxhrF+UOTGmCHHDlyKDw8XAUKFFBkZKQaNWqkDh06aNiwYRo1apSWLVums2fPasmSJXrhhRdsn9zpagWDyzh/Zw8cY/9n6NChRnGeTA398ssvjeJMlrYHAGQtNIYCAADANqZTN6Ojo1WiRAmHq7mkcuXKuummm1zGpaen2zK987JcuXKpa9euRnknTZqU6TyWZRk3htq5jHxCQoJt+/In3mis8LepGuPHj1enTp2y7d/0n0wbBXz9w7i38l8vf3eYCQkJUYcOHbRixQp99dVXbk0QHTNmjPEPDaay6/PTjnNNsWLFjJYvNGmyvHDhgsvJ4yaNqK5ilixZYjS5y6Tm2rVrK3/+/C7jMuPAgQNq3LixVq9e7cj+swtvv58xbaj29fnbX2q4nrnTfJ87d24HK7G3Bm9c+OJvn1Pgf37++WdFR0fr5MmTvi7FK0wvSjC5KBjwpr59+7q1osTlW1pamuLj43X69Gnt2bNHy5cv18yZM/Xee+9p4MCBatKkiaMXsZqe6zh/Zw8cY/+nVatWRp/vJ0+enKkVSJYuXaqtW7e6jKtYsaJatmzp9v4BAP6NT/oAAACwxYULFzR58mSj2D59+jhczd+ZTg0dP368rXm9sZz8kiVLtG/fPpdxVatWNWqQNXU9LtWcHc2ZM0cDBgzQxYsXfV2K3/HF9DVf5Oe1jKsJCAhQ7969tWrVKpUqVcp4u4ceekgbN260rQ6enxkzadZcvXq14uLiMoxZvny5EhMTM4xp06aNx/XEx8dr5cqVGcacP39ea9as8ThXZp05c0a33Xab9u7d68j+kXkXLlwwirNjGVNP2TWhH5lj2oARGBiooKAgh6txzbSRmHMifG3t2rXq0qXLdfVcNL2vXBAA2CM7Xgh0PR0z3cUx9u8GDx7sMubs2bOaPn262/s2nTTKtFAAyJ5oDAUAAIAtZs+erVOnThnF9u3bVwEBAV67Pfjgg0Z17dq1y+XELHc0bdpU5cqVcxm3bdu2TE+lMm0qNW2ONcUV71nfwYMH1atXr0w3hUZERKhZs2YaPHiw3nrrLU2bNk0LFy7UH3/8of379ys2NlaJiYm6cOGC0tPTjaZTuFqG2A6m0y1MJ4s6xVv5eS0jIxUqVNCiRYuMl8lLSUlR3759jaZCmuD5mTGT5si0tDQtXrw4w5gFCxZk+N9LlChhtExk9erVXT5XXE0DXbx4sdF5yanG0Pvuu89oksrVBAYGqmrVqurZs6deeOEFjR07VnPnztW6deu0e/duHT9+XPHx8UpOTlZaWprRedF0Gv/1wLThMy0tzeFKXLPrGIjMMX38/aEpVDJ/bvO8gi/FxcWpS5cuio+Pz9T2YWFhatiwoe677z6NHDlSkydPVkxMjDZt2qR9+/bp1KlTSkxMVEpKivFnR7u/47ga09cdFwQA9shK53DO357jGPt39957r3LmzOkyzt3l5M+ePasZM2a4jAsNDfXKuRUA4H2+f+cEAACAbGHs2LG+LsEW48aNU9OmTW3bX9++ffXiiy+6jJswYYLbEz0TExONvtjJkSOH7rnnHrf27UpAQICt+4P3DRgwQOfOnXNrm6pVq6pXr15q27at6tSpkyWXmzRtDPV1Q5q3pkrwWoYrkZGRmjVrlpo3b240sW/jxo0aMWKEhg8f7nFunp8Zi46OVmBgoNLT0zOM+/XXX3XHHXdk+N8z4k4TZqtWrTR16tQMc7300kuZrkW69MNgs2bNjGsyNXXqVH3//fdubZM3b15169ZN7du3V3R0tCIiImyvC5dklQs7/KWG65lp84C/NGqYTsO9XqZlwT89/vjj2r9/v1vblC5dWr1799att96qRo0a+UUjl7tMX3cc9wF7ZKVzOOdvz3GM/bv8+fOre/fuLlc0+/333/XHH3+oWrVqRvv96quvjL5j7NSpkwoVKmS0TwBA1pL1fsUDAACA3zl69Kjmz5/v6zJsMX36dCUkJNi2v8vTUV2ZOnWq8ZeKl3333Xcul4eVpFtuuUU33nijW/t2JVeuXMaxqampRhM//OG2aNEiWx8nfxUTE6Off/7ZOL5u3br65Zdf9Mcff+jZZ59VvXr1HGkK9caS9rlz5zaKM52A7BRv5Td9Lf/yyy8+f326c4O9GjZsqLfeess4/o033tDu3bs9zsu5JmP58+dX7dq1XcbFxMRc87/Fx8dr1apVGW7vTmOoq9gVK1Zk+D7LpDG0UaNGbj03TKSmpuq5554zjs+dO7feeustHTlyRKNGjVL79u0daQr1xnkxqzBtDM3sNDs7+UMN1zPT54plWX7RWGLa7GB6vwC77dixQ2PGjDGOL1++vKZPn669e/fqtddeU9OmTR1pCvXGOdJkcpt0/TQtAU7LjhcCcf6+No6x/zZkyBCjOHemhn755ZdGcSwjDwDZF42hAAAA8NiECROyzQ/X8fHx+uabb2zbX6lSpRQdHe0yLjY2Vj/++KNb+/bVMvKS+Zd3ku8nL+LfXnvtNePYRx99VCtXrlSbNm0crOgSb0zJLFq0qFHciRMnHK4kYydPnvRKHtPXMq9jPPzww2rZsqVRbEpKih599FGPc3Kucc2kaXPLli06fvz4Vf/bkiVLXDZG2dkYmpqaqiVLllz1vx0/flxbtmxxmaNVq1bG9ZiaPHmy9u7daxRbo0YNbdq0SU888YTtDar/5K3p0VlB/vz5jeJ8ff72lxquZ+6cO9ydnu+Es2fPGsXRWAJfef31142/7+nRo4c2bNigrl27Oj753RvnSNPjyZkzZxyuBLg+mL7mOH9nDxxj/61hw4aqU6eOy7ivvvrK6DuQ5cuXa/PmzS7jKlasaPT7BQAga6IxFAAAAB5ztcRJVjNu3Dhb92famGna6ClJhw4d0oIFC1zG5cuXTx07djTer6m8efMax9o5gRWe27NnjxYvXmwU+9hjj+ndd9/12rJ/3niumDaG7tu3z9lCXDBtUPKU6WuZ1zECAgI0atQo4+XefvjhB/3yyy8e5eRc45pp0+a13jO4mtBZpUoVFStWzLieMmXKqGzZshnGXCunyfsayb1GVVNjx441iqtQoYIWL16sMmXK2F7D1Vyvz+urKVKkiHLkyOEy7lpN0N6SkpLiF80K17PQ0FCFh4cbxfr6+SKZNxIXLFjQ4UqAf3PnwtmuXbtqypQpxq8/T3njHFmkSBGjuKNHjzpcCXB9KFCggFEc5+/sgWPs1Q0dOtRlzJkzZzRjxgyXcabTQgcOHGgUBwDImmgMBQAAgEd+//137dixw9dl2Oq3336zZQncy7p06WK0vOi8efOMpwR+9dVXSk9PdxnXo0cP4yYedxQtWlQhISFGsUeOHLE9PzLv66+/NoqrV6+e3nzzTYer+TtvfNlbsmRJo7idO3c6XEnGvHVcLVWqlFEcr2NIl5riHn/8ceP4Z5991qN8nGtca9asmdFjdK1mTFeNoZlpwnS1TWZrkaTw8HA1bNjQ7ZoycuTIES1dutRlXGBgoKZNm2Y8udIO19uPoBkJDAzUDTfc4DLu6NGjSkxM9EJFV/fnn3/6LDf+58YbbzSK8/W5Izk52XgKljtN+oBdZs+ebXRMLVGihMaOHev4lNC/8qfPjocOHXK4EuD6YHqu8/X5250aOH9fm+kx9vz58zp//rzD1fiPnj17Kk+ePC7jXC0nf/78eaPvgENCQnTvvfealgcAyIJoDAUAAIBHTCcsZSWWZdk6BTU8PFxdu3Z1GZeamqopU6YY7dOXy8hLlybHlShRwiiWH0n8y8KFC43iXn/9daPJXHaJj4/3yoStypUrG/1guXnzZlmW5Xg9GeX3BtPGUF7HuOzpp582as6SpDVr1uj777/PdC7ONa7lypXLqFHyak2Xp06d0qZNmzLczonG0I0bN+rUqVP/+neTxtDmzZsrODjY7ZoysmjRIqPjfY8ePVS3bl1bc7tyvT6vr8VkUqtlWdq1a5fzxVxDdrtgLqsybcLw5XNFuvR8MTn+BAUFGZ97ATuZfnZ88cUXjS6GtZM3zpGm70NjY2N17Ngxh6sBsr+scv6WzN/zFS9e3OFKsq78+fMbT5neunWrw9X4j/DwcN1zzz0u43777Tdt3779mv990qRJRhd3dOrUSYUKFXKrRgBA1kJjKAAAADItMTFR06dP93UZjpgwYYLRRE5TplfemjR8rly50ugLyMqVK6tRo0ZGeTPD1VKxl/3xxx+O1QD3WJalFStWuIyLjIxUmzZtvFDR/3jreZIrVy5FRka6jDt79qy2bdvmhYr+LS4uzmuPB69juCsiIkIvvPCCcfwLL7zg0fmU56hrJs2b+/bt0549e/72bwsXLsywISlHjhxq2bKl2/W0atUqwwZ8y7L+1Wiyd+9e7du3z+W+nVhG/vfffzeKGzRokO25Xbmen9dXU61aNaO4tWvXOlyJf+bG/5i815Pks/d67uYvVaqUAgP5KQfeZ3KOzJUrl3r16uWFav7n+PHjOn36tON5ChcubDwp3NXFNgBcyyrn72PHjhlP/Da9T9erihUrGsVdb8fYIUOGGMVlNDXUdBn5wYMHG8UBALIuvk0AAABApn3zzTeKi4vzdRmOOHjwoGJiYmzbX7NmzYyaW9avX+9yUqCvp4VeVq9ePaO49evXO1oHzB09etToNXvzzTd7dRlASdqwYYPXctWpU8coznRCjt2WLFlia2N6RngdIzMGDhxoPG32jz/+8OgiEp6jrpk2S/5zIqerCZ316tVTvnz53K6ncOHCqlGjRoYx/3yPZTItVLrUdGq3nTt3uowJDw9XkyZNbM+dkcTERL+YhuRPqlevbhRn2uzrhOXLl/ssN/7H1THoMpMLppxkmt/0/gB2Sk9P159//ukyrmnTpsqVK5cXKvofb352NJ0WvmTJEocrAbI/0/Pdtm3bfPp9tOn5O1++fMbLpV+vOMZeXfXq1dW0aVOXcRMnTlRKSsq//n316tVG58oKFSooOjo6MyUCALIQGkMBAACQaePGjTOKq1GjhizL8pub6RRN0/tnIiAgQH369DGKzajxMyUlRdOmTXO5j8DAQKNlZzxx0003GcUtWbLEp0ty43/+OS3uWmrWrOlwJf/mzSZM0wl4P/zwg7OFXMPMmTO9lsv0dXzixIkMl6jC9SUkJETPPvuscfyrr76a6WZnzjWuNWzY0GgJPncbQz2ZzulqW3drkaSCBQuqdu3ama7pWkzOjVWqVLF9CXtXlixZoosXL3o1p78zPR7YeXGXO+Lj433alIr/MX0vu2HDBiUkJDhczbUtW7bMKM4X782BI0eOXLXZ5J+y+2dH04uUfHXuAbKTatWqKUeOHC7jLl686NP3XKbnby7scM30GGt6IWF2MnToUJcxp0+f1nffffevf89okuhfDRw40O26AABZD42hAAAAyJTdu3cbX63r7WXFXDGtZ+bMmTp79qxtefv27Ws0hXHy5MnXbASYPXu20XJFbdq0UfHixd2u0R2NGzc2ijt27BjLavqJ2NhYozhvTzS4ePGiV7/kNb0afuHChTp+/LjD1fxdSkqKvv/+e6/lK1iwoPHSXT/++KPD1SAr6devn/HU0K1bt2Z6aijnGteCg4PVrFkzl3ELFiy40jx74MABl1PAnGwM3b17t/bv3y/p0tLyCxYscLnP6OhoR6ZZm5wbfTHpZ/78+V7P6e/q16+viIgIl3H79+/Xxo0bvVDR382fP9+oiQrOq1u3rtHxIi0tzWevtaNHjxqft0ybogE7+etnR8m750iTiW2StGrVKh08eNDhaoDsLSwsTNWqVTOKnTNnjsPVXJvpdyOcv10zPcYeO3bMuCE3u7jrrrtUuHBhl3H/bAKNi4szGioREhKie++9N7PlAQCyEBpDAQAAkCnjx483mswVEBCgu+++2wsVmevWrZuCgoJcxiUnJ2vKlCm25S1TpoyaN2/uMu7YsWPX/KHDdBl5b3yxU6xYMeMru+18HJF5phORTCbP2Wn+/Pk6deqU1/JVq1ZNpUuXdhmXmpqqMWPGeKGi//nmm290+vRpr+Zs3769UdzUqVMdrgRZSUhIiJ555hnj+MxODeVcY8akifPkyZPatGmTJNcTV8LCwhQVFZXpepo3b+7yvdblGrZs2aITJ0643KcnjaoZMTk3evu8ePHiRX399ddezZkVBAcHG/94/NVXXzlczb9NnDjR6zlxdQULFlSdOnWMYr15Qc4/85p8ng4KClKLFi28UBHwd/762XHr1q1eXUq+devWCgsLcxlnWZYmT57shYqA7K1NmzZGcbNmzfLJihFbt241Xk3F9L5cz2rUqGF8gYEv3t/7UkhIiPr16+cybtGiRdq1a9eV/z916lTFx8e73K5jx45GjacAgKyPxlAAAAC4LT093bhBsWnTpsYTxbylSJEixl/O2bmcvGTesHm1x/fEiRP66aefXG6bN29edezY0c3KMqdTp05GcRMmTFBycrLD1cCVtLQ0o7i4uDiHK/m70aNHezWfJHXv3t0o7qOPPvLaEqPp6el68803vZLrr0xfx+vWrdOqVascrgZZSf/+/Y1/xPFkaijnGtdMmyYvN2O6agyNiooyaoK4lty5c6tBgwa21HKZU42hJudGb58X58yZo6NHj3o1Z1ZhejHD+PHjvXo8OHjwoE8nV+HfTD/vfffdd7auEmHqyy+/NIpr0KCB8uTJ43A1wL/x2fGSXLlyqWXLlkaxn376qVJTU50tCMjmTM/fBw4c0M8//+xwNf9mev4OCQkxGg4A6fbbbzeKmzRpktcvpPa1wYMHG03B/+vUUNNl5AcPHpzpugAAWQuNoQAAAHBbTEyM8RJZPXv2dLiazDFdTn7NmjXasmWLbXnvuusuo4kaP/zww79+oJw8ebLRjzPdunVTzpw5M1uiW7p162b0BVVsbKw+/vhjL1SEjOTKlcsozmRym122bdummTNnei3fZaaTjI8fP653333X4WoumThxoq3HG1ONGzc2buB/5ZVXHK4GWYm3poZyrnGtdu3aKlCggMu4y02YrpZut6MJ09U+3GkMLVmypCpUqOBxTVdjcm705nlRkl5//XWv5stKunbtqhw5criMO336tD7//HMvVHTJyJEjdfHiRa/lg2t33nmnUVxiYqLXG82WLl1qPPHQ9H4AdvPHz46nT582bnixk+lnx4MHD2r8+PHOFgNkcy1btlTu3LmNYv/73/86XM3fxcXFGb/GW7Vq5fWJylmV6TE2ISFB7733nsPV+JeyZcuqbdu2LuMmTJigCxcuaP369Vq7dq3L+AoVKig6OtqOEgEAWQCNoQAAAHCb6RTN4OBgde3a1eFqMqdjx47GP3TYOTU0IiJCd911l8u45OTkfy0h6k/LyF9WoUIF3XLLLUaxr7/+uleXC8e/5cuXzyjOdFksOzzzzDM+Wf6rdu3aaty4sVHsyJEjtXXrVkfrOX78uB5//HFHc1xLYGCghg4dahQ7Z84clw1luL7cd999bk0Nzczy2JxrXAsICDD6YWfJkiXatGmTy2mU3mgMPX78uDZs2KAlS5a43FerVq08rudaTM6NO3fuzFRTc2bMnDlTK1as8EqurKhw4cK6+eabjWJff/11nTt3zuGKLj0/xowZ43geuCcqKkply5Y1in377beNlty0y3PPPWcUFxgYqN69eztcDXB1/vjZ8dVXX/Xaag5/1a1bN+XPn98o9vnnn/fJFGIgu8iZM6fR96bSpe8nVq5c6XBF//POO+8Yv7779u3rbDHZSPPmzVWlShWj2Pfee0979uxxuCL/MmTIEJcxJ0+e1Pfff68vvvjCaJ8DBgwwuvgWAJA90BgKAAAAt5w5c8Z4ut+tt96qggULOltQJkVERBhPX5k0aZKty4GZfjn410bQjRs3auPGjS63qVChgpo0aZLp2jLj4YcfNoqLjY3VoEGDHK4GGTGdCjl37lyHK7lk1qxZmjVrlldyXc0TTzxhFJeSkqIePXo41jCQlpam3r17+3RJrIEDBxpPGu7fv7/Onz/vcEXIKkJCQvT0008bx2d2aijnGtdMmjnj4+M1cuTIDGPy5s2revXqeVxP48aNXV6E88YbbxgdT5xaRl4yOzeePn1aq1atcqyGy+Li4oyf69ezhx56yCjuxIkTeuyxxxytxbIs3XfffSwd7Kf69OljFHfixAmNGDHC4Wou+fbbb40a4qVLy+kWL17c4YqAqytZsqRR00hMTIxXjoHr1q3z2WT4sLAw4wtwT5w4oWHDhjlbEJDNudNU+dhjj3nlAq79+/cbT6vMmzevOnbs6GxB2YxJ86N0aZDCoEGDvHbRnj+44447VKJECZdxH330kaZMmeIyLjg42KtDJQAAvkdjKAAAANwydepUJScnG8X66zLyl5nWd+LECc2ZM8e2vC1btlSZMmVcxi1fvlw7d+6UZD4t1BdXpN92221q0KCBUez333+vt956y+GKcC1lypRRaGioy7gdO3YYLT3kiYMHD+q+++5zNIcrHTp0UPXq1Y1iN2/erG7duiklJcXWGizL0pAhQxQTE2Prft1VsGBBPfjgg0ax+/fvV+/evVkyF1cMGDDA6IcKSdq2bVumpoZyrnHNtHly+vTpGf73li1bGi3V7UpISIiaNm3qUS2XOdkYWqlSJaO4yZMnO1bDZQMGDNDBgwcdz5PV3XbbbapatapR7JgxY4yfZ5nxyiuvaOnSpY7tH54ZPHiwwsLCjGLfeecdrV692tF6Tp06pQceeMA4nuYy+FJISIjR9xZxcXH64YcfHK3l/Pnz6t69u08/fzzxxBPGF9KNHz9eo0ePdrgiIPtq0aKFateubRS7bNkyffjhh47WY1mWBgwYYHyx8JAhQ4zff+CSgQMHqlixYkaxv/76q1588UWHK/IfOXLkMLr49ffff1dcXJzLuE6dOqlIkSJ2lAYAyCJoDAUAAIBbxo4daxTnzkROX3Fnoqmdy8kHBAQYT6+ZOHGi0tLSjJoRAgMDjfdrp4CAAL3//vvG8U8//bRf/UiyYsUKn06t9Kbg4GDjL9fdmQDorvPnz6tjx44+nZApXXrNuPPcnTdvnu644w7blgZMTk7WPffc4zfLzz733HMqXLiwUezs2bM1YMAAv2kOPXDggD777DNfl3Hd8sbUUM41rlWsWNGoQdeyrAz/e5s2bewqyWVDp6taJKly5crGPxJmhmnD8ahRoxxdtvC1115ztIExOwkICNALL7xgHN+vXz+tWLHC9jqmTJmil19+2fb9wj5FixY1vhApLS1NXbt21YkTJxypJS0tTd26ddPx48eN4uvXr69bb73VkVoAU6bnyOeff15paWmO1JCamqoePXrozz//dGT/pm688Ua3pnrff//9mj17toMVAdnbc889Zxz79NNP67fffnOslhdffNH4Yt5cuXI5PrE+O8qZM6db7+9HjBihzz//3MGK/MuAAQMUFBRky76u1xVWAOB6RmMoAAAAjG3evNl4imDHjh1dLh/qa8HBweratatR7Ny5c41/xDPRt29fo2XZvvrqK82dO9foB8ro6GiVLFnSjvLc1qRJE91zzz1GsZZlaeDAgXr11VeNGkKc8ttvv6ldu3Zq3Lix49OB/Inp1LWYmBhHmqrOnTun22+/XevWrbN935nRpk0bderUyTg+JiZGderU0aJFizzKu379ejVs2PCaTd+5c+f2aP+ZkTdvXr3xxhvG8ePHj1fnzp2Np2Y4Yffu3br//vtVoUIFr0zzw7UNGDDAeLnbzE4N5VzjWqtWrTzeh53TOe3Ylx33KSOmNV64cEEDBgzQhQsXbK/h3XffdeuHUEg9evRQ48aNjWITExN1yy23aOHChbblHzdunPr06ePT4wvMPP3008afS/fv32/rRUCXXbx4Uf369XPrOfjKK6/YWgOQGabnyO3bt2v48OG2509JSdHdd9+tefPm2b7vzHjmmWeML1ZJTU3VXXfdpWnTpjlc1d+dOHFCc+fO9WpOwAldunQxvrD5woUL6ty5szZu3Gh7HV988YVee+014/iHHnrI+IJb/N2AAQNUq1Yt4/j7779f7733noMV/VtcXJy+++47r+aULl2c0KFDB4/3U758ecc/XwMA/A+NoQAAADBmOi1Uknr16uVgJfYxXU4+LS1NkyZNsi1v2bJlXS6vKl2agvfII48Y7fPee+/1rCgP/fe//1Xp0qWN41988UW1bdtWhw4dcrCqv0tKStJXX32l+vXrq3nz5n7zA5M33XXXXcaxQ4cOtXXKyc6dO9W4cWO/W3L1iy++UNGiRY3j9+3bp+joaLVv314LFixwK9fKlSvVu3dv1a9fX5s2bbpm3JtvvunWfu3Sv39/dezY0Tj+hx9+UJ06dfT77787V9Q/WJalX3/9VR07dlTFihX12WefOdKoBfeEhoa6NTX0lVdecXtqqMS5xhVPGzFvvPFGValSxaZqpDp16ih//vwe7cPJZeQlqUKFCqpZs6ZR7MKFC3XvvffaNi35woULeuCBB/T444/bsr/rzUcffaQcOXIYxcbFxemWW27RG2+84dFUu/j4eA0ZMkT9+/e/5vPArmk+sEeJEiXcalhbvXq1oqOjdeDAAVvyx8fHq1u3bm59luzSpYtuu+02W/IDnujYsaPxcXbEiBH69NNPbct97NgxtWnTRt9++61t+/RU3rx5NWrUKOP4Cxcu6O6779Zjjz2m5ORkByuTDh8+rCeffFJly5ZlAjmyhYCAAH3++ecKDDRrZTh16pSio6M9voj3Msuy9Prrr2vIkCHG25QuXZqLvTwQFBSk8ePHKzg42Cjesiw99thj6tWrl+0X9fxTbGysRo4cqcjISH300UeO5rqWoUOHeryPAQMGGA2qAABkLzSGAgAAwEhqaqrxNLYiRYrYugypk5o2bapSpUoZxdq5nLxk3si5d+9elzG5c+dW586dPazIM3nz5tXkyZPd+jH8l19+UaVKlfTCCy/ozJkzjtSVmpqqX3/9VQMGDFDRokXVp08f48m32VGdOnVUr149o9i0tDR16tRJw4cP96gJ5sKFC3rvvfdUp04dbdu27aoxAQEBKlSoUKZzeKJw4cKaMGGC8Q8Ol/34449q3bq1SpYsqf79++uTTz7RL7/8ojVr1mjr1q1au3atfv31V33xxRcaMmSIypUrp0aNGmny5MkZNsT17t3bp80Ao0ePNlqO+rI///xTTZs2Vc+ePbVr1y7H6tq4caOee+45lSlTRm3atNGsWbMy1VgI5wwcONB4auj27dszNUGJc03GPG2itLsJMzAwUNHR0T7b3tTAgQONY6dOnWpL09jvv/+uevXqZdhEU6RIEY9yZHf169fX888/bxyflpamZ555RrVq1dKMGTPcem+TmJiozz//XBUrVtQXX3xxzbgmTZoYTzKF9wwbNsytCVQbNmxQnTp1NGXKFI/y/v7776pfv75bk6Xy5s3rs4YDeCYgIMBvb6YXm/5T4cKF3bpo7IEHHtDQoUOVlJSUqXySlJ6erokTJ6patWoZXlDoq3Pk7bff7tb7Bkl67733VKNGDc2cOdPWSdPp6emKiYnR3XffrcjISL399ttKSEiwbf+ArzVs2NCtxswzZ86oTZs2evHFFz06Dh04cEDt27fXs88+69Z2n3zyicLDwzOdF1Lt2rXdnkA9ZcoUValSRePHj/foArCrWbFihQYNGqSSJUvqueee0+nTp23dvztatWqlihUrZnr74OBg9evXz8aKAABZBY2hAAAAMPLjjz/q5MmTRrHdunXLMpNyAgICdPfddxvF/vHHH1q1apVtubt27Wq8rKE39+WJqKgojRkzxq2rjxMTE/Xaa6+pePHi6t+/v+bPn6+UlJRM12BZlrZu3aovv/xSd999twoXLqw2bdpozJgxOn/+fKb3m508+eSTxrEXL17Uyy+/rLp16+qrr75yazLjqVOn9OGHH6pixYp67LHHlJiYeM3YRx55RNWqVTPet91uueWWTC9BdejQIY0bN04PPvigbrnlFt10002qVq2a6tevrzZt2mjIkCH64osvtGfPHpf7qlKlij7++GPj3E5c6V+wYEHNnTtXefPmNd7GsixNnTpVlSpV0q233qrJkyd73IB3+PBhTZ8+XQ888IBKly6t2rVra+TIkbZN8IL9QkND9dRTTxnHv/rqq5lq7uVcc23Fixf36MciJy7s8aTZ1I6Joyb69evn1sUJv/32m2rUqKGnn37arWm0Fy9e1Jw5c9SuXTtFRUVpy5Yt14wtXbq0nnvuOeN9X6+ef/55NWnSxK1ttm7dqq5du6pUqVIaPHiwpk2bps2bN+vMmTNKTU1VSkqKTp06pdWrV2vs2LHq2bOnihUrpqFDh+ro0aPX3G9oaKjGjBnj9oUmcF5QUJC+/vpr5cmTx3ib2NhY9erVS40bN9aMGTPcajRYtmyZunbtqqioKO3YscN4u4CAAE2cONF4qWrAG5544gm34j///HNVr15dH3/8sVtNinFxcRozZoxq1qypvn37KjY29pqxnTp18umFdB9//LHRCjB/9eeff6pTp06qXr26PvzwwwzPJxmJj4/XTz/9pAcffFClS5fWzTffrGnTpik1NTVT+wP83TvvvGO8pLx06f32q6++qkqVKumjjz7SuXPnjLfds2ePHn/8cVWuXFlz5sxxq87HHntMt99+u1vb4OqeeeYZdevWza1tjh07pn79+ql8+fIaOXKk0fdvV5OcnKzFixfriSeeUMWKFdW4cWN9+eWXGX6f6S0BAQEaPHhwprfv2LEjFx4CwHUqa/xaDwAAAJ/LjsvIX9arVy/jZZvHjRunBg0a2JL38pRPO5ao9/Uy8n/Vp08fHTt2zK3mIOnS0rvjxo3TuHHjFB4ervr166tevXqqUKGCSpYsqYIFCypnzpwKDg5WSkqKkpOTdf78eR07dkxHjx7Vn3/+qW3btumPP/5w64vf61G3bt304YcfurX896ZNm9SnTx8NGzZMzZo1U9OmTVWhQgUVKFBA+fLlU1pamuLi4rRv3z5t27ZNS5Ys0apVq4x+oKpWrZpef/11tW3b1pO75bH//Oc/Onz4sN5++22f5C9UqJB+/PFH5c2b17ipMjQ01JFaatSooR9++EFt27Z1a9lDy7I0f/58zZ8/X0FBQapZs6bq16+vKlWqqGTJkipatKhy5cql0NBQpaamKjk5WQkJCTp+/LiOHj2q/fv3a+vWrdq6dauOHDniyH2DswYNGqQ33njD6O93eWpoz5493c7DuebaWrdurZ07d2Z6W7t5sk+nl5G/LDw8XCNGjHDrh7bz58/rzTff1LvvvqsGDRooKipK9erVU6FChVSgQAEFBwcrISFBx44d086dO7Vq1SotXLjQaMpMYGCgJk6cmOkfNK8nQUFB+u6779SoUSPt27fPrW2PHDmiUaNGubUscEbeffddVa5c2ZZ9wX6VKlXShAkT1LlzZ7cm9q1YsUJdu3ZVgQIF1KZNGzVs2FCVK1dWoUKFFB4erpSUFJ09e1a7du3S+vXrNX/+fLefi5c999xzuvPOOzO1LeCUhg0b6u6779bUqVONt9mzZ48eeughPfvss2ratKmioqJUtWpVFShQQAUKFFB6erri4+N18OBBbd++XUuXLtWyZcuMPnfccMMNGjVqlB5//HFP7pZHQkJC9P3336tRo0bavXu3W9tu3bpVjzzyiB599FFVrVpVTZo0UdWqVRUZGanChQsrV65cCg4OVnJysuLj43XkyBEdPHhQ27Zt08aNG7Vx40aPVvMAspqcOXPqu+++U/369TNsGP+ngwcP6j//+Y+efPJJNWvWTM2bN1eVKlVUvHhxRUREKD09XefPn9e+ffu0ZcsWxcTEaP369Zma6tuyZUu98cYbbm+HqwsICND48eO1f/9+rVy50q1t9+/fr+eee07PPfecKlSooCZNmqhGjRqKjIy88n1USEiIUlJSrnxWu3wu2rx5s9atW+fRBaROu/fee/Xcc8+59T3dZYMGDXKgIgBAVkBjKAAAAFw6duyYfvrpJ6PYsmXLqlGjRg5XZK8aNWqoRo0a2rx5s8vYadOm6f3331dYWJgtue+9916PG0PLlSunZs2a2VKPXZ588kmFhITo0UcfzdSXqgkJCVq8eLEWL17sQHWQpC+//FI33XST21e9nz59WjNnztTMmTNtqaNQoUL67rvvHGtwdNdbb72lXLly6eWXX/Zq3iJFimju3LkqW7asJBlPUbTrWHQ1zZs31/z589WhQwedPXvW7e3T0tK0bt06rVu3zv7i4LcuTw39z3/+YxT/6quvqkePHpmasMe55upat26tzz77zO3tKlasqBIlStheT6VKlVS8eHEdPnzY7W1btWplez3XMmDAAH399ddasGCBW9ulpaXp999/d+tiC1feeecdNW/enMZQQzfccIPmzZunpk2b+mx5xwcffFAPPPCAT3LDXMeOHfXJJ5/o/vvvd3vb2NhYTZ8+XdOnT3egMmngwIF65ZVXHNk34Kn3339fCxYs0PHjx93aLi4uTvPmzdO8efNsqeNyg5g7U76dUqhQIS1evFitW7d2azLwZenp6dqyZUuG08MBXBIZGal58+bp5ptvdnt1hpSUFMXExCgmJsaR2urXr6+ZM2dmmZWzsoqcOXNq/vz5ateuXaY/Z+3atUu7du2yuTLfKlCggLp166aJEye6tV25cuW8dtElAMD/sK4NAAAAXJo4caLx0nmZmfrlD0zrPnv2rL777jvb8rZq1UqlSpXyaB99+vSxqRp7PfLII5o6daqjjWvIvKpVq+rzzz/3aQ3h4eGaM2eOR8seO2H48OEaO3ascuXK5ZV85cqV07Jly1SvXr0r/2Z69b/TDbXNmzfXkiVLVLJkSUfzIHsZNGiQbrzxRqPY7du3uzWB6p841/xbdHR0phptnfyhKDP7DgkJ8eqFL4GBgZo8ebKKFy/utZxX8/jjj2vYsGE+rSErqly5spYsWeKTv1/37t31wQcfeD0vMmfo0KH68MMPFRAQ4OtSrujfv7+++OILv6oJ+KsbbrhBU6ZMUXBwsM9qyJEjh6ZNm6YmTZr4rIZ/Kl68uBYvXqw6der4uhQg22vQoIHmzp2r3Llz+7qUK+rWrauff/5ZefPm9XUp2VLevHn1888/6+abb/Z1KX5l6NChbm8zcOBA3mcCwHWMxlAAAAC4NG7cOOPYrLaM/GU9e/Y0/oLEncfDlYCAAI8aOwMCAtS3b1/b6rFb9+7dtXr1alWvXt3XpeAq7rnnHr311ls+yV2gQAHNnTtXDRo08El+V/r166c1a9Y4/iNfv379tHbtWpUvX/5v/27aGJonTx4nyvqbGjVqaMOGDercubPjuZA9hIWFubXE+6uvvmo8JfdqONf8XYECBVSrVi23t2vTpo0D1VySmcbQRo0aea1B/7KiRYvql19+8dkksscff9xn5+XsoGrVqlq2bJlq167ttZyXm9Nz5MjhtZzw3MMPP6wZM2YoPDzcp3UEBgZqxIgRGjNmDD/Ww++1atVKEydOzNTFJ57KmTOnpk6dqjvvvNPruV254YYbtGzZMvXv39/XpQDZXlRUlFasWKFy5cr5uhR16dJFS5YsUf78+X1dSrYWHh6uefPm6dlnn+W90v9r1KiRW593goOD1a9fP+cKAgD4PRpDAQAAkKHly5dr+/btRrF16tRR5cqVHa7IGaVKlVJUVJRR7IIFC3TgwAHbcnvS2NmyZUuVLl3atlqcUL16da1evVpPPvmk3ywX/lfFixfXTTfd5OsyfOaJJ57Qp59+6tWGhkqVKmnlypVq3ry513JmRpUqVbRmzRqNHTvW9uWVGzRooJ9//lljx4696nSJEydOGO3nhhtusLWuaylQoIC+/fZbjRs3TkWKFPFKTneEh4c72tQG9w0ePNh4auiOHTs8mhoqca75J3cbMQMDAxUdHe1QNZlrDPXVUndVqlTR0qVLFRkZ6bWcwcHBGj16tN5++21+8PRQ6dKltWLFCj344IOOPpb58uXT+PHj9f777/M3y6I6d+6sFStWeLWR+K+KFSumH3/8Uc8++6xP8gOZ0aNHD3333XdevXCjaNGiWrRokbp27eq1nO7KmTOnxowZo8mTJ/vlZyUgO6latapWr17ts2NCWFiY3nzzTX3zzTc+v8DkepEjRw6NGDFCP/30k8qWLevrcvzCkCFDjGM7dOjAuQkArnM0hgIAACBD18O00MtM609PT9eECRNsy1u+fHnjptR/8udpoX91+YvTbdu2qVu3bj6ZMvJXoaGh6tixo2bOnKn9+/erQ4cOPq3H14YOHaqYmBiVKlXK0Tw5cuTQsGHDrjoh018FBgaqX79+2rNnj6ZNm6ZWrVpluok2b9686tGjhxYuXKiVK1dmuBzW0aNHjfZZtGjRTNWSWffee6/+/PNPPfPMM16f5PdPAQEBatKkiT777DMdPXpUw4cP92k9+LuwsDA9+eSTxvGeTg29nJNzzSXuNlXWqVPH0Wk3xYsXV6VKldzaxleNodKlCxhWr17tlUnJjRo10po1a3Tfffc5nut6ERoaqv/+979asWKF7UsOBwYGqkePHtq6dWuWeR+Oa7t8UcEbb7zhteaOHDlyaOjQodq2bZtuu+02r+QE7NShQwctX77cK5Pa77nnHm3evNlvV5n4p549e2rHjh166KGHFBIS4vX8OXLk0J133qnBgwd7PTfgTfnz59f06dM1a9Ysx7/H+qtWrVpp06ZNevLJJ7kwyAduueUW/fHHHxo+fLhPmnIDAgIUHR3t1vccTunZs6fxd5ODBg1yuBoAgL+jMRQAAADXlJSUpK+//too9vKPpFlZ165dFRwcbBQ7fvx4WZZlW+57773X7W0iIiJ011132VaDN0RGRurrr7/Wzp07NWzYMOXLl89ruXPnzq3OnTtrwoQJOnHihL7//nt16NCBpT//X8uWLbV582Y9/fTTypkzp637DgwMVIcOHbRmzRq99957WXKqQnBwsLp3765ff/1Vp06d0owZM/TYY4+pXbt2qlChggoWLKjQ0FAFBQUpX758KlmypOrWratevXpp5MiRiomJ0cmTJzV16lS1bNnSZb6dO3ca1WU6kdFOuXPn1siRI3Xo0CG98847Xp3YEBQUpJYtW+qdd97Rvn37tGzZMg0ZMkS5c+f2Wg0wN3jwYOPmZTumhl7GuUZq1qyZ8XsayTtNmO7kiIiI8HkTSMGCBfXtt9/q22+/VcWKFW3ff6VKlTR69Gj9/vvvqlmzpu37x6Xp3MuWLVNMTIw6duzo0euwQIECGjJkyJVjlS/Ov3BGUFCQnnrqKe3bt0/PPffcVSe52yE4OFj9+/fX9u3b9emnnypPnjyO5AG8oWbNmlqzZo3efPNNR95nRUdHa+HChZo4caIKFSpk+/6dlC9fPn300Ufas2ePnnjiCceOKX9VqlQpvfTSS9q/f79mzZqlxo0bO54T8Ad33nmndu3apVGjRjm6vHybNm20cOFC/frrr6pQoYJjeeBaWFiYXnrpJR08eFCvvfaaVy6WLly4sB599FFt375dCxYsULt27RzP6cq6det08eJFl3HlypVjdR0AgAIsO3/NBgAAAAA3pKSkKCYmRjNnztS8efN0+PBh2/adN29e3XTTTWrWrJmaN2+uqKgot5pkrmcnT57U6NGjNWHCBO3YsSPT+6lcubLat2+vIUOGGDUPTpkyRQcOHMgwJm/evBo6dGima8oq7rjjDs2ZMyfDmEKFCunkyZNequjaLMvSqlWrNHPmTM2ePVtbt261rXE+NDRUtWrVUtOmTdWsWTNFR0d75cdVZC+ca+CpixcvatasWRo1apQWLFig1NTUTO0nf/78uvnmm9W3b1/ddtttLicNbd682eW5QLo0Mcab05KyqtjYWP3888+KiYnRpk2btH37dsXFxf0rLjAwUGXKlFHVqlVVq1YttW3bVk2aNOFiIjeYXDDYokULv3xPl5SUpB9++EFTpkzRL7/8oqSkpEzvKygoSI0aNdLdd9+tbt26ZbkGN8DE+fPnNXHiRI0bN07r1q3L9H7KlCmjdu3aafDgwUYXTMyZM0ebN292Gff0009nuiY7JCcna968eZo+fbrmz5+vM2fOeLzP0NBQNWvWTG3btlXbtm1Vo0YNGypFVvDBBx/o7NmzLuNq166tjh07Ol6PP0lPT9fixYs1ZcoUzZo1y+PvSipXrqzu3burZ8+ejlwkBnukpaVpwYIFmj59un788UcdP37c430GBQWpYcOGV46x9evX9/lqJP/Uu3dvTZ482WXc66+/7vPzIADA92gMBQAAAOA3Dh06pNWrV2vDhg3au3evDhw4oEOHDikuLk5JSUlKSkpSenq6QkNDFRoaqnz58qlQoUIqUqSISpcurcjISFWsWFE1a9ZUZGSkr+9OtrBz504tXLhQa9eu1fbt23Xw4EHFxsYqKSlJlmUpPDxcERERypcvn8qVK6fKlSurSpUqio6OVunSpX1dfpZkWZYKFy6s06dPZxjXokULLVq0yDtFueHs2bNas2aN1q5dq927d+vAgQM6cOCAzpw5c+V1nJaWpuDgYIWGhip37twqVKiQChUqpFKlSikyMlLlypVTzZo1VblyZQUFBfn6LiGb4VwDT5w7d06//vqrVq1apc2bN2v//v06duyYEhISdOHCBeXMmVMRERHKnTu3ihcvrsqVK6tSpUpq1KiRGjRoQHOhnzl//rzi4+OVmJiosLAw5c6dWxEREfydIElKTU3VunXr9Pvvv2vbtm3as2eP9u/fr3PnzikxMVFJSUkKCQm58n64RIkSKlu2rCpWrKhGjRqpcePGWXJSPpBZBw4c0IIFC7R69Wpt375dBw4c0MmTJ5WUlKSLFy9eea3kyZNHkZGRqly5sipXrqzmzZurcuXKvi7fcZZladu2bVq+fLm2bNmiffv2ad++fTpx4oQSExOVmJio9PR0RUREXHkvkTt3bpUqVerK5+zLt7CwMF/fHcCvbd++XcuWLdOmTZu0e/du7d27V7GxsUpISFBiYqICAwMVHh6u8PBwFS1aVGXLllW5cuVUv359NW3aVDfccIOv7wIyYffu3Vq+fLk2bdqkvXv3au/evTp+/PiVv3taWprCw8OvHF8jIiKufGa7fHytWrWqIiIifH1Xruns2bO68cYblZycnGFccHCwDh48yHMZAEBjKAAAAAAA/mTdunWqV6+ey7gHHnhAH3/8sRcqAgAAAAAAAOBLH3/8sR566CGXcV26dNGMGTO8UBEAwN/519xrAAAAAACuc9OnTzeKi4qKcrgSAAAAAAAAAP5g9OjRRnGDBg1yuBIAQFbBxFAAAAAAAPxEWlqaypQpo8OHD7uMPXLkiG688UYvVAUAAAAAAADAV1avXq0GDRq4jCtbtqz+/PNPBQQEeKEqAIC/Y2IoAAAAAAB+YsKECUZNoVWqVKEpFAAAAAAAALgOfPLJJ0ZxAwcOpCkUAHAFjaEAAAAAAPiB+Ph4vfzyy0ax3bp1c7gaAAAAAAAAAL52/Phxff311y7jgoOD1b9/fy9UBADIKmgMBQAAAADADzz++OM6ePCgUWzPnj0drgYAAAAAAACAr3344YdKTk52GdepUycVKVLECxUBALKKAMuyLF8XAQAAAADA9WzUqFEaPHiwUWyzZs20ZMkShysCAAAAAAAA4EunTp1SZGSk4uPjXcYuW7ZMTZo08UJVAICsgomhAAAAAABIWrVqlZKSkryed8yYMbr//vuN459++mkHqwEAAAAAAADgD1544QWjptAGDRrQFAoA+BcaQwEAAAAA0KWpnZGRkXr77bd19uxZx/OlpKRo2LBhGjBggC5evGi0TZ06ddSuXTuHKwMAAAAAAADgS7/99ptGjRplFMuF5ACAq6ExFAAAAACA/3f8+HE9+eSTKlGihAYPHqzly5c7kmfmzJmqVauWPvjgA+NtAgIC9MknnzhSDwAAAAAAAAD/sGfPHnXv3l3p6ekuY2vUqKGOHTs6XxQAIMuhMRQAAAAAgH9ISEjQqFGj1KRJE5UvX16PPvqoYmJilJiYmOl97t27V++9956qVKmiTp06aceOHW5tP2jQIDVu3DjT+QEAAAAAAAD4r/T0dE2ZMkUNGjTQ0aNHjbZ59dVXFRAQ4HBlAICsKMCyLMvXRQAAAAAA4GsDBgzQmDFjMowJCgpSjRo1VKNGDVWuXFmlSpVS0aJFlS9fPoWGhiogIEDJycmKj4/XkSNHdODAAW3atElr1qzRzp07M11b7dq1tWzZMuXKlSvT+wAAAAAAAADgfYmJiTpw4MC//v3ixYs6d+6cDh8+rNWrV2vGjBnau3ev8X6joqK0dOlSO0sFAGQjQb4uAAAAAACArCItLU3r16/X+vXrvZazSJEi+v7772kKBQAAAAAAALKgVatWKTo62tZ95siRQx9//LGt+wQAZC8sJQ8AAAAAgJ+68cYbtWjRIpUpU8bXpQAAAAAAAADwE4899phq167t6zIAAH6MxlAAAAAAAPxQlSpVtGTJElWpUsXXpQAAAAAAAADwE/Xq1dOrr77q6zIAAH6OxlAAAAAAAPxM3759tXr1apUvX97XpQAAAAAAAADwE8WKFdPMmTMVEhLi61IAAH6OxlAAAAAAACRFRET4ugTVqFFDMTExGj9+vMLDw31dDgAAAAAAAAA/Ubp0aS1cuFAlSpTwdSkAgCyAxlAAAAAAACR98MEHWrt2rZ599llVqlTJq7mbNm2qr7/+WuvXr1fr1q29mhsAAAAAAACAf+vXr582btyoihUr+roUAEAWEWBZluXrIgAAAAAA8Dd//PGHFi9erN9//13Lly/Xnj17bNt3QECA6tevrzvvvFOdOnVStWrVbNs3AAAAAAAAAP+xaNEiRUdHu71dUFCQOnbsqIcffljNmjVzoDIAQHZGYygAAAAAAAZOnDihjRs3au/evdq3b5/27t2r/fv36+zZs0pISFBiYqISExOVnJys4OBghYWFKWfOnCpUqJBKlCihEiVKqHLlyqpXr57q1q2rPHny+PouAQAAAAAAAHCYq8bQwMBA5c2bV/nz51eRIkVUr149NWrUSG3atFHRokW9WCkAIDuhMRQAAAAAAAAAAAAAAAAAACCbCPR1AQAAAAAAAAAAAAAAAAAAALAHjaEAAAAAAAAAAAAAAAAAAADZBI2hAAAAAAAAAAAAAAAAAAAA2QSNoQAAAAAAAAAAAAAAAAAAANkEjaEAAAAAAAAAAAAAAAAAAADZBI2hAAAAAAAAAAAAAAAAAAAA2QSNoQAAAAAAAAAAAAAAAAAAANlEkK8LAAB/c+TIEf34449/+7eyZcsqPDzcRxUBAAAAAAAAAAAAAAAA8KWEhATt2bPnb/92xx13qFixYj6q6NpoDAWAf/jxxx81ePBgX5cBAAAAAAAAAAAAAAAAwI998cUXGjRokK/L+BeWkgcAAAAAAAAAAAAAAAAAAMgmaAwFAAAAAAAAAAAAAAAAAADIJmgMBQAAAAAAAAAAAAAAAAAAyCaCfF0AAPibsmXL/uvfnn32WZUvX94H1cBuqampOnPmzN/+LX/+/AoODvZRRQCyEo4hADKL4wcAT3AMAeAJjiEAMovjBwBPcAwB4AmOIQD81Z9//qmRI0f+7d+u1mfkD2gMBYB/CA8P/9e/lS9fXjVr1vRBNbBbSkqKTp48+bd/K1y4sEJDQ31UEYCshGMIgMzi+AHAExxDAHiCYwiAzOL4AcATHEMAeIJjCICs5Gp9Rv6ApeQBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAAAAAAAAAAAAAAAAALIJGkMBAAAAAAAAAAAAAAAAAACyCRpDAQAAAAAAAAAAAAAAAAAAsgkaQwEAAPB/7N15fFT1vT/+1zln1uwJCVlIQoCAkV1QQMUFFK29t2pb0Gprq63grfX3tVRRK1pivVoXqtVb9Sq9ltbWFsE2UqsiiKZSDMi+GSVAyCRkJZB11nPO748wIQnJzDlnJskk83o+HjxIZj4byYeZSeZ13h8iIiIiIiIiIiIiIiIiIiIaJkyDvQAiIiIiIiIiIjLG7ZLR0OCEyyXDZpOQmmqH1SYN9rKIiIiIiIiIiIiIiGgQMRhKRERERERERDSEKIqKgwcasXljJfbuaYAsq533SZKAadNTMX9BNiZNToEoCr2O4XUraGnwwetSYbYJiE81wWwNfrCM6vZCbWwG3B7AaoGQkgDBag7bv40ig9H9QURERERERERERESRgcFQIiIiIiIiIqIh4nh5M1575RAqHa293i/LKnbtrMeunfXIzonDkh9PxOi8BACAqqioPOjCgY9aULHXCUU+20+UgNxpdky+Kh7Zk2wQugRKVUWF8uVxyJ/uhXLgGKAoXTqKECePgXTZNIjnje7Wj4YWo/uj2xgMDhMRERERERERERFFBAZDiYiIiIiIiIiGgAP7T+LF5/bB7ZaDNwZQ6WjFE4/txL0/m4qR8fHYvKoBjQ5vr20VGSjf5UT5LidScsyYvzgVaXkWKI46eN/4AOqJht4nURQo+45A2XcEQlYqzLd9DWLOyG5NBK8TptY6iF4nFLMdvriRUM12Xf92Ms7tktHQ4ITLJcNmk5CaaofVJnVrU1/uMbQ/gPAEh7lHiIiIiIiIiIiIiMKLwVAiIiIiIiIiogh3vLxZVyjUz+2W8fqvD+M8UyZkj7Y+jQ4vip6owfXfciFx4wbA03tYsCf1RAM8z6+Becn1kM7Lgb1yFxIPrUdsxTYIXcpPqqKEttzZaJp4PZzZMwCBR5SHm6KoOHigEZs3VmLvngbIstp5nyQJmDY9FfMXZGPS5BRUHXLhgxfq4XOrAUY8y78/rrs3DVmJLcaDw6rCPUJERERERERERETUTxgMJSIiIiIiIiKKYIqi4rVXDukOhQJADKwYI6dDVoK37SrBewox734CCDrn9Hgh/eGPyJlyFNYWR69NBEVGXPlWxJVvhTtlDGrnPQBP6nh981Cfjpc347VXDqHS0drr/bKsYtfOeuzaWY8xGUnIak7THBr287lV7HnxAEbElkDw6g8O21M9SP/4GVgbj/XalnuEiIiIiIiIiIiIKDS83J6IiIiIiIiIKIIdPNDYZ8gvmHFSOiTd1RZVXGb/HGa9oVAAsXH1GJOzpc9QaE/WxmPIfmcp7JU7dc9F5zqw/ySeeGyn5v0SV5+gOxQKACniaVxh3qo5FNrJ44XlT79DdtFP+wyF9sQ9QoLXCfOp47DWlcJ86jgEr3Owl0RERERERERERBTxWDGUiIiIiIiIiCiCbd5YaahfohCDWMGqu1+WVIcUqVl3P5utCbm5uyBJ+gKlos+FzA0rUHnD86wKGYDL5UJ9fT2cTifsdjvi4uJgtZ79/h4vb8aLz+3TXFnW6P4IJThsszUhN2s7RJl7hIJQFdgrdyHx0HrEVmyDoJzdM6oooS13NpomXg9n9gxAd/idiIiIiIiIiIho+GMwlIiIiIiIiIgoQrldMvbuaTDUN11INNSvwHLEQC8V2dn7dIdC/USfC+kfPwPHwlcZ8upCURRs374da9aswdatWyF3CVRKkoS5c+di0aJFuPDCi/DaK4c0h0IB4/vDaHCYeyQyuV0yGhqccLlk2GwSUlPtsNqkQV2TpeEw0j9+ps+qsoIiI658K+LKt8KdMga18x5gYJiIiIiIiIiIiKgHBkOJiIiIiIiIiCJUQ4MTsqzq7idCQJIQq7ufCT7kmGp094uLa4DN3qK7X1fWxmOwV+2GM3tmSOMMF6WlpSgsLERZWVmv98uyjOLiYhQXF2N8/hWwiNdpHtvo/gCMBoe5R/qb0+lEdXU12tvbERMTg8zMTNjt9l7bKoqKgwcasXljJfbuaej2GCNJAqZNT8X8BdmYNDkFoij0OobXraClwQevS4XZJiA+1QSzNXBgV3V7oTY2A24PYLVASEmAYDV3a2Ov3InMDSsg+lya/t3WxmPIfmcpqq99jPuCiIiIiIiIiIioCwZDiYiIiIiIiIgilMtlrLqiFWaIQu+BrkBixXaIgv4gakpKhe4+vUk8uJ7hLgAlJSVYtmwZnE6npvau9lxY4rSPb3R/GA0OA9wj/cFfUXbt2rXYsmVLnxVlZ82aBVHsCG0eL2/Ga68cQqWjtdcxZVnFrp312LWzHtk5cVjy44kYnZcAAFAVFZUHXTjwUQsq9jrR5XR3iBKQO82OyVfFI3uSDcKZQKmqqFC+PA75071QDhwDFKVLJxHi5DGQLpsG8bzRsDaW6QqFdg7jcyFzwwpU3vA8K4cSERERERERERGdwWAoEREREREREVGEshk80lmE/tAfAJjh091HEHyIT6gzNF9PsRUlELxOqObeKx1Gg9LSUl2hUEEwIz62QNccRveH0eAw90j46akom5+fj8LCQvi8aXjxuX1wu7UFzisdrXjisZ2492dTMTI+HptXNaDR4e21rSID5bucKN/lREqOGfMXp2KEdBreNz6AeqKh9wkUBcq+I1D2HYGQNQK5eZ/oDoX6iT4X0j9+Bo6FrwJC4MqlRERERERERERE0YDBUCIiIiIiIiICoO2Y394IXidMrXUQvU4oZjt8cSOjPrQVLqmpdkiSoPs4eQX6w3sA4DXwqyKLxQnBQFiwN4Iiw9RaB2/y6LCMN9QoioLCwkLNoVAAsJiTIQj6AsRG94eR4DDAPRJueivKlpWV4Sd3P4q8nLvg6z3X2Se3W8brvz6M80yZkD3a+jQ6vNj25F5cFfMZBJ+2PRPbXApri0Pf4nqwNh6DvWo3K8oSERERERERERGBwVAiIiIiIiKiqKbnmF//0cBnOsJeuQuJh9YjtmIbhC5nCquihLbc2WiaeD2c2TNYvU0jp9OJ6upqtLe3IyYmBpmZmbDb7Zg2PRW7dtbrGssNLxRV1X1ceJsSA0UVdFWFFEVjx933OZ5XeyhyuNm+fXufFSD7IooW3fMY3R9GgsMA90g46a0o20FAavL1ukOhABADK8bI6ZCV4G39UsTTuMK8FYJP+/c9JaVC/+J6kXhwPYOhUYYXpxARERERERER9Y7BUCIiIiIiIqII5nbJaGhwwuWSYbNJSE21w2rwePGeFEedjmN+U2G+7WsQc0bC0nAY6R8/A2vjsV67CYqMuPKtiCvfCnfKGNTOewCe1PFhWfNwoygKtm/fjrVr12LLli2Q5bNBKkmSMHfuXMyZ9U3s2qlzXKg4rbYhRYjT1c8HExy+DIw2V2ufSwnPfuwcL4oDPWvXrtXdR1E0lnHs2sfg/jASHAa4R8LFSEVZAIiNyYfNmmloznFSOiRd4X4Vl9k/h1nQHgoVBB/iE+r0L64XsRUlELxOBgPDpD9fg4SEF6cQEREREREREQXFYCgRERERERFRhFEUFQcPNGLzxkrs3dPQ7RhxSRIwbXoq5i/IxqTJKRBFfRX//OQvjsO7aj3g0VZCTj3RAM/za5C4cBxGffEyRJ9LUz9r4zFkv7MU1dc+xipuPZSWlqKwsLDPCpGyLKO4uBjFxf/C+eOXQRRSdI1fqzYhBfqCfwBQ6hmnKxjq8dihqkJYjgpXRQm+uJEhjzMUOZ1ObNmyRXc/j/cUVFXWfZy8kf1hJDgMcI+Ei5GKsgCQkjTH0HyJQgxiBauuPllSHVKkZl19LBZnWPYG0HFhgqm1Dt7k0WEZLxoNxGuQUPDiFCIiIiIiIiIibRgMJSIiIiIiIoogx8ub8dorh1DpaO31fllWsWtnPXbtrEd2ThyW/HgiRuclnNPO61bQ0uCD16XCbBMQn2qC2dpRNUtx1OkKhfrZxAZk7X1X97HQos+FzA0rUHnD8wxnnFFSUqLjOGgVxyr+hDE5/6Xr2PAmtR1tqlt3sOuEPBKNcoLmcJeqmtDSPBIJibW65ulNW+6cqK30V11d3a1irFaq6kVLWykS4ibp6md0f+gNDgPcI+FipKKsIJgRH1tgaL50IVF3nwLLEd199D6nBB3Pq6+iarRwuVyor6+H0+mE3W5HXFwcrNbu//8H4jVIKOyVO5G5YQUvTiEiIiIiIiIi0oDBUCIiIiIiIqIIcWD/Sbz43D643dpCMpWOVjzx2E7c+7OpmDRlBFRFReVBFw581IKKvU50OVkVogTkTrNj8vw4jHz3A92hUEBFdvY+SAYDPKLPhfSPn4Fj4atRf6xraWmpjlBoB5f7BCpO/BG5Wd/XFQ51SPWYKGVD0fXtFvCp8yJ8PfYTzcdBNzbmhiX01zTp+pDHGKra29sN9208XaI7GAoAR+RaTJKydR0Vrjc47Mc9EhqjFWUt5mTd1WQBQISAJCFWVx8TfMgx1eieS1HCezS5EqXB4d4oioLt27djzZo12Lp1a7fwuSRJmDt3LhYtWoRZs2bh0MFT/f8a5Kp4ZE+yQTBQadTScFhXKLRzbl6cQkRERERERERRisFQIiIiIiIioghwvLxZVyDDz+2W8cJz+3DPkmn44l0XGh29JwAVGSjf5YRnbzmujW3Qvb64uAbY7C26+3VlbTwGe9XuqK7apSgKCgsLdYVC/dray3DM8b8Yk/t9iEJS0Pb+am5Sqxnvv1APn1v7Uc3N5mS0f+PrSPxQW4i4tTUVLmd8SHvEnTIGzlEXGO4/1MXExBju29ZeBpe7GjZrpq5+7XDjS+UEzhOzdIRDBWyVL8J/WIsh+Hya5+IeCY3RirJ6guRdWWGGKOgL78WK7RANHAnv8dihqkJYjpNXRQm+uJEhjzMclJaWorCwEGVlZb3eL8syiouLUVxcjPH5sxFr/Ra8Xn3fA72vQcp3OZGSY8b8xalIyzt3b6puL9TGZsDtAawWCCkJEKxmQFWQ/vEzukOhfrw4hYiIiIiIiIiiEYOhRERERERERINMUVS89soh3aFQP5vHik//twmiGjzsYOSYXwBISakw1K+nxIProzoYun379j5DOlq43Cdw9PjryM/7WcB2d9xZgMuvHAXxTFW2G5dnYOPL9WiqCR7k6xraUSYlwvv7d6HWnQ7SS0CV+3KMidsEUXZr/NecpZhsqJ33QFQHdjIzMyFJkqHwH6CiqmYt8nLugiTqOxq+WXXisHQCM5Jz0X5SCdo+JceMKxafD4srCd7X1uuoPiygsnYGxo4tgahwj+hltKKsongM9ROhv6KjGdqDwl2pqgktzSPDUlG2LXcOVFYMRUlJiY7K1AIU7xx4RWPBXD2vQQCg0eFF0RM1uO7eNGRPtkNVVChfHof86V4oB44BSpfHIVGEOHkM4ieZYG08Zmh9frw4hYiIiIiIiIiiTXT+JpWIiIiIiIgoghw80IhKR6uhvjGwYoKYqSmQYfSYX0HwIT6hzsjyzhFbUQLBq79a5nCxdu3aAZknf0JSZygUANLyLLj2ntSg/a64IwU3PZ7ZWclNzBkJ053fCNrPdMvVUJb9FNVf+yUUk03XWhWTDdXXPhb1R/za7XbMnTvXcH+X+wQcJ96ArDN0abVKWHJfAf5zafAqi133h1QwGpalN0MYmaRpHiErFcrdd6H6Ou4RI4xWlPV4T0FV9YeNFegPCXpDqEHQ2JhruG9XTZOuD8s4Q1lpaamOUCgQG5Ovu9qwn57XIF353Cref6EeJ7dVwfPUG/C+9Dco+450D4UCgKJA2XcEif9+09D6eko8uD4s4xARERERERERDQUMhhIRERERERENss0bKw33HSelaz4C2ugxvxaLMyxH/AKAoMgwtYYnZDrUOJ1ObNmyZdDmF8TgFQAzxlvPaSdoOE5aHJsFQRTgzJ6JyhuehydxlKY1uVPGoPKG51nB7YxFixaF1L+tvQzljleRmKSt2mN2ThyWr5iJSVNGGNofeoLDlodug5gzknvEIH9FWb1U1YuWtlLd/dzwQlH1Pe63KTFQVP2VRgGgtTUVLme8ob5+7pQxcI66IKQxhjpFUVBYWKg5FAoAKUlzDM+n5zVITyN9NbC+8TbUEw0B2/HiFCIiIiIiIiIiYxgMJSIiIiIiIhpEbpeMvXsChyL6kijEIFbQfmy00WN+RdHYEfd9jhcFoQyf4kN5aznkLpX6qqurDR4TPrR4UsejZsGKoO3qLl8Kx8JXo7oKZE+zZs1Cfn5+SGNk58TgvgcuDNrujjsL8PivZmN0XkJI8+kJDvtxj+gXSkXZxtMluvsoUHFabdPVxwcTHL4M3XN1EFBZORWyrD/8CnRUla2d9wBgMKQ4XGzfvh1lZWWa2wuCGfGxBYbm0vsapKsU8TTmx3wGk4bXJbw4hYiIiIiIiIjImOj+TRkRERERERHRIGtocEKWjQUe0oVEXe2NHvOrKMaCOn2OZ7aHdbxIU1Jfgms2XoOFnyzEgg8XoKS+I5TV3t4+yCsbQBrCWa70SVEf4upJFEUUFhbCbjf2f8Rut6OwsBCSKfj/2fwJSRA1VAntN9wjuhmtKNvWXgaXu1p3v1q1SXefUs843X38XK5EVByfqTscqphsqL72MQaIAaxdu1ZXe4s5GYJg7Dle72uQs1RcZv8cZkHbhRK8OIVCJXidMJ86DmtdKcynjrNqLBEREREREUUNY+8IEREREREREVFYuFzGAg8iBCQJsbr6+I/51XucvMdjh6oKYanYpYoSfHEjQx4nUtU6a7FsxzI45Y7QQbO3Gct2LMO6K9chJiZmkFdHkcKn+FDZXomc2BxIPUJZBQUFWLlyJe6//35dx0Hb7XasXLkSBQUFqKxsDfeSKQL4K8rqqQjZQUVVzVrk5dwFSdRe4bFJbUeb6tZVFfKEPBKNcgJSpGada+zQ1paK8pavISd3DyzNVUHbu1PGoHbeAwyFAnA6ndiyZYuuPqJoMTSXkdcgfllSna79wYtTyBBVgb1yFxIPrUdsxTYIytnX26oooS13NpomXg9n9gxegEBERERERETDFn/iJSIiIiIiIhpENpuxwIMVZogajnDuyugxv6pqQktzeMKcbblzoA7jUMbqstWdoVA/p+zE6rLVyMzMhCSFN+BCQ09fFWW7mj17NlatWoXc3FxNY+bn52PVqlWYPXt2uJdLESSUirIu9wnUNayB2azvecMh1UM06+kh4FPnRfCqBh/rLGbIt34XNdesCNq07vKlcCx8laHQM6qrqyHL+i42URSPobmMvAbxK7Ac0dXef3FKOAz3i1OGCq9bQWOVB7VH3Gis8sDrVsI6vqXhMHLW3YVR7z2EuPKt3UKhACAoMuLKt2LUew8hZ91dsDQcDuv8RERERERERJGCwVAiIiIiIiKiQZSaaock6Q88iDAWkjB6zG9jo7aAWjBNk64PyziRqNZZiyJHUa/3FTmK0IxmzJ07d2AXRRHFX1G22dtRLc9fUbbWWXtO24KCAjz99NNBx1y+fDnefPNNFBQUhH29FHn8FWX1hkPtdjsef+InePSxi5Ceoa16cXZOHH5WOAX/sXQkTFbtzzmNShI+8V4C1aTzsCqLGeYl10PMGampgp8rfRIr/XXR3t6uu4/Hewqqqr9yudHXICb4kGOq0dWHF6dENrdLRlVlK46UNaGqshXuPirhq4oKx34n3v9NHV7/LwfW/Lwaf3usBmt+Xo3X/8uB939TB8d+J1QltOr09sqdyH5nKayNxzS1tzYeQ/Y7S2Gv3BnSvERERERERESRiEfJExEREREREQ0iq03CtOmp2LWzXlc/BcbeODd6zG9raypcznjY7C2G5gU6jvx1jrrAcP9It7psNbyKt9f7vIoXq8tWY9GiRSguLh7glVGkCFRR9sEpD57TXhSDh96mTp2qqR0NH/6Ksg8//DAqKiqCts/Pz0dhYWFnePien07Bow9tC9jnjjsLcPmVoyCKHQHAG5dnYOPL9Wiq8QWdLyXHjDmLp8EqjYb39+9CrTsdtI+QlQrzbV/rCIWSITEx2gK/XamqFy1tpUiIm6Srn9HXILFiO0RBf9/GxlwkJJ4boNdrOF+cMpAURcXBA43YvLESe/c0QJbPfk8lScC06amYvyAbkyanQBQF1Jd7sHlVAxodvb9GUmSgfJcT5bucSMkxY/7iVKTlWXSvy9JwGJkbVkD0uXT1E30uZG5YgcobnmcFYiIiIiIiIhpW+FtjIiIiIiIiokE2f0G27j5ueKGoRoIZRo/5FVBZORWyYux4YMVkQ+28B4ZtdbdA1UL9ihxFGD1lNPLz80OaS+vx4hRZglWU7a1qKFFfQqko6w97BpI/Ialbu7Q8C669JzVovyvuSMFNj2ciLc8CMWckTHd+I2gf0y1Xw/LQbQyFhigzMxOSpP85uvF0ie4+Rl+DmBE8WNwb/8UpoRjuF6eEyul04ujRozhw4ACOHj0Kp9PZa7vj5c149OfbsPKp3di1s75bKBQAZFnFrp31WPnUbjz6823Ysekkip6o6TMU2lOjw4uiJ2pQeaD3+fukKkj/+BndoVA/0edC+sfPAGp4j7UnIiIiIiIiGkzD890YIiIiIiIioiFk0uQUZOfE6eqjQMVptc3QfI1KEj5qv1h3ONSlpOLE9J9CMdl09VNMNlRf+9iwrsIUqFqon1fx4o9H/4jCwkLdx0D72e123H33Twz1pcGlpaIskR4DXVFW0BAozRhv7dZOEIL3EcdmaRqbArPb7Zg7d67ufm3tZXC5q3X1MfoaxGv4ALMzF6fIvDglnBRFQUlJCe677z5ceeWVuOmmm3D77bfjpptuwpVXXon77rsPJSUlUJSOsOSB/SfxxGM7Uelo1TR+o8OLkj82w+fWFyL2uVW8/0I96ss9mvvYK3dpPj6+L9bGY7BX7Q5pDCIiIiIiIqJIwt+EEBEREREREQ0yURSw5McTYbXqCzzUqk2G56yW0/Fe25VokrUFUoWsVFiW3gz3xdd1HLWZOEpTP3fKGFTe8Dyc2TMNrzXSaakW6lfkKELy6GSsXLlSdzjUbrdj5cqVGDN2jIFV0mDSWlGWVUOJKBSLFi0y0EtFVc1ayIpbVy8jr0HalBgoqrEQsMuViIrjM3WHQ6Ph4hQjSktLceutt+Kee+5BcXExZFnudr8syyguLsY999yDW2+9FZ98vA8vPrcPbrfcx4jnGielQzL4FpTPrWLzqgaoirZQaeKh9YbmOWecg+EZh4iIiIiIiCgSMBhKFMWqqqqwdu1aPPbYY/jud7+Lr3/967jssstwySWX4Nprr8WiRYvwwAMPYPXq1Thw4MBgL5eIiIiIaFgbnZeAe382VVc4tElthxP6ghxdNSpJ2JkQvLpYz2N+PanjUbNgRdB+dZcvhWPhq8M+jKGlWqifvzLk7NmzsWrVKs3Hwufn52PVqlWYPXt2KEulQaK1oiyrhhJRKGbNmoX8/Hzd/VzuE3CceENXONTIaxAfTHD4MvQur1NbWyqOHZ0DtztGU/touDjFiJKSEixevBhlZWWa2peVHcH/vrRfVyg0UYhBrGA1ukQAHRVHKw8FPxpe8DoRW7EtpLn8YitKIHh1HmNPREREREREFKGMnt1CRENUfX09XnvtNaxbtw579uzR1TcnJwfXX3897r77bkycOLF/FkhEREREFMUmTRmB5Stm4qUXD6C2pj1o++ycOFx9Yyq2vd6q+5hOADBZBcxelAysDtyu12N+NRzH6kqfNOyPbdVTLdSvyFGE2/NvR0FBAZ5++mnccsstAdsvX74cN9xwQ9iOg6aBpbei7O35tyPdnt6/iyKiYUkURRQWFmLx4sVwOvWF29ray1BdtxpTJv4Epxp9QdsbfQ1S6hmH0WZ9R9d31VE5dAbGT9gSsF3d5UvRXHDdsH8doldpaSmWLVuma3/ExuTDatH3vJQuJOpdWq8OftSCnMmBK6ybWusgKNpDq4EIigxTax28yaPDMh4RERERERHRYOJvRWhIcDqd2Lp1K1588UV8//vfx/nnnw9JkiAIQsA/dFZjYyN+8pOfIDc3F4888ojuUCgAOBwOvPTSS5g0aRKuu+46HDx4MPwLJSIiIiKKcqPzEnDPT6cEbXfHnQV4/FezMfXiFFx3bxpMVn0/A5msAq67Nw3Jo8xGl0rQVy3Ur2tlSC1hz6lTpzIUOoQZqShL5FN8KG8th6yGJ+xE0aOgoAArV66E3R44TNeT3W7Hk7+6Hz97IHh1zVBeg5yQR+KUElpoUBiZErRNNFycopeiKCgsLNQdGk5JmqOrvQgBSUKsrj59Ob7HCa9bCTxfmCt8hns8IiIiIiIiosHC34xQxPF4PNixYwdeeeUV/OhHP8K0adOQkJCASy+9FPfeey/eeOMNlJaWQlEC/0KIznrzzTdx3nnn4eWXX4bLFfz4HS0++OADXHDBBfj5z38Ony94FQEiIiIiItJO7Fmdsxf5E5I622VPtuPG5RlIzNB2MEhKjhk3Ls9AdpAKTBSYkWqhfkWOItQ6a8O7IIo4RivKcm9Et5L6Elyz8Ros/GQhFny4ACX1JYO9JBpiZs+ejVWrViE3N1dT+/z8fKxatQqzZ88egNcgFlh+8DXAYvDCFIsZpm/MNdY3ym3fvl3z8fF+gmBGfGyBrj5WmCGGqWiDIgOtDYED8oo5vK9nwz3ecOByueBwOPDVV1/B4XDoDhcTERERERHR4OBR8jSofD4fDh48iB07duDzzz/Hjh07sH//fng8nsFe2rAgyzLuu+8+vPDCC/0yvtfrxVNPPYWSkhKsXbsWqamp/TIPEREREREFl5ZnwbX3pOKtR2oCtrvijhScf0XcuUfDk25GqoX6+StDLoxZGOZVUSQJpaLsg1Me7KdVUSSrddZi2Y5lcModoZtmbzOW7ViGdVeuQ7pd31HOFN0KCgrw9NNP45ZbbgnYbvny5bjhhhtCqkxt5DWInHg9vK+tBzw6HiMtZpiXXA9xpPaj6+mstWvX6u5jMSdDECRdfUSE9zWmxxW4QIQvbiRUUQrLcfKqKMEXNzLkcYYDRVGwfft2rFmzBlu3boUsn/36SpKEuXPnYtGiRZg1axYr2xMREREREUUoBkNp0Gzfvh1XXnklry7tJ7Is46abbsLf/va3fp/rk08+wSWXXIJPP/0U6el8k4KIiIiIaLBoCXtmjLcyFBoGoVQL9StyFGFe3rzwLIgiTqgVZW/Pvz2s66GhYXXZ6s5QqJ9TdjIsTIZoCWtNnTo1LKEuva9BpILREJbeDO/v34Vadzr4+FmpMN/2NYg5I4HG8hBXG32cTie2bNmiu58oWnT3URDe4K7FFnh/qmY72nJnI658a8hzteXOgcqKoSgtLUVhYWGfFWZlWUZxcTGKi4uRn5+PwsJCFBToqywbKQSvE6bWOoheJxSzvSNozD1ARERERETDBIOhNGja29sZCu0nqqri9ttvH5BQqN/hw4exYMECfPLJJ0hJSRmweYmIiIiIiAZDKNVC/byKF0UVReFZEEUcVpQlvQKFif1hYVYNpeFEzBkJ053fgPfJNwK2M91yNaSLp/DClhBUV1d3q/iolaLoP9nLDS8UVQ3LcfKiBMSlBq9Y2jTx+rAEQ5smXR/yGENdSUkJli1bpvm9m7KyMixevBgrV67E7Nmzu93ndsloaHDC5ZJhs0lITbXDatNXgbZfqArslbuQeGg9Yiu2das2q4oS2nJno2ni9XBmzwAEVkMlIiIiIqKhi8FQomHomWeewZ/+9CdNbVNSUvCd73wH11xzDaZPn460tDRIkoTGxkYcOnQI//rXv/CnP/0JR48eDTrW/v37cdttt+Hdd9+FEIZf/BERERFRZGAVFaLuPLIH6x3rwzLWxzUfh2UciiysKEtGBAoT+8PCrBpKw42W3yGKY7MYCg1Re3u7oX4e7ymoqqzrOHkFKk6rbUgR4gzN2dXo6XaYrR3BPNXthdrYDLg9gNUCISUBgtUMAHBmz4A7ZQysjccMz+VOGQPnqAtCXvNQVlpaqisU6ud0OnH//fdj1apVmDDhPBw80IjNGyuxd08DZPlsBVlJEjBteirmL8jGpMkpEMP4/zrQ/ujK0nAY6R8/0+deERQZceVbEVe+Fe6UMaid9wA8qePDtk4iIiIiIqKBxGAo0TDz2Wef4ZFHHgnazmw246GHHsKDDz6I2NjYc+7PzMxEZmYmrrrqKqxYsQJ/+MMf8OCDD6K+vj7guO+99x5WrlyJZcuWGf43EBEREVH/0fqGGauoBOdTfKhsr0RObA4kHW+W09BX1V4Ft+IOy1ihVh2lyMSKsqSXljAxq4YSkVExMTGG+qmqFy1tpUiIm6SrX63ahBSEHgydND8O8hflkD/dC+XAMUBRzt4pihAnj4F02TSI541G7bwHkP3OUog+l+55FJMNtfMeiNqfawBAURQUFhYaPuXN6XTiscL/wdjR30Olo63XNrKsYtfOeuzaWY/snDgs+fFEjM5LOKed162gpcEHr0uF2SYgPtXUGRDuSlVUKF8e17Q/BFGAvXInMjes0LxHrI3HkP3OUlRf+xic2TO1fSGIiIiIiIgiCIOhRMOI1+vFj370I/h8voDtUlNTUVRUhEsvvVTTuKIo4o477sDVV1+NG264Abt37w7Y/tFHH8W3v/1tjB07VvPaiYiIiKj/6H3DjFVUgiupL8HDux5Gs7cZCeYEPDnjScxJmzPYy6IBkhObg0RzIpq8TSGPFW+ORwtawrAqihSsKEtGaAkTs2ooERmVmZkJSZIMHSffeLpEdzC0SW1Hm+pGrGDVPZ/fmKxWjPxHMbwnGnpvoChQ9h2Bsu8IhKxUqLd9DdXXPqYr+Ad0hEKrr30s6n6e6Wn79u0oKysz3D82Jh8Svt5nKLSnSkcrnnhsJ+792VRMmjICqqKi8qALBz5qQcVeJ7pclwhRAnKn2TH5qnhkT7JBEAUojjp43/gAqsb9EXd9ATK3/VJ3cFj0uZC5YQUqb3g+6vdIuLldMhoanHC5ZNhsElJT7bDaIuuCS56eQkRERERDHYOhNGTk5OTgwgsv7Pzz2muv4e233x7sZUWU//mf/8EXX3wRsE1SUhI2btyI6dOn6x4/JycHmzZtwpVXXon9+/f32c7tdmPp0qV45513dM9BREREROGl9w2zxK+NQtbu51lFJYBaZy2W7VgGp9xRTafZ24xlO5Zh3ZXrWMUtSphEE5698Fks27EspHBoojkRSycuRSEKw7c4GnSsKEt6aakW6seqoURkhN1ux9y5c1FcXKy7b1t7GVzuatismbr6HZFrMUnKhmSgCmeOrQ5XuEugntD2PKieaIDn+TVQl1yPyhueR8am/4alqSpov2i9yK03a9euNdzXZs1CTtZtkER9QWC3W8YLz+3DPUum4Yt3XWh09P79VmSgfJcT5bucSMkxY8GCdsSsfx/waN0f9UjfXATRqr+aLNARDk3/+Bk4Fr4a1VVlw0FRVBw80IjNGyuxd08DZFntvE+SBEybnor5C7IxaXIKRFEI69w8PYWIiIiIohGDoRSRMjMzu4VAL7roIqSlpXVr8+abbw7S6iJTS0sLHn/88aDtfv/73xsKhfqlpKTg73//O2bMmIHm5uY+261fvx5btmzB3LlzDc9FRERERKGRvzgO76r1mt8wszYeQea2P0MU9VUSirYqKqvLVneGQv2cspNV3KLMjBEzsGHBBhxtPQqX7EJVWxUe3fNowD6PT38co2JHAQBskg1j48bi+LHjA7FcGkCsKEt6aakW6seqoURk1KJFiwwFQwEVVTVrkZdzl67gXzvc+FI5gfOkLEjQHp5Ks53GVTGfQfAGPhXrHB4vvK+th7D0ZtQsWIHcdUsCNq+7fCmaC65jsAsdx8Bv2bLFYG8BozIW6Q6F+tk8Vnz6v00QVY3fh6p6mNd+Agjaf2aNi2uAzdr3exlaWBuPwV61O2ouhtTL6XSiuroa7e3tiImJQWZmJuz27pU1j5c347VXDqHS0drrGLKsYtfOeuzaWY/snDgs+fFEjM5LCGldPD2FiIiIiKIdg6E06NLT0zFz5kxceOGFmDlzJi666CJkZuq7+piAV199FadPnw7Y5rbbbsONN94Y8lzjxo3Ds88+i7vuuitgu6effprBUCIiIqJBojjqdIVCARXZ2fsg6QyF+kVLFZVAVd2CVXFzuVyor6+H0+mE3W5HXFwcrFbjx2vS4DOJJkxImAAAGGkbiasyrwrY/oIRFyDDnjEQS6NBxIqypIeeaqF+/ucbIiI9Zs2ahfz8fEPHhbvcJ+A48QZGj/oBBKGXCnt9cFs8uOi7sTjyoRdNNcGDninZJlxn2QOhQWco1M/jhfeND2BdclnQpq70ScP65xY9qqurIcvGfg6MjcnXXU3WLwZWTBAztYdCoeIy++cw6wiFAkBKSoX+xfUi8eB6BkO7UBQF27dvx9q1a7Fly5Zue0iSJMydOxeLFi3CrFmzcOjgKbz43D643dq+d5WOVjzx2E7c+7OpmDRlhLH18fQUIiIiIiIGQ2nwXHDBBaioqEBOTs5gL2XI8/l8eOGFFwK2iYmJwVNPPRW2Oe+880689NJL2LdvX59t/vnPf+KLL77A+eefH7Z5iYiIiKiD162gpcEHr0uF2SYgPtUEs7XjDTVVUeF94wMdodAzVVTsoVWli4YqKoGquvVWxc3/ZtmaNWuwdevWgG+WiSLfmB7KMuwZeHrm04O9DIoQPSvK6sWKstFDT7VQP//zzcKYhf20KiIajkRRRGFhIRYvXgyn0xm8Qw+KWoUfLhmF9/7Ritqa9qDtu1b8y5/gxluP1ARsf8UdKThv5El4Xzmpe21dqScaoJRXhzRGtGlvD/797EtK0hzDfcdJ6ZB0hHOzpDqkSPoqfwqCD/EJdXqX1qvYihIIXidUsz1442GutLQUhYWFfQbNZVlGcXExiouLMT5/NmKt34LXq/bati9ut4wXntuH5Stm6q4cytNTiIiIiIg6MBhKgyYxMRGJiYmDvYxh4cMPP0RlZWXANnfccQeysrLCNqcoinjooYdw66239tlGVVWsXr0aTz/NN0eJiIiIwkFVVFQedOHARy2o2OuE0uU9C1ECcqfZMfmqeGSJtX1XxegDq6gEp6WqW9eqoXreLMvPz0dhYSEKCgr6YeVENBi6VpQl6o2RaqF+RY4izMubF94F0ZDhU3yobK9ETmwOJEEa7OXQEFJQUICVK1fi/vvv1xUOtdvtWLlyJWbPnoqx41rw6EPbAra/484CXH7lKIiiAAAQzvwdSMZ4K+T39mpeUyDKztKwjBMtYmJiDPUTBDPiY439/JIoxCBW0Hd6QoHliO55LBYnBEFfILEvgiLD1FoHb/LosIw3VJWUlGDZsmUaH0MEKN458IrGvgdut4zXXjmEx381u/PxJBienkJEREREdBZfoRINA3/+85+Dtrn33nvDPu+iRYswatSogG3+8pe/QFXD84sXIiIiomhWX+7BW49W491n61C+q3soFAAUGSjf5cS7z9ahYlXgN2p76o8qKsORlqpu/ipuJSUlWLx4seajOsvKyrB48WJs26bve0dEREOXkWqhfl7Fi6KKovAuiIaEkvoSXLPxGiz8ZCEWfLgAJfUlg70kGmJmz56NVatWITc3V1P7/Px8rFq1CrNnzwYATeGs/AlJmkNcnTxeKAeO6evTB6WsKizjRIvMzExIkv6QucWcDMFgOD1d0Fc0xAQfckyBq872Rm8FyKDjDdOfdbUqLS3VEQoFYmPyYbNmhjRnpaMVhw42amo72KenUPQRvE6YTx2Hta4U5lPHh+3vw4iIiGjoYjCUaIhzuVx45513AraZPXs2xo8P/zEWJpMJ3/nOdwK2cTgc2LJlS9jnJiIiIoomjgNOFD1Rg0ZH8Dc3TPAh3XtC1/j9UUVluNFT1e3v2/+O+5fpq8IEAE6nE/fffz9KS1nhiIhouAulWqjf5prN4VkMDRm1zlos27EMzd6Oo5Sbvc1YtmMZap21g7wyGmoKCgo0nfK0fPlyvPnmmwNS1V5obgEUJTyDhWucKGG32zF37lzd/UTRYmg+EQKShFhdfWLFdogGfmZVlPBWVVai+Bh5RVFQWFio6+fclKQ5YZn7o42BT8zzU748Pqinp1CUUBXYHTuQseEXGLv6Rox+60fI+fs9GP3WjzB29Y3I2PAL2B07AJXPRURERDT4GAwlGuI+/fRTtLW1BWxz00039dv8N998c9A2GzZs6Lf5iYiIiIa7+nIPPnihHj63tjfBjLxhxioqwWmu6qYAvrd9cDldhuZxOp0oLCyEyjeziYiGtVCqhfr5FF+YVkNDxeqy1XDK3V9nOWUnVpetHpwFUUTyKT6Ut5ZDVgO/xhfF4G8PTZ06VVO7cBB0VPij8Fu0aJHuPoriMTSXFWaIgr6KsmYYe87zeOxQVZ3Va/ugihJ8cSPDMtZQtH37ds0nYgCAIJgRHxueUPne3Q1wu4L/3kL+dK+ucXl6CullaTiMnHV3YdR7DyGufCuEHsf5CIqMuPKtGPXeQ8hZdxcsDYcHaaVEREREHRgMJRriNm3aFLTNtdde22/zz5w5EyNGjAjYRssaiYiIiOhcqqJi86oGzaFQwNgbZqyiEpiuqm5HAYT4vlJZWRn2798f2iBERBSxPLIH6x2sKkX6BHo9UuQoYtVQAgCU1Jfgmo3XYOEnC7HgwwUoqS8Z7CVpplrMg72EqDZr1izk5+fr6uPxnoIaJIDcGxH6g5pemHT3AQBVNaGlOTxhzrbcOVCH2c+6eqxdu1ZXe4s5GYIQnt81yLKKkycDX3ypur1QDhzTNS5PTyE97JU7kf3OUlgbte0za+MxZL+zFPbKnf28MopUgtcJ86njsNaVwnzqOMPjREQ0KBgMJRriNm8OfGxYRkYGJk2a1G/zi6KIefPmBWyzY8cONDc399saiIiIiIaryoMuTcfHd2XkDTNWUQlMV1W3z8Mz54cfbgzPQEREFHGq2qvgVtyDvQwaYgK9HvEqXlYNJdQ6a7FsxzI0ezt+D9vsbcayHcuGTGhYTYgHwlWddICqnA4noiiisLAQdrv24KOqetHSVqp7LgX6g3htSgwUgz+zNjbmGurXU9Ok68MyzlDkdDqxZcsWXX1E0RLmNQS+CFZtbAZ0nrzB01MGhsvlgsPhwFdffQWHwwGnc+h9nSwNh5G5YQVEn77TYUSfC5kbVrByaDRRFdgdO5Cx4RcYu/pGjH7rR8j5+z0Y/daPMHb1jcjY8AvYHTsAlScF9Te3S0ZVZSuOlDWhqrJVU+VpIqLhyNgldkQUEbxeL/bt2xewzezZs/t9HXPmzMG6dev6vF+WZezZsweXX355v6+FiIiIaDg58FGL7j7+N8z0HCfvr6KSkBj6m8bDrYqKrmqhHgBh+l3/zp07MTZ3bngGIyKiiJITm4NEcyKavE2DvRQaIrS8HilyFOH2/NuRbk8fmEVRxFldthpOuXvYxik7sbpsNR6c8uAgrUoHixni5DFQ9h0JeSgxf1QYFhR9CgoKsHLlStx///2ag1uNp0uQEKevMIUbXiiqqus4eR9McPgyMNpcrWsuAGhtTYXLGQ+bXf/P137ulDFwjrrAcP+hrrq6GrKsL1CjKJ6wrsFuD/KWtlv/fDw9pf8oioLt27djzZo12Lp1a7f9I0kS5s6di0WLFmHWrFkQIz3MrypI//gZ3aFQP9HnQvrHz8Cx8FVAiPB/K4XE0nAY6R8/02dVWUGREVe+FXHlW+FOGYPaeQ/Akzp+gFc5vCmKioMHGrF5YyX27mmALJ/9/bgkCZg2PRXzF2Rj0uQUiGJ4iiQQEUU6vvogGsIOHjwIjyfwD7szZszo93XMnDkzaJvdu3f3+zqIiIiIhhOvW0HFXv1VFPxvmOnFKiq901Ut9DSAMF3wryi8ip2IaLgyiSY8e+GzSDQnhjROnCkuTCuiSKfl9Qirhka3QOHhIkfRkKkaKl02LSzjiDMLwjJONJo9ezZWrVqF3FxtPx9mZqlIG2nWNYcCFafVNt1rK/WM092ng4DKyqmQZWMhQMVkQ+28B6I60NXe3q67j8d7Cqoanp9rJUnAiBG2wI2s+iuU8vSU/lFaWopbb70V99xzDz799NNzQsWyLKO4uBj33HMPbr31VpSW6q88PJDslbs0Hx/fF2vjMdir+D7pcGav3Insd5Zq3ivWxmPIfmcp7JU7+3ll0eN4eTMe/fk2rHxqN3btrO8WCgUAWVaxa2c9Vj61G4/+fBuOl/O0UyKKDqwYSjSEaQlbTp06td/XoWUOBkOJiIiI9Glp8MFoNrDUM053JRVWUTmXrmqhQEfFUCIiIg1mjJiBDQs24GjrUbhkF7yyF3WuuoB9RtpGwix1hG9skg2oBW598daBWC4NIj2vR1g1NHoFCg/7Q8NDoWqoeN5oCFmpUE80GB5DyEqFmJcJMGdhWEFBAZ5++mnccsstAdstX74cN9xwAxwVrXjisZ1wu7X/AFurNiEF+i5wOCGPRKOcgBRJf5DD5UpExfGZyB2zC5IQ+EjyrhSTDdXXPhb1Fd1iYmJ091FVL1raSnVXlO3NtAtSYbUFDvYKKQmAKOo6Tp6np4RfSUkJli1bprnqcFlZGRYvXoyVK1cOyAmIRiQeWh+ecQ6uhzM7eKEd0sbtktHQ4ITLJcNmk5Caag/6ONFfLA2Hkblhhe6qsqLPhcwNK1B5w/NR/zwTqgP7T+LF5/Zpfi1S6eh47XLvz6Zi0pQR/bw6IqLBxWAo0RD21VdfBW2Tn5/f7+tISUlBcnIyTp061WcbLWslIiIiorO8Lu1Hwfdk7A2zjioqY8aWQJL0J1KHYxUVXdVCAUB/gRIiIopiJtGECQkTDPc/Uh/6ccsU+fS8HhlKAUAKHy3h4aESGhZEAebbvgbP82sAj47X4X4WM8y3fQ2CqL+6IXWn5WjnqVOnQhRFjM5LwL0/m4oXdAQymtR2OOGGHVYdqxLwqfMifD32E5gF/T+ztnkzUTn3l8g88BIsTVVB2/OY37MyMzMhSZLu4+QbT5eEJRh61YLsoG0Eqxni5DFQ9ul7fdTYmBuWYOhwOz3FiNLSUl2hUD+n04n7778fq1atQkHB2YrPkRD8E7xOxFZsC8tYsRUlELxOBohDEJHHhKsK0j9+Rnco1E/0uZD+8TNwLHx1WP1OdSAdL2/WFQr1c7tlvPDcPixfMROj8xL6aXUUqSLhOYZooDAYSjSEHTsWuBy9IAgYN87o8Sr65Ofn4/PPP+/z/mBrJSIiIqLuzLZQfoFp7A2zzioqeTshidr7DccqKh7Zg/UOnVUhkgCICMtx8qLIX0QRERFFO93VyzF0AoAUPlrCw0MpNCzmjIR5yfXwvrZeXzjUYoZ5yfUQc0YCjeX9tj7q3aQpI7B8xUy89OIB1NYED+Zm58Th6htTse31Vvjc2i+KbFSS8FH7xbgq5jN94dAz+8NbMBo1manIXbckYPO6y5eiueA6hnTOsNvtmDt3LoqLi3X1a2svg8tdDZs10/Dc2TlxmDgppfNzr1tBS4MPXpcKs01AfKoJZmvH90m6bJruYChPTwkPRVFQWFioOxTq53Q6UVhYiD/96c/44tDpiAn+mVrrIBg9zqcHQZFhaq2DN3l0WMaLNsfLm/HaK4dQ6Wjt9X7/MeG7dtYjOycOS348cUDCfvbKXZqPj++LtfEY7FW7WVHWAEVR8dorh3SHQv3cbhmvvXIIj/9q9sCFiWnQRGS4nGgAMBhKNIQFC1uOGDECdvvAXHmWnZ0dMBhaU1MDp9M5YOshIiIiGuriU00QJRg+Tt7oG2Zt3kw4LlyOrCP/F9VVVKraq+BW3Po6WQCMB/Bl6PPPnDkTp+pDH4eIIkOrtxUl9SUB28xJm4M4s74jVYloeNNdvRxDKwBIodMTHh5KoWGpYDSEpTfD+/t3odadDtpeyEqF+bavdYRCadCMzkvAPT+dgkcfClxd7447C3D5laMgigJS4u14/4V6XeHQelMGWhd9Eyn/2mRsf2gIe7rSJzEU2sOiRYt0B0MBFVU1a5GXcxckUU912A5Wq4QlP54IAYBjvxMHPmpBxV5nt9+TiBKQO82OyVfFY9T5uRCyUqGeaNAxC09PCYft27ejrKwspDEqHe1YtrQYjSd7v9pWS/AvUHDYCNFrLOg6UONFi0g+JjzxkM6Lyvsa5+B6BkMNOHigsc+wsFaVjlYcOtiIyTxSfliL1HA50UBgMJRoCHM4HAHvz8jIGKCVaJvL4XBgwgTjR6QRERERRROzVUTuNDvKdxn/pXG1nI732q7EguTtiPEGr37hf8PMlzMSNWOzo7qKSk5sDhLNiWjyNunreBHCEgy95poFWPNnvmEwlNS76vH64dcDtvnh+B8izZY2QCuiSFLrqsVDux4K2GbNFWsYDCWiTkaqhfr5A4A0/OkJDw+10LCYMxKmO78B75NvBGxnuuVqSBdPgcCqPhFBS3Wl/AlJne2yJ9tx4/IMbHy5Hk01vqB9U3LMmL84FWl5FsgTuD8G0qxZs5Cfn687/Odyn4DjxBvIybpNVzjUapVw78+mIgY2vPVoNRodvT/WKTJQvsuJ8l1OpOSYcfX1VyF2zd90VRzm6SmhW7t2bUj9Y2PykZN1W5+h0J66Bv8mTkpB5UFX0OBw9iSb7scCJczHvod7vGgQyceEC14nYisCXwyhVWxFCQSvEyr3iC6bN1aGZZyPNlYyGDqMRXK4nGggDL9374iiyMmTJwPeP5DB0MzM4EeBBFsvEREREXU3+ar4kMdoVJLguvG6oO1Mt1wNy0O3sYrKGSbRhGcvfBaJ5kR9HccCCLFQUX5+PqZMmRLaIDTgmr3NWHt8bcA/zd7mwV4mERENEUaqhfr5A4A0vBkJDxc5ilDrrO2fBfUDQQge4BHHZjH0N8Sl5Vlw7T2pQdtdcUcKbno8E2l5FgDcHwNNFEUUFhYaOhWurb0M1XWrkZyirV5Rdk4clq+YiQQhBkVP1PQZCu2p0eHF334no+marwEWs741njk9xZM4SlN7d8oYVN7wPCv8oeMY+C1bthjub7Nm6Q4OA2eOgP51Kf78YBXefbYO5buc55y64w8Ov/tsHd56tBr15R5dc/jiRkIVJV19+qKKEnxxrGzdG6fTiaNHj+LAgQM4evQonM6OC6XDdUy4omivSq2HqbUOgtGjnnoQFBmm1rqwjBUt3C4Ze/foqRDdt727G+B2hed7qZXgdcJ86jisdaUwnzoOgRWF+0Wo4fLj5fxdLg19rBhKNES1trbC4wn8A0xSUtLALEbjXI2Njf2/ECIiIqJhJHuSDSk5Zs1vgvQmJceM9Hwzgo3AN8zONWPEDGxYsAFHW4/CJbtQ1VaFR/c8GrDP4zMeh+8xH55a+hTcLp1H0QOw2+0oLCyEIA7PwC0REREFF0q1UL8iRxHm5c0Lz4IoIhkJDw+1qqHUP3yKD5XtlciJzYEkhCfwFCotP4tmjLfyZ9ZBVlBQgJUrV+L+++/vDG5pYbfb8eSv7kdm5kQ8+lDg6np33FmAy68chZMVXhS9UAOfW1+gy+dWsf5tK75157cQt2ED1LrTQfvw9JTQVFdXQ5aNBqoEjMpYpDsUCgCJQgzGy5loqdU2d6PDi6InanDdvWnInqwt4Kya7WjLnY248q2619dTW+4cVoPsQlEUbN++HWvXrsWWLVu67SFJkjB37lzMmfVNVDpcIc3Tn8eEi2EO8oV7vOGuocEJWQ5P6FeWVZw86ULWqNiwjNcnVYG9chcSD61HbMW2bsFiVZTQljsbTROvhzN7Bp9jwiBc4fLHfzVbU1V8okjFRxOiIUpLyDI+PvQKU1ppmYvBUCIiIiJ9BFHA/MWpMFmN/eLBZO3ozzfPjDOJJkxImICpyVMxIXFC0PYTEifgGxd9A8/9+jndlVTsdjtWrlyJgoICo8slIiKiYSCUaqF+XsWLooqi8CyIIk4o4eGhVjWUwqukvgTXbLwGCz9ZiAUfLkBJfclgL4mGmNmzZ2PVqlXIzc3V1D4/Px+rVq3C7NnaQhX5E5IgANi8qkF3KNTP51axab0A6Yf/GbQtT08JXXt7u+G+sTH5sFmDn0jYUwysmCBmQtL5ffC5Vbz/Qr2uyqFNE6/Xu7zex5kUnnGGg9LSUtx666245557UFxcfE6wWJZlFBcX480/7wzLfB+F6bjxnpQwB33DPd5w4XK54HA48NVXX8HhcHRemOAKc4VPp9MX1vF6sjQcRs66uzDqvYcQV771nGqzgiIjrnwrRr33EHLW3QVLw+F+XU80OHigEZWO1pDG8IfLBwOrylK4sGIo0RDV0tIStM1ABkMTEhKCtmluHphS25999llI/ffv33/ObV6vF263/opPFHm83nPfWOntNiKi3vAxhPqL2y3jZIMLbrcCq1XEiFQbrNaOyi0JmcBVdyfho5dP63pTxGQVcNXdSUjIVOGpCf4Lb4/HA6Hr650g1en9faLpNVKwiv3+Nm63G9OnT8fLL7+MX/ziF3A4HEH7jRs3Do888ggmTJgAt9sNr4a5vL18/T2e4I9JHWs8u5dUjf8uoef3mnukGz37I9R+A7k/AIN7hPujm4HcH4CxPTKg+6PjRo3zRcceMWIg90fHWHyOGQgexYN3HO+EZazNNZuDz8fnmCHp/776P8PhYa/ixf999X/4puWbQdvyOWZ4qXPVYdmOZXDKHW8qN3ubsWzHMrx5yZsYaet+vDGfY6Jvf+gxZswYPP744/jBD34QsN0DDzyAb3zjGxBFUdfPucf2KCGdnAJ0VIc88ZUXwQ7u9mWnQvZ2WRf3h24mk/G4QUrSHEP9xknpukOhfj63io9erceNvxih6UJqd9okjEjOg+1UuaH5AMCVnIfTqRMB7hts374dDz/8cNCqw4JgRnxseC6c3rO7Ac3N7Z2/aw0XjzkJqiBBUEMPKKqChDZzElTuEQAdFWU///xzvP322ygpKTmnouwll1yCK6+4MaxzSpLSb4/tsSd2Y9Tm/4bk01YB19p4DKPeWQrH/EfQlnVBv6wpGmzcUBG2ccZPiAvLWEGpCmJP7EFK6T8RX/l5t8cXVZDQkn0RGgv+A21Z03mRyiAbSu8NMxhKNERp+cWM1ar/6AWjtMw1UA+Ol1xySdjHPHXqFOrr68M+LkWG06dPD/YSiGgI42MIGaUoKo6UtWPbZ6fw5RetUJSz94kicN75cZh9cTLG5cfAkibgksUCdv5FRdvJ4GPHZwAXLBRgSWtGfT0gNTYhOUifU42nIEtnFxHTciroPI2nTqHdFxN8QcPEKWfwr8mpxlOod3a8bkxOTsZ9992Hn/70pwH73H333bj66qshimLna87GxuC/iGxsPAWzpXtljpZTwcPDp06dgs9y9s0PI/sD4B7pSe/+6LztlIZ+PX4eGcj9AfAxJBwGcn8AxvbIQO4PgHskHAZyfwB8jhkoDpcDHkV7FatAfErwqjd8jhl6GjwNWF+5PqQx1leux7S4aUHb8TlmeFlVuaozFOrnlJ1Y9cUqLMnufnQ2n2Oib3/o1dTUFLRNdnY2Tp48+0sMrfvj+MbwvH395b+bgwZD+RwTOpPJBEmSdB8nbzT4lyjEIFYI7f3PU1U+fFFSj7TxZx5TPD5IzW0QPD6oFhPkhFjAcnYfOifdgQs+exKSrD80JktWHJh0B1obNPxCb5g7evQoHn74YbhcwcNxFnMyBCE8QU5FVlF2uBoj08P/vvnIkVORWrs75HEaRk5D3ekWAMELQw13R48exQsvvIDjx4/3er8sy/j000+xZUsJzs8vDMs+EUVAUVtQX98W8lg9xTUdR4GBxw/J50LOR49j98UPozVxdNjXNdx5PAr27w3P4+6+PSdRVVULi6V/g5hxTcdRsHcV4lp6r3IsqDISHCVIcJSgNT4bpdMWc28MIi0/L0UKBkOJhigtwdBQrtLTS8tcWtZMREREFA1OVLmwbk01amt6/4WQogBfHGzFFwdbkZ5hxcKbM5E1yoYLvyug+MXAb5hNvVFA7oUCj4+PEKIY/BdGBQUFmtoRERHR8JdlzUK8FI8WOfQ3hWPFWLQh/G9u0uD6W93f4FNDO+rSp/qwqXFTmFZEQ0GDpwEfnvyw1/s+PPkhvjXyW0i1pA7wqojOJXuBui/DM9bJYwCY3+x3NpsNM2fOxPbt23X1Mxr8SxcSdffpTXmJjCxTA2y7ymA5Ug1B6VKRWBTgGZcJ14x8ePPS0Zo4Ggcu/H+YvONFXeEuWbLiwIX/j8EddFSAfOGFFzSFQgFAFC1hnd/tVoI36kuA4HDV6KvCEgw9MXp+yGMMB3v27MFTTz2laZ+oqhctbaVIiJsU8rznnR/XP6E/VUHB3lWGQuUAIMluFOxdhR2X/ZLVIXU6fcrbrRBHKBSlY7z+CJf7JdcfwOSd/6N5r8S1VOKCz57EgQv/H06lhv5/gIY3PnoQDVEMhhIRERENTWVftWHVK8f7DIX2VFvjxqpXjqPscBsEIXjYM2U0Q6FEREREQ5UkSHhozEOIl+JDGideisePsn8UplVRpPAqXmw6GZ5A52enPwvLODQ0BAoU+1Qf/lb3twFeEVHvPM2AGqYgR7jGoeCuu+463X2MBP9ECEgSYnX36ylFPI3ZFZuQuOZfsB4+0S0UCgCCosJ6+AQS1/wLSa9/CKnmFE6lTsLuix9Ge2y6pjla47Ox++KHGdg5Y+/evX1WgOyNEqYK+n5Wq85YjKrCfKwG8W9vwYjf/B3Jv9uApD9+hOTfbcCI3/wd8W9vgflYDU6NOB+t8dkhra01PhunUieGNMZwcPToUc2hUL/G0yVhmXvOxcFqkBuT3HCoz+qPWsW1VCK54VCYVhQ9QgqDD8B4XcU1HdcVCvWTZDcm73gRcU3aH1spOrFiaBBerxfbt2/H7t27sW/fPhw/fhxVVVWor6+H0+mEy+XqVhr/wgsvxLZt2wZxxURnaQkOhIuWCkeqGvw4GCIiIqLh7ESVC3/+YyU8Hn2vizweFX/+QyW+d9NoAOb+WRwRhcQqWjEpNvAbPlax/64sp8iWa89F0fSiwV4GEQ0Rk+ImYfXk1ahwVcCt6K8uYxWtyLXlospR1Q+ro8FU46mBRw1PUCLUqqM0dASqFurHqqHkJ6syatw1yLBmQArTMc665vcO+JQUBtOmTcPo0aP7PfhnhRliiO99Zkm1mB/zGcyCHLwxAFN9E5L+/DGav30pWvNG48CMezDr00cD9imdcgdqci5jhb8u3n//fV3tPd5TUFU5bMeEJyVr/32qVHMK8f/cDlN9U6/3+4PD1sMn4EtLxFfzbsa0r35rqCqkLFlROm1x1O8VvRVl/dray+ByV8NmzTQ8d3qGFWPz+6e89KjjH4VlnKzjm3EqbXJYxooWusPgAzxeJ1aVpQHAYGgv2trasGbNGrz99tsoLi6G0+nsdn+gcJve4JvP50NFRUWf948aNQpWK984onOZzcFfwPp8A/fLPa83+E/rFkt4y/73ZevWrSH1379/P+66665utyUnJyMtLS2kcSkyeL1enD59utttSUlJmv5PERHxMYRCoSgqXn5xl+5QqJ/Ho+KjjY3IRODKBMnJyUhO674nVTn4LwWSU5IhpI3o/Nxqag/aJyU5GbHJ0fMayeq14mfCzwK2GZ8xHgnmhM7PW1qCHwPb22tNr6cNwLGA/VJSkpGW1r1ShsnjBXAy6Hxd94iR/QFwj/SUhjS8lv2a7n5G9shA7g+AjyGDaSAfQwZyfwDcIz35FB9afIG/3/GmeJjEs7/O5XPM8N8fGcgIqX97a/CvI59jhpZkJRmJRxLR5O09qKBHvCkeLQj8OMLnmOHhj6V/DBoE9qk+vNfyHu4ruA8An2OiaX90tf3kdvxi3y/Q4mtBvCkev5z6S8waMavXtv32c0xqAoDg36Nw4XNM+BQWFuLuu+8+5331vhgJ/okILRSaIp7WFQr1E7w+JP7t38BPvgVbyoig7U1jL0JasrbKotHA6XRi586duvqE85jwqdNHYNQobd8P9UsH8ObHgEfbe+ym+iagqA0V3/wv5H71KiSf9mCjbLLBMf8R2LMugF1zr+Fp27ZtuoLlZ6moqlmLvJy7IBm4GNtqFbH4vyYiPT3OwNyBCV4XRtTtC8tYqXV7MTIpHqrZFpbxokFCggxRKocih164TJQE5I/PhNUa/gtmYqt2haWqbJ7vBNqyLgjTqkiL2trawV6CZgyGdnHixAk89dRTWL16Ndra2gD0HfQMVyVGURRxzTXX4Nix3n8Qevzxx/Hwww+HZS4aXoZiMHSgQjMXX3xx2Mc0m80MaQ9j/P4SUSj4GEJa7d93ElWVob25UVfrQmaQn+IsFgus1u4X5CgWC4LVYbBYLBC77GUtF/VYLBYgivZ/mjUNt+bfqquP1q9jz8cRs0XD6+te+lkswX9W7blHjOwP/21a5oqmPWKEkT0ykPsD4GPIYBrIx5CB3B/+27TMFy17pLKlEjcX3xywzZor1mBc/LjOz/kcEz37o7y1HHduvTNgm99d8jvkxeV1u43PMcNvf1hhxbMXPotlO5aFFA5NNCdi6aSlKERhwHZ8jhn6ap21+EfVPzS1/UfVP/CjCT9Cuj2dzzFRsj+6qnXW4uG9D8Mpd4T6WnwteHjvw1h35Tqk288NVPXXc0z8SBtEqR2KvtxerzQcdMfnmDCaMmUKVq5cifvvv19TONRI8E9BKAEfFZfZP9cdCu3k8UFYsxnmJZcFbco90l1VVVW3E1i1ajxdEpZg6IJrczX9/l5x1MGz+n3NodBOHh/a/l6Oyh/+ApkHXoKlKXjVfnfKGNTOewC+1PHgTgHeeecdw31d7hNwnHgDOVm36QqHWq0S7v3ZVIyfEDzsbYS5vQaCGoYnMwCCKiPWexreuNFhGS8aWK3A9Omp2LWzPuSxpl+QioSE/qkqm3pYXzXlPsf56n34xswJy1ikzVAqGMRgKACPx4PHH38cv/71r+F2u7uFQbUGQI0ekS2KIh588MFzqhP6/eEPf2AwlHql5YdTjyc8xwppEUkVQ4mIiIgi0eaNoV35SURERETRSVZlnPacDtqGosOMETOwYcEGHG09Cpes77hNALBJNoyNG4vjx4xUZaKhZnXZangVbWdzexUvVpetxoNTHuznVVEkWl22ujMU6ueUnQO+J0wWAbnT7Cjfpa3qZCCZBVag70MbqR/Mnj0bq1atwsMPPxzwxEw/W0wFAO3BPze8UFTV0HHyWVIdUqRm3f26Uk80QCmvDmmMaNTebuxC+XAcE56dE4eJk1KCtlMVFd43PgA82p4zz+HxonV9KaoX/wKj/9Z77sOv7vKlaC64jsc+n+F0OrFly5aQxmhrL0O541VkZ94KqyU1aPvsnDgs+fFEjM5L6Ha7162gpcEHr0uF2SYgPtUEs8EjxEVv6M9j/TleNJi/IDsswdCrFmSHYTXnErxOxFZsC8tYsRUlELxOqOZorz9MvYn6YOi+fftw880346uvvuoMd/YMgwYLfYZaPfQHP/gBli9fjpMnux+ToaoqysrK8Nlnn/VLBUQa2uLigpc0b21tHYCVdNBybEhsbGzQNkRERETDkdslY++ehsFeBhERERERDQMm0YQJCRMGexkU4WqdtShyFOnqU+Qowu35t/fLeihyBdor/j3RW9XQ/jL5qviwBEPz58QyGDoICgoK8PTTT+OWW24J2G758uX4xjeux4rln6PSoe39TAUqTqttSBH0H/tcYDmiu0+va9hZGpZxoklMjNFKe6EeEy5hyY8nQhSDZzmUL49DPRHa727VEw1Qjgc/WtiVPomh0C6qq6sNVZTtqaNy6B+Rn/ezgO3uuLMAl185qnNfqIqKyoMuHPioBRV7nd0qVosSkDvNjslXxSN7kg2Chr3kp4Q5oBfu8aLBpMkpyM6J0/wc0xut4XIjTK11EMJRIh2AoMgwtdbBm8yqsnSuqH7GWbNmDS655JLOUKggCJ0hT1VVO//0N4vFgh/+8Iedc/Wc849//GO/r4GGnuTk5KBttIQ1w0XLXCkp/fOkSURERBTpGhqckOX+/9mCiIiIiIiICNBXLdTPXzWUokugvTIYeyJ7kg0pOaEdz5mSY0b6OJ5iN1hEMXgEYerUqTCZOoJ7VqukeexatUn3ekzwIcdUo7tfb5Sy4MeEU3eZmZmQJO3f4678x4TLiltXP/8x4T0rQvZF/nSvkeWdg8Fh/YxWlDUqf0JSZyi0vtyDtx6txrvP1qF8V/dQKAAoMlC+y4l3n63DW49Wo75c+2mtvriRUEVj+74nVZTgixsZlrGiiSgKup9jutITLjeCVWVpoERtMPT3v/89vvvd73Y+0fQMhPr5w6I9/4Tb4sWLz7lNEASoqop169aFfT4a+hITE4O+iG5q0v/DkVFa5mIwlIiIiKKVy8WjPYmIiIiIiGhgGKkW6lfkKMJJ98ngDWlY0LJXihxFqHUGr4IXLoIoYP7iVJisxt6PNVk7+uup7EaDZ3ReAu792VTNwZ0mtR1tqr6QYKzYDlEI0wXbihKecaKI3W7H3LlzDff3HxPu9mg7Ejo7Jw7LV8zEpCkjNLVX3V4oB44ZXl9XDA7rZ7yibGgcB5woeqIGjQ5tF9E0OrwoeqIGlQe0he9Usx1tubNDWWKnttw5PCLcIL3PMX56w+VGsKosDZSoDIa+/fbbuPPOO6EoSq+B0K4B0K6VQ/uziui4ceNw0UUXdVYu7TpHY2Mjdu7cGfY5aWgTBCFo1dDa2oH7Qb2mJviVdiNGaHsBTkRERDTc2GzhuTqYiIiIiIiIKBgj1UL9vIoXRRVF4V0QRSwte2Uwqoam5Vlw3b1pusOhJquA6+5NQ1oeq4UOJZOmjMDyFTORnqEtINaa1gxJx7fYDJ/BlVG4LFq0KKT+/sqhwdxxZwEe/9XsPsNcXreCxioPao+40VjlgdetQG1sDl/gl8Fh3UKpKNuTqLFCZ325Bx+8UA+fW1/ux+dW8f4L9ZorhzZNvF7X+H2OMyk840Qrvc8xesPlRrGqLA0U02AvYKAdPHgQt99+e2cAE8A5FUK73jZ16lRcfvnluOKKKzB+/HiMGDECKSkpiI2NPSfAGaqbbroJn3/+ea/3bdq0CTNnzgzbXDQ8jBo1Cg0NDX3eryWsGS5a5ho1atQArISIiIgo8qSm2iFJAo+TJyIiIiKisHK0OXDf5/cFbPPri36NnNicAVoRDbZQqoX6ba7ZHJ7FUETTs1eKHEW4Pf92pNvT+3dRXWRPtuPG5RnY+HI9mmqCB/tScsyYvziVodAhanReAu756RQ8+tC2gO3uuLMAl185CicOufC+xmCXN/oiERFn1qxZyM/PR1lZmeExcnNzg7bpeky4n6qoqDzowoGPWlCxt/tx4aIETDqvDRcaXhWFyl9Rtri4OOSxZs6ciVNBCsuqiorNqxp0h0L9fO6O/jc9nhm0MrUzewbcKWNgbTRekdadMgbOURcY7k8d9D7H9Nfx8V35q8rGlW8NeSxWlaVAoqpiqKIo+P73v4+2trZzAqBdK4QKgoCFCxdi+/bt2LNnD1588UV8+9vfxtSpUzFq1CjY7f3zH+q6667r875Nmzb1y5w0tI0ZMybg/XV1dfD5BuYquBMnTgS8Pzk5GYmJiQOyFiIiIqJIY7VJmDY9dbCXQUREREREw4xH8eBo69GAfzyKtqpGNDyEUi3Uz6ewul400LNXBqNqKNBROfTae4L/PuWKO1Jw0+OZDIUOcVqCOP7gnz84nJgRPPTZpsRAQZhCPmJUxSvCRhRFFBYWGs5Z2O123H33T3T3qy/34K1Hq/Hus3Uo39U9FAoAigxUlMq9d6YBE2pFWb9rrlkQtE39Ea/m4+P70ujwovKQK3hDQUTtvAegmGyG5lFMNtTOewAQ+LgTDnqeYwYKq8rSQIiqy2N++9vfYvfu3b2GQv2f5+bm4q9//SvmzJkz4OubOHEiRo0ahRMnTnSuyR9W3bp1K7xeL8xm84CviyJXXl5ewPtlWUZ5eTny8/P7fS3BrvAKtlYiIiKi4W7+gmzs2hnkkmUiIiKKSln2LPzvnP8N2oaiU6o1FQ9MfiBoGyIij+zBesf6wV4GDQFGKssORtVQAEErsgFAxnirpnY0vPiDw289EvhUw0vvGAnTV2Oh7D8S8pxiPk9HNKqgoAArV67E/fffD6fTqbmf3W7HypUrMWrUGAC1mvs5Djg1HRfepsRAUQWIQhhOemJw2JBwVJTNz8/HlClTsAbbA7YrL9EQ6NTg4EctyJkcPOjsSR2P6msfQ+aGFRB92udWTDZUX/sYPKnjQ1kmhZnXraClwQevS4XZJiA+1QSz1fj/e1aVpYEQNcFQt9uNX/3qV72GQv1VQq+++mqsWbMGycnJg7bOSy65BGvXru22LgBwuVz48ssvMXny5EFbG0UeLYHPsrKyfg+GtrW1BT1KfiDCqURERESRbNLkFGTnxKHS0Wp4jPSMGKAhjIsiIiKiiGA32XFhKg8wpN4lWhJxU95Ng70MIhoCqtqr4Fbcg70MGgKMVJb1Vw19cMqD/bQqIv20BoeljGnhCYbOLAB2hjxM1Jo9ezZWrVqFhx9+GBUVFUHb5+fno7CwEAUFBais1P471fpyj6ZQKAD4YILDl4HR5mrN4/eFwWFj/BVlFy9erCs07Ge321FYWAghSDBXhIC6L0OrFup3fI8TXrcCs1WE6vZCbWwG3B7AaoGQkgDBerbgmzN7JipveB4Zm/4blqaqoGO7U8agdt4DDIVGCFVRUXnQhQMftaBib/fKw6IE5E6zY/JV8cieZNN/kcqZqrLZ7yzVFRz2Y1VZ0iJqdscf/vAH1NZ2XEHSWyj0ggsuQFFR0aCGQoGOF0N9KS0tHcCV0FAwffr0oG0OHDjQ7+s4ePBg0DZa1kpEREQ0nImigCU/ngirVTLU32qVsOg748K8KiIiIiIiIhoucmJzkGhOHOxlUIQzUi3Ur8hRhFqn9op9RJFCPG80hKzQKqwLWakQ8zLDtKLoVVBQgKeffjpou+XLl+PNN99EQUGBrvFVRcXmVQ2aQqF+pZ7w/M5VnKlvrXSWv6Ks3R68CmdX/oqyWvaJFWaoitEVdqfIKtq3H4PntXfgXvYSPE/8AZ6Vf4HniT90fP7aO5C/KIeqdOxDT+p41CxYEXTcusuXwrHwVYZCI0R9uQdvPVqNd5+tQ/mu7qFQAFBkoHyXE+8+W4e3Hq1GfblH9xz+qrKKyaarH6vKklZREwx94403un3ur8QJAKmpqfjnP/+JmJiYgV7WOQJVBGUwlHqaNm0axCBXvuzatavf17FzZ/BL4y64gOWriYiIiEbnJeDen03VHQ61WiXc+7OpyMqK7aeVERFRf3L6nNjRsCPgH6dPf1UMIiIioq5MognPXvhsyOHQOFNcmFZEkchItVA/f9VQoqFGEAWYb/saYDEHb9wbixnm276mvxoc9SrY+9sAMHXqVE3teqo86EKjQ99j3Al5JBrlBN1zdcXgcOj8FWVzc3M1tc/Pz8eqVasCFl/rSkR4/v+miKdxQ+wmWNe8A2XfEUDpkTZVFCj7jsD70t/geeoNKI66jts1VHV0pU9i9ccI4TjgRNETNZofTxodXhQ9UYPKA/p/v+evKutJ1FZ12J0yBpU3PA9n9kzdc1H0iYqj5Kurq7F169ZuYVAAndVCH3nkEaSnpw/S6ro777zz+rzviy++GMCV0FAQFxeHCRMmBAwNf/755/2+ju3btwdtM2PGjH5fBxEREdFQMGnKCCxfMRMvvXgAtTXtQdtn58RhyY8nYnReAhor9V9xSkQDo9HdiLXlawO2WZS3CCnWlAFaEUWSE84T+K+S/wrYZs0VazAunpWhiYiIKDQzRszAhgUbcLT1KFyyC1VtVXh0z6MB+zw+/XGMiu14I9om2YBa4NYXbx2I5dIAC6VaqF+Rowjz8uaFZ0FEA0jMGQnzkuvhfW094NERHLSYYV5yPcSckUBjeb+tj8LjwEctBnoJ+NR5Eb4e+wnMghy8eU+dweHgv+ulwPwVZW+55ZaA7ZYvX44bbrhBV3hYgfYqsn3JkmoxP+YzzftEPdEAz/NrYF5yPTAy5OlpgNSXe/DBC/W6Kg8DgM+t4v0X6nHj8gyk5Vl09fVXlc1dtyRgu7rLl6K54DoGiEmzqAiG/utf/+oMgfr/9hs9ejR+/OMfD+LqusvOzu5cX88g6/HjxwdjSRThrrjiioDB0LKyMjgcDuTk5PTbGjZv3hzw/oKCgogJXxMRERFFgtF5Cbjnp1Pw6EPbAra7484CXH7lKIisRhARHG0O3Pf5fQHb/PqiXyMntv9ee1PkOuU5hVWHVwVsc3XW1QyGEhEREVG/M4kmTEiYAACINQU/eWJC4oRuF6gcqT/Sb2ujwRVKtVA/r+JFUUVReBZEQ45P8aGyvRI5sTmQBH0n4kQCqWA0hKU3w/v7d6HWnQ7aXshKhfm2r3WEQimowd4fPo+Kir3GTuNoVJLwUfvFuEpH6A8Ag8P9oL8qyrrhhSDC8HHyKeJpXaHQTh4vvK+th/XOS41NTANKVVRsXtWgOxTq53N39L/p8Uz9VaZZVZb6QVQEQ7du3XrObf6A6KJFi2AyRc6XQZIkjBgxAidPnux2u6qqaG5uHqRVUSRbsGABXn311YBtNm7ciB/+8If9Mv9XX32FioqKgG0WLFjQL3MTERERDWVawp75E5IYCo0gHsWDo61Hg7YhIiIiIhooyZZkLB6/OGgbil4J5gQsGr0oaBsa/jyyB+sd68My1sc1H4dlHBpaSupL8PCuh9HsbUaCOQFPzngSc9LmDPaydBNzRsJ05zfgffKNgO1Mt1wN6eIpPD5eo0jYH85TMhQDBT/9quV0vNd2Ja60b0Oi1Bq0PYPD+gx2cFiBipHnmVH7hZELJFRcZv/cWEVZAPB44fvHFiDJWHfqndPpRHV1Ndrb2xETE4PMzEzY7faQxqw86NJ8fHxfGh1eVB5yIWdyaGshCofISUT2o6+++qrP+6677roBXIk2ycnJ3YKh/kqnLS1Gyp7TcDd//nxIkgRZ7vtFyLp16/otGLp2beCjEgEGQ4mIiIiIiIiIiIj6Q4o1BXedd9dgL4MiWJotDQ9OeXCwl0ERoKq9Cm7FHZaxQq06SkNPrbMWy3Ysg1PuqMbY7G3Gsh3LsO7KdUi3D71TA3ue3NkbcWwWQ6EaRcr+8HlCPyq8UUnCZuccfDNuU8B2DA7rEwnBYQDIm2MzFAzNkuqQIoVWyE2tO8VgaBgoioLt27dj7dq12LJlS7ecjCRJmDt3LhYtWoRZs2bprioLAAc+Ck8u6+BHLQyGUkSIivqyR48e7fPF3aWXRl65ZpvNBlU990ULK4ZSb5KTk3H11VcHbLNp0ybU19f3y/x/+ctfAt6fmJiIa665pl/mJiIiIiIiIiIiIiIiouByYnOQaE4My1jx5viwjENDx+qy1Z2hPz+n7MTqstWDsyCKKJGyP0yWcIU0GRwOJ39wuNnbkXfxB4drnbUDvpa0cWak5Jh19yuwHOmH1ZBepaWluPXWW3HPPfeguLj4nOJpsiyjuLgY99xzD2699VaUlpbqGt/nUVGx1xm8oQbH9zjhdSthGYsoFFERDG1sbOz8uGtANCkpCWaz/gf9/tbXmlpbg5crp+j03e9+N+D9Xq8X//u//xv2eTdv3oyDBw8GbLNw4UJYrdawz01ERERERERERERERETamEQTnr3w2ZDDoYnmRNw38b4wrYqGglpnLYocRb3eV+QoGpRwF0WOSNof9mQJ4sCfUE5BREpwGAAEUcD8xakwWbWHek3wIcdU04+rIi1KSkqwePFilJWVaWpfVlaGxYsXY9u2bZrncJ6SofR9UK8uigy0NoRpMKIQREUwtK2trdfbR44cOcAr0cbtdvda4VRLSXuKTt/85jcRHx/46syXXnqpz/8LRj3zzDNB23z/+98P65xERERERERERERERESk34wRM7BhwQa8efmbeP3S1/H49MeD9nl8+uN4/dLX8fqlr+PNy9/EhgUbcH7S+QOwWooUq8tWw6v0fvSyV/GyamiUi6T9YbIIyJ3Go5sjSSQFh/3S8iy47t40zeHQWLEdonDuib80cEpLS7Fs2TI4nfqqeTqdTtx///2aK4f6POH9PntcrBhKgy8qgqFeb/cXIv5j2iOxWijQd2XQmJiYAV4JDRVxcXFYsmRJwDa1tbV46qmnwjbnhg0bsGHDhoBtLrzwQlx++eVhm5OIiIiIiIiIiIiIiIiMM4kmTEiYgKnJUzEhcULQ9hMSO9pOTZ6KCQkTYBJNA7BKihSBQl1+rBoavSJxf0y+KnAxJRpYkRQc7ip7sh03Ls9AYkbw5zQzfAOwIuqLoigoLCzUHQr1czqdKCwshKoED2maLOEt1mexRUUkjyJcVLxyj4mJ6Ra2FAQBqqri5MmTg7iqvlVXV/d6e2xs7ACvhEKRl5eH48ePB2zz8ccf48orrwzLfD/96U/x4osvnhOE7urZZ5/Ft7/9bUyfPj2kuZqamnD33XcHbbds2bKQ5iEiIiIiIhoqLKIFY+PGBm1D0Wl07GhsXLAxYJt4M9+8IiIiIiKiyBIo1OXnD3c9OOXBAVoVRYpI3B/Zk2xIyTGj0RF4XYEkZpiA3mt5kQ5ag8O359+OdHv6wCyqi7Q8C669JxVvPRL4mPjp3xwBBP6VDvWj7du3az4+vi9lZWXYv39/0Hb2ZAmihLAcJy9KQFyqFPpARCGKimBobGxsr1U4GxsbB2E1gVVVVcHj8XSGV/1/A0BWVtYgr44iWXZ2Nu6++2688MILfbZxu9246aab8O9//xtpaWmG5pFlGT/4wQ9w9OjRgO0uuOACLFy40NAcRERERESRKNmSjMXjFwdtQ9EpJzYHb1351mAvgyKUSTQh2crHByIiIiIiGjq0hLr8BjPcRYMjUveHIAqYvzgVRU/UwOfWfyy0ySpg9sIkYHXYlxZ1IjE43JMgBq8QOWLKCOAjEdBQcZJC41N8qGyvRE5sDiShI1S5du3asIz94YcbAcwN2MZkEZA7zY7yXcaqk3Y1erodZisrhtLgi4pgaGZmJmpqarqFLQHA4/GgpqYGGRkZg7zCs/bs2dPr7YIgIDc3d2AXQ0NOYWEh3nzzTdTX1/fZ5vDhw1iwYAHef/99ZGZm6hrf7XbjjjvuwDvvvBO07W9/+1uIIp/oiIiIiGj4SLGm4K7z7hrsZRAR0TB0pOUIbi6+OWCbNVeswbj4cQO0IookjjYH7vv8voBtfn3Rr5ETmzNAKyIiIqJooCXU5TfY4S4aeJG8P9LyLLju3jS8/0K9rnCoySrgunvTkDyiDZ5+XF80iNTgsCEWM8TJY6DsOzLYKxnWSupL8PCuh9HsbUaCOQFPzngS0+KmYcuWLWEZf+fOnRibGzgYCgCTr4oPSzB00lUdJwOpbi/UxmbA7QGsFggpCRCs5pDHJ9IqKoKhY8aMwe7du3u971//+hduuummAV5R34qLi/u8Lz8/fwBXQkNRUlISnn/+eXzve98L2G7v3r2YMWMGXnvtNXzjG9/QNPa+ffvwox/9CDt27AjadvHixbjkkks0jUtERERERERERER98ygeHG0NfHqPR+Fb10REpF+sKRZXZV4VtA1FHz2hLj9/uIuGv1D2x0CF/7In23Hj8gxsfLkeTTW+oO1TcsyYvzgVaXkWKNVtA7DC4S2Sg8NGSJdNYzC0H9U6a7FsxzI45Y5AZrO3Gct2LMNzo5+DLIfhXHcAisbz4bMn2ZCSY0ajQ9v+7U1KtglZQi08r+2FcuBY92qzoghx8hhIl02DeN5oTVVriUIRFcHQ8847r8/7iouLIyoY+u6773ZWNO3pwgsvHODVDAyj/67y8vJ+G7uwsBD/+Z//aajvYPvud7+Ljz76CL///e8DtqupqcH111+PSy+9FHfeeSeuvfbacyqINjU14dNPP8Uf//hHvP3221A0lEefPHlywOPsiYiIiIiIiIiIiIiIaPBl2DPw9MynB3sZFIH0hLr8/OGuhTEL+2lVFClC2R8DGf5Ly7Pg2ntS8dYjNQHbXXFHCs6/Io4BrTAZCsFhvcTzRkPISoV6osHwGMLI5DCuaHhZXba6MxTq55SdWHd43YCvRRAFzF+ciqInanRVHPZLs53GdZY98L5ysvcGigJl3xEo+45AyEqF+bavQcwZGeKqifoWFcHQOXPmnHOb/1j5d955B7/5zW9gNg9+qd5t27ahtLS0c209zZo1axBW1f927twZcWM3NBh/Qo8Ev/3tb3HgwAF8/vnnQdv++9//xr///W8AQFpaGtLS0iBJEk6dOoWqqqpe92JfRowYgbVr18JutxteOxERERERERERERERERENDiOhLr8iRxHm5c0L74IoooS6Pwa6qqyWsGfGeCtDoWE0VILDegiiAPNtX4Pn+TWAx0AlSYsZpm9cCny6PvyLG+ICPaYUn+r7xOX+lJZnwXX3puH9F+p1hUNzbHW4KuYzCA3BqxQDgHqiAZ7n18C85HpIBaONLpcoIHGwFzAQLrnkks4qnD1Dl9XV1XjjjTcGa2ndPPfcc90+71o59LzzzkNOTs5AL4mGqJiYGHzwwQeYMmWKrn719fU4dOgQ9u/fj8rKSl2h0MTERGzYsAEFBQV6l0tEREREREREREREREREEcBIqMvPq3hRVFEU3gVRRAl1f6wuWx3eBQWh5f3umsNuqIr+yoB0rlCDw7XO2vAuKAg9+0PMGQnzkusBi86icxYzzEuuh5iRYnCVw1ugxxRfgg+CFJ7QtihKutpnT7bjxuUZSMzQVm9xTFYrrootgeDTFgrt5PHC+9p6KI46ff2INIqKYOiIESNw6aWXnvOg7g+JPv300/B6jb14CZfPP/8c69atO+cYeVVVIQgCbrjhhkFaGQ1VKSkp2Lx5M6644op+nysnJwebN2/GzJkz+30uIiIiIiIiIiIiIiIiIgq/UEJdfptrNodnMRRxwrE/ihxFOOnu44jlMKsv9+CD/wl+Umjx7xvx1qPVqC/3AICmkKhy5ATDpL0YSsFhI/tDKhgNy9KbgbQkTXMIWamwLL2Z1SD7EPQxxQJgfHjmMpJlScuz4Np7UoO2u+L2ZMxL2AnBaO7M44X3jQ/4mEL9IiqOkgeAm266CVu2bOn83B+4BICysjIsXboUv/3tbwdlbW63Gz/84Q8719TbVQm33nrrIKyMhrrU1FRs3LgRy5Ytw//8z/9AUZSwz3HVVVfhz3/+M9LT08M+NhERERERERERERH1raq9Co/teSxgmxXTV2BUzKgBWhFFmhpnDZ4/9HzANksnLkWGPWOAVkREkSyUUJefT9FZLW0QaA3+CekjeMR4F+HYHwNVVdZxwIkPdBwD3ejwouiJGvznd4Hk4k1B2/v+ugnyv/bAfNvXIOaMDHW5w0K4gsNX5AYvfLVv3z6MGTMGomisFp7R/XHdvWnISgSg8eTVbtkfNXhWw1pzEJ7kXECIihp/mh5T1AtVoDT0ua65ZgHW/Nmpv6OGpwB7XRXUE8FDxoGoJxqglFeHNAZRb6Lj0QTA9773PcTFxQE4e0R71yDmK6+8gjVr1gzK2u644w4cPHiwWyjU/7EgCLj00kt1HwlO5Gc2m/Gb3/wGJSUluOiii8I2blZWFv70pz9h06ZNDIUSERERERERERERDQKX7MKuxl0B/7hk12AvkwZRm68NH1V/FPBPm69tsJdJRBHAI3uw3rF+sJehi5FjwhVHHby/+0fQfr6/boLnqTd4vO8Z4dwfH9d8HLTNvn37DBc9qi/36Ar9+Y301SBu7d+B+tOa2qsnGuB5fg3k0uNnbtAW/NPSbigKV3D4obceCtruiSeewK233orSUv2JQaP7w+dWsefFA3A/twZoaNLWqfokPM+vgenzfyHjw8AXcwFA+qfPI2fdXbA0HNa1tqFIc5B4LIAQ4yj5+fmGMldaq8p6Pt5jYFXnUnaGIQFL1EPUVAxNSkrCkiVL8Nxzz51zXLs/hHnbbbehtbUVP/rRjwZsXUuWLMFf//rXc9bU1X333Tdg66Hh66KLLsL27duxefNmvPDCC/jggw/g8Xh0jSEIAi666CL85Cc/wXe+8x1YLJZ+Wi0RERERERERUfRIt6XjqRlPBW1D0SnZkozF4xcHbUNERDQcaQ3+JWeZWdkxRFXtVXAr7kGbX0sVz8NfnkZWVixEUUB9uQcfvqztGOj9m1owf3EqUpzV8K5aD3i0hdf8wT/zkuuj/ijocO4PLeHBJ554AmvWrEFhYSEKCgo074/MjBhsXtWgO/SXIp7G/JjPYBZkXf3g8cL72nrYfjgbGftfCto8/dPnkXSwCLXzHoAnNUxnZEeAcAaHW7NbNbUrKyvD4sWLsXLlSsyePVvTHvmq9BTqN0u69wfQsUeuMG+F4NW3R2ItJ5Cz411IorZ+1sZjyH5nKaqvfQzObP3Hnw8VmoPEIoAbAWm1BNmt8/8nALvdjsLCQgg6q8tqrSprgg85phrd6+qNUlYF5AduE21VZSl0URMMBYAHH3wQr7/+OpqamjrDoF0rdPp8PixZsgRffvklfvnLX8Jms/XbWmpqanDbbbdh8+bNnbf1VS30hhtu6Ld1RAItP9ANReXl5YO9hF7Nnz8f8+fPR1tbGzZt2oR///vfOHjwIA4fPoxTp06hpaUFsiwjPj4eCQkJGDNmDCZOnIgLL7wQ1113HTIyeJwMEREREREREVE4xZnjcHXW1YO9DIpQKdYU3HXeXYO9DCIiogFnJPiXlseiJkblxOYg0ZyIJq/GSngh6HkM9PHyZrz04v6g/Vb/Xyk2fViJby4Yj91r2nQdA1385Bf4j5hiCD6dR92fCf4JS28GYqL3KOiw7g+XACDw925S4izEnU7CqmVv4bJLr0FZefDv/VX7LwABAABJREFU9d4/lKPqL9Ww+kxIlQABKmRVQqOSFLBfulSHy+w79YdCz4i1nED2vx6FJGkP/mWu/X/4pPIm1DjHdt5+NtqunnObcE4jtUefjtvOiccLHV+Hc7ur3W4QeuvbcyhB7fZtE7qs40RMHdyzwhQs15BienD8d5BpGwEBgO/VL7D/zSqcaBcBxAXs5/vLdhRIAmDrWH+7YsNuz6SAfWZY9iNWdCLHVKN7j9hsTcjN3aU5FOon+lxI/+cv8FniA2i2jgUkEZBECCYRkKQzf0QIJgmCKEAQO3JGgghAAEQRgCBA8H/c5X5B6PGx2PXjM/f5Pw7Y70xfwT+n0LHfurTti+ZqoX6ZAL4D2N6yweXUfhqC3W7HypUrUVBQAEdFS9D2/osPTlZ4NVeVjRXbIQphyjxpqJI8XMPl1H+iKhialpaGJ598Enffffc5D0Jdj5X/9a9/jb/+9a948skn8b3vfS+sa2hpacFLL72Ep556Ci0tLd3mBbo/OEqShN/85jdhnZ/ILzY2FjfccMOwDx4TERERERERERERERHR0KK1Updfo8OLoidqcN29aciebO/n1Q1PJtGEZy98Fst2LAsp/Cd4BKhBQn9dq0H6vGl48bl9cGusBNfo8KLkj82QoDV4qcAMH+ZK2/WHQv08Xoi/ex3pubuDNk3/9HkkfvZnnEi4AW5TRkduTlV7/On9NrXr54o/hHf2c/XMn86P5Y77VFntyPkpSsf9/o9VdLTtHE89e3/PuaACSpf51O7zC6qKwuRL8YtpH6HFYjwAmOCx4P/7agaeQEnAdg+OTsXYmKSOTyq34gSs2I/zAva5PmYvskzd13ZKjkdR2zUB+11s24N4sT3o2nvTGfzTGAr1M4tezB/1Vxw7OgcuV6KhuSPJWLeCRI8VTSHsDb94rxktCFxJcpK9GWNjujwGyI2IlaxAkD2Sb67ptkdOyfFBg6G55mokS8FDhedSkZ29T/fe8DPBjYtqfoOysrnoGQHuSlEFKBChQICiipAhdnyunrntzOeyKna2k1URKs607XL72Y+73id0Ga/7PGfHODtPZzuh4zZVFKFCgiqc+VgUUTz5/+DN01a52U8eI2P8f1yM2veP4lTbiaDt05Py8K2L78OpkjH4+8cncOjwyaB9Pny9Fp+/1YwUIU7z6w8zDD6vhCBaqspSeERVMBQA7rrrLrzzzjvYsGFDt0Cmn/+2yspK/OAHP8ADDzyAb3/727jpppswa9YsWK1W3XPW19djy5YteOedd/C3v/0NbW1t51QH7cofFn3kkUcwY8YM4/9YIiIiIiIiIiIadG7Zjcr2yoBtsmOyYZX0/96JiIiIiGi4qS/36AqF+vncKt5/oR43Ls9Aijl4X+XICQjpI3gEfRczRszAhgUbcLT1KFyy9qpsAHDgwAG89PxLcDu0BcOOlh3BfT9ZgfycOxDnUxAvqGhQA/9MNM/agAKTFTahASbIcKsWbHdPC9jnxthNBkNdZ8XG1SM3fRckn7aAl81Xh9H1r6Pi+Ey0taWGNHdfzhTpG1AXnUzCPz7+Jo7FNcEt6Q9DWWUTxrQmoqKtuR9WNxhCC/5Jkozs7H1Bg3/9Q+38WxC6fnz2vq63d6082u32M59boOLpAxfiwSnb0WTWF/jrKtFrxn3HxuMXOBSwXXx8HRLj285WLRVUtHrigObAwdCk5EqkWls6+wieVKAt8JpGpB7FSGsDIPirtKrw+ixoqA9crTFr1D7Y7KE99tjsLcjN3QmPNwaqKgDqmdquqgBVFaFC6OX2nh+LfdzedRwAqnhOG5wZXz3Tzv9517/1qrO247XcDYa+HmXnf4b7yr6Jp/esC9ju5uwbMWvEhUB1G5QTB2CGiAkK8FWQ8cdKAmLcChS1BWahI+DqUyX4YO6zj3eQYneiz4XMDStQecPzrBxKAUVdMFQQBLz55puYOXMmjh8/3i2Y2bNqp6qqqKmpwcsvv4yXX34ZoigiLy8P559/fp/jl5eX47bbbkN7eztqampQXl6Ompqazvt7m6Pr2vx/z5s3D48++mgY/+VERERERERE1F+aPE3YcCLwLzWvzboWiZahXwWC9Ktsr8TNxTcHbLPmijUYFz9ugFZERERERGScouGo055HhWulKio2r2rQHQr187lVbP/tV5hn3xa0nqTvr5vg3rQb7ddeBWVkGuwtHuQG6VNT5kJbjLOzqCJw5m9VPfu50vV2dFTPVLt+7m+jdn7e7f4zN3Qbp+t4qtpjHHQZR+0xTi/r6zKXf33dPldVCHIyBNkHUfZ1/K10fCzKcufngu/M7YoPnrY2pDlO4b/jb0HDuFN4uuydgF/H16d8HRNik8581hEAO+Gz4rEgoa7LrSfPqfaHMJ1e3RejFSElSUbu6J3DpiKkn0kVMb4lGQBwyuLC33IDR62+VTEByR6bgZlUCIJ8JoSoQpSCP5ZYbS2wm9sgCGpnP7fPFzT4l5BYjRRrQ0fwUVAh+0w4fTrwo0Fa2lewxzSFJfg3fnwxFNWEzqPgewlq9nX72fv8t58b2jxnrH7KoE4AsLAuBl+YFDhFFeWSgiUpgSuxvtYYgzy543trVwSc7xNxONGBXwSZKyPjS+SkSN1u87SlAo4rAvZLTTuGjNiGsze0twKOwHOlpFQhNaZ7hUqXKy5oMDQmxnjl5a4SEuvCMk5/6Hg+6R4UVc8ETP1h1Z4f/1/qKXjF4K8jeuOTZBw8fxOwJ3C7W8eWY3xcfbega4U7Hu9WXRaw39dTPsQoc3u3kGyjNwlrT/d9Cm+bEgNVRZj+X+n7uog+F9I/fgaOha8Cgr7XWxQ9oi4YCgDJycn48MMPccUVV6Cmpuacqp3+ip09w5uyLOPIkSM4evRot9u79j158iTefPPNbmN11fWo+N5CoaqqYurUqfj73/9+znH3RERERERENHiq2qvw2J7HArZZMX0FRsWMGqAVUSRpcDfgmQPPBGwzc8RMBkOJiIiIiGhIKy0txc9//vOg7TqOCn8Lj/x8BfJy8tFUE7yC3Mb/q0OiaEejw3i1uSypFpc7P4Po0hbikxpOwvant/FR+8VQLR4EO8yxfO02bK+1dlRgG3AqRCgwQYYkyDBBhkmQYRJ8PW7zdd4ndfncLPjb+Dr6dbY5+7kkdLQzIj++4++jUvDvn2nIvA3e3xUhzwT7ugQZBeFMJUN0v63jY6UjfCQoZ+/v2vbMx73ddvZjRVc/nJn77MfKmSCiAqfVhd+POx7wa/ADSwPyvaZuY6inPcC+wF+78eO34PwuwT9bWyqwY3LAPjm5ezC2a+gPgL09C6gPfKFmenoZMroE/1yuuKDB0MSkGthsrQHbaGW1GTvGPhKZIGCKr+P7Fm8K/v9milfC+T4paDuKTIKAzscpLapEBX9ODO3/zQdJp4O2GZl2BFm9BYeDBEN7ewypac8CdvcdDPXBBGtsEzztof/ONzauUXcfa+Mx2Kt280h56lNUBkMBID8/H5s3b8aCBQtQWVl5Tgi0a2XPngHNnmHPQPf1Fu7sq42qqpgyZQo++OADxMfH6/wXERERERERUX9yyS7satwVtA0RERER0UBJMCdg0ehFQdtQ9Io1xeKqzKuCthlqVIXHhPcX2afC61LgdanwOBV4XQo8zo7bSg+W4e/r/oEYdwGClVj7Rt5TGGkZj09/DXyKKrSrwcs6Npb54BI8hteeIp7G/JjPdAcbzYKM/0z5AKnZgY8uBoCb8t/A3MyP8dfDP0RV2+jO24Uzgc2zQUsFJvg6gpg9ApsBA5xdApq9BTi5nfWz2VoQY27sCDQKHaFIRRHR1pYWsN+I1COIjT0VloqQ50/c2Pm5ICg4G/YMaehBF6ch+Ge1tsEmdQ9omTT0I6Lh5zfxLnhCfNzzReDjpi2xISzB0KTEakP9Eg+uZzCU+hS1wVAAOO+887Bjxw7ceOONKCkp6QyB9qwe6tf1qPe+wqFagqC9tVdVFVdeeSX+/ve/IzGR1UOIiIiIiIiIiIiIiCiwNFsaHpzy4GAvgyJYhj0DT898ekDm0hLWPPzlaWRlxUIUez9hry81h91IzjJDEAUojjp4X383aB/fXzdB/tcemG/7GsSckf5FBu1nrTkIT3LukDmSU1VVyF4VHpcKr/NsiLNroPPsfR2BT/9tJ731+DR1DRRZhexTocjnfommHfo2Yl0pZz5LwswRt+GUqwJfnt54zlq6MovW/vkH90nFZfbPDVW7jI2r13VUeFZsJe6d8gQOl1+MtrYRZwKg2qqlDTWnLE78PfervqtHQsVN1TkY4TOfCToqiBODBylTU48iM9EKQVQ6A5uKKxEIcpR83thtGBvb0Nmn1pkB7LkmYJ+c3D3dqkECHRUhyw4HDoYmJ1eFrSKkJPnCMg4R0VDlhoo3Yo1f/BHJzPYWWG3NcLuMX5BntTXDHnPaUN/YihIIXidUs93w/DR8RXUwFABGjhyJ4uJiPPbYY3jmmWfg8/n6PO5dyw+mWtoA3QOhoijikUcewYoVKyCKQ+OHTCIiIiIiIiIiIiIiIiIAOF7ejJde3B+03er/K8WmDyux5McTMTovAfXlHnz4ckPQfsW/b8T+TS1YsKAdMevfBzzajhpXTzTA8/wamJdcD3uqBxkb/zton/RPn0fSwSLUznsAntTxmubRS1VUeN1qj6CmAq9T7fy7I9h5pnJn1wqezjNBzy7BTw15116dSmjE7snvBWxzftm1iHUlQ4ICAQokQYFVCF79M93UgAyTBBEqREFBiyJjX5Dc5TRLKdIkX2cfEQraFSu2uy8I2O9a+7+QIp2GTdR/BL3N1qQrFOonSTLG532GY0fnwOUyWvRH7VLF8mw1S0FUIPZ2u/9j8dzbxN7adWvf8/YefXtto6DULOP19MBBzzvstRjT5Sjo9sbgX8vk5CqM6HHMb2ObhiPoTR6YTGeDRUO94iYRUbQoNylwDdPHbEEAsrP34eiRi6GqUvAO5/SXkZ29z/BzmqDIMLXWwZs8OnhjijpRHwwFALPZjP/+7//GwoULcd999+Hjjz8GcO4x8lpDn33pbazZs2fjhRdewKxZs0Iam4iIiIiIiIiIiIiIaLjgUeGDR1GCpwz37duHMWPGQBRFHNh/Ei8+tw9ut7ZgXaWjFU88thPf/9ZEfLHeDZ9b4/tvVfUwr/0E0FsR0uOF5U+/Q3beLohy8EAjAFgbjyH7naWovvaxzqM5ux2x7g9xnjlq/extZ6tz+oOc/lCn16XA065AdsuQXTJEKJ3hx46PVUidH/tv7whI+kOZFiiwCWdu97cznbm/a//OMc62k3q5vdJej78F+VrcELsR45DU7baj0mn8JUi/i227MTbmbL8TPiv+4Q5cDXKs2YEsU/fv0Sk5HgjybYu3nEaC+XRnBcuOo8IFeDzxAfvFxtZhVPYB3aFQP0mSMWbsNrS2jugSqjw3XCmeCXueGwI1NC0R0ZBgVYECb+DCaNbhWWyZejHOJyJFFtAo8ZveH0Svc7CXQBGKwdAupk+fjo8++gibN2/Gr3/9a2zYsKHzh9+eIVGjugZC77vvPixcuDDkMYmIiIiIKPx8ig+V7ZXIic2BJOi/ypOIiIiIiIiMCemocApJaWkpfv7znwdt98QTT2DNmjX4r7sexpt/PKk5FOonuU3Ys7YdErSepGf8mHCbrQm5Wdshyvr6ij4X0tc/guIj30JT2wiISo/w5ZnwpgQVZiiIF/oOZXa06wgIwoKOP13+bTgTZhSEsx/3eluX4GOg2wTB//6mAgiAgDMhREGBgDN/CyrMtragX4e0tCPITLB1O0K8rTl4+CA7ex/GJJ05XhwKJGcycCBIMHTcVoyJbej2b6l1ZgG7Ax8VPmbs530cFX55wH6ZWaWwWFxB/y2BSJIPiYm1IY1BRDQcjZUllNSdPVpbRkdWRgJT8dHIBAFvNMbieyPacEo0Hg5NUIDmMK4rHFQVqKyaaqhaaEd/CZWVU5Gfv8XwRSMKj5GnPjAY2ov58+dj/vz5qKysxJtvvol//vOf+Oyzz+Dz+bq1CxQU7a266NixY3HjjTfilltuwcyZM8O+biIiIiIiCo+S+hI8vOthNHubkWBOwJMznsSctDmDvSwiIiIiIqJhT/7iOLyr1hs6Klwq4PGJoSgpKcGyZcvgcgYP/Y2zJyGuthmfrtqB8eYkmMwqvKqAg76EgP2usdUhRfRipBgLC+ogCTKcihXb3dMD9vu6/ROkSEZiACqys/cZrghpkry4ctzbaGtN6QhYnglGouvfZ4KPHfefDWR2DWAGDn4aWlpYNJm0HPl9AiN83YMOCQjez25vQmzs2X5W1RKgdQdRkg1/r4iIKLKts3shALjJGfz5IBgZAryKCAUCVFWAAgFO2Ry0X4M7FjGSFyaYAVVEo2tE0D7VbaPglm1IEptgQsfzvMcdE7Sf0xkPm601+D8miLLWVDhlKyRB6fJH7fF5xx+xl9tNQuRU6LzUY8Lh6gR8YVLg7CUcusnasUeucvf+vbQrAoR6FXMR+tc1nLzOeLhdgV8DB+N2JcDZnoSY2NO6+6qiBF8cL5Kj3jEYGkB2djYeeOABPPDAA2hpacGOHTuwe/duHDx4EBUVFXA4HGhsbITT6YTL5YIgCIiJiUFMTAwyMzORm5uL/Px8zJw5E7Nnz8aYMWMG+59ERERERERB1DprsWzHMjjljjfCmr3NWLZjGdZduQ7p9vRBXh0RRSpJkJBkSQrahqJTdkw21lyxJmgbIiKiaKc46nSFQjt5vPC+th7C0puB2P5ZWzioigL4ZED2/y1D9cmATwFkufM+9cx959zu/7jL/WqX+8+O2b0ffPK5Y/boL3u8KHC58cHUG3Dc2Yzv73sv4L9lxfhLzhwTfvrMn46jwg82B35T/GLLqTNHhZ/svE3LUeEW8eyeEAQZkuSFz2cL2CcnZydi4xphMuncTz1Ikg8JiXUhjUFENBz1PCq86UwALVEVurWJdE6vDW3eOFjgBVQBXq81aJ/29iSoigh7TOi1CzfXF6DanQwVAlQVHWFHCFDUjr/VLuHHjksROj5H58fodrsqdG/f+bEqAEL3cf0fAzgbshTEzj5QBahd7us69tmxABVd+qDL+Gf+9kHF5otfgQrgHzt+AhUSVEHs7H/qVBO8PhmqKqDd3QDgDwG/ZreWLESsPQ+iqC9kunT/LQCABMGO88QsSELwyuV/+uq/AABJQiO+HlcM65mLQIKpqpwOu60VNnuLrjV2Vdaahtt3/rDze2SMChE9A6MqREGBqUfQVOwlfGryVz7vNYx67m09w6n+Oc5dQ/f+EGS8MWknBAAXHp0IS+d9aucYMhRUtDqBIMHQJq8Np72mbnPJav9dieNqSg3LOKebMg0FQ9ty50BlxVDqA4OhGsXHx2PevHmYN2/eYC+FiIiIiIj60eqy1Z2hUD+n7MTqstV4cMqDg7QqigQJ5gQsGr0oaBuKTnlxedh0zabBXgZFKKtkxbj4cYO9DCIiooimKiq8b3ygPxTq5/HC+4f3YPn+7KBN5cMOyBbP2dBkgMBkt3Blb2HNroFLn6+jrT/w2SWsCZ/Scc5khJIASOLAX8gkCAokyRO0XU7ubmTFVcBk8kIUZU3HhFttbSGHQomIhjJVEKEKIiB0hPBUUQIEEaogBf9YlKAKvbeB2DFeiiDh/TMf+wQB17reAyDgnbhvQhRNHe3SRdQKIv5WtB71JxshK0CtM3hl4F/sjMeYzOsgqyIUVUSLL3gAcOm+myAKgKIK8KkirKod01KCVxP/7YHlSMk24+pr2hG7/n1Nr0VOVE0FoCJ/wr9hsxoPh7pTxiB3yYvI1RBQHMreq3wP6/d0XBQy6wEzrsu+rtv9paWlWLx4MZwaqpYDQEXV64iNGY+87B8ZWk+z6sRBuRL5UgZihOB7KzHThJnfGQevKxaWtz6A4PUF7QMIcDimYuy4EkPVsNt8Iu7bloa6po8BQYAAERDEM393fC4IItD5t3D2PkHq/Lzzvp5tu3zedUwI5h6fnzun0A8Xv5/O241q278BAD9tH4Ok8gt6bedy1wJ4PuBYP9n7Pdis+ot8/HTvzbBKMmIFE86T0mASAUUN/H/TBB9c7YkIx//gttYUQ/2aJl0fhtlpuGIwlIiIiIiI6IxaZy2KHEW93lfkKMLt+bezamgUS7OlMRxMRET9ory1HHduvTNgm99d8jvkxeUNzIIoolS1V+GxPY8FbLNi+gqMihk1QCsi0kfVEIasOexGQlMV1BMNoc1V0wjvC28BEwK38721GV53fEhzUW+Cf68zsw5gbHwdTJIXkskDSfKhpj0L2P2fAfvZbK2wWFzhWigRUVAuVxwAhOUo6NOTboAnZUz3wKXYPWSJrkFMUcPtnWFNCarY8/OO9hD6r0JeT+9VvodjezpOynhrXP45wb+c5EvwSx3Bv43lJzBOjYPNmql5DQ2e7hdsZ+fE4Zq787Du0ZqA/a74YQrOvzwOgihAGXczPK+/C9SfDjqfkJWG2vkPIWfbLyH69D9HKSYbauc90PG9GsZ8ig+/O/y7zs9XHV6Fa0Zd0+1knYKCAqxcuRL333+/5j3S1l4Gt6cWVoux39e3w43m1CbEnEwL2K7r/gAS4DMr8L3xQccFQEG45RQ4xt+D3IpXde0R2WTD0Yt/inu+Pg5tbW1wOp3n/N3e3t7lT0u3z3u20fJ6XL+O6rDnBku7fi51ub2PMKsgQhUEuL5W2TnyiYK/o+mz/RBV6ZxxFSX41/HU6RLY7aORlDBd17/opDceOJMLrxWgqapsrNgellBoB/0juVPGwDmq9xAtEcBgKBERERERUafVZavhVXq/ItyreFk1lIiIiPqFrMo47TkdtA1FJ5fswq7GXUHbEOmhKMHfyN63bx/GjBkDUTz7BqWqBH9T+fCXp5GVFQtRFFBf7sGHLwcPe5r+uh4ec10Y31Sl/jYy/SvkJkuQTB6YJA8kkwd2VyKwsyBgv9i4U4iJaRqgVVIwdhW41B246pc9cgvd0gDoelR4k6Ci2tSxITJ9Qudx4UaOCj/Y6MMpjwpZtUCy5MKnmlHlTAra78+O2YiRPDCpNqQiFe3e4Ce3vHrgZx35JbMZ8+/KQEaSC+4/fAAg8GNRpWMGhKwRyE/7BNYWh7Z/WC/cKWPQcOlPhnX4r7+Cf1U1azEm5790HxcOAFarhCU/nghJCh6Ozci3ngn9AWLOSJjv/Aa8v3ojYB/TdxZAumQyvKKA6qTHkLlhha7gn2Kyofrax+BJHa+5z1D14YkPUdFW0fl5RVsFPqz68Jzw8OzZs7Fq1Sr8/Oc/h8MR/P9cfv44/NddU/DmH0/C7db/87LVKmHRLePw6W8DV3ztuj/kL47D9+ZGTaFQAIBPRuv75Si/+WFkH30VluaqoF3cKWNQO+8B2FPHY4y2WQJSVRUul6tHkDS0P16vFx0XBKlQVaXj0iAjrxfsACYDGAWgS7FMNcWD1vmHgBMADgDQ9pDRqbHpM6CpBDZruq5weVfNqhMNaScxXspEc23fFWLN0FI9tn9ES7icQsNgKBEREREREQJXC/Vj1VAiIiIiIhrqSktL8fOf/zxouyeeeAJr1qxBYWEhCgoKcLy8GS+9uD9ovwN//AzyuwomZVjhPt6C2bKIjfj/2bvzOKmqO///r3tvrb1vQK/QQIPNqoAsGnCLaxbJTFATZ5zJhhlnJnH0qybR+cV2JpqRkDhJxiSKiSYmZlCTUZIYcYlBXBAVQRZRmqUXet+32u/9/dFU0013V9W9Vb1/nj54NF11zrmnm7K6uu77fj5rI85JVXtQLZ1NFrFSlCA2WwBN82Oz+fsFOvvdduqj0eGB9yOvl55WT1r6wEDhKBamEwlSHNL4U9Pp6rmhU/8fasg/5nhmKCqG5sBQbRiaDUO1Y2h2UG0Ymv3U7fZTt9v6Pqfvc/sZ407dH/67autdX7PhVm38XrUTUFXWf/gf4KsHwJGSyxMrfoyqOTE0O9uPneBfb76Fjm4P/hjyWV955XTKJysjl5kFnycQiP5z4Pn6JUBvoOvLf7eImhcCECWU0xHIJKvIziUbc5hW3BswtH/l6piDf/Ut51P47C1SETKCkQr+FRYlcf0/5PN/T7WaCv45nRo337qUWcVpNFf6oo6vO+IjM9/eF/4Lf4xEnZvXN85TuILq9Q+Q++J3TAX/pkIo9MzQcNhQ4WHoDRBv2rSJz3/+8xHXveuuu1i/fj2qqjItp5kf/uB9S4+RvMxkIHIwNEyvaiCwZRv4hy4sMSx/gJ6t71Lz5a9R/No3Iw6tv+AWOkuvSuhzhqIouN1u3G432dnZCVkzEAjQ09MzZCXToT72D5X2v6/d2U77J4cJ6S879ecEpoOhvQxO1j1FcdFX0VSn6dlOp8YXvz6fFM3Jk3cNX3U4MEaxu6kULhfxkWCoEEIIIYQQQhC5WmiYVA0VQgghhBBCTGS7du3i9ttvj7lS19Hycr5x07/yr39/Ox++2cOsQJB6MiPO+aS7gfyAD6oAFVqN0W7ZHj1YlJTUis+XAhM0/KYoIbRTrdjD4c5w1c7TH8Ot2nvDnqoaY2UrwNYjVaqnqqfdARTgWo/56nxTWTApG0/+2WeEMU+HL4kQxjRU+8D7w38P398/uKna+1qJj7bnqp/jxKlQKECFt5Y/dX/QF/ybuySHsu/2VoM0YvwZA+B2u/nPe/+F3BkLePBH+6mviz63sCiFG29ayKziNErO8kUM7MCZbaB7mQn++XPmUXuFVIQczmgE/xYu7LD0+Gg84efFGCqX73i0hf0vdQ4ID5vlz5lH3eV3M/PpGyOOG4ng33h2Zmg4bLjwMDCgWv1wli5d2jdu0ZJs7rp7haXHSEu1P4avordqfuDx582HQsP8AYJ/fAMyIg/zzVg0IR4bdrud9PR00tPT41rnaOdRrttxXcQxc+bM4VjjMUvre301VNU8TlH+DabCoWbC5d16EoaioBgJuMhNiW2NqRQuF/GTYKgQQgghhBBiyoulWmiYVA0VQgghhBBCTESHDx82FQr9QelFLE/Lxaaq8N5B1rmgxuZkdyByMHQsuVztFBW9F3VcQeEBsrMrqK5eitcb3wnt+Bmnwpu9lTuHCnf2r+apaQE0bexaVoqJSUdBR8NAwVA0dEXrrTqJ2vtR0QgoCvenVYAClzIXVdUwFA2U3jHHK6ro8XoJ6nC8I3rQ+JkKJwd6ziaEim4oNPpSos75xYmPkWLzEzIUgoaKbqh87MIFEOV/64Pzb8e/0one2EHg8e0Y/hC6Hj1Yc7J6EXNL3oo6Lpr6i+/AU7gi7nXGq1iDf+bbQJf0VaUG+Nq/LeXfvxn53+OLXynlgosKUMOVHWMoVdy/DbRVUhFyeKMR/JtVnGb68VF1wMPzP2wk6IstaNVSFeCZe+u46uZp5FstqhhDoG+iBP8SYbjnjrDhwsNWWHmMmKF/WIFREz1kHInR0Bo1GDrVhPToFyNd97nr+O5b37V8jO6eck5UPcSypTfT0R79+cBsuDyIjUp/LrPstZb3GKbOmxl1zFQLl4v4STBUCCGEEEIIMeXFUi00TKqGCiGEEEIIIcY7IxSC9m6Mti6M1k701g4+/O1T3Fm4gmmOJDyhALccfiXiGjmOpN5Q6ASRnNLIzJl70LTYql263J3MnrOLyooVdHfnJGgXBqoaHBjk7B/wPBX41LRA3xhNC4xqC3ZpFW5NnUfj3VY3hqr2nohXNVBV0Gwoqoai2VA0G6qt949mt6Pa7Gh2R+8fmx3N4Tz1uROb3YHN4cTmcGFzOrE5nCjhIKbaG9qkL5ipnTpu/4+nApvhj0rvfoxB9/X+PZYH2XPVz3Fs77cB+M0l1w4Kc9UePszGjRtjDpff/04Tc2ctxuXMi/n7/ErTggGfFxalcNXKZfBM5IqQqWefhX+6A6aD/oVpBB7eBsHo7/N4PFl4Pam43J0x7/FMvqzZeAqWWZ4/EZgJ/lmpBhkWS3izZH6G6UBXokhFyMFGM/hn5vHReMJvKhQaFvQZ/PmHjfztV+0kW92o6DPcc0dYpPCwGYZhYGBgxFBt0cpzSJOvCdtf32K81dLWDZ3XGl7r+/rDtxkYfbctzVxqqcDFtqpt+EN+jPB/xsCPq3JWUZJWYnrd3x77La3+1r797mvZF3VOZ24nJSUllJeXmz5eWGFRErd9YyXfvnN3xHFWw+WH/XMTEwxdUQrvRh4zlcLlIjGmTDBU04Z+sXHuuefy1lvxXwmWKCtXrmTPnj2DblcUhWBQrgAVQgghhBAi0cxUCw2TqqFCCCGEEEKIsWIEghjt3dDWSV1zBf/d/EuMQAD8QQgEMfxB6Hc+4WuHlzPDm8wV7lxw9952rKdtbDY/QlyudlOh0DBNCzFz1rscP7ZmiMqhBqoa6lfFM3BGNc+BLdzDVT+VGFtAjpZaVef7qadbHx+x6ShASfD0CeX/1+kiL4bqihNNa0sBTmc3WdnVca8V2nAfZ41ARUgd8J/6M5bODHcNFeYqLS1l8+beVuGxhkNP1j3F7KJ/QlXNx2mcTo0bb1qIajI5rZXOQrnlOvy/+CM0tkUZrXDSdwGzU15CDUVuFTsU3eai/uI7JnVAw0rwz2w1yAlFKkIOMFrBPzMM3eAvW5pMh0LDgj6DnVsbuDLB+wp7ufZl1GApH5v+MdNzdzXu4t3mdzEMAx2976Nu9P49x5XDF0q+YHrdHXU7eLbqWQzDIGSEMDD6Aoa6oZPuSOf+FfebWjOoB/nxBz+OOs5qePhzOz4HH9AXMARwtk2nhFtNrROLW17/GlsPnQeMr/+vdUPn1rcjf72bVmyydA7jgUMP0BkY/qKJby35lqVg6FMVT0V8zhjK05VPs+nuTXz1xq/G/PqjP7fbTVlZGZot+r+f1XB5TWg6LaE0srQO0/sLU/JzUIvzogZDhTBrygRDDWPo/2GHu30sjcc9CSGEEEIIMVmZqRYaJlVDhRBCCCGEECPB8Acw2rswWrugrbOv4qfR1oXR1onR2gldp0+ItqW08Ze1e0CjN/TpHrzml8qXjNr+x4ZBYeH7pkOhYZoWonj2bto7p2Oz9VbytGm+3oqeqrU1x5M21eCRlMGxw7/2+/uXu53kRe8MPqbebjiPVLWHOWo1hGz4A0M82M/Q3DwXMEhKapeKkFGcGe4aLsxltlV4YVES1/9DPv/3VCs+X+z/PzmdGjffupRZxWm0VJuPzapF07F/5dMEvvt4xHG2z12Gfv5iamsuIG/73ahBb8Tx/ek2F7VX3DPpW4XHEvzbfnI7VxRc0VdJzq+PXNS5qrsKb4ed2amzTQfJuoPd7G/dD4CjuYuFI7FB4Pma52lozwB6g1s6OpfnXc5093RT64SMEP/zwf/0rnMqBBiu2Bf+/DMzP8NZ6WeZ3mPZ3jK6g919a+roYJw+zrXF17J2xtqIa0QLDYfds+8eHv7oYQwM/m7O33FN8TWm9/uVN77C4WN1zOXfoo6tPuilpcrce71n8jSqkBLXEsN66KOHSO9caSkY+m7zuzxa/uiw989Pm28pGHqy5ySv1r867P3TnNNMr/lCzQs0+hqjjrMaHu4fCI2HoUdfZ0FdKTZjfIVCobe4XDRWv09KlMryI7XuUOo8dVSkVpi+OAV6Q6GbN2+mtLSU6uqumOZYC5cr7PSs5BPJf8WuWPj9wWHHfsOVKGqP+blCRDFlgqEQ2xPjeHDmPiUoKoQQQgghxMiwUi00TKqGCiGEECJRcpw53LH4jqhjxNSUZk/jmlmRT6Cn2dNGaTciHoYv0BvubOuC1v6hz9PBT7pjDyUJsNl6SEuvjyv017tOgOzMkwnalYhkV8sc3mubSXcglaRQPp5gKi3e6D/j/nryEwDkafV8POlNEyfdFarrlzNnzi5UXSpCDmW4cNdwVdystApfuLCDB3+0n/q66GGOwqIUbrxpIbOK4/vZFkvbaXVuHoqq4ClcQfX6B8h98Ts4OqI/F/iyZlN/8R2jFgoN6kECegAdnWSb+QbXe1v28m7zuwT0AH7d3/fRH/Lj1/1kO7O5ddHgqnOxBv++vffbfHvvt0/f0GB6izG77e3/hy+jgZcvf5l0x5mVniM72XOSf33rXwGY3ZnO43xyJLbIL478gsP2gWn7RemLTAdDAR4/FjncvDJnpaVg6Kv1r9IRGL6y3QW5F0RdI1poOCxoBKnq6Q2StwfaY99kP70B1tiuYDjwcnyvCUaD1VCdGuVnkW5Yu8oj6roxfu/DYn3uCLNaNTRejSf8vPiTpqjjVh/aACmvjMKOzIklZGk1axR1bYsRJquZrS1HtvDURU+ZujilpKSEsrIySktLTR3Lari8Rc/g5Z7zTL5OpTcUeuPVqEXToeWE6eMKEc2UCoZC7xOfoijjOmzZf48TJcwqhBBCCCHERGSlWmiYVA0VQgghRKKkO9K5tvjasd6GGKemuabJa84JwPD4Tlf1bDtV7bP1dJVPva0TxTPWzaLHr3L/TOx2L0vch0l1dGDT/IBBR0d+xHnFs9/B5Yqt+o9IrPeaghxpD9HsNegMZWC4VnPSkx113oPHLgF6K0L+w98u5INtPlMVmRptuXRd8zdk7ngphjbhvW059Rv+nlrlE1IRchjDhbsiVXEz2yp8VnEaX/u3pfz7N9+KOOeLXynlgosKUGMIdSaaP2cedZffzcynb4w4rv6CW9hbMJ9GXzP++lr8If+gwGV+Uj4X5V5keg8Pf/Qw26q2DQhuhgOhAMuylrHl/C2m132n6R1+9tHPhr1/ZvLMIYOhsQb/xoKVYJ06hm2gzQbrILbQl9UgYLyhL7PBv75lLWY0ogUXw4J+g8p95ltNjzbLAc4oj2ErjzOIoTqkyX83s88dVquGxqPqgCfmVuGBcRqriikYarWyZ5Sc0kg91obT9xgpvcr0xSlmxRMurw3N4Lnui1jnfjumtvJKfg72G67sDYUKMULG5zOYEEIIIYQQQoyweKqFhknVUCGEEEIIIayLpXWjfrQGZUZ2TJXfRoJhGODxDWznfkbwU2/tRPFFvuBsKpWACKLSabgIqCohFTo0J3RHnnPFoifITx5Ypc/rTYkaDBWJ4cueS10whb+8tY+G7gAftUWvcvTPO04Hb9xu+M//uJryP3QC5ipCnrXEzws/aaSjLhh1XlaRnUs25jCt2EFoXmxtwrXzF/dWhGT6uK4IOVaihbsSWcUtlufxacXQ4Kvvq2QZ0AO0tQeBkamM/b/H/pfr8/61/yajzvHNWMQvyrewvWb7sGPWzVhnKRjaFeiizlM37P1WW7TbVXvE+4e6aNpq8G+0WAkYjmVBJkv7HcehL6uh4RELsp7iaQ2hW+jiPNosfx+i/LuNVPDWTAjQ6nPHaFYNbTzhjzkUCtCtJ6EbCqoyvorPjWkr+ZGqRBpB+DESC6v7S0S4vEXP4NnuSymwN3D5ylo4dBz0fv8PqSrq4tlo685BPWvmmP2eK6YOCYYKIYQQQgghpqR4qoWGSdVQIYQQsQjqQToDkSsOpNpTsanyVp0QYurQqxoI/OKPUccF//clQq/uHZFKKoZhQLf3VFXProEt3du60Ft7q30qgciBtcl/Ks9AVYPYbH5stiBEKX4zZ+6blKbV9H1e15PPq60XRpwz3k60T0S6PYmQK42QK/3UnzR0VzptWgAafxVxbv3Hv0VK6lyMore4/7bb8Hhi/13Z7XazefNmVq9eyty5naYrQk4rdnDl13J48q7hw3AAF34piwUXpPSdPDfTJjzMTEXIztKrJl37eMMwCBkhAnoAm2rDrtqjhrvOrOK2rWobbf426ioi/3tZdeMbN+LLGNiHPKO9iM/y3yNyvGZ/s6V5DtUR8X6r7zeN1bpDBU7Hc7VQsBZ2iieQFC9L+1UUFJSIcy23JI9SeTJSqCqe0HDIsJbaNFMxdCKwWm0xasXQcRA4tfrcMVpVQw3d4C9bmkxVKw9ioyqYyyx77QjuzJqozxEjFOC0+twTz9NwZXclj+18jD/995+ijr3vvvt48sknTbeST1y4XOFkYAaeTy8j44tgtHaA1w8uB0pmGooz8gUbQiSSvNsshBBCCCGEmHL8IT/bqrYlZK1tVdu4ddGtUasvCCEmt65AF7sad0Ucs2baGlLsKaO0IzGeVHRXcN2O6yKO2XrhVuamzh2lHQkhRGLFcsKx7oiPzHw7iqoQ+qCCwJZt4I8t4GLUNOF/YCv2G6+GGLOhhm5At+dUpc+BwU9OVfk02rpQgpHP/E3O0KeBpkX/3k8vOkBxjoHL1oNN7f0+2bpzoGF5xHkOzVpFO3GartkJuTLQzwh6hlzp6P3+HnKfvg9t6OBXR+dR2BE5GBq2evVqtmzZwre+9S2qqqqiji8pKRlwwj2WsGbJ/IxBbcJjqXiVW+JMTEWlGCtCmgmFhp8DzVYjDBkhXjj5AgEjQEDv/RPUgwM+v7LgSkuvEa/bcR3t/va+dcJrht215C4+XfTpmMJd/au4/fzIzznZcxIaok6bEKwGLaO9B+QPjUxlT8sVQzVz6473aqFgLQAXa7hwJMRTtS/S3BELAkY4Zjyh4aOdRy3Ni/XfzuaYGK/cxuLfLZJEtaiP97nDTEVIqxqPBmipMv/cf9g/d2IGQ0eoqrBVihHHukfhZ1t/hhFjALy8vJyNGzeeuoBpdUxzEh0u93t1FKcTJTc7oesKYYYEQ4UQQgghhBBTzsmek/h0X0LW8uk+TvacpDilOCHrifGrzlPHA4ceiDjmloW3kOvOHaUdifGk3lvPN/d8M+KYrRdulWCoEEKIcS2W1u5HPmwjPz+5L9jVeMLPCz9pijpvx6Mt7H+pk0uvNkjeGnsotI8/QODhbTi/8rGoQ73/8zS+ZhtKKPJJ7IkRHYhfXt4HzAqqaLYANs2H3eZHaw3Ce5HnpbtaSXGMfDvPyc5Q1L5w56CgpztjyNsNmwsSdEI+FEPZo/4BldLSUjZt2sTnP//5iHPuuusu1q9fj6qO36qar9S+QptfHRC4/HzquabXafO3ceObN/auoQfw6/6+v4cDl1vO28Ky7GWm1/7/9v5/Ee8/K+0sS8HQZl8zbf62Ye8PGIGYw139q7hNtotig6HIFaGH49ScEe+3XNlzmIB3vOvaFXNB1vFeLRTiqFY3RuIKAo7Al2q1TXS8wb/3Wt6zVDU01mqv7kwNVSMBFf+if9P1YzUoM7ItXbQwYi3fLT7OErVuvM8d4Z8385lveY1oTuzyWppXE5pOSyiNLC1K6fwIKpM6mGd59tBG6jkizZ5GUA/2HUNB6XucKCi4NJeldaP9nBtWLfC/YATMfbEej4fbbruNLVu2kJJSGHV8osPlDtf4fZ0spg4Jho4zodDpVyn9U/gjlcgXQgghhBBiKipKLiLdnk57oD3utTIcGRQmRX9TQUx83cFuXq59OeKYG+dHbkkohBBCCDFeVZzo4MEf7Y867rGfH+alF6q58aaFqF12nv9hY8ytGFuq/Ph/+TLJqrVgC/4A/kf/ACWRhyUHqvGHipiY0U8DVQ2haX5sNj+azY/tjL9rtt7PbZqfNKeH9Z7ewE+VprPH0XuOYblfoyjUeyIyL7mZ1JCclEwEAwXdlTqggufgYOfpNu4hVzq6IzlhIU8r3m56O/qYxreZl3Y6qhBL2LM+p54nK57kuuLrTJ/DOtx+mP/a/199wUpHUzYfI/JFVlb87MOfcTx14O/9V539A0trHes8FvH+gGH+eU1TNDRFixiSChrWgovRgoC+kI//Pf6/Ma8XruIWrSX5RGPl3w1GsLLnCFUiNdOifiJUCwVrwbpoVRFH0ki1c7YcOI227jAVIuMN/nUEOiwF/zQltgtVbA6FmWe7ObHHY2V7AGSpbVzkfivquOBvXyK0Yy/2G65ELYqxpD3g1tzYLIbqMh2ZlKSWoCpq7x9UFEXp+zjdFfs++itMKuSqgqv6wn/hNcPHcaqRw/CQuOeOLUe2cH/R/VHHfW3B18idmdu3V4D2etj23PBzVBQaPrT4ewgKOz0r+UTyX7Er5pPHhkMj42+vgN37LB5/aDuu3IES/k854+Opv1vx1EVPJXSf0PsY6Q52m5+oA/8HWPyn83g8lJWV8b1ND0cdm7hwOagapOTIRXZi7EkwdJzp7u4e8snZbp9cV+AJIYQQQggxlmyqje+d+z1uf+f2uMKh6fZ0Nq3YhE2VX62EEEIIIcTEdWB/Mz/6wfv4fLGdAauu6uIHZftZqBVipnhZvtZApmr99bfL1U5RYZQyl0BB4QGysyuorl6K15tu+XiJ0du2fUCos3/Q0+bvC4GG71fV2EMeM4FftiQTxGDN9M6+2zsUg1+0JKFNyHDs2Ai6M+kpOnfYoGfIlY7uTO09yzvOvNf8Hq81vIYn5MET9PR+DHnoCfRwsP1g1PlPVz7NdXOuizl4A/SGP9phw6wN2BRzvxN7Q14OtB3o+zzDazWkYV7QQqW6WKpkWq3kaFNsEYOhI9Xq/FDbIVPhrnAVt0lXMVS3Frw1E7RM5LojFTjV0QnqQWyqbUJUC4XYW1v3N1qFmNLsaWQ51AFV9qz+v7MgfUHfc4SqqANCX6qikunItLTuBbkX0OHvGBAqDK+tojInZc6gOaMd/OvvH+b+Ax+zNfFchNBf2OKPp1oOhuZr9VyS9GbMwT+jpgn/A1ux33g1WumsmOb8cu0v8WcVW9rfZ2Z+hs/M/IyluZGcm3Mu5+aYr6jdX6KeOyq7K3m94fWo49ZOX8vcgoEVtav1Lraxa9g5TuxYzFID0KJn8HLPeXzcxGMEAIcdx41Xkz7dgN3Wjz8Uq5U7x4Llx8gxoCG+Y5eXl7N/f/SLIBMRLg+bdY4bu1MuzhNjT85ejjPt7UO/KeZ2u0d5J0IIIYQQQkxuy7OXs/2y7RzrOoY3ZL6FjEtzMSdljoRChRBCCCHEuKTr0c96vv/++6hKjqlQaFhRaBoxHKLPMsdBSh2RK+5FkpzSyMyZe9C02Pbpcncye84uKitW0N2dY/m4Z1IUHW2ogOcZlTz7hz5HI4fyO3eAcvvpf5Byu87v3AGu9Uyu6n4jqf6Sb+IpXDGix3i94XV2Ne7qC2/2hHrwBr19Qc6ipCI2r9xset2DbQf55dFfWt5X/1bhZgWNIDaTpxvHMlwYtBDYi1Z9E+ILcPp0X8LXjfZexe4m88mULUe2kOXIsrSf8WqkKoaOt2BomiONwqRCHKoDu2o//VE7/blu6AkL/mU6MmmlNe51hvL9lT9gRr6THKf5n+35Sfm8fPnLvQHLmhZ4/XcRx1ttFf7I+Y9YDv6d6dG1jyZknTN9a8m3TM8Z7eBff+fmnEuut4vnIoT+wgoXucgqstNSZe7/wyy1zVQotI8/QODhbSi3XAfJ5qZOFomuNPx0xdMJW6s/NQEXTNWGZvBc90Wsc78dU1t5JT/ndFXZlhNxH3+iiusxEr34fUxeeOFFYG3UcfGEy/tb9PHUuNcQIhHkDOY40t7eTkNDA4qiYBjGgKuWsrOzx3BnQgghhBBCTE421cb8NHOti4QQQgghhBhL4apRkSr7HT58mG99K/oJ/3vvvZcF8wKoirmgT7qSRLLiRCNEqtqFS/FSF5oRcc4s+0lcqrVAi8vVbioUGqZpIWbOepfjx9YMWzlUUYK9Yc4zA57DhD41zVp1uZEUxOB7qYMvdtuU6uWzHvuErRqqa9HbltZf8i0oyiP3hXtwtlZYPpYvazaegmV9n79Y8yLvNL9DT7AHb6g3uNn396CH0oxSvrv8u6aPs791P789/tth77faathti7+4SLhVuJmqodDb2tpstaqxDYaa/384lgtCrVaeHKmAYbR1rXRPqeyuNF0ddrwLJKhiqKZoAwKXmU5rVRwXZSziX0v/FYfqGBDidGi9nztjeF4cyqqcVTxzyTNRxz1X/VxCgn+t/pEJhQIUJhdSmJpiaa6maKQ70tGrGgj88mWiPeNabRU+GU2U4B+AoipcsjGHZ+6tI+iL9eeqwTr325ZahAO94dDHn8d54zpr8ye4RFcarvPUJWyt/vSo/9fHpkXP4NnuS7n+xhDuQwfQDxxnwBVzqoq6eDbaunNQz5ppOlw+GVl+jPiBI4nZw7vvvsucmdGDoVbD5f1lFdkpXDhxqrmKyW1yvXqf4N55551Bt4UDojNmRH5TTQghhBBCCCGEEEIIIcTkt/3kdhSUYSv77dq1i9tvvx2PJ3qVE7drpulQ6Ofc7cy315Cu7iNZ8aAo0BpK5Znuy02tEzuDwsL3TYdCwzQtxKzit2lvz8MWbuner327mbbt49WZ1ULDJlLV0KMz/4HQuWnoSRmn27c3dcG9v4o478+BCl4/8Ty+QheG5qGbINNDKo+1xl6yS7e5qL/4DlBOt3rc27KX31UMX0kuw5ER8/r9RQtQ9oR6LK3r1uIPhlqtGmql4mK0qogjKWiYDwKqioqmaGPS8n2k1rWq1lM7IuuOlUvzPm5p3jXF17C+aH1fxU2zgerhzEubx7y0eQlZy6xEB//Gq9AHFQS2bAN/bP9vWWkVPhlNlOBf2LRiB1fdPI0//7AxpnBovtYQU/XHSIyaJvQTk+s5MhYj8twRQ35z3759zJ49G1WNvVW3jwCKSlzt5MNUTSFp5Wzsa+di+AIYrR3g9YPLgZKZhuIcu4tgxpu4HiNtQIJ+XdP12H6ftBYuP83m7J0vgWAxXkgwdBz57W+Hv0p0zpw5o7gTIYQQQgghhBBCCCGEEONN/5NqQ1X2O3z4cMyhUICiaetJwUWSojJDDZGi+HgzSmbqLHsd+bbh2x4nmtvdisvdGdcadrufnBzr1STHs+GqhYaNRdXQDwv+BtfyGRhJGYTc6TS0pMB7kQOPv8o6wu2zbjrj1q6oxzrUdog/9Pyx95NThfRKA7GfwNVtLmqvuAd/zsAgVrSgpSdkrb1k1HWDI7NurMJVQ82wElwcy6qT8VT2DIUiBENHqiW5xXVHKnzrCXlIs6eR5EqijsQHu7599t3kFboHVMv01Gm8vN161a5IPp5vLRjq0lymK+WOd4kO/o1HelWDqVBonyneKnyihoYLF7v5zF25/GVLU9TKf6WOowk5pv7u4YSsM5Hsb91Puj2dJRlLErKep9pD5dOV+IncaeC+++7jySefpKysjNLS0pjW1jGYfpad+g/i/5ky6xw3dmdvKFVx2lFypQPwcOJ5jPS093CUxPz/aYbZcHmYzalw1c3TmFY8/i/ME1OHBEPHibfeeotf/epXA9rH97dgwYJR3pEQQgghhBBCCCGESIR8dz4/W/OzqGOEECKa/qGNpz74A8vVi2ht89He6qO11csf/vAK07Oux2ZLRdd9HK/6acT1bkxrY1HyAZKVHlQFaoJO3uw4azS+lJjl5R0a6y2Ma8NVCw2Lp2roV/IdGLkq3YToMYJ4jACftK2Cwc3PBnB/7JP0FJ5u86v3+IHIwdDOYPQQ6FDiCWb5smZTf/Edg0KhAC5b5HUtB0OjtHz3hoYP+cazbqzCVUPnMz/mOVaClmPaSj5C1c9I7Ko94r+PX48cYBmOU3Pi0lzYVTt2xY5dtWNTbX2fp9vTLa17bfG1XJZ32YD1VEXlR4d+RKOv0dKaYRmODO5fdT+f5/NxrTOURZmLKMwc2Ca8xekHpl4VvtE0UYN/Zhi6QeDx582HQsOmcKvwSKEub8jLsa5jEefPSZkz6Oe11+PlSKL6Q0cwrdjBtf+ZR/UhLwdf7qRir4f+RQNVDWYvtTPzeH1CqhLq5SehJP51JpJl2ct4dO2jCVlr165d3P7g7fg9sf1MLS8vZ+PGjWzevJnVq1fHNKd4jSshwdBFH0+Ne42pIp7HyLH8Y1z7wLUJ3lFszITLobd9/CUbcyQUKsYdCYaOscbGRn75y19y7733EgwGURQFwxicOF+zZs0Y7E4IIYQQQoipwxP0cLDtYMQxizIWJeyEm5h4km3JfDxKm7lk2xQsHSEAmJs6l3c+FSUlIaYst83NuTnnjvU2hBATgMcTpL3NR1ubn9bW3sBnW5uftlYfLW09PD//fyCpd+yP9v6MxX9Kx4UTJzacip1S7XxyMoJMU70E/CfYHOV407VmUtWMkf6yAHC728hIqsVu92K3e7Dbvei6SlXViojzVG3it3ofjoGBDpaqeX4zvYdyW4jXHNFDbv+VpXBpyhUo7szeFu3udBoaeuB334k472CoGc44B9rlGJnKo76gtUCk1WBo/QW30Fl61YD28f0laUkR51ut7BltXZ/uI2SETLelTlTFUOitGnp/0f0xj7dSMXS0gqEOzUGqPfWMwKW1U6P/OPcfCRrBvrXO/LMg3VqBlycvfNLSvGiuLLhy0G3PVT8XdygUegPErze8Hvc6YvyIFvw70hk5wDcvdd6A5+PRCv2ZoX9YgVHTFNcaU7VVeCKDf2FHjx7lOq5L6JrDUVSFosVuiha7Cfh0uppC+L06DpdKSo6G1tKK/96E9apOzDpTkNnOB2Eej4fbbruNLVu2kJJSGHX8tLl2sorsMQX9hpNVZKdwoYXXoDH0sHfVHcSfOXPY16hTTV5eHpqmRazaHitVNff6GmILl886x82ij6dSuNAl7ePFuDThgqE7duxgx44dCVuvpqaG//iP/0jYepHouo7f76e9vZ2amho++OADysvLMQwDwzAGhEL7Vw5NSkri/PPPH5U9CiGEEEIIMVXVeGr4p13/FHHM1gu3Mjd17ijtSIw3ue5c7l8R+wlSIYQQIlZV3VX8v7f/X8Qx31/5fYqSi0ZpRyKRDMPA4wnR1uqjrc3X+zEc+Gw7/ff2Nh9e7+mzTBoqTmyQ3EXFsmfwFbXQk9TQd78/rYnGK37ENE8K1x/6GLP9KqlqN6rS+x7zMaVtxL82RQlhs/lwOXTojjy2sGg/uUk1A27zelOGGT2+BOj9ntotBDhvyuimVjPoUQy6VIMeBbqV3s+7Vbi/zc1Xu50R1zAUlZArjZCrtzW77krn1cBODumtMe3hGN38pmQxVxVe1XebV7PWktGrWwtwRl/XZ2meU438vRuOb8aiiCfcR6qVfCxBVk/QQ4rd3P8bibyAMdbQX5ItCZfDhW6hxFqSLYnrZ1/fF6rUmtKx1uA9ssfXPY6alzPgNkfLCUtrfaHkC/FvaAwluiLk0xVPJ2wtMfYiBf+Odh7luh2RA3zfWf6dAe+XjWboL1ahnfsSss5UbBU+EvQYApT79u1j9uzZqGriAnJ2p0pmwcD1dJ+1is8icXRdp6yszHQoNMzj8VBWVsb3Nj0cdayiKlyyMYdn7q0z1SI8zObsnW82AOhoOkLuS5EvygKYvvMB0g8+M2xV+8kuqAep7qmmKLkITdFwu92sXbs2IRmxFStW0Grh+pho4XK7U0K8YnybcMHQv/71r9xzzz3DtlyPJBy67F+Rs7a2lnvuuSdh+7OyH2DIryccFv3Upz6F02ntzQ0hhBBCCCGEEEIIIcT45tf9UVswWm1RK0aOYRh0dwcHhD3bT1X6bGs7/ff2Nh9+/+CT33Y0HKcqfTpxkKsk41RtOBQ7LjTSVR9pahc9ydV8f+aeIfdQlVVFFfBvx2eTHsoY2S/4lLy8Q8xN6638abP3Pi7revKh6ZpROf5IuT6ri7YhgpvdikFAgZ+1JPE5C+3YX3MGqbINf9K5LSOfzrxzCLnTe6t5utIJuTP6fUxDd6YOCjFqr30R2mILhkJvFcjLCy43XYnyTP6QtQBnND6LLdSd2sicO4ml5Xv4HE4i1w2vbTYYmmpL7avYd6TziOWW9GGxhP4e/dijzJ1r7cJJl+bi1kW39n3ekuxnq7QKH1Ev1LxAZXdlwtar89QlbC0xvmmKRoYjI+qYcc0fQD9wPCFLTcVW4Yl2+PBh7rzzzqjj7rvvPp588knKysooLS0duQ05pe3zWNu9ezfl5eVxrVFeXs7+/ftjGjut2MFVN0/jzz9sNBUOtTkVrrp5mulW4e7qd8nbfjdqjBXynS3HKXz2FmqvuAdPYeTuChNdV6CLXY27ADjScYQnjj+BJ+TBrbm5fvb1zEubx6f+5lMJCYZefvllbP2NtfBx2FDh8oSSqrJiBEy4YGjYUO3Wx3IdK858w2C4vXz9618fje0IIYQQQgghhBBCCCHElKfrBl1dgd5wZ+vpcGf/6p7h4GcgMPyJGwc2nNhIU5JxKOEA6OmPqqKQrHhIU7tIUztPfez9k6p2oym9ax9ztY3Y1+pydZCW7jnd2j3ogo6zIs5JTm3GndRh+ZgBDLoVgyTDfPEHPwb/L93Dj9sjt+O24nVniHZ1+PMF3RHuCzmSCLky0PuFOcPVPV31j4G/Ydi59SUXUl/6z6b32xPqMTW+sruSF06+MKBqqBVWK3uO1LpWW8lHE61iqIGBT/eZPn6GI4NFGYtwa+7ePzb3oL9b+ZrykvL47YW/5bnq5/j23m+bnn8mCf1NLomuFiqmluKUYl66/KWx3kZclI7OxLX4llbhcdm1a5epduHl5eVs3LiRzZs3U1CwaET2pGSlgaom5t82gdVNp5KnnnoqIeu88MKLwNqYxhYudvOZu3L5y5ammNrKZxXZuWRjjulQqKPpiKlQaJga9JK3/W6q1z8wqSuH1nvr+eaebw663RPy8PPynwPw23W/paSkJK7wcElJCUuWLGEruy2vMdKkqqwYKRM2GGr2KszhQpdWKo8m2pl7C7eUVxSF9evXc955543RzoQQQgghhBBmeDweamtr6enpISkpiby8PNzuxLX0E0IIIYQQ1um6QWen/1R1T/+goGdbv0qfoVDkggIKCk5suBUnTuw4FduAjw5sp957NkjqC382Dwp/2pToJ6BDRC9uoA8YY/S2d3d1Rp1XVLSPmVmnq3x1dOdEGB2fy3I6qctoI3DqLfk/NqZwrsmihnbgHcdINJyGZAPaI9zfVLiMxuyLT1f2DFf1dKWBNvwJYsdrf4oYDLXSkjyoB6npqTE9LxFVQ70mT2rHymdx3ZGqGJrjymF51nJcmmvI8Kbb5kbB/Pmlualz+eXaX47AjiX8J4a3v3U/6fZ0lmQsSdiaXo+XIxxJ2HpCWGXo0V8ntRztpmAU9iIiO3z4sKlQaJjH4+G2227jvnt/MiL7Upx21MWz0d8/Gvdaaok80szyeDy89tprCVnr3XffZc7M2IKh0Fs59Nr/zKP6kJeDL3dSsdeDHjp9v6rBrHPcLPp4KoULXabbx2PozHhlk+lQaN/xg15mvLKJqg0PTenqkKqqUlZWxsaNG00/fwC43W7KyspQxnFwW6rKipE0YYOhkJhqn2NZMXQo/YOqM2fO5KGHHhrD3QghhBBCCCGi0XWd3bt389RTT/Haa68RCp1+90jTNNauXcs111zDqlWrUMfxmw9CCCGEEBNVKKTT0RHoa+fe1nYq7HlGS/eOdj96DOEBABVlUODT0T/4qfR/a90gSfGSeir8mT4o/Bka9jix2JUTPQC4e/5uLm5LxW33YbN5UVUDoyVEtIIodZrOzTk9dJ1qoe7tcJId126H16nSFwoF6FHMvzevoOCy+JZ+yJ6Mb0Zpv3bt6b1VPU+FPB2H7gLP8N/r5vzFtM//G9PHTdIiVzf1BM2f3Hyh5gVLgdJEVA316T7slmcPz2rF0GmuaazOWU2SLak3xKm5meMLQsOrce1nUcYiHj7/4bjWGG2JbhUuJo9l2ct4dO2jCV3z6NGjXMd1CV1TCLMaT/h58SdNUce99Yce/jZlFDYkhqXrOmVlZZZCXdAbHvzJTx7EoW5I8M56aevOTkwwdEUpvJuADU0htbW1A95Pj4eum19HURWKFrspWuwm4NPpagrh9+o4XCopORp2p/X3893Ve3C2HLc8H3oDgO6T703p8F+zr5lVpavYvHkzt912m6nnEbfbzebNmyktLaW6umsEd2mdVJUVI21CB0Mni6Fayi9YsIA//elPTJs2bYx2JYQQQgghhIjm8OHDlJWVDdvGJBQKsWPHDnbs2EFJSQllZWWUlpaO8i6FEEIIIU6LparSkQ/byM9PRjVbEWUU/fIXH/BBSz1trT46OvyYvf7fhjog6HlmANQ+qKKigVvxkqZ2D6j62Rv+7MIeZ/gzfAxNC2C3e/tauyt2D3+aczDqzJ9Mb2aj7md2yHwlyN3O03t3qsaIBUPPZCUYCuC20IIeoO7yb0c8oeoqT4sYDLUS4ARw2SK3BTcb8Iy3KmS4aqhVvtDIBEP/Ye4NluYtzFjIgwseHHCbo+UE7IkvGDrRSLVQMZnF8tql7oiPzHy7+WpuYsKqOuDh+R82EvRFf3x060nohoJq8bXHAHLRtyW7d++Oqw00QGVlJSXFidnPmdSzZqHk52DURA8aD0fJz0EtzpNgqEk9PT1jvYU+dqdKZkHi/h9PP7QtMesc3Dalg6HPVj7LqpxVrF69mi1btkQ8H9PfhDgfI1VlxSiY0MFQM23gx3MreTi9v4yMDP7t3/6Nb3zjGzidI9MCRQghhBBCCBG/Xbt2mWp/VF5ezsaNG9m8eTOrV68e4d0JIYQQQgxWcaKDB3+0P+q4x35+mJdeqObGmxYyqzhtRPd0cH8Lde97aG87Vemz1U9KdyWbCyPP+/BwGxU9w8fT7GgRK35qQ540MXApPtLU1kHhzzS1G7sSTwtzA1UNDgh92h1e7DZP70d77x9VHRgw3er2Ux1j6/Rn3QH+rctcMNQ9hg21utXYDt4+/TxsgXexeVoAcFto3+3Lmo2nYFnEMW7NHfF+KxU6IYaKoSbXjbcqZLhq6HzmRx17ef7l5M3Kw625cdl6q3HSksE2Ev/AuXDGhQlfcyqJ1Co8qAdp9jVHnJ/tzMamnj5lKG3CxXgRa0XIHY+2sP+lTi7ZmMO0Ysco7EyMhFgqux/5qA1HwB5zKBQgiI2qYC6z7LXxblFahVv01FNPjfUWIlJUBfsNV+J/YCv4A+YXcNix33Alijp+Qo4TRVJS5NfKE5US8JBc+VZC1kqu3IUS8GDYI/++MhFFe40K8HLty3zd83VmuGdQWlrKE088we7du3n66afZuXPnoA5u69atY8OGDROig5tUlRWjYcIGQxPVAn48tJKfMWMG69atY/369XzmM58hOTl5rLckhBBCCCGEiODw4cOmQqFhHo+H2267jS1btpCSEiXtIIQQQgiRQAf2N/OjH7yPzxdbZcvqqi7uveddbr51KYuWZMf0Pmr1Bx4CWoD29gBtbT78VQ2cG2XObx7/iNrQwIqKs5N6IMpLJQc20hQ3Doaq+GlDHbZahoFT8ZN+qtLnmQFQh8XwZ//Qp9fVRWNSO/VJ3dS7eqhzeql1+DhpCxECXmhKjWnNIAbfS429csgjyT6+1uVEMxGcdOtjVzihJXsOndkr4Ejk73n7RV/GZ/9bCp+9BTXoNR1m1W0u6i++I2oFlWjB0J6gtRP9UQOnJiqRJqoq5JYjW7i/6P6o474878vMnTt3wG3VWhfb2BX3HkRiRWoVfrTzKNftiNzy+8drfszc1NP/1tImXIwHZipCArRUBXjm3jquunkahYsnX3hmsuu9gOlA1HGPPXKY5S4vjqC5+tWH/XMTEwyVVuGmeTweXnvttVE51pGPrHc+UIumY7/xagIPbzMXDnXYsd94NWrRdGg5Yfq4U11eXh6apiWknbyqmu+eMFJsXQ0oFlrbD0XRQ9i6GghkzkrIeuPJs5XPRh0TNII8Vv4Y31jyDQBUVWXNmjWsWbMGj8dDXV0d3d3dJCcnk5ubi9s9cV4DSFVZMRomXDD0oosusjTvnnvuQVEUDMPo+wiQn5/Pxo0bE7jD4WmahsPhIDk5mZycHAoKCpg3bx4zZswYleMLIYQQQgghhjcreRYvXvZixDGp9lR0XaesrMx0KDTM4/FQVlbG9zY9bGm+EEIIISafTEcmG+dFfo8y05Fpef2KEx2mQqFhPl+IH/7gfb76hSUcfCb6a5/XH2+j2/BxNFRPDz7yNQ/npkeeM0frpi7kxOgXZozlNO6VmT3s9udjMHTYz6n4+rV6H9j+3amYqwKkKKHTVT77/oQrffbermm94cbHk3x8LXP475Vm9AY+bTF8lb9zByi36zHvs9pm8Dt3gGs9sVdKs5/aU2gM8qH18y+mNflT8Nyvoo7158yj9op7yNt+N269O+Zj6DYXtVfcgz9nXtSxbtvIVAw9J/scdHTcmpskWxIurbfypltz47a5meGK/fxAvNVCwyq7K3m94fW41xFCiJHSeMJvKhQaFvQZ/PmHjXzmrlyypTHjhGHmAqZ0Jcl0KBSgJjSdllAaWVqHlS0C0ircqtra2rhDfy5nPoV5n4867rFHDvPSduudD7TSWSi3XEfg8edjaiuv5Odgv+HK3lCoiCqoB6nuqaYouQhN6Q1xut1u1q5dy44dO+Jef8WKFbQ2xr1MQqgBa787jNZ640G9p56Xa1+OaewzVc/whZIvMMM98Hcnt9vN7NmzR2J7I06qyorRMuGCoRdeeCEXXmi+pcg999wz5O35+fncfffd8W5LCCGEEEIIMcHZVBuZzuiBi127dlFeXh7XscrLy9m/P3obVyGEEEJMDVnOLL561ldHZG1dN3j4p4dMh0LDXH4nbz7SOUzr9cGSFSeLtEI6lSN8Pqki6vh/SDnJFaE2tvcsoV3PZk5yDV88649R511b8jjr8v7Cn8uvweNNPx381MyFP3tDn71hT83uocfVRWNSJ22uHi71q9jtXmy22IOk+aHI36eQAnWaQWGUJKbZaqFhm1K9fNZjj7lqqIJCsgEdJoKhTamlZM1PJ5Q6nWDKNILJ06nvzIb3Yg+xAnhD5r4+T+EKqtc/gOOvN8Y03pc1m/qL74gpFAqwJmcNGY6MAaHN8N9dmou8pDxT+w37VOGn+FThpyzN7S9R1ULDnq54OmFrCSFEIhm6wV+2NJkOhYYFfb3zN/yz+fCgGH1mL2CaoUS56mhYCjs9K/lE8l+xKxZeF0urcMt6euL7niUnlVCUfwOaGlva+8zOB2apRdNxfPMG9A8rCe3ci37gOOj9XueqKuri2WjrzkE9ayZK/+qkRvTXw666g/gzZ0atZj8ZdAW62NXYW2n+SMcRnjj+BJ6QB7fm5vrZ1zMvbR5rpq3hmmuuSUgw9LLLLuXJJyL/jhFPVVkz9AQH9BK93njwWPljBI3YOnYE9MCAqqFW6Hr01xWj9fgAqSorRs+EC4YKIYQQQgghxFh66qmnErLOCy+8CKxNyFpCCCGEEMM5eKCF6qouS3OTcDJfzYs5FBpWZGvkkqQPYj7pPkPr5vMpb1Nuz+Hq+U/g1HwxzctLPsk/Lv4xlRUr6O7OGWKEPrjK56m/VyV18Mf0DmocAao1ve9P96kvVTOgviY9psqe/RVGCYYCVGt61HFmq4WGldt101VDkw2FDmIP3/RcdRtNhSkDbgtW+wFz7VmttGb358xj6VnXwhu/iziu/oJb6Cy9ytQJ97+Z9Tem9zOaElUtNKzOU5ewtYQQIpGqD3ppqTJX3ftMLVUB6o8aZCVoT2JkmL2ASUUhQ0m2fLwWPYOXe87j40lvmguHSqvwuCQlJVme63LmmwqFhoU7H9x19wpLlUMVVUFbMAttwSwMXwCjtQO8fnA5UDLTUJyDg+eOpiPkvvSdqGtP3/kA6QefMXUB00RV763nm3u+Oeh2T8jDz8t/DsDWC7eyatUqSkpK4irGMK9kNTv+Ev13t3irysYqmDIdQ9USEvwzVI1gyuSqSlvvqeeZqmdMzRmuamgsKk508OCPDkQdN1qPD5CqsmL0SDBUCCGEEEIIIWLk8Xh47bXXErLWu+++y5yZEgwVQgghxGAho/fkUbi9nlUP/eQATQ0p0QcOY642w3QoNEtt4xKzJ9uBVHcLfzvnOTTN3DxNCzGr+B2am2eiKAwIf9psPpRhzg3WOQN8N3P4luSxVvY8U0GMwdBIrFYLDQtXDY3F9S920TzLBmnxBXBi8eV5XyY1j75KnIVJhdBpfp2rCq4CIgdDfTMWTaoqTImuFiqEEOPZgZct/HAYQvmublYlZCVhlq5Hv7hl3759dHelmbqAyYkddbgXdzGqDc3gue6LWOd+O6a28tIq3JyhWoXn5eWhaZqFdvIKBbnXmA6Fhvl8IR7+6SH+87ur46r+pzjtKLmRK4+6q98lb/vdqMHYXsM7W45T+Owt1F5xD57CFZb3NlmoqkpZWRkbN27E4zEfbsvKWESy82+pr4ttbrxVZWNh2N10z1xNyok34l6re+aaSdci/LHyxwjo5n4HtVo19MD+ZlOVqUfj8QFSVVaMnikXDFVOvVhU4nzRKIQQQgghhJh6amtrLbyJOTQ9QW1ChBDjgyfo4WDbwYhjFmUswm2TN+mmoqOdR7lux3URx2y9cCtzU+eO0o7EeLf95HYUFK4qvGrQfd1dAWpre9izpzHqOhUnunA5rVVVylZSSVbMnoQ1WOd+20J7ToPCwvdNhUIfSfKx1xHipKbzVHMy06adMHXERFX2PFOKoZCpK7Sqw1fgjBYMtVotNKzcrvPI6s8wN7gYfnd7xLHXf+1O2he30x3qxqW5CDWl8rrlI0d2Rf7lZBUOrGSqdzaN0NEml/2t+0m3p7MkY8mg+7whL0c6j0ScPy91Hi7NNXCex8sRIs8TQojRFvQbVO5LTMWr2sM+sF6oUFh0+PBh7rzzzqjj7rvvPkrn/ROaUhzz2qrJSu7DadEzeLb7Uq79QpDU8oPmWoWLAWJtFb527VrTrcKTk0pwOfPi2l91VReHDraweATDXY6mI6ZCoWFq0Eve9rupXv/ApK8cGkmzr5m5qXMpLS1l8+bN3HbbbabCoelpsykquIFAIPYOCBB/VdlYtC+8OiHB0PZFVydgN+OHlWqhYWarhlac6DAVCg0bjceHVJUVo2VKBUMNw9wPAyGEEEIIIYTor6fHfLtLMXk0ehv5xZFfRBzzpXlfYppr2ijtSIwnNZ4a/mnXP0UcI8E/IUQswpUBQyGD3Ibl1Nd6qanpoa62m9qaHjo6/AB4ffUjtofFahEpqiv6wDNMU5tjqrw0kE5mZjUut7nqYI+k+Dh8Kjw5VpU9h1MYVGl1DH9yJ9K68VYLDXuw9RXuL7oy6rilS5cyd+7pn03V7i5eZ1fcxxeJtSx7GY+ufXTI+2K5+OA7y78z6DXI0aNHuY7I84QQYrR5WkMk6jraGIpWigTbtWsXt99+e0yhLkWxo1Jkan2dRJ7rV1DPmoXjkpKYW4WLwWJtFX7NNdeYDoZmZaxJyB5ffrF65IKhhs6MVzaZDoWGqUEvM17ZRNWGhyZVtXsznq18llU5vfWdV69ezZYtWygrK4uprXxJSQmFuTfR2GCt+0GiqsoOx1O4HF/WbJwtxy2v4cuajadgWQJ3NfasVAsNM1M1VNcNHv7pIdOh0LCRfnxIVVkxWqZMMPTRR4d+0yQnJ2eUdyKEEEIIIYSYqJKSpNTEVNYR6OCpiqcijtlQvEGCoUIIIWLm6QlSeyrwGf74bvCvVJZWAlD29K/IOGH9JJACuLDjUuw4T31UDIUTRuRqo1ZbdK5yvW96ztyS13GbDIWeaawqew6nMKSwP8L9VZqOoagEk3MIpkwjmDz91Mdp/D5YQfnJX1s6bn+V3ZW83jBStT/FeOLSXCzPWh51jJi6HKqDOSlzoo4RYjwI+qXIz3g3VKtw6K0UGmsoFMBhz0TpNz8WPgLohhF3O3kAVYOUnN7jx9IqXMRn1apVlJSUxBT2g97gcGpyaUKOve+9JnzeEE6XucdbLNzVe+IK/UFvW3n3yfcmZUv5Zl9z1DEv177M1z1f76sAWVpayhNPPMHu3bt58sknef311wd08NI0jXXr1rFhwwaS3HP5/v374trjiFaVVVTqL76DwmdvsRQe1m0u6i++Y1KFhuOpFhoWa9XQgwdaqK7qiutYI111WKrKitEwZYKh//iP/zjWWxBCCCGEEEJMcHl5eWialpB28qqa+DcjhRBCCDH+6LpBc7OX2ppu6mp6qKnppq62h9qabtra/APGGkqI8k8+1/d54+KXSa84G8WwdiJoiTaTLNvMAbf1GD4w9VLGwK14SVG6adQjX2T/7rQq2jOP05TcToO7GyWkcc+7l0acoyjxB0DGorJnxHVDGhAEwI5CnppCnj2TXNd0ZiQVMD97CUdnfro3kdBPUA/y4I5rLR1zKE9XPJ2wtcT4VZBUwMPnPzzW2xDjWFFyEU9e9ORYb0OMU+3+drbXbI845or8K0h3pI/KfmwOadk93sTSKnxV9irKyspMtX9WLQTSdQzajG6ylBTTc8806xw3dufkCVuNZ+FW4WVlZWzcuDGmx4mV4PBwQqHe38fyC5ITsl5/6Ye2JWadg9smZTD02cpno44JGsFBFSBVVWXNmjUsW7aMqqoqGhsb8Xg8uN1uFixYQEZGBgA//H58odCwkawq68+ZR+0V95C3/W5T4VDd5qL2invw58wbkX2NlXiqhYbFWjX0Ly9Wx3WcsJF8fEhVWTEapkwwVAghhBBCCCHi5Xa7Wbt2renWR0NZsWIFrZGLdQkhhBBiAvF6g9TW9PSFPmtPfayr7SEQiC1g2D7rffxpTX2f+9OaaJ+1j6wTy/sqfvZWAHXgUw2ORlnParSi2FbFHHsnmWoHGWoHLtVPayiVZ7ovjzjvwdL3aEuv6vt8dufohEhGsrLnUIJJWQSTp/VV+Tz9sbfy5xV6Fx8L9ZDrziXLmYUaY4WXF2peoLK70sJXMrQ6T13C1hJCCDE5Nfma2HRgU8QxK7JXjFow1J2poWokpJ28Kpm/hIilVfidSXfGXAkyTNf90QcNtR+jnSziD4Yu+nhq3GuI2IRbhZeWlrJ582Zuu+22qOFQK8HhSDyeYELXA1ACHpIr30rIWsmVu1ACnknVCrreU8/LtS/HNDZSBUiXy0VRUVHf52537/fI5w2xb2/ToPFWjGRVWQBP4Qqq1z/AjFc2xRQA9GXNpv7iOyZdKNQf8rOtKjFh6m1V27h10a3YVfuQ90+Yx4dUlRWjQIKhQgghhBBCCGHCNddck5Bg6OWXX8bW38ReSUEIIYQQY0/XDVpbfb3Bz5pTLeBreqir7aalxRfX2oqi07z4L4Nu71j8Kpef/CyqMfAkRKvSHtfxIpmTso8FBoCBw9GD09kFSht0j9gh42I9GBr55ElNSjpN8754OvSZnEMwOQe0oU8+hRUz3fRegnqQR448YnqeEEIIMZnYHAozz3ZzYk/875fklTohcddbiAheePYF03P8gVYMI2S6KmS70UO34SNZcZo+ZlhWkZ3ChS5rk43orztddQfxZ86cEkEds63CV69ezZYtWygrK4sYJrYaHB6O2534WIytqwElESl2QNFD2LoaCGTOSsh648Fj5Y8RNGIL5MZaAbK/piYPoVD83SdgZKvKhvlz5lG14SHcJ98j/eC23jBwv8ePoWp0z1xD+6Kre6s/TsLnj5M9J/Hp8b1vEubTfZzsOUlxSvGQ90+kx4dUlRUjTYKhQgghhBBCCGHCqlWrKCkpMV0Job+SkhKWLFnCVnYncGdCCCGESBSfL0RdbW/gs6bmdOXP2tpu/D5rIUQADfVUxU87Tuy4FQfOU1VAK2e9zoG0weXEO9NqOVb0OiWVF5g+nopOptpGptpBptZBhtpOvaOF95tLI84LFByixNWMw9mNqvZ+vXU9+RClE1uaDm2mdxm/4Sp7ninkTD0d8EyZxkxqWeL9kFz3DGYkFzAjdTYzkgvIdeeS684l05FJmzI6LW33t+4n3Z7OkowlCVvT6/FyhCMJW08IIYQYDYs/npqQYGjJmmQJho4GP+zZtcf0NMMI0Nl9mLSURabnHg3Vs0grRLMQnLI5FS7ZmIOimn+N52g6Qu5L34k6bvrOB0g/+MykrPh3JiutwktLS3niiSfYvXs3Tz/9NDt37iQUOh2Q0zSNNWuW0NIAuvVfvfqtp5CdbTEIHIEaSOwF/4lebyzVe+p5puoZU3MiVQ0ditebmFBu2EhUlR1EUfEUrsBTuAIl4MHW1YAa8KDb3QRTpk+qirFDKUouIt2eTnsg/otcMxwZFCYVDnv/RHt8SFVZMZIkGCqEEEIIIYQQJqiqSllZGRs3boza9mgobrebsrIyFOlpJoQQQowpw+it/tnX+r3mdAv45ibzLbzCbKfCn07F0RcCDbeAtytDvx2rKyH2Lnx62DX3LnyKOVUfG1A1VFein+j4dPJfmJt8uvWrqgbQbNFPaHSktuKydUYdd6bckDom+YtqW+8ZYwPoKVhOMDW3r617bwi0Nwx65om2q079GQ+WZS/j0bWPJnTNo0ePch3XJXRNIYQQYqQVLnKRVWSnpSpgeY2sIjsz5tqxvoKIWRvoIWvpvZa2XZaCoT34+FCv4Sw131Q41OZUuOrmaUwrNt+m3F39rqlqbs6W4xQ+ewu1V9yDp3CF6eNNBPG0CldVlTVr1rBmzRo8Hg91dXV0d3eTnJxMbm4ubrebH35/H3veHXzhnFlnL8sZkRbQeoJDfIlebyw9Vv4YAd3cM7DZqqGuBP+bjkRV2UgMu3tSVYiNhU218b1zv8ft79weVzg03Z7OphWbsKnD/5tNxMeHVJUVI0WCoUIIIYQQQghhUmlpKZs3b+a2224zFQ51u91s3ryZ0tJSqqu7RnCHQgghxpMZrhn81/L/ijpGjAy/P0R9nedU6LP7VOv33hCo1SoSdjScA0Kfjr7wp81kO0yAY0Wv0Z5WM+z97Wk1vPix/8IedOFNaqAruYnOjjb4aeR1MzJqyMupxunqwunswm734erOgbrVEefVW2zNPkMfneqaANNCCqmGRmFQZX6w94RId/HHqLvinlHbgxBCCCEST1F7Kzo+c28dQZ/5NrCnK0J2jMDupp6orcLj6Pjd3VOO11eLy5lnem6H4eFgqJpSVx6OoD3q+KwiO5dszLEUCnU0HTHd4hdADXrJ23431esfmJRV3RLVKtztdjN79uxBt19yWWFCgqEfv2z4qoLxCKZMx1C1hLSTN1SNYMr0BOxq7FmpFhpmpmpoTo4bTVMS0i58pKrKisGWZy9n+2XbOdZ1DG/I/AW5Ls3FnJQ5EUOhMIEfH1O8qqwYGRIMFUIIIYQQQgjAF/JR3RO5P2phUiFOzQnA6tWr2bJlC3feeSeVldFrY5WUlFBWVkZpaeTWrWL8cmkulmctjzpGTE2zkmfx4mUvRhyTak8dpd2I8SbFnsKl+ZeO9TYmNcMwaG/39wU+a2q6qavpobamh6YmD4aFcwF2tFMVP0+HPsMhUCttK4cTrVpoWHX+GS06YyjoOX16OdlZ5oOq9areW37TpBmh0atY8Yfmwc+p7YuuHrXjCyGEEGLkTCt2cNXN0/jzDxtNhUP7V4TUa0dwg1NI1Fbh5nOW/RicrHuK4qKvoqlO07NDziDr/30aWo+Dgy93UrHXQ/+MnqrBrHPcLPp4KoULXZbax2PozHhlk+lQaN8egl5mvLKJqg0PTarqbqPRKnzR4iwKi1KorrJ+cX1hUQoLF2VZnh+JYXfTPXM1KSfeiHut7plrJk3gy0q10DAzVUOdLo2zz8kZ11VlxdBsqo35afNH9BiT4fExFavKipEhwVAhhBBCCCGEAKp7qrluR+RWm1sv3Mrc1Ll9n5eWlnL//ffz+c9/PuK8u+66i/Xr16NK+/gJrSCpgIfPf3istyHGKZtqI9OZOdbbEGLSCwR0Gup7A5/h6p+1Nd3U1fbQ0xNbtZr+HNgGhT6dpz5PZPgzksqiv0asFjoW6jQDzH87ybVQMbSxYQ6hkIO8vA9wurrNH/QUX9bs3nZqk1Cjt5FfHPlFxDFfmvclprmmjdKOhBBCiJFXuNjNZ+7K5S9bmmJqKx9PRUgxtJhahWcAKmCt4DxeXw1VNY9TlH+DqXCo06lx861LKZ6TDkDRYjcBn05XUwi/V8fhUknJ0bA743tN767eg7PleFxrOFuO4z753qRqKT8arcJVVeHGmxZy7z3v4vOZr8rpdGrceNNCVCuB4Bi1L7w6IcHQyXKBWzzVQsPMBIjHe1VZMbbk8SFELwmGCiGEEEIIIUQcYgl7Ll26VEKhQgghhEnHj3dwZN/J3uDnqQBoQ4P56p9ObL1VP0+FP/tawGNHHYHwp66E6EyupzW9kpaMClrTK1i19wtk9mSSoXWSqXaQobaTqXWQprVx45LfJXwP8arXdGvB0JBKmg6FIZWikMrC7ugn99vbe0+yVFU5mT13F5pq/qSvbnNRf/Edk6oKU38dgQ6eqngq4pgNxRskGCqEEMI0TdHIcGREHTNWphU7uPY/86g+5B25ipBiWDG1CncA84APrR+nu6ecE1UPMX/uFwkFo3faKCxK4cabFjKrOG3A7XanSmZBYl8Pph/alph1Dm6bNMHQ0WoVDjCrOI2bb13KD3/wvqlwaDg4fOZjJNE8hcvxZc2OKzw8mS5wi6daaJiZAPF4ryorxpY8PoToJcFQkzweDx6PB5/PRzAYxLDSh8oCt9vNtGnyxp4QQgghhBBCCCGEmBq2/PQgx3uivx+mwICwp/OMEKiqjGxAIKj6OTz3BVrTK2hJr6Q1vZKQzT9gzN/Xp3Jl43QANM2P09mF09nFn3MrqUqOoSf8KKvTrL3nmVxxMf/T9hnmLs9Geel9dBMdN716DjXn/BsFhx401apTt7moveIe/DnzLOxYCCGEmNqKU4p56fKXxnobESmqQtFi94hVhBRDMxX+W0lcwVDorRy68aZcUlPm8/KL1ex7r4lQ6PRrUk1TOHtZDh+/rJCFi7JGtApkmBLwkFz5VkLWSq7chRLwTIp24aPVKjxs0ZJs7rp7BQ//9FBMAa/hgsMjQlGpv/gOCp+9xdTvMGGT6QI3f8jPtqrEBKm3VW3j1kW3Rh03EarKirEjjw8hekkwdBiVlZW88sor7Nu3j/3791NRUUFtbS09PT1jsp8rr7ySP/3pT2NybCGEEEIIIYQQQgghrOrpCVL7UVu/9u/d2JpO8N/Fsa+hoAyq/Nk//KmMcPhz6D3ppKldpKltPLHk1wRsw58c7SrYz+yUZJzOLmz23tBoEIOfTR9/oVCAc/waAQzsnP6+Bol+slK76vMsuCAFRVXQFy3F/4s/QmNb1HlKfg72G67EVzSd6nkl5L74HRwdJ6PO82XNpv7iOyQUKoQQQkwRZipCxlLcRz9WgzIjWyqNDsFU+G8OMB1osH68kpISVq9ejaqqLF6Sjc8bornZi8cTxO22kZ3twuka3eq1tq4GFN18mGgoih7C1tVAIHNWQtYbK6PdKjxsVnEa//nd1Rw62DJugsNh/px51F5xD3nb757SF7id7DmJT/clZC2f7uNkz0ny7HlRx473qrJibMnjQwgJhg5w7NgxfvnLX/Lb3/6Wo0ePDrhvtCqDDmesjy+EEEIIIYQQQgghJgZDj/4+0pEP28jPT+47YRbLe091R3xk5ttNnzj/Ttk71IZcA26bneSB4sjzCtRsXGoBLsWOA9uYhD97GaQoPWRq7WSoHb2t4LUOMtRONCWEw9HDUx4XB1OHP3F+PL2F5NDAk2S/cwcot+sjvXlLyvT59MybRiCrGH/GTPyZs2joyIL36iPOyy1x9j0+1KLp2L/yaQLffTziHNvnLkM7f3HfPH/OPOouv5uZT98YcV79BbfQWXrVpKiuI4QQQkw0uh79Ncy+ffuYPXs2qjr6P6v1qgaCj/4x6rjgb18itGMv9huuRC2aPgo7mxhMh/9U4G+AXwAWCkm63W7KysoGPFacLo38gmTziyWQGvCM6/XGwmi3Cu9PVRUWL8keN8Hh/jyFK6he/wAzXtkUU1v5yXiBW1FyEen2dNoD7XGvleHIoDCpkFAgtiDfuK4qK8acPD7EVCfBUODw4cOUlZXxu9/9Dl3Xh3wjfOzeeBZCCCGEEEIIIYQQIjYVJzp48Ef7o4577OeHeemFam68aSFJuHjhJ01R5+x4tIV9L3RQ+gkX3YaP2poevBX1XGNifyoKLuykK0lRx2YrKQTV6OOs8jo6+7V/r6Alo4Ilxy7iY5XLyNB6A6DhMKhD9eNwduN0duE61Qbe6erC4ehBVXXOUX0cjHCsg7aBJ7SCGHwv1XyrwdHSfFUZ7sKUgTd2+k2vE0uIWJ2bN3hcDGFP34xFEgoVQgghxsDhw4e58847o4677777ePLJJykrK6O0tHQUdtYr9EEFgS3bwB9beM2oacL/wFbsN17dW/VSWAv/5QGfA/4XU+FQt9vN5s2bR/UxEis9wW3fE73eaBuJVuF21W5p/ngIDp/JnzOPqg0P4T75HukHt5FcuWtAxVlD1eieuYb2RVfjKVg26X6Xsak2vnfu97j9ndvjCoem29PZtGITNtVGiNgrPI7nqrJi7MnjQ0xlUzoYGgwG+c53vsN//dd/EQgE+gKhkUKgo1m5U1EUDMOQUKoQQgghhBBCCCGEiOrA/mZ+ZKI9VnVVFz8qO8R8LY9Yz/u2nQzy+sMdfKjX0GF4yNO8XJMeeU6Rkk2mlokLOw6l9+3IGerYvC25/6xnqZm+n9aME3S7Wwfdn9YT4jM9J3G6OnGeCoI6nb0B0Ehv0S0MRD6pd8ym48HAfao1eyKqhV7tsbGNYMQxOgYVnSE+bNX5sC3ER206RsHMuI4rhBhfWnwtPHXiqYhjrim+hixn1ijtSIw37f52ttdsjzjmivwrSHdE+YEuBLBr1y5uv/12PJ7YKh+Wl5ezceNGNm/eTEHBohHeXW+lUDOh0D7+AIGHt+H8ysdGZmMTSFytwucCXwKeASIXmgd628ePdnDYjGDKdAxVS0g7eUPVCKZM7OTxSLQKL04pTsh644ai4ilcgadwBUrAg62rATXgQbe7ex9PEzwcHM3y7OVsv2w7x7qO4Q2ZvxDSpbmYkzIHm8X3C8ZzVVkx9uTxIaaqKRsMbWlp4bOf/SyvvvrqkIFQad0uhBBCCCGEEEIIISaKihMdpkKhAEk4mR2aQQydQAfQFJWz1HyOhxrIJPob51lqCqo+NifAbATI0DrJVNvJVDvYN+M1qnOPDTu+ZnoFc9UW08dZFIz8fdAV+NAe4pyALWHVQt+zR/+3vuT/uvCd8e/7H9ev573fTPw2lkKIXq3+VrYc2RJxzKX5l0owdApr8jWx6cCmiGNWZK+QYKiI6vDhw6ZCoWEej4fbbruNe7/zYNSxRz5qIz8/2VKlLkM3CDz+vPlQaJg/QPAPOyEj8jBX3UH8mTMnXbW/sLhbhecBX4ULei6A3fD6668TCp1+3appGuvWrWPDhg2sWrVqQPv48cawu+meuZqUE2/EvVb3zDUTPhQ4Eq3CJzPD7iaQOWustzHqbKqN+Wnzx3ob47KqrBg/5PEhppIpGQxtbm7mggsu4PDhw4Mqcg4XCA2PiXZ/tHUikcqgQgghhBBCjJ3CpEK2Xrg16hghhBBivNF1g4d/eshUKBRgrjYDzeIJbU1RKbHlkqF2WJqvED2NWpx2hAZPHgaD96grQVTj9FubGiHS1U4y1A4ytQ4y1HYytXaynM04XV19lT8P2Vt4J8IxP7CHMDBQMPc+3cJA9IDsgVPB0ERUCwWoskV///HMUGhJSQlLlixhK7vjPr4YPS7NxfKs5VHHCCGEECNF13XKyspMh0LDDD2TLT/7CFXJiDjusUcO89L2am68aSGzitPM7fHDCoyaJkv7A3C52ilyvxd13PSdD5B+8BnqL74Df848y8cbjxLWKlyFt9LeYvu926k7WUdjYyMejwe3282CBQvIyMiI/xijpH3h1QkJhrYvujoBuxlbI9EqXAghhBAja8r9tA0EAnziE5/ggw8+QFGUYQOf8YY0h5sfKTA6VOVSCYsKIYQQQggxOpyak7mpc8d6G0IIIYRpBw+0UF3VZWpOCi6SFWcCjh49nDhNbaJNT4VTYcuC5Ar+fv5DUeddW/I4q/Je5qd1n+CwI0BregWt6RW0ZVSQ157H13Z/jky1g0ythRxXA25XV2/7935BUFUdmIw8R/FHPGanCpWazqyQuRZi03WVaSGFRm3g98Otw4KgxsKAxuyglrBqoVa43W7KyspQxnFVJjG0gqQCHj7/4bHehhBCiCls9+7dlJeXW5qbnFRCUf4NqDG+9qyu6uLee97l5luXsmhJdszHCe3cZ2l/AMkpjcycuQdNi+1CK2fLcQqfvYXaK+7BU7jC8nHHm0S3Cq/x1JDkSqKoqKjvdrd7YlXN9BQux5c1G2fLcctr+LJm4ylYlsBdjZ2xbhUuhBBCCHOm3E/cb37zm7z99ttRA6Fn3p6WlkZmZiYVFRUoitJXaTQ8zm63k5eXh67rtLW10dnZOejYQwVR+6+VnZ1NcvLQ5YpnzJgRx1cthBBCCCGEEEIIISajXW/W8e7uWtPzctWMuI+dpbZxkXtX1HFrk95jYegoOz0ryUk9yRcWPIhTi37C+e+yutief4jg/EOD7ku1dXH1vF/jcnbhcPagKLF174mlsudBu/lgKMDlXjsdqsHCgMqigMaigEZxSEXrV310q9ufkGqhZrndbjZv3kxpaSnV1eZCxEIIIYQQTz31lKV5Lmc+Rfk3oKnmLkjy+UL88Afvc9fdK2KqHGr4AugHrAX3XK52U6HQMDXoJW/73VSvf2DSVA5NdKvwAncBrT2tCdjZGFJU6i++g8Jnb0ENmg9C6jYX9RffARY7NYxH46VVuBBCCCGim1LB0Pfee4///u//jhgKDd923nnn8dnPfpZPfOITzJkzB4fDAYA6zBX1S5cuZffu0y2YQqEQra2tHDt2jNdff53XXnuNHTt20NLSMiAg2v+4NpuNBx98kE984hMJ/bqFEEIIIYQQQgghxOS07f9O4HKav6A4SXHEddx8rZ5Lkt7ErsR2Aj1L6+Cz2c8yZ+4uHFrkqp1hR206wWGa6dQ4/BgZtTgNcydY5wZVnAb4IjTpOWQL8QnsptYFeLAtacjbQ7rB8U6dD1pD3Hm2tfar8SgpKaGsrIzS0tJRP7YQQgghJj6Px8Nrr71mYaZCQe41pkOhYT5fiId/eoj//O5qVDVyh0WjpQN0KxffGBQWvm86FBqmBr3MeGUTVRsemhTBP2kVPjR/zjxqr7iHvO13mwqH6jYXtVfcM2mCw0IIIYSYeCbHq7EYfeMb3xhU6RMGVgmdO3cuP/jBD/j0pz8d17E0TSMnJ4ecnBxWrVrFLbfcgt/v59e//jU//OEP2b9//4DjKopCXV0dn/70p7nlllvYvHlzXMcXQgghhBBCCCHE6PGFfFT3VEccU5hUiFNLROtuMdGc6DrBV974SsQxj5z/CLOSZ9Ha6qPyRCcnTnSyb++HMR9DAdw4SFZc2NGoMUauMk+W2mYqFNrLoLjovZhDobH4wK5znt/cCXgbCmcFNN53DL/3Q3ZrwQBv0KC8Xedwa4iP2kJ82KbzUVuIo+06fh2YeepPK2g2jZTkFFJSev+EL0o3w+PxUE7klq533XUX69evH/ZidyGEEGKiOrP4y1D0YzUoM7JRooQKRWS1tbWEQuZfHyUnleBy5sV17OqqLg4dbGFxtJbyPmuvMVNSmnC5B3eBNMPZchz3yfcmTUv5RLYK9/kS05Z+PPAUrqB6/QPMeGVTTG3lfVmzqb/4DgmFCiGEEGJMTZlg6IEDB3jppZeGDIWGPz///PN57rnnSEuL3pLACofDwZe+9CW+9KUv8cQTT/Cv//qvtLW1DdiDYRg88MAD1NTU8Ktf/Qqbbcr8EwkhhBBCCCHEuNbia+GpE5Hb511TfA1ZzqxR2pEYT6p7qrlux3URx2y9cCtzU+eO0o7EeBIyQrT52yKOeeThA7R9VEFnR6DvNq8verizUM0iVysiCQfqqSpFPYaPmtBIBUMN1rnfNhUKNTQfORkn4z7pfqZD9hDn+c2/d7YwqA4KhhYHVRYGVBYGNM6Psma73+DDM8KfH7bqVHbp6MNkVNxuN8uLlrMydSWrVq2ipKQk7rDm0aNHuY7IzztLly6VUKgQQohxzxjuB2g/dUd8ZObbUVQFvaqB4KN/jDon+NuXCO3Yi/2GK1GLpidiq1NST0+PpXlZGWsScvyXX6yOHgx1WquGn5VVaWnemdIPbps0wVCQVuHD8efMo2rDQ7hPvkf6wW0kV+5C0U//XmGoGt0z19C+6Go8BcsmRRVZIYQQQkxsUyZ1+NBDDw26LRzIVBSFc889lxdeeIGkpKFbPiXa9ddfz9q1a7nhhhvYuXPngNbyhmGwdetWbDYbv/rVr0ZlP0IIIYQQQgghImv1t7LlyJaIYy7Nv1SCoUKIQULB6G0tjxxpx9XhMr12tpJCimJ+nlX5WgNZWkff5x+mtnBWZ+TnPfu8N8izm2+hPiOkcDhCR/eDNmuVPa/02EnVFRYHNBYGNEqDGqnG4EpidT2nQ5/9Q6B1PdHDKzabjaVLl7Jy5UpWrlzJ4sWL5QJwIcSIcKgO5qTMiTpGTF2aopHhyIg6Zqw0nvDz4k+aoo7b8WgL+1/q5LLLekja9mfwB6LOATBqmvA/sBX7jVejlc6Kd7uTXlAPUt1TTVFyUd/jwsq5U0Wxk5pcmpA97XuvCZ83hNM1/ONUyUoDVTXVTl5RgqSmNSRii70BwYAHw+5OyHpiHFNUPIUr8BSuQAl4sHU1oAY86HY3wZTp8hgQQgghxLgyZd6NfPbZZweEL/v/3el08stf/nLUQqFhM2fO5OWXX+baa6/lmWeeGRBUNQyD3/zmNyxatIhvfOMbo7ovIYQQQgghhBBCCGGNzxuiqrKTiopOKk50cuJ4J0c7yuHK6HMVFJJxkqz0/glqKkdHfssxy9XqWe3ah6oGcTq7cLo6mePshijB0KM2HSuxgJKgxg4S3/L9M14Hn/H2hqR0w6CyU+eNU6HPj9rCreB12v3RA6BhiqJw1llnsXJlb0XQc845B7dbTgoLIUZeUXIRT1705FhvQ4xjxSnFvHT5S6NyLD2Gyp9HPmojPz8ZVVWoOuDh+R82EvTF+DP3ZCP2p/4KJiqXA+APEHh4G8ot10FS9OCgq+4g/syZU6LaX1egi12NuwA40nGEJ44/gSfkwa25uX729cxLm8fZOWejaZqpdvIOeyZKggLHoZBBc7OX/ILkYccoTjvq4tno78f+6tnh8KAosb/ei0TRQ9i6GghkSvh4KjHsbvk3F0IIIcS4NiWCoQcPHqS6unpQG/lwCPOOO+6gtDQxV62ZZbPZ2Lp1KxdddBFvvvlmX2A1vNdvf/vbXH311SxYsGBM9ieEEEIIIYQQQgghhtbVFaDiRG8AtPJEJydOdFBX24NxxvnlYHr0tc5S88jV5gy4mLmV9gTveDADA4+rjc7kemY0R35/7G/m/IaZGcdwOE5X/8zyJnOsLvK8cluICPnOYZUEI4cxDtlDGBgoDK72eSZ/yOBoh85Hp0Kfh9tCfNSqU94ewmMtX8rMmTP7gqArVqwgIyPD2kJCCCHEJFBxooMHf3Qg6rjHHjnMS9urue4z83nrF12xh0IxWOd+G7vZUGiYP4D2xG/Inbk36tDpOx8g/eAz1F98B/6cedaON0HUe+v55p5vDrrdE/Lw8/KfA7D1wq2sXbuWHTt2xLyumuBKxR5PMOoYbd3ZpoKhqmrxsTTcegHzFfKFEEIIIYQYSVMiGPrWW28N+Lz/G+w2m42bbrpptLc0gN1uZ+vWrSxevJjOzs4B9wUCAW666Sb++te/js3mhBBCCCGEEEIIIaY4wzBobfVRcfx0JdDKE500NXljmh9LrSmXYh/wntVI21/6NJ15B2lKr6bb2U1GexGf3f7fEeekpLQOCIUCqDGEMsttuqVg6NzgwCpT6brCwoDKooDGooDGwqCGAQN20B0w+tq+f3gqBPphW4gTHTrBOAtC5eTk9AVBV65cSW5ubnwLCiGEEJPEgf3N/OgH7+PzxfYDv7qqi5d+2oQbZ8zHyNcayNI6rG6R5JRGZqbuQeuIbY/OluMUPnsLtVfcg6dwheXjThbXXHONqWCorvsTeny3O/opbfWsWSj5ORg1TTGtqeuJqWjat560EBdCCCGEEOPMlAiG7tmzZ9Bt4Wqhn/rUp5gxY8YY7GqgwsJCvv3tb3PbbbcNaim/c+dOXnvtNdauXTvW2xRCCCGEEEIIIYSY1HTdoKHeQ8WJjr5qoBUVnXR2BGKar6H2toLvawnvwqM6OTLC+zbryKzX8GU0jMqxjtp08JmftySgUdbuYuGpEGhBSOmrDtrqNfigNcQv2/x94c+PWkOc7DZITENQSE1NZcWKFX1h0OLi4lEN7wohhBATQcWJDlOhUIB0JclUKBSg1BF7JcgzuVztzJy5B00zd6WKGvSSt/1uqtc/MOkrh0bS7Gtm1apVlJSUUF5eHtMcf6AVwwglpJ28pilkZ7uijlNUBfsNV+J/YCv4o7929/vdGIaSkHbyhqoRTJke9zpCCCGEEEIk0pQIhkb6JeXyyy9PyDFCofjbDfzzP/8z3/3ud2lpaRn0JvP//M//SDBUCCGEEEIIIYQQIoGCQZ2ak92nA6AnOqms7MQbY2/xgSFQF8mKE7cyuG2mdxSyhAo66WoXmWo7htLO+x5zYYuRVKsZdCqQapj7RuTpKv/WNTAEENQNztnaQXVXouKfpzmdTs4+++y+iqClpaVoWmIrSQkhhIidYUR/rteP1aDMyEZRJbg/FnTd4OGfHjIVCgWYoaSbGm8jSJGtztSc0wwKC983HQoNU4NeZryyiaoND4ESSx34yefZymdZlbOKsrIyNm7ciMcTvWW6YQTo7D5MWsqiuI9/9rIcnK7YXpOpRdOx33g1gYe3RQ2HGoaNzo7ppKXXx73H7plrMKRiqBBCCCGEGGemRDC0urp62Kv5V65cmZBjBIPBuNdwuVx87nOf48EHH+zbb7hq6B/+8Ad8Ph9O5/h5U18IIYQQQgghhBBiovB5Q1RV9lb/PHG8NwR6srqLYIz9xW2oveHPvkqgTlxDhECHkuTNpOT4hZTPHrr9Zsnxi0jyZsb8tfS3NnUXq3P+Qpa7AberE6eri5qgk//d82VL642UD+whVvnjfyvy+cpAwkKhmqaxcOHCvoqgS5YskffehBBinNCrGgg++seo44K/fYnQjr3Yb7gStUiq9Y22gwdaqK7qMjVHRSFDSTY1J1ntQbVY1TElpQmXu9PS3DBny3HcJ9+blC3lm33NUce8XPsyX/d8ndLSUjZv3sxtt90WUzi0pW1XQoKhH7+s0NR4rXQWyi3XEXj8+aht5VtaZiYkGNq+6Oq41xBCCCGEECLRpkQwtKHhdFus/gFRTdNYunRpXGuHg5t+vz+udcI++clP8uCDDwKn290DeL1eXn31VS677LKEHEcIIYQQQggxUFAP0hmIfLIo1Z6KTZ0Sv0aJIThUB3NS5kQdI6amwqRCtl64NeoYMTq6ugL9qoD2toSvq+0hhsJjANjQBlQCTVGcOBW75f3YA0k0Zg/fTL4x+yPsgaS+zzuT62nOOE49e+FY5LXPK3mOBVkDKygp3TmW9zoSft+UTLGjOyFrPXIovvfg5s6d21cRdPny5aSkpCRkX0IIIRIn9EEFgS3Rq/2FGTVN+B/Yiv3Gq9FKZ43w7kR/f3mx2vQcJ3bUYYq5DMeO9eIsWVmVluf2l35w26QMhj5b+WzUMUEjyGPlj/GNJd9g9erVbNmyhbKysqht5bt7ytGNFlQly/L+CotSWLjI/Hy1aDqOb96A/mEloZ170Q8cB13vN0BFXTwb39q/wXewCWfLcct79GXNxlOwzPJ8IYQQQgghRsqUOKM53FVraWlp2GzmvgWapqHr+qAKpJ2d8V1tGHbeeecNe9/OnTslGCqEEEIIIcQIqeiu4Lod10Ucs/XCrcxNnTtKOxLjTVFyEU9e9ORYb0OMU07NKc8PY8AwDFpbfL0B0IrT7eCbm7wxr2HvC4G6+iqBxhMCHcqxotdoT6sZ9v72tBqaZj3PupOl5Drr+MF5j7M3sxEagBcTupUxodaexbGAi4LC/bhc5qqK9XewOcSOk+aCIfn5+axcubLvT3Z2tuXjj6Q6Tx0PHHog4phbFt5Crjt3lHYkxpMWXwtPnXgq4phriq8hy2k9eCPEeKFXNZgKhfbxBwg8vA3lluvAXDFKMQS9f4BuGO++u499e821hIfeiqFmBSyezlSUIKlpDdEHxiC5chdKwDOp2oXXe+p5ufblmMY+U/UMXyj5AjPcMygtLeWJJ55g9+7dPP300+zcuZNQKNQ3VtM01q1bx4YNG5gxfQHf/c89+HyhCKsPzenUuPGmhaiq+ccMgKIqaAtmoS2YheELYLR2gNcPLgdKZhqKs/c1f/30Oyh89hbUYOy/Q4TpNhf1F98Bimppj0IIIYQQQoykKREM9XqHfiGfkZFhei2HwzHkeu3t7abXGkp6ejo5OTk0NzcPCp8ePnw4IccQQgghhBBCCCGEmGh03aChvqdfJdDeMGhnR+zBkd4QaG8F0HA1UIcysm+P6UqIvQufjjru4DmP88iMdJy2IG/Ye9g7ortKnGAweqXkzo48AKqrzmb2nF1omvlgQFfA4KYdPUQr+pqZmcm5557bVxW0sHBiVOrtDnZHDWbcOP/GUdqNGG9a/a1sObIl4phL8y+VYKiY8AzdIPD48+ZDoWH+AIHHn8d547rEbmyKOXz4MHfeeWfUcT/870coKb7V9Pp61J/mg3XrSeiGYrqdvMPhQbHYgv5Mih7C1tVAIHPyVKV9rPwxgkZsF90E9EBf1VAAVVVZs2YNa9aswePxUFdXR3d3N8nJyeTm5uJ2nw7Q3nzrUn74g/dNhUOdTo2bb13KrOI0c1/UMBSnHSV36AuE/DnzqL3iHvK2320qHKrbXNRecQ/+nHkJ2aMQQgghhBCJNiWCoWeGOY1TfcPS0sz/MuF0OvvW6t/qvaenB6/Xi8vlinu/06ZNo7m5ecBthmHw0Ucfxb22EEIIIYQQQgghxHgXDOrUnOzmxPFOKk9VAq2s6MTrjf1ksgNbXwXQcDXQkQ6BhinoOJwNuB2NtOTuiVgtNOyYI8CzqT1c63GwMKBFHT8WPBlzaStZgU/JofvPH+HrchMKRQ+Ghnm96Rw5fjYzZ+0hyURR1q6Awd+90M37zYP//ZOSkli+fDkrV65k1apVzJ07F1WVik1CCDER6R9WYNQ0xbWGUdOEfqI2QTuaenbt2sXtt98+bCe+/lQ19tcA/fkIoBuGqXbyQWxUBXOZZTf3b6uq5i9GibheIPr3ZaKo99TzTNUzpub0rxran9vtZvbs2cPOW7Qkm7vuXsHDPz1EdVX06vGFRSnceNPChIVCY+EpXEH1+geY8cqmmNrK+7JmU3/xHRIKFUIIIYQQ49qUCIampaUNCIYqioJhGDH9YnumzMzMYauD1tTUMGfOHMv7DHM6nQNCp+H9NjY2xr22EEIIIYQQQgghxHji84aoquyt/nnieG8I9GR1F8Fg7NWdnNhIVk61gqc3DGoflRCoQbLiIVNrx5FylJb8PVTkHGN/eiMfubz8bbeTfc7Yq55tSvXyWY+dRaMQDM3WFUq9NhYGNBYGNQraktgWZU7tJXfwbuuHvP3227Q3tfNlNQm3ia32hALc+e5B/O938otLkijJiD75YHOIm3b09IVC7XY7S5Ys6asIumjRImy2KfEWpxBCTHqhnfsSso7+rnRfs+Lw4cMxh0IBdN1v6Tg6Bm1GN1lKiql5h/1zTQdDdT2xr6n0SdRG/rHyxwjo5qrznlk11IxZxWn853dXc+hgCy+/WM2+95oIhU6/3tc0hbOX5fDxywpZuCjLcvv4ePhz5lG14SHcJ98j/eA2kit3oeinw8WGqtE9cw3ti67GU7BM2scLIYQQQohxb0q8a5qWlkZDQ8Og29va2kyvlZOTw/Hjxwe1eQc4duxYQoKhnZ2dQ67f1RX9KjohhBBCCCGEEEKIieB/n/iI3SdqqKvtwTDR4dOJfVAlULsy8kFKp+IjU21nmq2JouRK8pKqOTy9nOem1fFMUg+V9sEVqV5x+2gxsbVyu87v3AE+6bWjGFhotBq7bS3ZFDgK8U+fi3/aHGr8c+HtyHO+9KUvUdd+pO/zd5MyuafkfGYmpUc9Xnl3K/ce3cWRnlYAbnipmzc3RK4C9bVXe/jNRwHOKi3lHz7ZWxH0nHPOSUjHHiGEEOOMP4B+IHqVvljo5SehJCFLTRm6rlNWVmaqoIo/0IphhFAsvA6rN9rJwlwwtCY0nZZQGllaR8xz/H43hqEkpJ28oWoEU6bHvc54YKVaaNhwVUNjoaoKi5dks3hJNj5viOZmLx5PELfbRna2C6drHFTNV1Q8hSvwFK5ACXiwdTWgBjzodjfBlOkYkygcLIQQQgghJr8pEQxNT08fUIEzbLjKn5EUFBTw9ttDv0t+8OBBLr30Ukt77K+lpWXI23t6euJeWwghhBBCCCGEEGKkGTEkPd/f20xtT+QqO66+EKirrxKobYRDoDYCZGid5GjNzEyqIC+5mhx3PSnuNlzOLuyOHsJvMb2c4uXpdO+wa5kJhYaFq4bODqkcQ7f4VURX/dkHoSi173NftR+IXIWrf0cegCM9rdx15DUeP/uTEef919G3+FPj0QFB11jiGRf8/c184fwrSU+PHjwVQggxsSkdnaAn6OdeotaZpIJ6kOqeaoqSi9BOva7avXs35eXlptYxjACd3YdJS1lkeg/tRg/dho9kxWlilsJOz0o+kfxX7EpsLeINw0Znx3TS0utN7/FM3TPXTJpQoJVqoWHxVA3tz+nSyC9IjmuNkWbY3QQyZ431NoQQQgghhLBsSgRDZ8+ezTvvvAMwICDq8/nw+/04HI6Y1yopGf4y03fffTe+jdLbjr61tbWvfXz/MKvdbo97fSGEEEIIIYQQQohEa2r0cPxEHRUnelvBU3eUhxaaW6M3BNpbATRFcZLEyIZAVXTS1U6ytRaKkiooSK5mmruOVHcLLlcXDkc3QzR0GeA8X+LfWgtXDV0Y0EwFQ3U0/El5+HNm06adBe9EmXDqi2tqauKdd97h3Z0fkcX6OHY+vINdTZaqn65evRq/hEKFECKidn8722u2RxxzRf4VpDvG9/Op4rcWUhPRdQW62NW4C4AjHUd44vgTeEIe3Jqb62dfz7y0efzhyT9YWrulbZelYCjA0VA9i7RCNBPtuFv0DF7uOY+PJ70Zczi0pWVmQoKh7YuujnuN8SCeaqFh8VQNFUIIIYQQQoyeKREMLS0tHfa+Dz/8kCVLlsS81llnnTXotnCI85VXXrG0v/7eeOONYe9LSTHXVkMIIYQQQgghhBBiNPzge/uoDZ1u7z07KRh1ToaSzCw1p68aqJlQgBkKBilKN1laCzOTqihMrmSau450dzMuVydOZzftaoh0Q0EhShL0DEsDGm4dPAne+qZUL5/x2HjBAH+UsY3n30TS2ecRSMsHtTdI21HdBeyKOO+xRx/j/f2vcuzYMQAynEV8du7IBEPPlJaWxqpVC4HDo3I8IYSYzJp8TWw6sCnimBXZK8Z9MNRwSGGMkVLvreebe7456HZPyMPPy38OftBet3YxTndPOV5fLS5nnum5Pfj4UK+h1JaPasT+YqrRlkvXNX9D1ht/xahpir7HtFJ8qXU4O6tM7zHMlzUbT8Eyy/PHk3iqhYYlqmqoEEIIIYQQYmRNiWDoggULhr1v3759poKhK1euHPB5/6qeNTU17N69m1WrVlnbKPDrX/960G3h9msFBQWW1xVCCCGEEEJElu/O52drfhZ1jBBCjDVDj1578ciHbeTnJ6Oq5oKO/fm8IaoqO2l4v47lllcZ3kw1B6eamcAVDZIULxlqKzOTqihKqmR6Ui0Z7ibcrg6czm5UtbcC50lV5yVnkDcdQd50Bjlk19lbl0pxyFwowoHCuQEbO53Rg7BmlNt1ZnbZ2N6Wy8VURhz7Voud3LQCVNVcOvXPf34On78hnm3GzO6ws+bsNaxcuZJVq1Yxf/583O1V8NRXRuX4E0GyLZmP53086hgxNTlUB3NS5kQdI8REZqSlgqompg28yZ+JU14bhEKxVd8czOBk3VMUF30VTTXTFr6Xz+Fn3Y3pfPBHLy1V0cOKWUV2LtmYw7RiB8YFN6B/WElo5170A8cHPnZUFXXxbLR156CeNZP6lvMpfPYW1KDX9B51m4v6i++AEbqIaTT5Q362VW1LyFrbqrZx66JbsasS6hZCCCGEEGK8mvLB0L179/L3f//3Ma+1ePFiUlJS6O7u7qsU2t/PfvYzy8HQjz76iD/+8Y8D2seHKYrCvHnzLK0rhBBCCCGEiM5tc3NuzrljvQ0hhIio4kQHD/5of9Rxj/38MC+9UM2NNy1kVnEawKD3MIby4tM1tGidVFR0Ulfbg2FAnuZleQxFxhTAjYNkxUWBGv3EfnHaERo8eRiYP8nuwE+m1k6Rq4rC5Apyk2rIcjeS5G7H6ezqC4CGeTH4VZKfN5xBdjlCVNoGh07edIQo9pivlnWeT0t4MBTgu9PTsP1f9H+ze++9l61bt1JWVkZpaSmhUIjyI0cSvp94PProozhnmq8kNpXkunO5f8X9Y70NMU4VJRfx5EVPjvU2hBhZDjvq4tno7x+Neym1RIpsmBKtPHkUXl8NVTWPU5R/g6lwqNOpcfOtS1m0JIslqw2qD3k5+HInFXs96P1yqqoGs85xs+jjqRQudKGcuvBJURW0BbPQFszC8AUwWjvA6weXAyUzDcV5OrDoz5lH7RX3kLf9blPhUN3movaKe/DnTI7zcyd7TuLTfQlZy6f7ONlzkuKU4oSsJ4QQQgghhEi8KREMPTPM2d/evXtNraWqKpdffjm///3vB6wVDon++te/ZuPGjZx33nmm1tV1nS984Qvouj5k4BTg3HPlJLUQQgghhBBCCDFVHdjfzI9+8D4+X2wVnaqrurj3nne5+dalTE9N5YWfRG+12bJHodtw0h5qI3ok8bR5ai5FZKMqKgXJFfz9/MEdUc50bcnjrM17hf898iVOds8acoxGkAy1g0JXNTOTK8hNOkmWu4EUdztOZyeaFtv3wgb8e7qHrggZ1DedQT7vMV9x73y/DUjMCfb+agN1EGO2ory8nC9+8YssWLCAY8eOEfAnUVJ8a8L3ZJXdLpWkhBBCRKetOzsxwdAVpfBuAjY0VSSg4HB3Tzknqh6iIPeamNrKFxalDLiASVEViha7KVrsJuDT6WoK4ffqOFwqKTkadmfkC4kUpx0lNzviGE/hCqrXP8CMVzbhbDkedY++rNnUX3zHpAmFQu+FBun2dNoD7XGvleHIoDCpMAG7EkIIIYQQQoyUKREM1TSNtWvX8vzzz/eFOcPhyzfeeIPu7m6Sk2NvxbR+/Xp+//vf930ebievKArBYJBrrrmGd955h9zc3JjWMwyDr3zlK+zatWvYUCjApZdeGvMehRBCCCGEEEIIMXlUnOgwFQoN8/lCPPK9j5iv5oEeW1v5ZMXJIq2QD/UaOgxPTPU8Z2mdHDFymJ9+kC8seBCnFltQMj+5mn9Zcj+PffDP1HcWUeCoYWbKCfKTqsl2N5DqbsXl6kTT4qvIaUNhpd/GK67h13nTYe0Y5/ptaAaETn17FQOM2L7VMSwOxFj8MxAI8P777wPgdCQlaAPDKygoYNWqVVx41hL4a/mIH08IIcTkp541CyU/B6Mm+sUsw1Hyc1CL8yQY2k+zrznygAxABQYXVDfF66vhRPWD/OTB/+O1VxvY914TodDp812apnD2shw+flkhCxdloapDv2CyO1UyC0ambbs/Zx5VGx7CffI90g9uI7lyF0q/8qSGqtE9cw3ti67GU7BsUrSP78+m2vjeud/j9ndujyscmm5PZ9OKTdjUKXGaWQghhBBCiAlryrxiv/jii3n++eeB00FOAJ/Pxx//+Eeuu+66mNfasGEDX//61+no6OgLcvYPh9bU1HDOOefw85//nE9+8pMR1yovL+df/uVfeOmllwZVM+3/eXFxMcuXL495j0IIIYQQQgghhBg9QT1IZ6Az4phUe6qlk6e6bvDww4dMh0IBknAy18iNORQapikqpWoBqWoTVyRFT1asTXqPlY53WFLyCg7NXD9Sp+bjxkUPEArZsNmihzN1DFTMJy/PixIMPWLXaVJ1cvTYAwBBNRkluYB/1NrISiuky5XCz+q2md7bsDITt1QifOxjH2PZ+SWsWrWK/Px8APTaJvwSDBVCCJEAiqpgv+FK/A9sBX/A/AIOO/YbrkRRexK/uQns2cpnIw9wAPOAD+M/1rp1a1lxbh4rzs3D5w3R3OzF4wnidtvIznbhdGnxHyReioqncAWewhUoAQ+2rgbUgAfd7iaYMh3D7h7rHY6o5dnL2X7Zdo51HcMb8pqe79JczEmZI6FQIYQQQgghJoAp86r9oosuGva+//u//zMVDHW73Xzxi1/kv//7vweEN/uHQxsaGrj66qtZvHgxn/vc51i2bBm5ubmkpKTQ2NjI4cOH+eMf/8if/vQnAoFA39wzq4WGb//qV79q+msWQgghhBBCCJE47f52ttdsjzjmivwrSHekj9KOxHhS0V3BdTsiv7ew9cKtzE2da3rto+XtVFd1WdrXXG0GmsVKR4W2Bi5JehO7Eksg1WDRzDdMh0LDFIVhQ6FVms6bjiC7HEHedAY512/jx23mK2Ke54seRHjTEeTT3sH9VEOKC19SPv6s2fjz5xOYPhdfZjG6OwOAf6Y3HHztjmtN72siufnrXyerMAH9ZoUQQohhqEXTsd94NYGHt5kLhzrs2G+8GrVoOrScGLH9TTT1nnpern05+sCVJCQYumHDhr6/O10a+QWxd+sbC4bdTSBz1lhvY9TZVBvz0+aP9TaEEEIIIYQQI2zKBEPPPfdccnNzqa+vH9RO/s9//jMejwe3O/arAL/1rW+xZcsWenp6BgQ6+4dDDcNg//79HDhwYNh1wvPODIX2D5xOmzaNf/mXfzH19QohhBBCCGHGVKySIYRZTb4mNh3YFHHMiuwVEgwVCffWm/X0lnIyJ11JIllxWjpmltpmIhQKbncrLnfkiqmxOqGFeMXZGwJ9wxGk2jbwIlqfYr3lu92AQIRio284DS5lFv6sWfjz5uPPnYc/s5hQUlZvejWC/a37SbensyRjyaD7vCEvRzoj94SflzqPmooauru7T9/YGnFKQtlsU+ZtQiGEmFQ0RSPDkRF1zESilc5CueU6Ao8/H1NbeSU/B/sNV/aGQsUAj5U/RtCI4bXTHGA60GD9WCUlvVXFhRBCCCGEEEKMD1PmHV9FUbjmmmv48Y9/3BfCDIcvu7q6eOSRR/ja174W83rTpk3jO9/5DrfccsugFvBnhkPPrAJ65r7Cc84UXmfz5s0kJ4/vqyqFEEIIIcQEZOi4q/eQfmgbyZVvoeinwz+GqtE9czXtC6/GU7gcLFabE0IIEb8PDrXidMwwPW+GYjWkbLDO/XbMoVCAnJwTFo812O/dAf4jffi2lsdsOvWqzgwTLd8B3Cgs82vsdg7/db1aOIeTa39uat2wZdnLeHTto0Ped7TzaNSKss0PN9P9YXfEMYmkqCoLFy5k1apVrFy5kpnTFvFMWfOoHV8IIURiFKcU89LlL431NhJOLZqO45s3oH9YSWjnXvQDx0HX+w1QURfPRlt3DupZM1HUyBdwTEX1nnqeqXomtsEq8DfAo4CFAvBut5uysjJUVd47EEIIIYQQQojxYsoEQwGuu+46fvzjHwMMqBoK8P3vf59//ud/RtNiv3L25ptv5rnnnuPFF18cVPGzfyXQaM4Mhfbf2/XXX8/f//3fx7wnIYQQQgghYuFoOsKMVzbhbDk+5P2KHiLlxBuknHgDX9Zs6i++A3/OvFHepRBCCIAI15sOKw03mYq1i0zztQaytA5Tc5wua63uh3KeP/rbVW86gnxmiJbvZ9LR8Nun4U+fiW96CUtsH7K7+XQ7VafqZHHmYpZlLeOcrHNYkjm42udoaWlpGdXj/fyRRzirNPf08astpECEEEKIEaSoCtqCWWgLZmH4AhitHeD1g8uBkpmG4rSP9RbHtcfKHyOgB2KfkAdcB9qTGiFf7BcIud1uNm/eTGlpqflNCiGEEEIIIYQYMVMqGHr++edTVFREVVXVoPsqKyt54oknuOGGG0yt+fTTT7Nu3Tref//9Iat/RqoWOpT+a1xyySX84he/MDVfCCGEEEKIaNzV75K3/W7U4PDV2Ppzthyn8NlbqL3iHjyFK0Z4d0IIIRKhWJsW08WqZ7IRYLnz4IDbNM1HKGStJb0Vy/waDgP8EVu+DwyGGoaKz56DP7UQ/7S5+AtLCUybSyAtD9TTFwEvb3yLjzQ/52Sdw7LsZSxIX4BdHflQSc3JmhE/hlnJKSljvQUhhBBjSO9ffXMY+/btY/bs2eOiCqTitKPkZo/1NiYMU9VC+5sLypcUircXc+LYiajDS0pKKCsrk1CoEEIIIYQQQoxDUyoYCvD73/+e6urqIe/Lz883vV5qaio7duxg/fr1vPrqq30t5MFcKLT/yRrDMNiwYQOPP/44drtc8SqEEEIIIRLH0XTEVCg0TA16ydt+N9XrH5DKoUIIkQBNjR7e29PEjr9+MNZbGeCTSa8wzdVEcnIzKcnNJKe0YBgK5UcuiGl+pabzpiPIcVuIb3a6Le3BhcIKv8abEVq+v+6205z9GfyFpfhz5xFIKwAt+ttcq6etZvW01Zb2ZUYwGOT9999n586d7Nixg0pPJfzLiB9WCCGEiMnhw4e58847o4677777ePLJJyX4NwGZrhbaT3BGkHPvOpfbPLfx5JNP8vrrrxMKnX5dpmka69atY8OGDaxatWpcBIeFEEIIIYQQQgw25YKhK1asYMWKxFY5Sk9P5y9/+Qv33Xcf9913H16vd0BANFaGYZCRkcF9993HP/3TPyV0j0IIIYQQQmDozHhlk+lQaJga9DLjlU1UbXgIFDnxI4QQZlWe6GTPwXL2vtdEdVVv63Wvr93UGim4SFGc1Bnm5sVqVvG7zMosH3Cb1xu9suTdaR7+lNlOta33ItnSgGo5GAqwxmeLGAw9pPVQddEXSLGPn6qXXV1d7Nq1i1dffZXXX3+d9vZ+/0bTRncvar8qqUIIIUR/u3bt4vbbb8fj8cQ0vry8nI0bN7J582ZWrx75iytE/CxXC+3n2ZPP8sWLv8h3l32XqqoqGhsb8Xg8uN1uFixYQEZGRkL2KoQQQgghhBBi5Ey5YOhIUVWVf//3f+fLX/4ymzdv5te//jWNjY0DxpxZFbS/vLw8vvKVr/D1r3+d7GxphyKEEEIIIRLPXb0HZ8vxuNZwthzHffI9aSkvhBAW/OwnB3G1zzA9L01xU6hOJ1NJxq7Y6DF81IViDYYapKld5GmNpKud7PadHXG009ljen8AL7iCfaHQeBiKSvWnv89sown23D78OAz2te7jY9M/Fvcx41FbW8urr77Kzp07eeeddwgGg0MP7AH+GmUxa9/6Ia1YsYLWxujjhBBCTC2HDx82FQoN83g83HbbbWzZsoWkpIKo44981EZ+fjKqeqq7mh79NULdER+Z+XYU1VzBDTFYPNVCwwJ6gMfKH+Pf5v8bLpeLoqKivvvcbusX/wghhBBCCCGEGD0SDE2wvLw8vv/977Np0ybefPNNXn31VQ4dOsTx48dpb2/H6/XicDjIyMiguLiYpUuXcsEFF3DeeeeZrjAqhBBCCCGEGemHtiVmnYPbJBgqpiRN0chwZEQdI6amfHc+P1vzM9rb/ZR/1E75kTYqKzoJhU4HIRxdmZbWnq1OI1NNNzWnUKtjgaOJfFsDabZ2kpNb6LGp7K6IHAwda92zzsOXt4SlgS4UFAxOf/+cqpMlmUtYlrWMc7LOYWnm0lHfn67rfPDBB+zcuZNXX32Vjz76KLaJ3UQPhibQ5ZdfxtbfmAv9CCGEmNx0XaesrMx0KDTM4/FwT9mPKcq/PurYxx45zEvbq7nxpoUk4eLFnzRFnbPj0Rb2v9TJJRtzmFbssLRHAf6Qn21Vifndf1vVNv6l5F8SspYQQgghhBBCiNEnwdARomkaa9euZe3atWO9FSGEEEIIIVACHpIr30rIWsmVu1ACHgz75KoScrTzKNftuC7imK0XbmVu6txR2pEYb4pTinnp8pfGehtinNF1g2NHO9i7p5H39gSpruoB7MA0XKPdP7yfC7Ne5aysSpKTm3G721EUqOvJh4ox21JM2hddDUCKPYWVOStxaS6WZS1jWdYyzko/C7tqH/U9eb1e3nnnHXbs2MHOnTtpaooebhlLJSUlLFmyhK3sHuutCBMavY384sgvIo750rwvMc01ds8rYuy0+9vZXrM94pgr8q8g3WHuIgIxtezevZvy8nLL85OTStD4BPV1sQVLq6u6+FHZIeZrecRavLKlKsAz99Zx1c3TKFw8uX7fHC0ne07i030JWcun+6jx1JBEUkLWE0IIIYQQQggxuiQYKoQQQgghxBRg62pA0UMJWUvRQ9i6GghkzkrIekIIMdF4vUEOvN/C3vca2fdeMx0dfkvrpOAkQ03nqMl5CtHbseYXHmBa8vgOMJ7JlzUbT8Gyvs9/suYnY7aX5uZmXnvtNV599VXeeustvF7viB9z7ty5XHDBBcyaNYv777/fUkU3t9tNWVkZiqqOwA7FSOoIdPBUxVMRx2wo3iDB0CmqydfEpgObIo5Zkb1CgqEioqeeivwcE4nLmU9R/g1oqjPmOUk4mR2aga6bO1bQZ/DnHzbymbtypXKoBUXJRaTb02kPtMe9VoYjgwJ3Aa09rQnYmRBCCCGEEEKI0SbBUCGEEEIIIaYANZDYdrKJXk8IIca7pkYPe99rYu+eJj441EIwGDmcaSi9KQjFOB3QU1BIV9xkKilkKsk4FButwcqYjp+hdpBvqydPawCljX0d803tX8egXEvMBQIjQbe5qL/4DlDGJtBoGAbHjh3j1Vdf5dVXX+XAgQMYRvQAbjw0TWPFihVccMEFrFu3joKCgr77pk2bxm233WYqHOp2u9m8eTOlpaVUV3eNxJaFEEJMUB6Ph9dee83ibIWC3GtMhUIB5moz0Cz+XA/6DP6ypYlr/zMPRVUsrTFV2VQb3zv3e9z+zu1xhUPT7elsWrEJmyqnEYUQQgghhBBiopLf6IQQQgghhJgC9AS3fU/0ekIIMd70bxG/970mqirNBe3aZ+0DIPvECjKVZDKVZDKUZEsBiauS/8qKaT6SU5pJTm6m3tBgj7lg6AMpPn6c0sNnTR995Ok2F7VX3IM/Z96oHjcYDPLee+/1hUFPnjw54sdMTU3lYx/7GOvWreP8888nNTV1yHGrV69my5YtfOtb36KqqirquiUlJZSVlVFaWproLQshhJgEamtrCYWsXSCSnFSCy5lnak66kkSyYi5IeqaWqgDVh7wUSUt505ZnL2f7Zds51nUMb8h81XOX5mJOyhxsqg2fLzFt6YUQQgghhBBCjD4JhgohhBBCCDEFBFOmY6haQtrJG6pGMGV6AnYlhBDji9cb5MD+Fvbuia9FvENRaF38V1QULqv+W7Q4335ZOO8V5mSfDpQ2dOeYXuNcvwYmu7HquoqnJ4P29lzTx3MasVX38mXNpv7iO0YtFNrZ2cnrr7/Ozp07ef311+nqGvnKmgUFBVxwwQVceOGFnHPOOdhssT0eSktL2bRpE5///OcjjrvrrrtYv349qrSPF0IIMYyenh7Lc7My1pieM0NJt3y8/g6+3CnBUItsqo35aeYuJBJCCCGEEEIIMblIMHSC0HVd3uAXQgghhBCWGXY33TNXk3LijbjX6p65BkMqhgohJonmJi/vnaoK+sHB6C3ih5OEkyw1mUwlhdpZu+hJqwfg+Mw3KKm8YNB4jRDTtGZyHeVR11aV+FuarwzYsNmjj+tMmoPjnIvwFJxDd3sK/p9vB38g6ryUgJ119YUs7chlxcUbOKdwFvzupohz6i+4hc7Sq0a8fXx1dTU7d+7k1VdfZc+ePZYrpsVKURSWLFnCBRdcwAUXXMDs2bNRFGttcGN5L2jp0qXynpEQQog+QT1IdU81RclFaIoGQFJSkqW1FMVOarK5atQqChlKsqXjnalir4eAT8fulJ9zQgghhBBCCCGEWRIMHeeOHTvGf/zHfzB//nzuvPPOsd6OEEIIIYSYwNoXXp2QYGj7oqsTsBshhBgbum5w/FhHbxh0j/kW8WEKkKYk9bWJdyq9qUv9/2fvvsOjKtM2gN/nTE8mvUEKSWiG3pQeOojKggUsKBYE1raLsmL/BNeOKGIXVLK6oIAFsIKgAoIUpQeCBEgjvbfJ1PP9wQYTSKaXlPt3XV7CzHPe9wHjJDNzz/MKZhzq+fmFukM916Nz9giIkogwsRwd5YWIlhcgwf8sAgMKkWPKw/Np1veSICFDZsZulRl7lCbcrrM43K+fJOAyk+1QRdk1T0CIPT9aVIwFlA8Fw/DRN0BRudXr3t43EbLoCChmTYYYFwl5aYbNvfRRvTwSCrVYLDh27Bh27tyJ7du348yZM27f42JqtRpDhw7FqFGjMHLkSISGhnp8TyIiIgCoNlZjT9EeAMCpylNYc3YNdGYdNDINZibORLfAbugX3g8ymczhD0coFSEQ/hcutZcKCohOfiDiYhYzUF1sRkiMgz8vSLZ/VlLnp8IQ0snjH1AhIiIiIiIi8hUGQ1uozMxMPPvss/jkk09gMpmwaNEiX7dERERERK2cLnYg9KGJUJWedXoNfWgidDED3NgVEZHn1dWZkHq0FIcOFuPwwWJUVDh3RLwMIoIFP4QIWgQLfpA3EZQ4E/crKgJzL/y+IjAXqi4pmFWuQmhAPvz9S+HnXwq5/PwUzvJS2wGNqeHVKG5wmns/hXMTL/sZZNDbqNGZ69DwzHkxLhKKOX+D8cVPrF6nvHkSZMN7QxDdEwRxlE6nw969e7Fjxw78+uuvKC0t9fieERERSE5OxqhRo3D55ZdDrVZ7fE8iIqKLFdQV4LEDj11yu86sw4fpHwIA1o5ei5EjR2L79u0OrS2KSttFF18D9/4sYKhz7AMxyuJT6LD1OZt1kTuXISh1AwrGPgJDeDdn2yMiIiIiIiJqsRgMbWFycnLw3HPPISUlBUajEZIkOX3cGBERERFRI4KIgrGPIHbjQxBNdQ5fbpGrUTD2kTY7USVKHYWXBr5ks4aIWoeS4jocOliEgweKkXa8DEaj41M2AUAJ+YWpoIGCn9UJWAqxFqm9Pr3k9h/7bMbzhVrInAxKFF+UPz2oMNl9rT6sC3TR/VAb3R9xxXqk/2q9Pr3qFGIwqNFt9oQ9xS4dvR4KLSoqunBE/P79+6HX24q9uq579+4YPXo0kpOTkZSUxCPcyW3UMjUGhg60WUPtk0yQIVgZbLOGyJoZM2Y4HAy1WBz/MI0FksPXWKNU2/+9VpPzBzpuXmT3811V6VnEbnwIeVc+A13sINsXEBEREREREbUiDIa2ELm5uXj++efx0UcfwWAwQJLc++IJEREREREAGMK7Ie/KZxx6sww4HwrNu/KZNj1JRavQYkL0BF+3QUROqj8i/tCBYhw6WISsTOeOiAcAPygRImgRIvpDKzQfxJLDhChZMaLlBejsfxoHEvejOKDokrrTCjO+0Bhxo87xqVtNOaKwHXItHnYvMKA/LOqgC7d1l0qQDut/L5GqSJf78xRJknDq1Cns2LEDO3bswPHjxz2+p1wuxxVXXHFhMmiHDh1sX0TkhBi/GKwYvsLXbVALlaBNwNZJW33dBrViJfoSDB48GF27dkV6errd1xmMZZAks0PHyethhEWS3HKcvCgDtOH27a0sPuXw81wAEE116Lh5EXKmLWvTz3eJiIiIiIio/WEw1McKCgrwwgsvYOXKldDr9RcCofVTQhkQJSIiIiJ308UOQs60Zeiw9TkoK87ZrNeHJvJ4PSJqkfR1Zhw7WuLyEfEAECho/jcZVAu1oGiyRoAF4bIyRMsK0NnvDOID0xGgLYG/tgSCog73RVY1u/6SgDrcoFM4PTW0oT8VZnSxUVMbNwgWtbbRbQGKAMBGMDRK07ImIxsMBhw4cADbt2/Hjh07UFBQ4PE9g4KCMHLkSCQnJ2Po0KHQarW2LyIiImrBNmZtxODwwVi8eDHmzp0LnU5n13WSZERVTRoCtb3s3ssCCeVSDUIF179/xvfXQKGyY2KoZEHUz0ucOhkDOB8Ojfp5CbKnv99mT8ggIiIiIiKi9ofBUB8pKirCSy+9hPfeew91dXWXBEKJiIiIiDzJEN4N+RMXodPn86zWFY56CJVJV/HNMSJqMUpK6s5PBT1QhBMuHBEvQkDw/46IDxb8oWhyEpaEILEK0bJCdNacQefgkwjSFsHfvwRKZePgwVqNEelWJnmmKyxumxra1j9CWl5ejl27dmHHjh3Ys2cPampqPL5nfHw8Ro0ahVGjRqFPnz6Qy/mSGRERtQ4l+hKbNdvytuGfun8iKSkJS5cuxcMPP2x3OLS0fI9DwVAAKJAqEArXg6G9xgfYVafJOQBV6VmX9lKVnoXm3EEeKU9ERERERERtBl/l9rKSkhK8/PLLePfdd1FbW9tkIJQhUSIiIiLyCjvCnnVRvRgKJSKfcucR8QrILkwFDRI0EJt4fPMTdOgoL0Rn9Rl0C0pDaEA+/P1LoVTVNruuCRKWBNieUOXOqaFtTWZmJnbs2IGdO3fi0KFDsFicC/zaSxRF9O/fH8nJyUhOTkZCQoJH9ztXew7PHHrGas2i/osQ4xfj0T6IiKjt2Zi10WaNSTIhJT0Fj/Z5FEOGDMHKlSuxePFiu46V7xgtISJSgaJCo909VUi1qJH08BdUdl9zsdA4BWJ7qu2qDTq+yel9Gq2TuonBUCIiIiIiImozGAz1krKyMrzyyit46623UFNTYzUQSkRERERERC1PtbEae4r2WK0ZGjEUWgWPnXaVvs6M1GMlOHigGIcPFaOi3Pkj4tVQIFTQIkT0R4CgueR+BYzoKC9CovosugedQGRADvy1JVBZCYI2lCY346lAHU5bmRZaz51TQ9uCEydO4JvfN2LHjh3IzMz0+H5+fn4YNmwYRo0ahREjRiA4ONjje9arM9fhQOkBmzVERESOKNAVYFveNrtqN2RvwJ1d70SUJgpJSUlYs2YN9u3bh88//xw7d+6E2Wy+UCuTyZCcnIzp06dj8ODByM6qxvPP/AG93mxlh8ZOmwvQSxYLmRMfNJSrBIybGw5BtP1hGsGog3/WXof3aIp/1h4IRh0kxaU/MxIRERERERG1Nm06GCpJEk6ePImzZ88iJycH1dXV0Ol00Gg0CA4ORmhoKPr06YPOnTt7rIeKigq8+uqreOONN1BVVeVwIJRTQ4mIiIiIiFqGgroCPHbgMas1a0evZTDUSe46Ih4AAqBGiKhFiOAPjdA4hCnCjAhZKRLVmUgKOoaOAZnQakuhVjs+ifRfQbX4UOtYaPXiqaFmVSCAKruv95P5oVdoP9gXW23ZFi1ehLQyz04GjYqKwqhRozB69GgMHDgQSiVDuURE1HakpKfAJJnsqjVajBemhgLnp2cPHToUQ4cOhU6nQ35+PmpqauDv748OHTpAo/krHBmfEIj5C/pi+WtH7A6H1kKPs7ICdJd1hMX+YaOQqwRcNT8CEQn2fc+WVxdCsNgfWLVGsJghry6EMSTeLesRERERERER+VKbC4YWFhZi/fr12LhxI/bu3Yvqattv7AQFBSE5ORl33HEH/va3v0GhULjch06nw+uvv46lS5eivLzcoUBofU39/UOHDsWUKVNc7omIiIiIiIiopbBYJGScPX9E/MEDrh0RL0JAkOD3v2Pi/aEQGr7cISFUrECCKgs9go8iLvAsAvyLodbYH8ZsTj+jzOFr0hUWrI7vgslxU6CL7o9zJQZgzc1WrxkcPhgje47EgNAB6BbYDfm5dXgS1qfXtmc9e/bEqFGjMGrUKHTr1o0fuiUiojapQFeADdkbHLqm4dTQhjQaDRITE61e26tPGJ5cNAgr3j2OnGzbP7fFxmkx796e8IMaP60sRmm27XRoaJwC4+aG2x0KBQDRqLO71hfrEREREREREflKmwmGZmVl4d///jdWr14Ng+H8tA57j2YvLy/HN998g2+++QZhYWF49tlnMW/ePKffOPjPf/6Dxx9/HAUFBS4FQocPH45FixZh4sSJTvVBRERERERE1JLUHxF/6GAxDh107Yh4OWQXgqBBgl+jY0q1Qg0SVFnoFXwUnQLTEaQtglpdCXfnA/+mU2B+sA6Sg+suVRVjSM9rIBNkQOlpm/X/6vUvdOncxckuvUuSJKSlpeHkjq/xsJf2VCqVGDx4MEaNGoXk5GRERER4aWciIiLfSUlPgdGRUZy4dGqoo+ITAvHsi0NwPLUU237MweGDxTCb/3q/QyYT0G9AOMZPjEXPXqEQ/3cU/I3PdkTO8TqkbqtC5iEdGg74FGVAfH8Neo0PQGxPtV3HxzdkcfOx7+5ej4iIiIiIiMhX2kQwdNmyZXj66adRW1vbKHTpSLCz/rri4mLcd999eP/99/HFF1/Y/JRsQ6mpqZgzZw727dvnUiB0xIgRWLRoESZMmGD33kREREREACDpjZBKKwG9AVApIYQGQlC5PhGfiMhZpSV154OgB4pwPNW1I+LVUJwPg4paBEB94fm0StCjkyIHvYOPIDHoFEK0+dBoKtweBL3YFrXJ4VAoAGTVZGHLuS24KvYq9zflIwcOHMCWw79j586dKCoqQlKIiIenB3psv5CQECQnJ2PUqFEYMmRIo+NuiYiI2jpnpoXWa25qqL1EUUDvPmHo3ScM+jozSkrqoNOZoNHIERamhkp96UR1QRQQ11uDuN4aGPUWVBebYaizQKkWoQ2XQaESm9jJPiZtJCRR5pbj5CVRBpM20uV1iIiIiIiIiFqCVh0MNRqNmDVrFtavX99kEBOwb2qoIAiXBDgPHTqEIUOGYOPGjRg2bJjNNV566SU888wzMBgMkCTJqUBocnIyFi1ahHHjxtncj4iIiIjaPqPegqpiE4x1EhRqAQHh8ibfMJMsEiwnM2HeeRiWY2cBS4PQlShC7J0IWXI/iJfFOzx9hYjIFW8uP4Ldp9JdWkMLFUJELUIEf/gJKgCADCbEKHLQN/gwugSdRLg2Fxq/CgiCfSeHuIMJEl4JqHP6+pWnVmJSzCQ3duRbL7/0Ms7qKjy6R+fOnTF69GgkJyejV69ekMkuDZ4QERG1B85MC63n6tTQhlRqGaJj/B26RqESERLjfBD0YpJCg5pOQ6DN2O3yWjWdhkLixFAiIiIiIiJqI1ptMNRkMmH69On45ptv7A5iNufiKaP1axUXF2Py5MnYu3cvkpKSmry2vLwct9xyC7Zs2XJJONXeQOjo0aOxaNEijBkzxqG+iYiIiKjtkSwSclLrcGxbFbIOX3rEXqd+GvQeH4DYXueP2LNkF8L4yQ+QcoubXtBigeXIaViOnIYQHQ7FrMkQ4zgBhYi8I+9cDQA/h64RICBI0CBEOB8GVQpyCLAgUl6EfkGH0S3oBCIDc+CnKYMouh4E1UPC92oj1BAwuc72hGWLoIQuogc+jfRDetn3Tu9bPzW0O7o7vUZbJ5PJMHDgwAuTQWNjY33dEhERkc+5Mi20nqtTQ1uaip5T3RIMreg11Q3dEBEREREREbUMrTYYunDhQnz99deNgpyOBkKb0jDcKQgCqqqqcO2112Lfvn0IDGx8BFpWVhYmTJiA06dPNwqn2hsIHTNmDBYtWoTRo0e73DcRERERtX5FGQb8tLIYpdlNT36xmIGMAzpkHNAhNE6BiRNr4bfpe8Bg36QYKbcYhmVroZg3FbKkeHe2TkTtUEW53m1rySCePyJe8Eew4A+ZICBUVoa+QTtxWdBxdAzMhL9fGUTR+WPoL3ZCbsYn/gZ8pjGgVCahr0HWZDDUIsihC70MuoQrUBfbH3URl8EkCHhj+40u97Dy1Eq8HPeyy+t4islkwqFDh3D0x+24Bd6ZOK3VajF8+HCMGjUKw4cPv+S1mNYqUBGIGfEzbNYQERHZ4sq00HrunBraEuhiB0IfmghV6Vmn19CHJkIXM8CNXRERERERERH5VqsMhm7evBnLly+3OxB68fHyDTV3bcOg56lTp/DMM8/g1VdfvXB/ZmYmRo0ahezs7EZ7NLXexfeNGzcOixYtQnJystW+iYiIiKj9yD6mww/Li2DS2/lhp3NFUKz/BRDMNksbMRhhXLEJwkM3AY6d+EdE7ZzFIiEzowoHDxTh0IFiyApP45MrrF/TJ/AcMmrDITURKlRBfmEqaKCggVZWg35Bh5EUdAyxgWcR4F/i1iAoAFQJEr7SGPCJvwH7lY0fP48ozTikMKGvUYW6oK7Qdb4CutiBqItKAmTKRrVbcr5DVk2Wy/1k1WRhV+Eul9dxp5qaGuzf/DN27NiB3bt3o6qqComaINzS7xqP7RkTE4NRo0Zh1KhRGDBgAOTyVvlylVUR6og2E74hIt8zWUzIqc1BnH8cZILM1+2QFxnMBmzK3uSWtTZlb8KCXgugEG1PTG/xBBEFYx9B7MaHIJrqHL7cIlejYOwjgOC+I+6JiIiIiIiIfK3VvdJuMpkwf/78C7+3NZ3zYhcf927rCHpBECBJEt555x088MADSExMRHV1NaZMmYLs7GyHAqHjx4/H4sWLMWLECJt/TiIiIiJqP4oyDI6FQiEhWbMfCkdDofUMRhg/+QGqefygUkMZ1RmYs3uO1ZoPhn+ABG2CdxqiFqdLQBf8PuV3X7fhE199fgY7ThxHebkBANBNm49/99po87pHL/sBN8T8gedOXoNT1R3gDxVCRH+ECFqEChL6BB1Br+CjiA08gyD/IshkTj6u2WG/woRrw6tRY+X9/vd6Xo6Flz8PSa5qtsZkMeGDUx+4ra/PMz9321ruMGfOHJToMr2y1y0334KkMVPRuXNnqx/qJWoPSvWlWJ+x3mrNjIQZCFWFeqkjakmqjdXYU7QHAHCq8hTWnF0DnVkHjUyDmYkz0S2wG4ZGDIVWofVxp+Rp52rPQW9xz9R2vUWPc7Xn2szzG0N4N+Rd+Qw6bl7kUDjUIlcj78pnYAjv5sHuiIiIiIiIiLyv1QVDP/74Y/z5558XAptNuTiQKYoiIiIiEB4ejqCgIFRVVaG4uBhFRUUwmUwXrrl4zYZTQw0GA5YtW4Y33ngDjzzyCFJTU5sNhV58+4QJE7B48WIMHz7cXX8NRERERNRGSBYJP60sdiAUCkTLChEqq3Rt39xiWDLyXFqjrTFLZpQbym3WELVH+/cVotysBgBcEXIWL/T6En4y+44w7aotwnv91+DD4/OglWrQK+QXJASmI0RbAJnM5Mm2G+ltlMHWTLVvyn/HA4IEtZWaLblb3DIttF6+Lt9ta7mD2eLeKa3WXHfddTCEJnhtP6KWrMxQhpWnVlqtmRA9gcHQdqqgrgCPHXjsktt1Zh0+TP8QALB29FoGQ9uBOP84BCmCUGGscHmtYGUwYv1i3dBVy6GLHYScacsQ9fMSu46V14cmomDsIwyFEhERERERUZvU6oKhy5cvb/a+hoFMpVKJ22+/HVOmTMGYMWMQGBh4Sb1Op8POnTvx/fff46OPPkJVVVWTYc/6wOhnn32Gu+++G++//75dodDBgwdjyZIlGDVqlGt/aCIiIiJqs3JS61CabV+4ql6S8rRb9rb8keaWdYiodbNY7A+md9PmOxQKraeWGXBf77fgi6GQkiSgTh0DXWx/XO2Xic9KdzZbW22qxk95P+Hq2KubvN/d00K9qa6uDvt/PwAgxtetEBERXdDc8IeGLGdyIUSFQRA5XVouyvHK5a9g4e8LXQqHBimCsGTQEsjFVvcWkU2G8G7Inv4+NOcOIih1E/yz9kCw/PUBP0mUoabTUFT0mgpdzAAeH09ERERERERtVqt61n/o0CEcPXq0yWmhDQOZN910E5YsWYK4uDir62k0GkyaNAmTJk3C008/jWeffRavv/76JcfL1/++pKQEN99884XbLg6P1tdHRkbilVdewaxZs9zy5yYiIiKituvYtiqH6uUwIU7unulylvRzQFe3LEVErYxeb8bxY6U4eKAY+QczscDG++GdZTUoMCvx1GXfOhwKreetUKgkAXplB+g69oPusuGoi+kHi+r8BLUpFWn4bGfzwVAA2JC1odlg6NGyowhSBKFPcB+39Vunq8MpnHLbeg0VFxdj586d2LFjB/bt2wcNInFDl9c9sle97t27Y9SoUbhmUDfgwIse3YuIiP5Soi9Bl4Auvm7DIZbsQphWfWOzzvTpVpi3H4Ji1mSIcZFe6KxlGxg2EJsnbsaZ6jOoM9t/ZHo9tUyNztrObTIUeoEgQhc7CLrYQRCMOsirCyEadbAoNDBpIyEpNL7ukIiIiIiIiMjjWtUz//Xr1zd5e31IUxAELF68GE8//bTDa4eEhOC1117DoEGDcPfdd8NoPP9GlyRJFwKgkiTh5MmTVkOhM2bMwLvvvovQUB7rRERERETWGfUWZB3WOXSNv1gLUbB/up9VXjwumIhajo9XpeFYejGMRgviZDrM8c8EbARDb9eewwzNcXTVFnmnSQfVySKgi+xzPggaPxAW9aWnhgBAUlASLgu8DCcrTza71oHSA8iqzkInbadL7hsQNgCrRq5yW98AcPr0adyEm9y6JgA88fjjOH7it0a3aVRu3+aC2bNno//kcejYsSMAQFmaARzw3H5ERNTYxqyNGBw+2Ndt2M18IhPGlZsAg30fOJFyi2FYthaKeVMBZkMhF+XoHtjd1220CpJCA2NIvK/bICIiIiIiIvK6VhUM3bp16yW3NQyF/uMf/3AqFNrQrbfeCp1Oh3nz5jWaHNpwr4a/B84HQmUyGZYtW4YHHnjApf2JiIiIqP2oKjahwYl2dlHA5JlmiKhFkew43v3UyXJER/tDdPBY1bQT5TDCgh7yKtwTkAm1YF9I/LKIdIf28ZRUuRmbNHL8XTUc+stGoK7LFTBrQuy+flqnaVhybEmT93XWdsbUTlMRrAx2U7e2WewI6R85cgSJiYkQRfuPOj19+rQrbTnsyslXQuwY7tU9iYjaixJ9ic2abXnb8E/dPxGlifJCR66xZBc6FAq9wGCEccUmqOaM8ExjRERERERERERtiP3vKPiYTqfDwYMHG4U1GwY1e/TogSVLmn5jx1Fz5szBtGnTGh0jD6DREfINQ6EKhQLr169nKJSIiIiIHGKsc3zyp7F1fbaLiJyQmVGJN18/YrMu5cM0/N/je5GZUXnhNqPRvpBnnEznUCgUMCEgsNDOWvcrFgLxbngMRiX4Y0RUFV4OLMMv425ATe9JDoVCAWBy9GSoxL9GZ2pkGkyLm4aPRnyEtaPX4rbOtyFQ2fTEUXdLS0vDI488YrPu+eefx8yZM5GWlgYAqK6q9nRrRETUgmzM2mizxiSZkJKe4vlmXCRZJBg/+cHxUGg9gxGmr391b1NERERERERERG1Qq3lX+ejRozCZTJdM7QTOB0SfeOIJKJVKt+333HPPYePGS19wa7h3fUD0rbfewrXXXuu2vYmIiIiofVCoHZvyBwA1Fj9YJME9x8k7MHmOiLzj2NESvPHaEej19o0TzsmuxnOLf8eYcTEoLNDhzNEq9MSlR6A3FCCocKd/tgOhUMDPvwyCOx537GSQAlAT0A2746KxTlOAzcU7UWfOAhpkSDZkbUDfkL4Orx2oDMS4juOQU5ODaZ2mYWL0RPjL/d3YvX327NmDhQsXQqfT2VWfnp6Ou+66C/Hx8TiXU4POneZ7tD9RFNG3b1+MGjUK43r2B1IuPcWFiIg8r0BXgG152+yq3ZC9AXd2vbNFTw21nMyElFvs0hpSYRkQ7J5+iIiIiIiIiIjaqlYTDK2filGv4STPiIgIzJgxw6379erVC2PGjMEvv/zS5BHy9aHQ5ORkzJ071617ExEREVH7EBAuhyiDQ8fJmyBHtqkD4hV5Lu8vdo1xeY22JFwVjkd6W5/cF67iMcnkOZkZlQ6FQusZDBZs+SEbflChq6wDYCNzPkQhR6y8zqE9oqNPOFTvKIPFH7V+XaGLH4i6vqNhDo3FvN3zcKD0J6Cy6Wt+zP0R/+r1L6dCnU/3exoKUeFi185LS0tzKBRaz2g0Ij09HSplpIc6A4YMHoJh4+/GyJEjERwcDACw5BXD4LEdiQgAlKISnbWdbdZQ+5OSngKTZLKr1mgxIiU9BY/2edTDXTnPvPOwr1sgIiIiIiIiImoXWk0wND09/ZLb6sOZV199NRQK97+hc/311+OXX36xWvPyyy+7fV8iIiIiah8UKhGd+mmQccCxYFCaoYt7gqGDkoA/XF6mzQhSBuHGhBt93Qa1UxaLhBXvHnc4FFovSPBDd7EjZILtScCJimyn9nAno1mFWnUX6GIGoK7faJiiEgGhcaI1KSgJB0oPNLuGzqzDj7k/4tpO1zq8vy9DoRaLBYsXL3Y4FOot//rXAoTGMnxG5G1x/nFYN2adr9ugFqZAV4AN2RscusZXU0Mli+3J4gUnquF37KwXuiEiIiIiIiIiolZzdmRBQUGz911xxRUe2XPw4MGX3NZwUmn37t0xZMgQj+xNRERERO1D7/EBDl+Ta45EqTnQpX2F6HCICR1dWoOI3Cf1WClysqudutYPKrtDoQDQQeba8a2ukgQRWXPWo2j2G6i+8i6YOnS+JBQKANM6TbO51sasjZ5o0aP27dvX5IdfiYiILpaSngKjxejQNfVTQ72pKMOAzW/Z/vni4OpzgMXihY6IiIiIiIiIiKjVBEMLCwubve/yyy/3yJ79+/eHTCYD0DgQWj+p9Prrr/fIvkRERETUfsT2UiM0ztHJdQJ26q6AUZI5t6lSAcWsyRBEG+dNE5HX/PRjjtPXdpFF2R0KBQBRaDjRS4Kfn3eDojXxwyAp/WzWdQnogj7BfazWHC0/itNVp93VmlesX7/e63sqlUqMGDECc+fM8freRETkHGemhdbbkL0BBbrmBy24U/YxHTY8n4+KfNvH3Stgu4aIiIiIiIiIiNyj1RwlX13d/OSUyMhIj+ypVCoRHByM0tLSJu8fMGCAR/YlIiIiovZDEAWMmxuODc/nw6S3ffxivVJLMLbVDsN4v9+gEBw4elqpgGLeVIhxkUBphuMNE5HbGfQWHD7kXDgzSPCDv6By+DpRNCE4JAdhYRmQJBHpp0Y5tb8zKnpNtbt2WqdpOFp+1GrNxqyNWNBrgatteYVOp8Ovv/7qlb0CA4MwdNgQjB49GoMHD4afnx9KcwxY+3OeV/anxvJ1+Vh2fJnVmod6PoQOmg5e6oiIWjpnpoXWq58aOt1vupu7aqwow4AflhfZ/TzG2HrejiAiIiIiIiIiavVazSsxdXV1zd4XHBzssX2tBUN79+7tsX2JiIiIqP2ISFDiqvkR+N6BN1UBoEjeAdUzrkPojq2QCstt1gvR4VDMmnw+FEpEDtOZdEgtT7Va0yu4FzRyjUPrlpfXwWy2///9hqKEIIevCY84g+4dDkImOz+1q65O69Te9qiChM/9DOhnlGGgUQ59aCJ0MfZ/yHJi9ES8mvoqdGbdJff5yfwwKXoSJsdMdmfLTsuozsCc3dYnct5YfSPMZgfC/C54//330Sk+0Ct7kW01phpsy9tmtWZe93le6oaIWjpXpoXW25C9AWMTxjp8ncVi+2eSU3+Wo2MHP/y0stih5y81Fj9YJOGi6eVEREREREREROQJrSYYajAYmr0vKMjxN8LsFRgYeOHo+IuFhYV5bF8iIiIial9ie2tw7ZMd8OM7RXYdwxgap8C4ueGISFDC3P1vML7widV6+S0TIBvWh8fHE7kgV5eLe/bcY7Vm7ei16BLQxaF19XrngoICgGDBv9FtGtRCB+vHtIeEnLsQCvW0KeFVOKyy4MZaBd6r0qJg7COAA8fe+8v9MSl6EjZmb7xwW9+QvpgWNw0ToyfCT277SHpvMUtmlBvKrdasWLnCO80AEGX2/z0TEVHL4sq00HpGixEbsjY4dE1mRiXefuOYzbqUD9Kwc1MhIkode33cBDmyTR0Qr+D0aiIiIiIiIiIiT2s1wVCLxeKTfUWx+TdSPBlIpaYVFxdj165dSE1NRVpaGkpLS1FVVQWDwQCtVovAwEB06tQJPXv2xIABAzBo0KAmQ73tndlsxrFjx3D06FGkpaUhNzcXBQUFqKmpQV1dHQRBgFqtRkBAADp06ICYmBj06NEDffv2xWWXXca/UyIiIg+JSFDiygfCse6pfKt1o+8KRY/R2gshT3u+N4udoxkKJWqhNn+XBdgIczZFDQVEQQAgIUZegB6K0/AXarCxdpLbe6xnschQXR0GrbYYomj7ebr+f0+pN2mMeHDwI1CGd3N4z2mdpmFHwQ5cE3sNpsVNQ2JAosNrEBERtRYGswGbsje5Za2f8n6yWXP48GEkJibieGoZ3njtiN0fWJEVqwAnPoOQZujCYCgRERERERERkRe0mmBoS6RUKn3dQrtQVVWFVatW4bPPPsPevXsdCglHRkbi6quvxj333IMhQ4Z4sMuWr7q6Ghs2bMD69euxfft2VFRUOLVOZGQkxo0bh5tuuglXX301/z8gIiJyM3vCmx26qRjyJGpDzpypglrleDA0SRaGXso/kaQ8g0CxBgBQZg5wd3sAAKNRhbKyWJSVxsFiUUCtrkCnvulQ6grsur5OADYgHzc6sXef4D74bsJ3UIgKJ64mIiJqXc7VnoPeond9oTzAtN72hPAXXngB69dtg7/qehiN9h3xLkK4ZGq5vXLNkSg1ByJUVunU9QAgRAbbrFHnp8IQ0smhSeVERERERERERG0JXxWhFqu2thZPPfUUYmNjMX/+fPz2228OT44tLCxESkoKhg4diuHDh2PXrl0e6rblysvLw8MPP4zo6GjMmjULmzZtcjoUCpz/O/3ss89w3XXXITY2Fs8995xL6xERERERkXOu9v8Vg9VH/xcKlaDxK0OHDmke2Ssz4wqUFHeGxXI+nKkP7YK8q//t0BobszbaLmqCIAitIhRaXV3t6xaIiKgNiPOPQ5DCxZOqTgP4CECpPcUCLMahdodCAUB1YWq5MwTs1F0BoyRz6mp1QA06Re+3WRe5cxniPv87lMWnnNqHiIiIiIiIiKi1YzCUWqQtW7agZ8+eeP7551FZ6fynxxv67bffkJycjDlz5rSLN+zMZjOWLl2K7t2749VXX0VVVZXb9ygqKsL//d//4bLLLsPHH3/s9vWJiIiIiKh5cpghCBYEBZ9D5y670aXLbwgILPLQbg1ePlAqoJg1GYLoWKDjZOVJpFV4JrjqS8XFxXjjjTfwwP0P+LoVIiJqA+SiHK9c/orz4dA8AJ8BMNpX7u/XFWpVR4e2EOHa6QWllmBsqx3mcDjUP7gMnTvvgbI23656VelZxG58CJqcP5xpk4iIiIiIiIioVeNR8tTiLFmyBI8//rjD00HtIUkSPvzwQ+zbtw8bN25EYmKi2/doCfLy8nDLLbdg+/btXtmvoKAAd9xxB77//nusXLkSWq3WK/sSEREREbVnIWGZ6N4xFQqFG46btZdSAcW8qRDjIoHSDIcv35i1EUl9ktzflw+cO3cOn3zyCTZt2gSDwQBEeG/vTp06eW8zIiLyuoFhA7F54macqT6DOnOd3ddZLBYsvmcxcow5dl8TGjzU4f4ssH+6aHPyzFH4rmYMkjX77TpWXhMnID7sAESzYz/3iKY6dNy8CDnTlsEQ3s3ZdomIiIiIiIiIWh0GQ6lFmT9/Pt544w2P73P06FEMHToU27dvR1JS23hTst6pU6cwadIkZGRkeH3vzz77DGfOnMF3332HsLAwr+9PRERERNTS6PVmh6/RQoXecgv2mKyP+goLy3JLKLRaZ99EMiE6HIpZk8+HQp30/bnvMb/nfKhlaqfX8LXTp08jJSUFW7Zsgdns+H9fV2k0Gtx33/344L0Cr+9NzvOX+2N8x/E2a4iI6slFOboHdnfomj179iDnrP2hUEFQIMDf8ddG9TDCIkkuHCd/XqklGF/XTcBdD0nAniOwHDsLNBwWIIoQeydCNrIvYlNfgFjq3M89oqkOUT8vQfb09wGBh6gRERERERERUfvAYCi1GE8++aRXQqH1CgsLMWHCBPz6669ISEjw2r6elJubi/HjxyM7O9tnPezbtw9XXXUVfvnlF/j5+fmsDyIiIiIiXzt8sBjvvH3Y7vpIQYVx6hr0V56FTjJgT+VlHuvNLIk4UjwIO/MmANoOGIfNVuvlN0+EbHhvCKLzAZB+If1wbadrIaJ1BjKOHTuGlJQU/PLLL00XVAP41sYi1ef/pdVqMWLECGzfvh11dfZPgtNoNFi6dCliYhIBMBjamnTQdMDLg172dRtE1MatX7/eoXqlIgSC4Nhx7sD5iaHlUg1CBddPDYrv7wdl30igbyIkvRFSWSVQZwDUSgghgRBUCmiyf4eq9KxL+6hKz0Jz7iB0sYNc7pmIiIiIiIiIqDVgMJRahLVr1+KFF16wq9bf3x833HADpkyZggEDBiAqKgpqtRplZWU4efIkdu/ejdWrV+Po0aM21zp37hyuv/56/Pbbb1CpVK7+MXzKZDLh2muvdSgUGh0djSlTpmDEiBEYMGAAwsLCEBoaCkmSUFpaiuLiYhw4cAC7du3C119/jcLCQrvW3b9/P+bMmYM1a9Y4+8chIiIi8rrsmmz8a/+/rNa8esWriPOP81JH1NLE+8fjx4k/Wq0JUASgstKA1R+fxJ7dBajTG2yumygDrvevQA/lOSgEEwBAZ/Lc85Pf8pJxtPRyVBhCIVcJGH9dDfBf69eIXTo6FQoNUgRhVucpmNZpGhK0Cc417EOSJGH//v1ISUnBvn37rBfrAOy3XhIaGoqZd8/E9OnTodVqkZaWhscff9yu53Fdu3bF4sWLkZSUhJycavv/EETUKlQYKrA513pI/8roKxGktG/KM7U/Op0Ov/76q0PXiKLS6f0KpAqEwvVgaK/xARd+LagUEDpcegpR0PFNLu8DAEGpmxgMJSIiIiIiIqJ2g8FQ8rnTp09j3rx5NusEQcC9996LZ555BuHh4ZfcHxkZicjISCQnJ+PRRx/Fxo0b8dBDD+HsWeufJj948CAWLFiAt99+2+k/Q0vw0ksvYf9+G+9C/k+XLl2wePFi3HTTTVAoFE3WxMTEICYmBv369cNdd92Furo6rF69Gs8884xdb1p++umnuOGGG3DDDTc49OcgIiIi8hWDxYAz1Wds1lD7JRflCFGFNHu/JEnY/Ws+1nzyJ6qrrR8D39Dt2pPorAq+8HulqhoRodmAhyaG/po/CRbBjNxOv6Ns7E5szUjFf3CVR/Z6d+i7sIR39cjanmSxWLBjxw6sWrUKqampLq/XsWNHzJo1C1OnToVarb5we1JSEpYsWYJbbrnF6vVPPvkkpk2bBlFsndNWici2Yn0xlhxbYrVmUNggBkOpWXl5eTCbzQ5dY3HhZ9sKqRY1kh7+gvMfZgmNUyC2p9pqjWDUwT9rr9N7NOSftQeCUQdJoXHLekRERERERERELRmDoeRz99xzDyorK63WaDQarFmzBtdee63d606bNg2jRo3CzTffjC1btlitfeeddzBz5kyMGDHC7vVbksLCQrz00kt21c6cORPvvfceAgICbBc3oFarcffdd+P666/H3Xffja+++srmNY8++iimTZsGuZwPNURERETUthUV6rDqwxNIPVrq5AoStNoihIVnICCgGGdqLv0wnLsYRT2+/Ns/UK0qAXRAouS5kJFclKM1xalNJhO2bNmClJQUnDljPShuj8TERNxxxx2YPHlys8+L7Al79u3bl6FQIiKyqra21uFrDMYySJLZqePkAeC0uQC9ZLGQCY5/j5KrBIybG25zIrm8uhCCxbHAa3MEixny6kIYQ+Ldsh4RERERERERUUvWJtJaH3/8scfWLikp8cm+F+vfvz/69u3rtf285csvv8TWrVut1iiVSmzYsAGTJk1yeP2QkBBs3LgRU6ZMwbZt26zW/uMf/8Dvv//eKt9se/vtt1FTU2Oz7s4778SqVatc2iskJARffPEFbr75Zqxbt85q7enTp7Fu3TrMnDnTpT2JiIiIiFoqi0XClu+z8MXnp2HQW5xaIygoF90SD0Olsv0zvTtMuLMj/lR3w57i5p/vtjd6vR5ff/01Pv74Y+Tm5rq8Xs+ePXHXXXdh9OjRrfI5JhERtT5+fn4OXyNJRlTVpCFQ28upPWuhx0lLLi4Tox0Kh8pVAq6aH4GIBNtH2YtGnVO9eWs9IiIiIiIiIqKWqtUGQyVJuvDvu+66y6v7eXPfeosWLWpzwVCLxYLHHnvMZt3LL7/sVCi0nlqtxrp169C/f3+rR6AfPHgQa9aswW233eb0Xr4gSRJSUlJs1g0ZMgQrVqxwy56CIODjjz9Geno6Dhw4YLU2JSWFwVAiIiIiapOyMqvw0coTOHum6RMQFLCgl6ICp22sExl5GiqVc5O6GjIExqC0+83AQet1HbqqcK14LfYU73F5z9auuroaX3zxBdasWWP1g6H2uvzyy3HXXXdh8ODBEATrE9CIiIjcqWPHjpDJZA4fJ19avsfpYCgAVEo6pJpzMLRDAmqLbX9IJjROgXFzw+0KhQKAxc3Hvrt7PSIiIiIiIiKilqrVBkMbqg9rttV92+qbSV9++SVOnTpltWbUqFF48MEHXd4rNDQUH3zwAa688kqrdUuWLGl1wdDU1FRkZWXZrHvllVegUCjctq9KpcKSJUswYcIEq3W//PILamtrnZpaQERERETUEhkMZmz66iy++yYTZvOlzwvDRT3GqUoxXFWGvLpiWJ+z77ramIEo73M9ajsNRvU5E4A8m9eMihqFIEUQKowVHu6uZSovL8enn36KdevWoaqqyuX1Ro0ahbvuugt9+vRxQ3dERESO02g0GDlyJLZv3+7QdTW16ajT50Gt6uj03qFxCtz2fAxy0/RI3VaFzEM6NDz9XZQB8f016DU+ALE91TaPj2/IpI2EJMrccpy8JMpg0ka6vA4RERERERERUWvQJoKhng5ONhcA9UZg01ehV29YunSp1fsFQcDrr7/utv0mTZqEa665Bt9++22zNUePHsUPP/yAyZMnu21fT9u1a5fNmhEjRiA5Odnte48fPx5Dhw7Fnj3NTxoyGo3Ys2cPxo0b5/b9iYiIiIi8Le1EGVZ9cAL5ebWNbhcgoZeiCuNUpeipqIQ3Pt9X3XkUskZdDUNogsPXKmVKXBN7DdacXeP+xlqw/Px8rF69Gl999RXq6upcWksURVx55ZW444470LVrVzd1SERE5LwZM2Y4HAwFJJzLX4+EuL9DJqoc3lOlkmHevT0hk4uI661BXG8NjHoLqovNMNRZoFSL0IbLoFDZf9R8o+4UGtR0GgJtxm6nrm+optNQSJwYSkRERERERETtRJsIhrbViaFtdVIoABw/fhx79+61WnP11VdjwIABbt33ySeftBoMBYBVq1a1qmBoWlqazZqrr77aY/tfffXVVoOhwPkeGQwlIiIiotaspsaItWvSsf3nc41u9xNMGKEqwxhVCcJlhkb3yeV1CAvL8FhPp/v8Db+XbsUUvymIUEc4fP20TtPaTTA0MzMTH3/8Mb799luYTCaX1lIoFJg6dSpmzZqF2NhYN3VIRETkusGDB6Nr165IT0936Lo6fS6ycz9BXPQsh8KhKpUM8xf0RXxCYKPbFSoRITHOBUGbUtFzqluCoRW9prqhGyIiIiIiIiKi1qFNBEOp9Vm9erXNGnccIX+xYcOGYfDgwdi3b1+zNV9//TWqqqoQEBDg9v09ITs722bN2LFjPbb/uHHj8PTTT1utyczM9Nj+RERERO4SogzB3G5zbdZQ+/P7/kJ8sioN5eV/BT/jZLUYoy7BYGU5lELjDw1qNOUICz+LoKB8pJW5FkK05r4990EXdP7Y+Lu63uXw9V0CuqB3cG/UVNl+TtFanTx5EikpKdi6davLH+708/PDDTfcgFtvvRXh4eFu6pCI6DyZIEOwMthmDZE1oihi8eLFmDt3LnQ6nUPX1tSmI68wBQP6PoCiQqPN+tg4Lebd2/OSUKgn6GIHQh+aCFXpWafX0IcmQhfj3iEEREREREREREQtGYOh5BOfffaZ1fujo6M9NmFy1qxZVoOhOp0OGzZswKxZszyyv7tVVVXZrImJifHY/vZMyLGnRyIiIiJfC1WF4u+X/d3XbVALUlamx39T0vD7/iIAgBwWDFRWYKy6BJ3ltRdVWxAUlI+w8Az4+ZV7pT+LZAYAbMzaiDu63AFRcHwy17WdrsXW4nXubs3nDh48iFWrVmH3bteniwUFBeGWW27BjBkzEBQU5IbuiIgulaBNwNZJW33dBrUBSUlJWLp0KR5++GGHwqEajQYvvPgwrrhiMI6nlmLbjzk4fLAYZvNfH6yQyQT0GxCO8RNj0bNXKETRSydeCSIKxj6C2I0PQTTVOXy5Ra5GwdhHACd+ViIiIiIiIiIiaq1aVTC0/mj1tnzE+sXa4p/11KlTOHPmjNWaG264AaLomRfqZsyYgX/+859Wp8Vs3ry51QRD7eHJaTYREbaPrDSbzR7bn4iIiIjI3SwWCTt+ycXaNadQW2tCiGjAKFUpRqpKECg2/tlWJtMjNDQboWGZUCj0btnfpAlGRfzfgN/tq8+pzcGBkgO4PPxyh/eaEjsFU+QjYNr6icPXtjSSJGH37t1YtWoVDh065PJ6kZGRuO2223DddddBo9G43iAREZGXDBkyBCtXrsTixYvtOla+a9euWLx4MZKSkgAAvfuEoXefMOjrzCgpqYNOZ4JGI0dYmBoqtW8m1xrCuyHvymfQcfMih8KhFrkaeVc+A0N4Nw92R0RERERERETU8rSqYKirx75Ry7B1q+3pB1deeaXH9o+KikK/fv2svlG4bds2j+3vbqGhob5uwaaQEB65SkREREStQ35eDVZ9cAJpJ8qQJK/GGG0J+ikqcfFALJW6EiFhZxEUnAuF6J7nqnXh3VDR5zpUdRmDijwDgD12X7sxe6NTwVC5KIellX8g0Ww246effsKqVavw559/urxeXFwc7rjjDlx99dVQKpVu6JCIiMj7kpKSsGbNGuzbtw/r1q3Drl27Gn14WyaTITk5GdOnT8fgwYOb/JC+Si1DdIy/N9u2Shc7CDnTliHq5yV2HSuvD01EwdhHGAolIiIiIiIionap1QRDFy9ejOLiYl+34TP9+/f3dQtu89NPP1m9Xy6XY/To0R7tYcKECVaDofn5+UhNTUWvXr082oc72DMNtLi4GJ06dfLI/kVFRTZrwsLCPLI3EREREZG7mEwWfP9NJjZ/lY5BYgluDipBR9nFE0AlBAQWICwsA1ptKdZqDBAA3KhzLTxYGzcIOePvQF2H3sCFkKbBoTV+yvsJj/R+BIDKpV5aE6PRiG+//RYff/wxsrKyXF6ve/fuuPPOOzF+/HjIZL6ZhkZtV1FdET469ZHVmtndZiNCbftUDiIie4miiKFDh2LAgAHIzs5GUVERdDodNBoNevTogeDgYF+36DBDeDdkT38fmnMHEZS6Cf5ZeyBY/gq8SqIMNZ2GoqLXVOhiBvD4eCIiIiIiIiJqt1pNMPSaa67xdQvkJr//bv08xF69ekGr1Xq0h6FDh9qs+eOPP1pFMLRPnz42a3JycjwWDM3JybFZ06NHD4/sTURERETkDmdOV2DTe38gqSwbz2nLoBYsje4XRSNCQrPhH56Bc5oa1AIwQ8JzAToAQC+jCBHnA52JJhFqODaBs3jYvQjq2MWlP4PeoscP537AePk0l9ZpDXQ6Hb766iusXr0aBQUFLq/Xr18/3HXXXRgxYgQEF6anZtdk41/7/2W15tUrXkWcf5zTe1DrVWmsxPrM9VZrpidMZzCUiDxGrVYjLu6v70EajcaH3bhIEKGLHQRd7CAIRh3k1YUQjTpYFBqYtJGQFK34z0ZERERERERE5CatJhhKbUNZWRkyMjKs1gwcONDjfQwaNMhmzcGDB3H77bd7vBdXJScn26z55ZdfMHz4cI/sb2sCrCAIGDFihEf2JiIiIiJyRV2NAXs/2I3g4ydxj6IGUDe+X6msRlh4JoKDcyCTmXFCbsawqKpL1hkRVX3h178VBKCHyTfTJjdmb8T4xLYbDK2srMS6devw6aefoqKiwuX1hg8fjrvuugsDBgxwQ3eAwWLAmeozNmuIiIjIfSSFBsaQeF+3QURERERERETU4jAYSl5l7fj2en379vV4HwkJCQgMDERlZWWzNQcPHvR4H+7Qo0cPxMfHIzMzs9mab7/9Fk888YRH9v/222+t3j9w4ECEhIR4ZG8iIqLWQl9nRnGxDnV1ZqjVMoSHa6BS85hiIl+RKmuQ++VeKH5PxRAYAUWje6HVFiMsPAMBAUW+atEhMkGGEZEjMC1uGiSj5Ot23K64uBhr1qzB559/jtraWpfWEgQB48ePx5133omkpCQ3dUhERERERERERERERNSyMBhKXvXnn3/arOnatasXOgG6dOliNfxpT68txf33349HHnmk2ft3796NHTt2YNSoUW7dd+vWrdi7d6/Vmvvuu8+texIREbUWFouE1GOl+OnHHBw+VAyz+a+wlkwmoF//cIybGItevUMhis4fXUxE9pEkCdKZXNRtOwDpaDrCpMYBSkEwISTkHELDMqBW17hlT4tCg+NdegLY5pb1LtZB0xF/S7oRU2KnIFwdDgAozWk7EynPnTuHTz75BJs2bYLB4NqfSyaT4ZprrsHtt9+OhIQE9zRIRERERERERERERETUQjEYSl519uxZmzXeCoZ27drVajA0Pz8fdXV1UKvVzda0FHPmzMHzzz9v9TjFhQsX4tdff4VCoWi2xhF6vd5qGBUAIiMjMXPmTLfsR0RE1JpkZlRixbvHkZNd3eT9ZrOEA38U4cAfRYiN02LevT0RnxDo5S6J2gdJb4T59xMw7zgM6VwRxIvuVyh0CA3LQGhoNmQyk1v2LA+Mwtr4rvjUkoVDf3omFAoAywe/jti4AI+t7yunT59GSkoKtmzZArPZ7NJaKpUK119/PW699VZ06NDBTR0SERERERERERERERG1bAyGklfZEwyNi4vzQidAbGys1fslSUJGRkarOF4wJCQEr732Gu6+++5ma/bt24d58+Zh1apVLu8nSRJuv/12q8FaAFi+fHmrCNYSERG507GjJXjjtSPQ6+0LM+VkV+P5Z/7A/AV90atPmIe7I2o/LEVlMO84DPOeVECnv+heCX5+ZQgLP4vAwAIIbhza+8flN+PRvNWoKT3pvkWb487GW4Bjx45h1apV2L59u8trabVa3HTTTbj55psREhLihu6IiIiIiIiIiIiIiIhaDwZDyauys7Ot3q/VauHv7++VXuyZFpOVldUqgqEAMHv2bGzYsAFff/11szUpKSkwGo147733oNVqndqnrKwMc+bMwZdffmm17oYbbsDNN9/s1B5EREStVWZGpUOh0Hp6vRnLXzuCJxcNQoCcH6ogcpZkscCSmgHzzkOwHM+45H5BMCMoKA9h4RnQaCodXt8MyWZNSMIYBBR/jRpTrcPrt0eSJGH//v1YtWoV9u/f7/J6YWFhmDlzJm644Qann/MQERERERERERERERG1dgyGklcVFxdbvd+bR/t17NjRZk1JSYkXOnGfzz77DFdddRV27NjRbM3q1auxd+9ePPPMM5gxY4bdR8vr9XqsWbMGixYtshnwHT58OP7zn/841DsREVFrZ7FIWPHucYdDofX0ejNWvHscDz0wwM2dEbV9UrUO5j3HYN55BFJJxSX3y+V1CA3NQmhYFuRyg9P7/Ki2fdT8b4W/YWrcVKz4c4XT+7QHFosFO3bswEcffYTjx4+7vF50dDRmzZqFv/3tbzy1gFoktUyNgaEDbdYQEREREREREREREbkDg6HkVaWlpVbvDw4O9k4jdu5lq9+Wxs/PD99++y1uvPFGfP/9983Wpaen49Zbb8XChQsxdepUjBgxAgMGDEBYWBhCQkIgSRLKyspQXFyMP/74A7t27cKmTZtQWFhos4fhw4fju+++89rkVyIiopYi9VgpcrKrXVojJ7sap9MvDbURUdMsmfnnj4s/kAYYLw1lazTlCAvLQGBQHkTR9rRPa0yQ8JHfxUfSX+rzrM/x/rD3sfLPlZDsmDDa3phMJmzevBn/+c9/cObMGZfX69y5M+644w5ceeWVkMt9+xJHiDIEc7vNtVlD7VOMXwxWDGdgnOxnspiQU5uDOP84yASZr9shIiIiIiIiIiKiVobBUPIaSZJQXl5utSYgIMA7zdi5V2sLhgKAVqvFt99+i9dffx2PP/449Prm37zOzc3Fe++9h/fee8/lfQVBwMKFC/H888/7/A3Z3377zaXrjx49esltRqPR6t8ltR5Go9Gu24iImmLtMeTHzVlu2eO3XflQIchqjcFggF7/V+BMMtiegGgwGCBc/L3Mzuvay/fAXF0uXkh9wWrNE72eQLQmutFtBif/Ho12XGe86DqDwfb3rIu/PgAnv0Za6NeHZDQBh08Du44CWQVNVFgQGJSP8LAM+PmXu2VPiyjHJ3HxyDb9YbM2X5ePPwr/wBVhV2BfyT671nfX18f5tRz/GvHGY4her8e3336LNWvWIC8vz+Z1tvTo0QO33347Ro4cCVEUYTabYTY7N7HZXfzhjzsT7rRZd+l/M8f/X/Pm1wfQth5DWps2+z3m/I127tc+vkaqjdXYV3r++0Z6VTrWZa2DzqyDRqbBjZ1uRNeArhgcOhhahfbCNd78+ji/Vsv8HkO28bUQInIWHz+IyBV8DCEiV/AxhIhaqtb0WMRgKHlNbW2tzTfqvBkMDQwMtFlTWVnphU7cTxAEPPTQQ5g+fTpeeuklfPjhhx59oXzSpEn497//jSFDhnhsD0cMHz7c7WuWlZWhqKjI7etSy2ArtE5EZE15eTkMBguOHi5xy3p/ppWjj2g9GFpWVgaTUrjwe1lpBWzNoCsrLYNZZml0m19Vmc1+SsvKUGvys1nXFuTp8nCw7KD1mqI8KDSKRreVldn+e2zqZ4nSUts/n5WWlkGhrL3w+6oy2xMoL/76AJz7GmlpXx9iRQ3Uh05DfegsRN2lf3cymQEhoVkIC82CQlnnlj0NygDkdhqL7E6j8UrG/wG2T5IHAHxw6gPc0uEWu4Oh7vr6AJz7GvHkY0huXi4+X/cDNm3a5Jafufr06YPp06ejb9++EAQBJSXueez1JWceQ7z59QG0jceQ1qqtfo8B+DVysSxdFv7v5P9dcrvOrMN/zv4HAPDGZW+gk6bThfu8+fUBtLzvMe3p68MT+FoIETmLjx9E5Ao+hhCRK/gYQkQtgT2vybUUDIaS19gzxUClUnmhE/v3ak0p76bExcXh7bffxqJFi7BhwwZ8+eWX+PHHH2GxWGxfbENsbCyuu+463HbbbRg8eLAbuiUiImq9ysuMcMO3VwA4v47onrWIWj1JgiKzEOo/TkGZngdBujSQolJVISw8A8HB5yCK7vkfsSqwE84lTERh9BBYZEr8UvoLcvW5dl+fq8+F0WJEgCwAVahyS0+t1aJFi3Awt8bldQYPHozp06eje/fubuiKiKh9k5r4fnqxzIxaREQqIYqCzVoiIiIiIiIiIiJqeRgMJa+xJxjqzSPI7dnLnp5bg1OnTuHUqVM4e/asW0KhMpkMI0aMwPDhw3HZZZe5oUMiIqLWTa93UyqUiAAAQp0BqmMZUB84DXlpU8FKCQEBhQgLz4BW656JkRIEFHcYiJyESagI7Q4IAiRJgkUyY13BOofX+7zwc4wJGYNDpYeQjWy39Nga6XQ6p68VRRHJycm4/vrrER8f78auiIhapzJjWaOJoc7IPVeHz1afs1m38csC7Nldjuk3dUR0jNqlPYmIiIiIiIiIiMj7GAwlr2Ew1LssFgu++uorPP/88zh40PqRqI4ym81Yu3Yt1q5dC5VKhTvuuAOPPfYYEhMT3boPERFRa6FSccQnkTvIiiqgPpAO9bFMCMZLz20XRSNCQnIQFpYJpaq2iRUcZ5T7Ia/TKOTGj0edX8SF28uN5Xg542V09+vu0LTQern6XEyPmo6JiRPxT/zTLb22FwqFAuPHj8d1112HqKgoX7dDRNRibC3din6B/Zy+Pv3PGqz+OAcGg+2JoQBQkK/Hynczcesdsejazd+uSaOlmRK0EYDASaNEREREREREREQ+xWAotSiC4L0XjUXRdoDDnhe8W6ITJ07g1ltvdXsgtCl6vR4rVqzARx99hDlz5mDp0qXw9/f3+L7W7N6926Xrjx49ir///e+NbgsJCUFEREQzV1BrYjQaUV5e3ui24OBgKBQK3zRERK1Kc48hgYEiRFkGLGbXf3YQZbZ/HgoJCUFIxF+PW5LZ9s81IaEhECLCGt2mktsO1oWGhMA/pH18D6yqtn3kd0hoCCK0jf8+qqrsuK6JnyWMhhoAZ61eFxoagoiIv362khuMAKxPyLz46wNw7mvEW18fktkMHDsL7DoKnG46gKlU1iA0LBMhIdmQycwu7VdPHxSLkh5TUdFlHCwKDQIABPzvvjPVZ/BY2mPIr8tHWk2a03t8VfwVnuvwnM06d319AM59jXjyMcQRGo0G119/PW688UaEh4e7de2WzJnHEG9+fQAt+zGkrWur32MAfo1cLLMk02bNbxW/QQqQEKmOBODY10dWZjXWfPKn3aHQegaDhDUfn8Pf7+qNtE0GANa/Dx/ZICF7vwyjZgchrJOCXx8tBF8LISJn8fGDiFzBxxAicgUfQ4iopSooKPB1C3ZjMJS8xp5v0CbTpVOBPMVoNNqsUSqVXujEvd577z0sWLDA4SMbVSoVQkJCEBYWBrPZjNLSUpSWltr938RkMuG9997DTz/9hDVr1mDQoEHOtO8Ww4YNc/uaCoUCKpXK7etSy8D/vkTkivrHkP79w3HgjyKX10tKCgZOWq9RKpVQqf76OcWiVMLWnHOlUgnxosc6e37WUSqVQDt5jFQa7Pv7uPh7hr1/jxdfp1Da/nlUcdF1SqXt4PDFXx+Ac18jnv76kCqqYd51FKZdR4CKmqYq4K8tRlhYJgICCuGuz5DVxA1GRZ/rUBs7CBBEXPwsZXfhbjx+4HHUmGr+14Xzge/s2mzsL99vs85dXx/n13L8a8SZr4+DBw9i25p38V5Xm9vZFBQUhFtuuQU33ngjAgMDXV+wlXHmMcSbXx9Ay3wMaS/a6veY+tvs2a+9fI18l/+dzRqTZMKarDV4tM+jAOz/O1QolEj58BT0eotTvakNauz5sAaiZN+U/LJzJny7pBRXzY9AdBi/PloqvhZCRM7i4wcRuYKPIUTkCj6GEFFL0JoC6gyGkte0xmBoa/qfGQBeeOEFPPnkk3bV+vv748Ybb8SYMWMwevRoxMfHN1mXlpaGnTt3Ytu2bfjyyy9t/r39+eefSE5OxrfffouxY8c6/GcgIiJqrcZNjHVLMHTI8CgcOOnYBzyIWgtJkiCdPgfTjsOwHDoFWC4NqAiCGcHB5xAWngG1utot+5plalQlXYmK3tfCGBzXbN3as2vxauqrsMC54ExTPs/83G1r+ZokSdi1axdSUlJw6NAhJIWIQFfng5yRkZG47bbbcN1110Gj0bixUyKi1qVAV4Btedvsqt2QvQF3dr0TUZoou9dPPVaKnGznvqf6QYXuYke7Q6H1THoJ3y8vwvXz5LB1rozlTC6EqDAeP09ERERERERERORGDIaS19jzSX+DwdYMAfdpaxNDX3vtNbtCof7+/njkkUdw//33IywszGZ9UlISkpKSMHfuXOTk5OC1117Dm2++aTXEq9Pp8Le//Q3ff/89kpOTHfpzEBERtVa9eociNk7r9JvuABAbp0WXrkE4AAZDfSFQEYgZ8TNs1pDjJL0R5v0nYN55CNK54iZrFAodQkMzERKaDbnc9s/q9tCpI1Ez4HpUXjYZFpW22TqTxYRlx5dhbcZat+zbUL4u3+1r+sLuXbvxzpef4c8//3R5rbi4ONxxxx24+uqrW9VzLiIiT0lJT4FJsu/D0kaLESnpKRemhtrjpx9znG0NXWRRkAmOhULrBRrLIH2yz2ad6dOtMG8/BMWsyRDjIp3ai4iIiIiIiIiIiBpjMJS8xs/PD4IgQJKaP4qxuto9E4HsUVVVZbPG39/WTIOW4bfffsPChQtt1vXq1Quff/45kpKSnNonNjYWr732GqZPn46bbroJOTnNv7FQU1ODG264AampqYiIiHBqPyIiotZEFAXMu7cnnn/mD+j1ZoevV6lkmHdvT4juOi+bHBahjnAoZEG2WQrLYN55GOY9qYBO30SFBD+/MoSFZSAwqACC4Pyx7Q2dUyUBo26GLmEYIMps1u8u2u2RUGhbsnz5cpzVVbi0Rvfu3XHXXXdh3LhxkMls/3chImoPCnQF2JC9waFr6qeG2sNgsODwoaY/lGFLkOAHf8G5I/qiZQUY5/cbFBb7fi6WcothWLYWinlTIUtq+lQbIiIiIiIiIiIisp9zH/cmcoJMJkNgoPUJS/aENd3Fnr1CQ0O90Ilramtrcccdd8DSxDGcDQ0dOhT79u1zOhTa0PDhw/HHH3+gS5cuVuuKiopw7733urwfERFRaxGfEIj5C/pCpXIs8KRSyTB/QV/EJ3AaJbV+ksUC85HTMLz1BQz/XgXzzwcuCYXWHxffpcsudO6yB0HB+S6HQg0WOfYYByN10pvQ3fkWdJ1H2hUKBYBRUaNwc8LNLu1Pzevfvz+WL1+O1atXY+LEiQyFEhE1kJKeAqPFsUnZ9VND7VFRboLZ7Nz32CghyKnrQsXy86FQwcEPSxmMMK7YBEt2ISBZf50LANT5qXbVERERERERERERtUecGEpeFRoaioqK5qfMWLvP3ezZqzUEQ9966y2cOnXKak1CQgI2btwIPz8/t+0bGRmJb775BsOGDUN5eXmzdV988QW2bNmCSZMmuW1vIiKilqxXnzA8uWgQ3n7jGArya23Wx8ZpMe/engyFUqsnVetg/u0oTDuPAKWVTdbI5HqEhmYhNDQTCoXBLfuW6APxbekgBEy6CX2Gd3V6nYd6PYTs2mzsKtzllr7ovGcWP4MuI67ydRtERC2SM9NC623I3oCxCWNt1hkMzoVCRQgIFpw5SUdCsma/46HQegYjZGtWo0OnQzZLI3cuQ1DqBhSMfQSG8G7O7UdERERERERERNRGMRhKXhUWFoazZ882e39BQYHXesnPz7dZExYW5oVOnGcymfDWW2/ZrFuxYgUiIyPdvn9SUhJefvll/P3vf7dat2zZMgZDiYioXYlPCMQDD/bB/z2212rdXXOSMGpMDESRx8dT62XJzIdpxyFY/jgJmJoOgajVFQgLz0BQUB5E0T2TvU5WxmJNzkBIvcfihoVJ8PdXuLSeTJDhhYEvYOb2mTinO3fJ/WGqMHTUdIQAx/5/rdPV4RSsf5DL18rLyuG+j5A11qNHD7gnAkzUupXqS7E+Y73VmhkJMxCqavkfUCX3cWZaaD2jxYgNWRts1imVzv2cqYICouD4tdGyQoTKmv6AiD38tUXoFHAAskr7gqWq0rOI3fgQ8q58BrrYQU7vS0RERERERERE1NYwGEpeFRMTg99//73Z+8vKymAwGKBUKj3eiz3B0JiYGI/34Yqvv/4a2dnZVmtGjRqFiRMneqyHu+66Cy+//DLOnDnTbM3mzZvx559/onv37h7rg4iIqKWxJ+zZtXswQ6HUqhlWfQPD2eZifxYEBhYgLDwD/v5lbtnPbBGxs7gXVucMQIl/V8y+pweSeoS4ZW0A8Jf74/3h7+OOX+9Aib4EACBCxL96/Qs3Jd4Ek8WEKmOV1TUCFAGQi3891T59+jRuwk1u69GdcnJy8Mknn+Doj9vxUU9+kMtV52rP4ZlDz1itWdR/EWL8WvbzTPKMMkMZVp5aabVmQvQEBkPbEVemhdb7Kf8nmzVBwXLIZILDx8mLDn4Qol6S8rRT1wHnP0jSqdMByGSOTRsVTXXouHkRcqYt4+RQIiIiIiIiIiKi/2EwlLwqMTHRZk1ubi4SEhI83ktubq7NGnv69aUtW7bYrHnwwQc92oNCocADDzyABQsWNFsjSRK+//57BkOJiIiIWhPJ9mRPTXk66hAHNAiPyGQGhIRkIzQsE0plnVtaqTJq8U3eQHx2rg/KzIG4eko8HrouEUqlzC3rN9RB0wGvXv4q/v7b3yEX5Xhh4AsYETkCAJBZk4mbtlsPea4dvRZdArq4vS93ysrKwrL3/4MtW7bAbDYjURPk65bahDpzHQ6UHrBZQ0QEuDYttJ7JYrJZo1SK6Nc/HAf+KHJobQscP4JeDhPi5LY/iN00CbGxRxwOhdYTTXWI+nkJsqe/Dwiikz0QERERERERERG1HQyGklfZE/hMT0/3SjA0PT3d6v0hISEIDAz0eB+u2LFjh9X75XI5xo8f7/E+7JlIunPnTsyfP9/jvRARERGR65TFp9Dhx+ds1sXEHkNYWCZycvpCkkSEhWUgOOSc246Lz67piHU5V+Cbwm4wWBRI7ByI+fN6oFOnALes35zeIb3xwsAXEOMXg66BXT26ly88vHAhyvXWTx6wJSAgANdfPxnAj+5pioioHTGYDdiUvclr+42bGOtwMFQPIyyS5NBx8v5iLUTB8UApAGi1xVBrrE/ltkVVehaacwd5pDwREREREREREREYDCUv69rV9puq6enpmDBhgsd7OX3a+tFW9vTqS7W1tThx4oTVmssvv9wr4dbevXsjKioKBQUFzdbs3bvX430QERERUdMki+2QhuV0LoSoMPjlHkDHzYsgmuybbKjWVKFL111wIDdivQ9JwMGS3liTMwB7KjoCEKBUibhlRhdMmtwJouimjWwY3WG0V/ZpbcLCwjBz5kzccMMNCDUUA+sZDCUictS52nPQW/Re269X71DExmmRk11t9zUWSCiXahAqaO2+RgHbE0ybExqa5fS1DQWlbmIwlIiIiIiIiIiICAyGkpf179/fZs2xY8c83kdhYSGKiqxPSrCnV18qLi6GJFl/gz8+Pt5L3Zzfy1ow1Np9REREROQ5luxCGD/6xmad6bOtUOzaho6hP0K0GBzawx2hUJ1Jg5/zB2P1uT7IqPsrhNK7TyjuvLsHIiI1rm9CTouIjMBNt9yLKVOmQK1Wn7+xtNi3TRERtVJx/nEIUgShwljhlf1EUcC8e3vi+Wf+gF5v/1HtBVIFQmF/MNTo5EvNgmBCQGChU9dezD9rDwSjDpKCPzcQEREREREREVH7xmAoeVVMTAwiIyNRWNj8i70HDhzweB9//PGHzZoBAwZ4vA9XlJSU2KyJiIjwQifnhYeHW73faDSiqqoKAQGePfaTiIiIiP5iPpEJ48pNgMFoR7WEGNVOh0OhrirUReK7cyOwLr8rKsyyC7f7axW4dVZ3DB/ZAYITydOvMr9C54DO6Bfaz53ttngms/2BH0csf305FHFRHlmbiKi9kYtyvHL5K1j4+0KXwqFauRbVsG8KaHxCIOYv6Ivlrx2xOxxaIdVCBz00UNlVXxBNWVkAAQAASURBVGPxg0USHD5OXqnUQXDyCPqLCRYz5NWFMIZ478PSRERERERERERELRGDoeR1AwcOxA8//NDs/YcPH4bRaIRCofBYD/v27bNZM2hQyz52qrra9gv/QUFBXujkvODgYJs1FRUVDIYSEREReYklu9CBUCig0ZRBranycFd/OVHWCxvPDcHmkg4wwNLovmHDO2DmrO4IDFI6vK5ZMmP58eVYc3YNQpQhSBmZghi/GHe13WLV1dXh66+/xpf/3YJRQU+5fX2ZXGa7iIiI7DYwbCA2T9yMM9VnUGeuc/h6tUwNFAAz35hp9zW9+oThyUWDsOLd43YdKx8bp8WEa8Ox96NqmPS2g5smyJFt6oB4RZ7dPQGAKLr3Qw2iUefW9YiIiIiIiIiIiFojBkPJ60aPHm01GFpbW4s9e/YgOTnZYz389NNPVu8PCAjAwIEDPba/O1w4vtGK8vJyzzfiwF4qlX0TJoiIiIjINZJFgvGTH+wOhQJAUJBjIQ5n6M1K7C8chi9yBuGPWjXMsAANQqFh4WrcMTsJ/fpbn0bfnFpTLZ48+CR2FuwEAJQZyvDQvofw0YiPoFXYfxRua1JdXY3PP/8cn376KUpKShCsigO89/kwIrKTUlSis7azzRpqX+SiHN0Duzt9/emi0w5fE58QiGdfHILjqaXY9mMODh8shtn8V+hTJhPQb0A4xk+MRc9eoRBFAaEBGny/vMiucGiaoYvDwVCLxb0fPrDwGHkiIiIiIiIiIiIGQ8n7Jk6ciMcff9xqzY8//uixYGh1dTX27NljtWbMmDGQy1v2/x7+/v42a4qLi73QyXlFRUU2a+zpmYiIiIhcZzmZCSnXsZ8F/bWlHuoGKK0LxY68MfgyrzfOGo2wQELDQKggABMmxWH6TV2gVjv3c3i+Lh8L9i/An5V/Nrr9TPUZPHbgMbx+xeuQiy37Z3xHffbpZ/jm2//adZoAeV6gIhAz4mfYrKH2Kc4/DuvGrPN1G0QAAFEU0LtPGHr3CYO+zoySkjrodCZoNHKEhamhUjcOasb21uDaJzvgp5XFKM22/qGTXHMkKsQgBFkq7O7HYNBAkgS3HCcviTKYtJEur0NERERERERERNTata13xahVGDBgAMLDw62GFr/44gv8+9//9sj+GzduhMFgsFozceJEj+ztTjExto/DzMjI8HwjACRJsrlXUFAQ/Pz8vNIPERERkTPydflYdnyZ1ZqHej6EDpoOXurIeeadhx2+xh1hjIudruiGn3LH4oeiOBRItZBw6c/hMbH+mD23J7p2c37M5fHy41iwfwGK9U0/x9hTtAdLU5fi0d6PQhAEp/eJ1kTjvaHv2azxlq+++hJ6g/OhUJlMhkmTJmHOlOuBT352Y2ftU4Q6Ao/2edTXbRBRO2KxWGzWHD58GImJiRBFscn7VWoZomNsf5A3IkGJG5/tiJzjdUjdVoXMQzpYGpwAL8qA+P4a9BofgPCAKTAuX2f35HJJkqOqMhKBQQV21VtT02koJE4MJSIiIiIiIiIiYjCUvE8URdxwww14//33m605fvw4Dh06hP79+7t9/08//dTq/fX9tXRBQUEIDg62eoT777//joqKCgQFefYsySNHjticGJqQkODRHoiIiIhcVWOqwba8bVZr5nWf56VunCcZTLAcO+vTHo6X9MFXWVOwr0qLYqkKQM0lNXK5gKnXJuKaqQmQy5sOq9jjTNUZzN09F3qL3mrd55mfI94/Hrd0vsXpvTRyDS4Pv9zp61sKhUKB6X+bjlmzZiEmJgaWvOImIrtERNSSpaWl4YknnrBZ98ILL2DdunVYvHgxkpKSXNpTEAXE9dYgrrcGRr0F1cVmGOosUKpFaMNlUKjqv59rgHlTYVyxye5waGlpJ7cEQyt6TXV5DSIiIiIiIiIiorbA+XffiFxw66232qx588033b5veno6vv/+e6s1Y8eORXS096b8uMJWcNZsNuOnn37yeB+bN2+2WdOvXz+P90FEREREgFRRDdgxQcyT3jgzBt9VSv8LhV6qW/cgPPviUEy7vrNLoVAASNQmYmyHsXbVvn7ideTV5rm0X1vw1ltv4bHHHrPrFAIiImp59uzZg7lz5yIrK8uu+vT0dMydOxd79+51Ww8KlYiQGAWiuqgQEqNoEAo9T5YUD+VDN0GIDrdrvZrAJOgD4lzqSR+aCF3MAJfWICIiIiIiIiIiaisYDCWfGDlyJDp37my1ZvXq1Th37pxb9126dKnNY7Zuv/12t+7pScOHD7dZs3z5co/2oNfr8dZbb9msGzZsmEf7ICIiIqL/Mdo3metikuT8EesNmSwiTtUpmrxPrZHh9ruS8MTTl9t1bK09BEHA//X7P/QN6Wu1TiPT4JXLX0FHv45u2dfT0k6c8NjaIcHBHlubiIg8Ky0tDQsXLoROp3PoOp1Oh4cffhhpaWke6uxSYlwklI/NguL+GyD27QJcfJy9KELs2wWK+2+A8rHbUTDpCVjkaqf2ssjVKBj7CCDw5W4iIiIiIiIiIiKAwVDyEUEQ8NBDD1mt0ev1eOyxx9y2Z2pqKj744AOrNdHR0bj55pvdtqenXX311TZrtm/fjq1bt3qsh/fffx/Z2dk266666iqP9UBEREREDSiaDmXaUlMd6pbtd5V2QZ1FecntAwaF48UlwzB+YixE0T0h1HoqmQpLL1+KaE3Tk/+j1FH4YPgHGBU1yq372sPWB9MA4MiRI7BYLJAkCb/++ivuvvtuLFq0yAvdERFRa2KxWLB48WKHQ6H1dDodFi9ebNf3JncRRAGyHvFQzpsG1Sv3Q/nUHVA+fAuUT91x/vfzpkHWIx6CKMAQ3g15Vz7jcDjUIlcj78pnYAjv5qE/BRERERERERERUevDYCj5zOzZsxEWFma1ZvXq1fjuu+9c3stoNOLuu++G2Wy2Wjd//nwolZe+ie0MQRBs/pORkeHSHsOHD0dcnO1jtubNm4eioiKX9mrKkSNH8OSTT9qsGzx4MOLj492+PxERERFdSgjSXjqRyw4VFe6ZpPlV7sBGvw8KUuL+f/bB/AX9EBrm3BQwe4SqQvH64NfhL288ibRHUA/8Z+R/cFnQZR7buzlpaWl45JFHbNY9//zzmDp1Km644QY8+OCDOHz4sBe6IyKi1mbfvn1IT093aY309HTs27fPTR05RlApIHYIg5jQEWKHMAiqSz/MoosdhJxpy6APTbRrTX1oInKmLYMudpC72yUiIiIiIiIiImrVGAwln/Hz88NTTz1ltUaSJNxxxx0uv+j90EMPYe/evVZrYmJicP/997u0j7cJgoD77rvPZt3Zs2dx7bXXOj1Roinnzp3DlClTUF1dbbP2gQcecNu+RERERGSdoJRD7G1fmKIhmdzg8t7p1RH4vSzhwu9HjYnGC68Mw+ChURAE904JbUrngM54edDLkAkyAMDYDmOxYtgKhKvDPb73xfbs2YO5c+faNV0fAPLz85GVleXSnt27d8eDDz7o0hpERNRyrV+/3i3rfP75525Zx1MM4d2QPf19nLvmZVQnjIAkyhrdL4kyVCeMwLlrXkb29Pc5KZSIiIiIiIiIiKgJcl83QO3bAw88gBUrVuDEiRPN1hQXF2P8+PHYsmULLrvMsSk/FosFjz76KN5++22btUuWLIG/v7/NupbmnnvuwZIlS1BWVma1bvfu3Rg6dCjWr1+P7t27u7Tnzz//jJkzZyI/P99mbWJiIm655RaX9iMiIiKi8yRJslmTf0qPbj0SgCOnHVo7MsKx+ovVmhV47uQ1kCAgMkqDO+/ugV693XM8vSOGRgzFwl4LkafLw/1J90MUvP95yLS0NCxcuNCtH8yyZsCAAbjzzjsxfPhwlJ0zYu3XeV7Zl4iIvEen0+HXX391y1o7d+6ETqeDRqNxy3oeIYjQxQ6CLnYQBKMO8upCiEYdLAoNTNpISIoW3DsREREREREREVELwGAo+ZRcLsf777+PsWPHWj3mPSsrC1dccQWWL1+OO++8065pQ2fPnsW9996LzZs326ydNGkSZs6c6VDvLUVwcDBefPFF3HPPPTZrjxw5gssvvxyPPvoo7rvvPoSEhDi0V2ZmJpYuXYp3333X6n+vht58803I5XyoISIiopbPX+6P8R3H26zxlaIMA7a8U2yzbvuqYgQH/I5QBwd0ijL7fr5rSq1ZgceP3YDTtR1x9d864drrO0Olktm+0EOmJ0z32d4WiwWLFy/2Sii0f/8BmDN3OgYMGODxvYiIyLfy8vLsfi3GFrPZjPz8fCQmOj5h3BckhQbGkHhft0FERERERERERNSqMK3lJRaLBcXFxSgqKkJlZSX8/f0RExODsLAwX7fmc8nJyXj66aexaNEiq3VVVVWYPXs2Xn/9dcybNw9TpkxBfHzjF4Vra2uxZ88erFmzBv/973+h1+tt7t+xY0d88sknLv0ZfG3evHnYuHEjvv/+e5u1VVVVeOqpp/Diiy/i5ptvxpgxYzBq1Ch06tSpyfq0tDTs2LEDW7ZswcaNG2Eymezua/bs2bjmmmvsriciIiLypQ6aDnh50Mu+bqNJ2cd0+GF5EUx62xNDL5OfRahQ4YWuzkuvjsBzJ6+BIbwbFi3sgYTEQK/t3RLt27cP6enpXtnr8SceR2ys1it7ERGRb9XW1rp1vZqaGreuR0RERERERERERC0Lg6EeVFpaipSUFGzZsgU7d+5EXV3dJTWRkZGYMGECZs6ciauuusoHXbYMTz31FH7//Xd8/fXXNmuPHDmCBx54AA888ABCQkIQFRUFlUqF8vJy5OTkODQ9Qa1WY+3atYiMjHSlfZ8TBAGrV6/GsGHDcPLkSbuuqampwYcffogPP/wQAKBSqRAWFobQ0FCYzWaUlpaitLQURqPRqZ6GDRuGd955x6lriYiIiOgvRRkGu0OhAHCZ8oyHO/rLSycnY3PJAFw3vQuuvLoTZDL3HNteVFeEamM1EgNaxySzhtavX+/rFoiIqA3y8/Nz63r+/r6bgk5ERERERERERESex2CoB+j1erz00ktYtmwZqqqqAACS1PSbuAUFBVizZg3WrFmDnj17Yvny5Rg3bpw3220RRFHE+vXrcc0112Dbtm12X1dWVoaysjKn9lQoFPjiiy+QnJzs1PUtTUhICH7++WeMGzcOaWlpDl+v1+uRm5uL3Nxcl3sZNmwYfvjhB6hUKpfXIiIiImrXLBJ+WllsdygUAETB/lpX6SJ74LlHhyEqyn1hlbSKNCzYvwAyQYaUkSkIU7WeUxZ0Oh1+/fVXX7dBRERtUMeOHSGTydxynLxMJkOHDh3c0BURERERERERERG1VO0qGPrDDz9g3bp1Td4nCAJeffVVBAcHu7RHcXExpk6dir179zYKgwqC0Ow19XWpqamYOHEiFi5ciJdeesmlPlojlUqFTZs24c477/T4lJ2QkBB89tlnmDRpkkf38baOHTti9+7dmDlzJn744Qef9DBr1iy8//770Gg0PtmfiIiIqC3JTzegNNu5Ce7eMHtuTxjD3BcK3Z6/HU8dfAo6sw4A8PD+h/HusHehlqndtocn5eXluSWwQ0RtT4WhAptzN1utuTL6SgQpg7zUEbU2Go0GI0eOxPbt211eKzk5ma/bEBERERERERERtXHtKhj62muvNTuNMjk52eVQaFFREUaMGIHTp09DkqRLwqBNTQ0VBKFRnSRJeOWVV5CXl4eUlBSrgdK2yM/PD+vWrcNLL72ERYsWwWAwuH2PAQMGYO3atejWrZvb124JQkJC8O233+Ltt9/GU089hcrKSq/sGxkZiVdffRW33XabV/YjIiIiag/S99T4ugWr3PV8RZIkrD6zGstPLIeEv543HS0/in8f/jeeH/B8q3huVFtb6+sWyIfydflYdnyZ1ZqHej6EDhpO6WuPivXFWHJsidWaQWGDGAwlq2bMmOGWYOj06dPd0A0RERERERERERG1ZO0mGFpSUoKff/4ZwKUBTUEQ8OCDD7q0viRJmDFjBtLT0xuFPZs7Qr7hdQ37EAQBkiThv//9L6KiorBkifU3Ddqqxx57DNdffz3+8Y9/YMuWLW5ZMzg4GIsXL8YDDzwAmUzmljVbKlEU8Y9//AM33ngjXnnlFbz//vuorq72yF5hYWH4xz/+gfnz57scriYiIiKixvJO1kENlU/2NlhEKEWLx/cxWUx4+djL+Crrqybv35K7BfH+8fj7ZX/3eC+2nK46jZu232S9KAJAkVfaoRamxlSDbXlNfxi13rzu87zUDRG1RYMHD0bXrl2Rnp7u9Bpdu3bF4MGD3dgVERERERERERERtUSirxvwlq+++urCkX71Acz68GZiYiKuvfZal9Z/++23sWPHjkaBUFuh0IvVX1MfDn311Vfx448/utRXa9a9e3ds3rwZ+/fvx6233gp/f3+n1unVqxfeeOMNZGdnY/78+W0+FNpQVFQUli5dinPnzuHDDz/ExIkToVa7fgynVqvF1KlT8emnnyI7OxuLFi1iKJSIiIjIAyyez2U267Nsz4dGakw1+Oe+fzYbCq238tRKfJ/zvcf7cQs3DTYVxfbzvIWIiOwjiiIWL17s9DHwGo0Gixcvhii2m5eEiYiIiIiIiIiI2q12MzH0p59+uvDrhuFLQRAwY8YMl9auqKjA4sWLrU4JtXXsYVNTTCVJwoMPPogjR460qzDjxS6//HL897//hV6vx/bt27Fjxw6kpqYiLS0NJSUlqK6uhsFggFarRUBAADp16oRevXphwIABmDx5MhITE33St6PBYE8KDAzE7NmzMXv2bNTV1eG3337DwYMHkZqairNnzyIvLw9FRUXQ6XTQ6/UAALVaDT8/P0RGRqJjx47o3LkzevfujUGDBuGKK66AQqHw8Z+KiIiIiOxVYfZHkMz+Y+l/LemCLYU9cXv8Hg92BahEFeSCfU9L/33k34jzj0PvkN4e7cllbnoaMGjQIJRx8igREV0kKSkJS5cuxcMPPwydTmf3dRqNBkuXLkVSUpIHuyMiIiIiIiIiIqKWot0EQ/fu3dtsOPNvf/ubS2u/8847KC0tvRDmvFhztze8v2FNfWAVANLS0rB8+XIsWLDApR7bApVKhUmTJmHSpEm+bqVVU6vVGDt2LMaOHevrVoiIiIjICyySgAP6Xhjrt8+u+mK9Fi+fmoJrrwwGKjzbm1yU44WBL2D27tk4U3XGau3QiKHoHNDZsw21IJMmTcTa1fYHfoiIqP0YMmQIVq5cicWLF9t1rHzXrl2xePFihkKJiIiIiIiIiIjakXZxblBRURHOnj0LoHHoEgDCwsIwbNgwp9c2m8146623mgydNgx89urVC++//z7S09NRW1uL4uJi7N69G/fddx+USuWF+ouvlyQJL7/8Msxms9M9EhERERFR6+SOk14PG5JgtHMdiwR8WHUT/vXvsZg4Kc71ze2gVWjx+hWvI1QZ2mzNbZ1vw9LLl8JP7ueVnnyta9eu6NOnj6/bICKiFiwpKQlr1qzBW2+9hTFjxlxy2pBMJsOYMWPw1ltvYc2aNQyFEhERERERERERtTPtYmLovn2XTsapD4hOnDjR5jHv1nz//ffIy8u7ZCpow6Pq77nnHrz55puNXqBVq9UYOnQohg4ditmzZ+O6665DTk7OhesaBliLi4vxww8/4JprrnG6TyIiIiIian06XqZGWZrzZ5OXmINwRN8dd3Z/A1J+vM36w0FX4bp5N0MUBaC02Ol9HRXtF42lVyzFPb/dA4PFcOF2mSDDY70fw3Xx13mtF1/TaDRYvHgxBHekgomIqE0TRfHC64s6nQ75+fmoqamBv78/OnToAI1G4+sWiYiIiIiIiIiIyEfaxTtN1o5U6tevn0trf/rpp5fc1jAUOnXqVLzzzjuXfGq/oYEDB2LDhg1Qq9UXrr/Y6tWrXeqTiIiIiIhan7BOCqevNUsCduquwJiYLegSkGmzvjYwHgE3/vN8KNQH+ob0xaJ+iy78XivX4s0hb7a7UOjSpUs51Y2oDZIJMgQrg63+IxOaf+2IyBaNRoPExET07t0biYmJDIUSERERERERERG1c+1iYmhGRkaz9/Xu3dvpdY1GI7755ptGQc6Gv1YoFFi+fLldaw0YMACPPfYYFi1adMl6kiRh06ZNMBgMF46dJyIiIiKitu/P32ogwrlw6CF9T2j9SjC501cwGmwfwV4+4u+AzPkgqjtcGXMlsmqy8E3ON1g+eDkStAk+7cebunbtisWLFzMU2or5y/0xvuN4mzXUPiVoE7B10lZft0FERERERERERERE7US7D4b26dPH6XV37dqFqqqqS46Rr58WOn36dHTq1Mnu9R588EG89tprqKysbDR1FAB0Oh2OHTuGgQMHOt0vERERERE1r6iuCB+d+shqzexusxGhjvBSR0BdpQV+DQZ4homlKLGE2ryuyByCP81xeKj7s5CJFhjt2MsUENkijpSY020Obkm8BVqF1tetXCJKHYXHOj+GlStXoqSkpOmiysa/DQgIQFVVldV1n3zySUybNg0ij49v1TpoOuDlQS/7ug0iIiIiIiIiIiIiIqL2EQzNysq68OuG0zhFUURcXJzT627dan3Sw+zZsx1aLyAgAFOmTMHq1aubPE7+0KFDDIYSEREREXlIpbES6zPXW62ZnjDdq8HQhuQwYaAqFT/qkq3WWSQRO+sux7Vd1iBcU+Sl7txHEIQWGQoFgPKCcqQ8koKS/GZCoReJiIjA448/jgULFlit69u3L0OhRERERERERERERERE5Dbt4p2nioqKJoOWAQEBLq27Y8eORr9vuEdERATGjh3r8JrXXHNNs/cdOnTI4fWIiIiIiKhtuFx9FP6izmbdcUMXxIYewhWRe7zQVdNqTDU+29tTzpw5gzlz5iA/P9+u+o4dO2LlypWIiYnxcGdEREREREREREREREREjbWLYGhtbW2TtwcFBTm9ptFoxP79+y8JnNYf/3711Vc3GUa1ZcCAAc3ed/z4cYfXIyIiIiKi1q+jrAA9lGfsqj0AA27u8qmHO2qayWLCy0dfxuxds1FtrPZJD55w8uRJzJs3D8XFxXbVd+rUCStXrkRsbKyHOyMiIiIiIiIiIiIiIiK6VLsMhkqSBMC1YOihQ4eg1+sbrdfQ5MmTnVq3S5cukMvlABpPIJUkCaWlpU6tSURERERErZcCRozUHLC7/o7EzfCTGzzYUdOqjdVYsH8B1meux+mq03jiwBMwWUxe78Pdjh49invuuQfl5eV21Xfp0gUrVqxAhw4dPNsYERERERERERERERERUTPaZTDUHfbu3Wv1/jFjxji1rlwuR1RUVKPb6gOilZWVTq1JREREREQtj2S59ANmTblCfQRa0f7nNF21Rc625LTc2lzM3j0bu4t2X7htd9FuvHb8Na/34k6///477r//flRVVdlV36NHD7z//vsIDw/3cGdERNZZ7Pgec+rPcrvqiIiIiIiIiIiIiKj1aRfB0IvVBy1dCYz+9ttvTa4JAN27d0dkZKTTa/v7+zd5e0VFhdNrEhERERFRy5GZUYk3Xz9isy5KLMZlygzPN+SCI2VHcMevd+BM1aVH3a/LWIe1Z9f6oCvX7d69G/Pnz7f7eWO/fv3w7rvvIjg42LONERHZkJlRibdeP2qzLuWDNPzf43uRmcEPIhMRERERERERERG1Ne0iGKpSqZq8vaamxuk1f/3110ZhUOD8ce+CIGDEiBFOrwsAfn5+TR5Pb++UGiIiIiIiarmOHS3B88/8gYJ8nc3aAeoTXujIeb8W/op7frsHZYayZmteTX0Vuwp3ebEr1/38889YsGAB9Hq9XfWDBw/GW2+9Ba1W6+HOiIis++t7jH2h9pzsajz/zB9IPVpi1yTr/FN6uydeExEREREREREREZHvyH3dgDdotdomp7wUFhbCZDJBLnfsr+HMmTPIzs6GIAhNBjhdDYaazeYmb784iEpERERERO6jlqkxMHSgzRpXZGZU4o3XjkCvb/pn/otphDqX9vO0H879AIPFYLXGAgueOPAEPhz+IboGdvVSZ8774YcfsGjRomafl10sOTkZL730UrMfSCQi8hZHv8fU0+vNWPFqGgaGdLJZu31VKY5urcK4ueGISFA62yoREREREREREREReVi7CIZGRkaioKDgQpCzPmBpsVhw5swZdO/e3aH1tmzZYvX+kSNHOt0rANTV1TUZAg0ICHBpXSIiIiIial6MXwxWDF/hsfUtFgkr3j3ucGCnJXu418PYn/p/yNPl2awtNZR6oSPXbNiwAc8//3yTHwBsyoQJE/Dss89CoVB4uDMiIutc+R4TJPihm7kjakssdtWXZhux4fl8XDU/ArG9NQ7vR0RERERERERERESe1y6Oko+NjW32vsOHDzu83jfffNPo9w1DnJGRkejWrZvDazZUXFzc5O08lpCIiIiIqPVKPVaKnOxqn+xtET3zmcBgZTCWXbEM/nL/ZmuiNdH4aMRHGBw+2CM9uMunn36K5557zu5Q6JQpU/Dcc88xFEpELYKz32P8oEJ3sSNkgmMvEZr0Er5fXoSiDOtTo4mIiIiIiIiIiIjIN9pFMPSyyy5r9j5b0z8vVl5ejq1bt14y0bN+Eunw4cOd6rGeXq9HWVnZhTUb/psTQ4mIiIiIWq+ffsxp9Hu1Fw9wqOh3o8fW7hrYFS8OfBFiE08v+4b0RcrIFHQJ6OKx/d3ho48+wquvvmp3/fTp0/H0009DLm8Xh3AQkQeYLCZkVGfALLlnivTF32Ps1UUW5XAotJ5JL+GnlcWQLPYF6omIiIiIiIiIiIjIe9rFu1j9+vW75Lb6Y+W//vprGAwGKJVKu9b69NNPYTAYLlx/seTkZJd6PXPmTJO3C4KA6Ohol9YmIiIiIiLfMOgtOHzor5MBBAjoJIbjT0u+x/euiR+Gqq5jAXzisT2GRw7Hv3r9C6+kvnLhtiujr8TT/Z6GSqby2L6ukiQJ77zzDlatWmX3NbNmzcI///nPSz4sSERkTbWxGnuK9gAATlWewpqza6Az66CRaTAzcSa6BXbD0Iih0CocPy3GYGj8PcZeQYIf/AXXHqNLs40oOC0h1KVViIiIiIiIiIiIiMjd2kUwdNiwYY1+Xz/dEwCKiorw0Ucf4Z577rG5jsViwfLly62+AThp0iSXek1NTW32vq5du7q0NhERERER+UZ5eR3M5r8+WBYrhkIt2PfhNFeY/MJQMPphoNzo8b1uSrwJmTWZWJexDnO7zcW87vNadHhSkiS8+uqr+Oyzz+y+Zt68eZg7d26L/nOR7xTVFeGjUx9ZrZndbTYi1BFe6ohakoK6Ajx24LFLbteZdfgw/UMAwNrRa50KhlaUmxp9j7FXlBDk8DVNSd9Tg8HOXChZbJao81NhCOkEODnVlIiIiIiIiIiIiKi9ahfB0O7duyMxMREZGRmNJn3W//rJJ5/E5MmTkZCQYHWdN998E3/++ecla9Tr3Lkzevbs6VKvBw8ebPY+BkOJiIiIiFonvf6v8IsWakQLIdDB4NE9JQgoGPsoLJogoNzxSXLOWNBzAUZHjcaQiCFe2c9ZZrMZL774IjZs2GD3NfPnz0fydcmY+ONEq3UfDP8ACdoE1xqkVqnSWIn1meut1kxPmM5gKLmdweB4KFSEgGDB3y3756XpAT/HrlEWn0KHrc/ZrIvcuQxBqRtQMPYRGMK7OdkhERERERERERERUfvTbj5uf/311zc6+r3hr8vKynDVVVdZndb5+eefY+HChU1OhqmfQHrTTTe53Oevv/7a7H0MhhIRERERtU4q1fmnXiIEdJVFOT1xMt1of/KmvP+N0MUOdGofZ8lFeYsPhZpMJixatMihUOijjz6KWbNmwSyZUW4ot/qPWTJ7rnkiatNK9CVOXadUOv49RQUFRDdNP7bYHvzZiCbnD8RufAjKinN21atKzyJ240PQ5PzhRHdERERERERERERE7VO7CYbOm/fXMYb1/64PdAqCgJMnT2Lw4MG4++678c033+DYsWM4ceIENm7ciOnTp+Omm26CyWS6cF3Ddep/PWfOHJd61Ol02L9/f7NvEvft29el9YmIiIiIyDeCg9WQyQR0EsOdPkK+1iLCEFRkV21dxGUoufwup/ZpywwGAx5//HH88MMPdtWLoojFixdjxowZHu6MiAjYmLXRqeuCguWQyRwLeYpwTyj0PNsTSy1nciFZJCiLT6Hj5kUQTXUO7SCa6tBx8yIoi0852yQRERERERERERFRu9JugqHdunXDtdde22hSKNB4cqhOp0NKSgqmTZuGfv36oXfv3rj++uvx1VdfXQiRNnW9IAi49tprbR5Fb8u2bdtQV1fXaN16HTt2RFxcnEvrExERERGRbyhVIvp1jkIHMdjpNX4T5bgm5qDNOotchfzxTwIyucN7HCs7hoW/L4TerHemxRatrq4ODz/8MH7++We76mUyGZ5//nlMmTLFw50RUXtgzzTQbXnbUKArcHhtpVJEv/7hDl1jsSPMaY9QsRzjNHts1pk+3QrDSx8jassLDodC64mmOkT9vASQHBxRSkRERERERERERNQOtZtgKAC8+OKLUKlUABpP+2w4OVSSpCb/uXiKZ8Pfy2QyLF682OX+Nm68dDJE/d7Dhg1zeX0iIiIiIvINg84CZY6/09cfN6kwvevPkAu2gzxlA2+DKSja4T32FO7B33/7O37O/xnPHn72kg/FtWY1NTX45z//id27d9tVr1QqsXTpUkycONHDnRFRe2HPNFCTZEJKeopT64+bGOtQvR5GWFx8nI+WFeBq/18QJKu2q96/Mg2qqmyX9lSVnoXmnO0PSRARERERERERERG1d+0qGNq9e3c8+2zTb3A2PB6+qX/qA6IXXyMIAh544AH07t3bpd4MBgO++OKLZo+RZzCUiIiIiKj12r2uFDA2fvqlFuybylljERERcwIxmgr76uOde+6w7Pgy6C3ne/oh9wd8kfWFU+u0NJWVlbj//vtx4MABu+rVajWWLVuG5ORkD3dGRO1Fga4A2/K22VW7IXuDU1NDe/UORWyc1u56CySUSzUO71MvVCzHOL/foBDM9l8TmuX0fg0FpW5yyzpEREREREREREREbVm7CoYCwMMPP4xbbrml0ZTQes1NC704ENrwmoEDB+Kll15yua+vv/4a5eXlF/q42MiRI13eg4iIiIiIfKMgzXDRLRL6K0/YdW26Xw3GRqa5vykb1mWs8/qe7lZaWop77rkHx44ds6ve398fb731FoYMGeLhzoioPUlJT4FJMtlVa7QYnZoaKooC5t3bEyqVzO5rCiT7PnBwKQnJmv0OhUIFwYSAwEIn92vMP2sPBKPOLWsRERERERERERERtVVyXzfgCx9//DFkMhn++9//NgqH2joq8eIQ6cCBA/HNN99AqVS63NM777zT7F5hYWEYPHiwy3sQEREREVHL0FWRhY7yIgChVusyBQG3Ju7yTlNtTGFhIe677z5kZGTYVR8UFIQ333wTPXv29Gxj1GapZWoMDB1os4balwJdATZkb3Domg3ZG3Bn1zsRpYly6Lr4hEDMX9AXy187Ar3edmizQqpFjaSHv6ByaJ9oWSFCZZUOXaNU6iAIrh1dX0+wmCGvLoQxJN4t6xERERERERERERG1Re0yGCqTyfDxxx9j2LBhePzxx1FZWXnJ9NDm1IdHb7vtNqxYsQJqtetv6hw/fhw///zzhSPrG+4lCAImT57s8h5ERERERGRdqb4U6zPWW62ZkTADoSrrYU5b/IRaDFYfRonZ9gEOXaNT4Se/eNoo2ZKbm4t7770X586ds6s+LCwMb7/9Nrp27Wq1LlwVjkd6P2KzhtqnGL8YrBi+wtdtUAuTkp4Co8Xo0DX1U0Mf7fOow/v16hOGJxcNwop3jyMnu9pmfXVEJQIrI2B24FtNkvK0w32Jov3TRe1ajxNDiYiIiIiIiIiIiKxql8HQevfeey9uvPFGLFu2DCkpKcjNzbVar1QqcdVVV+Gpp57CoEGD3NbHkiVLLvy6YTi1/tfXXHON2/YiIiIiIqKmlRnKsPLUSqs1E6InuBgMlTBCcwAqwQjA9oS2eP8SF/ZqnzIzM3HfffehoKDArvqoqCi88847iI+3PXkuSBmEGxNudLVFImonnJkWWq9+aqgz4hMC8eyLQ3A8tRTbfszB4YPFMJv/+iCyTCag34BwjJ8Yi569QpF7vA7fLy+CSW97oqccJsTJ8x3uyWKx/4h7u9ZTaNy6HhEREREREREREVFb066DocD5yTDPPfccnnvuORw5cgS///470tPTUV5eDrPZjNDQUISHh6Nv374YOXIkNBr3vvCckZGBNWvWAGj6KHuZTMaJoUREREREbUQ3RQZi5fYFFslx6enpuP/++1FSYl+gNiYmBu+++y6io6M93BkRtUfOTAutVz81dLrfdKeuF0UBvfuEoXefMOjrzCgpqYNOZ4JGI0dYmBoq9V9BzdjeGlz7ZAf8tLIYpdnW+/UXayE6cSS8waCBJAluOU5eEmUwaSNdXoeIiIiIiIiIiIioLWv3wdCG+vbti759+3p1z4SEBBgMPBqSiIiIiKit8xdqMFh9xNdt2E0mtK6niydOnMADDzyAiooKu+oTEhLwzjvvIDKS4SIicj9XpoXW25C9AWMTxrrci0otQ3SMv9WaiAQlbny2I3KO1yF1WxUyD+lgaXD6uygD4vtr0K+3BHzleA+SJEdVZSQCg1z/cERNp6GQODGUiIiIiIiIiIiIyKrW9U4fERERERFRKzVS8weUgsnXbdglSBGE/+v5L+DH13zdil0OHTqE+fPno6amxq767t2746233kJoaKiHOyOi9sqVaaH1jBYjNmRtcE9DdhBEAXG9NYjrrYFRb0F1sRmGOguUahHacBkUKhGWvBIYnAiGAkBpaSe3BEMrek11eQ0iIiIiIiIiIiKitk70dQNERERERERtXYIiB9HyIl+3YdXwyOEAgE7+nZAyMgU9g3v6uCP77Nu3Dw888IDdodDevXvjvffeYyiUiDzGYDZgU/Ymt6z1c/7PblnHUQqViJAYBaK6qBASo4BCdf4lRCE0EBCdezmxujocdboAl/rShyZCFzPApTWIiIiIiIiIiIiI2gMGQ4mIiIio3TJZTMiozoBZMtsuJnJBb+Wfvm7BpnsvuxczE2ciZUQK4vzjfN2OXXbu3IkHH3wQdXV1dtUPHDgQb7/9NgIDAz3cGRG1Z+dqz0Fv0btlLVenjrqboFJA7J3o7NXIyekLs1nm1NUWuRoFYx8BBL6cSURERERERERERGQLX0klIiIionZpT9EeTPpxEqb/Mh0Tt0zEnqI9vm6J2jC50PLDx0qZEgt6LUCgsnWEJrdu3YqHH34YBoPBrvqhQ4fijTfegL+/v4c7I6L2Ls4/DkGKILesFaBwbcKmJ8iS+zl9bV1dELIyBzkcDrXI1ci78hkYwrs5vTcRERERERERERFRe8JgKBERERG1OwW6Aiz8fSEqjZUAgEpjJRb+vhAFugIfd0a+pBSV6KztbPUfpaj0aY+1HZ0P47Ql33zzDZ544gmYzfYFbkePHo3XXnsNarXaw50REQFyUY5XLn/F5XBokCII/+r5Lzd15T7iZfEQosOdvr6mJhwZVZOhD7Vv8qg+NBE505ZBFzvI6T2JiIiIiIiIiIiI2hu5rxsgIiIiIvK2lPQU6My6RrfpzDqkpKfg0T6P+qgr8rU4/zisG7PO4evMRskD3VzK5BeGkivuAr6rst6PZPFKP77y+eef46WXXrK7/sorr8QzzzwDuZxPf4nIewaGDcTmiZtxpvoM6sx1Dl+vlqnRWdsZmWczPdCdawRRgGLWZBiWrQUMThx1r1TAPPMmZMeGQ3PuIIJSN8E/aw8Ey19hf0mUoabTUFT0mgpdzAAeH09ERERERERERETkIL4zRkRERETtSoGuABuyNzR534bsDbiz652I0kR5tylq1Y7+aD2o6Q4SBBSMewySpAVgfb9PTn+CBXFzPd6TL/z3v//F66+/bnf9tGnT8MQTT0Amc+zIYiIid5CLcnQP7O7rNjxCjIuEYt5UGFdsciwcqlRAMW8qxLhIAIAudhB0sYMgGHWQVxdCNOpgUWhg0kZCUmg81D0RERERERERERFR28eP2xMRERFRu5KSngKjpekAg9FiREp6incbolYtN60OJ3+tdvJq+yeNlve/6fzENDt8d+47fJ7xuZM9tUySJGHFihUOhUJvvvlmPPnkkwyFEhF5iCwpHsqHbrL7WHkhOhzKh26CLCn+kvskhQbGkHjoI5NgDIlnKJSIiIiIiIiIiIjIRZwY6mEWiwX79u3Dzz//jOzsbBQVFaGyshL+/v6IiYlB7969MWHCBHTp0sXXrRIRERG1edamhdbj1FCyl0FnwU8rSxzJdzYS0rEAqEyyWVcXmYSSy+90aO1XUl9BjF8MhkUOc665FkSSJLzxxhv45P/Zu+/wKMq1DeD3zPb0BkmAhBYg9N4ERBTBgwoWrNg9ICoWUARFJVaUop8KWJADx45YKCqIiCJIl6KACJGSUBLS62bbzPcHJzGb3WwvSfb+eeWSzLzlSQibhdz7vB9+6PKcu+++Gw888AAEQfBjZUREJKY0h3rm7ZD+yoJly35IB08AklRrgAixW1sohvWC2CkVgsjHZSIiIiIiIiIiIqJAYDDUT0pKSjB37ly8/fbbKCkpcTq+X79+ePzxx3HDDTcEoDoiIiKi0OSoW2i16q6hM7rPCFBV1Fht/6wIZXlmj+bqwoqgi8wEMNzhOFmpRc6lTwEK9/7qZpEtmLl3Jv4z5D9oH9l4X4QmSRLmzZuHlStXujzngQcewD333OPHqojsKzQUYuVJx1+rN7S5AXGauABVRBQYgihA0bk1FJ1bQzaYIBeVAlVGQKuGEBsFQaMKdolEREREREREREREISekgqGVlZXIz8+v935ycjJUKu//sfrrr7/Gv//9bxQXF0OWXWsftHv3btx8881YtGgRPvroI7Rq1crrOoiIiIjoH650C63GrqHkzKkDehz+ybMj5EXRhJQOh3G6zPnfPQr63Ia46BYe7VNhrsDUXVPx36H/RbRHKwSXxWLBiy++iLVr17o8Z9q0abj11lv9VlN2RTYe2/2YwzEL+i9ASniK32qghqvIWIQlx5Y4HDOyxUgGQ6lJEzQqCEnxwS6DiIiIiIiIiIiIKOSFVDB01qxZePPNN+3ei42NRXZ2ttfB0Ndffx3Tp0+H9L9js1w9ulCWZciyjF9++QV9+/bFd999h759+3pVCxERERH9w5VuodXYNZQcqSq34OelBR7OltGi7VGopRIACU5HV7YZBG8iZGf1Z/HcgefwWsrTXqwSeGazGc888wx++OEHl8YLgoAnn3wS1113nV/rMkpGHC8/7nQMERERERERERERERERUTCJwS4gkL744ouaAGbtNwC49957odPpvFp/2bJleOyxxyBJEgRBqAmF2tuz7lvt8Xl5eRg5ciQOHjzo3QdMRERERADc6xZabVX2KuTqc/1TEDVqWz4oRGWxxaO5MTFnEBN2yscV1S8lLAVTu0wN2H6+YDAYMH36dJdDoQqFAs8995zfQ6FEREREREREREREREREjUXIBEO3bduGM2fO1AQwawcxlUolHn74Ya/Wz8zMxEMPPQQANoFQV9QNiJaUlGDcuHEoKSnxqi4iIiIicq9baLXqrqFEtWXuqEDmjkqP5qrVFWiR8qePK6pfn7g+WDZ0GVpHtA7Ynt7S6/WYOnUqtmzZ4tJ4pVKJOXPmYMyYMX6ujIiIiIiIiIiIiIiIiKjxCJlg6Jo1a2p+XR3WrA5ijhkzBi1btvRq/YcffhiVlZVWodC66oZSa4dT69YGACdPnsSzzz7rVV1EREREoc6TbqHV2DWUaqsoNuOX/xbaXI8Sy5zOFQQZKe3+gAj3AsqeurrV1Vg0aBFi1DEB2c8XysvLMWXKFOzatcul8RqNBgsWLMCll17q58qIiIiIiIiIiIiIiIiIGpeQCYZu27at3nvjxo3zau0tW7Zg/fr1EATBbpdQR8fKV9+vq3qtt99+G4cPH/aqPiIiIqJQ5km30GrsGkrVZFnGz0sLYaiQrK6LkNBXe8jp/Pj4k9CpbEOl/nBr21vwbM9noRJVAdnPF4qLi/HAAw/gwIEDLo3X6XR44403MGTIED9XRkRERERERERERERERNT4KINdQCBYLBb89ttvNQHM2kFMQRBw5ZVXerX+3Llz671XOxDasmVLjBgxAi1atEBlZSWOHj2KTZs2wWw21wRBq8dWz7NYLHj88cfx3XffeVUjERERUSjypltotVXZq3BX2l1I1CX6pihqlP7cXI6sA3qb6z00RxBtcd4xNDb2NACFHyqzdU3qNXZffNZQFRQU4IEHHsDff//t0viIiAi89dZb6N69u58rIyIiIiIiIiIiIiIiImqcQiIY+vvvv0Ov19eEL2v/f8CAAWjWrJnHa2dnZ2PdunU2P3itHQhNSEjAm2++iZtvvtlmfm5uLh566CF88cUXVuHQ6jVkWcaGDRuQlZWF1NRUj+skIiIiCkXedAutVt01dEb3GT6qihqb0jwTtn1SZHM9XixCT/URnLTNi5KLcnNzcf/99yMrK8ul8TExMVi4cCHS09P9XBmR+9SiGu0i2jkdQ0RERERERERERERE5G8hEwytz+DBg71a+8MPP4QkSVahztqh0Li4OGzatAndunWzOz8xMRGff/45pk6dijfeeMPqOPra63z66aeYMYNhBCIiIiJXGS1GrMle45O11mSvwbSu03yyFjVcJcYSfH/2e6trsiTjjw1lKGllBgC0zxoKjTESIiwYptsDUZDtLUUuOH36NB544AGcPXvWpfEJCQlYvHgx2rVzHLzzp1h1LCZ2mOh0DIWmlPAUfH7J58Eug4iIiIiIiIiIiIiIKDSCoSdPnqz3nrfHD65cudLu9epg54IFC+oNhda2YMEC7Nq1C9u3b7fpHCrLMj766CMGQ4mIiIjccKbyDAySwSdrGSQDzlSeQbIq2SfrUcOUb8jH3INzbW+0+t8bgOTzXaExRqKX5k/EKkoDWl9TcvLkSdx///3Iy8tzaXxSUhLefvttpKSk+Lkyx+I0cbiv031BrYGIiIiIiIiIiIiIiIjIGTHYBQSCv4Kh2dnZOHDggN1uoQCQlpaGO++806W1RFHEK6+8YnWtdtfQw4cP49y5cx7XSkRERBRqUsJTEK2K9slaMeoYtApr5ZO1qPFLEAvRXf1XsMtotI4ePYqJEye6HApNSUnB+++/H/RQKBEREREREREREREREVFjEfLB0C5duni87oYNG+xerw503nefe51khg0bhr59+1oFQmvbt2+fR3USERERhSKlqMS8fvO8DodGq6Ixt+9cKMWQaLZPToiQ/neEfLAraZwOHjyI++67D0VFRS6Nb9euHZYsWYKkpCQ/V0ZERERERERERERERETUdITET7dzcnJqgpa1A5darRY6nc7jdX/++Wer92uvLQgCJkyY4PaaY8eOxW+//Wb33v79+zFmzBi31yQiIiIKVX3i++D7y7/H8fLjqLJUuT1fq9CiXUQ7hkKpRmf134gxlvlkreIWPXyyTmOxd+9ePProo6isrHRpfHp6OhYuXIiYmBj/FkZERERERERERERERETUxITET7jr+8FjVFSUV+tu2bLFprNndbfPQYMGITEx0e01R4wYgdmzZ9u9d+DAAY/qJCIiIgplSlGJjlEdg10GNREdVCcBY4zX65yNiMHDunNer9NYbN++HY8//jgMBoNL43v06IE333wTERERfq6MiIiIiIiIiIiIiIiIqOkJiaPk6wuGRkd7fqzouXPnkJWVBeBCGLSuK6+80qN1O3fuXO+96v2IiIiIiChIfHCE/GGlhJHNynCs7G+nYytNrnXXbMh+/vlnTJs2zeVQaP/+/bFw4UKGQomIiIiIiIiIiIiIiIg8FJLB0OogZ3h4uMdr7ty50+H9yy67zKN14+Pja45KrN2NVJZllJaWerQmERERERE1HFmdLsV5U4lLY9/48w1YZIufK/Kf9evXY8aMGTCZTC6NHzJkCF5//XWEhYX5uTIiIiIiIiIiIiIiIiKipiskjpKvrzNNVVWVx2vu2LHD6v3aIc6IiAj069fP47VjYmJQUvLPD4oFQYAsy1bXiIiIiMh95aZy7Mjb4XDMoGaDEKFip8JQlH/cDG1VlM11QZCgFkwQAChk71qGVjVPR9rgmXj6XC/M+Xmx0/EdozpCbKSv51u9ejVefPFFuycs2HPppZfipZdegkql8nNlRESNhyRJTsccOHAAbdu2hSg2zu8XREREREREREREROR7IREMValUMBqNNe9XBy3rO2LeFb/++qvNNVmWIQgCBg4c6NU/xkdERNSsVRs7hhIRERF5J7cqFzP3znQ4ZsXwFQyGhiCjXsKx/4ZjQv4yq+tKmDEuYiOixIp652q1rj1Pl1RhyLnsKUChxFWtrsKR1Bz84WTO9W2ut/l7QWPw2WefYf78+S6PHzNmDJ599lkolSHxV1QiIpccOXIETz31lNNxL7/8Mj7//HNkZGQgPT09AJURERERERERERERUUMXEq0EtFqt3etFRUUerVdVVYU9e/bU+wPaoUOHerRutfo65HjT4ZSIiIiIiOr36ydFKMu3PbK9r/agw1CoKJqQlHTEpT3OD3sE5qgWNe/f1PZG9wttBJYvX+5WKPT6669HRkYGQ6FERLXs2LEDEydORFZWlkvjMzMzMXHiROzcudPPlRERERERERERERFRYxASwdD4+PiaX9c+xrCsrAz5+flur7d169aa4+ntHYs4ZMgQD6r8R1VVld3QaVhYmFfrEhERERGRrZP7KnFkc7nN9STFeXRR/+1gpowWLQ9CpTI43aO8zWCUd7jM6pogNK2/jsmyjMWLF2PhwoUuz5kwYQJmzpzJ44+JiGo5cuQIpk+fDr1e79Y8vV6Pxx9/HEeOuPaCBSIiIiIiIiIiIiJqukLip2+JiYl2A5wAcOzYMbfXW7dundX7tUOcSqUSgwcPdnvN2srLbX8oDVw4Yp6IiIiIiHxHX2bBz/8psLmuhAlDdb85nBsTcwYxMedc2qeo9wSP6mssZFnGa6+9hv/85z8uz5k4cSIeffTRek9iICIKRZIkISMjw+1QaDW9Xo+MjAxIkuTjyoiIiIiIiIiIiIioMQmJs/rS0tKwfft2u/c2b97sdpBz1apVNj+8rA6e9uzZ0+vOnrm5uXavR0ZGerUuERERERH9Q5Zl/LK8EPoS2/BMf+0fiBQr652rVpcjucUh1/dSaT2qsTGQJAlz5szB119/7fKcKVOm4K677vJfUURBUGIswfdnv3c4ZnSL0YhWRweoImqMdu3ahczMTK/WyMzMxK5duzBo0CAfVUVEREREREREREREjU1IBEPT09Prvbd+/XrMnDnT5bV27tyJEydOQBAEmy6kgiB4fYz8+fPnYTQaa9av/f/Y2Fiv1iYiIiIion8c216J47ttw58tFLlIV5+od54gSEhJ2Q+FwuLP8hoFs8WM2bNn25yq4Mj06dNx0003+bEq/zlTeQbP7X/O4ZjZvWajZVjLAFVEDUm+IR9zD851OKZvfN/QCYbKzjtWanMOwRibCgghcaCNS1auXOmTdb744gsGQ4mIiIiIiIiIiIhCWEgEQwcOHGj1fu3A5ZYtW3Dw4EF069bNpbXeeecdh/cvvfRSj+sEgD///LPee23btvVqbSIiIiLyXlVVFfLy8qDX66HT6RAREQGNRhPssshN5YVmbPmg0Oa6CiYMcXKEfPPEv6ALK/VXaY3K//3f/2Hd9ztcGiuKIp5++mmMHTvWz1X5T5WlCnsL9zodQxTq1PnHkLTxRafjmm95HdGHViF3xBMwJnQIQGUNm16vx9atW32y1pYtW2qeqxARERERERERERFR6AmZYKharYbJZLLb6XPWrFlYvXq103UyMzPxySefWB0jX/vXarXa62DooUP1H0eZlpbm1dpERERE5BlJkrBr1y6sWLEC27Ztg8XyT6dIhUKBoUOH4oYbbsCAAQMgiux61tDJsoyf/1MAY6VtN7sB2t8RIeoBABZcuK/AP7+nERF5aNbMuptosei8K15TtWvXLpfGKRQKvPDCCxg1apSfKyKiYNOd/g3J38+GaHYtJK0pPIFWq6fi3OjnoG/V18/VNWznzp2zeo7hDYvFgpycHL7ImIiIiIiIiIiIiChEhUQwNDw8HJdddhnWrVtXE+Ss3TX0m2++wcsvv4ynnnqq3jUqKytx22232Q2XVq81atQohIeHe1Xr9u3b673HYCgRERGRd9pHtseeq/a4NefIkSPIyMhAZmam3fsWiwWbN2/G5s2bkZaWhoyMDKSnp/uiXPKTwz+VI/t328BSK+U5dFSfrHl/Y/IpCABGnbsQqlEoDGjZ6oDVnKNKC+6Nsz2Onv6hUqnwyiuvYPjw4cEuhajJkCTZ6ZhjR4vRokU4RPGfF7TKLszLOWZAbAsVhFrzXKXOP+ZWKLSaaK5C8vezcXrc6yHdObSy0rffTyoqKny6HhERERERERERERE1HiHTzmjChAk212qHQ5955hnccccdOHXqlM24gwcP4tJLL8WuXbvsdhytduedd3pd59atW626kNbWqVMnr9cnIiIiItft2LEDEydOrDcUWldmZiYmTpyInTt3+rky8lRJrgnbPi2yua6GERdp/zki3CxIWJ52EMvSDv6vc6iMVq1+h0plrBnzs8aEkc3KcFbhPGgVqjQaDV5//XWGQol86NTJUiz8vz+cjlv+/hE88+ROnDpZCgDIO2nE9wvznc7bvKwQnz9zDnknjU7HWpElJP401+1QaDXRXIXEn+YCcuh2YQ4LC/Ppet6+eJmIiIiIiIiIiIiIGq+QCYbecMMNSE5OBmB9/HvtcOjHH3+M9u3bo1+/fhg/fjxuuukm9O7dGz179sTu3btt1qy9TsuWLTFu3Divajx69GhNMLW6rmoqlQq9evXyan0iIiIict2RI0cwffp06PV6t+bp9Xo8/vjjOHH8hPPBFFCSJGPTewUwG2yDnAO1BxAu/hNm+jHpFLLDy5AdXoYfk08hPv4kIqPyau4vDzPg+vgKlIbM36jcFx4ejoULF2LQoEHBLoWoyTj4RwFeeu435Oa41lnydHY5XnruN2xdm4tVL+WgJMfs0rzCbBNWvZSD0wdd/x4YlvcHNIXefe/TFJ6A7sw+r9ZozJKTk6FQKHyylkKhQFJSkk/WIiIiIiIiIiIiIqLGJ2R+jKlSqfDMM8/Y7fZZOxwqSRL27t2Lr7/+Gl988QUOHDgAWZatxtibO336dK//8f6bb76xWxsA9OrVC2q12qv1iYiIiMg1kiQhIyPD7VBoNb1ej8WLF/m4KvLWgXWlyDlmsLmeojyLNHVWzfvV3UKrLe/wOxKSjgAALJAxK0qPR2P1sLh/ynLIiIqKwqJFi9C7d+9gl0LUZJw6WYo3X/sdBoPFrXkKgxL7V1baDcU7YjbIWPdGnsudQ2NO/uDW+vWJPrTGJ+s0RjqdDkOHDvXJWsOGDYNOp/PJWkRERERERERERETU+IRMMBQAJk2ahP79+wOAzXHt1QHP6uvVYdDqsXVDodXjBEFAhw4dcP/993td38qVK+1eFwQBgwcP9np9IiIiInLNrl27XD4+vj5ZWVnOB1HAFGQbsevLYpvrGsFgdYQ88E+30GpZYRX4OvxCoPQ3tQWLI2zDpfSPuLg4vPvuu+jWrVuwSyEKKIWgQIw6xuGbQvDsBaWyJOO9tw+7HQoFgPaKRCg8/Ocfs0HGpiX5kCyOj3cXBDPCc/Y6HOOq8KwdEEyevTCjKbjhhht8ss748eN9sg4RERERERERERERNU7KYBcQSKIo4qOPPsLgwYNRVFRkE/asGw6tfb222uFRpVKJZcuWQan07lOZmZmJnTt32u1KCgAXXXSRV+sTERERkevqe8EONU4Ws4xN7+ZDsnOC8kDtAYSJF4Ke5UojdiScxeJOtscYPxulh1IGLjOo8EKpFk9HV9mMIaB58+ZYvHgx2rRpE+xS/CJKFYUbWjsObUWpogJUDTU0bSLaYOOojX5Z+/hxPU5nl7s9L1oIQ7ig8W7zM3moenuPw39AUqv1EOA4POoqQbJAWX4eptjWPlmvsRkwYADS0tK8eoFKWloaBgwY4MOqiIiIiIiIiIiIiKixCalgKAB06NABq1atwlVXXYWysjKrkGft/ztTPe6tt97ySTfPpUuXWr1fO5wqCAJGjBjh9R5ERERE5Jxer8fWrVuDXQb50G+rSpCfZbK53lp5Bu1V2TXvn9dWIqPXNrtr5Chl3BNfie25kXiwXINMpYTl4a4dr9xYZWVnI9WN8S1btsTixYvRsmVLv9UUbM20zTCj+4xgl0EhaM/OMueD7EgUor3at4UiF5eGbYeyxHGnUlF0v5Opw/VCuGOoKIrIyMjAxIkTode7/3nQ6XTIyMiAKIbUIUFEREREREREREREVEdI/ivx0KFD8dNPP6Ft27Y2x8Xb6xha954sy9DpdPj0009x3333eV2PwWDA0qVL6z3evn///khISPB6HyIiIiJy7ty5c7BYfBtwoeDJ/duAvWtLbK5rBAMGa607g1rg/EViEmQIEDCvWIdLqpru6+yOHDmCjIwMl8e3bt0a7733XpMOhRIFiyCocOxopdvzRAiIEcI93jdOLMalYduhEpx/T5Qkhcf72F1PpfPpeo1Neno65s+fD53Ovc+DTqfD/PnzkZ6e7qfKiIiIiIiIiIiIiKixCMlgKAD07t0bBw4cwIwZM6DT6SDLslW30Loh0er7sizjyiuvxM6dO3HTTTf5pJaPPvoI+fn5VnvXduWVV/pkHyIiIiJyrrLS/fANNUwmg4Qf382H7aEAMi7S7oPuf0fIV9uRcNbpmj9oL5xHr4KA5YVhaK+I8U2xDciBAwdw3333obzctQ6FHTp0wHvvvYfExEQ/V0YUmtSqWEgenNKugQpinX9fcJ2MYbrdLoVCAcBo1EGWPd2rzs6iAuaI5j5ZqzEbOHAglixZgrS0NJfGp6WlYcmSJRg4cKCfKyMiIiIiIiIiIiKixiBkg6EAEB4ejjlz5uDs2bN49913cc0119R0uKkdBA0LC8PgwYPx9NNPY+/evVi7di26devmkxokScKrr75qs2ftkCqDoURERESBExYWFuwSyEd2rixGSY7Z5npb5Wm0UZ2xumYWJKxOPeZ0zaVhhprOotpmXbFgyPuIUEb4puAGYPfu3ZgyZQoqKipcGt++XXu88847iI+P93NlRKFLFNWezYPnQc0WivOIU5S6PF6WlSgr9U2YsyJ1EOQQ7xhaLT09HZ988gkWLlyIiy++GAqFdWdWhUKBSy65BAsXLsQnn3zCTqFEREREREREREREVKPpnn3ohqioKEycOBETJ04EcOFo95KSElgsFsTFxUGj0fht7zNnzmDChAn13lcqlejdu7ff9iciIiIia8nJyVAoFDxOvpE7fUiPPzbYdrzUCVUYpN1vc/3HpFPICXPeLTZbJeNLnQnXW2KQc9lTaBWVjCe6PYFn8awvyg6qvXv34tGXn4PBYHA++H+eeeYZKKOj/VgVEUmS0bN5sGmX7LJ09d9uzyksTEVUdK7He1Yr6TrW6zWaElEUMWjQIPTu3RvZ2dnIy8uDXq+HTqdD586dERMTE+wSiYiIiIiIiIiIiKgBYjDUDo1Gg+bNA3NsWUpKCmbPnh2QvYiIiIjIOZ1Oh6FDh2Lz5s3BLoU8ZKiU8NOSAjt3ZAzW7oVWtA5ZmQUJy9MOurz+3MgqDOn2MMxRyQCATtGdvCm3wZg/b75boVDgQoddzyJrROQqo6kIogi3j5M3wARJlt0+Tl4JM1KUOe5tBqC8PAFV+khodbahfFcZ4tpC35Ivjq2PVqtFSkpKzfs6HTurEhEREREREREREZF9IX2UPBERERGRPTfccEOwSyAv/PpxIcoLbTu+tlNlo7XqnM31H5NOITvc9SBTpkrCVzqTVzU2ROySS9QwybIJHTqGuT1PgoxiucLteeFiJUTBk26jAk6f7gGLReF8qB2SUovcEU8AAv+pioiIiIiIiIiIiIjIW+wYSkREREQhQ2/W41DxIYdjusZ0xYABA5CWlobMzEyP90pNTfV4LnnuxG+V+GuLbRBKJ+jtHiHvbrfQakuOLcGolqOgEDwLQBERuaPfwEj8daTS7Xm5cgniEOHWHBXMbu9TraoqGlmn+iK19W9QKFwPm0tKLc6Nfg7GhA4e701ERERERERERERERP9gMJSIiIiIQsZZ/VlM3jHZ4ZgVw1egfWR7ZGRkYOLEidDr9W7vo9Pp8MADD+L9d3I9LZU8oC+1YPMy+0fID9HuhUaw7fLpbrfQalkVWdhwZgP+1epfHlRKROSedu10aJUSgdPZ5W7NK5ErUSEbEC5oXJ5j8vKfiioqEnDi+CC0avW7S8fKG+LaInfEEwyFEhERERERERERERH5EM/nIiIiIiKyIz09HfPnz4dOp3Nrnk6nw/z589G2XVs/VUb2yLKMzcsKoC+VbO6lqU4hRZVjc93TbqHVlhxbAovM49eJyP8EUcCk+7tAo3G/S/HfllxYYPvYWJ8KKQySLLi9T21VVdHIzByKEycHojx1MGTRum5ZVKC8zRCcufJVZI9/l6FQIiIiIiIiIiIiIiIfY8dQIiIiIqJ6DBw4EEuWLMFTTz2FrKwsp+PT0tKQkZGB9PR0nD7tXlc38s7RbRU48Zttd9dwoRIDtQfszvG0W2i16q6hHdHR4zWIiFzVuk0UHpnWA2+89jsMBtdD6RaNGb2uC8OfawwwG2Sn481QItuchNaqc96UC0CAvu0A5PxrHASTHsry8xBNekgqHcwRzSGr3HvhBRERERERERERERERuY4dQ4mIiIiIHEhPT8err77qdNysWbPwySefID09PQBVUW3lBWZs/bDQzh0ZQ3S/QS2Ybe6YBQkfdLAfGHXHkmNLIMmud+IjotBhlsw4WX7Sp52Fu3aPx6zZfdEqJcKl8a1SIjBrdl8MvToR18xKQlyKyqV5Z6J9E3hXDOsFAJBVOphiW8PQPB2m2NYMhRIRERERERERERER+Rk7hhIREREROSGKzl9P1aNHD5fGkW/Jkoyf3i+AsdK2C15H1Um0VJ63O++nln/jVFil1/tnVWTh1/O/er2Ov0kW98Ort99+O6Bf7YdqiJqmclM5duTtAAAcKz2GT058Ar1FD51Ch1vb3ooOUR0wqNkgRKhcC3XWp3WbKLwwZyAOHyrEjz+cxoF9+bBY/nkMVCgE9OydgMsub4UuXeMgiheOhW/WRo0bX0jG6cNVOPRjGU7t10OqlVkVFUDrXjp0vSwSLdNTYJp7CPLZfI/rFFokQOyU6vF8IiIiIiIiIiIiIiLyHIOhRERERETUaB3aVI7Th6psrkcIFRig/d3uHLNgwYcd9vushi9OfeGztfzBbDbjrbfewv2IdWm8IAiYOXMmrh7RF1jJYGhtOfocvH74dYdjpnaZiiRdUoAqooYktyoXM/fOtLmut+ixNHMpAGDF8BVeB0MBQBQFdOsej27d42GosqCgoAp6vRk6nRLx8VpotAq78wRRQEo3HVK66WAySCjPt8BYJUGtFRGRoIBK888LHFS3XwHj6ysAo8n9AtUqqG6/AsL/QqlERERERERERERERBRYDIa64MyZM9i3bx9+//13nDp1CmfOnEFeXh70ej2qqqpgNv9zNGXPnj3x9ddfB7FaIiIiIqLQUJxjwvbPiuzcuXCEvMrOEfIAsLPDbziu8SDoVI8cfY7P1vI1g8GAJ598Etm7D+D+nlc6HS+KImbPno0rr7wSKDzp/wIbmQpzBX4896PDMZM6TgpQNUQXaLQKtGgZ7vY8lUZEbMv6O12LKc2hmjQWpvfWuBcOVaugmjQWYkpzt2siIiIiIiIiIiIiIiLfYDC0Hps2bcKXX36JDRs24Pjx4zb3Zdn2qEoASEhIcHsvSar/WEceR0pEREREZEuSZGx6rwBmo+3z8nTVcbRQ5tmdp9QVYUmK7fP7pqiqqgqPPfYYdu7ciba6aKfjFQoF5syZg8suuywA1RGFpgJDAdpHtg92GS5TpLeGMPUmmD5c79Kx8kKLBKhuv4KhUCIiIiIiIiIiIiKiIGMwtJaqqiosXrwYCxcuxKlTpwDUHwCtJgiCS+PqYzAY0LZtW+Tm5tq9//rrr+Phhx/2aG0iIiIistY6vDV+uPwHh2MiVZEBqoa8sf/bUuRmGmyuRwjl6Kf9w+4cQTAjN203YmUByWYB55SOn8NrRA06RHWAAMdHIVfpq3AMx1wvPgDKy8sxdepU7Nu3z+U5j09/HP0YCiXyq9VZqzEgYUCwy3CLmNIc6pm3Q/orC5Yt+yEdPAHUfoGrKELs1haKYb0gdkrl8fFERERERERERERERA0Ag6H/s3TpUsyaNQt5eXlWIc/q4Ke/aDQaTJs2DU888YTd+8uXL2cwlIiIiMhHlKISsZrYYJdBXsrPMmL3V8V27sgYpvsNKsFid15yi8PoCjOG510I//6gMWFWtB5HVfY7+M/tNxdDmg9xWs/ff/+Nm3CTq+X7XVl5OZ556lEcPnzYrXl9+vTxU0VEoaHAUOB0zI/nfsTD+oeRqEsMQEW+I4gCFJ1bQ9G5NWSDCXJRKVBlBLRqCLFREDSqYJdIRERERERERERERES1hPw55WfPnsWIESMwadIknD9/HrIsQxCEmjfgQjdQR2/emjx5MiIjI632rd77wIED+OMP+x2PiIiIiIhCjcUkY9O7+ZDsZD+7qDORpLR/1HFU1DnExZ22una5QYVfz0dibrEOsZL1C8IGNxvsUii0IXr+uefcDoUSkfdWZ612OsYsm7E8c7n/i/EjQaOCmBQPsU0yxKR4hkKJiIiIiIiIiIiIiBqgkA6GbtmyBX379sUvv/xiFQgF4NPgpzMRERG47bbbavaqu+cHH3zg9xqIiIiIiBqD3auKUZBtsrkeJZahr+aQ3TkqlR4tW9l/sZUKAiZVaLA3JxL3l2ughAIKQYFHuzzqy7ID6lRWVrBLIAo5ufpc/HjuR5fGrspehVx9rp8rIiIiIiIiIiIiIiKiUBaywdDvv/8eo0ePRm5ubk0oFIBNGLRuF8/a4VFfuu+++2yuCYIAWZbx6aef+nw/IiIiIqLGJudYFfZ/U2pzXYCModrfoLR7hLyEVin7oVCYHa4dK4uY3n4iPrtkBWZ2m4n2ke19VDURhYLlmcthlh0/zlQzSaZG3zWUiIiIiIiIiIiIiIgaNmWwCwiGLVu24JprroHBYLAKhNZWO/wZiK6hPXr0QJcuXfDnn3/WBEKrazh37hwOHz6MLl26+L0OIiIiIqKGyGSQsOm9Ath7at5VfQyJygK785o1/xvh4UVO19cndsGZnuORX3oEKeEp2JO/x+64rjFdoVPq3Kqdmo5wZTguS77M6RgKLbn6XKzKXuXWnFXZq3BX2l1I1CX6pygiIiIiIiIiIiIiIgppIRcMzc7Oxvjx4+sNhda9FhsbiyFDhmD48OHo0KED4uPjERcXh65du9YEOH3lpptuwuzZs+12JN24cSODoUREREQUsnasKEZJrm03vmixFL3rOUI+LKwQzZsfc7q2RR2G3MuewllDLibvmOxw7IrhK9hNNIQl6ZLwat9Xg10GNTDLM5fDJJncmlPdNXRG9xl+qoqIiIiIiIiIiIiIiEJZyB0lf/fddyMvL89pKLRfv374/PPPkZ+fjzVr1uCxxx7D2LFjMWTIEHTu3NkvtY0ZM6beexs3bvTLnkREREREDV32QT0ObiyzuS5AwjDdHigFyeaeKJrQKmU/7LzmykbesKkwRyb5olQiCjGedAuttip7FXL1ub4tiIiIiIiIiIiIiIiICCEWDP3oo4+wadMmm1CoIAg13T8jIyOxYsUK7Nq1C+PHj7fbvdNf+vbti4SEhJqaqv8vyzJ++eUXSJLtD7yJiIiIiJoyQ4WEn5bYPya+m/oYminsHRMvo2XLP6BWVzldv7TjaJSnjfCyyoavdZvWwS6BqEnypFtotequoURERERERERERERERL4WMsFQi8WCjIwMu6HQ6l/37NkT+/btww033BC0Oi+66KKaemp3My0rK8OxY86PwSQiIiIiakq2flSIiiKLzfUYsQS9NYftzomNPY3omBynaxujWyJv6BSva2zounfvjtmzZwe7DKImx5tuodVWZa9CgcF++J2IiIiIiIiIiIiIiMhTymAXECiff/45jh8/bhUErd0NtE2bNtiwYQOaNWsWrBIBAIMGDcKaNWvs3jty5Ag6deoU4IqIiJoWpVKJ2NhYm2tERI40a9YMzz77rNMxtcXGavDv+7o4nBMbq7G5Fh6rwIh/xzucFx6rsHpfiI6A8rZRDucI0RE218zh8ci95HGH88zhjmvxp9LzZsSnqNBnbDRKz5tw7i8DKoosNUfIK+wcIa/WlCO5hf3AaG2yqETuZbMgq3T+KN1v9vz2G4AWLo/v27cvXnvtNehK9TD6ryyikORNt9BqJsmEVVmrfFMQERERERERERERERHR/4RMEuaDDz6wer9259CIiAisW7cu6KFQ4EI3n/ocOXIE48aNC2A1RERNjyAIUKlUNteIiBxRq9VIS0tzOqY2lUpEqxTbMGbdMXUpVALiUlR2RluPsaJUQGyR4HAOlAqbS7JCDWNcW4fTZIXa4X1/sZhlGPUSWnTW/u+KDj3/dSEsKh47iYSDBqDceo4gWJCSsh+iaNthtK6CAffA0Kyj7wv3ow0bNmDB/HdxTdvXXBp/0UUXYe7cudBqtZBK9X6ujii0GC1GrMm2/6JOd/2U85NP1iEiIiIiIiIiIiIiIqoWEkfJFxYWYuPGjTbBH1mWIQgCHnvsMXTs2DB+KOyoI+iff/4ZwEqIiIiIiIJDlmWUF5ghSbLNvbjmAloPS4D63qsgdm9ndS8x6S/odKU1729Vm2GE7RqVrfqiuMd43xfuR2vWrMHTTz8Ni2TbJdWeESNGYP78+dBqtc4HE5HbzlSegUEy+GQtb7uOEhERERERERERERER1RUSHUO3bNkCi8VSc4x87YBo8+bNMX369CBWZy01NbXeeydOnAhgJUTU0AiCwM6WPiCKIhSKOkcw8/NKFFJkO0HB2gTYPibodDqnHUM1Go3V44lGI6JVSqTDOWq1AnUfglQaEQmtbLt71qZQC9bzNGqghZPu9yolbDfTwhLvuGOooNAE/HFSkoDIOBERsYAsyZAkGaYqCUa9BeHmCgiCDGhUUP5rEKSURJi/246IiDwkJJysWSNTacE1CeVItYh4oUSHMVVKCBBg1sYgd8QMQGg8r5H7/PPPMXfuXJfHDxs6FLNeegRKZUj8dY8oKFLCUxCtikaJqcTrtSJVkShDmQ+qIiIiIiIiIiIiIiIiuiAkflK4detWm2vVAdEbbrgBYWFhQajKPrVajdjYWBQXF1v9AF6WZRQXFwevMCIKGlFsPMEVIqKGToYMg8VxhzeNQmM3HEoBIgOS+UJ4VxAAQSFAVAhQqkSER4kQLDGQSisg66sAAGK3tlAW5KFVyUarZZ6J0sMsAMeVEibEV2CYQYmXi3WIHzEdlrA4u1u3Dm+NHy7/wWF5kSrHYV9fW716NZYte92tOQ9OmcJQKJGfKUUl5vWbh+l7pnsVDo1WRWNql6nIQIbviiMiIiIiIiIiIiIiopAXEj8tPHLkSL33/vWvfwWwEtfEx8dbhUCrO52WlbGDCFEoqa9DKDuHek+qcwwvw7dEocMiW2CSHR/ZqxE0EOt0k7RYLDCZnMzTaKweTyRJhsXiuB5BECCK1o/psgSYLI6PC1cJonXDS0kGnMyBWgTq7AVZgsJkdjxPpQ1od02jXoZU6/MmCPL/tpchQgIUIhSxkZC0akhFF46N147sAvOO9lCe/xMAsFljwjqd9ce1RWPGxYlluKZ4IyYnpiFeE2+zt1JUIlYT668PzSOffPyx23NEPk8gCog+8X3w/eXf43j5cVRZqtyer1Vo0S6iHU6dOOWH6oiIiIiIiIiIiIiIKJSFRDD0+PHj9YaoLrnkksAW4wKtVmtz5D0ABkOJQkjd8KdCoah5YyjUO7Isw2y2DgsplUp+XolChEEyoNBY6HBMjCYGGlFjPc9gQGGhk3kxMdBo/plnMkkoL3McJo2O1kClqhNCNclO50VGq6BQ1XrcMpkh55c6nCNERV44Tr72NYsRmvJih/MMkTGQFWqHY3xFX2qBodhOmlaQEKmpBFQCJOWFz5eo0wCmcIhVRVAoLSgYcA+S1z0F2WLEU9F6u+vLAL7O+hobzm7AU92fwuiWo/340RBRKFCKSnSM6hjsMoiIiIiIiIiIiIiIiKyERIu0vLy8ml/XDv5ERkZCp9MFoySH1Gr7P3hnMJQodNR+rFKr1dBoNAwvEhFRk2YxyagotN9iNUwwQGMyQVNphEr/T2hWjAqDIuzC90ZJHQZD83R8FGbEIZXj7qkV5gqkhKf4rngiIiIiIiIiIiIiIiIiogYkJIKhFRUVdq83b948wJW4xmg02r0uy3KAKyGiYKgd/lSpVFAqQ6K5MxERhbjSPDPsPd1VCmbohH+OaFaaLFBWXej8LAgSZG1Uzb3i5O54Mcr5cc5XtboKXWK6eF80EREREREREREREREREVEDFBJpo7pBy+qAZVhYWDDKcaqystJuV8CGWi8R+Vb1n39BEBgKJSKikFBZbIHZYJsKFSAjQqxE3WfGSqMZklYABAAqLS683k3CyVbdkJ/reC+tQosH0x/0UeUUavKq8vCfY/9xOOaeDvegmbZZgCoiIiIiIiIiIiIiIiIishUSiSOdTmfVNVQQBMiyjIKCgiBWVb9z587Zvc5gKFFoUSgUPDqeiIiaPLNRRkVxPUfIi1VQwvaeQmGCWrbACC0gCJDVOgjGCrRURuMNOR3PyEdQItrvtn9X+7sY2iOPlZpKsfLUSodjxrcZz68xIiIiIiIiIiIiIiIiCqqQOEo+PDzc7vWGGAw9f/489Ho9gH86m1b/PykpKWh1EVFg1A6CKhSKIFZCREQUADJQlmcG6jlCXivYHgsvCBLUaj1U0j+nAsiqCy+gEgCMi+mHfbmRmFSugaLOX3cStYm4rf1tPv0QAo3dxImIiIiIiIiIiIiIiIjImZD4qWLz5s2Rm5tb0ym0OnhlMBhQWFiIuLi4IFf4jwMHDti9LggCUlNTA1wNEQVa7WCoKIZEdp+IKKDUohrtIts5HUOBUVFsgdlo/wj5SLHC5gh5AFCp9RAgQykZLwRKBUBWaWrum8NiES+JmNl+Ei5Pvxj/9+f/4dfzvwIAHur8ELQKrZ8+GvdVVla6NV6j0eCJJ57AXyv8VBARERERERERERERERERNQkhkTpq27Ztvfe2bt0awEqcc1RP+/btA1gJEQWTIAg8Rp6IyA8ECNCIGodvgt04IvmaqUpGZUl9R8jroYBkc12pqoJCNAO40B1UqB4j/PPXGkkVBn1SVxT2vQ1tI9vijQFv4K0Bb+HKVldidIvRPv84PFVcXIznn3ve5fFhYWF488030atnTz9WRURERERERERERERERERNQUgEQ9PS0uq9t3nz5gBW4ty3335b770+ffoEsBIiCiaGQomIqCmTZaAs3/4R8irBDJ1gsLkuihYoldbXBdlOMFQTidxLnwJERc21wc0H47lezzWY76/5+fmYNGkSTpw47tL4yMhILF68GH379vVzZURERERERERERERERETUFIREMHTQoEE216qPlV+zZg1k2c5PpIPg8OHD2Lt3b01tdQ0YMCAIVRERERER+VZFoRkWk/0j5CPECtsJggyVutKml2vN+7UCn/rkHjBHJvqsVl/LycnBxIkTcfy4a6HQqKhovPvuu+jWrZufKyMiIiIiIiIiIiIiIiKipiIkgqFDhgyxer926PL48eP48ssvA12SXW+88YbV+7U7GqWkpDjsfEpERERE1BgY9RL0pbbHxAP1HyGvVukhCvbn1GbRRsMclex1jf6SnZ2Nf//738jOznZ5TkZGBjp27OjHqoiIiIiIiIiIiIiIiIioqVEGu4BASE5ORu/evbFv3z6bbpyyLOOVV17B+PHjg1ghcPToUSxbtszmeEtZliEIAsaNGxekyoiIiIiIfEOWgLJ8i9179R0hr1AaoVCYnK+tUMMc3tyr+gwWA05XnnY4plVYK2gUGrfXPn36NObMmYP8/Hy35rVs1dLtvch/tAot+sT1cTqGiIiIiIiIiIiIiIiIKJhCIhgKADfeeCP27dtX83514FKWZezbtw8vvvginn766aDUJssy/v3vf8NsNtd7jPxNN90UhMqIiIiIiHynrMAMyez6EfKCKEGlqnK6rgzAFJkMiN4diHC68jRu2uz4efeK4SvQPrK922tnZGSgrKzM09KogWgZ1hLvXfResMsgIiIiIiIiIiIiIiIicigkjpIHgDvuuANqtRqA9RHt1UHM5557Dj///HNQaps+fTq2bt1qFQqt/esePXrgoosuCkptRERERES+YKiQYCi3fxx8eH1HyKsrIcA2SGpDVEJWBa9LoyQ5P+aeoVAiIiIiIiIiIiIiIiIiCpSQCYYmJyfj9ttvtzlGHrgQwrRYLBg7diw2bNgQ0LpeeOEFvPbaazZHyFcTBAFTp04NaE1ERERERL4kWYDyArPdeyrBBK2dI+RVqiqIgv1j52uTBRGyGLyDEI4cOYInnngiaPsTEREREREREREREREREdUVMsFQAJg1axa02gudhKqDmLXDoeXl5bjqqquwePFiv9ei1+txzz33ICMjo+Za3W6hgiCgW7duuP322/1eDxERERGRv5TlmyHZyXheOEK+0ua6qDBDqbQNiwKAScA/PUQFAbJC5btC3bRjxw5MnDgR2dnZQauBiIiIiIiIiIiIiIiIiKiukAqGtmnTBk899ZRV11DAOpBpNpvx0EMPYcCAAdi6davPa5BlGZ999hm6dOmC//73vzUB0Lo1VXPUTZSIiIiIqKGrKpdgrKzvCPlK2yPkBRlqtW1YFAAkATiqtOBvpQS9AEgqHYDgPFc+cuQIpk+fDr1eH5T9iYiIiIiIiIiIiIiIiIjqE1LBUACYMWMG+vXrBwBWgcu63Tr37NmD4cOHY+DAgViwYAGysrI83lOWZezbtw8ZGRlo164dJkyYgFOnTtkNhdbuFjp58mRcdtllHu9LRERERBRMFrNc7xHyasEErWC0va6uhAD7L5o6L8owCkCZKOOIyoJK2QS5nrH+JEkSMjIyGAolIiIiIiIiIiIiIiIiogZJGewCAk2lUuGLL75Av379UFBQYBXMrA5kVl+TZRm7d+/Gnj178MQTTyApKQldunRB586d613/7NmzeOaZZ1BZWYmcnBycPHkSf/zxByoqKmr2AGyPsq99TRAEdO/eHa+99ppfPgdERERERIFQlm+GbKdZaH1HyCuUBihE+0FSowDkitaLGS1GyIIMpagEZEAUAvO6t127diEzM9PrdTp37gITs6VERERERERERERERERE5GMhFwwFgNTUVKxduxajRo1CeXm5TTgUsA5uVl87d+4ccnJysGnTJquxtcOd586dw8svv2y1n73wZ33XZVlGamoq1q1bB41G45sPmIiIiIgAADJkSPaSirWIggghSMeTNyX6UgtMevvdPMPFSoh1jpAXRAtUqqp61zunkCDV89tilszIKstCoi4RkapIj2t21cqVK32yTnh4OIoZDCUiIiIiIiIiIiIiIiIiHwvJYCgADBw4EN999x2uuuoqlJaW2hzpXjcgWvd6fezdd7ZG7VBoy5Yt8f333yM5Odn1D4aIiIioAfrqq6/w1FNPWV275ppr8MorrwSpIsAoGXG87LjDMe0i20Ej8gU63rCYZFQUWuzes3uEvCD/7wh5+yoFGYWi4+fhRskIs2S/26irWoW1worhKxyOiRfisXXrVq/2qbZ37160Sx3mk7WIgsJJ0B4AtDmHYIxNBQLU0ZeIiIiIiIiIiIiIiIhCOBgKAEOGDMH27dtx9dVX4++//7Z7vHvdrp72xtRWNwRqbx1742VZRufOnbF+/XqkpKS4/8EQERERETUEMlCaZ4a9p7+CYP8IeZWqCqJgP2AmAzitcBwKBQCtQosYdYybxVrTKDRoH9ne4Zjjx4/DYrEfenWXJPlmHaJgUOcfQ9LGF52Oa77ldUQfWoXcEU/AmNAhAJURERERERERERERERFRSAdDASA9PR27d+/GlClT8MknnzgMfzrrFurqGAA2e9x+++1YtGgRIiIi3CmfiIio0XjrrbewaNEit+ZotVpEREQgIiICSUlJ6Ny5M7p06YKhQ4ciNjbWT5USkTcqSywwG+w/J44QbI+QFxUmKBVGu+MBoESUUeGkWygAJGoT632Rli9VVtoGW4lCje70b0j+fjZEc5VL4zWFJ9Bq9VScG/0c9K36+rk6IiIiIiIiIiIiIiIi4lluAGJiYvDRRx9hzZo16NChg9Ux8rWDot6qu54sy2jdujVWrlyJ//73vwyFEhER1VFVVYX8/HycPHkSO3bswLJlyzB9+nRcfPHFeOSRR7B///5gl0hEtZiNMiqK6ztC3ghNnSPkBUGCWq13uGaELCBBcvx8XBREhKvC3SvWQ2FhYQHZh6ihUucfcysUWk00VyH5+9lQ5x/zU2VERERERERERERERERUjcHQWq666iocPnwY77//Pjp37gxZlu2GRF0JjNY3tnrNli1bYu7cuThy5Aiuv/76gHx8RERETYXJZML333+PW2+9FS+99BL0esfBMiLyP/l/R8jDTnNPUZDsHiGvVldCsDehFqUMJGuaoV1EO4Qr7Yc/VaLKo5o9kZycDIVC4ZO1RNE36xAFjCwh8ae5bodCq4nmKiT+NBeQJeeDiYiIiIiIiIiIiIiIyGMhf5R8XaIo4p577sE999yD7du348MPP8R3332HrKwsq3HVQU9H4dC6x8qHh4dj9OjRuOWWW3DNNdf47AfKREREoUqSJHz44YfIzMzEu+++C7VaHeySiEJWZZEFFqP9kGe4UAmxTgBUqaqCKNrvLlqbpNLBHBYPDYDU8FSUm8uRq8+FUbrQfVQhKCBAgOwkYOorOp0OQ4cOxebNm71eq2/fvijK80FRFDCFhkKsPLnS4Zgb2tyAOE1cgCoKLN3pvdAUnvBqDU3hCejO7OOR8kRERERERERERERERH7EYKgDgwcPxuDBgwEAf/75J3bs2IF9+/bh0KFDyMrKwunTp2EwGOzOjY2NRWpqKtLS0tC3b18MHDgQF110ETQaTSA/BCIiogbvs88+q/deVVUVSkpKcOzYMezatQu7du2yO2779u2YNWsW5s2b568yicgBU5WMylL7IU+NYIRGMFldE0ULlEr7z6Nrk0URpqhkq2sRygiER4ajyFgEi8ECpRj4v9LccMMNPgmGjhp1OVZ8zI7HjUmRsQhLji1xOGZki5FNNhgafXiNb9Y5tIbBUCIiIiIiIiIiIiIiIj9iMNRFnTt3RufOnXH33XdbXa+srIRer0dVVRUEQUBYWBjCwsLYsYyIiMhFvXr1cjpm9OjRAIDMzEzMmjULBw4csBmzdu1a3HLLLejTp4+vSyQiB2QJKMuv/wj58LpHyAvy/46Qd84UkQTZTvBTgIA4dRyqpCpIUuCPpDYajV6vkZaWhu7du2MF7AfeiQKp7mkXdsdknkD4qZ0+2S88awcEkx6ySueT9YiIiIiIiIiIiIiIiMgag6Feqg6CEhERkf+lpaXho48+wqRJk7B9+3ab+2+99RaWLVsWhMqosVAJKrQOb+10DLmuvNAMi8l+qCzCzhHyapUeguA8zGnRRUPSRPikRl+qqqrCggULvFpDp9MhIyMDgij6qCoiz0nZ52Fe9o3TceKq7yB0tN8Z2F2CZIGy/DxMsY4fj4mIiIiIiIiIiIiIiMgz/EkkERERNSoqlQrz5s2DTmfbZWz37t0oLy8PQlXUWIiCiDBlmMM3UeBTZFcZ9RKqyuyHPDWCEeo6R8grlEYoFCa742uTlGqYwpv5pEZfW758Oc6cOePxfJ1Oh/nz5yM9Pd2HVVFTJEnOu3geO1rs0rj6WP48BePrKyCfL3Y6VhR9EwqtWc+k9+l6RERERERERERERERE9A/+1JuIiIganYSEBIwdO9bmutlsxs6dvjnmlogckyWgLM9+UMzeEfKCKEGlqnK+riDAFJkMNMCA7qlTp/Df//7X4/lpaWlYsmQJBg4c6MOqqCk6dbIUC//vD6fjlr9/BM88uROnTpa6vYeUfR6mJWsAo/OwNgBIksLtPRyux2Pka0iS8y7KBw4ccGkcERERERERERERERERwKPkiYiIqJEaPHgwVqxYYXP95MmTXq1rMpmQnZ2N48ePIz8/HxUVFTCZTIiKikJ0dDQSExPRrVs3aLVar/bxtLbDhw8jMzMTRUVFkCQJcXFxSEhIQO/evREdHe23vauqqrB//36cPHkSxcXFUCgUiIqKQps2bdCtWzeEh4f7bW97DAYDDh8+jFOnTqGgoABGoxFqtRoxMTFITU1Fly5dAl5T9e/P8ePHUVxcDIPBCItFg9TUtujUsavbXzMlpcU4mvknTp89hfKKcqjVGsTHxqN9206IaxX8bpNlBWZIFjeOkFdXQoDzzobm8ATISo1PavQlWZbx6quvwmRyLURX16xZszBu3DiIPD6enDj4RwHefO13GAyudeg8nV2Ol577DY9M64Gu3eNd20SWYfpwvcuhUAAwGnWQZQGC4HmH0prtRQXMEc29XqcpOHLkCJ566imn415++WV8/vnnyMjIYMdhIiIiIiIiIiIiIiJyisFQIiJqtCorK3H27FlUVlYiLCwMLVq0QFhYWLDLogBp1aqV3euFhYVurSNJEvbs2YNff/0Vu3btwsGDB50Gv1QqFbp27YoxY8bgxhtv9CokOnPmTKxatcrq2ssvv4zrrruu5v3s7GwsXboU3333HUpL7XeFUygU6NmzJyZOnIgRI0Z4XE9df/75J5YsWYKNGzfCaDTaHaNWqzFs2DDce++96NOnj8/2rkuSJGzYsAFfffUVtm/f7vD3SaFQoE+fPrj22mtx9dVXQ6VSebTnW2+9hUWLFlldu+mmm3DzzTfXvH/69GmsWrUKO3bsQEVFhd11dLowXHLJaNx+20TExSU43POXXzZj6fvLse/Ablgk+8Gw1NRU3HnnnbjllluCEjQ0VEgwlNd3hLzB5gh5laoKouA85GZRh8Oii/VJjb62ceNG7Nq1y+P5PXr0YCiUnDp1stStUGg1g8GCN177HbNm90WE6DxYXfLrcYSdzXdrD1lWoqy0OaKic92aZ09F6iDI7BiKHTt2YPr06dDr9S6Nz8zMxMSJEzF//nx2HiYiIiIiIiIiIiIiIocYDKVGJT8/H7/++isOHTqEI0eOoLCwEGVlZTAajYiIiEBUVFRNl7DevXujb9++EAQh2GUTkQ9JkoRt27bh008/xebNm2E2m2vuKZVKDB8+HLfccgsuuugiBnCauIiICLvX6wtO1iXLMl5++WWsX78eeXl5bu1tMpmwf/9+7N+/H++88w4effRR3HjjjW6t4WqN77//Pt566616Q5nVLBYL9u7di/vvvx8XX3wxXnvttXo/R64wGo1YsGABPvzwQ6dH1xqNRvz444/48ccfcd111+HZZ5/1eUfVvXv3Yvbs2Th27JhL4y0WC3bv3o3du3dj0aJFmD17Ni6++GKf1iTLMlauXImVK1daPRbZo9dXYt26r7F58wY8OfMl9O9/kc2Y/Px8PPnkk9iyZYvTvbOysvDCCy9g1apVePfddxEXGeXxx+EuySKjrMD+x3vhCHnrgJOoMEOpNDhdVxaVMEcm+aRGT5klM8pMZTbXKyoqMG/RPCAMQBUAnuYcstSiGu0i2jkd4wlJkvHe24fdDoVWMxgsWPbmUXRUJDsda/xpP+BBXr6wMNUnwdCSrmO9XqOxO3LkiFuh0Gp6vR6PP/44lixZws6hRERERERERERERERULwZDqcErKyvDsmXL8Nlnn2Hnzp1Owym1NW/eHGPGjMHkyZPZUcWJyspK/PLLL9i1axf++usvHD16FLm5uSgvL0d5eTlEUURERAQiIiKQkJCA9u3bIy0tDR07dsSAAQOQnp7OEC753eHDhzFz5kwcPXrU7n2z2VwTTuvYsSNeeeUVdOnSJcBVUqCUldmGtwC4HEi0WCz48MMPva6jsLAQzz77LA4dOoSnn37a486UdVksFjzxxBP49ttv3Z77yy+/4K677sLy5cs9CoeWl5fjwQcfxM6dO92e+9VXX+H48eNYunSp23Pr88EHH+DVV1+FxeJZWOrMmTOYNGkS7rvvPkydOtUnNUmShDfffBObN292a15lZQVmZzyG559/Df36Dq65npWVhbvuugtnz551a70//vgDd955Jz5cthzRbs30XFm+BXI9vxU2R8gLMtTqSqdrygBMkUmQRYVvivTQqYpTuGnzTfZv/vt//18EwL0sOTUhKeEp+PySz/2y9qGDhTidXe7x/GghDAl58SgRHAfVlTAjRZnj0R7l5Qmo0kdCq7P/PdgVhri20Lfs7fH8pkCSJGRkZLgdCq2m1+uRkZGBTz75hC+EIiIiIiIiIiIiIiIiuxgMpQarsrISL7/8Mt566y2Xu7/Vdf78eSxfvhzLly/H4MGDMW/ePAwZMsTHlTZelZWVWLlyJT744ANs3brVaTc6g8GAgoICnDp1Cr/99pvVvZiYGAwaNAiXXXYZrr76anTq1MmfpVMI+vXXX/HQQw+hstJ5wAgAjh49ittuuw0LFy7ERRfZduajxi87O9vu9fj4eK/XVqlUaNGiBSIjIxEREQGTyYTS0lKcOnWq3sfKFStWQKPR4KmnnvJ6fwCYPXu2TShUoVAgJSUFcXFxEEUReXl5OHXqlN35Bw8exKuvvooXXnjBrX3NZjMeeeQRh6HQxMREJCUlQaVSITc3F2fOnLF64cb+/fsxffp0jBw50q297Vm6dCnmzZtX7/2wsDC0aNECcXFxKCkpwdmzZ+sNDb/77rvQ6/U++T3673//axMKValUSE1NRVxcHIxGI06fPo2CggKbuZJkwSuvPI0l732Olq0iUFhYaDcUGhUZjcRmyYiMjERZWRlOnT4Bo9G28+axY8cwZ+6reGXKY15/XM5UlUkwVtp/kY7WzhHyanUlhNpB0Xr8rVFAaSlFM1kDhRDccChRsGz64bTHc8OgQUcxGQrBeUgwXKyEKDj/c2mfgNOne6Btux1QKNwP60tKLXJHPAG4UGdTtmvXLmRmZnq1RmZmJnbt2oVBgwb5qCoiIiIiIiIiIiIiImpKGAylBmnDhg2YNGlSvWEXT2zfvh3Dhg3DPffcg//7v//z6njdxq64uBivvPIK3nnnHZSUlPhszfXr12P9+vWYPn06OnTogNmzZ2PChAk+WZ9C2+HDh90KhVarrKzElClT8NFHH7FzaBO0bds2u9c7d+7s9lphYWEYMmQILrnkEnTv3h3t2rWDUmn7NMlkMuHw4cNYtWoVvvzyS5uQ6AcffIBBgwbh0ksvdbuG2r766ivs2bOn5v127dph8uTJGD58OKKjrftC5ubm4r///S8+/PBDmEzWobyVK1fi2muvRZ8+fVzee+nSpfj1119trisUCtx666248cYb0aFDB5savvnmG7z99tsoL7/Q7W7Tpk0ev7Cj2u7du7FgwQK797p164ZJkyZh+PDh0Gg0NdfNZjO2b9+O//znP9i+fbvNvA8++AC9evXCmDFjPK7rwIEDOHLkSM37LVu2xE033YTx48cjLi6u5rrRaMHGjduxdOlbOHTogNUa5eVl+O8H72Du3Jfx2GOP1YRCBUHAv64Yg7GjbkHnjt2sOsHpqyrxw0/f4b3lb6KktNhqvdVr1uDGEaPQp2t3jz8uZyxmGeWFrh8hr1QaoBAddy4EgGKVEmWyATAaUWoqRYImAbGaWAhoPJ3Io6KivP56p9BmNEo4sD/f4/ntFYkuhUIBQAXnfy4dqaqKRtapvkht/Ztb4VBJqcW50c/BmNDB+eAmbuXKlT5Z54svvmAwlIiIiIiIiIiIiIiI7AqpYKjZbMbbb78NWbbfHeXSSy9Ft27dAlzVhY5emzZtsntPo9HgvvvuC3BFwTV37lw8+eSTbh0Z7ypZlrF06VLs2rULq1evRtu2bX2+R0MmSRLeeustPP/88ygsLPTrXseOHcP27dsZDA0Cg8GArKysYJfhM5IkYdq0aW6HQqtVVlZi2rRpeOONNyCKImRZtjmOWqFQQBAaTwApNTXVKggXis6fP4+1a9faXNfpdOjbt6/L67Rr1w533nknxo0b59IR9CqVCj179kTPnj1xxx134NFHH8Vff/1lNea1117zOhhaOxR67733Ytq0aVAo7HdRTExMxBNPPIGBAwdiypQpNuHQjz/+2OVg6IkTJ7B48WKb6zExMXjnnXfQq1evemu49957ceWVV+KBBx7A4cOHbT4Od5WVlWHGjBl2nw/cf//9mDJlit3PiVKpxLBhwzBs2DB88MEHmDNnjs1zv4yMDPTp0wdJSUke1VY7FPqvf/0L9957LxQKBcLDw63GCYKALp17YO6rb+PFl2Zi+/ZfrO7/+OM6LF3aribAGh4ejrfeegsD+w9G4Wnr30cA0GnDMPZf49G9S288NOMumxd3fLpmlV+DoWV5Zsj1PD2LFCqsOoMKogVKVZXTNSVBxFmFDPxvXYtsQW5VLoqMRUjUJiJC1TheyHPbbbfZ/bND5KqSYjMsFs+6eEYLYQgXXH9eYPLBPwNUVCTgxPFBaNXqd5eOlTfEtUXuiCcYCsWFY+C3bt3qk7W2bNkCvV4PnU7nk/WIiIiIiIiIiIiIiKjpCKlg6Nq1a/HII4/YDf9oNBqcOHEiCFUBzZo1w8yZM2Ew2B4NClzoiBUqx58/8sgjePPNN/2+zx9//IFBgwZh8+bNSE9P9/t+DcHp06dxxx134Keffgp2KeRnWVlZuPrqq4NdRoNy8uRJjBs3Lthl+MzatWttOjaGEpPJhMcff9zu980rrrjC5Y7QSqUS3377rceh4LZt22L58uW48cYbrY61z8zMxK+//uqT7933338/HnnkEZfGDh8+HBMnTrQJp/3www8oLy936fOyYMECm8+rTqfDe++9hx49ejidn5SUhPfffx+33HKL112/ly1bZnO0OgBMnDjR5c/JHXfcAQB4+eWXra6XlpbizTfftLnurlGjRmHSpElOxykUSkx99Gn88cd4lJf/01XSZDLijTdeB3Dh63HJkiXo06cPLCbH4bC2rdtj2tTHMDvjWavrG7dtQUVlJcLDwjz4aBzTl1hgqrJfl1YwQCXU6kAoyP87Qt6587owGMy23cuNkhHZldkIV4YjUZsIjaLhhuF79+6Niy++mMFQ8orR6OnR7kCiEO18UC0VUhgkWfDiOPkLqqqikXn8YsROvQjRR79DeNYOCNI/L76RRQUqUgehpOtY6Fv2Dvnj46udO3fO5kVKnrJYLMjJyQm5FzwSEREREREREREREZFzIfWTmSVLlgC40DWy9hsA3H333UhMTAxKXYmJibj77rtt6qqu7b333gtKXYE2a9asgIRCq50/fx4jR47EyZMnA7ZnsGzbtg09e/ZkKJSIGr1jx45hwoQJ2LVrl809nU6Hhx9+2K31vO0UGxsbiyeffNLmur1upu7q1asXpkyZ4tace+65x6bzqdFoxMGDB53Ozc3Ntft9YvLkyS6FQqvFxcXhxRdfdHm8PUajEZ9//rnN9S5dumDq1KlurXXHHXfg4osvtrn+7bffoqioyOMaW7RogXvuucfl8VFRMRh5Wf3H10+ePNnlzq4AcM24axEdbR0GqzIYcPDokXpmeM5iklFeZD/EpLBzhLxKVQVRcN753aiJwHlLucMxFeYKFBr92+XcGwqFAjNmzGhUXaepYVKrPfsaEiEgRgh3PrAWM5TINnvWMdlm/27toG87EDmjn8Pxu1bh1I1LkX3tQpy6cSmO37UKOaOfg75VX4ZCa/G0C359KioqfLoeERERERERERERERE1DSHz05msrCxs2LABgiBYvQEXOjTNmDEjqPXNmDEDSqXSpj5ZlrFy5UoUFxcHtT5/W7Fihctdu8LDw3HHHXfg888/x7Fjx1BaWgqj0Yjc3Fz88ssveOWVV9C9u2vHqJ45cwbXXXddvd1am4LVq1dj5MiRfj86nojIU/v376/3bceOHdiwYQMWLVqE22+/HVdffTV+//13mzUEQcCcOXOQnJwc8PqHDx+O2NhYq2v79+/3et0HH3yw3uPj6xMREYFhw4bZXD906JDTuV9++aVNB7OkpCTcfffdbtUAAP3798fll1/u9rxqGzZsQH5+vs31p556CqLo/tNXe/MMBgO++OILj2u85pproNG418Vy0CDb3xvgwnObu+66y621lEolhg8fbnP9cOYxt9ZxRUWRBainsWBEnSPkFQoTlAqj0zVlhQrnVCIssuOueaIgorm2uVv1BtKtt96KtLS0YJdBTUB0jBIKhfvhUA1UED0IJh8xtnd7jj2KYb1qfi2rdDDFtoaheTpMsa0hq3i8uT1hPu7qHB7uXjCYiIiIiIiIiIiIiIhCQ8gcJf/VV19BkqSasGXt/48aNQqpqalBrS81NRVXXHEFvvnmG6vagAvBhVWrVrkdGGgs/v77b5eOYRUEAffffz+ee+45JCQk2Nxv3rw5mjdvjmHDhmHGjBlYvXo1pk6dihMnTjhcd9++fZg2bRoWLVrk8cfQUH333XcYP348zGaz88EANBoNhg8fjuHDh6Nnz55o3749mjdvjvDwcAiCgKKiIhQVFSE/Px+///479u/fjwMHDmDv3r0u70FEVNfNN9/s1XydToeXXnoJV1xxhY8qco9CoUCXLl3w66+/1lw7deoUiouLERMT49GaiYmJdgOerujatSt++OEHq2uuHOv+yy+/2Fy7+uqroVarPapj/PjxNnW4auvWrTbX2rVrh379+nm0Xps2bTBo0CBs27bNZp+JEye6vZ5SqbTbhdSZtm072L0+cuRIREREuL1ep06dbK6dPJ3t9jrOWOo54lonVlkdIS8IElRqvd2xtcmCgPKIeBTpzzodm6BJgEJwLyAdKImJiR59/RDZo1aL6NkrAXt/y3NrngjPOo2etTRHoSUKcYpSj+YDgNAiAWKn4P49ujFKTk6GQqHwyXHyCoUCSUm+6f5KRERERERERERERERNS8gEQzds2FDvvZtuuimAldTv5ptvxjfffGP33vr165tsMHTy5MkoLXX8A0mdTodPPvkE11xzjcvrjhs3DhdffDFuvvlmh7//ALB48WLceuutGDJkiMvrN3S7d+/GjTfe6FJgs02bNpg+fTpuueUWm653tSUmJiIxMREAMHTo0JrrRUVF+O6777B27Vp89913KCsr8/4DICJyQqlUYtSoUZg2bRpatWoV1Fri4+Ot3pdlGdnZ2R4HQ/v27etxLfZe7FJe7vi4bpPJhD///NPmujdh2yFDhiAqKsrp93h77HVcHTOm/mPYXXH11VfbBEMP/HEABwsP2nRmbRfZDhqx/m6gaWlpbncLBYDo6BhoNFoYDFVW1z39/W7ZsqXNtbIAHSmsECwIE6w/DrW60qp7aH0sYXGQlVqEKcNQYa6/XpWoQpwmzuta3dFC1wLjy8c77iZbfOF/jz32mM87/1Fou/TyVm4HQyUX/szZJ2CLvj/GhP8MleBBQFGtgur2KyCIngVTQ5lOp8PQoUOxefNmr9caNmwYdDp2ZiUiIiIiIiIiIiIiIlshEQw1Go345ZdfajpwCrWO2tNoNG6FDf1p3Lhx0Ol0qKqqsqpVlmVs3LjRqotoU/HVV19h48aNDseo1WqsWrUKo0aNcnv92NhYrF69GldddRV+/PFHh2Mfeugh7Nmzx6MjahuavLw8jBs3DhVOwiFarRYvvvgiHn74YahUKo/3i42NxYQJEzBhwgSUl5fjo48+wttvv+3xekREzlQ/fl111VU+XbeiogJbtmzBoUOHcPToUWRnZ6OsrAwVFRXQ6/WQZdcDON6E5L05mtpe50lntfz1118wGAxW19Rqtd2OlK5SKpVIT0/Hrl273JpXXFyMkydP2lzv2bOnx7XUN7+qsgpZf2ehbce2bq3lTRA5LCzMJhjavr1nRzrbOz64vMJxCNhXIgTrEKhSVQVRdB4uk1Q6mMPioQaQGp6KclM5cqtyYZRsj59P1CZC8LAboqfKCsvw3eLvgErH4y666CKMGDEiMEVRyOjaLQ6tUiJwOtv1P8cGmCDJskfHyRdKMfixcjAuC9vuXjhUrYJq0liIKc3d3pMuuOGGG3wSDB0/frwPqiEiIiIiIiIiIiIioqao8SfgXLBz505UVl746W51oKM6ZDlixAiPju70h/DwcIwcOdKqxmpFRUXYu3dvsErzC0mSMHPmTKfjXn31VY9CodW0Wi0+//xzpKSkOBy3b98+fPLJJx7v05DcfffdOHfunMMx7dq1w969e/HYY495FQqtKyIiApMnT8aBAwcwe/Zsn61LRFRbVVUVHn/8ccycORNGo22gzF1Hjx7FtGnTMHToUDz66KNYsmQJNm/ejOPHjyMvLw+VlZVuhUIBeNQps1p0dLTHc+11sqwb+qzrzJkzNtfS0tKgVHr3GqL09HS359T3/atz585e1dKmTRu73R3zctzrzgfYD9+6SqWy/f3x9PdbrVbbXDOYvP/z4EzdI+RFhRlKpeOvMQCQRQVMUclW1yJUEWgX2Q6J2kSrI+PDlGGIVEX6rmgXvf766zV/b6iPWq3GE0880eResEXBJ4oCJt3fBRqNwvng/5Ego1j2vFPwOUsivqu4BIWWKJfGCy0SoJ56ExTprT3ek4ABAwZ49SIQ4ML36QEDBvioIiIiIiIiIiIiIiIiampCIhh68ODBeu8NHDgwgJU45+gHO44+jsboq6++wrFjxxyOufjii/Hoo496vVdcXBzef/99p+Pmzp3r9V7B9vbbb+Pbb791OKZHjx7Yvn271yEbZ5o1a+bX9YmoaThy5IjdtwMHDmDz5s1YunQp7rjjDkRF2YZWVq1ahSlTpsBkMnm0t9lsxquvvorrrrsO3333HfR6vbcfTg1v1vL1sbDOQq32Qqxxcd4f4e3JGiUlJTbXRFFEfHy8V7WIooiEhASb6+Vl7nfY9OQYeUe0Wq3P1nIzv+w2myPkBRlqld6lvp6miETIom3YWICAOE0c2ke2R6w6FgIEJGoTfVe0i3bs2IEffvjB6bi7777bq66xRI60bhOFR6b1cCscmivbPm66o1CKweqKkSi+8iqIPdoDdU9QEEWIPdpD9eD1UM+8nZ1CfUAURWRkZHj8/V6n0yEjI6NJnHZBRERERERERERERET+ERJHyf/555/13uvfv38AK3GuX79+9d5z9HE0RvPnz3d4XxAE/N///Z/P9hs1ahSuvPJKh6HJP/74A+vXr8cVV1zhs30DqaCgALNmzXI4JiUlBevWrUPz5vyBblOVmpqKtWvXBrsMn9m7d69Pus8+//zz6N27N2RZhsVifVyqQqFoVJ3fUlNTg11CQGg0GiQmJiIxMRFDhgzB/fffj5kzZ9ocvfrLL7/g5ZdfdvvrxGQyYdq0aS4FwTzhbofRYLIXDPVFR/XISPc7PtqrJTw83Cd/Ru19TBWlnnfaC0URovUR8mqVHoIgOZ1n0UVD0jj+mlIICiTpkpCgTYBSCOxfUwwGA1599VWn41JTU3HHHXcEoCIKZV27x2PW7L547+3DLh0rH9lSRKSsQFmuG8fB1xGXokbi6NYQxI6QDSbIRaVAlRHQqiHERkHQ+O6EAbogPT0d8+fPx+OPP+7Wi0l0Oh3mz5/vUVduIiIiIiIiIiIiIiIKHSEfDHUUxAyGvn371nuvKQVDDx8+jJ07dzocM2bMGPTu3dun+86aNctpN81ly5Y12mDos88+i6KionrvKxQKfPbZZ2jRokUAq6JA02g06NChQ7DL8Jn27dvj448/xtGjRz1eo2PHjhg/fjxEUYQsyzCbzVb3lUplowqGhqrY2FgsXrwYDzzwgE049NNPP8WQIUMwcuRIl9dbsGBBvaFQrVaLbt26oXv37khOTkZiYiLCwsKgVqvtdot8++23bWpqTOx1XFWpvA8B2Tvq3Bl7x977qqOmvXWqqqrsjCR7dGIVVPjn8VOhNEKhcN6tV1KqYQp3vYt4oEOhAPDBBx8gOzvb6bgnnnjC5x1jqXEpMZbg+7PfOxwzusVoRKujvdqndZsovDBnIA4fKsSPP5zGgX35sFj+CWUrFAJ69k7AZZe3QpeucSjIMmHVSzkwG9x/UYJSI+DSiQkQxAvPhQSNCkKSd12ayTUDBw7EkiVLkJGRgczMTKfj09LSkJGRwVAoERERERERERERERE5FRLB0LNnz9YEfmoHf1QqVYM76johIQFqtRomk8mqVlmWkZWVFcTKfOvjjz92OsYXR8jXNXjwYAwYMAC7du2qd8zatWtRVlbmUZezYMrKysJ7773ncMzUqVNx0UUXBagiIt8QRRGvvPIKbrvtNlRWVro9PywsDK+88gqP2mwiFAoFFixYgLFjx+Ls2bNW9zIyMjBo0CCXOl1mZmbio48+srkeExODhx9+GNdccw3CwsJcrsveMfeNid1OmhXed9IsL3f/mPbw8HC/1FLfOuERtvuRrQtHyP/T0U4QJahUzkO1siDAFJkMCA33Mfj06dNYtmyZ03GXX345Bg0aFICKqCHLN+Rj7sG5Dsf0je/rdTAUAERRQLfu8ejWPR6GKgsKCqqg15uh0ykRH6+FRvvPcfPN2qjxr0eaYd0beW6FQ5UaAf96pBmatXE/yE++kZ6ejk8++QS7du3CF198gS1btlh1t1coFBg2bBjGjx+PAQMG8DktERERERERERERERG5JCSCoWVlZXavx8TEBLYQF8XGxuL8+fM17wuCAFmW7R6t2lh99tlnDu+3aNECl156qV/2vv322x0GQ/V6PVatWoXbb7/dL/v7y+uvv27TBbG2uLg4PP300wGsiMh3unTpgoULF2LKlCluhUPDwsKwcOFCdOnSxY/VUaBFRETgueeew8SJE62u5+fnY9GiRZgxY4bTNT799FObx8yEhAR89tlnaNWqlds1Nfbv0faCrfU9f3KHJ2tER9uGqSorK2GxWKBQKOzM8K6eiCjnQWKSESlWoHZfZbXa+kj5+pjDEyArG26HTVmWMXfuXBiNRofjwsLCMHXq1ABVRWRLo1WgRUvHQfZW3XS4ZlYSNi3JR2G2826+cSkqXDoxgaHQBkAURQwaNAiDBg2CXq9HTk4OKioqEB4ejqSkJOh0umCXSEREREREREREREREjUxItJqoL6wRGxsb4EpcU19dvghoNATHjh3D8ePHHY65/vrr/dYJ5YYbbnB6ZPT33zs+HrKhKSkpwdKlSx2OefTRR+2GbYgai4suuggfffQROnbs6NL4jh074qOPPmKX3CZq2LBhGD58uM31jz/+GOfOnXM6/6effrK59uSTT3oUCgWAoqIij+Y1FPaee5w6dcrrdU+ePOn2nPq6r54+fdqrWoxGo9ULb6q1TmiNlmEtrd5UgsqrvZoarWCAEv90r1Op9BAFi4MZF1jU4bDoGubz7Wo//fQTtm3b5nTc5MmT0bx58wBUROSdZm3UuPGFZFz1RHO07auDWCdPLyqAtn11uOqJ5rjxhWSGQhsgnU6Htm3bolu3bmjbti1DoURERERERERERERE5JGQ6Bha99hQWb7Q3cidI2IDSavVQpZlm/BiUwmGbty40emY0aNH+23/xMRE9OzZE/v37693zI8//ui3/f1h5cqVDr8+VCqVTWc9osaoS5cuWLVqFbZv345PP/0UP//8s1XXR6VSiUsuuQS33HILBg8ezKM2m7hp06bhl19+qfm+DlwI/y1evBgvvPBCvfOKiopsjqEPCwvD5Zdf7lEdJpMJR48e9WhuQ9GpUyeba+fPn0dhYSHi4uI8XvfIkSNuz2ndujVUKhVMJutud3/++Sdat27tcS1//fWX3c7a3Tt1R5TKfhiVLtCKRsjShcdTUWGGUum4uyYAyKIS5sgkf5fmlcrKSixYsMDpuA4dOuDGG28MQEVEviGIAlK66ZDSTQeTQUJ5vgXGKglqrYiIBAVUGj4/IiIiIiIiIiIiIiIiaupCIhiqVqtRVVVV83710ex1A6MNhV6vt9vRUpKkIFTje5s2bXJ4X6lU2u0C50sjR450GAzNycnBoUOH0LVrV7/W4Suffvqpw/ujR49GUlLDDmcQuUoURQwZMgRDhgxBZWUlzp07V3PUZnJycoMN/ZPvderUCaNGjbLp8rxq1Srcd9999Xb/zM/Pt7nWqlUrqNWedU07dOiQ1fOMxqh58+ZITk626ba6bds2XHXVVR6tmZOT41HHULVajS5duuDAgQNW13ft2oUrrrjCo1qq59fVrFkztGzZ0uM1mwLJ4vw4+BqCDLW60qWhpsgkyHVbFTYwS5YsQW5urtNxM2fOhFIZEn9toiZIpRER25JBUCIiIiIiIiIiIiIiolATEj8hqi8kVFBQEOBKXFNfXU3lCLk9e/Y4vN+1a1dERET4tYZBgwY5HfPbb7/5tQZfyc3Nxc8//+xwzNixYwNTDFGAhYWFoX379ujRowfat2/PUGgIeuCBB2xeTGEymbB48eJ659jrsOzN186XX37p8dyGpHfv3jbX1q5d6/F6a9eu9fhFLb169bK5tm7dOpsuou5YvXq1S/uEmsoi50fCV1OrKyHAeZDUHBYLSd2wH48zMzPxySefOB03btw49OzZMwAVERERERERERERERERERH5TkgEQ6Ojo2t+Xfu42cLCQpSXlwejpHqVl5fXdDKrXSsAhIeHB6MknyoqKnLaPaxPnz5+r6Nv375Ox+zbt8/vdfjChg0bnAZv/vWvfwWoGiKiwOrUqRNGjhxpc33NmjXIysqyOycyMtLm2vnz5z3aPzc316vwZENi70UEW7duxV9//eX2WpWVlfj44489rmX06NE214qKirBmzRqP1vv1119x9OhRm+vedCBtCvRlEkxVrnUMVSoNUIhmp+MkpRbm8AQAQIGhAIXGQsguhEkDSZZlvPLKK7BYHIdio6Oj8dBDDwWoKiIiIiIiIiIiIiIiIiIi3wmJYGhqaqpNyLJaQwv/2TvevLr2Fi1aBLga33N0fHu1Hj16+L2ONm3aICoqyuGYhva1UZ+ffvrJ4f1WrVrVe5wyEVFT8MADD9hcM5vN9XYNbdasmc21s2fP4u+//3ZrX1mWMWvWrEZ/jHy1iy++GMnJyVbXLBYLnn/+eacBuroWLVqEnJwcj2vp06cPunTpYnP99ddft9vx1RGj0YgXX3zR5nrz5s0xatQoj2ts7CxmGRWFzoOeACAIFihVzr/OZUGEKSoZgACTZEJeVR5y9bk4XnYc5eaG82Ksb7/91qXnpA899BBiYmL8Xg81LgpBgRh1jMM3haAIdplEREREREREREREREQU4kIiGNq6det6723ZsiWAlThXXz2CIKBt27YBrsb37HXrqistLS0AlQDt27d3eN+VWhsCZ8HQgQMHBqgSIqLg6Ny5My699FKb62vXrrXbpTomJgYdOnSwuf5///d/Lu8pyzJefvllbN261Z1SGzRRFHHXXXfZXP/tt9+QkZHh8jpffvklli5d6nU99mrJz8/HQw89BKPR6NIakiThiSeewIkTJ2zuTZgwASqVytsyG62yPDNkxw3Ha6hUVRBcGGeOaA5ZceFzer7qfE2nUKNkRHZFNrIqsmCwGDys2DdKSkoc/1lvBiDjwtuLyhfR75t+Nm9/l7kXIqempU1EG2wctdHhW5uINsEuk4iIiIiIiIiIiIiIiEJcSARDu3XrZve6LMv44osvAlyNY47q6dSpUwAr8Q97wYy6AhUMdbZPTk5Og+8Cl5+fbzf0VFt6errD+5Ik4ddff8Wzzz6LcePGoWPHjoiPj4darYZWq0VcXBzS0tJw2WWX4b777sN//vMfj44VJiLyJ3tdQy0WC95++2274y+77DKbaz/88ANeeOEFmEwmh3vl5eVh6tSp+PDDD2uuKRRNozvcbbfdZvd508qVK3H//ffj/Pnz9c41GAyYN28ennnmmZprOp3O41quvvpqDBkyxOb6jh07MHHiRJw5c8bh/IKCAjz00ENYv369zb3OnTvj7rvv9ri2xq6yxOLyEfIAIArOE6QWTSQs2gvd2PUWPUpNpTZjKswVOF5+HDn6HFhk97rQ+sqiRYtQXFwclL2JiIiIiIiIiIiIiIiIiAJFGewCAqFux0RZliEIAmRZxoEDB7Bv3z707t07SNX9Y+/evdi3b19NbXU1hc6PrgRDU1JSAlAJnB6vLssyTp486TRYGUwHDx50OsZeVzzgQvB18eLFePfdd50GfYqKivD3339j06ZNeO+99wBcCJzefPPNmDx5MhITEz37AIiIfKRbt2645JJL8PPPP1td/+abbzB58mSbrtt33nknPvzwQ1RUVFhd//jjj7F9+3bccsstGDRoEFq2bAmlUomCgoKax8HVq1dbzWvbti3S09Oxbt06v318gaJQKPDSSy/hxhtvhMFg3dnxp59+wvbt23HJJZdg6NChSExMhEqlwvnz57Fv3z58//33KCwsrBkfERGBe+65B2+++aZHtQiCgDlz5mDs2LE2Qb6dO3fi6quvxtixY3HFFVegbdu2iI2NRUlJCbKzs7FhwwZ8/fXXKCkpsVlXo9Fg3rx5UKvVHtXV2JmNMiqKfBvKlBUqmCP/eS6Qq891OL7IWASjZERqeKpP63Dm4MGD+PrrrwO6JxERERERERERERERERFRMIREMLRfv37QarUwGAx2Q5cvvPACvvrqqyBV948XX3zR6n1BEKx+PXjw4ECX5HPZ2dkO70dERCA8PDwgtSQlJTkdk5WV1aCDoYcOHXI6JjXVOnRhMBgwd+5czJkzB3q93uO9jxw5goyMDMyZMwf//ve/8fzzzyMuLs7j9YiIvPXggw/aBEMtFgsWL16MefPmWV2PjY3Fk08+iaefftpmnePHj+Oll15yac/o6Gi8+eabPjk6vaHo1KkT5s6di2nTpsFisQ4QVlVVYf369Xa7cNYmiiLmzZuHoqIir2pp3rw5Fi9ejH//+9+orKy0uldZWYnPPvsMn332mcvrqVQqLFiwIGDdyRsaWQbK8s2A681Cna8pCDBFJkMWLhxEUGIqgd7i/PlFM20z3xXhAovFgjlz5th98VVtsXGxKIJ3X7dERERERERERERERERERMEWEkfJa7VajBo1yuoHwbW7hq5evdppwMHf1q1bh1WrVtkEV6vrvOiiixAfHx/ECn0jPz/f4X1Xwpq+kpyc7HRMQUFBACrx3NGjR52Oadbsn+DFX3/9hT59+uDZZ5/1KhRam8FgwKJFi9CxY0d8/vnnPlmTiMgT3bt3x8UXX2xz/dtvv8Xx48dtro8fPx7333+/x/s1a9YM77//fr2dmRuz0aNHY+HChYiIiHB7rkajwWuvvYYRI0b4pJY+ffrgww8/RIsWLbxaJzY2FkuWLMHIkSN9UldjVFVmgdlQNxjpXUrUEhYPSaUFAEiyhPP6+ruQV4tSRUGn0Hm1r7u++OIL/PXXX07H3XnHnQGohoiIiIiIiIiIiIiIiIjIv0IiGApcCH/YUx3EvPvuu3H27NkAV3XBmTNncM8991h1CK3rpptuCmBF/lP7iFl7YmJiAlOIi3s5qzfYXPmaTUhIAABs3LgRAwYMwOHDh/1SS0FBAW666SY88sgjkCTJL3sQETnz4IMP2lyTJAmLFi2yO/6RRx7BggUL3P7+M2rUKHzxxRfo3r27J2U2CiNGjMCqVavcClIOGDAAX375Ja644gqf1tK1a1esWbMGd955J7RarVtzlUolrr/+enz77bcYNGiQT+tqbPRl1t+fVQoj4rV5Hq8nqcJgDvunW7hJNkEUHP/1QoCA5trmHu/pifz8fCxevNjpuIEDB2LQ4ND+GiEiIiIiIiIiIiIiIiKipiEkjpIHLgRDp02bhoKCgpowaHU3TkEQkJubiyuvvBIbN24MaGfOgoICXHnllcjNzbXqFlo7JBoeHo4JEyYErCZ/kWUZxcXFDsdERkYGphgX92rowdCcnBynY8LDw7Fp0yaMHTvWZ11CHXnzzTeRm5uLDz/8ECqVyu/72bN9+3av5v/xxx8210wmEwwGg1fr1kepVNb8mRfFfwI1zo67Jc/Y+7zycx0Y48ePx9ChQ22u+/Lz36NHD3zxxRcwmUxW1xUKRb37jBkzBpdccglWrlyJH3/8EQcOHIDRaLSZ37ZtWwwZMgTXXXcdOnbsaFX72LFj0a1bN6s5PXv2dOljmzNnDubMmWNz3dPPy4ABA/Dnn3/6ZL2WLVvirbfewt9//421a9diz549OHHiBMrKyiAIAqKiotC6dWv06dMHo0ePRteuXa32uvbaa3Httdf6pJbw8HDMnDkTkyZNwjfffIOff/4Zv//+OyoqKmzGarVadO3aFcOHD8dVV11V0yXck32nTJmCKVOmwGAw4MSJEw7HVj+/rHlfst3vg/+utnq/RYtwqNSi1TzJzry6JEm2/r02mYEc15+3aBV6xOvyIMKzF3PIogLGyESrutWCGm3D26LIWIR8Yz4k2XbtOHUclILSL4+71S9MkWUZZrO55vqCBQvsfp3UplKp8Oijj9o8dthjNBptnhPUfcxwdZ7JhXmmOvOMRldrtP4cyy7WKNSu0cOPi6x5+vVBRFSbve9RrnzfIiIC+BhCRJ7j4wcReYOPIUTkDT6GEFFD1Zgei0ImGKrVajF58mS8+OKLVqHL6nAoABw4cADDhw/H6tWr0b59e7/X9Pfff2PcuHE4fPiwzRHytWu75557AtpJ018qKythsVgcjglkMDQqKsrpmNLS0gBU4jlXgqGnTp3Ctdde61IoVBAEJCcnIzY2FkqlEmVlZcjOznb7QW3FihWIiIjA+++/79Y8X7nooot8vmZRURHy8jzvquZIbGxsTYhWoVAAuBBuqR1qIf9y9thEvpGQkFDTxbg2X3+td+rUye51R/uo1WpMmDABEyZMgMlkQkFBAYqLiyHLMiIiIpCUlGQVdq+7Vv/+/dG/f3+39mxMWrdujSlTpjgdF4iPNyoqCrfeeituvfVWABe6QRYUFMBkMkGlUiEmJgbNmze3er7ni7pceZywWCxWe5ktzkOXZosZgtm6y6bF4jw0abGYAXOtbvNmi8tP7FUKo1ehUACo0sXDLAGQbD+3UYoohGvDUWgqRIm5pOa6QlAgWhHt068TSZJqnkNXr2symVBUVAQA+P333/HDDz84Xefaa6+FTqdDVmGW07FFhUXI01s/J6jez+E8O88lCgudBwELC4ugUlfWvF9W5Pzro6ioCGa19WkEisISxDqbV1gEi+Kfr4uwMucfV2FRESrNYU7HhTJPvz6IiJxx9uJbIiJH+BhCRJ7i4wcReYOPIUTkDT6GEFFD4MrPfRqKkAmGAsBjjz2Gd955x6prKPBPAFOWZRw+fBj9+vXDggULcM899/itlqVLl+Lxxx+3GzysHWSIjIzEzJkz/VZHILnSKUej0QSgEtf3augpb1eCqzfffLPDcbGxsZgwYQKuueYaDB48GGFh1j/YlyQJv//+O77//nssX74cR44ccam2pUuXomvXrpg6dapL44mIGgqVSoWkpCQkJSUFuxRyQX2B4/oYJSPOVJ1xOKaltiXUotrb0hqsOE2+V6FQWRBhVjoOAioEBZqpmyFKGYV8Uz70Fj3iVfFOj5r3JZPJhHfffdfpuMTERFx//fUAgHh1PKa3me5wfLw6cKcLEBERERERERERERERERF5InA/mW0AoqOj8eKLL9Z7jHD1sfIlJSWYOHEiBg0ahG+++canNaxduxYDBgzApEmTUFJSYhVKtVdPRkZGkwmmuBIMVSoDl1V2ZS9Xag6mqqoqp2MOHTpk97pSqcTMmTNx8uRJvPXWW7jssstsQqHAhaPNe/XqhRkzZuDw4cP4+OOPkZiY6FJ9Tz75ZL37ExERBYvFyX9NmVaph1r07vmNIEtQmJ0/BwEAjahBC3ULtNC0QKQicJ3hAWDVqlU4c8ZxCBgAJk2aVPOCoXBFOIbEDHH4Fq4I93fpREREREREREREREREREReCalgKHDhB7+jR4+2OkK+WnU4szqouWvXLowbNw6tW7fGzJkz8fPPP7vdQdJkMuHnn3/GzJkz0aZNG1xzzTX47bffrIKotUOh1e8LgoDhw4fjkUce8f6DbiAYDPU9g8H58aP2JCQk4KeffsKcOXMQFRXl8jxBEHDrrbfi999/x+DBg12qb9KkSR7VSERERL4XoSrzyToqo/Ou5dUEQUCYIszmubc/5ebmYuXKlU7HDRo0CH379g1ARUREREREREREREREREREgRNSR8lX++ijj9CrVy+cPXvWJphZN7ApyzKys7Mxb948zJs3DyqVCp06dUJ6ejpatGiBZs2aQafTQa1Ww2g0Qq/XIy8vD2fOnMGRI0dw9OjRmjBp3QBofdcAICkpCZ999llAf4DeEATy4xVF57loe91lGxJPgquxsbHYtGkTunfv7vG+zZs3xw8//IBRo0Zh27ZtDsdu27YNa9aswdixYz3ez13OanLmjz/+wH333Wd1LTY2Fs2aNfNq3foolcqar/3q/4uiGNCgdCiRZRkWi3VHQIVCEXKPt0Shqu6ff3sUCgWUCuvHYJfn1XrsliUJgOMXcSgVSiiVdZ6TSDIAs5O9lFAqaz1uufCURYAMrULvfKALlGY9lAoRCODR8PZYLBZIknShpv997hUKBT744AOnz5N0Oh2eeOIJn3x/LytzHri191zCZKwAcMLhvLi4WDRr9k+XUqXRBKDA6V6xzVRW12SL89+r2LhYCM3ia97XKCudzomLjUV4rH+eIzUVnn59EBHVZjKZUFxcbHUtJiYGKpXK/gQiolr4GEJEnuLjBxF5g48hROQNPoYQUUOVm5sb7BJcFpKpo/j4eKxfvx6XXHIJCgsL7YZDAeuQYvU1o9GIP/74AwcPHnS6T91Qob316t6TZRlxcXFYv349mjdv7uZH1rC58g3abHYcgvAlV7q/qtXqAFTiOYVC4fbn7L333vMqFFotPDwcK1euRLdu3VBUVORw7KuvvhrQYKgr3UzdpVKpao6ZDRQGFQOn+gUBRNT0CaLzP+uCaPuY4MpjRN3HEk/3cuG1KxDrzhMEp9lQhWCB81GuEWQZomyBLCp8sp4vVL/oJycnB7/++qvT8RMnTkRqaqpP9nblOaNarbZ5LqFSO38+qqozT612/nV1YS/rmiS1Gs5eUqRWqyFa7eXax4UAP0dqSMySGacrTyMlPAUKwf6fB0+/PoiInAnG31OJqOngYwgReYqPH0TkDT6GEJE3+BhCRA1BYwqoh2QwFAC6du2KdevWYcyYMSgoKLAJhwLWAdG6oU5XO0nWd1y9vTGyLCM+Ph7r1q3zSXCvoWmMwdCG/odZrVa79Tm75ZZbMH78eJ/t36JFCyxcuBATJkxwOG7btm34/fff0aNHD5/tTURERO4RBMm368mSj2KmviNJkksv4GrXrh1uvfXWAFRETU25qRw78nYAAI6VHsMnJz6B3qKHTqHDrW1vRYeoDhjUbBAiVBFBrpSIiIiIiIiIiIiIiIhCWXDPfgyyfv36Yfv27UhLS7M6Qr6u6iBo3aCoK2/25tdWe0x6ejp27tyJfv36+fGjDh5XOuV4cjS6p5pCx1B36lOpVFiwYIHPa7j11lsxaNAgp+NWrFjh872JiIjIDbJvOyPLQT5G3p78/HxUVjo//vzJJ5+sOXqeyB25VbmYuXcmZu6diaWZS6G36AEAeoseSzOXYubemcitajxHiBAREREREREREREREVHT1PB+mhtg7du3x549e3DnnXfW2yG0ttohT1ff7Kneo3rMvffei507d6Jdu3Z++1iDLSwszOkxrOXl5QGqBigrK3M6Jjw8PACVeE6r1bo89tprr0VycrJf6njwwQedjvn222/9sjcRERG5Rg2Tzzp8yoIAWWxYwUqDwYCCggKn46666ir07t07ABUREREREREREREREREREQVHyAdDASAyMhLLli3DN998g06dOtntDOoLtderDoR2794d33//PZYsWYLIyEif7NNQKRQKREVFORzjSljTV1zZKy4uLgCVeM6d+iZPnuy3Om644QbEx8c7HHPgwAEUFxf7rQYiIiJXKAUlknRJDt+UQsMKPPqKWjBDsqh8spakDgcaWMfQnJycel+UVS0yMhIPP/xwgCqiUFVgcB5QJiIiIiIiIiIiIiIiIvKnhvXT3CAbM2YMDh48iP/85z/o1auXx8fHu3KsfP/+/fHxxx9j//79uPzyy4P5YQeUsyBjSUlJgCpxba+GHgx1FsasptFoMGTIEL/VodFoMHToUKfj9u7d67caiIiIXKEQFIhVxzp8UwiKYJfptqpyyaVxZovaq33KRBmlogyLLsardXzNYrGgoqLC6bgHH3ywwT+/o8ZvddbqYJdAREREREREREREREREIY7B0DpEUcRdd92F3377DTt37sS0adOQlpbm8hHx1eyNT09Px/Tp07F3717s3LkTt9xyi8+6kTYWzoKMubm5AarkQlcpZ1wNXgaLq/X17t0barV3QRBnBg4c6HTMwYMH/VoDERFRKLKYZOhLLS6NlSxKSLJnwVcJQLZCwt9KCaeMBTBKRo/W8QeTyeR0TNeuXXHttdcGoBpqylzpBvrjuR+Rqw/c32uIiIiIiIiIiIiIiIiI6mqa52T6SP/+/dG/f3/Mnz8fWVlZ2LNnD/bu3Ytjx44hOzsbZ8+eRVlZGfR6PQwGAzQaDbRaLaKiotCyZUukpKSgU6dO6N27N/r164dWrVoF+0MKupYtW2LPnj313i8qKoLRaPR7iBFwLRjasmVLv9fhjeTkZJfGDRgwwM+VuLZHdna23+sgIiIKNaX5ZsgyABdfb2Q06qDRVECA4xc61ZWnkGH43x7l5nJUlFUgRh2DZtpmQe2y6kooVBRFzJw5EwpF4+sGSw2LK91AzbIZyzOXY0b3GQGoiIiIiIiIiIiIiIiIiMgWg6EuSk1NRWpqKq677rpgl9KotW3b1umYs2fPok2bNn6v5ezZs07HuFJvMLlan6sBUm+4socrn3MiIiJyXWWxBeYqGQo3mtDLkgKSpIBCNLs8xywAuaL1cfUyZBQZi1BqKkWCJgGxmlgIrqZTfcRiscBicd4tdfz48ejcuXMAKqKmLFefix/P/ejS2FXZq3BX2l1I1CX6uSoiIiIiIiIiIiIiIiIiWzxKngLKlcBnZmam/wtxYZ/Y2FhERUUFpBZPtWvXzqVxMTEx/i0EFz5fzpSXl/u9DiIiolBhNsqoKLZAKVgQJbr3PVYUXTt6vtpZpQBLPZlPi2xBblUuTpWfcmtNX9Dr9U7HxMfH4/777w9ANdTULc9cDrPsWqDaJJmwPHO5fwsiIiIiIiIiIiIiIiIiqgc7hlJApaWlOR2TmZmJkSNH+r2Wv//+2+F9V2oNNldrbCjB0MrKSr/XQUREFApkGSjLM0MFE6JE946FFxUmt8ZXhMejwHTe6bgoVWBfUFNUVASLxQJRdPxat6lTpyIyMtKlNU+Wn8S/t/3b4Zj3L3ofbSLauFomNRG5+lysyl7l1pzqrqFEREREREREREREREREgcZgKAVUr169nI45ePCg3+s4f/488vLyHI5xpdZg69y5M9RqNYxGY7BLISIiogDSl1oAk9ntUCgAKBSuHyEPAHkW591I1aIasRrnLxLxFbPZjLy8PERHRzsc169fP4wePdrldS2yBcXGYqdjKPQsz1wOk2Rya05119DxYeP9VBURERERERERERERERGRfTxKngKqZcuWaN68ucMxe/fu9Xsdv/32m9MxvXv39nsd3lKr1ejWrZvTccXFxX6vpaioyOmYsLAwv9dBREQUCqrKJER4EAoFAIXCvXCbwVLldEyiLhEC6jlr3g/Onz8Pi8VxQFOpVGLGjBkQhMDVRU2TJ91Cq63KXoUCQ4FvCyIiIiIiIiIiIiIiIiJygsFQCrg+ffo4vH/gwAGYTO4FFty1a9cup2P69u3r1xp8pX///k7HuBLa9JYre0RFBfaIWSIioqZKKZihhPudK0WF2e0waUp4KmLUMfXeD1eGI0IZ4XYtnqqsrERJSYnTcbfffjvatm0bgIqoqfOkW2g1k2TCqqxVvi2IiIiIiIiIiIiIiIiIyAkGQynghg8f7vB+ZWUlduzY4dcaNm3a5PB+ZGSk0wBrQ+Hs8wkA586d83sdruyRkpLi9zqIiIhCgUYwejTP3W6hAKAQFUjWJaNdRDuEK8Nt7idqEz2qxROyLCMnJ8fpuOTkZNx7770BqIiaOm+6hVbblOP47x5EREREREREREREREREvsZgKAXc5Zdf7nTMDz/84Lf9y8vLnQZPL7nkEiiVSr/V4EuXX345RNHxH2VXOqR6a+fOnU7HtG7d2u91EBERhQIVzB7N8yQYWk2j0CA1PBUpYSlQi2oAQKw6FhqFxuM13VVYWAiDweB03PTp06HVagNQETV13nQLrWaWPPvzSkREREREREREREREROQpBkMp4Hr37o2EhASHY7788ku/7b969WoYjY67bLkSXm0oEhISnHY33bdvn0shCm+40uW1V69efq2BiIgoZAgeTBEtbh8jb0+EKgLtItshUZuIZtpmXq/nKpPJhPz8fKfjkpKScPHFFwegImrqjBYj1mSvCXYZRERERERERERERERERG5jMJQCThRFXH/99Q7HHD58GPv37/fL/p9++qnD+67U19DceOONDu8bjUZs2bLFb/tXVVVh69atDseo1WoGQ4mIiFwge5/dtEsh+q5roQABcZo4KASFz9Z0Jjc3F5IkORwjiiK6desWoIqoqTtTeQYGyb8vriIiIiIiIiIiIiIiIiLyh8ZxVraPVFVVYdasWZDr+Wn7Lbfcgv79+we4KmD37t31hhU1Gg3mzJkT4Ir8b8KECXj33XcdjnnrrbewdOlSn+6bmZmJdevWORwzYsQItGjRwqf7+tttt92GJ598EhaLpd4x77zzDkaOHOmX/VesWIGioiKHY4YNGwaNJnBHzRIREdljlIw4XXHa4ZhW4a1qjkoPNLNRRul5/xw7LSoa73HW5eXlKCsrczouISEBYWFhHu+ToEnAE92ecDqGQkNKeAqiVdEoMZUEuxQiIiIiIiIiIiIiIiIit4RUMPTzzz/H66+/DkGwPXszKioKGRkZgS8KQMeOHfGf//yn3h92jxgxAqNGjQpwVf41dOhQtGvXDsePH693zMcff4znn38eLVu29Nm+8+fPd9pp6o477vDZfoGSnJyM0aNH47vvvqt3zOrVq3HmzBmffj6rLVq0yOmYa6+91uf7EhERuUuG7LQDoOyD49Y9YdRLKD1vhuz4qcoFMtw+Tl4QgvNxeUuWZeTk5Dgdp9FoEBcX59Ve0epo3NjGcSd2Ch1KUYl5/eZh+p7pXoVDI5QRKEe5DysjIiIiIiIiIiIiIiIiciykgqFLliwBAJuOoYIg4P7770dUVFQwykJ0dDQeeOABvPLKKxAEwao+QRDwzjvvNLlgqCAImDp1Kh566KF6xxgMBsycORMffvihT/Y8dOgQ3n//fYdjWrRogZtvvtkn+wXa9OnTHQZDzWYzpk2bhhUrVvh03w8++AC7d+92OEar1eKmm27y6b5ERERNSXWnUJdCoQBMUEKJ+juFNyX5+fkwmUxOxyUlJUEUxQBURKGkT3wffH/59zhefhxVliq352sVWiAXuPXNW/1QHREREREREREREREREZF9IfOT0z///BO//vorBEGwegMAnU6HadOmBbW+adOmQafTAYBVfbIs45tvvsG5c+eCWp8/3HPPPYiPj3c45uOPP3YYdnSVyWTCvffe6/CodQB45JFHoFb75ujYul9r9t5Onjzpk70A4JJLLsHgwYMdjvn88899Ggw9ffo0HnnkEafjbrnlFiQk8NhVIiKi+pTluR4KBQCDHJyj7gPNaDSioKDA6TiFQoHw8PAAVEShSCkq0TGqI3rE9nD7rWNURyhERbA/BCIiIiIiIiIiIiIiIgoxIRMMXb16dc2vqztyyrIMQRBw1VVXBT20lpCQgLFjx1rVVs1isWDVqlVBqsx/wsLC8PTTTzscI8sy7rzzTmRmZnq119SpU7Fz506HY1q2bIkHH3zQq32Cbc6cOU7HTJ48GQcOHPB6r/Lyctxwww0oLi52OE6tVmPWrFle70dERNRUGfUSzEb3jnk3y0qY0fTDZjk5OTbd/u1RKkPqIAQiIiIiIiIiIiIiIiIiIodCJhj6/fff13uvoRxx7egI8/Xr1wewksCZMmUKOnfu7HBMfn4+LrvsMvz1119ury9JEqZPn45FixY5HTt37txG32lq+PDhuP322x2OKS4uxmWXXYZffvnF431yc3Nx+eWXY8eOHU7HPvzww2jfvr3HexERETV1+jI3WoXWUi6FQ4bg42oajtLSUlRUVDgdp1Qqa04CICIiIiIiIiIiIiIiIiKiEAmGVlRUYNu2bTU/MK79g+OIiAiMGTMmWKVZ+de//oXo6GgAsKpVlmX89NNPMJvNwSzPL5RKJd59910oFI47XmVlZaF///5YtmyZS12jAODEiRMYM2YM5s+f73TsqFGjcOutt7q0bkO3YMECJCUlORxTUFCASy+9FE8++SRKS0tdXluWZXzyySfo0aOHS6HQzp074/nnn3d5fSIiolAjSzKMlZ4FQ82yAlVN9Eh5SZKQm5vrdJxCoWC3UCIiIiIiIiIiIiIiIiKiOkIiGLp9+3aYTCYAtsfIjxw5EhqNJpjl1VCr1bj88svtHidfUVGBXbt2Bas0vxo2bBieffZZp+PKyspwz/+zd9/hVZb3H8c/z5nZJEAIKwwFxQgq4kLFhYqgtlZBUeuo1r2tq7Wu1vVzj7qr0loXiEVt3ajgwAGKIJGKIrITQvY86/n9ERMTzt4Z79d15TK5n/u5729CODmYz/neZ5yh3XbbTQ899JB++uknvzmNjY1677339Pvf/1477bRTyE6xbQYNGqRnnnkmptq7osLCQs2ePTtsSMLr9er222/X8OHDdfHFF+v9999XY2Oj3zyfz6dly5bpjjvuUElJiU4++WSVl5eHrSM7O1vPP/+8MjMzY/5cAADo6XxeSdGdIt+JVd6E1dKVbNmyJaIXRfE8AwAAAAAAAAAAAAD89Yr2OqWlpUGv7bXXXimsJLw999xTL730UsBrK1as0L777pviilLjz3/+sxYvXqzXXnst7Nxly5bpwgsv1IUXXqiCggIVFRXJ6XSqurpa69evl9cbeUAiIyNDL774ogYMGBBP+V3OpEmT9MADD+j8888PO7e6uloPPvigHnzwQRmGocGDB6tv376yWq2qq6vTunXr5HK5otrfZrNpzpw52nXXXWP9FAAASAqbYVN/Z/+wc1IlwkboARmGKbsRX0f5BsNUttm1jmFvbm5WZWVl2HkFBQWyWq3y+WLruAoAAAAAAAAAAAAAPVWvCIZ+++23Qa/tscceKawkvFD1rFy5MoWVpJbFYtGcOXN05JFHav78+RHfV1VVpaqqqpj2tNvtmjt3riZNmhTT/V3deeedJ5fLpUsvvTTie0zT1IYNG7Rhw4aY93U6nXrhhRc0derUmNcAACBZrIZVhRmF6S6jnRFHJtMht+KJdJqSyq2mRnq6VjB08+bNYedYrVYVFha2nwoAAAAAAAAAAAAAAPhFrzhKPlQwdMKECSmsJLzdd9896LVQn0dP4HQ69eqrr2rGjBlJ36ugoED/+c9/NG3atKTvlU6XXHKJZs2apYyMjJTsN3DgQL399ts65phjUrIfAADdncUqxZrudBrRdfTeVqXFVLMRQcvSeNqaRqm6ulpNTU1h5xUVFclqtaagIgAAAAAAAAAAAADofnpFMLSsrEzGz+2YjA5tmRwOh/Lz89NUVWB9+vRpD/F1rNU0Ta1fvz5dZaVMVlaWZs+erdtuu00OhyMpe4wfP16fffaZDj/88KSs39WcdtppWrRokXbaaaek7vOrX/1KX3/9tQ444ICk7gMAQE9iWAw5sqJ/Sm4ovmPkvYa00RrhEezxtDWNgtfrVXl5edh5WVlZ6tOnTwoqAgAAAAAAAAAAAIDuqVcEQ+vq6gKOFxQUpLiSyGxbV1tANNjn0RNdc801Wr58eULDm/n5+brvvvv0xRdfaPTo0QlbtzvYbbfd9PXXX+uee+5J+Pf9brvtpjfeeEOvvPKKBgwYkNC1AQDoDTJzo39KbjM8MhR7J88yi09d7AR5lZeXy+v1hpxjGIYGDhyYoooAAAAAAAAAAAAAoHvqlcFQ8+fjMLtLMLRNfX19iitJrx122EFvvfWWvvjiC5188snKzs6OaZ2dd95ZDzzwgNatW6dLLrmk1x47arfbddlll2n9+vV67LHHNGHChE5daaORl5enE088UfPnz9dXX32lI444IsHVAgDQezgyLbI5ovuZ7DDcMe/nMaQtltQdDx+JpqYmVVdXh53Xt29fOZ3O5BcEAAAAAAAAAAAAAN2YLd0FpEJjY2PA8a76S2W73S7TNP1Ce72pY2hHe+yxh/71r3+ppaVFCxYs0MKFC7VixQqtXLlSW7duVX19vVwul3JycpSbm6thw4Zp55131vjx43XEEUdo5MiRaam7LYDc1WRlZenss8/W2Wefrc2bN+vtt9/W4sWLtXLlSv3www+qqalRfX29PB6PMjMzlZubq+LiYo0YMUK77babJk6cqIkTJ3bZvz8AAHRHuYU2VW10K9ImoDbFfoy8zZRGeyxa77TL622JeZ1EMU1TmzZtCjvPbrerf//+Sa1lXcM6/eGLP4Scc/eed6s4uzipdQAAAAAAAAAAAABAPHpFMNTpdKqpqan9Y8MwZJqmGhoa0lhVcI2NjQE7OXbVoGGqOJ1OHX744Qk9Xr63GzhwoE499VSdeuqp6S4FAIBezWJVxKFQSYqx6Xe7TFk0LGeEGltqJPeW+BaLU1VVlVpawgdUi4qKZLEk98ADl8+l1fWrw84BAAAAAAAAAAAAgK6sVwRDs7KyOgVD25SXl6ehmvC2bAn8y/msrKwUVwIAAND1jRkzxm9s5cqVaagkdi0NqX0BkM+eLRkWZduzJaUvGOrxeII+9+2orTM8AAAAAAAAAAAAACC8XhEMLSgo0NatWyWp0xHttbW1qq6uVn5+fhqr66y6ulrV1dXtXU07dg7NyclJY2UAAKRWZWWl1qxZo40bN6qyslItLS3yer3Kzs5Wbm6ucnNzNWDAAI0ePVoZGRnpLheIS0ujN6X7+Zxd43llWVmZfD5fyDmGYWjgwIEpqggAAAAAAAAAAAAAur9eEQwdPny4Vq1aFfB49sWLF+vQQw9NQ1WBLVmyxG+sLSA6dOjQNFQEAEBqNDc3a+HChZo/f74WL16sDRs2RHSf1WrVyJEjtdNOO2m//fbTIYccory8vCRXCySOzyu5m1PXMdQ0DPmc2SnbL5iGhgbV1taGnde/f3/Z7fYUVAQAAAAAAAAAAAAAPUOvCYYGs2DBgi4VDF2wYEHQayNHjkxhJQAApEZlZaWefvppzZ49WzU1NVHf7/V69f333+v777/Xa6+9JrvdrokTJ+qYY47REUccIYvFkoSqgcRxNfmkFJ4kb9ozZRrW1G0YqAbT1ObNm8POczgc6tevXwoqAgAAAAAAAAAAAICeo1ckJXbddVe/sbaj2ufMmZOGioKbPXt2wM6mkrTTTjuluBoAAJLH5/Np1qxZOvzww/XEE0/EFAoNxO12a+HChbr88st15JFH6tVXX5XXm9pjuoFotDSEPko90bxd4Bj5rVu3yuVyhZ03cODAoM+NAQAAAAAAAAAAAACB9YqOoXvvvXenj9uOZpekVatW6YMPPtBBBx2Uhso6e//99/Xdd9+1h1a3tc8++6ShKgAAEm/r1q264oortGjRorBzMzMzNWjQIOXn5ysjI0Nut1uNjY3atGmTKisrQ977448/6qqrrlJVVZVOO+20RJUPJIzpM1s7hqZqP0k+R27K9gvE5XKpoqIi7Ly8vDxlZ6f/yHsAAAAAAAAAAAAA6G56RTB0/Pjxys3NVX19fcDQ5U033dQlgqF/+ctfOn3csTuSzWYjGAoA6BHWr1+vM888Uz/99FPA6zabTQceeKAmT56s3XffXcOHDw/aMbC+vl5Lly7V559/rnfeeUc//vhjwHkejydh9aN7c/vc2ti0MeScwZmDZbfYU1KPq9lM/THylvQeI7958+aAL4LqyGKxqKioKEUV/aLAUaCzRp8Vdg4AAAAAAAAAAAAAdGW9Ihhqs9l01FFH6fnnn28PlrR1DTVNUwsXLtQzzzyjU045JW01PvPMM1qwYIFfcLWtzoMPPli5uent7gQAQLwqKip02mmnacOGDX7XLBaLZsyYofPOO08DBw6MaL2cnBztv//+2n///XX55Zdr6dKleuaZZ/TGG2/I50vt8dzoHnzyqdHTGHZOqrhT2C1USv8x8nV1dWpoaAg7r7CwUDZb6v+p0tfZV+fseE7K9wUAAAAAAAAAAACARLKku4BUmTFjRsDxtiDmhRdeqG+//TbFVbUqLS3VBRdcELQbmiTNnDkzhRUBQPfh9Xnl9XnTXQYi4Ha7df755wcMhRYVFemZZ57RTTfdFHEoNJDddttNd999t1599VUdeOCB8ZQLpIS7OYXtQiX5nOl7oZHP59PmzZvDzsvIyFBBAV05AQAAAAAAAAAAACBWvSYYevTRR6u4uFiSOnUNbfu4rq5O06ZNC3oEbbKsXr1aU6dOVX19vV9Nbfr27asTTjghpXUBQHfx37X/1etrX093GYjA3/72Ny1btsxvfOjQoXruuec0YcKEhO01atQoPfbYY7rzzjuVl5eXsHWBRAtzonpi97I6ZFrSd2BARUWFPB5P2HkDBw4M+YIpAAAAAAAAAAAAAEBovSYYarVadfHFF3c6pl3qHMT86aeftP/++2vRokUpqemTTz7RpEmTtG7dOr8j5NtqMwxD559/vjIzM1NSEwB0Jx6fRw+veFgPrXiIrqFd3OrVq/Xkk0/6jWdnZ+uxxx7TkCFDkrLv0Ucfrblz52qHHXZIyvpAV2HYwh9J73NkpaCSwFpaWlRZWRl2Xn5+Ps97uxIz/PdVxuYVEc0DAAAAAAAAAAAAkDrpaxmUBhdeeKH+9re/ae3atZ2CmG0BTMMwtGnTJh100EG6+uqrde2118rpdCa8jpaWFt18882644475Ha7/Toidfx4wIAB+sMf/pDwGgCgJ3h97etaU7em/f2jRxyd3oIQ1P333x+wU+CVV16p7bffPql7FxcXt3cNT6SqqiqVlpZq3bp1qqurk8fjUXZ2tkaPHq2JEydGtVZdXZ1KS0u1fv16VVdXy+12q0+fPurbt6+GDBmikpISWSzJfz1PU1OTvv32W61du1aVlZVqaWlRbm6u+vfvr6KiIo0bN042W3KfPn733Xf63//+p/LycrndbmVlZWnw4MEaM2aMhg4dmtS9uzOr3SePJ/T3iM+enaJq/G3atMnvRVDbslqtGjBgQIoqQjiOilUa+O7NYecN+PBe9VkxT2UHXyVX/9EpqAwAAAAAAAAAAABAOL0qGOp0OnX33Xdr+vTpfmHMjuFQt9utW265RbNmzdJVV12l008/XTk5OXHvX19fr6efflp33nmnNmzY0L5n2/6B6rnjjjs4AhcAAmjrFtrmoRUPadqwabJarGmsCoFs3LhR77zzjt/46NGjdfzxx6ehouDGjBnjN7Zy5cr2991ut1555RXNmTNHy5cvl8/n3yVvzz33jCgYWldXp7lz5+r111/XN998E3CtNn379tWkSZP029/+VuPGjYvws4lMS0uLXn31Vb322mv68ssvQx71nZubq3333VfHH3+89ttvv4TVUF9fr3/+85+aM2eONm3aFHTe6NGjdeKJJ2r69OlyOBwx7fXj6h/1m6N+02nMMAw9+vKjGjA4/lDi/PnzdcEFF3Qay8nJ1bP/+q+czoy41w/GIpfCPbXf5KpQX8cAOSyxfe1iVVNTo6amprDzBgwYIKuVx/BkCRfMlSTf6o0yivopa+OXGvTWDbJ4miNa21n5o4a+cpk2TblJTUMnxFsqAAAAAAAAAAAAgDj1mqPk2xx77LE69dRTO4Uy23Q8Vt40Ta1fv16XXHKJBg4cqJkzZ2rWrFlas2ZNVPutWbNGs2bN0syZMzVw4EBdeumlWr9+fdBQaNvehmFo+vTpOuWUU+L7hAGgh+rYLVSS1tSt0etrX09fQQjqpZdeChh6POOMM1LSBTNRvvnmGx1zzDH685//rK+//jpkkDMUj8ejJ598UgcffLBuv/12LVu2LOxalZWVeuWVV3T88cfriiuuUFlZWUx7d2SapubOnavJkyfruuuu0+effx4yFCq1hlnfeustnXnmmTr77LO1evXquOtYsGCBjjjiCD3wwAMhQ6GStGrVKv3lL3/Rb37zG3377bcx7Tdyu5EaO2FspzHTNPX2K2/HtN62XnzxRb+xyZOnJTcUavPJiOAo70ZPo1bXrdbmps3ypejob6/XG9H3a2ZmpvLz85NfUC/lW1cuz99fCzvP8/y7stx5nwa9eX3EodA2Fk+zBr11gxwVq2ItEwAAAAAAAAAAAECC9KqOoW0efvhhLVmyRKWlpZ2OlJc6dw5t+7ixsVFz5szRnDlzJLV2y9pxxx01ePBgFRYWKjMzUw6HQy6XS01NTdqyZYs2bNig7777TnV1dZ3WljofFb9tKLTNjjvuqCeffDI5XwAA6Oa27Rbahq6hXdO7777rN5aVlaUpU6akoZrYLFy4UBdffLGam6MLSm2rvLxcl1xyib766quY7jdNU//5z3+0ZMkS/f3vf9f2228f0zr19fW6+uqrNX/+/Jjul1q/JkuXLtXDDz+sPfbYI6Y1nnnmGd16660RdTLs6IcfftDJJ5+sRx99VHvttVdU91oNq6afMF3fLPmm0/gH//lA511wnmw2m6xGbI8hmzZt0kcffeQ3PnXqMTGtFymrwytFmPM0ZarR2+j3Aqlk2bJli7xeb8g5hmFo0KBBKamnN/J++5PcT7wqudwRzDY1xPmhLN6WmPayeJpV9P4dWjf9McnoPsF/AAAAAAAAAAAAoKfplcHQrKwsvfXWW9pvv/20du3agOFQSX4B0Ta1tbX64osvQv5CPVDAIVggtOM10zQ1YsQIvf322wk5vh4AeqJtu4W2aesaevSIo1NfFAIqKyvTd9995ze+zz77KCsrKw0VRe/bb7/VJZdc4hcKzcrK0pAhQ1RQUKD6+nqVl5eroqIi6DobN27UaaedpnXr1gWdU1hYqMLCQuXl5am2tlYbNmxQTU2N37xNmzbppJNO0j//+U/tuOOOUX0+NTU1OvPMM/XNN98EnZOfn69BgwapT58+amho0KZNmwJ+brW1tTrzzDP1yCOPaN99942qjnnz5umWW24Jej07O7v961tZWakNGzaosbGx/XpjY6Muuuii9hfuRMpm2HTc1OP00J0PacuWLe3jWyu26ttPv9Vhhx0W1Xodvfzyy37dX0tKdtWI4bEFeCNlNVoUTbS2KKNIhpIfDG1qalJVVVXYeQUFBXI6nUmvpzfyrSuPIhQq5eRUKCOzLvzEEJyVPypzw1ccKQ8AAAAAAAAAAACkUa8MhkrS4MGDNX/+fE2ZMkU//PBDwABooIBox2vhulsFCo6GCoyapqntt99eb731loYOHRrdJwQAvUSwbqFt6BratSxbtizgeLRdHtPpqquuUlNTU/vHkydP1imnnKIJEybIbrd3mvu///0vYODS5XLpwgsvDBgKLSws1CmnnKLDDz9cI0aM6HTN5/Np2bJleuqpp/T2252POq+pqdHll1+uuXPnKiMjsmPKTdPUVVddFbDG3NxcnXjiiTryyCO1ww47+D2PWblypZ599lm9/PLLnTpAtrS06Morr9Srr76qfv36RVTH2rVrddNNNwW8tuuuu+qcc87RpEmTOn19XS6XPvzwQz366KNavny5pNavwZ/+9KeI9uzIbrdr+vTpeuSRRzqNz549O+ZgqNfr1bx58/zGp037TUzrRcqw+mT4vPIpsu6MObYcZduyk1qT1Pq9tnnz5rDzbDabCgsLk15Pb2T6TLmfeTPiUKgk9e27NiF791nxKsFQAAAAAAAAAAAAII16bTBUkrbbbjt9+umnOuaYY/Txxx+3B0C3DW8G6u4Z6fGbkYZHTdPUAQccoJdffll9+/aN4rMAgPBW1awKeX1g5kDlOnKjXnd17Wp5zeBHBBdmFCrfmR/1uj/V/SSXzxXw2vsb3g/YLbRNqK6h6+vXq9HT6HessdVqlWEYynPkqSizKOp6NzVsUr2nPuj1HFuOBmVHf0xyWVOZal21Gt1ndNT3dhXffvttwPExY8akuJLYrVrV+vcnIyND99xzjw455JCgc3fccceAHTxvv/12lZaW+o0fc8wxuuGGG5SZmRlwPYvFot12200PPPCA3n33XV1xxRWdOpf+8MMPuuuuu/TnP/85os/lqaee0oIFC/zGJ02apDvuuEMFBQVB7x0zZoz++te/6je/+Y3OP/98VVdXt1/bunWr/vznP/sFLYO5/vrrO4Vt25x//vm68MILZbH4hxwdDocmT56sgw46SPfff78ef/xxSdLixYsj2nNbxx9/vB5//PFOjwcff/yxNmzYoCFDhkS93pIlS1ReXt5pLC8vTwdMmhz1Wj6ZskTY0dPm9EmmIu7/GctjXCyqqqr8uuwGUlRUFPDPG/Hz/e8nmRuDdzHelmF4lJtXHn5iBLLXfirD3STTHvixDQAAAAAAAAAAAEBy9epgqCT169dPH3zwgW6++Wbdcsst8ng8IY98DzYWjW3Xdzgcuu6663TNNdfIaqXDHYDEO/qN0Eer37fvfTpi2BFRr3vy/JNV1RL8mODrJlynk0efHPW6F3x4gb6v/T7q+9oE6xr6x8/+qC+2fBH0vpNGnaTr97g+6v1uX3q73lr3VtDrU4qn6P797o963cdWPKbnvn9OK2eujPreriLYsekjR45McSXxsVgsevTRR7XPPvtEfe+SJUv03HPP+Y2feeaZuvLKKyNe59BDD9WDDz6os88+u9NzkRdffFFnn322BgwYEPL+9evX67777vMbnzp1qu65556IX/Sy++67a9asWTrhhBPU0tLSPv7+++/rm2++0dixY0PeP3/+fH366ad+42eccYYuvvjisPtbrVZdfvnlam5u1j//+c+Iag5k0KBBOvDAA/Xee++1j/l8Pr300ku65JJLol5v246ukvSrX/1aDkf0R6S39v+M7DmhxWhR6zny4f/8+jj6yGFxRF1PtDwej7Zs2RJ2XnZ2tvLy8pJeT2/l/fDrqOY7HE0yjPj+ndPG8Hllqy+Xu2B4QtYDAAAAAAAAAAAAEB3a86g1YHDDDTfoiy++0GGHHdbpmPi27qCRhiWC2Xadtj2OPPJIffnll7r22msJhQJAgrR1DUX6lZWV+Y1ZLBb1798/DdXE7pRTTokpFCpJf//73/3G9t13X11xxRVRrzVp0iSdcsopncbcbreef/75sPfOmjVLbnfnI6VHjx6t22+/PernOWPGjNHll1/uNx5JUPOFF17wGxs1alTA9UK58sor4w4Yn3jiiX5jc+fO9esqHE5FRYW++uorv/HjjpsRU11e+SKaZ1h9svg8Ea+b7wjeETaRysrK5POF/hwMw9DAgQNTUk+v5HLL982PUd1isUT3fR92Pbd/V2AAAAAAAAAAAAAAqUEwtINdd91Vb731lt577z39+te/ltVqDRoSjfZN+iUMarPZNGPGDH388cd67bXXVFJSks5PGwB6pIdWPCSvL7EhF0SvtrbWbywvL69bvRjC4XDo3HPPjene1atX64MPPug0ZrVadc0118T8opOzzjpLdru909jcuXND3lNdXa2XX37Zb/yqq66S0xl9R0tJmjlzpvr169dp7I033lBjY2PQezZs2KCPP/7Yb/zKK6+UzRZdI3u73R5Vx9VA9t9/fw0bNqzTWHl5ud+fWTjvvvuuXxBy/PjdlZs7OOqaTJlShF0brY7IAqTt843kP/VvaGgI+Pd+W/369ZPDkfzupdHa0LhBZ39ydsi3DY0b0l1mWEZtnRQmnLstny+xj8s+jpEHAAAAAAAAAAAA0qbXHyUfyEEHHaSDDjpImzZt0ty5c/Xaa69p4cKFnY5L7Sjc0fOSlJGRoYMPPlhHHXWUpk+frsLCwqTUDgBo1dY19OgRR6e7lF6tubnZbyzWIGKbww8/XGvXro36vgsuuEAXXXRR1PdNnjxZBQWxdVp8/fXX/Z4b7L333tphhx1iWk+SCgsLte+++2rBggXtY+Xl5Vq3bp2Ki4sD3vP+++/7BTaHDx+uSZMmxVyH0+nUlClT9Nxzz7WPud1uLVu2LGh31Y8++sgvQFlUVBRzHQceeKAKCwsjOrY8EMMwdMIJJ+jOO+/sND579mxNnjw5ojW8Xq/mz5/vN37Yob+Wxx1dME+SPPIpr49Drurwc60WlyJsLpoSpmlq8+bNYefZ7fYu2zW42dusLyu/DDunqzNc7vCTtuFyZco0jYQcJ29arPLkDIh7HQAAAAAAAAAAAACxIRgawqBBg3ThhRfqwgsvlNvt1vLly/Xll19q1apVWrdunTZu3Ki6ujo1NTWppaVFTqdTGRkZysvL05AhQ1RcXKwdd9xR48eP19ixY6PuhAUAiM9DKx7StGHTZLV0n+6UPU20R3J3RXvvvXfM9y5evNhv7PDDD4+nHEnShAkTOgVDJemrr74KGgxNZh0dg6FtdQQLhi5btsxv7LDDDpPFElsnS6vVqsMOO8yvhmgce+yxuv/+++VyudrHPvzwQ23cuFGDB4fv+Pnll1+qoqKi01hubh/tv/8hMdVj2ExlZ9vlqg4d7DMMnyy+6MN/ybR169ZOX8dgBg4cGHPHXETGdNjDT9r2HtOmutoByutTFvf+DcP2kUnHUAAAAAAAAAAAACBtSCpGyG63a/fdd9fuu++e7lIAABGia2j6BeoOWl9fn4ZKYrfzzjvHdJ/b7dbXX3/tNz527Nh4S9KQIUP8xv73v/8FnR8oGJqOOgIFQ8eNGxdXDfHeX1BQoCOOOEKvvvpq+5jP59NLL72kiy++OOz9b7/9tt/YoZOnyuGIvjOuKVNemVKQDvQdWR3xd3VMJLfb7ReQDSQ3N1c5OTkpqKh3M/NyJYsl6uPkKyuHJSQYWrPzr+JeAwAAAAAAAAAAAEDsCIYCAHo0uoamV0ZGht9YY2OjfD5fzF0iU62oqCim+9atW6empia/8draWi1dujSumrZu3eo3VlNTE3Cuy+XSTz/95Dfe3Nwcdx2bNm2KuA5J2rBhg9/YmDFj4qoh3vslaebMmZ2CoZI0d+5cXXDBBbJagz92VFRU6Msv/Y8dnzr1NzHV4ZFPHo9X7vpmhXuabrF0rW6hmzdvlhkm0GqxWGL++4QoOeyyjB0p37Iforqtvr6/mptylZFZF/PWLX1HqmnI+JjvBwAAAAAAAAAAABA/gqEAgB6NrqHp1b9/f78x0zRVV1enPn36xLTm/fffr5aWlpBzLrroIm3ZsiWm9beVm5sb033V1dUBx88444w4qgkuWCCzqqoq4PjVV1+d0jo8Ho8aGxv9xvv27RvXfvHeL0m77767dtxxx07dTsvKyrRgwQIdckjwI+Hnz58v3zYdGceO3U3Dho2MqQ6vWtcyG1sUNhjqc0tdJFtdV1cXUSfg/v37y26P/ohzxMY6adeog6GSofXrd9HI7T6V1eqNek+fLUNlB18lGV3kmxMAAAAAAAAAAADopQiGAkAv8NrU10JeH5g5MKZ1n538rLxm8OBIYUZhTOs+NOkhuXwueX1eXfDRBdrQ4N9lMKr1fu4aetvet6nR0yivt3PNVqtVhmEoz5EX0/rX7HaNLhx7YdDrObbYjk0+Z+dzdOLoE2O6t6sYNGhQwPFNmzbFHAzdaaedws5JZPgsMzMzpvtCdc5Mhrq6wB3+ukodwcbjPVY81uDutk488UTdeOONncZefPHFoMFQn8+nd99912982tRjY9q/9Rh5rwxJNl/0gbx08fl8KisLf/S40+lMSIgXkbPsOFzG4P4yN1ZEdV9zcx+t/WmChg1fElU41GfL0KYpN8nVf3S0pQIAAAAAAAAAAABIMIKhANALjO6TnJDGdnnbJWXd4bnDJUmvrnk17lCo1LlrqGma8ng8na7bbDYZhhHz+oOyA4cf41WUWaSizO597PL2228fcHzZsmUJOQK8KwsWhEyWbQPPXa0Ol8sVcDzeEK/D4Yjr/jZHH3207rzzTjU0NLSPffTRR9q0aVPAgPOXX36piorOgbvc3Dztv3/wDqOhtHULzTS8iuPhKOUqKirkdoc/1n7gwIFxPc4ieobFkP2UI+S690XJFf7PqKOGhv76cd3+Kh63Ws66dWHnt/QdqbKDryIUCgAAAAAAAAAAAHQRBEMBAF2Sx+fRwyseTth6bV1DLRxvm1I777xzwPHly5fr+OOPT3E1qWW1WtNdgqSuU0ewzqANDQ0xd4+VFNER5h25fW6VN5f7XzCkydMm69U5r7YPeb1evfTSS7rooov8pr/99tt+Y5MnT405qOr5ORiaZXSfbqEtLS2qrKwMOy8/P19ZWVkpqCh+efY8zRg+I+yc7sJSPED2s38l9+OvRhcOddjlPe1UrduxWJkbvlKfFa8qe+2nMjp0szUtVjUM20c1O/9KTUPGc3x8CD6fL+ycr7/+WiNHjpTFwtcRAAAAAAAAAAAA8SMYCgDokl5f+7rW1K1J2HptXUOPGn5UwtZEeDvvvLOysrLU2NjYaXzx4sVpqih1ggUhly5dqoyMjLTX8d///jdoR9dkyM7Ols1m8+vYW1dXl9JgqE8+1bprA1475DeHdAqGStLLL7+s888/v9NYZWWllixZ4nf/1CN+HVUtbUx17Bjqk0/dIxi2efNmmaYZco7VatWAAQNSVFH8CjMKdfW4q9NdRkJZxwyXcdkJcj/zZkTHyhuD+8t+yhGyFLf+uTUNnaCmoRNkuJtkqy+Xxd0knz1TnpwBMu2ZyS6/21u5cqX+9Kc/hZ136623avbs2brxxht7fEdtAAAAAAAAAAAAJF/3+K0zAKBXSXS30DYPrXhIXl/36cbXEzgcDu23335+4z/++KO+/PLLNFSUOgMHDgw4Xl1d3SvrkFo7R27rp59+imvNH3/8Ma77Oxq+/XDttOtOncY2bdqkhQsXdhp79913/ToAlpSUaNiwETHt65VXkqlMwyeLQgct26yz+tScxpPZa2pq/ALfgRQWFnaZrrW9maV4gBzXnCL7BcfJssv20rZdKS0WWXbZXvYLjpPjmlPaQ6EdmfZMuQuGq2XAGLkLhhMKjcCnn36qs846S2vXro1o/vfff6+zzjpLn332WZIrAwAAAAAAAAAAQE9Hx1AAQJeztGKp+jj6aNd+uyZ+7a1LtWtB4tdFcEcddZTeeecdv/Hnn39eu+++exoqSo0RI0YE7JC5cePGoGHNZMjJydHAgQO1efNmvzomTJiQsjokaccdd1RFReeOhStXrgwYHo7UypUr4y2rkyOOO0Lffv1tp7HZs2dr3333ldR6JPS7777rd9+UKVOUkWFVS0v0e3rau4VGHlyvt0grrV719xoa6LPIElmeNCF8Pp/Ky8vDzsvMzFRBQUEKKkIkDIsh607DZd1puMwWt8yqWqnZJWU4ZBTkyXDa011ij7Jy5UpdeeWVampqiuq+pqYmXXHFFXriiSfoHAoAAAAAAAAAAICYEQwFAHQ5ewzYQy8e9mJS1jZN0y+oh+SaPHmyBgwY4Bcke/PNN3Xeeedpu+22S1NlyeV0OrXTTjtp+fLlncY/++yzlAdid9ttN7355pt+dRx99NEprWPXXXfVxx9/3Gnsk08+0ZlnnhnzmosWLYq3rE4mHjJRs+6bparKqvaxhQsXqqysTJL01VdfacuWLZ3uyc3N1cSJE5WdbVdLS7SPL2b7MfJZUQRDW++UtlhNVVq8GuIxlBXlzrEqLy+P6HE0lQHo3sT0hU8Bb17VooLBdhmWwG1lDaddxsB+iS4NP/P5fLrxxhujDoW2aWpq0o033qjnnntOlm27uwIAAAAAAAAAAAAR4LdMAAAgqWw2m8455xy/cbfbrauuukputzsNVaXGQQcd5DcWqHtqOupYsGCBXC5XSusYP36839inn37q10U0UmVlZfr000/jLasTu92uY449ptOY1+vVv//9b0nS22+/7XfPwQcfLLvdLmeGVXZHx2PTw5/17pUpyZRTPlkjPEbebw1D2pKilqHNzc2qqqoKO69v377KyMhIQUW9y5Y1Lr31t/B/XxY8XanZ123SljWp/TuOVp9//rm+//77uNb4/vvv9fnnnyeoIgAAAAAAAAAAAPQ2BEMBAEDSHX/88dp+++39xr/55hvdd999qS8oRY4++mi/bm+lpaV67733UlrHoYceqqyszv0kt2zZohdfTE5n3mAmTpyowsLCTmNer1dPPfVUTOs99dRT8vl8iSitk+nHT/f7c/v3v/+tiooKLVmyxG/+4Ycf3v5+YWGG2gKh1gieard3C7VE1y10W/184UOoibBp06awc2w2m9+fM+K37psmzbtls2o2R9aVtnKdW/Nu2az138TWtRKxmzNnTkLWeemllxKyDgAAAAAAAAAAAHqfXnOU/Nq1a9NdQtyGDRuW7hIAAIiJ3W7X7bffrhNPPNHvCOonn3xSDodDF198sQwjNeG2VBk2bJgmT57s1yX05ptv1rhx41IWnsvJydGMGTP0j3/8o9P4gw8+qH333TdgaDcZbDabjj32WD322GOdxp955hn95je/0ejRoyNe63//+5+effbZRJcoSRo6dKj2339/LVy4sH1s8+bNuvfee+X1dg5w7rzzzhoyZEj7xw6HVXaHRW6XV1ZZ5FXowGesx8h35DClvj5Dye4NWVVVpebm5rDzioqKOP46wbascenN+7fI0xJdZ1hPi6k37t+iY64dqMIRjiRVh46ampr00UcfJWStDz/8UE1NTcrMzEzIegAAAAAAAAAAAOg9ek0wdMSIEd06bGIYhl+QBgCA7mTcuHG65pprdPPNN/tde+SRR/TNN9/ohhtu0NChQ+Pap7y8XE1NXadD3h/+8Ae/Y9s3btyoc845R4888oiKioriWr+0tFTr16/v1LUykPPOO0+vvPKKqqur28dqa2t19tln6/HHH487HLpmzRotXbpUxxxzTMh5J554op555hk1Nja2j7ndbp1zzjl6/vnnI/p6tH39YnluZJFFefa8sHNOPPHETsFQqfVrva0pU6Z0+tjjMeV2eSUZskZwlLxkKtsu2XyxHwU/xGuREdFesfN4PCovLw87Lzs7W3l5ob++iI7pM/XeExVRh0LbeFpa7z/+r4NkWLrvv4e6i02bNvkFyGPl9Xq1efNmjRw5MiHrAQAAAAAAAAAAoPfoVa18TNPs1m8AAHR3v/3tb3XOOecEvPbhhx/qyCOP1A033BAwgBfOihUrdPPNN+uwww5TVVVVvKUmzIgRI3TFFVf4jZeWlurXv/61/v3vf8vtdke1ZnV1tebNm6ff/va3OvbYY/Xxxx+HvSc/Pz9gKHfDhg2aPn26/vGPf0QdqG1oaNCbb76pc889V1OnTtV//vOfsPcMHDhQl156qd/4xo0bdcIJJ+jDDz8Mef8HH3ygmTNnavPmzZIUdSc9u8WuIVlDQr7ZLXYdeOCBGjx4cMi18vLytM8++3Qaa2ho/bO0ySJFENbs1z9T/XNif0qe7TPUx2fItDljXiMS5eXl8vl8IecYhqGBAwcmtY7eaMsPblWui+4xYluV69xaXxq+2yvi1zH0nggNDQ0JXQ8AAAAAAAAAAAC9Q6/pGCqp23YMJRQKAOhJLrvsMuXm5uruu+/2+xnX0tKiF198US+++KIGDx6sCRMmaMyYMRo8eLDy8/PldDrldrvV2Nio+vp6rV27VqtXr9ZXX32ljRs3hty3T58+yfy0Qjr11FO1atUqzZkzp9N4dXW1/vjHP+ree+/V1KlTNWHCBO24447q06ePcnNz1dzcrPr6elVVVWnVqlX67rvvtHTpUn355ZcxdaQ79NBDdckll+j+++/vNN7U1KTbbrtNDz/8sKZNm6YJEyaopKREBQUFys3NlcvlUn19vWpqavTDDz/ou+++0/Lly/XZZ5916oQaqd/+9rd66623tGTJkk7jmzdv1llnnaWxY8dqypQpGjFihPLz81VVVaUff/xRb731ll9o+LLLLtOtt94adQ3hWCwWHX/88brvvvuCzjn44INlt9s7jTXUtwb4rLJGtE+G0ypVxB7YG+pt7RXqdWRJii88GExzU5NqamrCzuvXr58cDo4rT7Q1nyYm0Llifp2Kx3IkebJlZWUldL3s7OyErgcAAAAAAAAAAIDeoVcFQ6XuF7LsrmFWAABC+f3vf6+SkhJdffXV2rJlS8A5Gzdu1MaNG/Xaa6/FtdeQIUN05ZVX6ogjjohrnXjddNNNstlsev755/2ulZeX6x//+If+8Y9/JL2O8847T4ZhBAw81tTU6Pnnnw9YYyJZLBY9+OCDOvHEE/XTTz/5Xf/mm2/0zTffhF1n2rRpOuWUU5ISDJWk6dOn66GHHgra0fWwww7r9LHH45Or/Rh5i0yFf95pejySJ/qQr8OUMn2GsszW54o+e5ak8OHNWFRUVISdY7fb1b9//6Ts35tZZKj8f4kJ/P60tEnuFp/szl51aETKDRo0SFarNSHHyVutVrrwAgAAAAAAAAAAICb8VhAAAKTFvvvuqzfeeENnnnmmnM7EH4M9cuRI3XjjjXrzzTfTHgqVWsOQN9xwg2655ZaEd4Cz2aJ7rc+5556rRx99NOFBvmjq6Nu3r5577jntuuuuMe115JFH6vbbb0/qi2j69+/vF/5sM3bsWA0ZMqTTWGOjR5JklSWCQ+R/1hx9x1VJGumxaIi39am8z54hWZL3eq9IusIOHDiQFzQlgVN2mb7ErOXzSvUV8YcVEVpmZqb233//hKw1adIkZWbS5RUAAAAAAAAAAADR63XBUMMwUvoWb20AAPRkOTk5uvLKK/XBBx/o8ssv1+jRo+Nar3///jr++OP1j3/8Q2+88YZmzpzpd9R3uh133HF66623dPLJJ8d15HBGRoaOOOIIPfLII/rjH/8Y9f0HHXSQ3nzzTZ177rnq06dPzHXY7XYdcMABuueee/yOqA+nX79+evbZZ3XZZZcpJycnonsKCwt1yy236O67707JseUzZ84MOH744Yf7jTX9HAy1RfMUO8ZgqEWS7eeGpD5HZF+7ZMnNzY34zw/RiSJiHBFXc4JSpghpxowZCVln+vTpCVkHAAAAAAAAAAAAvU+vO0o+1QKFO4MdZ982TiAUANDbFBQU6Oyzz9bZZ5+ttWvX6osvvtA333yjH3/8UZs2bVJVVZWam5vl8Xhkt9uVmZmp/v37a8CAAdpuu+20ww47aPfdd9eoUaPiqmPlypUJ+oxC69+/v6677jpdeumlmj9/vhYuXKhly5Zpw4YNAZ8nGIahQYMGabvtttPYsWO1zz77aPfdd487GJmTk6NLL71U5557rj744AN98MEH+vrrr/XTTz/J5wscIGv7mpeUlGifffbRHnvsEVfA1Waz6ZxzztHJJ5+s//73v/roo4+0cuVKbdmyRW63W1lZWRo0aJB22mknHXjggTr00EP9Pu9k/rnV1Pgfz56Xl6d99tnHb9zjMWWxtB4jHynT7VW82T+vM1dKU97PMAwVFRWlZ/Mk2Ny0WfeW3htyzmUll2lgZmqO9/Yp8L8bYuXI6HWvC0yLvfbaS6NGjdL3338f8xqjRo3SXnvtlcCqAAAAAAAAAAAA0Jv0mmDosGHDUhq4rK2tVU1NjV+oomMnUNM0ZRhG+3/z8/OVl5eXshoBAOiKhg0bpmHDhum4445LdylJl5ubq2OOOUbHHHOMpNYjuzdv3qyGhgZ5PB5lZWUpOztbBQUFcjqdSaujrfvoEUccIUlyu90qKytTfX293G63MjIylJ2drfz8/LhCoKHk5OTohBNO0AknnJCU9WM1Z84cv7GDDz44aCfa1mPkU/ec02dzyrTaJZ8nZXt2VFhY2OW68sajwdOg+Zvmh5xz9g5np6gaqUVuGRYl5Dh5i1XK6W+NfyGEZbFYdOONN+qss85SU1NT1PdnZmbqxhtvlMVCkBcAAAAAAAAAAACx6TXB0DVr1qR8T9M0VV1drdWrV+vjjz/WRx99pHfffVfV1dWdAqIdw6H33Xeffv3rX6e8VgAAkH4Oh0PDhg1Ldxmy2+0aOnRoustIuw0bNuijjz7qNGYYRsBj5NtEdYx8Avic6TvC3eFwqG/fvmnbvzfwydSAHe0q+9Yd91rDd8uU3UnQMFXGjBmju+66S1dccUVU4dDMzEzdddddGjNmTBKrAwAAAAAAAAAAQE/HbwaTyDAMFRQUaMKECbr44os1e/ZsrV+/Xvfff7+22267TkfFGoahyspKHXvssbr66qvTWDUAAAAkafbs2X7d38eNG6fBgwcHvSeaY+QTwetIXzB00KBBKe3I31uN2CcjIevsPDk3IesgcnvvvbeeeOIJjRo1KqL5o0aN0hNPPKG99947yZUBAAAAAAAAAACgpyMYmmJZWVm66KKLtHLlSv3xj3/0+2W6aZq666679Lvf/c4viAAAAIDUqK+v1wsvvOA3Pm3atKD3tB4in8Jj5K0OmTZnyvbrqE+fPsrKykrL3r1N4fZ29S22x7VG32K7hpYkJmCK6IwZM0bPPfec/va3v+mAAw6Q1WrtdN1qteqggw7S3/72Nz333HN0CgUAAAAAAAAAAEBC9Jqj5Lsaq9WqW265RYceeqhmzpypioqK9pCoaZr65z//KZvNpieeeCLNlQIAAPQ+Tz75pGpqajqNFRYWao899gh6j83oHcfIWywWDRgwIC1790aGxdAhZ/XXvFs2y9Nihr9hGzZn6/2Ghe6u6WKxWLTPPvto/PjxWrdunbZs2aKmpiZlZmZqp512Un5+frpLBAAAAAAAAAAAQA9Dx9A0O/jgg/Xuu++qT58+7WOGYcg0TT311FO6++6701gdAABA7/PJJ5/o73//u9/49OnT/br9dRTLMfIei08bsurlskTfKT5dwdABAwbIZuP1ZalUOMKhqZcUyuaMLtxpcxqaekmhCkc4klQZopWRkaHi4mLtsMMOKi4uVmZmZrpLAgAAAAAAAAAAQA/Eb3S7gHHjxulf//qXjjrqqPauoW3h0D/96U+aMmWKxo4dm+YqAQAAepa1a9eqsrJSktTS0qINGzboww8/1JtvvinT7NyZcdiwYZo8eXLI9WI5Rr7K0aw6u0v1NpcKXBnq15IpRdAU0rTY5LOl/mjwjIwMFRQUpHxfSEPHZuqYawfqvScqVLnOHXZ+32K7DjmrP6FQAAAAAAAAAAAAoBciGNpFTJs2TaeccoqeeeaZTuFQt9uts846S4sWLUpzhQAAAN2fx/SoorlCknT3g3frrdfeCnuPYRi67rrrQnYLjVW93SVJMg2p0tmsGkeL+jfnSE15Ie/zObISXkskBg0alJZ9UyXblq3Jg0IHgLNt2Smqxl/hCIeO/+sgrS9t1or5dfppaZN83l+uW6zS8N0ytfPkXA0tyeD4eAAAAAAAAAAAAKCXIhjahfz1r3/V888/L6/X22n8888/1xtvvKGpU6emqTIAAICewWt6VeWqkiS5fK6I7jnvvPO01157afXq1cksTZLkNUxVOFpU0BR6ns+eHcPB9fEpKChQRkbqu5Sm0sDMgfq/Cf+X7jJCMiyGisdmqnhsptwtPtVXeOVq9smRYVFOf6vszlR/ZwAAAAAAAAAAAADoavitYRcybNgwHXXUUX5Hl0rS3XffnYaKAAAAei+73a7LLrtMF198cbpL8WPanAlaKIJz6yVZrVYVFhYmZk8kjN1pUcEQu4q2d6pgiJ1QKAAAAAAAAAAAAABJdAztco477jjNmzev/WPDMGSapj744ANt2bKFX8gDAAAkicVqUVZ2lkaOGKl9J+6rGTNmaOjQoekuK7AEnRBeV1enSCKmRUVFslqtidkUAAAAAAAAAAAAAJBUBEO7mP3337/9fdM0ZRhG+/v//e9/dfrpp6epMgAAgJ7l4usv1sXX+3cD3S53OzktCerI2YV5vV5traxU/7zQ8zIyMtWnT5/UFAUAAAAAAAAAAAAAiBtnDXYxw4cPV1ZWliS1h0LbfPbZZ+koCQAAAD1QeXm5fF5v2Hn9C/unoJreyeczw85Z9V11RPMAAAAAAAAAAAAAoA3B0C5oyJAhAceXL1+e4koAAACQarYUZACbmppUXV0d0VyHw5HcYnqpn9bU6m/3hX9+P+vvK3XdHz/TT2tqU1AVAAAAAAAAAAAAgJ6AYGgXlJ2dLdP8JRFgGIZM09TatWvTWBUAAAASbUBztuy+zk/JC31GkNmJYZqmNm3alNQ9ENo3y7fqlpuWqGxzY0Tz16+r1y03LdGK5VuTXBkAAAAAAAAAAACAnoBgaBfU2Njod4y8JNXW0iUIAAAgHhZZlGXLCvlmSeFT5Gy3XSPr81XYnCmLKWWaUp8kB0OrqqrU0tKS1D0Q3E9ravXAPcvU0uKN6r6WFq/uv2cZnUMBAAAAAAAAAAAAhGVLdwHwV15eHnC8oaEhxZUAAAD0LHaLXcOzh6e7jE4sptTP5VSR1SWPpGTGQj0ej7Zs2ZLEHRCKz2fq8UdKow6Ftmlp8erxR0r119v2lsWS3AAxAAAAAAAAAAAAgO6LjqFdTE1NjaqrqyWp03HykuRwONJQEQAAAGIRoAF8UFaHT/afO4YmU1lZmXw+X3I3QVArvqnU+nX1ca2xfl29SldUJqgiAAAAAAAAAAAAAD0RwdAu5s033wx6LScnJ4WVAAAAIB72zMiToVabJ4mVtGpsbFJtLceQp9N776xPyDrzE7QOAAAAAAAAAAAAgJ6JYGgXM3fuXL+xts6hxcXFqS4HAAAAMXJkRPhU2zBl8bUktxhJFRUVSd8DwblcPn29NDF/Bl9/VaGW5tiOowcAAAAAAAAAAADQ8xEM7UK++OILzZ07V0aAc0cNw9Do0aPTUBUAAACiZRiSPSOyjqFWu1dRnDofM4/HnYJdEExNtUder5mQtbxeU1u3NidkLQAAAAAAAAAAAAA9jy3dBaBVfX29zj33XJmmKcMw2ruEdrT33nunoTIAAABEy5FlkWGJNBjqkXxJLggR2dK8RU+teirknDNGn6HCjMKo13a5EhMKbdPU5EnoegAAAAAAAAAAAAB6DoKhXUBDQ4OmTp2qr776KmgoVJImT56c4soAAAAgSS0t0R3b7ciKrDG/YZiymK5YSkIS1LprNeenOSHnTB8xPaZgqMOR2L6wmZn8Uw4AAAAAAAAAAABAYBwln2bz5s3T2LFj9cknn/gdId8xJDpmzBiNGzcuHSUCAAD0ek2NUXRnNCRnlkWKoEGkxeaVEeRFQehZ+uTbZLUmJhxqtRrq1y8jIWsBAAAAAAAAAAAA6HloM5MGZWVlevHFF/Xss89q8eLF7eHPYN1CDcPQBRdckOoyAQAAIMk0ozu2255pqNK9Vdme7LBzLTbOkO8tHA6Ldt2tv75csiXutXYd31/ODGsCqgIAAAAAAAAAAADQE/WaYOg///nPlO/p9XpVX1+vuro6VVVVaeXKlVq2bJnWr18vSZ0CoR0/7jgmScXFxTrzzDNTWDkAAADaNDV55Isiv9mSWaPK5i2yeR2yK/SR4xZxjHxvcshhQxMSDJ182NAEVAMAAAAAAAAAAACgp+o1wdDTTz/d76j2dNi2I2igUGjHuYZh6JFHHpHT6UxJfQAAAOisod4d8VzT4lW1uVWS5JVP9jDzDdOU0vgUNTcvT1JD+groZXYe21dDi3O0fl19zGsMLc5Ryc59E1gVAAAAAAAAAAAAgJ7Gku4CUs00zbS+GYbR6a1tvKO2sKhhGLrqqqs0derUdHypAAAAej2fz1RjY+THyDflVMmn7nE8vNVqVb++BAxTyWIxdPZ5JXI6YzsG3um06uzzSmSxpP8FbwAAAAAAAAAAAAC6rl4XDN02mJnqN6lzODVQfW1zfv/73+u2225L6dcHAAAAv2hs9AR8zhaI1+JWo60myRUlzoABA2SxxhZQROyGj8jTJZfvEnU41Om06pLLd9HwEXlJqgwAAAAAAAAAAKCLqy+L7zrQi/Sao+TbRPqL/VTrGAi1Wq268cYbde2116a5KgAAgJ7Fa3pV2VIZck5fZ19ZjdbQXjTHyDdlVMdTWkplZmYqPz9f8rrSXUqXkmHN0O59dw87J147j+una2+YoMcfKY3oWPmhxTk6+7wSQqEAAAAAAAAAAKD3WrdIKp0rlRwnFU+M/jrQy/S6YGhX0RYEbdMWWN1tt9300EMPaeJEHqAAAAASzWN6VNFSEXJOniNPVsMqr9dUU5M34rXdtuZ4y0sJwzA0aNCgdJfRJQ3JGqLH9308JXsNH5Gnv962t0pXVGr+O+v19VcV8np/eRGb1Wpo1/H9NfmwoSrZuS/HxwMAAAAAAAAAgN5r3SIZpS+1vl/6kkypc/gz3HWgF+p1wdBtA5np1LF76V577aXLL79cM2bM6FI1AgAA9FaNDR6p9Z+NssqS3mISqKCgQE6nM91lQJLFYmjsuH4aO66fWpq92rq1WU1NHmVm2tSvX4acGdEdNw8AAAAAAAAAANDjdAx9/szoGP4Mdx3opXpVMLQrHSOflZWlvffeW5MnT9Zxxx2nHXfcMd0lAQAAoIP6hl+Okbca4YOhhY4BqlaV3Gbkx88nSqRPc202mwoLC5NbDGLizLBq8JDsdJcBAAAAAAAAAADQdQQIfbYxSl+Suf5TGbXrg1+XCIei1+o1wdDTTjst5XsahiGHwyGn06n8/HwNGDBAxcXFGjNmjLbffntZrXQAAgAA6Io8HlMtzZ72jyPpGJrrzFFfWx9trVivSmezUvmSpNraGuVFMK+oqEgWS8/pfgoAAAAAAAAAAIAeKkQotE2wUGj7dcKh6MV6TTD06aefTncJAAAA6CYaOnQLtcgiI8L7jCa3+rdkKt/tVLndpVh6h5pWe1TzPR6PKquqlOfMDTkvMzNTeXmRxEcBAAAAAAAAAACANKovk0rnJmat0rlSwXZSTlFi1gO6CdoFAQAAANtoqP8l0mlTFF3eG5tb7/FZ1L85K6a9ffbo7isrK5Pp84Wd179//5jqAQAAAAAAAAAAAFIqp0gqOS4xa5UcRygUvRLBUAAAAKADj9snl8vb/rEt0qfMPlNqccW9v8+RHfHchoYG1dbWRjTXbo+uEykAAAAAAAAAAACQNsUTZZZMj2sJs2Q6x8ij1+o1R8kDAAAAhgw5Lc6Qc5oafwmFth4jH+FB8i0uyYynutZj5E2rQ4rgEHrTNLV58+b4NgQAAAAAAAAAAAC6quKJMiUZpS9FfSuhUPR2BEMBAADQazgsDm2Xu13IOevX1be/H80x8mZz/N1Cvc4cRZpD3bp1q1yu+PcEAAAAAAAAAAAAuqziiTLXfyqjdn3Et5h5QwmFotfjKHkAAADgZy0tXnk8vvaPIz5GXpJawnf5DMfnyIlontvtUUVFRdz7AQAAAAAAAAAAAF3aukVRhUIltc5ftyhJBQHdAx1DAQBAl7Ru3TqtXbtWmzZtUn19vZqbm2W325Wbm6u8vDz1799fY8aMUU5OZEE6IBIN9b+EO6M6Rl6STDPibp8Bb7fY5LNnSu7w59FXVFTINOM8tx4AAAAAAAAAAADoytYtiukYean1+HlTonMoei2CoQAAoEuoqanR/Pnz9e677+rLL79UdXV12HsMw9DIkSM1btw4HX744Zo0aZIcDkfEe55yyin64osvoq7VZrMpOztbOTk5GjBggHbaaSeVlJTooIMOUv/+/aNeb1vXXHON5s2bF/c6gRxzzDG6/fbbk7J2T9DQ4Gl/P6puoQngc0Yecm5sbExiJQAAAAAAAAAAAECaxREKbUM4FL0ZwVAAAJBWGzdu1N///nf9+9//VlNTU1T3mqap1atXa/Xq1XrllVfUp08fTZs2TWeccYaKi4uTVLHk8XhUU1OjmpoabdiwQV999ZWk1sDofvvtp3PPPVfjx49P2v5IjuZmr7zeX46Rt8qa0v29UQRDAQAAAAAAAAAAeqT6MsmeH/p6TlHKykGa1JdJpXMTs1bpXKlgO75v0OsQDAUAAGnh8Xj0xBNP6LHHHlNzc3NC1qypqdHzzz+vl156SSeeeKLOO+88FRQUJGTtSHg8Hi1YsEALFy7U9OnT9ec//1lOpzNl+yM+9R2OkTd+Pkg+VUyLtfUYeaRVZUul5qyZE3LOjBEz1NfZN0UVAQAAAAAAAADQi6xbJJXOlXWHX0v2kUGvq+Q4OkD2dDlFrX/OcXYMldS6DqFQ9EIEQwEAQMqVl5fr8ssv1+LFi8PO7du3rwYNGqTs7GxZrVY1NjaqvLxcZWVl8vl8Ae9xu9365z//qe+++06zZs1KcPXhmaapOXPmaMOGDXrooYeUmUngr6szTamx4Zdg6LbHyLutLUnd3+fIkVIYREVgVa4qPbHqiZBzDh18KMFQAAAAAAAAAAASrcOx4fbv5il70GQ19N2l/bJ14+cyvpvX+gHHg/cOxRNlSnEdJ2+WTOf7BL0WwVAAAJBS69at0+9+9zutX78+4PWMjAxNmTJFhx12mCZMmBC042dTU5O+/vprffzxx/rvf/+rjRs3+s3xer1R11dSUqLrr78+5Jzm5mY1NDToxx9/1NKlS7Vw4UK5XC6/eZ988on++te/6tZbb426jm0VFhbqwQcfjHudvn0JtAXS1OSRz2e2f2zb5hj5poxqqTF5+3OMPAAAAAAAAAAA6LU6hELb9N00X5LU0HcXZVcuk/3nj9sYhEN7hzjCoYRC0dsRDE2gL774QosWLdKyZcv0008/acuWLWpqapLValV2drb69eun7bffXiUlJTrggAM0bty4dJcMAEBKbd26VaeddlrAEKfVatVvf/tbnXPOORGFFzMzM7XPPvton3320eWtDm7tAAEAAElEQVSXX673339fjz76qJYtWxZXjdnZ2dptt92iuqeqqkp33nmnXn75Zb9r//73v3XcccdpwoQJcdVlt9ujrguRawhxjHyzs05eq3/wN1FMwyKfPStp6wMAAAAAAAAAAHRZAUKhbfpumq+cquVyNJcHvE44tJeIIRxKKBQgGBq31atX68EHH9QLL7yg8vLOP4hM0+z0sWEYeuedd9o/HjRokE455RSdffbZGjlyZErqBQAgXTwej84///yAodDCwkI98MADGj9+fExrG4ahQw45RAcffLBeeeUV3XbbbaqpqYm35IgVFBTo1ltvVX5+vp566qlO10zT1Isvvhh3MBTJ4/OZamz0tH/c8Rh50/CpMXOrFH3z2cj3d2RLBsfIAwAAAAAAAACAXiZEKLRNsFBoG8KhvUTxRJkttTJ+eDvkNFOGVHIc3w+A1OG33ohKZWWlzj33XI0ZM0YPPPCAysrKZJpmpzepNahi/PyL/m2vb9y4UXfccYfGjBmj888/X9XV1Wn8jAAASK5HHnlEX3/9td/4wIED9dxzz8UcCu3IMAwdc8wxeuWVV9ISxLz00ks1dOhQv/EPPvggpmPtkRqNjZ5OL+jpGAxtzKiWz5LcPzuvMzep6wMAAAAAAAAAAHQ59WVS6dzErFU6t3U99GwDdw0/Z/zvCIUCPyMYGoMPPvhAu+yyi5544gl5PK1BgrYA6LZvbYJdN01Tbrdbjz32mMaOHav33nsvjZ8ZAADJsXbtWj3++ON+41arVQ888ICKi4sTut/AgQP19NNP68gjj0zouuE4HA5NnTrVb7y2tlYVFRUprQWR63yMfOtB8pLktXjUnFGd1L1Nw5DPEf8x8nl5fRJQDQAAAAAAAAAAQIrkFLV2dkyEkuNa1wOy+qW7AqDL6HbB0AMPPFAOhyPo2/XXX5/U/f/1r3/piCOO0MaNGzsFQiX/jqDh3iR1Cohu3LhRU6dO1TPPPJPUzwEAgFS7//775Xa7/cbPOuss7bLLLknZ0+FwaObMmUlZO5SSkpKA41u2bElxJYiE12uqqemXjqA2Wdvfb8qskmmYgW6LiGH4ws4xbZmSEd9TcpvNpr59C+JaAwAAAAAAAAAAIOWKJ8osmR7XEmbJdDpEAkAAtnQXEI3q6mp98sknQY9idTqduuCCC5K2/9y5c3X66afL5/N16gba8ejRaAQ6bt7tdut3v/udnE6njj/++PiLBgAgzcrKyvTmm2/6jQ8ZMiSpP7fTJS8vL+C4x+NJcSUIxGt6Veuubf+4udkrj7NDx1DDKrsrV4bPquzGfrL4bGrKqJKp6J/vWew+Kcwp9D5HVocoamyKiopksVhiqBDbclgc2i5nu7BzAAAAAAAAAABAghRPlCnJKH0p6lsJhQJAcN0qGPrOO+/I6/V2CmVKau/cedJJJ6moKDmtoZcvX65TTjmlUyg01kDotrYNiPp8Pp1++ukaNWqUdt9994TsAQA9gav0NRn2LNlHTw45z71qvkx3oxwlR6eoMoQyd+7cgC/qOP7442W329NQUXLV1dUFHA8WGEVqeUyPNjdt7jyY/cu7bklOd5asssowLcpqKlBGS67qHVvkUmNUe1mtYVKhknz2+IKh2dnZrd9bboLHiVCcXazZB81OdxkAAAAAAAAAAPQuxRNlrv9URu36iG8x84YSCgWAELpVMDRQt7GOzjvvvKTs63K5dMIJJ6i5uTmiUOi2wdVAAt3f8Wj65uZmnXrqqfryyy/lcNCVCABcpa/J/e1/2j8OFg51r5ov17JfQj2EQ9PvnXfe8Ruz2+2aPj2+YyG6qm+//dZvzOFwqLi4OA3VIBEsPpuym/pFFww1TBmmO/w8S+zHyBuGoYEDB8Z8PwAAAAAAAAAAQJewblFUoVBJMmrXy1y3iHAoAAQR+2+i0+Ctt97yC2a2/Xf8+PHaY489krLvHXfcoZUrV4YNhXY8Et40zZBvHed21HHtb7/9VnfccUcSPiMA6F62DYW6ls2We9V8v3nbhkLd3/5HrtLXUlIjAisvLw8YlNxzzz3Vr1+/NFSUXG63O+ALWcaPH98ju6MiOKvNKyPGw92bmpojmtevXz9eQAQAAAAAAAAAALq3dYtiOkZe+vn4+XWLElwQAPQM3aZj6OrVq7Vx40YZhuEXzDQMQ6eddlpS9i0vL9ftt98eUSi07brD4dD++++vyZMna9iwYSosLJRpmiovL9eKFSv09ttva+nSpe33BVqzbfyuu+7Seeed1yPDMwAQiW1Doe3jPwdA2zqHbhsKbdN2L51D02PZsmUBx3fZZZcUV5IaDz74oH766Se/8Z7aHRXBWe1eecKfJO/HNE1VVGxRthG6E6jdblP//v1jrA4AAAAAAAAAAKALiCMU2sYofam1VQedQwGgk24TDF28eHGnjzt227RarTrhhBOSsu+dd96pxsbGkAHONjabTeecc46uu+46FRYWBl3z9ttv1+LFi3X11Vfr/fff91u7raOoJNXV1emRRx7Rn//85wR+VgB6G1/txvRsbLHJkjMg6tt89eWSz/PzB8GPYnYtmy2zpUaS5P7fWyEWdLd/DUzTlG+btJbPZm1/3LXkDY6+3sZKyRNZh79YxFJTV1FaWhpwfNy4cSmuJLmqq6t19913a86cOX7XdtttNx111FFpqAppY5iyqEWSNepbKysr5XK5le0MPa9fv/4Bu88DAAAAAAAAAAB0C/VlUuncxKxVOlcq2E7KKUrMegDQA3SbYOgXX3zhN9YWoJw0aZIGDIg+eBROY2OjnnjiiaC/dO/YJTQ/P18vv/yyDjrooIjW3mOPPTR//nzdfvvt+tOf/hS0E6ppmnriiSd07bXX8st/ADFreuemtOxr5A5S1uE3Rn1f8ycPy6zbFNHckIHQDnNCzfN0eD/7uMci2rcj17I58m74Mur7IhVLTV3F+vXrA47vtNNOKa4kcg0NDe2dvYNpaWlRQ0ODfvzxRy1dulQLFy5US0uL37wRI0bogQceSMjP8I0bN2rMmDEx3z948GC99957cdeB8Cw2r4wgXeZDcbvdqqiokBHBU/Ts7KxYSgMAAAAAAAAAAOgacoqkkuOkODuGSmpdh1AoAHTSbYKh23YM7ejII49Myp4vvPCCamtrg4Y2pdZQqNPp1DvvvKMJEyZEvcc111yjrKwsXXrppZ326dg1dP369frggw908MEHx/kZAQCQWps3bw44XlBQkOJKIldaWqqZM2fGtYbdbtexxx6rK664Qrm5uQmqDOlkcxqSf/Y38Fy7V4o+F6qysjL5fD5ZeS0QAAAAAAAAAADoDYonypTiOk7eLJnOMfK9hT1b5vaHh50DoFW3CYZ++eWXQbttTZ06NSl7PvfccyGvt4U3/+///i+mUGibiy++WJ988olmz54d9Mj6V155hWAoAKDbqa2t9Ruz2+3KzMxMQzXJ169fP51xxhk65phj1K9fv3SXgwAMGbLKKp/PlGmYktH6vMswLTLM4IlMR6ZF8v92DsgiV9R11dfXq66uLur7AAAAAAAAAAAAurU4wqGEQnsZZ640akq6qwC6DUu6C4jE5s2b239R3rGTpiT17ds3KcfRbtmyRQsWLAgYRu0Y3iwpKdHFF18c93533XVXe0im455te731VvijkgEA6Gqam5v9xnJyctJQSWps3bpV99xzj6688kotXLgw3eUgAIfFof6eYXJWD5Lhs7aPW3xW9a0Zrr7VI2T1Ovzus2dE9rTZYvPIMH1R1WSaZtDuugAAAAAAAAAAAD1e8cTWkGcUCIUCQGjdomPojz/+6DfWFhDdd999k7Ln22+/La/XG7SDp9Qa2rzuuusSst/QoUN16aWX6rbbbut0TH3b+999952qqqq69NG7AABsy+v1+o05HP6hu57E6/Xqk08+0SeffKL99ttPt956q4qKiuJet7CwUA8++GDM9/f0r3s0Gho88jqaZFo97WNeq1stjno5W3L95tszDFmskZ0Nb3X4oj5GvqKiQm63O7qbAAAAAAAAAAAAepLiiTJbamX88HbIaaYMqeQ4QqEAEEa3CIauWbMm6LVddtklKXu+/XbgHzQdu3kOHjxYxx9/fML2POOMM3TbbbcFvf75559ryhRaIgMAug+n0+k31tWPy95zzz31zDPPhJxjmqYaGhpUV1en77//Xl9//bVee+01/fTTT53mffzxx5oxY4ZmzZql7bbbLq667Ha7dtttt7jWgNTc7JXH65Mnx/9c+MaMKjldOdI2R8o7siySIusCalVLVPW4XC5t3bo1qnsAAAAAAAAAAAB6pIG7SmGCoRr/O2nAzqmpBwC6sW5xlHygjqFtxo4dm5Q9P/zww4DHyEu/dPJMZChUkrbffntNmDChU6fQjkpLSxO6HwAAyZaZmek31tjYGLCTaHdiGIZycnI0aNAgTZo0SRdeeKHefPNN3XjjjcrKyuo0t7y8XGeccYZqamrSVC06qq93+3ULbdPWNXRbzuwIj5G3eqM+Rr6iYmvQ7vQAAAAAAAAAAPRI9WXxXUfvltUv3RUAQLfQLYKh69atC3ptxIgRCd+vvLy8vUtpqF/Un3jiiQnf++ijjw56bdWqVQnfDwCAZOrfv3/A8a7eNTQWhmFo5syZevDBB2WzdW7KvnnzZt16661pqgxtTFNqaHDLk+nfLbRNY0aVZPzy/M/mNGS1GZIvfHjTYo8uFCpJTU2NUd8DAAAAAAAAAEC3tW6R9PGdrf+N5ToAAIhItzhKvr7ev3NTmyFDhiR8v88++yzgeMcunvn5+dpjjz0Svveuu+4a9FpbWBUAopV52A3p2dgS24+ZjH3Pl3yt3fw8az+V+39vBZ1r33GKJIWdYxu2j6TWwL/H07lbpc1mDdolOhKOXWZIJcGD/b3ZoEGDAo6vX79e+fn5qS0mRfbbbz8de+yxmj17dqfx1157TRdeeKGKi4vTVBmamjxy2xoDdgtt47W6VZe1RbmNhZJpyJn18+uoml1h17ca7kSVijSpcdXorY3Bf55I0pTBU9TH0SdFFQEAAAAAAABAD7JukYzSl1rfL31JpiQVT4z8OgAAiFi3CIY2NDQEvZaMUMmSJUuCXms75n3SpEkJ31eSxo0bF3Tf8vLypOwJoOez5A1OdwlRseQM6PCBPeg8xy7Hyz56siTJcPaRa9nswBMt9vavgWmasng6h8IsNltcwVBLVt+Y7+3pRo0aFXB8+fLlGjt2bIqrSZ2TTz7ZLxjq8/k0b948XXTRRWmqCvX1obuFtmlx1slja1FOQ6Gc2bmSJLO5JfwGUR4jj66noqVCd3xzR8g5E/pNIBgKAAAAAAAAANHqGPr8mdEx/BnuOgAAiEq3OEo+VDA0MzMz4fuFCoa2OfDAAxO+ryRtt912cjgckn7pUNr23y1btiRlTwDoyhwlR8u+01H+4x1CoZJkHz1Zjl2O95tn3+koOejmmTY777xzwPHly5enuJLU2mGHHdSnj39wbPHixWmoBpLk85mq89SG7BbakdfqksVuymr/+Rh5F91AAQAAAAAAAACISYDQZxuj9CVp0b2hr3OsPAAAUesWwdBQR8mbppnw/ZYsWRK2c9yee+6Z8H3b5OXlBRyvrQ3f4QoAeqJtw6HbhkLbbBsOJRSafiUlJcrNzfUb/+KLL5LyM7yrMAxDRUVFfuM//vhjGqqBJDU2euTOiPy5lGEaynVmt37Q3CL13G9XAAAAAAAAAACSJ0QotI1Ruz70dcKhAABErVsEQ32+4MdyJjosuWnTJm3evFlS59Bpx6CoYRjabbfdErpvR4ECNJLkcrmSticAdHVt4dBgodA2beFQQqFdg91u1/777+83vm7dOi1a1LP/AZ+dne03Vl1dnfpCIEmqbKqOuFuoJJmGKVdG64uTzMbmZJUFAAAAAAAAAEDPVV8mlc5NzFqlc1vXAwAAEekWwdCMjIyg1+rq6hK6VyRHvG633XbKyclJ6L4d5ebmBuyiRjAUQG/nKDk6ZCi0jX30ZEKhXcivfvWrgOMvvPBCiitJrZqaGr8xh8ORhkrg9frUaK2O+r5Kz9bW52RNqX0OlpkZ/LkvAAAAAAAAAADdRk6RVHJcYtYqOa51PQAAEJFuEQzNysoKeq2ysjKhe4UKhpqmKcMwtPvuuyd0z0jZbLa07AsAQDwOOOAADR482G/8vffeU2lpaRoqSj6Xy6VNmzb5jffv3z8N1aCiIbpuoW1cPpdqGyulAC/YSRbDMPg+AQAAAAAAAAD0HMUTZZZMj2sJs2S6VDwxQQUB6La8bql+c+g3rzvdVQJdRrdIGhYWFga9tmLFCo0fPz5he33++edh5yRyv0Campo6HV3fJtgR8wAAdGVWq1XnnXeerrvuuk7jHo9HV199tebOnZu0TppVVVUqKChIytqhLFmyRE1NTX7jxcXFKa+ltzNlqtpbGfPLoSrclcpVXmKLCqFv374//33gH60AAAAAAAAAgB6ieKJMSUbpS1HfSigUQLumrTI+vjPkFHO/K6WcgSkqCOjaukXH0IEDg/+F/eabbxK2j8/n06JFiwKGMjvac889E7ZnIHV1dQHH8/JSF0oAACCRjj32WO24445+46tWrdIdd9yRlD3ff/99/fGPf0zK2uE8/vjjAccPPPDAFFeC6uYa+Syxhyxdhke19pYEVhSc3W6nW2iaWQ2r8h35Id+shjXdZQIAAAAAAABA91M8UWbe0KhuMfOGEgrtbezZMrc/XJ7hh6imcJ9Ob57hh8jc/nDJnp3uKgGgW+gWHUNHjhwZ9NoXX3yRsH0WL16s2tpaGYYhs8ORoR2DohaLRXvttVfC9tyWx+NReXl5p7G2WugYCgDorqxWq/7v//5PM2bMkNvdOaT3r3/9S5mZmbr88svDvjgjEi6XS/fff7+eeuop7bHHHnGvF61HH31UixYt8hu32+067LDDUl5Pb2bKVEVLRdzrbM1o1uCWnARUFFpRUZEsFou83tQdXY/ORuSM0LuHv5vuMgAAAAAAAACg51m3SEbt+qhuMWrXy1y3iHBob+LMlUZNkaelRbVbtnS+VFgoq9OZpsIAoPvpFh1Dd955Z7+xtvDmhx9+qIqK+H/hL0mvv/560Gtt4cySkhLl5CQvGLB+/Xr5fL5Oe0qtny8dQwEA3dmYMWP8jpNv88QTT+jcc89VWVlZXHssWLBAv/rVr/Tkk092+jmaCmVlZbryyit13333Bbx++umnq6ioKKU19Xa17lp5EnAku8viVYPdlYCKgsvJyeFFQAAAAAAAAACAnmndopiOkZd+Pn5+nX9DDgAAEFq36Bg6btw4WSwWmabZHght6yjm9Xo1d+5cnXPOOXHvM2fOnJCdygzD0OTJk+PeJ5SVK1cGvTZ8+PCk7g0AQLIdf/zx2rx5sx5++GG/awsWLNDUqVM1c+ZMnXjiiSouLo5ozfr6er399tv617/+pdLS0rhrbGho0NKlS0POMU1TjY2Nqqur0/fff6+vvvpKn376qbxeb8D5o0aN0vnnnx93bYicKVNbmhLz4iFJqnYk7zh5wzA0cODApK0PAAAAAAAAAEDaxBEKbWOUviRTonMoAABR6BbB0D59+miXXXbR0qVLOwU320Ki9957r37/+9/LarXGvMdnn32mb7/91u8Y+W0dfvjhMe8RiVBBlB122CGpewMAkAoXX3yxMjMzdc899/j9zG1sbNRTTz2lp556SjvttJN23313jRo1SoMGDVJ2drasVqsaGxtVXl6uH3/8UUuXLtXXX38tlytx3RxLS0s1c+bMhK03evRozZo1S5mZmQlbE+HVumvlNhP3feE2fFHfY4Z4wVFH/fv3l91uj3p9AAAAAAAAAAC6tPoyqXRuYtYqnSsVbCflcDobAACR6BbBUEk69NBDO4UmO3YNXbVqlR5++GFddNFFMa9/9913BxzvGETNycnRIYccEvMekViyZEnQa6NHj07q3gAApMpZZ52lHXfcUddcc40qKysDzvn222/17bffxrxHTk6Opk2bFvP98TIMQ9OnT9eVV16pvLy8tNXRG5kyVdGcuG6hsaqP4BR7u92ufv36Jb8YAAAAAAAAAABSLadIKjlOirNjqKTWdQiFAgAQMUu6C4jUjBkzAo63dfi87rrrtHz58pjW/uSTTzR37tygx8i3hVCPOuooORyOmPaI1IIFC4LWQcdQAEBPcsABB+j111/XSSedlNBuiQ6HQ6eeeqreeecdnXjiiQlbN1JOp1PTpk3T888/r7/+9a+EQtOgydMkw7TI4nF0erN5nLJ6wj+Xc1qdyvTaOr05fdF3pq9t8Yad079/YdDnfgAAAAAAAAAAdHvFE2WWTI9rCbNkOsfIAwAQpW7TMXTPPffUDjvsoFWrVrWHQdsCm4ZhqLa2VtOmTdOHH36oESNGRLzu+vXr9dvf/rZ9rVDHyJ9++unxfyIhfP3116qoqAhaBx1DAQA9TX5+vq6//nqdffbZevbZZ/Xf//5XGzdujGmtXXbZRb/+9a81bdo0FRQUJLhSfxkZGcrJyVF2draGDBmikpIS7bzzztp///2Vm5ub9P0RXJYtS/nuQaqt/eUoeUOGsuSU1+pSVZ91Ie8fYiuSo7K+01iLz6sfVRNxDT5J9W5T4V5TlJWVGfGaAAAAAAAAAAB0S8UTZUoyYugcSigUAIDYdJtgqCRdfPHFuvDCCzt1VeoYDt2wYYPGjx+ve+65R7/73e/Crrdo0SKdeOKJWrt2bcAwZsd9Ro4cqcMOOyxxn0wA//nPf4Luv+OOOyonJyep+wMAkC4DBw7UH/7wB/3hD3/QihUrtGTJEn3zzTdau3atNm3apLq6OrW0tMhutysvL099+vRR//79VVJSonHjxmmXXXbR4MGDo973mWeeScJnE7/zzz9fM2fO7DSW7K7lPU1Dg6fTxzZF3vHTbHaFnxRGrcuUz6QTKAAAAAAAAAAAkmIKhxIKBQAgdt0qGHrGGWfo1ltv1aZNmzoFOTuGQ2tqavT73/9ed955p2bOnKkpU6Zo6NChKioqUkNDg8rKyvTxxx9r7ty5euONN0J2CO249mWXXZb0z2/OnDlB999///2Tvj8AAF3BzjvvrJ133jndZaTVsGHDNGzYsHSX0W01N3vl9fo6jVllaf2v16H+ldv73WNYpH7DHDIMydxYEXcN1S2hn2MCAAAAAAAAANDrFE+U2VIr44e3Q04zZUglxxEKBQAgDt0qGJqRkaHbbrtNp512WqdumlLncKhpmlq5cqVuuukm3XTTTUHXa7un7f2OOq4/ZMgQ/f73v0/gZ+Lvf//7n5YtWxb0GPlJkyYldX8AAICeor7eLZ/FK29GnazNObL67O3B0GAcmRYZhiS3R/J449rfp9aOoQAAAAAAAAAAYBsDd5XCBEM1/nfSgN7dRAQAgHiF/g15F3TKKafo8MMP7xTqbNMWqOwYEA31FiwU2nE9wzB0++23y+l0JvXzevLJJ0Nep2MoAABAeKYpNTa45XU2yJPRoJb8MrXkblGLo14ygoc1ndmtT4vNxpa4a6hzmfKSCwUAAAAAAAAAIDZZ/dJdAQAA3V63C4ZK0jPPPKNBgwZJUsBw6LYB0WBvHed21HbNMAxNmzZNJ510UlI/H7fbrVmzZnX6XDq+P2jQII0cOTKpNQAAAPQETU0eeX0+eZ0N7WNee4vqcspU2ecnNWZWymfxdL7JaO0YKklqbI67hhq6hQIAAAAAAAAAAAAA0qhbBkMLCwv1xhtvKC8vT5J/OFRS2G6hwbqEdlxr+PDhevrpp5PzSXTwwgsvqKKior3uNm3h1MMOOyzpNQAAAPQEDfVueR3NMi0+v2s+i1eNmVWq7POTmjKq28cdmRYZFrUeIe/2+N0XDVMEQ3sSj8+jNfVr5DW96S4FAAAAAAAAAICez+uW6jfLaCiTrbmi05vRUCbVb26dAwAIy5buAmK1yy676O2339bRRx+t8vLysMfCR6LjGkVFRXr99dfVv3//hNQbyp133hny+jHHHJP0GgAAALo7n89UY6NH3tz60BMNyeZ1tn/4yzHy8XcLrXeb8vhnUtFN1Lvr9emWTyVJq2pX6bkfn1OTt0mZ1kydNPIkjc4brX0K91GOPSfNlQIAAAAAAAAA0AM1bZXx8Z1yShq07bUfWv9j7nellDMwxYUBQPfTbYOhkrTnnntq0aJFOumkk/TZZ5+1HxEvRRcQ7dgl1DRNlZSUaN68eRo1alTCa97W66+/rm+++ab9+Ppt68nMzNSUKVOSXgcAAEB319jokdfiks/mCjnP6nXI7s5s/aDjMfJNLXHXUN1Ct9DurKy5TNd8eY3feJO3SU9+/6Qk6cUDXyQYCgAAAAAAAAAAAKBL65ZHyXc0cuRIffzxx7rrrrvUt2/f9mPi20KikbxJrYFQm82mP/zhD/riiy9SEgqVpBtuuKG9ho71tH18+OGHKyMjIyW1AAAAdGcN9W55MsJ0C5WU0ZLX/r49w5DFKsnrlVriP3qEY+QBAAAAAAAAAAAAAOnWrTuGtrFYLLr88st19tln6+mnn9Y//vEPffnllxHfP3jwYJ100km68MILNWzYsCRW2tmcOXO0ZMmSoNcNw+AYeQAAgAh4vaYam93y5jeFnGeYFmW05LZ/7MxqO0Y+/m6hTR5Tbo6R7/G2tmzV9rnbp7sMAAAAAAAAAOie7Nkytz887BwAABCfHhEMbZOTk6OLLrpIF110kcrKyrRw4UKVlpZq9erVqqqqUmNjo+x2u3JzczV06FCNGTNGe++9t3bddde01OvxePTXv/415Jxf//rXKaoGAACg+2ps8MgwDTlrC+XJqJfX0SQZ/t07na4cGeYvTfOd2ZEdI2+xesLWUEe30F7hlbWvaK/+e6W7DAAAAAAAAADonpy50qgp6a4CAIAer0cFQzsqKirSjBkz0l1GSCeeeGK6SwAAAOgR6htaj4G3eO1yNBTIbOwji9OlFmetvNZfjojPaO7T/n7rMfKG5PVJza6Q61vt4VuB1rkJhnZ3W1u2hp0zf9N8Xdx0sYoyi1JQEQAAAAAAAAAAAABEr8cGQ9EzVVRU6OOPP9aKFSu0cuVKVVZWqq6uTi6XSzk5OcrLy9OwYcNUUlKi8ePHa8KECTIMI91lAwCAJPJ4TLU0d+7oaTPtymjOUlZzvlz2RjU7a2QapmxeR/uc9mPkw3QLlSTDDB0cleR3jHxWVpZ83gg+AXQZr6x9Jewcj+nRrO9n6epxV6egIgAAAAAAAAAAAACIHsFQdHl1dXV6+umn9cILL+izzz6Tzxe+Y1ebAQMGaNq0aTr33HO19957J7FKAACQLg0Nbr8xm345Lt7hzpLDneV3tLyj/Rj55pDrG1aPFOXrTAzDUP/+/VVeFj50iq6hrKlM8zfNj2juvHXzdPqo0+kaCgAAAAAAAARSXybZ80Nfz+H/rQEAACQTwVB0WY2Njbr11lv14IMPqra2NqY1ysvLNWvWLM2aNUsTJ07UnXfeqf322y/BlfZc9fX1uueeeyIO41566aXKz89PblEAAGyjod4/GGrtEAxtZxoyDZ88thZZbYZa5JHcpkx3Y6dnxRleqyym0eG22MKd0byYBek36/tZ8pie8BMluX1uuoYCAAAAAAAAgaxbJJXOlXWHX0v2kUGvq+Q4qXhi6usDAADoJQiGokt6++23dfbZZ+unn35K2JqLFi3SpEmTdMYZZ+i+++5TTk5Owtbuqf74xz/qb3/7W8TzTz/9dIKhAICUcrt9crk6n9dulVVGkBafPotHNbkbJUmVDT8PZneeM7K+j5xea/vHDptHrigznqZpqry8XBajILobkRZlTWWat25eVPfQNRQAAAAAAADYxrpFMkpfkiTZv5un7EGT1dB3l/bL1o2fy/huXusHpS/JlAiHAgAAJEmAVkpAet1xxx2aOnVqQkOhbUzT1JNPPql9991XP/74Y8LX70k++eQTPfzww+kuAwCAkCLuFhojw+KRNcpj5Nu4XK6E1YHkmvX9LLl9/t9LobR1DQUAAAAAAACgTqHQNn03zVd25TJJUnblMtnbQqE/M0pfau0gCgAAgIQjGIou5ZJLLtHVV1+d9KNXly9frn322UcrV65M6j7dVUtLi84880yOwAUAdHn1AYKhtgQ+xTUthDt7uli6hbaZt26eyprKElsQAAAAAAAA0N0ECIW26btpvop+eFZ9N80PeJ1wKAAAQHIQDEWXce211+qBBx5I2X7l5eU69NBDtWbNmpTt2V385S9/ITQLAOjyWlq88ng6v4jBIkvQY+RjYbd5ErYWuqZYuoW2oWsoAAAAAAAAer0QodA2jubykNcJhwIAACQewVB0CS+++KJuvfXWiOZmZ2fr1FNP1ezZs7Vq1SrV1tbK5XKprKxMCxcu1O23365x48ZFtNaGDRt07LHHqqWlJZ7ye5SlS5fqjjvuSHcZAACEFegYeZusCVvfsHhlM8yErYeuJ55uoW3mrZunrS1bE1MQAAAAAAAA0J3Ul0mlcxOzVunc1vUAAACQEARDkXY//PCDzj777LDzDMPQ+eefrzVr1ugf//iHZsyYoVGjRik3N1d2u10DBgzQpEmTdPXVV2vZsmWaN2+eRo4cGXbdr776SpdffnkiPpVuz+Px6Mwzz5THQ3c0AEDX19Dg//Mq3DHyFlvk3URNCy8c6eni6Rbaxu1za97aeYkpCAAAAAAAAOhOcoqkkuMSs1bJca3rAQAAICFs6S4AOPfcc1VbWxtyTmZmpp577jkdc8wxEa/761//WgcccIBmzpypt99+O+Tchx9+WCeddJL222+/iNfvie666y59+eWX6S4DAICwmpu98nqjP0benhl5MNRm5YUSPZnL69Kr615NyFrvb34/IesAAAAAAAAA3U7xRJlS2OPkQzFLpkvFExNXEwCgZ7I6ZRbtEnYOgFYEQ5FWL7/8st59992QcxwOh+bNm6fDDz886vULCgr0yiuv6KijjtL8+fNDzr3ooou0ePFiWSy9s5Hud999p5tuuingNYvForFjx2rZsmUprgoAgMCq6xtkyuwUBA3XLVSSHBkWyRV+fcPild3CMfI92YbGDWrxJaYrbLxdRwEAAAAAAIBuLY5wKKHQXsjrlpq2hp6T2U+y2lNTD4DuI7NA2u20dFcBdBsEQ5E2Pp9P11xzTdh5//d//xdTKLRNRkaGZs+erd12203r1q0LOu+rr77Sc889p9/+9rcx79Vdmaap3//+92pubg54/aKLLlJ1dTXBUABAl2CaUo2lTL4Cr2wtWbI258jis8kqa8j7LDZDWRlO7eAcLd+mrZIvcPDTahqSPfDPRPQcxdnF6mPvoxp3Tdxr5dpzVae6BFQFAAAAAAAAdFPFE2Wu/1RG7fqIbzHzhhIK7Y2atsr4+M6QU8z9rpRyBqaoIAAAeqbe2RoRXcLLL7+sVatWhZxzwAEH6NJLL417r759++rvf/972Hl33HFH3Ht1R4888og+/PDDgNeGDRumm2++OcUVAQAQXFVDrXxWj2SY8mQ0qCW/TK7cCrkdDZIRvMunM8siwzBkdflk80o20wj4Zkiy27yp+4SQFjaLTXfucaf62PvEtU4fex/9oeQPCaoKAAAAAAAA6KbWLYoqFCqpdf66RUkqCAAAoHejYyjS5q677gp53TAM3XfffQnb7/DDD9eRRx6p//73v0HnLF++XG+++aaOOOKIhO3b1a1duzZk59aHHnpIOTk5KawIAIDQqtxVfi9v8tpbVGcvU4PPpoyWPGU295Fhdp7kzG49dt5sCn18uGHxySpP3HU6HI6410By7d5vd7112FtaXb9azd7ou8RmWDO0Xc52+unHn5JQHQAAAAAAANBNrFsU0zHyUuvx86ZE51AAAIAEIxiKtCgtLdVnn30Wcs60adM0fvz4hO577bXXhgyGStLTTz/dq4Kh5557rurqAh99OmPGDB111FEprggAgOBcXrdcRmPQ6z6LR83OGmU253cat1gle8bPQdHG0AFAqz3+bqEWi0UDBgxQxRZ33GshuWwWm3bI2yHdZQAAAAAAAADdUxyh0DaEQwEAABKPo+SRFs8++2zYOYk4Qn5bEydO1F577RVyzmuvvRY0KNnTPPPMM3rjjTcCXsvPz9cDDzyQ4ooAAAhtS0OlZISe42zJk2F2nuTI+vlpb4tb8vpC3m+1xhfmtFgsGjp0qJxOZ1zrAAAAAAAAAECXVl8mlc5NzFqlc1vXAwAAQEIQDEVavPDCCyGvDx48WIccckhS9j7llFNCXm9qatK8efOSsndXUl5erssuuyzo9dtvv10DBw5MYUUAAIRmylS9rybcJGW25PkNO7Nbn/aGPUbe8Mlixh4MdTqdGj58uLKzs2NeAwAAAAAAAAC6hZwiqeS4xKxVclzregAAAEgIgqFIuVWrVmn16tUh5xx33HGyWJLz7TljxgwZRuhWY2+99VZS9u5KLrroIm3dujXgtf33319nn312iisCACC0mpZa+YzQx7w73Nmy+GydxgyL5IjwGHlLHMfIDxo0SNttt50yMjJiXgMAAAAAAAAAupXiiTJLpse1hFkynWPkAQAAEoxgKFLu3XffDTtnypQpSdu/qKhIu+66a8g58+fPT9r+XcErr7yi2bNnB7zmcDj0+OOPhw3PAgCQau4WUxaPI+ScQN1CHVmW1uPnXR7JEzr4abN5Yq4vMzMz5nsBAAAAAAAAoNuKIxxKKBQAACA5CIYi5d57772Q1202mw488MCk1nDooYeGvL5582atWLEiqTWkS01Njc4///yg16+55hrttNNOKawIAIDIeBocctYWylkzQNaWLMns/CIGq9cuuzvL775fjpEP3S1UhinDdCWsXgAAAAAAAADoNWIIhxIKBQAASB5b+ClAYi1evDjk9Z133lk5OTlJrWGfffYJO2fJkiXaeeedk1pHOvzhD3/Qxo0bA14bM2aM/vSnP6W4IgAAwvN4TLU0t3bztHjtcjQUyGzsI8PZIpezVl6rRxktffzuMyySI7PtGPmWkHtYbR7RLxsAAAAAAAAAYlQ8UaanWfruP/L13VH11oJOl7OzsmRt3Cxt+VYqOY5QKAAAQBIRDEVKVVVVac2aNSHn7L777kmvY8KECWHnfPXVVzr11FOTXksqvffee3ryyScDXjMMQ4899picTmeKqwIAILyGBrffmMW0Kqu5QNnNBXLZG2X3ZPjNcWRaZBiS3J7WtxCscRwjDwAAAAAAAACQNPJgqbBEbnu+ards6XTJWVgoq9Mp1ZdJOUVpKhAAAKB34Ch5pNTSpUvDztlll12SXseIESOUl5cXcs5XX32V9DpSqbGxUWeddVbQ62eeeaYOOOCAFFYEAEDkGur9g6FWWdvfd7izZJj+T21/OUY+dLdQGaYs4hh5AAAAAAAAAIhbuNAnoVAAAICko2MoUuq7774LO2fUqFEpqETafvvtQ4Y/I6m1O7n22mu1evXqgNeKiop05513prgiAAAi43b75HJ5/cZt4V7jZHCMPAAAAAAAAAAAANAj1G+W8XHobIu535VSzsAUFQR0bQRDkVI//vhj2DmpCoaOGjUqZDB08+bNam5uVkaG/7G03c1nn32mBx54IOj1+++/X/n5+akrCACAKATqFioZsoYJhjoyLTIskjxeydW6hs+Q3Bb/kKnV1iLvz8lQpxmorb4ZbdkAAAAAAAAAAACIhtUps2gX+Xw+tbR0bvrhdDplsVgkqzNNxQFA90IwFCkVSTC0uLg4BZVIQ4cODXndNE2tWbNGY8aMSUk9yeJyuXTmmWfK5/MFvD5t2jSdcMIJKa4KAIDI1QcIhobtFqrAx8i7LV79mFMT8r4xbqsyt8mBNgbKpgIAAAAAAAAAACBxMguk3U6Tu6VFW7ds6XSpsLBQTiehUACIVPjfqAMJtG7dupDXc3JylJ2dnZJaBg4M3zp67dq1KagkuW655RatWLEi4LXs7Gw9/PDDKa4IAIDItbR45fH4v7jBKmvoGw3JkdV2jHxz3HU083oqAAAAAAAAAAAAAEA3QTAUKVVRURHyeiRhzUQZNGhQ2Dlbt25NQSXJs3z5ct12221Br//lL3/R8OHDU1gRAADRCXaMfLiOofYMiywWSV6f1BJfu09TkjW7T1xrAAAAAAAAAAAAAACQKrQ+QkpVVlaGvJ6fn5+aQiLcK1y9XZnX69WZZ54ptztwGGbChAm65JJLUlwVAARXW1ur0tJSbdmyRXV1daqtrZXFYlFmZqaysrI0YMAADRkyREOGDEn5MREVFRVas2aNNm7cqOrqajU1NUmS8vLylJeXpz59+miHHXbQgAEDUlpXb9DQ4PEbi+gY+Sz/Y+Rj1eQ1lJmXK2lL2LkAAAAAAAAAAAAAAKQbwVCkjGmaqq6uDjknNzc3NcVEuFd3Dobee++9+uKLLwJes1qteuKJJ2S1hjmGt5tatGhRXPcvX77cb8ztdqulJf5wUSA2m02GYUiSLJZfwk6maSZlv94u0NeVr3X6fPfdd3rppZe0cOFCrV27NqI/C4vFopEjR2rs2LEaN26cJk6cqO222y6hdblcLn388cd699139dlnn2nDhg0R3VdUVKSxY8fqgAMO0JQpU9SnT3RdJv/2t7/poYceiuqezMxM5eTkKDc3V0OGDNG4ceM0duxY7bvvvikP0CZac5NXXm+gY+TDB0MdWT//3U7AMfJue1ZE35umaXaaZ/oiuMdn+q3ti+A+n8+UpeO0COvzmxdpjZau/zjp87V+r5imKY/HP1CcTC6XK6I5yXouge4h0Au2gr2ICwC2xWMIgHjwGAIgVjx+AIgHjyEIxnC5FO63Fy6XSyb/P7VX4zEEgfD4ga6gOz0WEQxFyjQ2Nsrr9Yack8pgaF5eXtg5tbW1Kagk8X744Qddf/31Qa9feumlGj9+fAorSq1999034WtWVVVpy5bkdIorKCiQ3W6XpPawrs/nS3mopTcL99iExFu9erVuvvnmoAH2UHw+n3744Qf98MMPeuWVVyRJQ4YM0SmnnKKTTz45rroaGxv13HPP6bnnnovp73xZWZnKyso0f/583XzzzTrggAN08skna88994zo/rZgWzSamprU1NSkLVu2aPXq1frwww8lSX369NGvfvUrnXrqqRo4cGDU63YFdXWBj5G3KvQLG6xOyWd65XP5ZG12yYizDktWvlwRPE54vd5Oj92eAKHWbXm8HhmezkFXrzd8CNPr9UieDp+Zxxv2ib3H49W2XwyLN/zPGq/XI18EYdx08Pl87cHatq+92+1WVVVVSuuIZL9kPpdA9xXuhXMAEAqPIQDiwWMIgFjx+AEgHjyGQJJszZUaFGZOZWWlPI1d8/9LI314DAGPH+gKUv17yHjwNwEpE0knpVR2Notkr+6U8m5jmqbOOuus9mOOtzVixAj95S9/SXFVAPCLWbNmacaMGTGFQoPZsGGDlixZEtca77zzjn71q1/p/vvvT0h4y+12a/78+TrjjDN04YUX6vvvv497zWjU1NTomWee0W9+8xvNmzcvpXvHy+VzaW3TWtX5amWqc0jSKkvYoKcjo/W/RrM77lBoi2mVbI44VwEAAAAAAAAAAAAAIHXoGIqUiSQYarOl7lsykr0iqbmreeKJJ/T+++8Hvf7II48oKysrhRUBwC8eeughPfrooyHnOJ1OFRcXKycnR06nU/X19aqpqVF5eXlSHpfdbrf+7//+Ty+++GLYuTk5ORo0aJByc3PlcDjU3Nys6upqbdiwIeSLCRYsWKAPP/xQX3/9dSJLj0h9fb2uu+46rVmzRpdeemnK949FjadGLtMlZbmkzGrZWrJlbc6WxWeTLYLXNdkzW/9rtMT//eJ15sS9BgAAAAAAAAAAAAAAqUQwFClDMDT5NmzYoCuvvDLo9RNPPFFHHHFECisCgF+8/PLLQUOhgwYN0rHHHqtDDz1UI0eOlNXqf1S42+3W999/rxUrVuijjz7Sxx9/rObm5rhqam5u1mWXXaaPPvoo4HXDMDRx4kRNmTJFe+65p4qLiwPO83q9+t///qfPP/9cb775plasWOE3J5Zj4tv861//CnqtsbFR1dXVKi0t1cKFC7V69eqA85588kkNHDhQM2fOjLmOVPCZPtV56n4ZMEx5MurlyaiXxe2UrSVfNne2ZAbuBWp1SBabIflMGS3+x6TbfVaNrO/TurS1SQ6b/xHxzg5NSk2CoQAAAAAAAAAQOZ9HNld1yCkeR75kIaoAAACQTDzbQpdiGPEe+Bo5iyV8xzHTNMPO6UrOO+881dbWBrzWt29f3XfffaktKE0++eSTuO5fvny5zjnnnE5jBQUFKiwsjGvdYGw2W/v3ftt/LRZLSoPSvYlpmvJ6OwfBrFZrSh9/eqOqqirdc889Aa+dddZZuuCCC+R0OkOuYbPZNG7cOI0bN04zZ85UY2OjFi5cqBdeeEGfffaZDMOI6u+Nz+fTFVdcETQUOmnSJF111VUaNWpU2LVsNpt22WUX7bLLLvr973+vb7/9Vo8//rjefPNNv3mhBPvZNGHChLA1HH300brqqqv0zjvv6MYbb1RVVZXfnHvvvVdTpkxJ2uNZIlS5quRT4BCtz96iOnuZPM19lN3YP+AcZ7ZFNptVamyWAvwct5iS09saPHbYvbKG+FHvtdhlcWbJIvk9bgRitVo7/RmbPp+klpD32Kw22Wzb/Ln7TEn+odbOe9lks3V43IrgKYvNZpW2+R40gnytt93L0kV/Jnm93vbQddvX3mq1pvx7vK6uLuycZD6XQPfgdrtVXV3daSw/P192uz09BQHoVngMARAPHkMAxIrHDwCxMBrK5PzimZBzWva8RGY2/6+stzIafNIPoef07duX75FejuchCITHD3QFZWVl6S4hYl3zN7wxWrp0qUaPHq3s7OyY13C5XFq2bJn22GOPBFYGSRH9gPZ4QocgEinUkb9tHA5HCipJjOeff16vvfZa0Ot33nmnBgwYkMKK0mfixIkJX9Nut4cNrSUaQcXUMQyDr3eS/fOf/1RNTY3f+JVXXqkzzzwzpjWzs7M1depUTZ06Vd99953+97//RfXnePfdd2vBggV+43a7XX/+8591wgknxFSXJJWUlOi+++7Tl19+qRtuuEGrVq2SFPvf60jvMwxDU6ZM0dixYzVz5kxt2bKl0/XGxkY9+uijuv7662OqIxWq3dVh5zhduUGvZWS3Br3NptBdvy1Wj6xhvqxmZp5fcD+UbR9LDEsE91j8H38ieO2KLNveZxhhs6GGYUjb7BVpjdve1xV1DFYH6jqcTJE8Z3Q4HCl/LoGuLx3PMQH0HDyGAIgHjyEAYsXjB4Cw3JH9vzLxWNJ78T2CGPE8BDx+oCvoTgH1CH7t3PVVVFTonHPO0Z577qk77rgjrrXuu+8+7bPPPjrzzDNVXl6eoAohdc9gaHf5y1xRUaFLLrkk6PWDDjpIZ5xxRgorAoDO3n77bb+xXXfdNWGPTTvssIOOPvroiOd/+umnevrpp/3G7Xa7HnzwwbhCoR3tvvvueumll1J+fPuQIUOCPif673//G9ex9snU6GlUizdMh02PUzZP4H/MWR2GrHajtVNoc+h1TCN0cFSSvA6OkQcAAAAAAAAAAAAAdD/dOhjq8Xh07733aocddtDf//53eb1e3XPPPdq8eXNM623dulW33XabfD6fZs2apR122EH33ntvREeHIrxIOim5XOFDGonSkzqGXnLJJX5d4do4nU499thjKa4IAH6xYcMGrV692m/8uOOOS0unVo/HoxtvvFFmgGPGL7/8ch100EEJ3c/pdOrGG2/Un/70p4SuG87EiRMDdkCvqanRihUrUlpLpKpcVWHnZLb0CXrNmfXzU9tm18/HsQdns4V+MYrPapdp49WEAAAAAAAAAAAAAIDup1sfJb9p0yZdd911amxsbB9rbGzUDTfcEFMQ7q9//atqampajx81TdXW1ur666/XjBkzNHTo0ESW3itlZWW1f22Dqa+vT1k9dXV1YedkZ2enoJL4/Oc//9Fzzz0X9Pq1116rHXbYIYUVAUBnmzZtCji+0047pbiSVnPnztWaNWv8xvfYYw+ddtppSdv31FNPTdrawUyePFmLFy/2G1+2bJnGjRuX8npCMWWq0dMYco7hs8rhCt7F05ndGgw1G0N3CzUsXtmM0MFRn5NuoQAAAAAAAAAAAClVv1nGx3cqQ1JxkCnmfldKOQNTWRUAdEvdumNocXGx/vznP0uSDMNoDx0+/fTTWrlyZVRrrV69Wo888kinzmWGYejaa68lFJogVqtVeXl5IedEEtZMlEj26tu3bwoqiV1tba3OO++8oNdLSkp09dVXp7AiAPBXUVERcDw3NzfFlbT6xz/+4TdmGIb+8pe/yGLp1k+N/IwdOzbg+NatW1NcSXiGDI3KG6UsVz9ZPPaAczJcuTLMwF1mrXZDNsfP15pCB0NlCXNdks+Znu9PAAAAAAAAAAAAAADi1e3TD1dccYXGjBnTaczr9eqaa66Jap0//vGP7UeLm6YpwzC000476corr0xYrQgftKypqUlRJZHt1dWDoVdddZXWr18f8JphGHr88cflcDhSXBUAdBasU3RlZWWKK5EWL14c8Fj7fffdV9ttt13K60m2YD/HqqurU1tIhLweyazPkKN2gJw1hbK2ZEkdgqAZLcFfYNL5GHlfyH1s1tDHyJtWm3y2jMgLBwAAAAAAAAAAAACgC+n2wVCbzaaHH364PXTS1jX0tdde00cffRTRGp9//rnmzJnTqVuoJD300EOyWq0Jr7k369evX8jrZWVlKapE2rx5c9g54epNpwULFujxxx8Pev2cc87Rfvvtl8KKgNTymZLXNDq9+UKfDI00KSgoCDj+2WefpbgS6Z133gk4PnPmzBRXkhrBQrldVUND64t0DEkWr0OOhgJlVA9URmOBMlryZPUG7iQqSY72Y+SbQ+5hWLyyWUJ/XbwOjpEHAAAAAAAAACAprE6ZRbuEfJPVme4qAQDo9mzpLiARDjroIJ188sl69tln28Odpmnqqquu0ieffBL2/iuuuKL9/bZuoSeffLIOPPDApNXcWw0ZMkSLFy8Oer2qqkoulyslXS4jCYYOGTIk6XXEoqmpSWeddVbQwM/gwYN1++23p7gqILUWtAxWta9zR78CS7MOytiYpooQzIgRIwKO/+tf/9LMmTODBkeTYeHChX5jmZmZOvjgg1NWQypVVVUFHM/Pz09tIRFqqHf7jRnm/7N333FS1df/x9/33ik725e6NEFAEZRmb2BXLFGjJLEl1sQSS4zRxBSjKWos+amJfpOYWJIYTKICNhQTNVhQxIpiAQSUvsAWdnZ32r2/P4ZddpiZO7O7sztbXs889gF77+d+7lkgctl5zzmmAk0VMpV6hLwkmR5DXn+2Y+TDGetgjDwAAAAAAAAAAJ0kUCFNOTffVQAA0Ov1+I6hze68886WkENzOPTNN9/UY4895nrd3Llz9eqrryZ0Cy0rK9Odd97ZabX2ZbvuumvGNevWdU2oK5v7ZFNvPtxwww1atmxZ2vP33HOPysrKurAioGvV2L6kUKgkVdsFqrE7P1iOtqmsrEz539MtW7boggsuSDnavTPU1dVp5cqVScfHjx8vj6dXvFcmyZIlS1IeTzdiPp8iEVvhcCzpuCnTNRQqtRojH4pIMfcx8paVHD5tzTEt2d6Ae7EAAAAAAAAAAAAAAHRjvSYYOmjQIP3qV79KGil//fXXKxqNprwmFovphz/8Ycvnzd1Cf/3rX2vgwIFdUndfk65rXGvLly/v/EKyuE9FRYVKS0u7pJa2cgs8n3zyyTr99NO7sBqg662Mpv//5iqXc8ifr371qymPf/zxxzrllFP0gx/8QK+99poiEffQXkcsXbo05fGJEyd22j3z7cUXX0x5fPLkyV1cSWb1KbqFSpKVxeOqP+sx8ra8GcbI237GyAMAAAAAAAAZ1W/s2HkAAAAAnapXtce69NJL9eCDD+qdd95pOfb555/rD3/4gy6//PKk9X/605/02WeftYRIDcPQPvvso0svvbQry+5Txo4dm3HN8uXLdfTRR3d6LStWrHA9n02t+ZJuhLwkffTRR9p3331zfs9Vq1ZlXHPyySfL53Pv1njnnXfqsMMOy1FVyFad7c13CR3S5FhaEu4vW4ZMOap30n89q6PFqrF9ijmGLMPRAb6NCpjxLoQRx1CD7VHMSQyaWbbV0jm61Gx7MLHBthTtxPdatKem7ubss8/W3/72N1VVVSWdi0Qievrpp/X000+rqKhIkydP1uTJkzVx4kTtueeeGjx4cE5qWLNmTcrj48ePz8n+3c3ChQu1ePHipONlZWXac88981CRu1Rj5CXJI8v1OtOSvAW5GyMf8xEMBQAAAAAAAFx9uVBa+rg04XRpxEFtPw8AAACg0/WqYKhhGPq///s/HXjggS1BT8dx9Mtf/lLnnXeeiot3vNBfX1+vm266KWGEvGma+sMf/pCP0vuMKVOmZFzz4YcfdnodmzZtShlOai2bWrujTIHXzpRuZHFr1dXVXVAJdvbfphH5LqHL2DJV3Txm3pHWxYo0xqyTJG2KFWpROEXIsFVj6a8Wtn2s+ZJIf62LdV6YrD01dTdFRUW6++67dd555ykcTh/OCwaDev311/X666+3HBs4cKAmT56sfffdV/vuu68mTJgg02x7EHfDhg0pj1dUVLR5r+5u7dq1uu6661KeO/7449v169eZQqGYotHkEfBGFmPkfc1j5MMRKZo8ir410wrLkRRLs6VjmIp4/DLlyMhwXwAAAAAAAKBP+nKhjKXbJ9stfUyOlBj+zHQeAAAAQJfoXqmAHNh333118cUXJ3RU3Lx5s2699daEdbfddps2bdokaccI+Ysvvlh77713l9bb1wwbNkyDBg1yXdO642tnefvttzOumTp1aqfXAaDzrY0V5bsEbLf33nvrD3/4Q5uDmFVVVfrPf/6jW2+9VTNnztSRRx6pO++8UytXrmzTPnV1dSmPl5SUtGmf7sxxHL3wwguaOXNmyjdAFBQUdMvO6Om7hbZljLx7t1DDsOUzHTUZ0hJvLOXHh56IPtu2TGE7c2dRAAAAAAAAoM9pHfrczlj6WLxDaDbnAQAAAHSZXtUxtNnNN9+sJ554Qps2bWrpGnrXXXfpsssu09ChQ7V+/Xr99re/TegWOmjQIN188815rLrv2HvvvfXcc8+lPf/+++8rEonI6+280deLFi3KuGafffbptPsD6Dpb7AI12lbLOHnk18EHH6zZs2frtttu07x58xLeyJGtDRs26P7779cDDzygr371q7riiiuyGjff1NSU8nhPCIa+9957ac81NTWpurpaH374oV5++WXXztFXX311Vr9WXS0YjKY8nikYapiSr2D7mkxj5C3CngAAAAAAAEC7pQh9NjOWPiZnzRsy6takPy/RORQAAADoQr0yGFpWVqbbb79d3/rWt1rCn42Njbrhhhv05z//WTfccIMaGhpaQqOGYeiOO+5QaWlpnivvGw477DDXYGhDQ4PeeOMNTZs2rdNqePHFF13Pl5SU0D0W6DWMhHHyyL/Kykr99re/1SWXXKK///3vev7551VbW9vmfWKxmB577DG98MIL+u1vf6tDDjkk4/pUfD5fm+/d1c4444wO73Huuefq3HPPzUE1udXUGFMslmqMfHyQvBtfoSkZkiLR+IcL00zdlRQAAAAAAABABi6h0GbpQqEt5wmHAgAAAF2q142Sb3bOOefosMMOawl+Oo6jhx9+WI8++qgefPDBhFDoYYcdprPPPjvfJfcZxxxzTMY1L7zwQqfdv76+Xm+88YbrmsMPP1weT6/MTQN9jke2AoZ7YAz5sfvuu+sXv/iFXnnlFf3pT3/ShRdeqMmTJ7e5Y3Rtba2+853v6JlnnnFd5/f7Ux7ftm1bm+7X0xQWFurGG2/U9ddfn+9SUqoPphsjb2W8Ntsx8jIc+azk8CkAAAAAAACADOo3Sksfz81eSx+P7wcAAACg0/Xq5Nv//d//afLkyYpGozIMQ7FYTOecc45s227pJOr1enXffffludK+ZerUqRowYIA2b96cds3jjz+uX/ziF51y/7lz5yocdh8nm014FUD3V2aEtJ9/k0roFNit+Xw+TZ8+XdOnT5ckhcNhffrpp/roo4/00UcfafHixVq5cqXrHrFYTD/5yU+06667asKECSnXBAKBlMfr6+s79gV0UyUlJfrKV76iCy64QMOHD893OQnqI/WyTEsFZkANaYKhVjZj5APNY+SbXNeajJEHAAAAAAAA2qd4sDThdClDx9CsTDg9vh8AAACATtftg6F//etfO3T9vvvuq4ULF8owDBmG0RIKbe4Wus8++2jRokVatGhRu+/xrW99q0M19jWmaer000/XH//4x7Rrli5dqvfee09TpkzJ+f1nzZrler65vu5s1apVXX7P8847Tw8//LDrmpUrV2rUqFFdUxCQBUKhPZPP59PEiRM1ceLElmObNm3Sc889p3//+99atmxZyuuampp000036Z///GfK8wMGDEh5vK6uruNF55Hf71dJSYlKSko0dOhQ7bXXXpo0aZIOPvjgtGHYfHLkaEPjBkWciHyGX463UFYoIENGyxpDRsZgqC9gyjAkRWNSOENXYJNgKAAAAAAAANBuIw6SI2UcJ+/GmTCTMfIAAABAF+r2wdDzzjuvpbtnRzQHQVvv5TiO3njjjYxjxTMhGNp2Z599tmswVJJ+97vf6S9/+UtO77t8+XLNmzfPdc0RRxyhoUOH5vS+APKjzvYRDO0lBg0apG9961v65je/qblz5+pXv/pVyk6f77//vl577TUdcsghSeeGDBmScu81a9bkvN5c++STT/JdQs7UR+oVceL/vww7IakopEhhrTyhQllNRTJtjyzGyAMAAAAAAADdSwfCoYRCAQBAThgeOUUZuo8b3T4KB3SZHvP/BsdxcrJHc7fQXO2bi9BqX3TooYdq9OjR+vzzz9OueeSRR/SLX/xCw4YNy9l977jjDtm2eziEoC96o6MKvsx3CR22PFKm1bHSNl1Tbfs1TMGWzwdZDTrS/4VisVjCOsuyOvTf84neLRrvrW739cieYRg69dRTNX78eJ199tkpw6Hz589PGQwdO3Zsyj2XLFmS8zqRXnU4xf9XDFvRgnpFC+plRvzy1Q+W3B7RjDaMkTcj4mkNAAAAAAAAyIERB8lZ84aMuuzfbO+UDicUCgAAcqNogHTodfmuAugxekwwtCOBHbcgaK72RdsYhqGrr75aV1xxRdo1oVBIP/rRj/S3v/0tJ/f86KOP9Oc//9l1zdChQ3XGGWfk5H5Ad1LaC7pmFplRKZZ5XWtew97pc0elZkRRO3HstMf0dOjvg0IzpjYXhw4ZN26cfvCDH+jGG29MOpeuE/jo0aNVWFiohoaGhOMEQ7tO2A4rGA26rnHMqDyO+yOqL2DKMCXFbCmU4b9vVuIYeZ+ksdHWY+oNRUqHKr5hnNfwuu8JAAAAAAAA9EVfLmxTKFSSjLo1cr5cSDgUwA71G2S8drvrEueQa6Xiyi4qCACA3snMvCT/HMfp0Edn7Y2OueCCC9S/f3/XNY888oieffbZDt8rEonowgsvTOoSuLOrrrpKPp+vw/eT4uHXTB+rVq3Kyb2AvmCct0bT/GtVYiSGvEqNkEqNxFHSJUZY0/xrNc5b04UVoquddtppKiwsTDq+Zs2alH9Pm6apfffdN+X6tWvXdkqNSJSyW+hOfKESGRl6fLaMkW/MZoz8Th2CHanENlo+ijyFKvQWq9BT2PJhGj3iERkAAAAAAADoOl8ubNcYeWn7+PkvF+a4IAAAAABuun3H0HPPPbdD1y9atEgff/xxywj55o5wzT8fP3689ttvv1yUijYqLCzUT3/6U1199dVp1ziOo3PPPVcLFy5MOwI4G1dffbXefPNN1zXDhg3Td7/73XbfA0DnG2CFdETBGi2LluvTSLl28dRrkneLJOmDSH99ES3WOG+NdvfUyGR2dK/n8/k0adKkpA6hsVhMNTU1qqioSLrmiCOO0IIFC5KO//vf/9b3vve9zioVkmzHVk24xn2RY6ggVOq+xpD8hduDmw0dHyMf8xdnWAEAAAAAAAD0cR0IhTYzlj4mR6JzKAAAANBFun0w9MEHH2z3tTU1NRo3blxLGLR1OLT555s3b9Zdd92lsrKyXJWMNrj88sv1pz/9SR9//HHaNZs3b9ZRRx2l+fPna9y4cW3a37Zt/fCHP9S9996bce1tt92moqKiNu0PoOtZhrSHt0a7eurkbzUqfqpvsyZ4tyYcQ++XrvO0baf+czBjxgzdcsstCocTO88+/vjj+u53vyuvlxHinaUuUifbcf//pxUOyOu4/x54C7aPkbdtqSnsutYxM5yXZPtKXNcAAAAAAAAAfVr9Rmnp47nZa+njUsVoqXhwbvYDAAAAkFavnpP54x//WFVVVZLUMlL24osvThgvW1VVpeuvvz4v9UHyeDz64x//KMuyXNd98cUX2m+//fTggw+mHA+cysqVK3XCCSfojjvuyLj22GOP1VlnnZXVvgC6h1QBUEKhfU99fX3SMcuyUnYLlaSKigodd9xxScerqqr06KOP5rw+7FDkKVI/fz/XMe3+UOaQZnO30Ixj5CX5PDHX8443IMd0fwYBspEujN7a+++/n9U6AAAAAACAbqV4sDTh9NzsNeF0QqEAAABAF+m1wdBFixbpT3/6U0KX0GnTpun//u//NH369JZjjuPo/vvv1+LFi/Ndcp81bdo03XDDDRnXbdu2TRdccIGmTJmie++9V6tXr05a09DQoBdffFEXXXSRxo8fr+effz7jvkOGDNHf/va3dtUOAMivVatWJR2rqKiQaaZ/xLn00ktTviHht7/9bcr9cqW6urrT9u4JvKZXgwsGa3ThWHmDFTKjiZ1BzahXvmjAfRND8hdtHw7f4B4MNa1IxgddxsgjFz755BP98Ic/zLju5ptv1llnnaVPPvmkC6oCAAAAAADIoREHyZkw03WJUzrc/fyEmYyRBwAAALpQrwyG2ratSy+9NKkjz+23397yY/N4eUmKxWK69NJLs+5Eidz76U9/qq985StZrf3ggw90+eWXa9SoUerXr5/Gjx+vKVOmaNSoUSotLdVRRx2lv/zlLwqFMncSKygo0D//+U8NGjSoo18CAKCLLV26NOWbBKZOnep63ejRo/WNb3wj6XhjY6Ouu+46NTU15azGZqtWrdIZZ5yR8317ooZgTJ5QoXx1g+SvHSgrVCg5hqxQsSy5d+/0+g2ZliHZTofHyEuS7WeMPDrmjTfe0Le//W198cUXWa1fvny5vv3tb+vNN9/s5MoAAAAAAAByzCUc6ow5Vpp4ZvzHVOcJhQIAAABdrlcGQ++77z69++67Cd1CZ86cqf3220+StN9+++nrX/96yzlJeuedd3Tffffls+w+zTRN/fvf/9ZRRx3Vpuuqq6v1ySef6P3339fq1asVi7mPjG3N6/Xq8ccf17Rp09paLgCgDZYsWaIf/ehHOe3Gadu2br755pTnjjzyyIzXX3PNNRoxYkTS8Q8++ECXXXZZyhH17fXkk0/q9NNPTxli7YuC9RFJkiHJjPnkC1aooKZSvlCxDPdLW8bIqykkZXhDj8+Kup63PQVyTE+WVQPJPvnkE1177bVqbGxs03WNjY36wQ9+QOdQAAAAAADQ86QJhxor5st47XYZK+YnnSMUCgAAAORHrwuGbty4UT/96U8TOoJ6vV7dcsstCetuueUW+Xw+SWoJkP70pz/Vxo0bu7Re7OD3+/Xkk0/qa1/7Wqffq6KiQk8//bROOOGETr8XAPR1sVhMc+bM0YknnqjrrrtOH374YYf2C4fDuvbaa7V48eKkc+Xl5Vm9yaCoqEh33323CgsLk869/vrr+vrXv67333+/Q3UuW7ZMF154oa677joFg8EO7dVbRCK2wuHkN3EYjilvhm6hkuQrij+6OhnHyEdlZkiZ2oyRRwfYtq0bb7yxzaHQZo2NjbrxxhuTJhwAAAAAAAB0eyMOStsZtDVHBqFQAAAAII96XTD0+9//vurq6iSppSPoxRdfrNGjRyesGzVqlL773e8mjI+vq6vTNddc06X1IlFhYaH+9a9/JQR3c23q1Kl68803deyxmf/RCgDInVgspieffFIzZ87USSedpPvvv19ffvllm67/73//q1NPPVXPPPNMyjXXXHONSktLs9pvwoQJuuuuu1L+ffP555/rzDPP1NVXX61333036xqj0agWLFig7373uzr55JP12muvZX1tX1C/vVtoKlaGx1KP35DlMeKdQpvcg6GO6X5ekmKMkUcHLFq0SMuXL+/QHsuXL9eiRYtyVBEAAAAAAEAXqpycec3U8wmF9lWWX87gSYoN3EsNpbslfMQG7iVn8CTJ8ue7SgAAgF6vV83PfPHFFzVr1qyEbqGlpaW64YYbUq7/6U9/qgcffFC1tbUtXUNnzZqliy66SIcffngXVY1UfvSjH+m0007TFVdcofnzk8dOtEd5ebluvPFGXX755bKszF3JAACdZ/ny5brzzjt15513auDAgZoyZYomTpyoAQMGqLy8XGVlZQqHw6qvr9cXX3yhTz/9VK+++qq2bt2ads9jjjlGM2cmjzFyM336dP3hD3/QFVdckdTV07ZtzZs3T/PmzdPQoUO13377afz48Ro2bJhKSkrk8/kUCoW0detWffHFF1qyZInefvtt1dbWtuvXpEs4tgw7KsOx5RhmfJS60XXvEwqmCYZasmRkGCS/Y4x8WLLdx8h7M46R98uxvK5rADf//ve/c7LPY489pgMPPDAnewEAAAAAAHQrhf3zXQHyJVAhTTlXkVBIW6qqEk4NHDhQfj+hUAAAgK7Qa4KhkUhE3/3ud1s+b+4Wet1116l//9T/8KioqNCPf/xjXXfddTIMoyUcetlll+mDDz6Qx9Nrfnl6pN13313PP/+8Fi9erLvuuktz5sxp1yjePffcUxdffLHOP/98FRczNhYAupuqqiq98MILeuGFF9q9x4wZM3THHXckvDkkWwcffLAef/xxff/739fSpUtTrlm3bp3mzp2ruXPntqs+y7J06qmntuvaXDDDDbKaamSGgzJadUt3DEO2r0ixgnLZvsJOrSEUiikaTT02O1O3UEnyt4yRb3JdZ1pRWYyRRydqbGzUq6++mpO9XnnlFTU2NioQCORkPwAAAAAAAAAAAACQelEw9Pbbb9enn36aEAgZNmyYvv/977ted+WVV+ree+/VF1980XLs008/1e23367rr7++0+pF9vbdd1/9/e9/VygU0v/+9z8tWLBAH330kT755BNt2bJF9fX1CofDKi4uVklJiXbZZRftueeemjp1qmbMmKFdd901L3U7jns3s57m1FNP1ahRo1zXlJeXd0ktAHqWAQMGaNKkSVqyZEnO/9tYXl6u733ve/r6178u02x/58tRo0bpX//6lx555BHdd999Oe36ecQRR+iaa67R2LFjc7ZntoxoSN5tG2RGU49WNxxHVqheVqhetsevSEmlHE/nvFs7XbdQSfJkCIZaPkOW15AcSY1h17WO6X5ekmI+gqFov/Xr1ysWi+Vkr1gspg0bNuTteRUAAAAAAAAAAKDHCG6W3n3Afc3UC6SiAV1TD9DN9Ypg6KpVq/TrX/+6JRTa3C30pptuytiK3ufz6de//rXOOeechK6hv/71r3XWWWdp5MiRXfElIAt+v1/HHnusjj322HyX0iedeuqpee12B6DnGj58uP71r39p06ZNevHFF/XKK6/onXfeUXV1dbv33G233XTiiSfqjDPOyFko3ePx6Nxzz9XXvvY1PfHEE3riiSfSdhDNZNiwYTr55JN1yimnZAzVdxYz0iBv7ToZTuounUnroyH5ar5UpGyobG/uu4cGg6nHu5sysx8jHwpLtvvXk3GMvOXttPAr+oaGhoac7teejvgAAAAAAAAAAPRKhkdO0WA5jqNYLPE1H8vyxHNBRq+IOqE9nKiM4Eb3JY77a4VAX9Ir/mt5xRVXqLGxsSXUaRiG9tprL51//vlZXX/WWWfpt7/9rd59992WY42NjbryyivbPTIWAAAkGjRokM444wydccYZkqQVK1bovffe08qVK7Vq1Sp98cUXqq2tVTAYVGNjo/x+v4qKilRUVKQBAwZo991317hx4zRlyhSNGzeu0+osLCzUOeeco3POOUdr1qzRokWL9MEHH2jlypVat26dampq1NQUH2deWlqqkpISVVRUaNy4cZo4caL22msv7b777u0aa/+1r31N06ZN6/DXYERDbQqFtlzn2PLWrlO4fEROw5NNjTHFYqlr8cjKeH22Y+QNMybLcO9K2+ALaFntx65rRpeMlt8kPIrUCgtzG5wuKirK6X4AAAAAAAAAAPRYRQOkQ69TOBRSVVVVwqmBAwdmbA4HANihxwdD58yZo2eeeSYpfHHrrbe2aZ/bb79dRx11VELX0Kefflpz587VKaecksuSAQCApDFjxmjMmDH5LsPV8OHDNXz4cJ122mldcr/KykpVVlZ2eB/vtg1tDoU2Mxxb3m0bFK7IXdf0+mAHxsh7DXl825/zGkPuNzIznJdk+wqlxvZ3qwWGDBkiy7JyMk7esqyc/H8eAAAAAAAAAAAAAFpzfyW+m2toaNBVV12VNEL+iCOO0PHHH9+mvY444gidcMIJcpx4l6nmcOhVV12lxsbGnNcOAADQGcxwg8xo5oCk6x7RkMxI+8dlx5wdgTnHkRrSBEPbPEY+TdfRZp4MY+QdyyPH4p2k6JhAIKBDDz00J3tNmzZNgUAgJ3sBAAAAAAAAAAAAQLMeHQytq6vTxIkTW8KcUjzQedttt7Vrv9/85jeyrPg40+Y999prL9XV1XW8WAAAgC5gNdXkZp/G9u3TGGvUsrplWtewTo2xRjU2RmXbqce7Z+oWKkm+ljHy7mFXw4zJY7qPkY/5SpQhhwpk5Wtf+1pO9pk5c2ZO9gEAAAAAAAAAAACA1np0MLSyslJPP/205s2bp913312S9I1vfEN77713u/bbc889dd5558lxHO222256+umn9fTTT2vw4MG5LBsAAKBzOLbMcDAnW5nhoNSOcfTVoWo5clQbqdWq+lVaG1qtqL9BjpJDm5Ys9xo8hrz+7MbIG2Y4Y222vzjjGiAb+++/v8aOHduhPcaOHav9998/RxUBAAAAAAAAAAAAwA6efBeQC8cdd5yWLFmie++9V6ecckqH9vrlL3+pcePG6aqrrpLX681RhQAAAJ3PsKMyHPeumVnv5Tgy7Kgcy5f1NTEnprpIYqf1qBmWisKKFNbKEyqU1VQk0/bI3D5I3k3LGPlwRIrGXNeaVupx9c0c05LtDUi2e8AUyIZpmrrxxhv17W9/W42NjW2+PhAI6MYbb5Rp9uj36QEAAAAAAAAAAADopnrNK5Eej0dXXXWVRo0a1aF9Kisr9YMf/IBQKAAA6HGMdnT4zOV+NeGalJ1B45vZihbUK1YQ72hqZfEY6s96jLwtb4Yx8nQLRa7tscceuuOOOxQIBNp0XSAQ0B133KE99tijkyoDAAAAAAAAAAAA0Nf1mmAoAABAX+cYuX20a+t+1eHqjGuspiJJkifTGHlL8hY0j5Fvcl2bzRj5mK8k4xqgrQ444ADdf//9WY+VHzt2rO6//34dcMABnVwZAAAAAAAAAAAAgL6sV4ySBwAAgOSYHjmGkZNx8o5hyDGzf1Ssj9YrYruPczcjfpm2R0YWY+R9zWPkI1Ep4j5G3shmjLwv3tXRa3g1rHCY63qvQed4ZG+PPfbQP/7xDy1atEiPPfaYXnnlFcViO/7MWpaladOmaebMmdp///0ZHw8AAAAAAAAAAACg0xEMBQAA6C0MU7avSFaovsNb2b4iqQ0dQ6tDmbuFepri49w9uRwjb9jyme4j721fkbQ9iGoapkq9pRnvD7SFaZo68MADdeCBB6qxsVEbNmxQMBhUUVGRKisr2zxuHgAAAAAAAOix6jfIeO12FUgakWaJc8i1UnFlV1YFAADQ5xAMBQAA6EViBeU5CYbGAuVZr3W2/8+NYVsyIwWSMgdDDVPyFWxfk2mMvJXFGHl/ccY1QK4EAgHtuuuu+S4DAAAAAAAAAAAAQB9GMBQAAKAXsX2Fsj1+mVH3Tpuue3j8sr2FWa83ZGiXol0UtsOqDlerJlQjW4ldPK2mIhnb15oZgqH+QjPe4DMak8JR93ubGcbIG6Zsb1E2XwYAAAAAAAAAAAAAAL1C9vNBAQAA0CNESirltGEMfGuOYSpS0r4RPj7Tp8EFgzVYI+UNVsiMeps3lScUD2d6ZGXcZ8cYefduoTIc+awsxsgbRubiAQAAAAAAAAAAAADoJegYCgAA0Ms4Hr8iZUPlrV0nw3EPTiZcZ5iKlA2V4/F36P4N9TF5woWyQoVyPGHZVkSGEw97WlmMkfcGmsfIu3c9NbMYI28zRh4AAAAAAAAAAKBnCG6W3n1APsdRZSxxqpy10hNvBjL1AqloQJ4KBICeg2AoAABAL2R7CxUuHyFv3XqZsSwClB5/vNNoB0OhkYitcDgmKT4N3oj6ZEZ92z83MgZDfQEz3uAzZksh9zHxMt2/LscwFPMxRh4AAAAAAAAAAKBHcKIyghtlKP0IZMeJpjkDAGiNUfIAAAC9lOPxK1I6JOO6SMlghStGdjgUKkn19enDnFZexsjzuAsAAAAAAAAAAAAA6FvoGAoAANCbGUbGJbY3kLPbBV2CoZ5M70ky4h1DJWUxRj6iTF+Z7WOMPAAAAAAAAAAA3YrhkVM0OOMaAADQMfxtCgAAgJwIhWKKRtN18cxyjLwpybalJvcx8dmMkbf9jJEHAAAAAAAAAKBbKRogHXpdvqsAAKDXY7YmAAAAcqJD3ULVeoy8e7fQ+Bj5mOsSx1sox8g8uh4AAAAAAAAAAAAAgN6GYCgAAAByIhiMpj3nUYaQpiH5C5vHyDe5LjXNaMYx8jE/Y+QBAAAAAAAAAAAAAH0TwVAAAAB0WFNjTLFY+8fIewuax8g7cjKOkXfvKOpIsn0EQwEAAAAAAAAAAAAAfRPBUAAAAHRYfTA3Y+TVGJLhuK105PVkGiMfkGMyRh4AAAAAAAAAAAAA0Dd58l0AAAAAejbHkRpcgqGZuoXGx8jHh8PbDU2uY+JNK5oxZhrzl6Q9F7bDWlW/yvX6UcWj5DN9Ge4CAAAAAAAAAAAAAED3RDAUAAAAWdsa2ipHjsp95bKMeFfOxsaobDtdm09Dlty7d3r9hkzLiCdMm9zHxMvMMGZeku1PP0bekaOYk6HjqFxblgIAAAAAAAB9m+WXM3hSxjUAAAAA8odgKAAAALLiyNHm0GbFnJiqmqpU6itVha9C9fXpr7FkunYAlXaMkXcyjpGXvFbU9bztLZBj8ogLAAAAAAAAdJpAhTTl3HxXAQAAAMAFr5oDAAAgK3WRupZum44c1YZrVRuulWl5ZfmLZYUCMnaKgXoyDn6XfIXxNdG6oOvDqWlFZWZImdq+9N1CAQAAAAAAAAAAAADoCzK/Ug8AAABIqg5VpzxueyKKFFUrVL5Btpk4pt3K8Ljp8RuyPPEx8mbYvRuozAxj5iXF/CUZ1wAAAAAAAAAAAAAA0JsRDAUAAEBGTbEmNcYa3Rc5lgzbavnUkpXUQXRnzWPkI9uCGR9MPVbM9bzt8cuxvBl2AQAAAAAAAAAAAACgdyMYCgAAgIyqw6m7hbbmaSpKiIFm6hYqSf7tY+TDdfWu60wrKstwXNfYfsbIAwAAAAAAAAAAAADgyXcBAAAA6N5iTky14Vr3RY4hK1SYcMiTIRhq+QxZXkOxaFT+mOTaXNQMZ67TRzC0zRz3sK0kmZFGxSxfFxQDAAAAAAAAAAAApFFcKee4O/NdBdBjEAwFAADoaRxHisbiPxqG5LHiP3aSukidHLkHCK1QYcLYeFNm1mPk67dUqzRD/R5P1PW8bfnkePyuayTJY3hUGajMuKYvMKIheevWZ1zn3bZRVmONIiWVWf0aAwAAAAAAAACQVnCz9O4D7mumXiAVDeiaegAA6KX6xqveAAAAvUFTWE59g9QYTuz0aBhSwCejuFAqyH1nx3JfuTyGR9XhagWjwZRrPKHEbp0eWRn39ReachxHdkOT5NKR0jRjsjIEU7MdI28Zlip8FVmt7c3MSIO8tetkOHZ266Mh+Wq+VKRsqGxvYeYLAAAAAAAAAABIxYnKCG50X+K4N4sAAACZEQwFAADo7sJROVtrpXCab4Q4jtQQktMQknweGf3KJF/uHvMMGSrxlqjEW6KwHVZ1qFrV4Ro5iocKzYhfZizxfhnHyHsNeXyGamtqVGxmqNXKPEY+22AotncKbUMotOU6x5a3dp3C5SPoHAoAAAAAAAAAAAAA3Zj7K/YAAADIr6awnE1b04dCdxaOxtc3ZQ5TtofP9GlwYLBK6ofJGyyXEfXKEypKWJPVGPnC+GNosLpWHsP9kdTribmedyyPbE9BFtVDkrzbNrQ5FNrMcGx5t23IcUUAAAAAAAAAAAAAgFwiGAoAANBdhaNyNtdItvsY9SS2E78u2zBpG0UitiJhW55Qkfx1g2SGAwnnsxojX2SqoaFBvgz5RMOMyZR7MDTmK8l4P8SZ4QaZ0VDH9oiGZEYaclQRAAAAAAAAAAAAACDXCIYCAAB0U87W2raHQpvZTvz6dl7upr4+0vJzY/tHa1aGR0zTY8jjN7RlyxaVeHwZ1kZcz0uMkW8Lq6kmN/s05mYfAAAAAAAAAAAAAEDuEQwFAADojprCHe/4GY5K4czByrYK1qff09w+SN6Nv9BUOBxWpKFRvgxj5D2ZxsiblmxvwHUNtguFZYaDOdnKDAeldo6jBwAAAAAAAAAAAAB0Lk++CwAAAEAypz43o7qdYGNO9mkWCsUUjaYPBGbqFirFx8hv2VqVsVuoYdoyHfdwrO1njLzCUTlbajKvq6mV4c9NC1nDcWTYUTmW++8hAAAAAAAAeqH6DTJeu911iXPItVJxZRcVBAAAAGBndAwFAADobhxHagznZq9QbjuGunULlSSPLNfzpiWZXlu1tbUqyRAqtLIYIx/r62Pkm8JyNm2VIu6dVeNyEwptZtAxFAAAAAAAAAAAAAC6JTqGAgAAdDfRWDwc2g0Fg+k7eBpZjJH3FZqqqamRR4b8pnuI1PLEXLOMfX6MfDgqZ3ONZGf7Z8X996atHIP3mAEAAAAAAADYieGRUzRYjuMoFkv8frJleWQYhmQQUwAAAOhsPHEBAAB0N900FNrUGFMslr5LpCfLMfIb11ar1PK6rouPkXfvGGr7ipTrsGOP4UjO1to2hEIlxzbkKDe/Yo5hyDH5pwQAAAAAAL1W/UbJW+5+vnhwl5UDoAcpGiAdep3CoZCqqqoSTg0cOFB+vz9PhQEAAPQtvJoLAADQ3RjdM+xYH8w0Rt49GGqYUlOkXpFIRCUB906flpW+M2mzmL8k45pm4XBYn3zyidauXau6ujpt27ZN0WhUgUBAgUBA/fv317BhwzRs2DCVlGS/b96Ew1I4869RIkN2zCvLcv99zIbtK4r/hgIAAAAAgN7ny4XS0sdl7X6K5N017XlNOF0acVDX1wcAAAAAyIhgKAAAQAZPPPGEfvzjH3fK3kOHDtWLL76YeNBjxcOh2zuHzp4/Tz++49ZOuX9rs2fP1vjx41OecxypwSUYamwfJN+sumaLTvvmMYpGk8OLM087Tb+85CrXWixv1H2MvGHK9ha67rF582Y98cQTev755/XZZ58pEskuEFlZWam99tpLe+21l/bff39Nnjw57dp77rlHL730Ulb7dqZTj5mhW669PuO6aMyXk2BoLFDe4T0AAAAAAEA39OVCGUsfkyR5P5ujoiFHKdhvUstpa90iGZ/NiX+y9LH4t28IhwIAAKArNFZLnz7pvmbcyVKgomvqAbo5gqEAAADdjWFIAZ/UEOryWwejQRV5ipKONzZGZbuMLffISvj8+f8+nTIUKkkvv/w/xb59uSzLSnleRpZj5NN0Vq2trdXtt9+uOXPmpK3BzYYNG7Rhwwb95z//kSSVlZXpsMMO0/nnn9/mvbobO+aR7VgyjVj79/D4M4ZyAQAAAABAD9QqFNqs3/r/SpKC/SapaOsH8m7/vJlBOBQAAABdJRaSsfED1yXO2OO6qBig++vWwdAFCxbku4RuZfr06fkuAQAAdBGjuFBOFwdDG2ON+iL4hbymVxW+CpX7ymUZ8fBmsN49qGntNEb+2RfmpF27eesWvbJ4kQ4/IPULBpYnc5jT9henPP7aa6/pRz/6kaqqqjLuka3a2lotWLCgVwRDJSkcDsjvD8pwa8mahmOYipRUdkJVAAAAAAAgr1KEQpv1W/9fFVcvka9pU8rzhEMBAEDOFFfKOe5OhUKhpNd6Bg4cKL/fn6fCAKDn6dbB0MMPP1xGmk5QfY1hGO3qeAUAAHqoAp/k80jhrvv7vy5Sp4ACitgRbWrapKqmKpX5ylTmLVdDQ/o6DBkJwdClny7RytUrXO81+/l5LsFQ926WjmEo5kvuavrKK6/ou9/9rsLhcNprLcvSoCGDVFJWooLCAjU1Nqm+rl41W2vUUN/get/ewrEthcOF8vka2hQOdQxTkbKhcjx80wUAAAAAgF7FJRTaLF0otBnhUAAAAADoXrp1MLSZ47S9mxEAAEBn+93vfqeBAwd2aA+fz5f2nNGvTM6mrWnP33PDLzWwf/80FxsyKkplWLa8detda4iUDlHEMOQZmvho6MhRTbhGNeEamSU+eZqKZYUDSddbO42Rf3b+HNf7SdJLb76u6rpaVZSW7VS3I1Ppg51S8xj5xA6ly5Yt0+WXX54yFFpYWKivfvWrOv7447X7nrtrbXhtyn3Xf7leyz9ertUfrNbLL76sLVu2ZPw6vva1r+m44+IjKYYNGyav19tyLhp1VLUpddh0+YpPde+9tyUdv+GGG7TH7uNVtyl9ENc0bJWYwYRj/crKM9bamh3zKBQqks/XmNVYedvjV6SkklAoAAAAAAC9Tf1Gaenjudlr6eNSxWipeHBu9gMAAAAAtFuPCIb29a6hBGMBAOiexo8fr+HDh3feDXweGQPKpTTPQhPG7qZhlUOST5hG/LoCn4xYWP6tZclrWgn1G6VNkVptDm1Ou8b2hGVbEVlKDoZ6WnULDYVD+u+C55K/FJ8vIbQZiUT01H9f0Le+OjNhnWVFlenJL9UY+V/84hcKhUJJxw877DD98pe/1KBBg+L12SGly50OGTFEQ0YM0bmnn6tf3vRLLV68WI8//rieffbZtLUMGTJEQ4bEfw9Gjx6dMMIkErG1dk19yuvCkdRFjBkzRpMnT9HWNZG09zTkqJ+nVkYHnxEd21IoVCxrcLGsplqZ4WDCno5hyPYVKRYol+0t7NC9AAAAAABAN1U8WJpwupShY2hWJpxOKBQAAAAAuokeEQzty8HIvh6KBQCgzyvwSaXJY9PT8nlk9CuLj6HPkuPEO4O6L5I8TanqSBwj/79X/6P6+m0JK/r3G6Bjjj1ajz76aMLx2c/PSw6GetN3ypSaw4qJwdDXX39db731VtLaI488Ur/73e9kWVbSuUxM09T++++v/fffX9ddd53mzJnT5j06iyND8vukpuQgbJsF/LJ9RfEurI4tw47KcGw5hinH9CR1ZgUAAAAAAL3QiIPkSBnHybtxJsxkjDwAAAAAdCO80gsAANDdWVk+svUrlVHZv02hUEkKRoOKOu6BTCsSkOEkByw9Oz1OPvvCnKQ1Rxx+pI488sikN7x88vlyfbTssx0HDEemkb5TpiQ53kI5O4UV58+fn7SusLBQv/rVr9oVCt1Z//79dc4553R4n1xyCpM7t7aHUdyqE6hhyrF8sj0FciwfoVAAAAAAAPqSEQfFw53tQCgUAAAAALqfHvFqr2EYnf7RGTXlYk8AAIBsGX5vu66ri9RmXGOl7BYqebQjeLlh4zq98/6ipDWHTj9EAwcO1D6TpiSdmz1/x5h2y4pmHI8eSzFG/pVXXkk6duSRR6pfv36ue/VoPl+bA8DJe3jiHWkBAAAAAACkeDi0dHibLnFKhxMKBQAAAIBuiFHyWcgU0GxdX+u1qa5z+1ry/XUCANCVmpqatGzZMq1cuVJ1dXWqr6+XJAUCARUWFqqyslLDhg3T8OHD5fMRXutMAatQ9U40bddQI+aRGfWnOiPLMKXtjzDz/jM36Xlm7JjdNXLkLjJl6LRjZ2jx++8mnH/6xf/qum9fJp/PJ8sbc63TkZLGyDuOo40bNyatHT9+vOtePZ4hGf3K5GzaKtnteIY0DRn9ynJfFwAAAAAA6Lm+XCijbk2bLjHq1sj5ciHhUAAAAADoZrp1MHT69Old0jXz888/15dffinDMNKGPHcOOfh8PpWWlrZ8FBUVKRgMqq6uruUjHA4nXNO6C2jzfs33NAxDI0aM0K677tpZXyYAAHnX2Niop59+WnPnztW7776rWMw9CCjF/84dP3689tlnHx199NGaOnUqXbVzrMJfobLCQaqP1GtreKsaog0J5z1NxUr1K+7RjlCo4zia98LcpDVHHn60JKnI49Vxhx6mX/3+LjU0Nracr91Wp/8ufFXHH36ETCPcsl8qjrdQjpk4Gr6mpkbRaHKgtaSkJOUeHsOjAf4B6W+yfU0+ZfNeoUiTI6vEI2NAuZzNNW0Lh5qGjAHlHe84CgAAAAAAeo8vF8pY+li7LjWWPhb/lg7hUAAAAADoNrr1q8Evv/xyp+4fjUZ16623auHChWk7fTqOI9M0dfjhh+vggw/WlClTNHnyZI0dOzbj/itWrNB7772n9957TwsXLtTLL78s27aT7tEcDt24caMuuugiXX/99bIsK922AAD0SC+++KJ+9atfad26dW26LhwO6/3339f777+vBx54QN/4xjd00003dVKVfZchQyXeEpV4SxS2w6oOVas6VCNHjqxwYcprWo+Rf+f9RVq/MfH31rI8OmTagZKkEsunQr9Pxx56mOa88FzCutnPz9OJR05r1xj55mernW3dujXlccuwNLBgoOt98ikWleo2pe7c2tq2zVE11hkqGeiVZ1A/OVtrpXDm6+TzxDuFEgoFAAAAAADNOhAKbUY4FECL4Gbp3QfkcxxVxhK/Z2mt9EiGIU29QCpyfwM/AAAAOqbPviK8efNmnXLKKXrjjTckJXbwbP58zz331HnnnaezzjpLQ4YMafM9xowZozFjxuj000+XJK1fv17/+Mc/9PDDD+vDDz9MuJdhGAqFQvr5z3+uefPmae7cuRowgIdhAEDv8Ne//lU333xzTvYKhUI52Qfp+Uyf+nkGqmFDgWxPRIaTql9o4hj5Z+bPSVqx3z4HqrSsRIakYo9XknTqMcclBUNfe2exNtds1LBBqbt8NrNTBEPLy8uTur5L0ptvvqlLLrnEdb/uqH5LVLGh2XX/jIYd1ayPqGyQR97K/lJTWE59g9QYTmw7ahhSwCejuFAq8HVS5QAAAAAAoEeq3ygtfTw3ey19XKoYLRUPzs1+AHomJyojuFGGJDPdEieLN7kDAACgQ9I9i/Vqy5Yt0/7776833nhDjuO0BDObQwX9+/fXH//4R33wwQe65ppr2hUKTWXIkCG65ppr9P777+tPf/qTBgwY0HLv1j8uXLhQ+++/v5YvX56T+wIAkE8vvviiayjU7/dr7Nix2meffVq6c++2224qKirqwiqxs/r6iAwZsqKpg4RWqzHy9cFtWvD6f5PWHHXkUZKkIssrc/sw+v0nT9XQwZUJ62zb1uznn0u6PmGNt0COmfyeJsuyNGLEiKTjCxcu1KJFi1z37JbaMBFekhxbqt0UVTTsSAU+GQPKZQwfKGNIfxmV/eI/Dh8YHx1PKBQAAAAAAOyseLA04fTc7DXhdEKhAAAAANBN9Llg6KZNm3Tcccdp1apVktQSCJXinTvPPvtsffbZZ/r2t7+dMO49lwzD0EUXXaRly5bpm9/8ZksotPmcJK1atUrHHXecNm7c2Ck1AADQFSKRiH71q18lHfd6vfrGN76hf/7zn3rnnXf09NNP65FHHtEDDzygRx99VE899ZQWL16s//znP7rrrrt0yimnqKKiIg9fQd8VrI+4nvcaOx4j//u/5xQKNSWcLyku1dR9Jsd/7tkRSDQMQycfdWzSfo8/mxwsbc32p+8metBBqUeUXXHFFVqwYIHrvr2BY0vbqlq9w94wJK9H8nnjP3bSMy0AAAAAAOglRhwkZ8JM1yXhgkGu550JMxkjDwAAAADdSJ8aJW/btk499VStWrUqIfTZHMy88cYbdcMNN3RZPaWlpXr44Ye1++6762c/+1lS59CVK1fq1FNP1euvv95pIVUAADrTG2+8oXXr1iUc8/v9+stf/qJ9993X9VrDMDR8+HANHz5cM2bMUDgc1jPPPKPq6urOLLndHEeKRm3ZtiPTNOTxmBnzeI4j2VFHji0ZpmR6jG6R4QuFYopGbZcVhixZLZ89M3920oojph8jy2PEx8hbiZ0qTznmOP3hH39NOLZyzTotev8j7T95z5R3jPmSx8g3O/XUU/XPf/4z6Xhtba2+853vaL/99tPXv/51HXbYYSotLXX5unquaNhRuNGWL9Dn3vcFAAAAAAByYcRBciQZSx9LOrV1yFEK9pukoq0fqN/65Df3EgoFAAA501gtffqkvLat/qFQwinvJr9kmtK4k6UADWUAIJM+FQz9f//v/+mNN95IGQr9wQ9+0KWh0NZ+8pOfqL6+Xr/5zW+SwqGLFi3S7bffruuuuy4vtQEA0BGvvvpq0rELL7wwYyg0FZ/Pp69+9au5KCtnjj766A5d/6+H5mnI4GE7DhiSr9BUoMTMKuB39LfO6ND9W7v55pt12mmnScrcLbT1GPmVq1fo408/TFpz+BFHSJICllfWTmnXUcOGa+qEvfTu0sTr/v3sf1IGQ22PX47lTVvP1KlTdfjhh+vll19Oef6tt97SW2+9JY/Hoz333FOTJk3SpEmTtOeee2rXXXftNW/AadpGMBQAAAAAAHRAinBocyhUkoL9JqmkpETez+a0nCcUCgAAcioWkrHxA1mSCtMsccYe15UVAUCP1WdeOd6yZYt+/vOfpwyFHnLIIbr11lvzWF08jHHooYcmjZV3HEc33XSTNm/enNf6AABoj/Xr1ycdO2J7YBApOFI4aKt2Q1TVayOKhp28lBEMRl3Ptx4j/2yKbqEjho3U2N1GSUocI9/aqcck/6P92ZdeV0NjU9Jx25++W2izm2++WSNGjHBdE41G9f777+tvf/ubrr32Wp1wwgnab7/9dO655+qee+7RwoUL1dSUfP+eItRgy8nPHxkAAAAAANBbbB8r78hQZPdTW0KhzWJD9285TygUAAAAALqvPhMM/f3vf6+Ghoak44Zh6N577817pyi3OpqamvS73/0uD1UBANAx9fX1SceKioryUEnPEw07qlkfUaTRbaR77jU1xhSLud+zeYx8NBbV/JeeSTp/zJHHK+bEu46WpOn0OeOwI+T3JYZGg42NevrF5C6zMX9Jxrr79eunBx98UBMmTMi4trX6+nq9+eabuu+++3T++efr4IMP1vXXX69Fixa1aZ9uwZHsKMlQAAAAAADQQSMOkg65VrGh+7ueJxQKAAAAAN1Xnxkl/6c//Sllt9Bjjz1WEydOzGNlO0ycOFHHH3+8nn322aSuoffff79uuummPFcIAEDblJaWJh1bsmSJRo8enYdqeh7Hlmo3RWXHuu6e9UH3MfJmqzHyCxe9oq3VWxLOG4ahww9vHiPvkcdI/T6k0uISHXnQoZr3vxcTjj827z/6+olHt3xuWz45VuquozsbPny4Zs2apfvuu09/+9vfUr4pKJOGhgbNnj1bs2fP1v7776/rrrtOe+21V5v3yRena3PEAAAAAACgN6rfIOO121UgKd18FueQa7uyIgBAb1JcKee4O/NdBQAAvV6fCIYuXrxY69evbwlZtg6Inn322XmsLNlZZ52lZ599VpISat24caPeeust7bfffvksDwCANhk7dmzSsbvvvlv777+/hgwZkoeKcutnP/2N+vUbkHGdX76Ubdr7VwzMeK1jS011qZOh99zwSw3s37/lc6N/meSxEtYYdkTeuvWu94iUDtGIUWPkOFJDhmCoz7Sk7eHDVGPkp0zcV+X9ixVzwirJEOj86rFHJwVDF72/VKvWrNOo4UMlZTdGvjW/36+rr75a5557rh555BE99dRT+uKLL9q0R0stixbp61//uq655hqdc8457dqjq6XJ4QIAAAAAAAAAAAAA+pA+EQydP39+2nNHHXVUF1aSmVs9L7zwAsFQAECPcthhh+n3v/99wrF169bplFNO0QUXXKCZM2dqwIDMwcruaszYcaocPNR1jSVLBUo9Tj1bsTQdQyeM3U3DKncEbI0h/SVv4uOdEQvLv7XMdf9Qv1FyLJ8aGqKybfdR5M1j5LdWb9HCt5LHvh971AmKOWFJUonHPRh62EFTNbBfhaq2Vicc//ez/9W13/mmpLYHQ5v169dPV1xxha644gp98MEHev3117V48WK9++67CgaDWe9j27Zuv/12ffHFFzrjjDPaVUuXMSTTY2ReBwAAAAAAAAAAAADo1fpEMPTDDz9s+XnrbqEVFRWqrKzMR0lpDR48WP369VN1dXVCrVJ89C4AAD3JxIkTdcghh+i1115LOF5XV6e77rpL99xzj6ZOnaqDDz5Y++yzjyZNmqTCwsJ23au+vl7Lly9v17W77LKL+vXr165rM/HIyryomwjWZzFGfnu30Of/+5RisWjC+UBBQAcfdJBsNarAtOTN0L7S57N16rGH6f5H5yQcf+L5l3TNRWfL8Pplewra/HXsbNKkSZo0aZKkeNBz1apV+uijj/TRRx/p3Xff1dKlSxWJuH/t//znP1VeXq4ZM2Z0uJ7O4i80ZZALBQAAAAAAAAAAAIA+r08EQ5cuXZry+KBBg7q4kuwMHjxY1dWJnbMcx9HHH3+cp4oAAGi/m2++WV//+te1cePGpHO2bevtt9/W22+/LUmyLEvjxo3T/vvvrwMPPFAHHnigCgqyCwZ+9NFHOvfcc9td42mnndaua90Z8qQcIt/92Lajhoao6xqf5ZG2dy999oW5SeenHXyUTL8t287cLdQwYzKcmE6fcWRSMHT9ps1a8Na7OvSIo9v0NWTDNE2NHj1ao0eP1le+8hVJUkNDg1566SXNnj1br76a3AW12cMPP6yDDz5YpaWlOa8rFwpKesafNQAAAAAAAAAAAABA5+oTrx5XVVUldN90nPiI1EAgkK+SXBUUFLTUKO3ocrpp06Z8lQQAQLsNHjxY//znPzVlypSMa2OxmJYuXaqHHnpIl1xyiQ455BBdf/31+uijjzq/0E5gqGe0b6xq2qSaYDDh+SMVjxN/dPzokw+06osVSeePO+pERe2QJKnYcg+GWp54CHWPMaO0526jk87/+9n/yva1b4y8m4gd0erg6oSPKqdKex2+l352989010N3adSoUSmvbWpq0pNPPpnzmnLB4zPkC/SJR3sAAAAAAAAAAAAAQAZ9omNoXV1dwueGYchxHAWDwTxV5C4YDCaNkZekbdu25aEaAAA6rrKyUrNmzdIzzzyjBx54IG03750Fg0HNnj1bs2fP1rHHHquf//zn6t+/fydXmzs9IxYqbYtsU5OxTX5zsEw79eOhKVPO9jHyz86fk3S+qLBYps/Rp59+Kq9pqsnvHur0+ZtkKB4OnbrnOH207POE8y+8+qaqG8IqK8vtG3ls2WqINqQ9P3L8SD3yr0d04bcu1CeffJJ0/o033tA555yT05o6yjClkoF94rEeAAAAAAAA3YHhkVM0OOMaAAAAAPnTJ57Im5qaUh5fu3ZtF1eSnXR1hUKhLq4EAIDcMQxDJ510kk466SQtW7ZML774ot5880299957amhIH9RrNn/+fL377rt64IEHtNtuu3VBxR3n3n+zezGjvrShUEnybx8jHwo16cUFzyedDzbU6+prL8tZPeFwRE899VReQpjFxcW64447dMoppygWiyWcW7t2rbZs2dJ5AeU2pokNUyob5JHH11NiyAAAAAAAAOjxigZIh16X7yoAAAAAuOgTwdDi4uKWrqGO47R042xoaNDy5cs1duzYfJaXYMWKFS0dQ1vXKklFRUV5rAwAgNzZbbfdtNtuu+niiy9WNBrVxx9/rMWLF+vtt9/WG2+8ofr6+pTXVVVV6eKLL9aTTz6p4uLEjpQHHHBAyg6P+eT0oGio1eTe4dOSKUfSy6/9R/XBruli/sQTT+StO+fYsWN14IEH6rXXXks6t2HDhk4Lhhb3j4c8o+HMf3Y8PkMlAwmFAgAAAAAAAAAAAAASmfkuoCtUVFSkPff888kdr/LJrR63rwMAgJ7K4/Fo4sSJOv/88/X73/9eCxcu1J///GfNmDFDppn8qLJu3To98MADeai0PRxFZee1gpgdzbjGcExZ4YK0502ZcrY3zkw1Rr6zLF26VJ9++mmX3W9n++yzT8rjzW846gyWR6oY5lVZpUf+IjO5g6gh+YtMlVV6VDHMSygUAAAAAAAAAAAAAJCkTwRDd999dzlOctclx3H04IMP5qGi9FLV09w5tKeMzQUAoCO8Xq8OPfRQ3XXXXZo1a5b69euXtOapp57KQ2XtE1Us86JO1BRryrjGDAdkuMwwL/DGm8yv37hW737wVs5qy8bjjz/epfdrLV1XUNvu/LCvL2CqdJBHA0b61G+4VxVDveo33KsBI30qHeSRL9AnHuMBAAAAAAAAAAAAAO3QJ0bJ77XXXpo/f37L581BS8dx9O677+rZZ5/VCSeckMcK4+bNm6e33367pbad7bXXXnmoCgCA/Jk8ebJ+/vOf66qrrko4/uWXX2rjxo0aPHhwnirLXkwx2fLIdAleZmJZ7b9/kbdY0mb3/UMB176mlmPKljTvhblJzyjFxSWa88h/tc1eJ8nRyECpAmb6R0yPNyyvpzHlufsfna1f35v4JpmnnnpK1157rbxer+vX0Bnq6+tTHi8rK+uyGgxDsrx0BQUAAAAAAAAAAAAAZK9PBEOPOuoo/fa3v0063hzAvPLKKzVt2jSVlJTkobq4bdu26corr3Rdc+SRR3ZRNQAAdB9HHXWU/H6/QqFQwvHNmzf3iGCoJIUUUYF87YqGGqZUUNqBZGg293DS72/KlB2Nv7Fm3gtPJp0/7OCjJSsi2Y48hukaCpUkyxuVkt//Ikk66chpuuX/Hk7oyFldXa0XX3xRxx13XHZfTA6tWrUq5fHy8vIurQMAAAAAAAAAAADo8wL95RxybcY1AOL6RDD08MMPV3FxsYLBYEsYtLlrqCStXLlSZ599tmbPni2rIy252ikWi+mcc87RihUrErqFNtcnSYWFhQRDAQB9ksfjUWlpqaqqqhKOd8U471yxZStsROSXN20oMhXDlMoGeWR2/eNJiwKfRwpLb7/3pjZsWpd0/ujDj1coFpQklXjcu3oahi3TiaQ9P2TQAO03ZaLefOf9hONPPPFEzoKhlmGpwleRcU04HNZ///vfpHOlpaUaMmRITmoBAAAAAAAAAKDPaayWPk1uRJFg3MlSwP17+QD6IMsrFVfmuwqgxzDzXUBXCAQCOuuss5JGn7YeKf/MM8/o61//upqamrq0tlAopDPPPFNPPfVUyhHyzTWeffbZCgQCXVobAADdQX19vbZu3Zp0fNCgQXmoJpHHk11i0+uzNGhogSqGerMeC+7xGSof4pU3kN/HNcuJ3//Z+XOSzvXvN1BTJ++riN0gSSq2fK57mZ5oxvudeOKJScdeffVVbdq0Ke01F110kd54442Me0uSx/CoMlDp+uExPLrvvvtS/rnbd9998/JGIgAAAAAAAAAAeoVYSMbGD1w/FAtl3gcAALjqE8FQSfre977X8iJ+606crcOhc+bM0cEHH6y33367S2p65513dPDBB+vxxx9POte6Rsuy9L3vfa9LagIAIJduuukmffzxxx3a4+9//7tisVjCscGDB3eLYGj//gWZ1wwIaNiwIvl8ljw+Q6WDMjdsLxngUcUwrzy+9gyfzx3TMGVHpPrgNi1Y+GLS+SOnH6eo0yRHjizDUKHl3jHUyhAMdQxDx55wkrzexH1isZjmzp2b9rpFixbpvPPO09lnn62XXnpJ0WjmAKqbv/71r/rjH/+Y8txRRx3Vob0BAAAAAAAAAAAAtNHy56XVCzKvW70gvhZA3xglL0l77LGHLrroIv3xj39MCF1KieHQ9957TwcccIDOO+883XzzzZ0SOqmqqtKPf/xjPfjggwlj7dN1C73gggu0xx575LwOAAA629NPP61Zs2bpoIMO0qmnnqojjzxSJSUlWV3rOI5mzZql3//+90nnTjzxxKS/z/PBMJRxNHxBQWJ3yWzK9hZk97UtXb5MVdU7uloam8qknbqYGnZE3rr1rvusaypXxLZUUlKq4cNHthwP+LxSSPrPy/MUCiV3VT/m8BMUtuNj5Istn1yrNhyZSj9GXpJsX5HKS/vp0EMP1UsvvZRwbvbs2fr2t7/tev3bb7+tt99+WwMGDNCJJ56ok046SXvuuadMM7v3Qn344Ye666679Oqrr6Y8P336dE2YMCGrvQAAAAAAAAAAAADkwPLnZayYL2n7S7Mjp6det3qBjE/m7lg39riuqA7otvpMMFSSbrnlFj3zzDNau3ZtUhCzdTjTtm09+OCDeuSRR3TCCSfo7LPP1kknnSSfz308qptwOKxnnnlGjzzyiJ599lmFQqGW++9cS+ugy7Bhw3TLLbe0+74AAHQHCxcu1MKFC+X1enXAAQdo0qRJ2muvvTRq1CiVl5erpKREjuNo27ZtWr16td5++209+eSTWrZsWdJe/fv3zxgQ7Cuu/MXPcrrfQQdN189vuKPlc0umYnJSjpEfPmyk9hi3p7Y2rZIklXjcn5MsK+IeHJVk+4slSSeddFJSMPTzzz/XO++8o7333jvj17F582Y9/PDDevjhh1VUVKRJkyZpypQpGjJkiMrLy1VRUSHbthUMBrVp0yZ9+umneuONN7Ry5cq0e44cOVLnn39+xnsDAAAAAAAAAAAAyJFWoVBJMj6Zmzoc2ioUKknGivmEQ9Hn9algaHl5uf7xj3/oqKOOUjQaTRsObf55KBTSnDlzNGfOHBUXF2vvvffW5MmTNWXKFO2xxx4qLy9XaWmpSktLVVRUpGAwqLq6OtXV1ammpkaffPKJ3n//fb333nt65513VF9f37K3pIR7NWt9zOv16h//+IcqKiq65NcHAIDOFolE9Oqrr6btyJiJz+fTrbfeyt+NXcAyTcXCjlauXq6PP/sw6fzRh81QxG6QI1tmNmPkvTHX845hyPbFg6FHHnmkCgsL1dDQkLBm9uzZWQVDWwsGgy3B5PYaM2aM/vSnP6murq7dewAAAAAAAAAAAABog51Coc2SwqE7hUJb1hEORR/Xp4KhknTooYfqoYce0jnnnCMpuVtnczh059Dmtm3btGDBAi1YsKBd903XETRdKNQ0TT3wwAM69NBD23U/AAB6m7KyMt1zzz064IAD8l1KnxDwe+U0Ss+k6BYqSccccYJCseYx8l65DmvPZoy8t1COEd8lEAjoqKOO0lNPPZWwZt68efrxj3+sQCCQcHzatGl65ZVXFA6HXe/RVh6PR+ecc44uv/xyeb1egqEAAAAAAAAAAABAV/EG0p4yPpkrJxqSPP6UodBs9gB6uz4XDJWkM888U6FQSN/5zncUi8VShkMlJQREWx9vj9b7pNqrdSjUsiz94Q9/0Nlnn93u+wEA0B18//vf1wsvvKC33npLkYh7MDAdr9ermTNn6sorr6RTaBeyHFNN0bDmv/h00rndx47XLsNHacv2MfLFVqYx8lEZcn+Oah4j3+ykk05KCobW19fr+eef16mnnppw/N5771UwGNQrr7yil19+WYsXL9aaNWtc7+dmwIABmjFjhs4880yNGTNGkhQKhdq9HwAAAAAAANCrBDdL7z7gvmbqBVLRgK6pBwAA9E4jp8uR0gY/jeXPuV7u7HFK8sh5oA/pk8FQSTrvvPM0dOhQnXHGGaqpqUk51n3nbp47hzvbKl2wtPW9y8rKNGvWLM2YMaND9wIAoDs488wzdeaZZyoYDOqdd97Re++9pw8++ECff/65NmzYoFgs9XjxoUOHasKECTr00EM1Y8YMlZeXd23hOzn88MP16KOPJh0fOHCgqjbltktlKqeddppO+8rJctZvcV1nDOkveRMf74xYWP6tq1yv+7xhgML2jus8HlPRkKOt1Vt06olfT1o/ccJURexGObJlyFCxJ9MY+ajr+dZj5JsdcsghuuKKK2TbdsLxnbuFNisqKtKMGTNanqE2bdqkd955R8uWLdPq1au1evVqbdmyRcFgUMFgUKZpqri4WEVFRSovL9eYMWO0xx57aM8999Tee+8ty7Jca+6osWPG6f/99i8aOKhQHs+OZ8yxY8d26n0BAAAAAACADnOiMoIb3Zc47t8TBAAAfVQsLDXVxj9CNdKgiZLHn359hnBoOoRCgT4cDJWkY489Vu+9956+9a1vacGCBSlHyDfrSLfQdHbuRnrooYfqb3/7m0aOHJnzewEAkE9FRUWaNm2apk2b1nIsEolo8+bNCgaDamxslM/nU3FxscrLy1VUVJTHapP169dP/fr1SzoeidiSOj8Y2tUKfV7FGqRBAyt1wTmXpVxTH6mSJBVZXplyefOM4cg0InJrGOp4A3LMxCCmx+PRd7/73TbX3mzQoEEJQdHupqioWOPHT9Sw4cXyes18lwMAAAAAAAAAAAC0n+NI0SYpVCs11WwPf27/MVTb8rkRbUy87KChUulQ973bGA4lFArE9elgqCTtsssueumll/TAAw/opz/9qTZu3JjTEfI7SzVSftCgQfrVr36lCy+8sMNdSQEA6Cm8Xq+GDBmS7zJ6lepwtYqtcnlN9w6emZiOqViG0e9hOyhJKsnQLdQ0ozIyPEvFduoW2ltk8wjZ1BQjGAoAAAAAAACg9yiulHPcnQqFQqqqqko4NXDgQPn9Ll3hAADdk+NIkWDKoGdL58+mWhmxdjTUCdVIyhAMlbIOhxIKBXbo88FQKR7WvPDCC/WNb3xDf/jDH/S73/1OX375Zcu5VGHNbMKi6UKezdcOHz5cV155pS655BIVF/fOQAQAAOg61aFqbYhuVom3RBW+ChV52t551ee1FA25P+dE7EbZTkyGpGLL57rW441lvKft733PQeFwTJs2NWVct2Vzo+rqwho4sEA+X+eOrwcAAAAAAAAAAACShINSw5aWgGdSADRUK8OOds69m2o7Z18ABENbKy4u1g9+8ANdffXVeu655/Too4/q6aefVm1t4n+E0oVFU9k5QFpaWqqTTjpJZ5xxhmbMmCGPh98CAACQW9si27Qtsk0+06eBnhINasO1Ab9X0Xr3Nc3dQgstr6wMz0SmGXYdI297C+SYvet5qLExqk0bG7PuOh8Jx7R+XYMGDw6oINC7fi0AAAAAAAAAAADQzX3xiowVL+Tn3k012a1bvSCrUfLGJ3PjL03SNRQgGJqKZVk68cQTdeKJJ8q2bb399tv63//+p/fee08fffSRVqxYofr6DIkJxYOmY8aM0Z577qkpU6Zo+vTp2nfffWWajAsFAACdL2yHtSW0RYOUfSdK0zbkmuSUFIo1j5F37xZqWpnHyNv+kqxr6wnC4VibQqHNHMfRxo2NGjK0kM6hAAAAAAAAAAAAcBcLb+/uWZvY6XPkYVLRgLbt5S/vhAKzlE3H0CxDoc0IhwJxBEMzME1T++23n/bbb7+E48FgUBs2bNC2bdvU1NSkSCQir9ergoIClZSUqLKyUkVFbR/fCgAAkC9+v0eRJvdAY9Rpku3ER0VkGiNveTOPlIj5unaMfMSOaFPTJtc1gwoGyWt627V/VVVTm0OhzRzHUVVVk4YN4xkSAAAAAAAAAAD0QYH+cg65VuFwWFu3bk041a9fP/l8PinQP0/FdRHHkaJNO8a4J4x1r2k5ZkQbU18+YFzbg6EFZR0uu91CNe7n2xgKbUY4FCAY2m5FRUUaM2ZMvssAAADImYDPo0jIfU1zt9CA5ZEnwxh5y4y4j5H3+OVY7QtgtpctW3WROtc1Awra+I/l7UIhW5FwrF3XNouEY2psjCrASHkAAAAAAAAAANDXWF6puFJOKKRoQ+I0XqdooOT356mwHHEcKRJs1emzdfCzpuW4Ecvwgp2bbDpw7qygvP336yi3etsZCm1GOBR9Ha84AwAAQJIh0zEl2a6rws1j5DN0C42PkXffq7eNkW8Iun+92dpWFyEYCgAAAAAAAAAA0FPVb5S2fNYq/Lk9ABqqlWFnnrjXIaH2BEPz2DHUdmm6EkndFbVNcrEH0EP1iVecP/30U3366adpz++1114aPXp0F1YEAADQvQQCliKN7sHGqBNWzIlIkko8GcbIe7IYI+/v2jHynctQU1PHuoU2a2iIynGkDA1ZAQAAAAAAOofhkVM0WI7jKBZL/B6PZXlkGIZk9ImXGAEAQFda/rzkDWTu7rh6QTzsN/a4rqmrPWpWyfhkTn7u3Z6OoZ6AHNMrw47krAxHhuQvjYdOC8olf9mOnxeU7fjcdHmuHHucHEnGivntq2HMsd37zwnQyfrEv9p+//vf67777kt5zjRNffzxx11cEQAAQNfwm35JmUOaAZ9XoUaXue+SwrF6SVKB6ZHXMF3XWlamMfI+ORm6jvYkhmHlcDdH0agtr9f91xgAAAAAAKBTFA2QDr1O4VBIVVVVCacGDhwof08f4QoAALqf5c+3hP8cSao8IPW6VqPFHSk3ob9YZKdR7jWtunzWSrvNkAbs0bY989mBs6mm7dcYRrzmhs1ZLXcMK0Xgs0zyl+847iuWzBy8ftbOcCihUKCPBEPXr18vx0mdTDj66KM1duzYLq4IAAAg9yr8Fdocq1HU2REELfWVSaEtrtcZMmTYhlyTnJJCzWPkPV7XdaYZyzxG3tebuoVKRoagbFvZtvvvBQAAAAAAAAAAQK/QKhQqScYnc2VFo5J/94Rl1prXZCx/Zse6FfMzh0OjTfGg5M4j3VuPdo80uJbnBDdLA9r4NRWUt/GCHGpPx1ApXnPD5nhjl5aOnuU7BT63H/cVSTl+bczV9nCo7IiMlS+5LnV2PUIyvYRCAfWRYGh1dbUkxUdbbOc4jgzD0Fe+8pV8lQUAALqAI0cROyKf2Xu6U6ZT4atQuXeAtkW2qTpcrVAspAIVSnIPhhYELIUzdAuNORHFnLAkqcRy7wpheTN3KLX9JRnX9CROhiBsW5kmc+QBAAAAAAAAAEAvt1MotJl3+TMqrqxXff+9JUnFW96Rd8P/ktYZK+bLCVZJ/cakDIAasVDHawzVtP0afx47hoZqJceJdwFti4lnxUOhnoK2X9sVxh4n1W+QMgRDNXRfqbiya2oCurk+EQxtaNiR7m8OhDbbe++981ESAADoAsFoUGsb1irmxGQZloYVDlORpyjfZXUqQ4ZKvaUq9ZYq5sTUWN2oTL05C7we1Qez6xbqNy35zI6NkXcsr2xP7xo55jixHO5myONhjDwAAAAAAAAAAOjlvIG0pypaBUErUoRCmxkb3pU2vJvTshI01bX9Gk+BHMsnIxbOfT1pOL7iHWPd7ahkuU8ATFKQxzArgE7RJ4KhPl/6DmGMkQcAoHeK2lGtCa6RrXgnx5gT05rgGo0pGSOP2ScegWQZlhoao1KmZql25nf9he16SVKJ5b6ZYcZkZAhJxvz5GyNvylSptzTjmrZzVFBgqamp4wHRwkJPt3wjJgAAAAAAAAAAQE6NnC5H8fHxqbgFQrtMU03brzGMeNAyWNXh2zsyJH/p9lHu5TvCnzt/3kde/wSQvT7xX4Xi4vThg9JS92AAAADomTaHNreEQpvZsrU5tFmVgb4xPiAUiikatTMGQyNNtiQr7XnbiSpqx0dtFHvcN7M8WYyR9+UvGOo1vRpWOKxT9i4sMnMSDC0pbeM7OAEAAAAAAACgu2islj59Ul7bVv9Q4ghn7ya/ZJrSuJOlQEWeCgTQZRw7Hqps2Cw1bIl/NG6RRhws9d9tx7oM4dC8C9W27zp/ecZgqGNYrQKepfEfC8ri1zYf9xVLZvrX8QAgnT4RDC0vL097zuPpE78EAAD0KVE7qppwTcpzNeEaDfAP6BNdQ4P1kazW2RmynCE7Pkbea5gqyPAPT8uTYYy86ZHtMhakJ/P7TXl9liLh9odDvT5LgUDv/7MJAAAAAAAAoJeKhWRs/ECWpMI0S5yxx3VlRQA6UywSD3u2BD9bh0C3ppwy55SNSAyGSt07HNpUIzmO2jzurWiAnKaaHQHPlsBn6Y5On74iyWjPJDsAyKxPvOo8ZsyYtOfq6+vpGgoAQC+zObRZTpp0oiOnz3QNDQajLn1AsxeObR8jn6FbqGHGZHbjMfJdYeDAAq1f1yDHcUnHpmEYhgYOLOiEqgAAAAAAAAAAANop0ri96+fm5BBoU50Mt44hqTRsSX28m4ZDDTsqJ9Io+dLF3dOYMLNzCgKALPWJYOjuu++e9tyaNWs0YcKELqwGAAB0Jrduoc36QtfQpsaYYjFbVgffZGgrpojdJEkq87qHFrMaI9/Lg6E+n6XBgwPauLGxTeFQwzA0eHBAPh+jQAAAAAAAAAAAQBdyHClUtz302dzxc3PL6Hcj0pDb+6ULhnYTjq843s2zdafPtnYLBYBuoPemIVrZb7/90p77+OOPCYYCANCLuHULbdYXuobWB7MbI59JOBYfI+8xTPkzjLKwPNEMY+Qt2d42vpuyByoIeDRkaKGqqpqyGivv9VkaOLCAUCgAAAAAAAAAAOgaDZulT55s6QBq2Ll5XSkrjWmCoasXdGq3UEeG5C/dPtK9VeizOQDaHAbtxY1lAPQtfeK/ZuPGjdMuu+yiL7/8UsZOKf4FCxbo9NNPz1NlAAAgl7LpFtqsN3cNdRypIUfB0ND2MfJlPvduoYZpy3TcO4bavt7dLbQ1n8/SsGFFamyMaltdRA0NUSWmZg0VFnpUUupVIND7/gwCAAAAAAAAAIBuzLBkVH2Un3s3Vkt2NDGA2cFQqGNYrQKf2z/85YldP30lkkmTDgB9R595Ffqkk07Sfffd1xIMNQxDjuNo9uzZuvvuu/NcHQAAyIVsuoU2681dQxsbo7Lt7MeYp+O0GiNf7g9IsfR7WlbmIGqsl4+RTyUQ8CgQ8MhxpGjUlm07Mk1DHo/J1BEAAAAAAAAAAJA9x5EiwVaj3jfHu2+WDpdGTm/bXgVlcgxLhpN58lmuGXLkNFZLRQPjBzoQCnVGHibteoTkK5IyTL4DgL6mzwRDL730Ut13332SJMdxWgKia9eu1ZNPPqmTTz45n+UBAIAOaku30GY9qWtozIkp23/OButz1S20QZIjr2nJ4xIKlSTL4/6NA8cwZft6/xj5dAxD8nr5hgQAAAAAAAAAAHDh2FJTzfbw5xapcXOrIOgWGbFQ8iXhhrYHQw1TKuwnBatyU3dbNWyOB0M72CnUWP0/OYHytn/9ANAHdP8URI7sueeeOvroo/Wf//wnYZy84zj66U9/qhNOOEEeT5/55QAAoNdpS7fQZj2pa+iW0BYNVObxFrbtbB9b3nHh7WPkBxSXynDJfRqGLVPuYVTbXySJFpkAAAAAAADdXnCz9O4D8jmOKmOJ32eyVnri74CdeoFUNCBPBQIAerRAfzmHXJtxTa8Wi0iNW1MGP9W4te1dPBs3t6+OwIAuC4Y6MuIj3Qv7x39/fdunzEUaO755LvYAgF6oTyUh77rrLk2dOlXRaPwfsc3j5D/66CPdcMMNuvnmm/NcIQAAaI/2dAtt1hO6hsacmOqjQQ1Uaca1DQ1ROU4uxsjbitjxf0iXeHzxb1KkYVqZg6gxX0mHawIAAAAAAEAXcKIyghtlSGkn2DhObt6YDADogyyvVNz9G3Z0WKRxx6j3hODnZqmpTkYbm524atga7zTa1lHqhbl9k4djWPEupIUD4qHTwv47gqCF/aVUr8WNPU6OJGPF/Pbdc8yx0tjjOlY4APRS3TcB0QkmTJig6667Tr/+9a9bQqHNP/7mN7/RmDFjdOGFF+a7TAAA0Ebt6RbarCd0Da0J10hZhj1zNUY+HGuQI0clRcUyw+7f6Le87uf7+hh5AAAAAAAAAADQyzmO9OGseAfOhs0yIg1ddmvDiclpqpUCFW27sLDtnVkdT8H2oGfr4Of2nxeUtT2cKrU7HEooFADc9algqCT94he/0Pvvv6+nn346KRz6ne98R+vXr9ePf/xjmWY7/rICAABdriPdQpt1966h1eHqtN0ZWrNtR42NbRwvkkbYDkqSBhSXSPWh9AsNJ/MYeV9h+74RAAAAAAAAAAAA0BMYhlS9Ukbj1vzcv2FLzoKhjq9ke+hzwPbun/13hEC9RfGvNde2h0NlR2SsfMl1qbPrEZLpJRQKABl0z/RDJzIMQ7NmzdLJJ5+sl156Scb2v7Caw6E///nPNXfuXP35z3/W5MmT81wtAADIpCPdQpt1566h9dF6ReyI/LIyrm1siEk5GD3iyFE41iC/3y+/7b7WsiLK9M9/288YeQAAAAAAAAAA0A1FQ1Lj1sSx75I04fS27xXoH98rHxo3SxrbtmuKK+WMOKhVB9ABUqCf5PF3SokZjT1Oqt8gZQiGaui+UnH3e00PALqbPhcMlaSioiI999xzOu+88zRr1qykzqFvv/229ttvP33lK1/RBRdcoOOPP54OogAAdEOOnA53C21WE67R4MBgGRljjl1rayj7byA0NLqPdM9WxG6QI1v9Kiqk+rDrWsvr3qHUMQzZvqKc1JULUSeqzU2bXdcMKBggj9EnH5MBAAAAAAAAAOg8y5+XvAFp5HT3dasXSJHG3HSEdBwp0hAPfjZs2R7+3PFzI1SXfInll8af1vbOmIX9pa3LOl5zezQHWtsi0E+aMDP3tQAAuoU++4q31+vVI488ouOPP15XXnmlamtrJe3oHBqNRjVnzhzNmTNHlZWVOvzww7XPPvton3320fjx41VRUSGv15vnrwIAgL4tYkc63C20mSNHETsin+nLyX65ELbDCkaD2a8PxaQcBFtDsaAsy1KZLyA5LsHQbMbIewvldKMx8jEnpupwteuaCn8FwVAAAAAAAAAAAHJp+fMyVsyXtH32Wbpw6OoFMj6Zu2NdNuFQx5aaareHPbeHPluFQI1oU5tKNWIhOZGg5Ctu03XpRrN3FsdbuGPUe8nQLr03AKD76zOveI8ePTrtuZ07hjaPl3eceNBk/fr1evTRR/Xoo48mXOf3+1VaWqrCwsLOK7xVjStWrOj0+wAA0JN4Ta8sw1LMce9amQ3LsOQ1u9ebPqJ2VD7Tp7Dt3rUztxyFY0H1H9BPagq5rrSsqIwMwVzb38ZvmgAAAAAAAADo3oor5Rx3Z76rANCTtAqFSpLxydzU4dBWoVBJMlbM3xEOtaPbR7637vjZ/ONWGXZupqq1aNjS9mBoYEBOS3BkSAVl20e9N497778jDOoN5PR+AIDepc8EQ1etWtUS/NzZzkHQ5nCo0aoteKrrmpqa1NTUtneWtJfR1hblAAD0AYYMDS8crjUNazoUDrUMS8MLh3e7MfKFnkKNKRmjYDSo+oaaLrln2G6UDEcV5eXSRvfOmpbH/Zss8THyBEMBAAAAAAAAAOizdgqFNksKh+4UCm1Zt2K+nFULpFgoY7OKnGrYLJWPbNs17egY6hiWVNgvHiot3B4Abf55oJ9kda+mJgCAnqPPBEOb7RywdBwnZeiz9bGdQ6JdLVV9AAAgrtBTqN1Kd1M4FpYtu83XmzLls3zdLhTaWpGnSEUBv5yaLZ1+r3AsqNLSUnlithzb5RnEcGSaEbl9D8bxBuSYVu6LBAAAAAAAAAAAPYNLV8uWcOj2n6ddF+uahl0JGja3/Zo0wVDH8rfq9tk/MQRaUC4ZZsdqBQAghT4XDN3Zzt1CU0l3ji6eAAB0D4YM+S1/vsvoFcJ2UEP67SKnwX2MvGlGZWR480qMbqEAAAAAAAAAAPRtlVPkBDfL+PK1lKfdAqF51diOZh2eAjkjDpZ8JYmj371FEvkSAEAX63PB0Fx23+yKTp6ETwEAaBvbsdWU4Z2jBVaBTN59mSRiN6og4FdBQYGcLdtc13q87mPkJcn2EwwFAAAAAAAAAKDPaKqV6tYkfBihOjmGJWfcV2R8+lSbtnOG7C1j/TudVGwGDe2c4jbh9NzWAQBAO/W5YCgAAOjdIk5Eq4OrXdeMLhktv0GH0Z2F7aD69+snhcJSzHZdm2mMvO0NyDF51AQAAAAAAAAAoNdxHCm0Uwi0do2McOqmE4YTk1MxRs4ep2TdIdTZ4xSpbKTUhcFQx/TuGPFeOqLL7gsgS/4yOZO/lXENgLg+92o9HTgBAABSs82wSkpK5FS7dws1rcxj5Ltrt1BTpgo9hRnXAAAAAAAAAAAAxUOgTTXJnUDD9W3bp26NNHK6nGhIxvLn3G85doY0crrU1ntkwfEWSoFWY96bR74H+kv+Uka+A92ZNyBVTs53FUCP0aeCoV0x+h0AAKA7sczsvoERdZpUXlEa/6ShyX1PT+Yx8jFf9wyGek2vRhaNzHcZAAAAAAAAAAB0P44jNVUndAHVtrVtD4GmUrcm/mMslHlt8xpvkRzLLyOba1pxCsqkwIAdoc/C/jvCoN5AGwsHAKBn6jPB0JUrV+a7BAAAgC4XKPRI7lPhJUlhu0GDywdJ4UjGMfKWlWGMvMcvx/K2sVIAAAAAAAAAANBlHEdq3JrcCTTS0Dn3q1sjrV4gY+VLGZcaK1+S4y+Ndw0t7C9tW5dYumFJgX47dfxsDoD2k3iNAgCAvhMMHTmSzlAAAKDvCQQ8UjDzuoJiS6Zpymlw/4ZPfIy8e3DU9pe0pUQAAAAAAJAP9Rul4sHtPw8AAHqeYJW09s3tIdC1nRcCTaVurYzmrqFZMD6ZG+9RMXQfOaFxid0/C8olw+ysSgEA6BX4mxIAAKCX8nhMeTyZR8nHnLD69S+Pf5KLMfL+7jlGHgAAAAAAbPflQum12+M/tuc8AADomUJ1Mla+JGPLsq4NhUoy3EaRpbvmk7nxAOi4k6QRB0n9d4t3BCUUCgBARn2mYygAAEA2bNtWJBKRbdsyTVNer1em2TO/wVBU7NW2mnoFMmVDrai8Xq8UiUrRmPvSjGPkfXIsX9rzkUhEn376qVatWqVt27Zp27ZtMgxDJSUlKisr0+jRozV27FhZlpWh6NxobGzU0qVLtXLlStXW1ioSiaiwsFBDhw7VuHHjNGLEiC6pAwAAAACALvPlQhlLH4v/fOlj8X/mjzgo+/MAAKDnKh2W7wrarKVz6Mjp+S4FAIAehWAoAADodL/73e907733pjzn8/k0b948DRvWsW9GrFmzRkcffXTS8T/O/qMGDR2U8fpgMKjq6mrV19fLcXYkHw3DUHFxsSoqKlRUVNShGrtaUZFHtetiUoayi0r9kiQnQ7fQrMbI+5K7hTY2NmrevHl64okn9MEHHygcDrvuEQgEtPfee2vmzJk66qij5POlD5q21+uvv66///3veu211xQKhdKu22WXXXTqqafqtNNOy3kNAAAAAAB0udahz+2M1uHPTOcBAED+OHZ8FPz2MfAq7C/tckjb9vAUyCkcKKOhqnNq3M4xLKlkiFQ6XGqqlbH5445tGGnMTWEAAPQhBEMBAEBehcNh3X333brttts6Zf9dS3bVsJ3eAWu2GjHS1NSkdevWpQ0HOo7T0tnS7/dr6NChKigo6JRac8nrsxQKNchS5loDRf74CzwN6QOSkmRZ2YyRL0n4fM6cObr11ltVU1OT8dpmjY2Neu211/Taa6+psrJSP//5z3XEEUdkfb2bDRs26Gc/+5leeeWVrNZ/8cUXuueee/TQQw/pm9/8ZsrwMQAAAAAAPUKK0GczY+ljcta8IaNuTfrzEuFQAHGN1dKnT7qvGXeyFKjomnqA3sixpeCmeAC0bk1LGNSI7fg+vlO+a9uDoVI8rJnDYGg8BDo0vm/psPiPJUMkc0ccxVn+vIwV89u3/5hjpbHH5apcAAD6DIKhAAAg755++mldeOGFGjduXM73NmXKMlKPJQ8Gg1qzZo1s270LZrNQKKTVq1dr+PDhndo9dGtoqyqsMnnM9j+qFRd5VbN1i0qM0syLDSM+Qj7iHvy0PFHXMfKO5ZXjiXcfDYfDuuaaa/TCCy+0pewkGzZs0KWXXqozzjhDP//5z2UYRrv3WrJkiS699FJt3ry5zdfW1dXp3nvv1bJly3TxxRfLNM3MFwEAAAAA0F24hEKbpQuFtpwnHAqgWSwkY+MHrkscQlxA9ppDoLXNAdAvpW3rZMTcp29p29r4tUYbv19dNlza8G77SjU9UvGQ+B6l2z+KKxNCoCmNPU6O1OZwKKFQAADaj2AoAADIO9u2dccdd+j+++/vsns2NTW1KRTazLZtrVmzRiNHjpRl5X7EuSRVh2u0JValYm+xKnwVKvK0PYTq8cbkRCzJm936TGPkDTMmw4m5ron542Pko9GorrzySr388stp13q9Xo0aNUrl5eVyHEe1tbVauXKlotHU4dRHH31UsVhMv/zlL92/kDSWLVumiy66SLW1tSnPl5WVacyYMfL5fKqqqtLKlStT/tmYPz/+TatLL720XXUAAAAAANDl6jdKSx/PzV5LH5cqRkvFg3OzHwAAfY0d294J9MsdnUC3rc8cAk3BiIXlBKva/vdy6fCsljmmp1Un0OFS6Yj4vczUzTgy2h4OlR2RsfIl93vveoRkegmFAgDQAQRDAQBAt/DKK6/ozTff1AEHHNAl91u3bl2bQ6HNbNvWunXrNHz4yBxXtYMjR9si27Qtsk0l3hIN91Zmfa3f71FtbbV8ZrlcW3y2lmmMvCfzGHnbFx8j/9BDD6UNhU6dOlXf/va3dcghh8jv9yeca2xs1CuvvKL7779fS5YsSbr23//+tw488ECdeOKJGWtpLRgM6sorr0wZCp00aZKuvvpqHXjggQndSKuqqjRr1iz9+c9/Vjic+A25+fPna+zYsTrmmGPaVAcAAAAAAHlRPFiacLqUoWNoViacTigUAOAu0F/OIdcqHA5r69atCaf69esnn88nBfrnqbguZsfib9Co+3LHSPht62TYkdzdo25N2/9uLhmWdMgxvVLpTiHQokHtD4GmM/Y4qX6DlCEYqqH7xjuRAgCAdiMYCgAAuo0777xT//rXvzr9PsFgUKGQexAyk1AopMbGxhxV5K6tHUMDhaaqNjap3OeRlMU3mGIxKey+zvJE3MfImx7Z3gJt3rxZ9913X8o1l112mS6//PK0Y9gDgYCOPfZYHXXUUbrrrrtSdpC99dZbdfTRRyeFSt38/ve/18qVK5OOz5w5UzfeeKM8nuRH4oEDB+rKK6/UEUcckbLT6IMPPqh9991XFRUVWdcBAAAAAEDejDgoPr61A+FQZ8JMxsgDADKzvFJxpZxQSNGGxO8FO0UDpTZ8b7dHsWPxwGNzF9CWEGjmpgsdUrdGGrpP267xBuRUTpF8xTuCoJ0RAgUAAHlFMBQAAORFcXGx6uvrE4598MEHeu655zRjxoxOvXd1dXVO9qmrq5NUnJO90jENU2XeMimabXdTQ+FwvXxmG8KkTe4jagwzJjPLMfLPP/+8Ghoaks7PnDlTV155ZVblWJala665Rps2bdLcuXMTzlVVVem1117TkUcemdVea9as0d///vek4wcffLB+8YtfpA2pNps4caLuvvtuXXDBBQkdZhsbGzVr1ixddtllWdUBAAAAAEDedSAcSigUAAAXnz4lrX5FRobvo3eKujXtu27yN3NbBwB0hUijtOUz9zX9d5e8ga6pB+jm3F8JBwAA6CS77767pk2blnT8//2//6dotPPeQWvbdlIgtb1SBSBzrcxbJtPI/pGtoMBSTc1W+a3sA6tOhmCoZWUxRt4fHyP/4osvJp3z+Xy6+uqrs66n2bXXXiuv15t0/KWXMoyYaeWBBx5QJJLYDdXv92cVCm124IEH6rTTTktZx86jkAAAAAAA6NZGHCSndHibLnFKhxMKBQDAjacgP6FQKT6i3sm2sQQA9HChWhnv/9X1Q6HazPsAfQTBUAAAkDfXXHNNUjhv9erV+ve//91p94xEInIcl5nobZCrfdz08/dr03rTiki2JctIDlSmFXYPfloe9/OOacne/s671atXJ53fd9991b9//+zr2W7AgAHad999k45/+eWXWV0fCoX05JNPJh2fcfIM+Qf4VdVUlfIjluIbeN/+9rdlWYljdKLRaJtCqgAAAAAA5N2XC2W0sbOYUbdG+nJhJxUEAEA3EotI7Rn93sY3XeSC4ymQUzFGGnFgvG6gt/CXyZn8LYUnnKnNw09M+AhPOFPO5G9J/rJ8VwkAPQKj5AEAQN7sscceOumkk5LCe/fdd59OOeUUFRYW5vyerceBd3eFnkL5TF/W6w1Dqq/fKr/VhjHymfY0bZly/0aY7d/RnXTLli1J58eMGdPu+48ePVoLFya++FRVVZXVtS+//HLK7rDTvzJdm0Ob015X6iuVZSSGQCsrKzV16lQtXrw44fgrr7yi008/Pat6AAAAAADIqy8XtmuMvBQfP+9IdA4FAPQesYi0bV18FHvzR/2G+Ij1wZPatlcnB0MdT0H8Hq0/CvtLbZg2BvQY3oBUOVl2KKRGI/H1oOKBAyW/P0+FAUDPQzAUANBjNTVFVbWpQU1NMRUUWBo4qFAFBfzV1tNceeWVmjdvXsK476qqKj300EO67LLLcn6/bMeHdwf9fDu6hUYidsYHN69Xqq1rUrl/QM5qsKzM7zSO+XYEQ1N1Ue1IwLe4uDjpWLa/h6+88krSsWHDh2n0uNHtquWggw5KCoauXr1aW7ZsaVdHVAAAAAAAukwHQqHNCIcCAHqsWDgeAq1tFQINbpSRYgS7U7em7cFQf4kcf5mMHIwvdjyBHeHPsu0/BvrHO0MAAAC0AekZAECPYtuOPni/Ss89+7neWbxRsdiOEJplGdp738GaccJoTZo8UKbJP5J7guHDh+uss87Sww8/nHD8gQce0JlnnqmKioqc3s/r9cowjJyMgTc66RsxFb5y1atOxd4docjGxqhKMlwXjTbKMrzyGLl7t2TmMfKmbN+O4Gf//v21du3ahDU1NTXtvn91dXXSsYEDB2Z17Ztvvpl07IADD2h3LZMmpf5m4JIlS3T44Ye3e18AAAAAADpV/UZp6eO52Wvp41LFaKl4cG72AwAg16KhFJ1AN8pQlq8J1K5p331Lh0tVbQuGOt7C5E6ggX6EQAEAQE4QDM2grq5OS5Ys0erVq7V+/Xpt2rRJjY2NCoVCikajOQmVZGPixIm6+uqru+Re3dnmzZv12muv6aOPPtInn3yirVu3atu2bQqHwyouLlZpaal22WUXTZgwQVOnTtU+++zTaaEdAF3v8xU1+t1d7+iL1XUpz8dijt56c4PeenODdhlZqiu+t7dGjynv2iLRLpdccokef/zxhLHf9fX1uu+++/STn/wkp/cyTVPFxcXatm1bh/cqLCxUzD032S79/P000JvYgbKxIXMwtLFpm3xWcofN9jKMLMbI+4ol7fi7dtKkSUnB0CVLlrS7hg8++CDp2OTJkzNeV1NToy+//DLp+MRJE9tdy4ABA1RRUZEUVl2xYgXBUAAAAABA91U8WJpwutTBjqGS4vsQCu39iivlHHenQqGQqqoSR7gOHDhQfka4Auguok0pOoFuyj4Emsq2tZLjtD2cWTpcqvoo7WnHW7SjC2jJ9h8LKgiBAgCATkMwdCfBYFBz587Vf/7zH7300kv64osv8l2SJOm4447rs8HQbdu26cEHH9Sjjz6qN998U7ad3NI/nUGDBumEE07QJZdcogMOaH+HsJ7OcRx99tlnevvtt/XRRx/ps88+0+rVq7VhwwbV1NSosbFRkhQIBFRUVKQhQ4Zo2LBh2mOPPTR58mQdcsgh2nXXXfP8VaCve//dTbrtljfV1BTLav0Xq+v0s+tf0XU/PkCTpwzq5OrQURUVFbrooot01113JRx/9NFHde6552r48OE5v18ugqGlpaWq3pr930vtFQrFFI06kpVppSO/WZSz+5ptHCMvSccee6zmzZuXcOzjjz/WJ598oj322KNN929+I8jOjjvuuIzXfvrppymPj91tbJtq2NmoUaOSgqGrVq3q0J4AAAAAAHS6EQfJkTo0Tt6ZMJMx8gAAd8ufl7wBaeR093WrF0iRRmls5u/1tog2SXVrtwdAv9weAt3csRBoCka4Xk5TjRRo4zSzsh2vYzi+4uROoAXlhEABAECXIhi63ccff6zf/OY3evzxx9XQ0CBJXdYNNJO+2vGyoaFBN998s373u9+pri51d8BMNm3apIceekgPPfSQDjroIN1+++065JBDclxp97Rs2TK98MILLSHnbMb4btu2Tdu2bdOGDRv07rvv6umnn245N3r0aJ122mk699xztddee3Vi5UCyz1fUtCkU2qypKabbbn5Tv7xlGp1De4Bzzz1XjzzySEIXgkgkorvuukt33HFHu/cNO2GF7FDCsUBhQH6/X6FQKM1Vmfn9fgUCAVUrmHRu+fJPFYmEJUmbtxTK49nxd7kddVS3yb0LZ+kWj8xW19TVhhUKhrXJCrtetz7UqELPjlE1Xq9Pe+7e/iCkx+v+/znHMGX7EoOoxxxzjEaOHKnVq1fvWOc4uvHGG/Xwww9n3VGisbFRN954Y9Lxww47LKuAaapuoZI0YpcRqlbyePpsDR6c3BVl48aN7d4PAAAAAIAu04FwKKFQAEBGy5+XsWK+JMWjmpVpmvasXiDjk7k71qUKhzq2tPXzHQHQurUyGqqS13WWujVtD4aWj5Iz9fx4CNRfRggUAADkXZ8Phm7evFlXX321Zs2aJcdxEsKg3SGQ2V3CqV1t/vz5+s53vpMQKumohQsXatq0abrgggt01113qbg4d6N2uwPHcfTqq69q1qxZevbZZ3P6aydJn3/+ue644w7dcccdOuKII/Szn/1MRxxxRE7vgdwIh2PasCE5qNZT2baj397+VptDoc2ammL67e1v6Qc/2l+maUiOo2g0cS+Px+pR/0CvrCySz5exdWSPEwgE9N3vfjcpDPjMM8/owgsv1Pjx49u175f1Xyq0LTEAOrpktIYOHarVq1e3qRN1M9M0NXTo0LTPCr/45XXatGl9u+rNpcpBQzXnb0+172LDkSH3jqG2ryjp/zsej0e33HKLvvWtbyka3RGAfe+993TJJZfoN7/5jQYNcu/iu379el177bVJI+jLy8t10003ZVX+zuPsJcnn88VHwW9rfzC0f//+Sce2bNmiWKx9/40CAAAAAKBLtSMcSigUAJBRq1CoJBmfzJUVjUr+3ROWWWtek7H8mR3rVsxPEw41pPcflhFp6Lya3dStkQZPbNs13kJpEM11AABA99Gng6HPPfecvvWtb2nLli0tAcydAx75DGZ2h2BqPtx22226/vrr2xXUycRxHP3lL3/RokWLNHfu3F4xHv3tt9/WrFmz9M9//lNr1qzpknu+9NJLeumll/TVr35V99xzT85HPKNjNmwI6urLX8x3Gd3K+nVBXXPlS/kuI2f+3++P1C67lOa7jE4xc+ZMPfTQQwmjuR3H0R133KG//OUvOb1XQUGBhg8frjVr1rTp7xzTNDV8+HAVFBQoEun8MfL5YlkRZXoSsf2p32Sx995767bbbtN1112XEA5duHChjj/+eJ1yyik6/PDDNW7cOFVUVMhxHNXU1Ojjjz/WSy+9pCeffFKNjY0Je1ZUVOgvf/mLKisrs6p/69atScf69+8vQ4b8pnvXUsPlKy8vL086Ztu2tm3bllVdAAAAAADk3YiD5ITqEgI8qTgypAmnEwoFALjbKRTazLv8GRVX1qu+/96SpOIt78i74X9J61KGQw0j3nlzy2edVHQGdV3zmisAAEBn6rPB0Pvuu09XXXVVS3en1iHMvtqlszu46qqrdM8993T6fZYsWaIDDzxQ//vf/7IaR9tdPfXUUzr55JPzdv/Zs2fr5Zdf1sMPP6yvfOUreasDQO/h8Xj0ve99T9/73vcSjr/22mt64403dOCBB+b0fkVFRRo5cqTWrl2rcNh9TLsUHx8/dOhQFRQU5LSO7sjyuo+7dwxDsZ3GyLd2wgknaOjQofrRj36UEPQNBoP6xz/+oX/84x9Z1zJ9+nT98pe/TDnGPZ3a2tqkY8XFxfKZPo0uGZ31PjsrLCxMeZxgKAAAAACgR6mcLGUIhmrq+dKgPbumHgBAz+UNpD1VseF/Kt76gaLeUgWCLtMOU+1ROqzLgqFOQXk8iNr6AwAAoIfrk8HQBx54QJdffrkk90Boqo6d6UKjmbp7ZhM2TbVHX+oa+pOf/KRLQqHNNm3apKOPPlqvvvqqRo0a1WX3zaXuMLa2urpap5xyiu644w59//vfz3c5AHqBGTNmaNKkSfrggw8Sjt9xxx3697//nfO/G5s7h37++eeu64YMGZKyW2SvZDgy5R4Mtb2FkmG6rpkyZYqeeeYZPfPMM5o9e7beeuuthA6ibkpLS3XMMcdo5syZmjp1atalN2toSB4xlC7U2RZ+f+puo6FQqMN7AwAAAADQrRT2z3cFAICeYOR0OYqPj0/FG66WN1yd9nJnj1OkkdOTT5SOyFGBO92voGKnEOgwyV/SKfcCAADIpz4XDF20aJEuueSSrAOh2XYPdVtnGEZWe/blTqX//Oc/dfPNN2e1tqioSKeffrpOOukkTZ06VYMHD1ZBQYGqq6v16aef6vXXX9cjjzyiJUuWZNxr7dq1Ou2007Rw4cK0QQ9k5jiOrrnmGkWjUV133XX5LgdAL3DNNdfo3HPPTTj24Ycfat68eTrhhBPyUlMgkP5dzzv768M7vgE2bHixvN4dAcpYxNHWNRHX6/sN98ryGmpoiGrTxnjA0StHQ60m1+uq7VLFHGuno+73SiU+Rt79uSTdGPlUPB5PvFunz5d1MDQYDGr16tX6+OOPNX78+DZ3aU11H4+n44++6fbI9usCAAAAAAAAgF7BcaTgJmnrcql6pRzTK8Nu2/ej04ZCpZx07XQC/ZJDoL7sv7cNAADQk/WpYGgoFNLZZ5+taDTaEtRsHcbc+Vh5ebmOPfZYjR49WoMGDVJFRYXOP/98GYYhx3FafpSkXXfdVTfccINs21ZNTY2qq6u1detWff7551q4cGHLONPWIdHWexiGoQkTJuj73/++TDO5+9awYcM67xcmz1asWKHvfOc7GdcZhqFLL71UN910kwYMGJB0ftCgQRo0aJCmTZumH/7wh5o7d66uvvpqrVy50nXfd999V9///vd17733tvtr6CmGDh2qgw8+WPvtt58mTJigUaNGaciQISoqKpJpmtqyZYu2bNmiDz/8UC+//LJeeOGFjB30WvvRj36k0aNHa+bMmZ34VQDoCw444ABNnz5dCxYsSDh+991365hjjpHX681TZV0rWN/2UGcuWB73jtSOYcjO4ptnL730km655RZ98cUXba4hFotp8eLFWrx4se6991798Ic/1Mknn9ym63eW6hmrrdLt0R26eAMAAAAAAABAp2rcGg+CblkubV0mI1TX7q1cQ6GSFOgnxxOQEW3Mbr9A/8QAaOlwyVfU7voAAAB6uj4VDL3nnnu0YsWKhEBns9ZhzX322Uc333yzjjzySFlWYtet888/P+Xe/fv3T+ps1sxxHH344Yd6/vnndd9992nVqlUJAdHmepYuXaq//OUv+tvf/qZdd921o19uj3HJJZeors79Hw2BQED/+Mc/dOqpp2a97ymnnKLp06frjDPO0Pz5813X3nfffTrrrLN0yCGHZL1/TzF58mSdeeaZOv744zVp0iTXtUOGDNGQIUO011576YwzzpDjOJozZ45uueUWvfXWWxnv5TiOLrzwQh1wwAEaMaJzxjsA6DuuueYavfrqq7Jtu+XY6tWr9a9//Utnn312Hitru1AsJBmS38y+O7VtO2poyEMXSsORabgHUh1vQI65c2fSRL/5zW/04IMPpjw3ZcoUHXzwwdp9991VXl4uSaqpqWnp/P3+++8nrN+yZYuuu+46vfXWW7rpppuyCnju/Awn5Sa8mW6PVPcDAAAAAAAAgB4ttC0eBN26XNqyTEbjlpxs6+x6hHsoVJIMIx7u3Los+frCATvCn80f3sKc1AYgzyKN0pbPZEYiCuyUIzGdDZLXK/XfXfJmP+kPAPqqPhMMbWpq0q233pow0l1KDIRalqW7775bl112WU7vbRiGJk6cqIkTJ+r73/++Zs+erV/84hdasmRJUjj09ddf10EHHaRnnnlG++yzT07r6I6eeOIJ/ec//3Fd4/P5NGfOHB177LFt3r+iokJz587VSSedpP/+97+ua6+44gotXrw4J93E8q2srEznnXeevvOd72jChAnt3scwDH31q1/VqaeeqltuuUU33HBDxlBNXd3/Z+++w6Oq8v+Bv8+dnknvkNBDEVwQrIhIU1BW1BXLT1wXy+5XV8W6bnF1dXXXtaDiurprW3tBhRWxgVJEip0iVSB0UknPJNPu+f0xJGQyvSeZ9+t5eCDnnnvuJzAkk5n3/ZwG3HDDDVi8eHHY1yUiAoChQ4dixowZWLRokdv4v//9b1x44YUwm7vPnb5V1io02huRok1BpsgBoA94jsXi8LiRJR40iiPgNvLOANvIP/LII15Doccddxz++te/+rxR4ZxzzsEtt9yCjRs34t5778X27dvdjr/77rvQaDS47777/H8ScD1/6Mxuj7wDq68t45Oliy0RERERERERERH1YPYWoHb3sY6gTeWJrSejD2RrbYcAaB9XIJSBMKKey1oPsfFV6AF47iPrIsfdya8DRERB6P4JuCC99dZbqK2tBXBsq/iOoVC9Xo8333wz6qHQzhRFwcyZM/Htt9/i1ltvdTvWVk9lZSUmTZqENWvWxLSWRFNVFX/84x8Dznv44YfDCoW2MRqNeOeddwJ2sFy/fj3efPPNsK/TFfTr1w9PP/00Dh06hHnz5kUUCu1ICIG77roLS5YsgcEQuNvdhx9+iHXr1kXl2kSU3G6++WaPgF91dbXPTpTe9Entg4FpA91+6ZXAwcxocagONNobAQAWhwUVrRVBnZewbeR1/ruUSsDvNvKrVq3Cf//7X4/xCRMm4O233w7YvRpwdbueP38+JkyY4HHs7bffDtgJHIDX4HBzc3PA8wJpafG+bVFKCu9GJyIiIiIiIiIiom7GaQOqdwA/fQismwcsvwdi/UsQ+7+MaShU7FkB7FsVeOLg6cD4PwGjrgQGTAJyShgGIyIiIgpS0nQMfe2117yOSykhhMD999+PSy65JG716PV6PP744zj77LNx6aWXwmKxADgWDm1qasKFF16Ib775psduK79w4ULs3OnZ+r+jM8880yNAG47s7Gy88MILmDZtmt95jzzyCH75y19GfL1469u3L+69915ceeWVMe1YNmXKFLz++uu47LLL3LZ29uaxxx7De++9F7NayLfCQjOe+NfkRJcRNdu3HcGzT28MPDGA6288AUOPywakhMPh3vlWq9W4tiTpJgoLu0+nzEgVFRXh8ssvxyuvvOI2/tJLL2HWrFnIzs4OuIZe6EPawj3aGuwNgSd14nRKtLREvu15OBTFDn8NQ13byHt/CimlxD/+8Q+P8X79+uHxxx8P6uaCNgaDAY8//jh+8YtfYP/+/W7H5s6di7POOstvl++2Leo7amxsDPr6vvgKl6alpUW8NhEREREREREREVFMqQ6gfj9wZKdre/i6fRAyMa9Fi+2LXC9F+9tSvhu9d0NERETU1SRFMLSxsRFr1qxx20a+bet2IQROOukk3HnnnQmp7dxzz8WHH36IadOmuW1vKoTAkSNHcNFFF+G7776DRqNJSH2xNHfuXL/HhRCYN29e1K43depU/PznP8dHH33kc86PP/6ITz/9FOecc07UrhtLmZmZePTRRzFnzpyQwjaRuPjiizFnzhw8+eSTfuctXrwYtbW1yMrKiktddIxer0HfvumJLiNqiovT8MmHe7B/X+jhujZ9+6Vjytn9oCiur/2dt4LWarVu3yOoa7n++uuxcOFCt1Bfc3Mznn76adxzzz0JrMy3Xbt2wG63AQAcB+vhFLb2Y4qqQ3pTjd/ztQeBxkab+xgkKjU2H2e4NKpmqPJYWFKn02PEkJKg61Y0dogA29erfraRX7NmDfbs2eMxftNNN3nt4BmI2WzGnDlzPJ6n7d+/H6tWrcLEiRN9npuXl+cxVlNTA1VV/QZKA6mrq/MY0+l0YX1+RERERERERERdUkstsOMD6FQVOVar2yFdpQFQFGDo+YCJr/8TdSut9cDqhyCc/l9njqegwqHU8xgyIEf9KuAcIiIiikxSBENXr14Nu93eHgbt7IEHHkhoIGjChAn45z//ieuvv94tsAoAmzZtwhNPPIHf/e53CasvFrZu3Yqvv/7a75zp06dj9OjRUb3un//8Z7/BUMDVha67BEMnTpzoNxQTK3/5y1/w6quvora21uccm82Gzz//PK6deKlnUhSBObeOwT1/+hKtraHftWo0ajDn1jFQFAY/u6usrCxce+21HjcLvPPOO5g9ezb69u2bmML8uP+B36OysizRZaAwvzc+nP9h0PM1Wv/byAOA008wdPXq1R5jRqMRU6dODbqGzs4++2wYDAZYO70JsXbtWr/fA4uKijzGnE4nKioq0KtXr7Drqaqq8hjLz89nuJyIiIiIiIi6l9RCyGmPJboK6qqcVoiKTdAASPExRZb436GNiLogQ7prG/YuFAwFGA5NSjoTUDgq0VUQERH1eOG3S+pGfvjhB7ePO75x379//4jCCtHyf//3f5gyZYpbKLQtJHr//fejvr4+wRVG1xtvvBFwTjS2kO9s7NixOOWUU/zOWbx4cVS2mu3JsrOzce211wac98UXX8ShGkoGAwdl4vd3nQqjMbTuyUajBr+/61QMHJQZm8IobmbPnu3RAdJut0e1s3RPpTMFH1jUaPwHQ1WtEVLR+Ty+detWj7ERI0ZE1NXaaDRixIgRHuPbtm3ze17//v29ju/duzfsWgCgrMwz8BtJ0JSIiIiIiIiIiIgoLoQAsgcnugrv7C2JroCIiIiox0mKYOiPP/7oMdYWwLz88sujcg1vnUhD9fDDD3tdr7m5GS+++GLE63clb7/9tt/jvXv3xuTJk2Ny7SuvvNLv8ZaWFrz//vsxuXZPMmPGjIBzvAWEiMI16oR8PPCP8ejbLz2o+X37peOBf4zHqBPyY1wZxYPJZMKNN97oMf7JJ59g8+bNCaio+9Cbgnu6p2gcEFL1O8ffNvIAvHaSzsnJCer6/nhbw9uW7h0NGTIEWq1nc/zt27eHXYeU0muwdMCAAWGvSURERERERERERBQSawNQsSm8c7NLolKC1Oghc4dBDjkPcuxtkAPPDn+tQVMBdiEmIiIiirqkCIbu37/f57FTTz01KtdwOAJvvRrImDFjMH78eK9dQ5977rmI1+8qdu7cidLSUr9zZs6cCUWJzcPzkksuCbjd65IlS2Jy7Z5k3LhxMBqNfufs3r07TtVQshg4KBOPPTkJf/nr6TjltF7QaNz/L2s0Aqec1gt/+evpeOzJSewU2sNcfPHFHl0gpZR4/PHHE1NQdyAARRtcx9BIt5EHvD8f8hbODJVO59mlVFX9h1gNBgOGDBniMb5+/fqw69i/fz9aWjzvXB88uIveZU9ERERERERERETdn90CVPwIbFsIrH4EYuVfITa8ArTUhL5WmMFQKTSQWYMgS86BPOUmYPIDwIm/AQZMAtKLgcHnuAKeoa7LUCgRERFRzET+Tn03cOjQIZ9BwJNPPjkq14hGMBQALrvsMnz55ZcA4BYQ3blzJ/bs2dMjOlJ9/vnnAedMmxa7HwAKCgowatQobNiwweecZcuWxez6PYVGo0FBQQH27dvnc463znFEkVIUgVGj8zFqdD5aWx2ormpBS4sDJpMWuXkmGI1J8a0tKWm1Wtx222245ZZb3MbXrl2L1atX+9w6PBFefWVR+58Li0ywyEbU2mphU23QOPXIqu/j93wLbJBwDz7qINFb0+r3vFo1HU6paf/YnKUB4AyiYgmNxg74aYCuavWQGr3fVbKysrBnzx73mqLwvaCmxvMFzqysrIDnnX766R7dq7/6+itUWar8BlbTdenQCI3HuLdQqVarxfHHHx+wFiIiIiIiIiIiIqKgOKxA7R6gZidQswtoOATh7cXbml1A0SmhrW3KgkzJhbBU+50mIYCMPq4gac5gILM/EOD1YZRMc1Wp2iH2rPC//oBJgKJjKJSIiIgohpIiPdPQ0ND+544B0ZSUFBQWFka0dltHz+bm5ojWaTNp0iSfx5YuXYrrrrsuKtdJpOXLl/s9rtVqMWHChJjWcNZZZ/kNhpaXl2PLli0YMWJETOvo7gIFQy0WSxyroWRkNGpR3Cct0WVQHE2bNg2jRo3Cxo0b3cYff/xx/POf/0xQVf5phAbZ+mxkG7LR7GhGnaUh8ElRYjArCCYYqijOILaRD/x/zduW71u3boWqqmF3Anc6nR7hTgDIzs4OeO6kSZPwwgsvuI011DdgycolOHHciT7PS9GmeA2Grl692mNsxIgRMJlMAWshIiIiIiIiIiIi8kp1AHX7XEHQI7uA+v0QMogb/o+EEQwFgOzBgJdgqEztdTQIWgJkDQJ0YbzuWTINaCoHAgRD0fskIDWy9+mJiIiIyL+kCIa2tnrvrpWRkRHyWnq9Hna73aMDaVNTU1i1dTZs2DCf1+gcgumuvvvuO7/HR4wYgdRU/1vVRuq0004LOOf7779nMDQAKf20loPr/wsRUbTdcccd+NWvfuU2tnXrVnz44YcJqih4Zq0ZRlMKamCP+bU0OgGNTgTVMFTRBJ7k1Af+3jxixAh89tlnbmP19fX49ttvceqppwYuxIuvv/7a7SafNiNHjgx47pgxY1BUVIRDhw65jX/0zkd+g6HebNq0Cbt37/YYj/XNLERERERERERERF2OKQdy3J0B55APUgUaDrqCnTU7gdo9EGoYrxnX7ASkBHzsnOlTzmDg4DrIlFxXELTtVxDNAYiIiIio+wivdVM303mb97YwW2ZmZshr+Qq6RWvLbCEEioqKvB7bsWNHVK6RSLW1tdi7d6/fOWPGjIl5HSeeGDgM4m27WHJXXe1/m4n09PQ4VUJEyeSUU07xGsZ78cUXE1BN1+XqFgrAETj0qVEcfo9LjQ5Sawi4zhlnnOF1/F//+lfAmwm8UVXVZydYX9fqSAiBWbNmeYyv/2o9fvzux6DrkFJi3rx5HuMZGRkYN25c0OsQERERERERERH1CBqdq9ujv18aXaKr7DqkBBrLgH1fAuv/Cyy/B+KrJyF2fgRx5KfwQqEAhLUBaK4M/cTcYZBn/hkY/ydgxCVAr9EMhRIRERH1QEkRDE1L8/5EVqsNvWGq2Wxu/3PHgIOqqgFDcsFKS0tzW7ttu/o9e/ZEZf1E8rd9e5tgOoBFqn///gFDiwyG+tfY2Bgw5Nu/f/+41EJEyef222/32Jq8sbExQdV0TYaUo38/rbaAcwX8byPvDPJFwREjRmDAgAEe499++63PgKc/c+fO9frcoaSkBEOHDg1qjcsuu8zrtvNP/e0pNNR5diL15oUXXsD333/vMX7BBRewOzYRERERERERERG5k9K1VfuBr4CNrwEr74NYOxdi+/sQlVsgHN53uwxLza7Qz9EaAJPna6ZERERE1LMkRTC0cwCwbYv2+vr6kNfKzc31eSxQSC5YTqfTYxt5oGcEXn766aeAc0pKSuJQCTBo0CC/x4OpNZmtXbs2YPe3YEM7REShGjp0KGbMmJHoMuJKSv/hzY40OgGtwfVcQgYRDA1ENQTeRh5wPce69dZbvR7797//jbvvvhvNzc0B12lqasIf/vAH/Pe///V6/LbbbvP6XMmb1NRU3HHHHR7jVWVVuPfGe1F52P8d9S+++CIef/xxj/FevXrhvPPOC6oGIiIiIiIiIiIi6uFa64HD3wOb3wZW/R3iy39AbH0XonwDhK0pdtcNJxhKREREREkh9JaZ3VB6ejqklB4BgnCCofn5+diyZYvXMMLu3btx0kknhV1nm7q6Oq/jTU0x/KEhToLpehqvYGhJSYnfrqDl5eVobW2F0WiMSz3dzf/+97+Ac7i9LhHF0i233IJPPvkENpv/4KMKFU7pvp26IhQIBBcs7CqcaiuCvadH39Yt1KkCdgcQeBd4n6RGC1Ub/PfCadOmYcKECfjiiy88jr333ntYunQpLrroIowbNw5DhgxBZmYmpJSor6/H9u3bsWbNGixcuNDn857JkydjypQpIX0OM2fOxIoVK/D555+7je/dtRe3zLoF5158LsZOHos+A/pAp9OhvKwcm37YhNdffx0bN270WE+r1eL222+HTsftsIiIiIiIiIiIiJLeN09D1JbG/bJSSYq3+omIiIgoTEnxbDE/P9/reDgdOAcMGIAVK1Z4PbZ+/XpcdtllIa/Zkd1uR1VVlddjTqfT63h3EkwwtE+fPnGoBCguLvZ7XEqJvXv3YtiwYXGppztpbGzEW2+9FXBeqMEdIqJQ9O7dG7NmzcLLL7/sd96exj1obnDvUjkwbSAMSgRpyQRQ1VYAKUHNbdtGXrZYI46/OvXBdQvtaN68ebjqqqu8hiobGhrw8ssvB/x38+aEE07AY489FvJ5APDQQw/hqquuwubNm93GW1ta8b/X/of/vRb4hgcAUBQFc+bMiduNLERERERERERERNTFGdLichkpFCC9D5AzGMguATL7AxrevE5ERElEZ4YcNDXgHCJySYpg6NChQ7F8+XIAcOscqqoqKisrfQZHvfEXAli3bl1khcIVLrXZbBBCeHQ57QmdKw8cOOD3eGpqKszm+HyRLiwsDDhn//79DIZ68eyzz6KhocHvnJNOOgmDBg2KU0VElKyuv/56LFiwIKybPboTVXUC0h7UXEUjoDMeff5gaY382mG8qGkymfDiiy/igQcewKJFiyKuAQAuuOAC3HPPPTCZTGGdn5qaihdffBG33HoLvlr3VVhrGI1G3HTTTeyITURERERERERERMdkDwbKPW+SjwaZ1tu1fk4JkDUQCGF3J6Iuy94CHPnJ/5ycIYAuvPcDiKgHM6QBJdMSXQVRt5EUwdDjjjvO57GNGzfi7LPPDnqtUaNGeYy1hTi/+uor1NfXIyMjI6w6AWDp0qU+j+Xm5oa9bldRXV3t93gwYc1o6dWrV8A5R44ciUMl3cuRI0fw97//PeC8a665Jg7VEFGyy8zMxK9//Ws88cQTiS4lppyqBZog5xrMR0OhqgpYbYikZahUNFDDfOElNTUVDz/8MKZNm4b//Oc/2LRpU1jrjBw5Etdffz0mT54c1vkdZWRk4MUXXsTrr7+Of/3rXyEFik877TT88pe/RFFRUcR1EBERERERESVcSy2w4wP/c4aeD5iy4lMPEVGiqU6g4SBgzg89jJY9OGplyJQ8Vwg0ezCQPQgIY0cnoi7PWg+x8VW/U+S4OxkMJSIiilBSBEP9dXwMNRh6yimnuH3csaunw+HAO++8g9/85jdh1el0OvHcc8+5dQnteI1+/fqFtW5XUlNT4/d4ZmZmfAoJ8lqB6k1Gf/zjH1FXV+d3TkFBAa6++ur4FERE3cKcOXMwZ86cmKx93XXX4brrrmv/2KpaUdpYGpNrJYrT2QJNkAHPjtvIQyKiYKhqiPxFx8mTJ2Py5MnYsmULlixZgk2bNmHz5s1oamryOj81NRXHH388Ro4ciWnTpmHEiBER19CRRqPB7NmzMXPmTCxatAjLli3Dhg0bYLFY3OYJIdCnTx+cccYZuPDCCzF06FCUlvasxxURERERERElMacVosL/TZySnXiIqCeTKtBYDtTsBGp2ATW7IZxWyJG/BHqNDm2tlBxIYyZEa13oZRgzjoZAj3YFNWaGvAYRERERkTdJEQz92c9+5vPYxo2htfXPycnB8ccfj82bN7d3CgWOdQ199NFHcdVVV0Gn04Vc51NPPYWDBw+6rdvRyJEjQ16zK5FSBgwUpqWFvl1tuIK5FoOh7pYsWYIXXngh4Lw//elPMBoTt5XFunXrIjr/xx9/9Biz2+2wWq0RreuLVqttD4QritI+7u3rAEXO298r/657FqkG/veUqoQUx+YF8xiQUnrMC/paHc5TgzinI1W1Q0o7IAL3DBUKoDEcfR5hifxrlkNnjtr/j+HDh2P48OEAXH+XDQ0NaGxsbO/amZaWhrS0NKSnp7vdJBOr/59msxmzZs3CrFmzIKVEeXk56uvr4XA4kJKSgsLCQqSkpLTPD+Z7gLfHCMWPqqoAXP8ODocjwdUQebLb7UGNERF5w68hRBQJfg0hb4TNBkOAOTabDTJGr4lS18bHB/VIUkK0HIFSuxtK3W4odaUQdovHNGfVDjiyh4e8vC5jIDStPwQuQ5cCNXMQ1KyBUDNLIE3ZQMemQT3g/xW/hlAgfIyQP3x8EFFX151eU0mKYGhBQQGGDRuGHTt2tAcN2sKX4QTIzjvvPGzevLn9445dQ3fv3o05c+bgP//5T0hr/vDDD7jrrrs8uoV2dPrpp4dca1disVjgdDr9zolnMDQ9PT3gnIaGhjhU0j1UVVXh2muvDThv+PDhuPHGG+NQkW+x+L9SW1uLqqqqqK8LAFlZWe1hco3GFfxSVZWhljgK9LWJuhenGvjf0+l0wiEdbh8HdU6n/5cOpxrwPIfTAeE4Fvp2OkMLDjqdLQAARQR+2qbVA06nA1AlNK22SJqFQgoFNqEHYvS1yGw2w2w2o7Cw0G08Uf8f8/LykJeX5zbW8d873McIxZaqqu1h3La/e7vdjtra2kSWRRS0QDfOERH5w68hRBQJfg0hbWsNegWYU1NTA4dFCTCLeiI+Pqin0NgbYWg+AGPTfhiaD0Dr8L6LUUfyyE9hvR+Uos1DjpdxVdHDai5Gq7kPrOY+sBtyjwVBm1WguTrka3V1/BpCgfAxQv7w8UFEXV13eh8yKYKhADBx4kRs3769PRDaFsDcs2cPNm3aFFI3zv/3//4fHnroIbextjWllHj++eeRl5eHv/71r27d/3xZtWoVLrzwQrS2tnp0IW2j1WpxzjnnBF1jV2Sz2QLOMRgC3fsRPcFcqzulvGNJVVXMmjULhw4d8jtPCIFnnnkGWm3SfGkhIoo5p+q6a12nmALO1R5t1iysdogIO1c6dCnud6oTERERERERERERdWGKwwJD80EYm11BUJ2tLuQ1dLZ6aGwNcOoDN5jpyGruAwBQhQa2lN5oNfeF1dwHNlOBa6snIiIiIqI4S5pnoZMmTfJ5bOHChSGtNXLkSJx66qluAVPAPRz64IMPYty4cXj//fd9BiJ//PFHXH311Zg8eTLq6uq8biHftub555+PjIyMkOrsaoIJhsYzUBjMtYKpORncc889+PzzzwPOu/XWWzFhwoQ4VERE1H04ZfgdMFXVBnn0fL2SEmC2q2MoAIjWyL9/OXSBr0dERERERERERESUKMJphbGxFJnlX6Bg12so2vEscg9+hNTaH8MKhbYxNh8I+RynLg0VAy7DoWE3oKr/xWjMOwW2lF4MhRIRERFRwiRNW79JkyZBURSvYc7//e9/uO+++0Ja76677sIFF1zgMd4xHPr1119j5syZSEtLw7Bhw1BYWIjU1FRUVVVhx44dOHDggNs5/tx+++0h1dcVMRjaPb3xxht48MEHA84bMWJEUPOIiGJNK7TobegdcE40tKqtQIAN26tt1SjWB9r0wjun09UtVBFaaBQ9gNYAZwhASghrZB2vpRBwaAN3KCUiIiIiIiIiIqLkozgsSK3Z6HdOU/YoqNro3nwuVAf0lsMwNh+AofkA9C3lEIhs5yRvDM370Zw1IuTzbCn+X5cmIiIiIoqnpAmG5ubmYsKECVixYoXbdvJSSmzevBk//PADxowZE/R6M2bMwPjx47F69WqPTp8d15ZSoqGhAd98841HILVN23jnsbZ1LrzwQowdOzaST7/bCBSQjSZFCXyHXucOrslm3bp1uPbaawPOS0tLw4IFC2A0GuNQVWBr166N6Pwff/wR1113ndtYVlYW8vLyIlrXF61W2/7Yb/tdUZS4BqWTiZQSTqd7B0eNRhPXrz8Ue3roQ5rf+THhjUaj8fh/2WxpBpDq97wMfYb7eaoE4Ah4PSkBp9oCANBrzAHnA4BWqwEcTtfJEVD1Zmh1of0d9nThPkYotpxOJ1RVBXDsph+NRhOz79lEkbDb7airq3Mby8zMhE6nS0xBRNSt8GsIEUWCX0PIG9GsArv9z8nOzoY08+erZMTHBwUimitg2PGV3znG/qdG/hhRnRCNB6HU7oZSVwqlfj+EDPzaaqRSWg5Dk5sL8H2DsPBrCAXCxwj5w8cHEXV1FRUViS4haEn1zvVll12GFStWAPAMID788MOYP39+SOu9+OKLOOGEE9DS0uIzHNrxY29h0I7HvR3LycnBM888E1JdXVUwLzQ6HLH/Ya6N3R64m5pen7yhmB07dmDGjBmwWq0B577wwgsYOnRoHKoKTiyC1DqdDgaDIerr+sOgYvwIIfj3neSC+ffv/DhxqA5YnBYYAgRDU3WpbucFcV8CAEBVrZDSFXgzKMEFQ4UQkC2Bv24HvLYhjf8nOgnnMULx1fGmH41Gk8BKiIKXiOeYRNRz8GsIEUWCX0MI9sCvfev1eoCPk+TExwcFEo/HyO7PgD0rIJyRv94ZMkUDg7ADhrT4X7sn4NcQCoSPEfKHjw8i6uK60422SRUMvfjii3HTTTfB6XS2BzHbAp0LFy7E7t27MWjQoKDXKykpwauvvopLLrnEba02Ha/hLSTgrRtlx+6hBoMB7733HgoKCoL/JLuw7hgM7U7/maPpwIEDmDp1Ko4cORJw7v33349LL700DlUREXUttbZayCC2KQo3KOhU27aR10CnGAGogU+SAFpsYV2vfQkh4NQHF0QlIiIiIiIiIiKiJLNrCaAGfo8Nh78DFB1QMi2862gMcQuFSn0qkF0CZA8GckoAUw67hUbCkAE56lew2+1oaGhwO5Senu56/9WQkaDiiIiIiJJHUgVDs7OzMXv2bHz33Xdejy9atAi33357SGtedNFFeP7553HddddBVVWv28IHux15x3ONRiPeffddnHnmmSHV05UF033TZosszBIKdgz1rrq6GlOnTsX+/fsDzp0zZw7uueeeOFRFRNT1WNUYvigpJZzOo9vIK2YAwb0IKW12QA0iQOqHqjMDIsi2pkRERERERERERJQ8di2B2L00qKlij2sXRwmEFw7NGRz6OUGSWiOQPcgVBM0uAVILGQSNJp0JKBwF1WpFi6hyO5Sal8cuf0RERERxklTBUAB4/vnno77mNddcg6KiIlx99dUoLy/36BDqLxjqbUv5AQMG4J133sGJJ54Y9VoTKSUlxaOramdNTU1xq6exsTHgHLM5uTqm1dfXY+rUqdi+fXvAub/61a/w5JNPxqEqIqKuqTilGE1KC6rrg7g7vgO7PXBwU1WtOPqSKfSaEL4XtUZ+g4VqSI14DSIiIiIiIiIiIuphQgiFdiR2L4V0tALDLgjtxNQCSH0qhC3y9w6logOyBhzrCJpezJvjiYiIuiOnHWgJsPOtKQfQJOfuwESdJV0wNFamTZuGzZs347777sPzzz8Pq9XVRczXNvIdtQUl09LScPPNN+Ouu+6CyWSKec3xptFokJ6ejvr6ep9zgglrRksw18rOzo5DJV1Dc3Mzpk+fjvXr1wec+4tf/AL//e9/w94emYiopzBoDABCC4a2WBwI1AHUqbYCAAQU6JUQnhNEGAyVQkA1JNdNERISdtUOvZJ8XcKJiIiIiIiIiIiCEmYotI3Yt8rVpTOUzqFCcXX1LN8Y8vWk0ACZ/Y5uD1/i+rPCt8WJiIi6vZYjEGse9TtFjrvT1Q2ciBgMjabs7Gz885//xF/+8he8+eab+OCDD7Bu3Tq0tLT4PCclJQWnn346LrroIsyaNQvp6elxrDj+srOz/QZD/R2LtmCulSzB0NbWVlxwwQVYu3ZtwLnTpk3D22+/DY1GE4fKiIh6HovFAT3836WmHt2m3tUtNIQQvtdt5H136vaYqTO5XjTtwVSposnh6jJgdVpRY62BChUKFGQbsmHQGJCqTYXCjgFEREREREREREQuuig0tAlnjezBQQVDJQSQXnSsI2jmAEDL7cqJiLolnRly0FQ4HQ40Wyxuh8wpKdBotYAuuZqcEBGFi8HQGMjNzcXNN9+Mm2++GU6nE3v27MGePXtQX1+P1tZW6PV6ZGZmon///igpKYGiJE/wICcnB3v27PF5vKKiIm61lJeXB5yTk5MTh0oSy2azYebMmVi2bFnAuePHj8fChQuh17OrGhFROKxWJxxOiWC/ihpC2UbeC6E4oddbAk88StUaI7ped2CXdhyyHPIYV6Gi2loNABiYNhAGwReOiYiIiIiIiIiIAAD9zoQEILYvCn+NwtGhn5M92OchaS4AcgYf7Qo6CNClhF8bERF1HYY0oGQaHFYrGqqq3A/l5UFj4Ps3RETBYjA0xjQaDUpKSlBSUpLoUrqEoqIifPfddz6P19bWwmazxSV4GEwwtKioKOZ1JJLD4cDll1+Ojz/+OODcU045BR999BFSUviDNRFRuJqbgt92XkCBTgn/a66icUCvt0CE0DFU01IHVZ8ClS+iEhERERERERERUUe9T4asPwBR9kN459fsBHqNCe2clBxIYyZEax2kKftYR9DsEsDQs3dhJCIiIiKKFIOhFFcDBgwIOOfw4cPo379/zGs5fPhwwDnB1NtdqaqK2bNnY+HChQHnjhw5Ep9++inS0tLiUBkRUc/V3OwIeq5OY4IIZRv5Dto6hYYSCgUAIVXo6g/DltkHMom3WnKoDhiU5P38iYiIiIiIiIiIAAA2C1C1GajYBFT/BCGd4a91ZFfowVAhgJ/NgjRmAik9f5c/IiIiIqJoYjCU4iqYwOeuXbviEgzdtWuX3+NZWVlIT++ZdxtKKfHrX/8ab775ZsC5Q4cOxWeffYasrKw4VEZE1HO1tjjhdKoQUIKab1BSw76WXt8Scii0jZAqdI3lsGX1C/v63V2drQ5mrTnRZRARERERERERJYYpB3LcnbDZbKipqXE7lJ2d7dr1zcSQXo9lawIqNgMVG4GaXRBSjc66Nf7fl/Mpe1B0rk9ERERElGQYDKW4KikpCThn165dOOuss2Jey+7du/0eD6bW7uqGG27ASy+9FHDegAEDsGzZMuTn58ehKiKinq2pOZRt5AX0mvC2c1c0Digigjv3ASgOKxS7pUduKe9QA3dtbbQ3wqE6oFX4VJmIiIiIiIiIkpBGB6QWQlqtcFjcb3KW5jzAwJ1WehxrQ4cw6O6wbzr3R7QcgWypAUzZUV+biIiIiIg88d1uiqsTTjgh4JzNmzfHvI7KykpUVVX5nRNMrd3Rrbfeiv/85z8B5xUXF2P58uUoKiqKQ1VERD2blIAlhGCoVjEG3VnU41yNLazzOtO01PXIYGidrS7gHAmJams1Ck2FsS+IiIiIiIiIiIgoEVrrXVvEV2wCavfEJAzakRQaoLGMwVAiIiIiojhhMJTiqqioCPn5+aisrPQ554cffoh5Hd9//33AOaNHj455HfH2xz/+EU8++WTAeYWFhVi2bBn69+8f+6KIiKLMqlpR2ljqd87AtIEwKPHrbNDS4oCqBv/Cql5jCvNKEoom+ACqP4qtGZAqIMILqHZFDtWBRntjUHPrbHXINeSyaygREREREREREfUctmbg8HdAxUaIun1xuaTMHgwMmARkDQA0+rhck4iIiIiIEGYrKqIIjBkzxu/xjRs3wm6PTqjFl2+++SbgnBNPPDGmNcTbvffei4cffjjgvJycHHz22WcYMmRIHKoiIkoOzU2hfV/TKeEFQ4WQEGGd6WUtKSGC2Ha9O6m2VkMG2fmgrWsoERERERERERFRj+FogdjxQdxCoQAganYCzRUMhRIRERERxRmDoRR3EyZM8HvcYrHgq6++imkNy5cv93s8LS0tYIC1O3nooYdw//33B5yXkZGBpUuX4vjjj49DVUREyUFVJSyW0AKW4W4jDxHd7Z6EVKO6XiI5VEdQ28h3VGerg6OHhWOJiIiIiIiIiCiJpeRCphXF/bJi+yJg36q4X5cSxN4ClG+EUvkjTPU/uf1SKn8Eyje65hARERFRTCVNMPT9999HXV1dossgAGeffXbAOZ999lnMrt/U1BQweDpx4kRotT1j69h58+bhT3/6U8B5qamp+PTTT3tUIJaIKJqC7TTZWWuLE1JGN7Dpk4xWv9C25XrOU8VQuoW2YddQIiIiIiIiIiLqcQpHJua6DAImD2s9xMZXod/6FnIPfuT2S7/1LYiNrwLW+kRXSURERNTj9Zx3+wO46KKLkJeXh5NPPhl/+MMfsGTJErS08AeQRBg9ejRyc3P9zlmwYEHMrr9o0SLYbDa/c4IJr3YH//nPf3DbbbcFnJeSkoKPPvoIp512WhyqIiLqnvY17UN5Szlsqv/vIZ1ZWuLXcVJKEWZ81ctaQkAqPeMmiXC6hbZh11AiIiIiIiIiIuqSwr0ZvWBU6JeCgDRmh3c9AHLQVKBkWtjnExERERFR6JImGAoATqcT33//PebOnYvp06cjKysLZ555Ju677z58+eWXcDj4pn88KIqCmTNn+p2zdetWbNiwISbXf+utt/weD6a+7uCVV17BDTfcEHCewWDA+++/jzPPPDMOVRERdV+qVFFrq8Xuxt3Y17wPjfbGoDqBWlvj/fwiOl1DVb0Z6CEdQ8PpFtqGXUOJiIiIiIiIiKjLkBKoPwD89CHw5T+A5qrQ1zDnQab2CnwpoUDmDIUccQkw6T5gwp9dAc9QS2YolIiIiIgoIXpGG6ggCSEgpWwPcdhsNqxZswZr1qzBAw88AJPJhDPOOAOTJ0/G5MmTceKJJ0KI6G7JSi5XXHEFnn32Wb9znnrqKbz44otRve6uXbvwySef+J0zadIk9O7dO6rXjbe3334b11xzTcDAkk6nw3vvvddjOqQSEcWLxWGBxWGBTjVCi5xEl9NOp29FtHqGOk2ZUVkn0SLpFtqmzlaHNENadAoiIiIiIiIiIiIKhVRdYdCKjUD5JojW2mOHKjYBA6eEvmbBz4CmMs9LCQ2QOwQoGAnkHQ/oU9wnlExzvfqo2iH2rPBf9oBJgKJjKJSIiELjtAMtRyBsNmhba9wOiWYVsOsBUw6g0SWoQCKi7iOpgqEAPIKeHYNzFosFn332GT777DMAQEZGBiZMmIDJkydjypQpGD58eFxr7cnOOOMMDBw4EKWlpT7nvPHGG7j//vtRVFQUtevOnTsXqqr6nfOrX/0qatdLhPfffx9XXnllwM9To9HgrbfewnnnnRenyoiIeh5V+v9aG2+K4ozKOqrWAFWXEnhiNxBJt9A2EjLicCkREREREREREVHQpArU7QXKNwGVmyBa673PCzcYWjgK2L3UdSlFC+QOOxoGHQ7oTP7PLZkGNJUDAYKh6H0SkFoYem1ERJTcWo5ArHkUBgAe/a13u36T4+7k9xgioiAkXTC0YxBUCOE3KFpXV4cPPvgAH3zwAQAgPz8fkyZNwpQpUzB58mQMGDAgPkX3QEII3HbbbZgzZ47POVarFX/84x/x2muvReWaW7ZswQsvvOB3Tu/evfH//t//i8r1EmHJkiW47LLL4HD437ZYURS8+uqrmDlzZpwqIyKKH53QoSjF/00FOhGduwjNWjPsUVmp65BCgT2tZ/wwHc1AZ6O9MSrrEBEREREREREReaU6gdo9rs6glZshrA0BTxENByEtR4CUEHc1MhdA9j0DyOwP5B0HaI3h1UxERERERF1W0gVDO+q8zXagoGhFRQXmz5+P+fPnAwD69evXvu385MmTUVjYM0IU8XLNNdfgvvvuw5EjR3zOeeONN3D55Zdj+vTpEV3Lbrfj2muvhdPpv5PaLbfcAr1eH9G12nR+LHmzZ88e9O/fPyrXW7lyJX7xi1/AZrMFrOv555/HrFmzonJdIqKuRhEK0nXpcblWhj4D1T0oGiqFAntGb0itIdGlRIVdtUfcLbRN5+eNREREREREREREEVOdQM0uV+fPys0QtqbQ16jYBAyYFNo5QgDH/SL0axERERERUbeRdMFQf8HPUIOie/fuxUsvvYSXXnoJADBs2LD2becnTpyIzMzMKFffs6SkpODuu+/Gbbfd5nOOlBKzZ8/GunXrUFJSEva1brvtNnz99dd+5xQVFeHGG28M+xqJ9NVXX2HGjBloaWkJOPdf//oXrrnmmjhURUTUsxk1Rhg0BiBOwVBFie36qtYAe1phjwmFAoBO0UEjNHBK/zeGBEMjNHAi8nWIiIiIiIiIiLo8ayNwYC20DgfSLRa3Q9qmFECrBfqcDhjSElRgN6c6gCM7j4VB7ZbA5/gTTjCUiCiRdGbIQVMDziEiIqLIJE0w9JJLLsHKlStRVVXVPhYo+BlqUHTbtm3Yvn07nnnmGSiKghNOOKG9m+iZZ54Jk8kUzU+pR7jpppvw3HPPYdu2bT7nVFdXY8qUKVi6dCmGDh0a0vqqquIPf/gDnn766YBzH3nkEZjN3e8J5vr163HuueeiqSnwXaSPP/44brjhhjhURUTU82Xrs+N2La1wIk1pBtTYrG9PK4DTmBGbxRNIQKA4pRgHLQcjCodqhAYFpgIcxuEoVkdERERERESUQKYcyHF3BpxDScreDLF7KbQAfL1iJAtHMRgaCqcdOLIDqPjRFQZ1tEZtaVG/H7KlBjDF7/VKIqKIGNKAkmmJroKIiKjHS5pgaNv275s2bcLy5cuxbNkyrFq1Co2Nje1zIg2KSinb5zidTnz//ff44YcfMHfuXOh0OpxyyintHUXHjh0LrTZp/vp90mq1ePbZZzFp0iS/27zv378fJ598Mp588klcddVVQW/T/tvf/hZLliwJOHfq1Kndcmv1bdu2YerUqairqws49+9//7vf7qxEROSfEKJ9W3KN0CBdnw6HPfbbi+uEHelKM4Qa3rWkUCCk/0Spquu5N6+kaFMwOH0wbE4b1DCStQoU6DV62Ky2GFRHRERERERElCAaHZBamOgqiHo2pw2o3g6UbwKqtkI4rbG7VuUWoN/42K1PRERERETdTtIlE0eOHImRI0fi1ltvhdPpxLffftseFF23bh1aW4/doRdOULTz3LY5NpsNa9aswZo1a/DAAw/AZDJh3LhxmDJlCiZPnowTTzwxqLBjTzR+/Hj85S9/wb333ut3XmNjI6655hrMmzcP//d//4fzzjsP/fr1c5tjsVjw1Vdf4c0338Trr78OqzXwD9m9evXCa6+9FtHnkCg333wzqqurA87T6XRYuHAhFi5cGIeq3N13330477zz4n5dIqJo62fuB4uwoNZWi3RdOgQEgNgGQ7XC6QqFhnkdCcBhzoWuqTK6hXUzAgIGjSHRZRARERERERERUU/nsALV21xh0OptEM7Y3Wws9WlAwc+AglFA1oCYXYeIiIiIiLqnpAuGdqTRaHDaaafhtNNOw1133QWr1Yo1a9a0B0W/++47ty6W3jqEdtTx40ChUovFgs8//xyff/45ACAjIwMTJkxo7yg6fPjwqH6uXd3dd9+N7777DosXLw44d9OmTbjppptw0003ISsrCwUFBTAYDKirq8PBgwf9dh7tzGg0Yv78+cjPz4+k/ISx2+1Bz/v+++9jXI13wQRXiYi6A0UoyDHkIMeQAzVAB85oSY0gFAoADtUMVZcSxYqIiIiIiIiIiIjIQ0sNsP0DVxhUdcTsMtKQARSMBApHApn9AaHE7FpERERERNS9JXUwtDODwYDJkydj8uTJ+Nvf/obGxkZ88cUXWLZsGZYvX47Nmze3hzsj3Xa+85y6ujp88MEH+OCDDwAA+fn5mDRpUntH0QEDevadfoqi4N1338XPf/5zLFu2LOjzamtrUVtbG9Y1dTodFixYgPHjubUGERGFRonDC646YYcWwd/s0JnDqYfDpoViC+4mAiIiIiIiIiIiIgqTLsW1XbwM//U8X6Qx61gYNKMvw6BERERERBQUBkP9SEtLw3nnnde+DXZVVRVWrFjRHhTdvXt3+9xoB0UrKiowf/58zJ8/HwDQr18/lJaWRucT66IMBgM++OADXHXVVXj33Xdjeq2srCy8/fbbmDp1akyvQ0RE5EE6ARF4mlFY3QeECsjgXvR1qlrYbSbX5ZpbQq2QiIiIiIiIiIiIQqE1ArlDgaqtUVlOmnKOhUHT+wAiiBcUiYiIiIiIOmAwNAR5eXm49NJLcemllwIA9u/f377t/IoVK3D48OH2udEOiu7bty9qn0dXlpKSgnfeeQcPPfQQ7r33XthstqhfY/To0Zg/fz4GDx4c9bWJiIgCcapWQGPyO0dAQi86dPoUEnpdK2y2wNvCq1Jxn2e1A4ZwqyUiIiIiIiIiIqKgFIyKKBgqU/KAwlGuQGha764dBjVkQI76VcA5RERERESUOAyGRqBv37646qqrcNVVVwEAtm/f3h4UXblypdsW55EERTsfSwZ//OMfcdFFF2HOnDlYunRpVNbMzMzEfffdh5tuugkajSYqaxIREYVCgQKjkhpwnhDSramoXm+BEEE8H5CAzW4GZBd+0ZiIiIiIiIiIiKgra60H9KmAEuJ7SfnDIYUmpO3kZWqhKwhaMBJILezaYdCOdCZXiJWIiIiIiLosBkOjaNiwYRg2bBhuuOEGSCmxfv369m3nv/zyS1gslva5gYKfbWOdw6TJZMiQIViyZAm+++47zJs3D++//z6am5tDXmfEiBG47rrrcPXVVyM1NXAYh4iIKBY00MAAbVDf2wWOPTfQ6VqhURxQZeAXou12I6Qa3HbzREREREREREREdFRLLVCxCajYBFG3F/Kk64GcEHee06W4zqne7neaTOvdIQxaEEHRREREREREvjEYGiNCCIwZMwZjxozBnXfeCYfDga+++qo9KPrVV1/BbrcHXohw0kkn4fXXX4fVasUXX3yBVatWYcuWLdi+fTuOHDmCpqYm2Gw2pKamIi0tDX379sWIESMwevRonHPOORgwYEBC6o5Hp9eVK1fG/BpERBQ5BQoM0CHY2z3a+oVqtDZotdagr6OqfGpHREREREREREQUFMuRY2HQ+v3uxyo2hR4MBVxhTy/BUJne51gY1JwbZsFERERERETBY3ogTrRaLc444wycccYZuPfee7F//3789a9/xauvvgpVVQEk55bxoTAYDJg6dSqmTp2a6FKIiIgAAMF+6w4lFOpaV0AoTuh0LWHVRURERERERERERF40VwEVG4HyTRCNh3zPq/gROO4XgAhxd5784yG3vgchVciMfkDh0TCoKTuyuomIiIiIiELEYGicNDc3Y9WqVVi+fDmWLVuGTZs2tQdBGQglIiKKHptqw96mvX7n9E/tD72ij+w6NicqKwMHNxUoUEKKhQJ6xQqDoTnEs3ww6KKxSsRUVcXBgwexa9cuHDlyBA0NDbDb7UhPT0d6ejp69eqFESNGwGg0xrUuu92OrVu3orS0FDU1NbDZbEhJSUF+fj6GDBmCQYMGBb1WS0sLDAZDRPXs2rULO3fuRGVlJSwWC/R6PbKzszFo0CAcd9xx0Om6xr8nERERERF1E00VgC7T/3FuY0xEPV1TOVB+tDNoU1lQpwhbI2TtHiA7+NeGAAB6MzDySsiMPoApK4xiiYiIiMgnjQGyYGTAOUTkwmBojDgcDqxbtw7Lli3DsmXL8M0338DhcABgEJSIiJLPU089haefftrrMb1ej08++QRFRUURXePgwYM466yzPMaf/d+zyO+d7zYmcex7sU21hXytlhYHKitagvqeroUm5PUzDLUQiM7zBWE2Ac1RWSokdrsd69evx9dff42vv/4aW7ZsQUuL/yCtVqvF0KFDMX36dFx00UXIyordi+ebNm3Cq6++ihUrVqC52fdfUH5+Ps4991xMmjQJGRkZftcsKytDTU0NevfuHVLAtaysDK+99ho+/PBDVFZW+pxnNpsxefJkXHnllRg5MsAPvURERERERAfWAVsXQDPkAkA3wOdxDJ8J9Bkb//qIiGJFSqCp7FgYtLkivHUqNoUeDAVcXUKJiMg3px1oOeJ/jikH0LBRAhF1YsoCTpid6CqIug0GQ6Pohx9+wLJly7B8+XKsXr0aFoul/Vjn4IgQwuexzseJiIh6MpvNhieffBKPPPJI3K/tkA6UNpZCpwb/4oLN5gw6FAoAmjD6fipCDfkcr/RaQK+LWzDUbrdj7dq1+PTTT7Fs2TI0NDSEdL7D4cCWLVuwZcsW/POf/8SsWbNw6623RtyFs6OGhgb87W9/wwcffBDU/MrKSrzyyit46623cOmll+Kiiy7y+zzNarVi3759KC4uhtls9ru2qqp47rnn8J///Aetra0Ba2lubsbixYuxePFiXHDBBbj77ruRlpYW1OdBRERERERJ5sA6iK3vAQB0P70Pc68paM4+FlTSHP4G4qf3XR9sfc91ayLDocnF2ggcWOt/Tp/TAQN/7qRuQkqg4aArzFmxCcJSHfmaFZuAYReEvp08ERH513IEYs2jfqfIcXcCqYVxKoiIiKhnYjA0Aj/99FN7R9CVK1eitra2/Zi/IKi3Of6OK4qC0aNHR6tsIiKiLufDDz/Etddei6FDh8b1unW2OkhI2JzBdw2tqmoNsft3gm72UAREdgYQrZBpEDZt2oTrrrsuKmtZrVa89NJLWLlyJebNmxeVx8aBAwfw61//Gvv27Qv5XJvNhtdffx3bt2/HnXfeCb1e73Ouqqo4ePAg+vXr57NzaGtrK2655RZ88cUXIdcCAIsWLcKGDRvw4osvori4OKw1iIiIiIioh+oQCm2TXbYMANCcPRLmmk3QHf24jWA4NPnYmyF2L/U7RRaOYjCUujYpgfr9x8KgLTVRXV5YGyDr9wOZ/aO6LhERERERUTwwGBqCQ4cOtQdBly9fjsOHD7cfCycI2nlOx+NDhw7F5MmTMWXKFEyaNCmmW6kSERElmqqqmDt3Lp5//vm4XVNCos5aF9I5LS0O2G3O2BQUTYqAyM10dQwNIfQaD3q9Hrm5ucjJyYHZbEZDQwP279+PpqYmr/P37NmDq666Cq+++ioGDx4c9nUrKysxe/Zst+dvHZnNZpSUlCAlJQU1NTUoLS2F3W73mPfdd9/hkUcewZ/+9CdoNBqf11NVFYcPH8bAgQM9jjmdTtx8881Yuh6/BgABAABJREFUtWqV13N1Oh0GDRqErKwsNDc3Y9euXW6d6Nvs27cPs2fPxltvvYX8/HyftRARERERURLxEgptk122DKm1P0LfWun1OMOhRNQtSBWo2wtU/OgKg7bWxe5SihZoqmAwlIiIiIiIuiUGQ/2ora3FihUr2sOgO3fubD8W7SBocXFxexB0ypQp6N27d7Q+DSIiom7hyy+/xNdff41TTz01LtdrsjfBLj2Df/40NoQ2PyH0WlenUH3XeZp30kknYcKECTjppJNw/PHHQ6fTuR13Op3YsmUL3njjDXz44YdwOt3Dt7W1tbjmmmuwePFiZGZmhnx9p9OJ22+/3WsodMCAAbj99tsxadIkaLXH/s7Ky8vxyiuvYP78+R6hzO+//x5vv/02rrjiCr/XtVqtaG5u9thS/p///KfXUGh6ejpuvPFGXHTRRW5bxNvtdixfvhxPPPEE9u7d63bOoUOHcMcdd+Dll1/2G1QlIiIiIqIk4CcU2sZXKLQNw6FE1CVJFagtBco3AZU/QlgbYncpRQvkHgcUjgTyhgNa77vBEBERERERdXVdJzHQBbS0tGDVqlXtQdCNGze2hzejHQTNycnBxIkT24OgkXTAIiIi6ikee+wxvPPOO3G5Vq2tNqT5UgIWiyOMK0nEbTv57HSIVFN8rhVATk4OLr74Ylx00UXo16+f37kajQYjR47EyJEjcdlll+G2225DRUWF25yqqio8/vjjuP/++0Ou5a233sJ3333nMT5hwgTMmzcPJpPn35nD4cD555+Pk08+Gffeey+qqqrcji9cuBDjxo1D//79/V67trbWLRi6fft2vPDCCx7ziouL8dJLL6FPnz4ex3Q6HaZNm4bx48fj5ptvxurVq92Of/vtt0EFVYmIiIiIqAdrqgC2LojOWlsXAFkDgdSC6KxHRBQJSzXw9VMQNu+7zUSD1OiBvOOAglFA7jBAa4jZtYiIiIiIiOIlqYOhDocDX331FZYvX45ly5bh66+/bt8yNNpBULPZjPHjx7cHQU844YQofiZERETdT2pqqsf24Zs2bcKnn36Kc845J6bXtqt2NDuaQzrH6VThCnmGJvQzfKwjlYBzhEEXcE6sZWdn49prr8WsWbO8Bi4DGTNmDP773/9i1qxZqK+vdzv23nvv4Te/+Y3X8KQvTU1NeOqppzzGBw8ejCeffBJGo2fXB1VV2x+bvXr1wj333IM777wTVqvVbc7LL7+M++67L+D1VVWForj+/R5++GGPjqgpKSl47rnnAn5eKSkpeOqpp3DppZe6dbIHXF1IL7zwQo/upERERERElCRSC4DhM4EAHUODMnwmQ6FE1HWYshGLm66lxgDkjwAKRrrCoJrEv65GREREREQUTUkXDN2wYUN7R9Avv/zSbWvQQGHQUI7r9Xqceuqp7UHQU0891W17UiIiomQ3ZMgQmM1mfPnll27jTzzxBM4666yofd/MM+ah0FToNtZkD73DgKqGd30RhReuJQRajflQrLHrjBANgwcPxueff46UlJSI1hk0aBBuu+02j9Clqqr47LPPcM011wS91vz58z0CpgDwwAMPeA2FAq6t2zs+r+vTpw8uueQSvP76627zNm7ciN27d2PQoEE+ry+lhMPhgF6vx48//oh169Z5zPntb3+LgQMHBvX5mEwm3H///bj88svdxuvr6/HOO+/g6quvDmodIiIiIiLqgfqMde1ZEUE4VA6/mNvIE1HXIhSg4GfAgbURLyW1pqNh0FFA7hBA4ft2YbO3AEd+8j8nZwig6xq7GxERERERJaOk+YnnkksuwcqVK1FTU9M+Fk5XUF/HFUXB6NGj24Og48ePD6tLFhERUTK54447sGbNGqgdUpf79u3Du+++6xF8C1e6Lh1Z+iy3sWprNTRCA6d0+jjLkxK4YWdMSAC1jnykZBog67t2MDQ9PT1qa11yySV44oknPEKdq1atCikY+u6773qMjR8/3m/3dtVLCvi8887D+++/79HldunSpfjtb3/rt4a2DqHvvPOOx7HMzEz88pe/9Ht+Z6NHj8YZZ5zhsaX8u+++y2AoEREREVGyiyAcylAoEXVZBSPDDoZKXQqQf7wrDJpTwjBotFjrITa+6neKHHcng6FERERERAmUoIhD/C1YsAA1NTWQUrb/atv+veM28B2PA/B7fOjQobjhhhuwYMECVFdX47vvvsPDDz+MqVOnMhRKREQUhGHDhuG8887zGH/mmWfcunpHW64hF4PTB6OXqReMGu9dIztTlOhsWWUSrSHNb7BnQZ8TvcBld6HRaHDaaad5jB8+fDjoNTZv3oy9e/d6jF966aV+z1O8pIANBgPOPPNMj/G1a9d6bA3fmUajgcPhwNKlSz2OzZgxI6znjZdcconHWGlpKbZs2RLyWkRERERE1MP0GQuZXhzSKTK9mKFQIoothxUo3+jqNBmqrIGQOnPQ06U+FbLPWMiTrgMm3gccfxmQN4yhUCIiIiIiSipJ9xOQv+3fOwZAvR3v06cPJk+e3N4VtFevXrEtloiI/LK1qmiossHeqkJnVJCep4femDT3PPQYN998Mz755BPY7fb2saqqKrz88su44YYbYnZdAYFMfSYy9ZloUBpwCIf8zq+rtQIRbguforTAqGlFiz24MGqzIxVKVg60egHYA8/vabw916qurg76/C+//NJjzGg0eg14dqTT6SCE8OguP3bsWHz88cduY01NTfjpp59w3HHHeV1LCAGtVov169d73dJ+6tSpgT4NryZOnAij0YjWVveg8ZdffokRI0aEtSYREREREfUQB9ZBNBwM6RTRcBDywDqGQ4kouhytQOVWoGITUL0NQnVAHn85UHRSaOsoGtd28ge/8jlFGtJdcwpGAVkDXFvQE1Fi6MyQg6bC6XCguVMDCHNKCjRaLRBC2JuIiIiIwpN0wdDOb/C36dgRtE1ubi4mTpzYHgQtKSmJS41EROSbVCX2bmrGhk9rUPp9I9QOjfoUDTDwxDSccE42+o80Q0SpwyPFVnFxMWbNmoVXXnnFbfy///0vLr/8cmRlZfk4M3oMGkPAOS0tTigRdBUwKlaYNRYoOitgD/w52aQBMrsQOkPyvoit0+k8xjrfxOPP119/7TE2ZswYGAz+/70VRUFqaioaGxvdxocOHQq9Xg+bzeY2/uOPP/oMhqampkJRFK+1mEwmv1va+2MwGDB69GisW7fObfyrr77C9ddfH9aaRERERETUAxxYF9Y28oBr+3kJMBxKlOx2LQHUIO5QPvwdoOiAkmnu43bL0TDoRqB6B4TstNNKxcbQg6GAazv5TsFQacx0jReMBDL7MQxK1FUY0oCSaXBYrWioqnI/lJcHTYDXZ4mIiIgoOpIuGNpZWzcoKSVSU1Mxfvz49iDoqFGjEl0eERF1UFHago+fOoTqfVavx1UnsOubRuz6phG5/QyYPqcIBQND36KZ4u/666/HggUL0NTU1D7W1NSEZ555Bn/+858TWFl0GIQNqUoz9HoLnDLwC9Sq0AK5vaH1sqV5Mjl0yLOLa15eXlDnSim9bqs+cuTIoM7PysryCIbqdDoMGDAAO3bscBvfvXu333UAV3i0s+OOO85r+DVYP/vZzzyCoVu3bg17PSIiIiIi6uYiCIW2YTiUKMntWgKxe2lQU8WeFQDg+prRdxxQucXVGfTITs8waEfVO1ydRLXB7ajTLrsEUmsCdKajYdBRQEYfIISbiImIiIiIiJJJUgdDO3acUhQFEydOxDnnnIMpU6Zg6NChCayMiIg627uhCe8/cgD2VjWo+dX7rHjr7r248A990H9Uaoyro0hlZWXh17/+NebNm+c2/vbbb2P27NkoLi5OTGFRoBP29lCoIpxBBUOdaflQFE0cquu6VFXFN9984zHer1+/oM4/dOiQR7ATAAYPHhzU+WazGQaDAVarexC9X79+HsHQvXv3el3DYDDAbHZtidT5nFBq8cXb89WGhgYcOnQIRUVFEa1NRERERETdTFMFsHVBdNbaugDIGgikFkRnPSLqHkIIhXYkdi+F3L0UwcYzhXRCVm4Feo8J7UKKBjj9DsCYyTAoERERUbJqKodY86jfKXLcnUBqYZwKIurakjoY2nHbeCklPvroI3z00UcAgF69erV3Dp0yZQrfXCciSqCK0paQQqFt7K0q3n/4AC7/W392Du0GZs+ejTfeeANVHbaWsdvtmDdvHubOnZvAykK3a9cO2O2u7cZzFTuMulZoNK6PHaoWNa3Vfs9PP6KFou30ArfDCXmk3u95ojID0B4LlOr1eowYWhLGZ5B4q1atQnW159/ThAkTgjr/wIEDXsf79u0bdA29e/fGvn37oKrHvvYUFnr+IFldXQ2n0wmN5tjfvaIo6N27NwDAZrOhvLw8olq88XX+gQMH+NyViIiIiCjZpBYAw2cCEXYMBeBah6FQouQSZii0TcgxzYpNoQdDAcCUFfo5RERE1L1oDJAFI6GqqkfzDoPBAEVRAI0hQcUREXUvSR0M7ahjSBQADh8+jNdffx2vv/46AKCkpKQ9JDpp0iRkZ2cnokwiooAcNhV15bZElxE1UpVY/NjBkEOhbeytKhY/dhAX3FkMoQhIKeF0um9lpNE43LpId3WZhXpo9T1vi3GTyYQbb7wR9913n9v4Rx99hGuvvRbHHXdcYgrzQwMNnPDcGuv+B36PysqyBFTkrnfv3ljx2aeJLiNkUko8/fTTHuMajQaTJ08Oag1v29ADQEFB8G9uGo1GFBcX4+DBg+3h0JycHI95qqqiurq6fW1FUVBcXAyj0bUlWnl5uVu4NJxavMnPz/c67utzJyIiIiKiHq7PWEggou3k5fCLuY08UTLSxfmm+uptgMMKaBnqICIiok5MWcAJs2G3WnGkQzMZAMjLy4PBwOcPRETBSrpgaMfgT8cwqLdAUMfjO3fuxK5du/Dss89CCIFRo0a1B0XPPPNMmEzsREdEXUNduQ0v3bo70WV0KbVlNrx8e2miy4iaq+cNQm5fY6LLiImLL74YL7/8stvW3FJKzJ07Fy+++GLiCvNCCw100KDFSzCUIvPWW2/hxx9/9BifPn26146d3tTU1HiMCSG8Bjv9MZvN6NevHw4fPgyr1YrMzEyv8+rr61FQUACDwYDevXu3h0J91QIAubm5IdUS7Pm1tbURrUtERERERN1YBOFQhkKJkli/M11fO7YvisvlhOqArN4OFI6Ky/WIiIiIiIiSUc9rN+aD0WiElLL9F+AKB7T9AuD3uBCi/Ziqqli/fj0ee+wxTJ8+HVlZWZgwYQLuv/9+rFmzxqMTHREREQVHq9Xi1ltv9Rhfs2YNvvrqq7DWbHQ0ot7ufwv2UGmhgQE6hLFRFgWwe/duzJ0712PcZDLhtttuC3qd+nrPf3OTyeS23XuwjEYjBg4ciL59+/oMYzqdTvTt2xcDBw50C4X6qgUAUlNTQ66lI41Gg5SUFI/xurq6iNYlIiIiIqJurs9YV8gzBAyFEhGKToHsFcb27mGQGX0BJel61xAREREREcVV0vzUVVdXh3Xr1mHZsmVYvnw5vvnmGzgcjvbjHQOigOfW8t6Ot82x2WxYvXo1Vq9ejb/+9a8wm80YP358e0fRUaN4xyMREVGwzjnnHIwcORKbNm1yG587dy7effddr12+/am11kLfqkeGLsPnnE7f9v06FgqlaGtqasKcOXNgsVg8jt12223o3bt30Gt5W8NsNkdUX1v3UG9SUlJ8ru+tlrZzImUymTzW93U9IiIiIiJKIn3GQlobIHYv9TtNQgDDZzIUSpSsnHbXtu5lG4CqLRCqI+Ap4ZKZ/YGCUUDBz1xbxBIREREREVFMJU0wVK/XY8KECe2dPZubm7Fq1ar2oOjGjRs9OoV21HnbeX/Hm5qa8Omnn+LTTz8FAOTk5GDixIntQdGSkpJYfZpEREQ9wh133IHZs2e7jW3evBmffPIJpk+fHtJadtUOm2pDvb3eazhUSuDIkdag1tIEGQp99ZVj224NSKmGQTn2orpd1aHcUuT3/OxiHTS6TgFYuwOy7Ijf80SvHEDX6emd0xaw3q7A6XTi9ttvR2lpqcex8ePH48orrwxpvY43ALUJp1toZ1qt96fPdrs9pFr8rRVpPf5qISIiIiKiJFI4CggQDMXoq4H8EfGph4i6lpZaYO1cCEdwr4uFSkIAWQOBgpGuMKjR903bREREREREFH1JEwztzGw249xzz8W5554LAKipqcGKFSvag6I//fRT+9xIg6LV1dVYsGABFixYAAAoLi5uD4lOmTIFhYWFUf/8iIiIurNTTz0VZ555JlatWuU2/uSTT+Lss8+GThd6x87q1mqPYKiUQEW5BdZWZ8DzNVBgZKfQmLnvvvs8/r0BoKioCI8++mjInWKdTs9/U0VRwq6vja9wqbfrBToWq3r81UJEREREROQmJSfRFRBRohgzAX0qEMVgqBQKkD3I1Rk0/3jAkBa1tYmIiIiIiCg0SRsM7Sw7OxszZ87EzJkzAQCHDh3C8uXL24OiBw8ebJ8baVD0wIEDeOWVV/DKK68AAIYNG9YeEp04cSIyMnjXJBER0R133IHVq1dDVdX2sX379uGdd97BFVdcEfJ6NtWGnQ07oREaFJuLoRN6VJRb0Noa3BZZesGnTbHy6KOP4t133/UYz8rKwvPPP4/MzMyQ14xVYDKc7p/hhEkjqScanUiJiIiIiIiIqIcTAigcDZR+FtEyUihAzhBXZ9D8Ea6wKRERERERESVc5G2KeqiioiJceeWVePnll7F//37s2LEDzzzzDC6++GJkZ2dDStn+CzgWBm0LhPo7LoRwO75t2zY8/fTTuOiii5Cbm4tTTz0Vd911F5YtWwar1ZqwvwMiIqJEGjp0KGbMmOEx/u9//xvNzc1hremQDlhVK1RVhhQKBQDv/Sql11EK3lNPPYUXX3zRYzw9PR0vvvgiBg4cGNa6er3eYywaW6z7WsPb9QIdi1U9/mohIiIiIiIiImrX64TI1yg5BzjxN0DxqQyFEhERERERdSEMhgZp8ODBuP766/HOO++gqqoK69evx9y5czF9+nSYzeaIgqIdjzudTnz77bd4+OGHMXXqVGRlZWHKlCl48MEHE/OJExERJdDNN9/sEXKrrq7GSy+9FNG6h+orYLFFvk2WSYS+hqo1RnzdnuLZZ5/F008/7TFuNpvx/PPPY/jw4WGvbTabPcbCDRQHs0Zqqu83PrzVEst6/NVCRERERERERD1QSy1gbwn9vNRCyNReEV1a7PwY2LcqojWIqIdx2oGmcojmCmhbq91+ieYKoKncNYeIiIiIYor7TIZp1KhRGDVqFG6//XY4nU5888037dvOr1u3zq3TZ+et5TtuK992vKOOAdLW1lasWLECK1euxF133RXDz4iIeorMQj2unjco0WVEzaHtFiz9T1nE60z9bS8UDU1pD+F3pNFoPL4Wd2WZhcnTDbCoqAiXX345XnnlFbfxl156CbNmzUJ2dnZY69q0zUBmM/SNOdDYwwtqpigt0MIOSEPQ50iNDg5zHtCghnXNnuSll17CE0884TGekpKC5557DqNGjYpofW/bz1utVthstog6ajY2NgZ9vUDHGhoawq4DOPb5hFILEREREREREfUQ1kagYiNQth6ibi/ksF8A/c4IfZ1eo4Gd/l9/bU4fCrsxF5mVa7weF9sXufbV6Xdm6Ncnop6n5QjEmkdhAOARPd/t+k2OuxNILYxzYURERETJhcHQKNBoNBg7dizGjh2Lu+++G62trVi9ejWWL1+OZcuW4YcffmgPIXUOiQLuQdFAx4mIAtHqFeT27TkdCXOKDfjhkxpU77MGnuxDbj8DRk7JglAEpJRwONy3D9dqtd0qGJpsrr/+eixcuNAtkNfc3Iynn34a99xzT/gLSwHFHnyosyOjYkWKaIVNen/c7Nq1A3a7K7BXb6yHTnEAUGBPK4BT1qGh0v8W9ulHtFC0ndZ2OCGP1Ps9T1RmAFpN+8d6vR4jhpYE/oTi7NVXX8XDDz/sMW40GvHMM8/gxBNPjPgaeXl5XserqqpQVFQU9rrV1dVex3Nzc0Ouxddawaqqqgq5FiIiIiIiIiLqxuwtQOWPQNl6oGYXhOxw83H5+giCoR/7PFxbOAFNOWMAAFLRIqv8C9+1ERERERERUZfBYGgMGI1GnHXWWTjrrLMAuLpBrVy5sj0oumXLFp/nBuomSkSUbIQiMH1OEd66ey/sraF3WdQZFUyfUwSh8Otpd5WVlYVrr70W8+bNcxt/5513MHv2bPTt2zesdTXWFAiE/rgwCBtShQUAoNXZAKtnEPv+B36PysrIO91Gqnfv3ljx2aeJLsPNm2++iQcffNBjXK/X41//+hdOO+20qFzHV/izrKwsomDo4cOHPcYMBoPP8CcA5OfnQ6/Xe3T3LCuL7DHi6/zi4uKI1iUiIiIiIiKiLsRpA6q2usKgVdsgpNPrNFG3F7KlBjCFuMOOKRsysx9gOQJha3I7ZC/5OZoMQ9o/bsoZg9TUVOh2feQ2Tw6aCpRMC+26REREREREFFNKogtIBunp6Tj//PMxb948/PjjjygvL8ebb76JWbNmtW9fzAAoEZFvBQNNuPAPfaAzhvZtS2dUcOEf+qBgoClGlVG8zJ492yN4Z7fbPcKioVDU0O+P0Qs7UpVmAIBGa4NW47mNN/n29ttv44EHHvAY1+l0eOqpp3DGGWF0tfChf//+Xsf37t0b0br79u3zGOvbt6/f53JCCK8B5ljUAgD9+vWLaF0iIiIiIiIiSjDV4QqDbnoDWHEfxMbXICo3+wyFtivbEN71Tvw/YNJfXQHPo+SwC+AsHucx1Vk8DnLYBcfmMRRKRERERETUJbFjaBypqopvv/0Wy5Ytw7Jly7Bu3Tqoqqv7HbeLJyLyr/+oVFz+t/74+KlDQW0rn9vPgOlzihgK7SFMJhNuvPFG3HfffW7jn3zyCa655hocf/zxIa/pMDRD05oadM9QLRxIU2wQABTFCZ2uBbYwwqXJ6r333sNf//pXj+c8Op0OTz75JCZMmBDV62VnZ6OgoAAVFRVu49u3b49o3W3btnmMDRs2LOB5xx13HHbt2hXVWrZu3eoxVlhYiKysrIjWJSIiIiKiHsKQATnqV7Db7WhoaHA7lJ6eDp1OBxgyElQcEXmQKlBT6toSvmIThN0S+hrl64GBk0M/T3t0R5ySaZAAoDMB/c4ErD5eh+13pmuevYWhUCIiIoqupnKINY/CCKCPjyly3J1AamE8qyIi6paYZoixzZs3twdBV61ahcbGxvZjDIMSEYWmYKAJVz02CPs2NWP9pzUo/b4Raoeb5BUNMPDENIw+Jxv9Rpq5fXwPc/HFF+Pll19267IopcTjjz+O//73v2h0NPo+2QupccCpb4HWZoISRDzUrLRAQIEQKvSG5jA2oU9e//vf//CXv/zF47mPVqvF448/jsmTw3jDIggjR47EZ5995ja2fv36sNdraGhAaWmpx/ioUaOCqmXx4sVuY7t370ZjYyPS0tLCqmfDhg1er0NERERERATAFewqHAXVakWLqHI7lJqXBxgMCSqMiNpJCdQfcAU6yzdAWBsCn+OHaDwM2VQBpBaEv0iwQc9+Z4Z/DSIiIiIiIoo5BkOjbM+ePVi+fDmWLVuG5cuXo6rq2AtuncMQbVuOMiBKRBQ8oQj0PyEV/U9Iha1VRWO1HbYWJ/QmDdJyddCHuN08dR9arRa33XYbbrnlFrfxtWvXYvXq1VDyQv+3d5gaoLOlQC90aAkwV0ACQkJvsLj+7Merryxq/3NRcSp0umO1Oe0SNQftfs/PLtZBo+sUPbU7IMuO+K+xVw6g6/T0zpnY7e4XL16MP//5z+1d0ttotVrMnTsXZ599dsyuffrpp3sEQ7dt24aamhpkZ2eHvN7atWs9Pg8AGDt2bFC1dOZ0OrF27VpMmxZ6Z40jR4547V7q7TpERERERERE1MU0lgHlG4Cy9RAt/l/vCVn5eqDknOiuSURERERERN0Og6ERqqysbA+CLlu2DPv27Ws/5isI2pG/UKi3+UREdIzeqCCnmN0tksm0adMwatQobNy40W380ccexW0P3hbyelLjgGKwQbQG9zjS6y1QhDPwRAIAfPzxx/jjH//oEabUaDR45JFHcM45sX2TYsKECRBCuD3fUlUVn376KWbNmhXyeh9//LHHWL9+/TBw4MCA5w4aNAh9+/bF/v373cY/+eSTsIKhn3zyidfnmhMnTgx5LSIiIiIiIiKKA8sRV2izbD1EU3lMLiEVLeCIwk3C9hbgyE9Q7HaYGty7mCqyHNDpgJwhrs7EREREodIYIAsC7H6l4ft/REREkWIwNESNjY1YuXJle0fQLVu2tB+LRRCU3USJiIjc3XHHHfjVr37lNrZj2w58ufTLsNZrMdZC21oYcJ5Wa4VGcYR1jWS0dOlS/P73v4fT6R6k1Wg0eOihhzB9+vSY19C7d2+cdNJJ+Pbbb93G33jjDVx++eUh3YRTVlaG5cuXe4z//Oc/D3qNGTNm4Omnn3YbW7ZsGcrKytCrV6+g15FS4s033/QYP+WUU1BYGPixTERERERERARDBuSoXwWcQxGyNhzrDFq/P+D0cEihuEKavUYD+ccDWmPki1rrITa+Cj2AXF/XHXcng6FERBQeUxZwwuxEV0FERNTjMRgagM1mw5o1a9o7gn7//fftAYdYB0HT09MxYcIETJ48GVOmTAn3UyAiIupRTjnlFEyYMAFffPGF2/j/XvtfWOs5NXbYdBbA6n+eRut/+3c6Zvny5bjjjjvgcLgHaRVFwT/+8Q/MmDEjbrVcccUVHsHQ3bt3Y+HChZg5c2bQ68ybN8/j89Hr9bj44ouDXuPSSy/Fc889B7v92GPJbrdj3rx5ePjhh4NeZ+HChSgtLfUYv+KKK4Jeg4iIiIiIiJKczgQUjkp0FT3Xwa+Bsh+Amt0QiH4DEAkBZA1whUELRgL61Khfg4iIiIiIiLo3BkM7kVLi22+/bQ+Crlu3Dq2trW7HO+oc7owkCGo0GjFu3Lj2IOhJJ50ERVHC/VSIiIh6rNtvvx1ffvml2xblliZL2Ou1GuqBpmhURl9++SVuueUWt/Aj4AqFPvjggzj//PPjWs/UqVMxePBg7Ny50238oYcewkknnYR+/foFXOPjjz/GokWLPMZ/8YtfIC8vL+haCgoKMHPmTLz99ttu44sWLcKkSZNwzjnnBFxjz549eOihhzzGBw8ejLPOOivoWoiIiIiIiIgohg5/D1G7O+rLyvQ+rjBo4SjAmBn19YmIiIiIiKjnYDAUwNatW9uDoF988QUaGhraj0USBA00X6vV4uSTT24Pgp5++unQ6/XhfhpEREQ9noSEgMDQoUMxY8YMr2G9cKjcIj4qvv/+e9x0000eoVAAuOSSS9C/f39s2LAh4uuUlJQgNTW4ThiKouDPf/4zrrrqKrfxxsZGXH311XjmmWcwbNgwn+cvXrwYd911l8d4RkYGbrrpppDqBoBbbrkFn3zyCerr693Gf//738PhcOC8887zee7WrVtxww03oLGx0ePYn//8Z95QRERERERERNRV9BoNRCkYKs0FR8OgJwDm4G9QJSIiIiIiouSWlMHQffv2tQdBly9fjsrKyvZjsdweXgiBUaNGYcqUKZg8eTLOPPPMoEMNREREyUxC4rDlMACgKKUIAHDzLTfj408+ht3GLd67irVr18JqtXo9Nn/+fMyfPz8q13nllVdw6qmnBj3/tNNOw+zZs/HKK6+4jR8+fBiXXHIJLrroIsyYMQNDhw5FSkoKampqsGHDBsyfPx+rV6/2uuYDDzyAzMzMkGvPysrC3//+d49Qqc1mw+9+9zt88MEHuOyyyzBq1ChkZWWhubkZ27dvx+LFi/H+++97Dd3Onj0bp512Wsi1EBEREREREVGMFIyE3LYQQqqB53ohjVlArxOAwjFAWi/Ay3tPRERERERERP4kTTB0/vz5WL58OZYtW4Y9e/a0j8cyCAq4tvVsC4JOmjQJOTk54ZRPRESUtByqAwcsB9DqbAUAGK1G5BhyYM4x49yLz8UHb36Q4AqpO/jd736HvXv34osvvnAbt9vtIYdWb7nlFkyaNCnsWs466yzcdttteOKJJzyOrVq1CqtWrQp6rYkTJ+J3v/td2LUQERERERERUQzozUDOUKB6W9CnSH2aa4v4XqOBjH4MgxIREREREVFEkiYYevnll0MIEfMgaHFxcfvW8JMnT0ZRUVEEVRMRESW3FmcLDjYfhEMe2+q9srUSWuhQYanCxVddjM8/+ByWJktC6vP9jIG6Gp1Oh6eeegp//vOfsXjx4rDW0Gq1+P3vf4/LL7884nquu+46GI1GPPLII3A6nWGtcf755+Nvf/sbdDpdxPUQERERERERUQdSAo1lQPkPgD4N6D8h9DV6jQ4YDJVaI1Aw0jU3axCgaMIsmCjOdGbIQVMDziEiIiIiosRJmmBom2gHQXNzczFx4sT2IOjgwYOjUygREVGSa7A34LDlMKSX+OXhlsMQqhYZ5hzMvOISvPbsK15WcNE49dA6jD6PK1AhVCesCD2cV+9MuqdS3Zper8ejjz6KM844A3PnzkVVVVXQ544YMQL33nsvfvazn8HhcAQ+IQizZ8/GCSecgPvvvx9btmwJ+ry8vDzceeedOP/886NSBxEREREREREd1VwFlK0HytdDNFcCOLqte78zQ+/gmT8CUtFCqO6vI0hFB+SPcIVBc4cBCl9fom7IkAaUTEt0FURERERE5EdS/rQZSRA0LS0N48ePbw+Cjho1KiY1EhER9SRz5szBnDlzgp5f1VqFamu17wlCAkKFviEfV1x4I6648EZvk5Ai9BBSAA3elzEIG9KUZlhVJ/agPuj6AKDGKlHebINBH9JpPVqo/86JcsEFF+Dcc8/Fxx9/jCVLluD7779HQ4Png6SwsBBjx47FjBkzcPrppwPw/zwyHKNGjcKCBQuwdu1afPDBB1i3bh0qKio85qWnp+PEE0/EtGnTMH36dOj1fOARERERERERRUVrHVC+AShbD9Fw0OOwaK2FrN8HZPYPbV2tEcgbDlRsghQaIHeoKwyaNwLQGqJROREREREREZFPSRcMDXUreYPBgNNPP719e/iTTz4ZGg238iAiIooVh3Sg1lYbcJ7UOGFLPQJ9Yx48v5t3CIX6oBd2pCrNYdXY5JDY36QCUMI6nxJPr9fjwgsvxIUXXggAqKysRG1tLWw2G0wmEwoKCpCWlha3ek4//fT28GlDQwMqKyvR0tICvV6PrKws5Ofnx60WIiIiIiLqIewtwJGfoNjtMHW6GU6R5YBOB+QMAXSmBBVIlEC2JqB8E1C+HqjdA+Flxxo3ZetDD4YCQL/xkLlDgfyRgD4lrFKJiIiIiIiIwpF0wVDAMwzaMQiq0Whw0kkntQdBx40bB4OBd24SERHFi1Zo0cfcB/ua9nndRr4jqXFAKg4IteNTmsChUJ1wIE1pPhYoFcF3gbSpwJ4GFVKGvoMYdV35+fldJnyZnp6O9PT0RJdBRERERETdnbUeYuOr0API9TFFjruTwVBKHo5WoGKzKwx65CcIqQZ/bvlGYOj5gBJi45Csga5fRERERERERHGWdMHQtlBoWxhUCIGf/exn7VvDT5gwIa7doYiIiMiTSWNCoakQZS1lPucoDh10TTlQ1I4vyAsYNAINKb7PE0KiqMUIoR7r9qnTtQZVl1MCpQ1OOEJ434CIiIiIiIiIiBLEaQeqtrnCoFVbIVRHWMsIWyNk7W5Xl10iIiIiIkoMoYU0FwScQ0QuSfW/oS0MOmjQoPYg6OTJk5Gb6+t+aSIiIkqUTH0mWh2tqLV7biuvsZmga8qCcNtE3tUpVIUddl2L/8XFsW7gOl0r7MIZREUS+xolWjq8f9C5CzkRERERERERESWY6gSO/OQKg1ZshnBao7Nu2XoGQ4mIiIiIEsmcC5zx+0RXQdRtJE0w9Je//GX79vB9+vRJdDlEREQUgNMp4ahJhWJsgdqho6e2JQ3alnS4RzIFUhQ9hBpaUFOjtUGrtcIeRC60qkWi3ua+5XxKSgqc4TWaICIiIiIiIiJKHHuLKzzpT84QQGeKTz2RkipQu8cVBi3fCGG3RP8aFZuA4TMBJWneWiMiIoqNpnKINY/6nSLH3QmkFsapICIiop4paX56ffXVVxNdAhEREQXJ6ZQoK7PAYVehd2TDml4JqTihb86Cxtb5DYnwQqGK4oQuUGfRDo60So+x9PR01NZwX3kiIiIiIiIi6mas9RAb/b9vIsfd2bWDoVICDQddnTzLN0BY62NzGV0KUDAS6DUaEEpMrkFEREREREQUbUkTDCUiIqLuwemQKCtrhsPhClwKKaBvzAGEhOLUdZodXihUCBV6fQsi2QjeYDDAZDKhFs0RrEJERERERERERCFpqjgaBl0PYamOySWkRg/kH+8Kg+YMYZdQIiIiIiIi6nb4kywRERF1GZ1DoW0U1dtTFgFTGKFQANDpWiHg2QE0WIqioHfv3hAikmgpERERERERERGF5KePIPYsj8nSUmiAvOGuMGjecYBGH5PrEBERERGRJwcU2KCFHg5owR0biaKBwVAiIiLqEhwOiXIvoVBfTIoOShihUMDVMTTcXKiiKCguLobRaITdzh9KiIiIiIiIiIjiJmsAsCd6y0mhANklrjBo/s8AnSl6ixMRERERUVAqkY6tohh2oYVOOjBcHkQ+GhJdFlG3x2AoERERxZSERHlLORQoKDAVeJ0TeihUD0VVollmUAwGA3r37g2j0Rj3axMRERERERERJb2cIZC6FAi7JaJlZGZ/Vxi0YBRgSItObUREREREFDIbNNgiiuEQrgibXWixBcXIlDughzPB1RF1bwyGEhERUcw4pRMHLQdhcbherDdoDMjUZ7rNcThUlJdZohYKFVJBmjUFGuH+g4IiVCiKAwCgCeFzaNOrVy9kZmaGcSYREREREREREUWFogUKRgIHvwr5VJlW5AqDFp4AmLKiXxtRMnHagZYj/ueYcgCNLj71EBERUbdVgYz2UGgbh9CiUmagGDUJqoqoZ2AwlIiIiGLC6rTigOUA7Kq9fay8pRx6RY8UbQqAMEKhGj0Up/9OoamwI6XVvaOnojihNzRBBDjX77VN3EqMiIiIiIiIiCgqVAfQVA6kF4d+buHooIOhMiXvWBg01ftONkQUhpYjEGse9TtFjrsTSC2MU0FERETUXZUL7zdtlYlMFEsGQ4kiwWAoERERRV2jvRGHLYehwj3wKSFx0HIQA1IHQKiaqIdCTUorUkSr25gQKvSGZojQPgUiIiIiIiIiIoomqQI1u4Gy9UDFJtfHk+4DNPrQ1skeCGlIh7A2eL+MMcMVHu01GkgrAgRfFSIiIiIi6grs0KAGZlhxrKt4PVK8zq2HGfuR0/6xAXZkoxk6bi9PFDQGQ4PgdDqxbds2bNq0Cfv27cOhQ4dQVVWFlpYWtLa2wuFwtM8dOnQo/v3vfyewWiIiosSqtlajqrXK53GndGJ/8wHo63LhdPic5iaYUKhB2GAWLe6DQkJvsEBABnchIiIiIiIiIiKKHimB+v1Hw6AbPcKcsmobUDgqtDWF4uoAum/VsXX0qa4t5nuNBjL7u+YQEVFiaAyQBSOhqiqsVqvbIYPBAEVRAI0hQcURUaI4oMAGLfRwQIvgmsZQz9IEA74XA2ETusCTAUghsEMUuY3ppR0nylKkwurjLCLqiMFQH0pLS7FgwQIsWbIEa9eu9XjS6ktTU1OMKyMiIuq67KodR6xHAs6zqVY4jUega8oJ2MkzmFCoXtiRqjR7justUEQQd42xcwQRERERERERUfQ0lrnCoOXrIVr8bP9Ytj70YCgAFI6GPPQNkH+8KwyaPRhQNOHXS0RE0WPKAk6YDbvViiNV7k0k8vLyYDAwFEqUbCqRjq2iGHahhU46MFweRD68d3+nnqtUFAQdCvXFJnQoRQFGyv1RqoqoZ2MwtJOFCxfin//8J7788sv2MSlj12WstbUVJ598Murr670e/8c//oErrrgiZtcnIiKKJp2iQ1FKEQ40Hwg416mzQas4IFTfT0eCCYXqhANpiudW8VpdKzRKcC1JHeZcoKY8qLlEREREREREROSFpRoo2+AKgzYF+TpL9TbA3gLoTKFdK6MPMPE+QBPZG8tEREREFFs2aLBFFMMhXO8H2oUWW1CMTLkDem4JnlQsiM6NAdFahygZMBh61Oeff4477rgDmzdvBuAeBhVBdBELNzxqNBpxwQUX4MEHH/R6/Nlnn2UwlIiIupVUbSryjfmobK30OUc4tdA35kCJMBSqFU6kK00eW8VrtDbotMF1+3aYc6FqUoKaS0REREREREREHbTWA+UbgPINEPWhd+0RqgOycjNQdHKIJwqGQomIiIi6gQpktIdC2ziEFpUyA8Xw01meepwsNKERId4Q1omp+RDG/PBnQPppDjT6GsCcG9F1iHqKpA+GNjU14aabbsJrr70G4FjAs3MY1F/wM5jgqD+33norHnvsMdhsNo9rrlmzBnv27MGAAQMiugYREVE85RhyYHVaUW/37Iit2I3QN2VDSN/fP01aPRSH/1CoRjiRrjR6hEIVxQmdriWoOp3GdDhSsgFrcCFSIiIiIiIiIqJub9cSQLUHnnf4O0DRASXT3MdtzUDFJtc28LWlHq/NhKxsfejBUCIiIiLqFspFltfxMpGJYuklGCq0kOYCSCnhdLqH/zQarSufI5I+6tQtlchyNMKEWpEa9hqZznoYmg75nSP9hUaJkkxSf7XcsWMHfvGLX2DHjh0egdBYbh/fWW5uLi6++GK88cYbXkOmr776Ku6999641UNERBQNvVJ6wdZkQ4vzWEhT25oKrSXDY9v3joIJhSpCRbrSBKXTGw9CqNAbPLeV90bVGWFPLQhiJhERERERERFRD7FrCcTupUFNFXtWAIDr1Zf+E4DKLUD5eqB6B4RUo1dTzU7A1gTow3+DmIiIiIgSzw4NamCGFcc6u9fD+6599TBjP3LaPzbAjmw0Q2fOBc74PWxWK6qqqtzOycvLg8HAbcS7Kw0kxshSlKIAe0To79EOkBUYiIMxqIyo50raYOj69etx9tlno7a2FlJKn4FQX91Aox0c/e1vf4s33nijfW0hBIQQkFLijTfeYDCUiIi6HQGBQn1v7G3eCylU6CyZ0Fr9b9kebCg0Q2mCBp3egBASeoMlqC4VUqOFPb3Ite0YEREREREREVEyCCEU2pHYvRRy9+cQnV+LiZaUPKCllsFQIiKibs4BBTZooYcD2lg9b6AuqwkGfC8GwiZ0gScDkEJghyhyG9NLO06UpUgFd/rrqRQAJbICWunETqV30OcNVg+jP6pjVxhRD5WUwdAtW7bgrLPOQm1trVsAs6OOgdB4dA89/fTT0b9/f+zbt6+9nrYadu/ejdLSUgwcODDmdRAREUWL3a6iqtwGPXIAIaE49H7nm3R6KHb/oVABiXSlCRo4PY7p9RYownO8MykU2NKLIBVNwLlERERERERERD1CmKHQNtEOhUpTNlA4Gug1GkjrFdW1iYiIKP4qkY6tohh2oYVOOjBcHkQ+GhJdFsVRqSgIOhTqi03oUIoCjJT7o1QVdVV1whz6fMlgKFGoki4YWldXhwsvvLA9FAq4Bz87B0KFEDj++OMxYcIEDB48GDk5OcjOzsbPf/5zr4HSSFx22WV4+OGHvXYp/fzzz/F///d/UbsWERFRLNntKsrLLHA6VSgI/ENgKKFQrZdQqFbXCo3iCK629EJILbeZICIiIiIiIqIkojMlugJIfRpQeIIrDJrRlzu5dGU6M+SgqXA6HGi2WNwOmVNSoNFqAV1ob+YTEVHPZYMGW0QxHMIVP7ELLbagGJlyB/Re3tOhnsmC6Lz3Fq11qOtyQqAGoe0WUINUOCHAtj9EoUm6YOj111+P3bt3+w2FSinRu3dv3HrrrbjmmmuQnZ0dl9p+/vOf4+GHH/Z6jMFQIiLqLjqGQoMRTCgUANKUZuiEZ/hTo7VBpw1uSwmHORcqtyUjIiIiIiIiomTT70xIAGL7orheVmpNQMFIVxg0exAgAr8GRF2AIQ0omQaH1YqGqir3Q3l50BgY2CAiomMqkNEeCm3jEFpUygwUoyZBVVG8ZaEJjYj8ZqQsNEWhGurKGmGCU4QW8XQKDRqlCZmxKYmox0qqYOgnn3yCd955xyMU2vFjrVaLv//977j11luh00XW5jpUY8eORXp6OhobG9trautKumLFirjWQkREBAASEpWtldAIDXINuQHn2+0qyg5boKrBhUJTdHqIIEOhemH3GFcUJ3S6lqCu5TSmw5ESn5s9iIiIiIiIiIi6nDiFQ6VGD+SNcIVBc4cCSlK9FUVERJR0ykWW1/EykYliyWBosiiR5WiECbUi/AYtWbIJJbI8ilVRV+REeDeLhXseUTJLqp/G//SnP7X/uXMoFAD69OmDd955B6eeemrcawMAjUaDsWPHYsmSJe2B0Lb6ampqUFpaioEDByakNiIiSj6qVHHQchDNjmYAgEExIE2X5nO+3aairCz4UKgpyFCoWbHAIGwe40Ko0Bua0XnTMZsADmnca5BCA6lxAJZDAIB8Yz50SnxvACEiIiIiIiIiSrgYhUOl0AB5w4DC0UDecEDLjpJEREQ9kR0a1MAMK469x1KPFK9z62HGfuS0f2yAHdloBt+d6Zk0kBgjS1GKAuwRBSGfP0BWYKCsYPQvCWShGUZpQ6vQB32OUdqQheYYVkXUMyVNMPSjjz7Cpk2b2gOXgHun0NzcXCxfvhyDBg1KZJk47bTTsGTJEq/Htm/fzmAoERHFhU214UDzAdjUY4HMw5bD6JfaD0aN0XO+zbV9fPChUF1Q28enKC0wCS/bxAsJvcECAelxyAmgTuk87gDsje0f5RoDdz8lIiIiIiIiIup2rA1A9Xag1xjfnTr7nQlpbYDYE9lOZRICyClxhUELfgbovIdCiIiIqGdoggHfi4GwieCinVII7BBFbmN6acfJqII5FgVSwikASmQFtNKJnUrvoM8brB5Gf1THrjDqUhRInCR3YyuKUSN8NyUCAJO0Ig0tGCLLoHh5X5iI/EuaYOhLL73k9nHHUKher8eiRYsSHgoFgFGjRvk8tn37dkyfPj2O1RARUTJqdjTjkOUQnNLpNq5CxcHmg+if1h9acewpRKihUKNWC8WuCTjPpLQiRbR6PabXt0ARTq/HiIiIiIiIiIiShlSBhoNA1TagahtEwwHXsCHDtY17LC6Z2c8VBi0cBRjSY3INIiIi6npKRUHQoVBfbEKHA8jBsCjVRF1TnQgt+lsnzIBkMDSZmGDHUHkY64T/n1lOkHuRCi9NhIgoKEkRDG1qasJHH33ktm08gPat2q+//nqMHTs2QdW5GzrU9xe9bdu2xbESIiJKRjW2GlS2VEL6uOPKLu042HwQ/VL7QUCEHArVKwo0jsBPPwzCBrNo8XpMq2uFRrEHdT0iIiIiIiIioh7H0QpU73CFQau3Q9gaPedUbfMdDN23KuRuoTKttysM2usEwJQdes1ERNQjOKDABi30cEALH+8LNJVDrHkURgB9fKwjx90JpBbGqkyKEQsMUVmnFcFvH03djxMCNUgN6ZwapMIJAQ07QhIRRVVSBENXr14Nq9Xavo18x4Boeno67rnnngRW527AgAE+j+3atSuOlRARUbKxq3a/odA2Lc4WlLeUI0eTj/KylqBDoVpI6NTAP+zrhR2pSrPXYxqtHTot7wojIiIiIiIioiQiJdBcCVS7uoKithRCBng9pnobgAs9x/etgti+KLTLD5gMDPl5SOcQEVHPU4l0bBXFsAstdNKB4fIg8tGQ6LIojrLQhEaYIl4nHZYoVENdVSNMcIrAOwd25BQaNEoTMvnYICKKqqQJhnbWFhCdOXMmcnJyElCVd0ajEenp6WhsbHQLsEopUVdXl7jCiIiox9MpOvRK6YXDlsMB5zbYGmBtMAJqcD/YKdIJg0gJXINwIE1phvByTFGc0On4AyERERERERERJQHVAdTsPrpF/FaIliMhnS4s1ZDNVYA579hgGKFQABB7lkMa0oB+Z4Z8LhER9Qw2aLBFFMMhXPECu9BiC4qRKXdAD2eCq6N4KZHlaIQJtSK0bpAdZckm9AW3DO/JnFDieh4REfmWFMHQLVu2+Dw2ffr0OFYSnNzcXDQ2Htv6pa3TaccxIiKiWMjQZcBqsOKI1febDVqhg64hG3AEFwoVqhMmJQXwGvfsuK4D6UoThJeOpUKo0Bu8B0Y7k1o9AO/b0BMREREREfUoTRVAakH4x4moa2mtP7o9/FbgyE4Ipy2y9aq2AuYJrj+HGQptI7Yvcr1iw3AoEVFSqkBGeyi0jUNoUSkzUIyaBFVF8aaBxBhZilIUYI8I/eeMAbICA2UFFG4X3qNloRlGaUOrCLyLYBujtCEL3ncTJCKi8CVFMLS0tNTnsbPOOiuOlQTHZPLefp3BUCIiiod8Yz6sTiuaHE0ex4yKCUptFqQzmIgmIFQHTIoZgUKhGuH0GQqFkNAbLN6PdSI1WjhS84HmfUHVR0RERERE1G0dWAdsXQAMnwn0GRv6cer5dGbIQVPhdDjQbHHfgcOckgKNVgvozAkqjgAAUgXq9x/rCtoYeBeXkFRtA/ofDYbao3ATbTTWICKibqlcZHkdLxOZKJYMhiYTBUCJrIBWOrFT6R30eYPVw+jPTqFJQYHESXI3tqIYNSLN71yTtCINLRgiy44FhpurgfX/hV5KFDodbvM1e7SAEMDoawBzbqw+BSKiHiMpgqHl5eXt27J33J49JSUF6enpiSrLJ71e377VfUcNDQ0JqoiIiJJNUUoR9jbthVW1to+lazLgOJIKqQa5yNFQqAgQClWEinSlyecdonp9CxQReCsaKRTY0osgFAXpOv/f3xVuR0FERERERN3ZgXUQW99z/Xnre66fpjqGPwMdp+RgSANKpsFhtaKhqsr9UF4eNAZDggpLcvYWoHr70c6g2yHsMeyMVFsKOFoBrREomQYJQOxeGtZSctBUoGRadOsjIqIuyQ4NamCGFbr2sXqkeJ1bDzP2I6f9YwPsyEFlhzOpp6oTod1gVCfMgGQwNFmYYMdQeRjrxFC/806Qe5EKq/ugdEA0V0AAPt/Nk9Lh4wgREXWUFMHQ5mbvL6wUFHTNbZQcDu/fxJzOwKEYIiKiaFCEgj7mPtjTtAeqVJGjy4OlSg+pBrm9h2pHipIaVCg0Q2mCBt7TplpdKzSKPahL2tMLIbUG6OAKthIREREREfVIHUOfR4mO4c9Ax4kovqQEmitc27pXbQPq9kIEfddtBJcVGiC7BLA1u4KhQNjhUIZCiYiSRxMM+F4MhE0EF+2UQmCHcH89PhMOnBKL4qjLcEKgBqkhnVODVDghoOE28kRERHGTFMHQ1tZWt4+ldD3ZSEvz37Y6UVpaWjy6hQK+t5gnIiKKBZ2iQ3FKMWx2J+orjn3/DCjIUKiARLrSBA283/ig0dqh01q9HuvMYc6Fqg/tRQgiIiIiIqJux0vos43Y+h7kwa8gGg76Pg4wHEoUb3uWQ+z8OC6XkoYMIO8416/swYDWS1fYo+FQqHaIPSv8rzdgEqDoGApNRk470HIEwmaDttV9i2jRrAJ2PWDKATTsCUjU05SKgqBDob7YRVJEEJJaI0xwCk1I5ziFBo3ShExYAKGFNAdo4sXHERERUcSS4rupyWSCxWJp/1gIASklamtrE1iVb+Xl5V7HzebQ2rETERFFSuM0oL7CEmIoNPD28W2hUK2PUKiiOKHTWbwe68xpTIcjJTu4+oiIiIiIiLorP6HQNr5Coe3HGQ4lir+sgTFbWkIAmX2B3OGuMGhab8BL0wkPJdMAayOkEiD40+d0wNA1G2xQjLUcgVjzKAwAenU+ttv1mxx3J5BaGOfCiCjWLPByUwFRJ06fG3wHeZ45Fzjj91GsiIiIiLxJimBoSkqKWzC0zZEjRxJQjX+1tbVoampqD6+2/Q4AeXl5Ca6OiIiSidXqRHlZKKFQ29FOoYFfEEhTmqETDq/HhFChNzQHiJYevaTOCHtqgLtKiYiIiIiIurumCmDrguistXWBK6jGn6WI4iOzH6QuBcIe3A2wgUitCcgdCuQNd/0e7g4qhjR2AiUiIg9ZaEIjuIsl+ZeFZhilDa1CH/Q5RmlDFppjWBURERF1lhTB0NzcXFRXVwNAe9gSACwWC5qampCa2nW2nt20aZPXcSEE+vbtG+dqiIiou6tqrYJW0SJLnxXSeaGGQqXTBrMm+FCoXti9HxQSeoMFAoGvKzVa2NOLguuEQURERERE1J2lFgDDZwIBOoYGZfhMhkKJwqU6ASW0bVMhFCB3GFD2Q9iXlamFR7eIHw5k9Au9BiIioiCVyHI0woRaEf775+kyOjdDUNelQOIkuRtbUYwa4b+7uElakYYWDJFlUIJ474eIKGKWI+xsT3RUUgRDBwwYgG3btrUHQjtau3Ytpk6dmoCqvFu3bp3PYwMGDIhjJURE1J2pUsXhlsNotDdCQMCgGJCiTQnqXGurE+XlsQmFmhULDMLm87he3wJFeN9e3u2aQoEtvQiSb4QQEREREVGy6DMWEgi4nbw/cvjF3EaeKBRSAk1lQNU2oGorIDTAKTeEvk7ecSEFQ6WiBbIHHw2DHgeYskO/JhFRGBxQYIMWejighZrocigBNJAYI0tRigLsEaHfTDRAVmAgDsagMupqTLBjqDyMdWKo33knyL1IhTVOVRFRj1e+MfCc9S+5borl6x9EyREMHTRokM9jX3zxRZcKhn788cc+j40ZMyaOlRARUXdlV+04YDkAq9P1g7aExEHLQQxIHQCdovN7bmurExUhh0LNQYVCU5QWmITvH/61ulZoFB+dRDuxpxdCag1BzSUiIiIiIuoxIgiHMhRKFCSnDTiy0xUGrd4G0VrXfkhCADYLoA/u5tt2OcMgIfzukCKNWceCoNklgCb4rVmJiKKhEunYKophF1ropAPD5UHkoyHRZVECKABKZAW00omdSu+gzxusHkZ/VMeuMCIiSm4H1kHsXhpwmoAEtr7n+umLr4NQkkuKYOgpp5zidVxKiY8++gh///vf41yRd/v27cOaNWu8djYFgJNPPjnOFRERUXdjcVhw0HIQTuneddMpnTjQfAD9U/tDEd5DnKGHQq1I0aRCIHDXTpPSihTR6vO4RmuHThvcHaMOcy5Uffjb2FDXsnfvXpSWlqKsrAzNzc1QVRUpKSnIyspCcXExBg4ciIyMjJhd3263Y+vWrSgtLUVNTQ1sNhtSUlKQn5+PIUOG+L3BKBZ27dqFnTt3orKyEhaLBXq9HtnZ2Rg0aBCOO+446HT+w91ERERElAT6jIU8+BVEQ/CdmGR6Md8MIfKnpcbVEbRqG1CzC0J1eJ0mICGPbAd6hdjEQZ8CZPYH6va0D0kI11jecFcYNLUQ8PHeABFRrNmgwRZRDIdwvXVsF1psQTEy5Q7oEXiHJ+qZ6oQ59PmSwVAiIoqBA+tCvklWMBxKlBzB0NNPP93tYyklhBCQUuLHH3/EZ599hrPPPjtB1R3z9NNPu9XWMSCal5eHESNGJLA6IiLq6upsdShvKYf00X3CqlpxyHIIfcx9PI6FGgpVnVaYNalQggiFGoQNL732DJ5+/WWvx/U6HZa9+W/0KcwPuJbTmA5Hivft0w4ePIizzjrLY/zzzz9HcXFxwLUpfjZs2IAFCxZg5cqVqKqqCji/X79+GD16NM4880ycccYZSE9Pj7iGTZs24dVXX8WKFSvQ3Nzsc15+fj5mzJiBX/7yl+jVq1fE1/WmrKwMr732Gj788ENUVlb6nGc2mzF58mRceeWVGDlyZExqISIiIqJu4MC6kEKhACAaDkIeWMc3Q4jaqE6gbm97GFQ0VwR/btW20IOhAJB3HGRzBZA7zBUEzRkWeudRIqIYqUBGeyi0jUNoUSkzUIwazxM0BsiCAK9PabjjU3fmhEANQmvQUINUOINqJUFERBSCMEKhbRgOpWSXFMHQAQMGYMiQIdi5c2d76LKjhx56KOHB0LKyMjzzzDMe3ULbAqIzZsxIUGVERNQd2FQbylrKAs5rcjShsrUS+cZjIcywQqFKcKFQvbAjVfEdugMAm92Ox59/HU/cc7v/6+qMsKcWBFUjdU3bt2/Hww8/jHXr1oV03r59+7Bv3z68//77uPDCC/HQQw+FXUNDQwP+9re/4YMPPghqfmVlJV588UW88cYb+O1vf4vf/OY3YV+7M1VV8dxzz+E///kPWlt9d9Rt09zcjMWLF2Px4sW44IILcPfddyMtLS1q9RARERFRN8A3Q4jCZ2sCqrYD1VuB6h0QjsA/h3lVvR2QKuBjRxaf+o0HBkwK/TwiojgoF1lex8tEJoqll2CoKQs4YXaMq6JEaoQJThFaxNMpNGiUJmTGpiQiIuphtFCRL+v8zjEc+DLs10Ha8PUQSmZJEQwFgEsvvRR/+9vf2oOXHTtzrly5Ei+88AJ+/etfJ6y+G264ARaLxWtwFQAuueSSBFRFRETdhV7Ro8BYgIrWwB0uaqw1yNJnQafowgiFtrpCoUG8IKQTDqQpzQhmE7RFn6/C/13+CxxXMsDrcanRwp5exC3VurEXXngBTz75JOx2e8JqOHDgAH79619j3759IZ/b2tqKJ554AuvXr8fcuXNhMETW8aC1tRW33HILvvjii7DOX7RoETZs2IAXX3yRHXGJiIiIkkUEodA2fDOEkoqUQOMhV4fPqm1A/X4IH7ushELYLZB1+4As769h+KTRR3xtIqJosEODGphhha59rB7eOxjXw4z9yGn/2AA7stEMHbeX7/GcCO9GhnDPIyKi5GOEHaPkft8TmiqAre9E52JbFwBZAwE2IaIkkzTB0NmzZ+PBBx90C4QCaP/zLbfcgtNOOw3HH3983Gt74oknsGjRIo+62gwaNAhTp06Ne11ERNS9ZBuyYVWtqLPV+ZyjFVr0MfdxhUJbnKioCCcUGvjpg1Y4kK40Bf2Gi6qqeOg/r+CVufd5HJNCgS29CFLhBjTdkdPpxN13343//e9/PucYDAbk5uYiNzcXRqMRjY2NqKqqCmqb+WBVVlZi9uzZOHz4sNfjZrMZJSUlSElJQU1NDUpLS72GWFeuXInbbrsNTz31FDSa8B6TTqcTN998M1at+v/s3XmcXFWd///XuffW1nt3ks7WnT0EEgmrQFBZHAQXFmVRARX3ZVQEFUdFUOE3OiqjLAM6KovjBkj4wqAwoOKoSABlQDCBQPat00s66bX2e35/VFd3Vdd27+2qXj/PxyOEvsu5p6tvqqvqvu/n86e8630+H8uXL6exsZGBgQG2bNnC4OBgznY7d+7ksssu45e//CXNzc15RhJCCCGEENNGf3vqIkY5yMWQmSMZh/ABVCyGFcmu9qYGbIj7ITQLTF+BAaagRBQOvJIKgna9hIr2VuY4nS+5D4YKIcQk0E+AZ9UyYsrZc79Wis1qYdYyv45znN5GDdFKTFFMEo0MENQxIsr5jQ1BHaOR4h3EhBAzh5NqkBb2+ExGTE01c2H1BTDGm2SB1DjyOYiYgWZMMHT58uWcf/753HfffTlVQ5VShMNhzjrrLB5++GGOOuqocZvXf/3Xf3HVVVfltJDPnN+nPvWpcZuPEEKIqW1eaB7RZJRwMpyzLmSGaKluwVIWkXCC9vawq1BolcNQqKmS1Jv9KIdjp/3x6f9jw3Mvsu6YI7OWx2vnoa2xVWcUE+erX/1q3lCoz+fj7W9/O29605s46aST8PtzP2Ds7u7mxRdf5I9//CN/+MMfaGtr8zSHZDLJZz/72byh0KVLl/LZz36W008/HcsaOb97e3u5//77ufXWW+nr68va589//jO33norl19+uaf53HzzzXlDoXV1dXzyk5/k/PPPz2oRH4/Hefzxx/ne977Hjh07svbZu3cvn/vc57jrrrs8B1WFEEIIIcQUIBdDhBfhA6i/fIcAMH/0uq2pv/TrroKaeeM8sTIb6Eq1h+98Cbq3ovQ4VLHrehkOe2vljyOEEGW2Tc11HAotJKZ8bGMua4tV+BJTnoHmeL2VTbTQrWqLbhvSUWoJc5huwyhDdW4hxPRQshqkEE60rkPDmDqo6NUXSucUMWPNqFru11xzzfAF88xwaPrrtrY2TjnlFB5++OGKz0VrzXXXXccHP/hBbNvOmUva4sWL+fjHP17x+QghhJgeFGq4Imimel89i2sWYymLsOtQaJgqoxrTQSjUULanUGjav33/J1lfJ6pnYwdqPI2V1hntZH94f9afhE6MaUzhzJ133sl99+W+UTvxxBN58MEHuf766znllFPyhkIBmpqaOPXUU7n22mv5/e9/z/e//32OPfZY1/P45S9/yd/+9rec5aeeeir3338/b3rTm7JCoZAKab7//e9n/fr1LFiwIGffO+64g82bN7uey8svv8yPf/zjnOUtLS2sX7+eyy67LCsUCqkQ7VlnncX999/P61//+px9//rXv3L33Xe7nosQQgghhJhiWtelLmaMgVwMEdPKKw/DE/+GeuKbqJcfRB14paKhUO2vQS84Hn3Ue+G1n6jYcYQQopIGKc8N+OUaR0xuIeKs0vk7MGU6Wu/gKL2LELkdmMT0lq4IWeyPVIQUQozZGD4Pkc9BxEw3o4KhRx55JJ/61KdygjCZgcy+vj7OOeccLrzwQrZu3VqReTz11FOcfPLJfP3rX8e27awW8plzUkrxrW99q2BYQgghhMjHVCYtVS0YQ7/mm4PNLKhagEIRDifocBEKTSbDVBk1mA7uIjeUTYPZj6Gdvcmvra7KWfb3l17hN394InXsYB2JqiZHYxXTG+vlYOxg1p/keFQPmeFeeuklvvvd7+YsP+uss7j99ttZtmyZq/EMw+D000/nne98p6v9+vv7ueWWW3KWr1y5kptuuolQKFR0/0WLFvGjH/0oZ7tkMsm///u/u5oLwLe+9S2Syezzr6qqih/+8Ie0trYW3beqqopbbrmFlStX5qy7+eabGRiQNk1CCCGEENOeXAwRYkTPLtRAZ0UPoeta0MvehD7xcjjtq3DkxTDvaPAVfy8phBCTVSP9k2ocMflJ8E8Uk64IWexPUALDQohyaF2HrmtxtYuua5HPQcSMN2Nayaddf/31/PrXv2bbtm1ZgczMtvJaa/7f//t//PrXv+a8887jne98J29729sIBoOej3vgwAEeeugh7rjjDv7yl79kHTNT+vhKKc4//3wuuugi79+sEEKIGStoBofDoDW+VMVN96HQQaqNWkehUIWm3hzAcBG4XLVsMdVVIf749P9lLb/hhz/jTW88HVtaG05p1113HfF49gc+J510Ev/+7/+eU52zku655x56enpyll9//fWOX9stX76cT3ziEzlB1w0bNrBx40aOOuooR+O8+OKLbNiwIWf5Jz7xCcdB2VAoxHXXXcfFF1+ctbynp4d7772XD3zgA47GEUIIIYQQU5iHNmoSChXT0pwjoPvVsg6pTT/MOgzmrIbZh0OwvqzjTyrJOIQPFN8mNAvMsbWcFkJMLiv0fvoIcVB579LUqPtZofeXcVZiMpNW0KIiBrrguTuKb3PMB6F69vjMRwgx+e3egOrd42oX1bsHvXuDfB4iZrQZFwytqanh/vvvZ926dYTD4aLh0Fgsxn333cd9991HVVUVa9euZfXq1RxxxBEFxz9w4AC33347g4OD7N+/nx07dvD888+zefPmrONA/nb2aa2trfzoRz+qyGMghBBiZqj1jbSjdh0KTQxSbTqrFKrQ1Pv6Me0i7dlV/uP+y8cv489/fR7bHrmjePueffz8sSe5+JKljuYqJp/f/va3PPfcc1nL/H4/X//618c1FArwq1/9KmfZG97wBo4++mhX47z3ve/l9ttvzwmZrl+/3nEw9N57781Z1tDQwHve8x5XcznmmGN4/etfzxNPPJG1/Fe/+pUEQ4UQQgghZorWdehoL2rrY0U30yhYfYFcBBHT05zVsPm/xzyMrpoNs49IBU2bloMxQy6bhA+g/vKdopvo110FNfPGaUJCiPFgojlWb2Mbc9mu3N+Yv1S3s0y3z6yWlEKI8tMJ1EB78U10kWtOQoiZZfcGVzfHZlKb7kODfC4iZqwZ8glHtiOPPJJf/OIXXHTRRSQSiZxwKOSGNgcGBnjqqad46qmnhscZvQ/Ajh07+OhHP5p1vNEhnNFjj17W2NjII488QkNDw5i/VyGEECI8mKC9PQw4D4VWmTWYyu9o+zrfAFaxUChgmvnXr16xlPPOOIX/99j/Zi2/7fs/4Ly3v4Oqqtx282Ly+/GPf5yz7LLLLmPx4sXjOo9//OMf7NixI2e523b0kKrUefbZZ/Pzn/88a/ljjz3Gtddei89XPESdSCR47LHci/bnnHNOyXb2+Vx00UU5wdBt27axceNG1qxZ43o8IYQQQggxBc07CkoEQznmA9Asrw/FJDbQCZ2bUoFMl20BqZ6DrpqNGuxytZtWJjQuSwVB56yG6jnujiuEEFOcAazQ7Vg6yavGAsf7rbT3sQR3z7lCCCGEEGMyhlBomoRDxUw2Y2/oOvfcc/nlL385XLVqdEv3zIBoZhXR9J9CMrfJ3DbfOGmZodC6ujoeeuiholVJhRBCpOhojMTeTuLb9pLY24mOxiZ6SmV1IHqA3njvmMbwFgqtxnIYCq33DeCz40W3sXwRlCrcYv6zH74Uvy/7XpXOzk7uuusuR3MQk8vmzZv5+9//nrP8ggsuGPe5/PnPf85ZFgwGOeWUUzyNd9ZZZ+Us6+np4YUXXii579///ve8Le3PPPNMT3M57bTTCAaDOcvzfc9CCCGEEGIGq5o10TMQIpudgK7N8NID8Odvop74N9Tm/4a2//M23pzVjjbT/lr0wteij74M3ngdvPbjsORUCYUKIWa0Q6q6otsLIYQQQoxJfztsWl+esTatT40nxAwzIyuGpp1//vk89thjXHTRRXR1deVU8hwd3swMjxYKh44OmGbKt0/mMefNm8cjjzziuB2pEELMRNrWxDdtI/L7vxF74VVIjrQgxzTwr11J8J+Ox7d6Gcoo/Jw8mWk0bYNt9MR7UCj8NX6CZm4ArJTBwVT7eKeh0ERigGqzBksFHG1f6wvjs4uHcU0rjs+KFt2mdf5c3vP2t3LHr7Lbv91xxx1cfPHFNDY2OpqPmBwefvjhnGVHHnkkS5YsGfe5PP300znLjj32WAIBZ+f4aEcffTTBYJBIJJK1/KmnnuK4445zPZdQKOS6pX1aIBDgmGOOYcOGDTlz+fjHP+5pTCGEEEIIIYSoiEgPdL0EnS/BgVdRyTyfE3S+BKvOdT/2nCNg55/yrtJ1rSNVQesWgpqxdTKEyJLAIIaFnwQWdukdxLSURNFNjat9uqkhicJ0+HmzEEIIUTGDB6Bm3kTPQlRazVxYfQGMsWIokBqnZu7YxxFiipnRwVCAU089lWeeeYb3ve99PPHEE1kB0MwgZ7EqoZmcbjc6ZHraaafx05/+lIULF7qYvRBCzCyJnW30/ehBkns68m+QtIk9t5nYc5sxW5qp/ch5WIvnj+8kxyihE+we2E0kmQqeaTS7B3aztHYplnL+a9tTKNSodhwKrfFFCNiRotsYRhKfL+xovH/+6Ie495HH6e/vH17W39/PbbfdxtVXX+1oDDE55KtY+brXvW7c56G1ZuPGjTnL165d63lMv9/P4YcfzvPPP5+1fNOmTSX3ffHFF3OWHXHEESVb0Bdz5JFH5gRDncxFCCGEEEJME2YAPbfE61vT201RQoyJtqFndyrs2bkJ1be35C5qoAM92AVVs90dq3EZ2gygklG0GYDZq1Jh0NlHQKDW4zcgxPTVQR2bVAtxZeHTCVbrPTQzto5FYmrqI0RSma72SSqTPh2igcEKzUoIIYQA9ud2pcvx3J2poJ+0Bp/+WtehoWg7eV3XgurdU3j96gvlXBEz1owPhgIsWbKEP/3pT/zHf/wHX/3qVzl48KDjCqFujR6ztraWa6+9ls9+9rNFq40KIcRMF/vHVnpvuReixduWpyX3dHDoG3dRd/m78K9ZVuHZlUckGWH3wG4SOpG1PKET7BnYw+KaxShK/67wEgqtMqqxDGdVSat9UYJ28cCnUjb+wADKwRxsX5Ca2a18+MMf5sYbb8xad/fdd3PZZZfR0tLiaG75BK0gVVZV1jIDqRJSCb29vbz88ss5y1etWlVwn87OTrq7u7Ftm8bGRpqamvD7/WOey969e+nr68tZvnLlyjGNu2rVqpxgaL7vebTNmzdXZC6j9fb2snfvXrnZSAghhBBiJgg1wtGXTfQshEiJh+HA5lQYtOtlVKy/9D6jdb4Ei9/gbh/DgiPejg42QuPS1NdCiLximGxULSSGbj6PK4uNtNCgN+MnOcGzE+MtWeTz0Xo9QE+BtvHF9hNCCCHGbPcG1NbHSm6m0LDpvtRVSAn8TX9FwqHp0KfevaHoeiFmKvmUJMOnPvUp3ve+93HDDTdw22230d3dDeS2kU8rFRYttk9VVRXvf//7+epXv8qcOXPKMHshhJi+EjvbXIVCh0Xj9N58Dw1ffv+krxzaG+9l3+A+dIEgZTgZpm2wjQVVC4qO4z4U2k+VUY3PYSi0yhcjZJe4I1xp/IFBR6FQbVrE6xaCUlx22WX8/Oc/p7Ozc3h9PB7nxhtv5IYbbnA0v3wWhhbSUu09WOrFli2bicdjAHQdqMKyRl4T2AlNb0ei0K4A1B2wMKxRryMSSfSBnqL7qY56sEbu9Pf7/axZtcLl7L176aWXsO3cFmSjA4wbNmzg/vvv54knnuDgwYM52y9atIiTTz6ZU045hdNOOw3DcP+B8+7du/MuX7RokeuxMrW2tuYs279/P4lEAsvK/9I6Fouxf//+ss+l0P67d++WYKgQQgghhBCisrSGgQ7o3JQKdB7ajtJjbEnducl9MBRg4QljO64QM0Q79cOh0LSEsujQ9bTQPUGzEhOlkQGCOkZEjdygbekEa4aqyHbouqwgMUBQx2hkIPVF/37UX75T9Bj6dVdJm18hhBDOFQj2FaMkHDpz5AmHZoU+S60XYoaSYOgodXV1XHfddXzlK1/hvvvu42c/+xn/+7//SyQy0i43Hfh0UuFzdHj02GOP5eKLL+aDH/wgjY2N5Z28EEIAOpYg2Tl9PsjTtqbvtvXuQ6Fp0Ti9t62n9lMXoQyF1ppkYtQd8JY5oVWbY8kY+wf3lLzXup8eugL9zFq4DOXP/RU+OJCgo8N5G5+RUGjI0fYhX5yQPVByO78/jKGcVBlQxOoWoo1UkDEUCvHJT36Sr33ta1lb/eY3v+FDH/oQRxxxhKN5TgbXXf8FOjraJnoaLFiwgD/89n/G7XhbtmzJuzxd8fWVV17ha1/7Gv/3f/9XdJxdu3axa9cu7r77blauXMlnPvMZzjjjDFdz2bs3f6vCuXPnuhrHyf7JZJL9+/cXrGy7f//+vIHZsc6lubk57/JC37sQQgghhBBCjEkyDt1boSsVBlXhMn/+1L0VElGwAuUdVwgBwH6V/5pUm2qgRU+fz5OFMwaa4/VWXmE+AwRppJ+lupMgqc/hm+mlTr/KduZwkBqqiXCYbsNwWJBACCGEcMVDKDRNwqFTVz8BNhiFuw4CrLM3U0M09cVQ+JNN62H1Bbk/81LrhZiBJBhagN/v55JLLuGSSy4hHA7zv//7vzz11FM899xzbNy4kT179hCPFw8p1dfXs2LFCo477jhOPPFEzjjjjLxVpoQQopySnd0cuvoHEz2NScVu76bnmv+c6GkU1eRi29j1HyHQml0BdWAgTmdH8fbumVKh0CrHodCAL0GVHijZyN7yRTANZyFe2/ShR13sufDCC7nrrrvYsWPH8DKtNTfccAO33367o3HFxGlryw3D+nw+/H4/jz76KF/84hcJh52fpwCvvvoqn/rUp7j44ou5+uqrC1blHC1d+T2TUopZs2a5Ov5os2fPLni8QsHQfHMpNtZY55KvCqsQQgghhBBihtnyKNgO3p/v+xsYPlhxVv71kUOpiqCdL0H3q6hkrKzTzKR0Et39KjS/pmLHEGKmiGPSTTVRfMPLeqjKu20P1exi5POSAHFm0ZGxp5iuQsQ5Su8quD5InCP0vnGckZg2lIWunpsq1JHM7p5lmlaqUIeSmIIQYsgYQqFpEg6dQVrXQeMyqClQfKXUeiFmGHnF5UAoFOItb3kLb3nLW4aXaa1pb2+nu7ubcDhMJBJBKUVVVRVVVVXMnz+f2traCZy1EEKI6co0zKyv+3qjHDgQdbx/ItFHyKjGZ+T/MHi0gC9JDf0oXfxucNOK47Ocz4NR3weAZVlcccUVXHHFFVnL//KXv/DUU09x0kknOR9fjLvOzs6cZVVVVTz++ON87nOfI5FI5NnLmV/+8pfs3r2bH/zgB47CoT09PTnLQqEQppl73rlRU1OTd/mhQ4dczaXYWE6ZpklVVRWDg9mVgovNRQghhBBCCDEDbHkUtfUxR5uq7X8ASF1EXXEWaBsO7YSuVBhU9Y1PIEhbIZi9Cvxje58khEhVXnpWLSOmnEU7tVJsVguzljWQ4IRKTE4IMTNUz4bXf4FYNJrzmfGcOXMIBKQ6uBAzgZNqkK/r/SNVm9aX54Cb1ksgcKYo9TOWc0CIYRIM9Ugpxbx585g3b95ET0UIIcQM1n2gn54eG1WqlOeQeKKPKqMKv8NQqN9np0KhdvFQqDKS+HzuKkEW8uY3v5m1a9fywgsvZC2/4YYb+NWvfpW6m1hMSvkCkIlEgi984QtZoVDLsjj33HN505vexOGHH86sWbMYHBxk3759PPHEE9x7773s2bMnZ6wnnniCG264gS9+8Ysl5zI6LAlQXV3t8jvKFQrlr7Kb73il1lVVOft3WGo+o8cvNhchhBBCCCHENOciFJpJbX0sFQ6dtRL1zK1ln1Y+unouzDkC5qyGhiV5byAVQri3Tc11HAotJC6V/IQQQggxDuyaeamW32OsGAqkxpFAoBBCZJF3dkIIIcQUpLVmf1s3kYjPQyjUWTjO59PUqj5U0i66nVI2gcAAiuLhUTc+97nPcdlll2Ut+8c//sEjjzzCW9/61rIdp1L+6ycPDv//wpYafD5j+OtkXNO9p3g7v6YWH6Zv1A82nkC3HSi6n5o/C3yjXt5VsM3faLFY7rEGBgayvl65ciU33ngjy5cvz1ru9/tpaGhg9erVvP/97+emm27i9ttvzxnvrrvu4nWvex1veMMbis4lX3XSsVYLBQpWK43HC/9MC1VKdVL51Mt8is1FCCGEEEIIMY15DIWmqa2PobWNtkKoRHlu/sykDQuaVoyEQUNNZT+GEAIGkUp8QgghxoeTipDr7M3U4KLbnJh5WtehYUzt5PXqC6WNvBBC5CHB0Cmip6eH+vr6iZ6GEEKISSART7Bn5360Xe0uFGpW4VfOQqGWpakz+lCJ4qFQlMYfGCxrKBTgxBNP5JRTTuFPf/pT1vKbbrqJN73pTfh8Y6t6ICojmUwWXb9y5Up++tOf0tDQUHQ7v9/PVVddRW1tLTfeeGPO+ltvvbVkMDTfXAzDyLOlO4XCpcW+90LrKjWfUj8HIYQQQgghxDTly9/hwBV/daql+/7nxz4WoIP1MHt1KgzatAIsCawJUWmN9NNHGZ4PxIwgoS5RipwjQohxMYZwqIRChRCisLFfjRYV9ec//5nTTz+dm266aaKnIoQQYpLYt6/TdSi01lfjOBRqWpp6qx+VKB0u8/vDGMpJCM19+/fPfe5zOcG5nTt3cu+997oeS4yPYhUwfT4f3/nOd0qGQjN97GMfY9263Dfzzz//PH/961+L7lupwKSX6p9ewqRjmU85KpEKIYQQQgghpqDFp6BXned5d334ebD4lFSI0+sYKHTDEvTKt6JP/hyccg2suRCa10goVIhxskLvp1H3j2mMOj1YptkIIYQQQjjUug5d1+JqF13XIqFQIYQoQoKhk9STTz7JGWecwWmnnZZTLU0IIcTMZhp1rkKhDaEGTO2sSoBpQYNvABXPH37LZPkimIazltXJQI2j7TKtWrWKc845J2f597///Zz25GJyKFbJ9S1veQuHH364q/GUUlx55ZV51/3ud78ruq/f789ZVo4W64XGyHe8UusqNZ9icxFCCCGEEEJMI3YC+vbBvr/By/8Nf/0BbCv+XqmQ4VAowOzD0S5u8NRWCD3vGPSRl8LpX4cTPw3L/glqF+D4AwwhRNmYaI7V21iq2z3tv1S3s5o9ZZ6VEEIIIUQJuzeget29BlG9e2D3hgpNSAghpj4pJzTJPPPMM1x77bX89re/BUBrjZIPz4QQQmRQCkeN25N2P7NrZ5MIO/s9YpjQ4B9ARUuH1Uwrjs9y1homUT0bbXoLql1++eU88sgjxGKx4WVdXV3ceeedfOpTn/I0pqicurq6gusuuugiT2OuXbuWww8/nJdffjlreamKodXVuRVyyxEoLjRGTU3h8HO+uVRyPsXmIoQQQgghhJiiYgOpEGjmn/52lB57J4KsUCiAvwbqF0HPzsL71MxPVRadcwTUL059qCCEmDQMYIVux9JJXjUWON5vpb2PJXRVbmJCCCGEEPns3uCpjTyk2s9rkMqhU1CAOGvtwu8709sIIbyTYOgk8eyzz3LttdfyP//zP0AqECqEEF6Yc5po+NePT/Q0yib+6m4G7vrNmMep/sDb8K1oRWtNclSLdNMyyx7C74n34Fd+QpazSp2F9PX2ceDAAZTyY5n1KAV2U33J/QwjSlPNHKL9zn6fGCY0hsKocKzktspI4vOFHY2bDNaSqGpytG0+Cxcu5OKLL+YnP/lJ1vI777yTSy65hKYm72OL8mtsbMy73OfzcdRRR3ke9/jjj88Jhr788svEYrGC1THztayPRqNF93Gir6/P8fFKrevt7fU8Dxj5ftzMRQghhBBCCDHJaRsGu7IDoL37UNGeyhxu6enZodC0OUdkBUO14YNZK1PLZx8Bofzv/4QQk8shlf9m1aLb6y4wA+i5a7Ftm2g0++bwQCCAYRhgBso5VSGEEELMVGMIhaZJOHRq8mEzlx5syOlaodDSAluIMpBg6AT7+9//zrXXXsuvf/1rYCQQmg4oSUBUCOGW8ltYC5snehplY86fQ+R3fyW5p8P7GC3NBN9wLMpQqefVRHabdMuyyhYM1Wj2h/dzKJbAVJolNfPxG+5DaLZt09bWRi8xzOa5+KxGtMNKocGgTY2/kXCv7ehYhgmNVRHUYKTktkrZBAKDKAczsX1B4jXzHM2hmI9//OPcf//9WYG8gYEBbr31Vq655poxj18JW7ZsJh5PBfa6DlRhWSPnl53Q9HYkCu0KQN0BC8MadU4mkugDxS8Eqo56sEaqtPj9ftasWuFy9t41N+d/7lm+fPmYwphHHHFEzjLbtjl48CBz587Nu8+cOXPyLu/s7GThwoWe59LVlb9qxuzZswvuU2guhcZyqrOz0/VchBBCCCGEEJNIIgJ9baOqgO5HJUvftFlxc45A73l6qCroamhaAaZvomclhHAhiaIbd11FuqkhicIMNcLRlxGPRjkw6vOHOXPmEAhIKFQIIYQQxTmqBtm/BzatL88BN62HxmVQk/+6kZi8/qpW0KuqspbV6UFO1FsmaEZCTB8SDJ0gL774Il/72td44IEHgPyBUGkhL4QQoAxF7UfO49A37gIHLc5zBHzUfuQ8lFH559SkTrJncA+DicHhr3cP7GZJzRJM5bylWiQSYc+ePcTjcUyzCp/ViNNfCbW1FgEjQLjHWSs5ZUJDTQzV76ACqNL4g2EUpQOn2rSI1y3A8cSLaGxs5EMf+hA33nhj1vJ7772Xyy67jEWLFo35GOV23fVfoKOjbaKnwYIFC/jDb/9n3I7X2tqad3l9fekqt8UUqoB56NChgsHQQuHPtra2MQVD9+3bl7MsEAgUDH9CKjDr9/tzqnu2tY3tHCm0f0tLy5jGFUIIIYQQU0T/ftRfvlN0E/26q6AMN+yJMdIaIgeHq3+mQ6AqfGCiZ4ba/gd0oC63amjtQjjl6rK8rxdCTIw+QiRdfCYJkFQmfTpEA4MVmpUQQgghZop0NciiaubA6gtgjBVDgdQ4EgqdcnoJ5YRCAXpVFb06SB2lCxsJIQqTyrvj7KWXXuKd73wnxxxzDA888ABa6+EQqFJq+GshhBAjrMXzqbv8XRBwWZki4KPu8ndhLZ5fmYlliCajbO/fPhwKTYvZMfYO7kU7qvUJ3d3d7NixYygUWo3f5zwU2tAYIOgmFGpAY20co3/A0fb+QASD4pUuAbQyiNctRBvlu//ksssuywnexePxnLBoPt3RbjojnVl/ktrZYyTcWb58ed7lwWBwTOOGQqG8ywcGCp+7S5Ysybt8x44dY5rLzp25d7cuWrSo6A09Sqm8AeZKzAVg8eLFYxpXCCGEEEIIUWbJKOpP/4p67k7U1kdRHS9OilBomnr5Qdj5p1ELlYRCp6gEBoP4ScjlnxkvWeQcqNKFL7AX208IIYTIlK4IWexPAA9FX8TM0roOvfrCopvEgsW7ZerVF0ob+Slqj2oquG6vmjWOMxFiepKKoePklVde4Wtf+xq/+tWvsG1bWsYLIYRL/jXLaPjy++n70YOO2sqbLc3UfuS8cQmF9sf72Tu4F7tAJc2BxAAdkQ7mBgvfpZZMJtm3bx/9/f0AQ6HQBsdzaGwKYtkmg25CofUJjN5+R9tbgSimctbKLl47D9sqbzupUCjEJz/5Sb72ta9lLX/kkUf44Ac/yGte85qC+x6MHcQXzQ4V1/nrXFVxFc4sXbqUqqoqBgezA9LFApxO9PX15V1eqJIoQFNTE3PnzqW9vT1r+csvvzymubz00ks5yw4//PCS+x1xxBFs2ZLd8mKsc9m0aVPOsnnz5tHY2DimcYUQQgghhBBlZgXRoSZUuHuiZ1KQevnB1C2toyuHiimlgzo2qRbiysKnE6zWe2imd6KnJSZIIwMEdYyI8g8vs3SCNUPnRYeuY6NqIaFGLhUGdYxGxvY5jphaHLX5lVDXjCbniCjGUUVIrwYPSPeDacIGNNk3nSl09q0orevQgMpTObR7/j8x0LSW6u4XaGr7fc56CYVOLREsXlCLSWJgYtNH/uIwAPtopE8Fh7ddq3cSdFDESAgxYloHQzs7O3n22WfZvn07e/bsob+/n3A4TCgUoqGhgaamJo488kiOPfbYosGCsdi6dStf//rX+eUvf+kqEJpeL+3khRBihLV4Pg3XfYz4pm1EHv8bsb+/CsmMMKZp4D9qJcE3Ho9v9bJxaR8fSUbYPbi75Hbd0W4CRoAGf0POusHBQfbu3UsikXoh6zYU2tQUxNImA4ech0IbGmyMnvxhu9FMXwKf4axMf6J6NnagxtG2bl144YXcddddWVUWtdZ897vf5Y477qjIMYU7hmFw9NFH8+STT2YtP3BgbJVwurvzXzwtFYBcu3Ytv/3tb7OWPffcc57n0dvby7Zt23KWH3XUUSX3Xbt2LQ899FDWsq1bt9LX10dtba2n+Tz//PN5jyOEEEIIIYQoMzsJAx2pFvCJCCx6nfsxahfAJA6GgoRDp7oYZlbIL64sNtJCg96MH+mcMhMZaI7XW3mF+QwQpJF+lupOgkMBrmZ6qdOvsp05HKSGaiIcptswHHY+EtNDRUNdYlqQc0RUxP6/l97muTtTrcEl8Dfl/VWtyGkVXqcHOVFnF9PIFw5Nh0IBBprWUltbi++VB4bXSyh07PTwH4WNgY0a+n+Fge06iKmBbWpu1jiZ/99PgP48rePzsZVBD9XDX3foehYxebpvCDEVTLtg6PPPP8/Pf/5zHnzwQbZu3ep4v9e85jVcdtllXHrppcydW7iim1N79+7luuuu46677iKRSOQEQiF/KHT0esMweOc738l73vOeMc9JCCGmA2Uo/K9Zjv81y9HRGMkDPehIDBX0Y86qRwX8pQcpo6AZpMHfwKHYoZLb7g/vp8ZXgzX0Ab3Wmq6uLrq6uoa3cR0KnZWqFDpw0EUotFFj9jirFqEsG59vECefByeDtSSqCpf7HyvLsrjyyiv5zGc+k7X8ySef5IknnijYOnwi/NdPHhz+/4UtNfh8I/c9JuOa7j3F76BuavFh+kYFm+MJdFvxNztq/izwjXp5l3RW6bVcXv/61+cEQ3fu3El/fz81Nd5Cwy+++GLOsurqaurr64vud/LJJ+cEQ1966SW6u7tpanJ/rj755JPYdm5l4HXrSn/ocPLJJ+csSyaTPPnkk5x11lmu53LgwIG81UvzHUcIIYQQQgjhQnwwFQAd/tMGfW0onXrfra0gtJ7svs167QLo+EcFJpyifVVgBlCRg2MbKB4uz4TEuGunPqvyI0BCWXToelqY3KFkUTkh4hyldxVcHyTOEXrfOM5ICDEjDHTBc3fg15p5yexAkbndSr2OOuaDUD17giYoJtTuDaitj5XcTKFh032py1MS/JuyegnlhEIBelUVvTpIHaMK0wyFQ9m0nsRh5zHgW5q1OrngBCzLgk3rp0RwWENOMDIzgJm7PP3HKLBcodXo5alt1+jduC2Z9IJaRLtqKLi+WR8q+lqykG1q7JmrfNpVPYu0BEOFcGPaBEOfeeYZvvzlL/OHP/wBcN+a/cUXX+Sqq67i6quv5oorruArX/kK1dXVpXccJRqN8m//9m98+9vfJhKJjCkQ+u53v5trrrnGUXtSIYSYiVTAj7VgzkRPg3mhecTsGIOJwYLbGMqgpaplOBQaj8fZu3cv4fDIBRfLrMbnNhSqXYZCm8Ds6QEHvyeVoQn4B1EOtrV9QeLj0NLjrLPO4qijjuLvf8++m/S73/0uN998c8WPL0o788wz+c53vpP1ese2bZ588knOPPNM1+PZts1TTz2Vs/y1r30thmHk2WPEqaeeilIqZy7/8z//wyWXXOJ6Lg8//HDOssWLF7Ns2bKS+y5fvpxFixaxa1f2G+hHHnnEUzD0kUceyXlNqZTitNNOcz2WEEIIIYQQM5K2YbAb+vZmhUBLBStVIoIOd0PVLHfHq10whsmO0KjUsWsXpsasXQC18yHYAEqhtzzq6EJ73rGXnwkr3L8/EZPDfpW/q0abaqBFSzBUCCHEONIJ1EA7Cij0Ca7W0gp4Rtq9IW+r8GKUhEOntD2qcJGOvWoWdXpv7orWddC4jKSvATo7867XjcvQNfNgdEt6B8L46KYmJ6SZDlwWqnSZGdZ0so0eGnO8rPYQDFUlKgNp1yOCApS20crtT6a0Q1QTwZJ28kK4MOWDoYlEgs997nPcdttteVu1O6W1RmtNNBrl29/+Nj/72c9Yv349J5xwguMxfvvb3/LRj36UXbt2eQ6EmqbJu9/9br7yla+watUqV9+DEEKIiaFQtFS1sL1/O3E7txKk3/DTWt2K30hVM+3r66OtrY1kciTQ6SUU6sOkv9thKFRB/SyFeegQ2A5unlDgD0VQdunxtWkRr1vgvlqKR5/73Od43/vel7Vs06ZN/PrXvx6X44viWlpaOPHEE3PCnL/85S89BUP/8Ic/sG9fbuUKJ1U6FyxYwPHHH89f//rXrOU///nPufjii129Xmxra+Pxxx/PWf62t73N8RjnnHMOt956a9ay3//+97S1tTF//nzH42it+cUvfpGz/IQTTmDevMoHtIUQQgghhJhyElHo3z8U/kwHQfejklFv4/XtG5dgqDb9qdBnZgi0Zh5YgcI7rTgr1X7RZThUQqFTSxyTbqqJ4hte1kP+dow9VLOLkfM1QJwmBjL2FEIIIYQYG5vcAJkaHdjzEAodHkvCoRNqpOqlkVXRMv3/yaEwZBKDKBY71RxsFAqyXq+Oto9G+lSQJAYmNmv1zpHAX81ciEbZOv8UbGWiVeoYmw0zFbisS7WXf429i/kccvX99BFik9Hq7cGYxFL/Bt0V0DNKbG97CIamx3V2BdslpaSdvBAuTelgaE9PD2effTZPPvmk4yBmIaP327t3L6effjo/+9nPeMc73lF030gkwhVXXMGPfvSjMQVCL7nkEr7yla+wcuVKx/MWQggxOZjKpLWqlR39O7AZaTVdbVWzsGohpjLRWtPe3s7Bg9nVRyyzBp+veEvsTLNmhbAw6D/g8CW1gvrZBlbPQcjTBjsff3UMw0ELcq0M4nUL0cb4vaQ44YQTOPXUU/njH/+Ytfz2228ftzmI4j7wgQ/kBEM3bNjA7373O8444wzH44TDYb7zne/kLA+FQpxzzjmOxrj00ktzgqFbt27l/vvv54ILLnA8lxtvvJFEIvsORL/fz4UXXuh4jHe+85388Ic/JB4fCZDH43FuvPFGvvWtbzke5/7772fbtm05yy+99FLHYwghhBBCCDEtaQ2RQ0Pt3zNCoIMHSlZCcaVvH8w90t0+oSa0FUQlInlX62DjUAh0wUgQtKop1f7DraFwKHYctf0PRTfVS08Hwyeh0CmknwDPqmXElLNop1aKzWph1jK/jvNaOnHfM00IIYQQItdf1YqcduF1epAT9ZbUF2MIhabNxHCohpz24vnCmPnWD/+/KrE+a4z86ytR+RHAVgY9Ga9I8wX+4maw6DVIL8FFA2fXSqcaGwPTZRyzEhVDoXLBUFMnCZJbpEkIUdiUDYb29/fz5je/maeffhoYCVq6bSGflhnoTI8VDoe5+OKLefzxxzn55JPz7rd9+3bOP/98XnjhBbTWngKhl156KV/5yldYsWKFp7kLIYSYHAJmgIVVC9k9uBuApkATzcFmFIpYLMaePXuIRrOrkbgOhc4O4cOkr8thiXwF9XMMrJ5DkHT2RsdXa2MmwqU3BOK187CLVSqpkM9+9rP8+c9/xs4Iuvb19Y37PER+p556KscddxzPPvts1vKvfOUrtLS0cPjhh5ccIx6P86UvfYkdO3bkrLv44otpaircfiTTmWeeycqVK3n11Vezlv/bv/0bxx9/PIsXLy45xsMPP8yDDz6Ys/wd73gHc+bMcTQPgLlz53LBBRdw9913Zy1/8MEHOf3003nzm99ccozt27fzb//2bznLV65c6Sp0K4QQQgghxJRnJzKqgLYNt4NX8cHKH7svt6tBSUpBzXx0z66hAOj8jFbwC8CXv9qjZyvOgvBB9OABbNvO+TwiEAhgGAa0vg5C+VuQi8lpm5rrOBRaSEz52M0sSr87F0IIIYQorpdQTigUoFdV0auD1PXvhE3ry3OwTeuhcVmqmuQkEMPkENWFg5dKsUy3u251vkktpI3GVOhxHFuRT7R2Vc8inR0MVeii0UUvwcVSVTKnKm8h2VIVQ72Fgst6Y+aQGh1mrd5JNaULGwkhRkzZYOhHPvIRnn76ac8VQgsZHRCNxWJccMEFPPfcczmtOZ9//nnOOussurq6skKhTgKhlmXxnve8h6uvvprly5ePed5CCCEmhxpfDc3BZkxl0uBvAODQoUO0t7dnhRhhvEKhJr6+Q5Bwdl+WWWtgJXocbZuono0dqHE2lzJbtWoV55xzTt6w3mh+w0/AyA6vKo93uAnnvva1r3HBBRcQi428QTt06BDve9/7uOaaazj77LMLtnLfuXMnX//613nyySdz1s2fP5+PfOQjjudhGAZXX30173//+7OW9/X18YEPfIDbbrutaFD1oYce4stf/nLO8vr6ej71qU85nkfaZz7zGR555BF6erL/nX3hC18gkUhw9tlnF9x306ZN/PM//3PeEPTVV1+duqgrhBBCCCHETLH9D6gt/zMxx/YSDAU4+rJUANQwyzufQkKNcPRlxKNRDnR2Zq2aM2cOgcD43+gpxm6Q8vzcIvjLMo4QQgghZrY9qnARh71qFnU1EVh9AYyxYihAePXFRGqWFqxsWaxK5kiFzfz7rND7mYez62NpvVTxd2NJ0W2W6E7XFSr10Pcw0xyimgjWSDt5QOnij52XMGQlQouTgZeQbKnHYiyt5Mttrd4loVAhPJiSwdCf//zn3HPPPY6rhBYKHRTbNzPo2dHRwZe+9CXuvPPO4fXPP/88p59+Oj09PcMhUqeB0Pe9731cffXVLF26tOi8hRBCTE2zArMAsG2btrY2ent7c7bxFApV7kKhdXNMfP09EHO2j1Fj4Ut2O9o2GawlUeWsYmOlpAN2mcHDfFqrW2mpbRmnWYm0lStXcs0113DNNddkLe/t7eWqq67iP//zP3nTm97E4YcfTlNTE+FwmH379vHEE0/wxz/+MavdelogEODmm2+msdFdNZuTTjqJyy67jJ/85CdZy/ft28dFF13E+eefzznnnMOqVauoqqqiu7ub559/nnvuuYcnnngi75jXX389DQ0NruYB0NjYyL/+67/mhEpjsRif//zn+e///m/e9a53cdRRR9HY2MjAwAAvv/wyDz30EA888EDex+Wyyy7jpJNOcj0XIYQQQgghprTa+RN2aBXuRsfD4Au52zFQW5kJiRmlkX76cHnu5VHHOFTXFUIIIcS0E8Hi/9QykhgoNBEKVzLfQxPtqh570RoWqvkcvvEWz8fduOYK9i56m+f9S4lr9zdvOQl8egnWmdO01XlJSuW0k69EMFQqho4o9ViMpZV8ufUTpJpo6Q2FEFmmXDB0cHCQf/mXfykZCh0dBi0U2nTS+l1rzU9/+lOuvPJK1q5dS0dHB+ecc85wKLTYvul1Pp9vOBC6ZMkSZ9+sEEKIKSsSibBnz568IS63odDZs0P4DJPezgSOXkcrqJtt4h/sg2ju8fPuUu3Hr7tRDqpv274g8Zp5JbertAULFnDJJZdw1113TfRURAEXXXQRXV1d3HTTTTnrtmzZwpYtWxyPVVVVxQ033MCRRx7paS6f//zn2bFjB3/84x+zlsfjce655x7uuecex2N95jOf4fTTT/c0D4AzzjiDK6+8ku9973s56/70pz/xpz/9yfFYp512Gp///Oc9z0UIIYQQQogJk4ikKm/27oOGxVDf6m7/2oWVmVcJ2gqmWr/HB90HQ4UogxV6P32EOKi8d3Fp1P0soquMsxJCCDHd2eQGhBTaY5Nh4Vb6yo3biFYHdfSoquGKmTbGcMXMJAa1hFml21yOWc+ACjrbWCniQ5GUXYvOJYnJmo03uvwuKh8KBW8ts52E31LjOuvqlzZdK1qWYuokQbKva5YKhkor+RGVaSXvLRhaRRRD2xjooVq9euj/bRSaAYLOn0eG9KoQc7W7qr5CiCkYDP3hD3/Ivn37ClboBHLCmrNnz2b58uXMnj2b+vp6+vr66OrqYufOnezbt294n9H7jW4Pf+ONN3LHHXfwqU99ir179xYMhWYutyyL97///Vx99dUsXry4nA+FEEKICjkUO0TADBAyvV3g6e7upqOjI+/vKcusxeerczyW51BopB/CDu+aCvnxG70oB+3mtWkRr1sARapxj6ePf/zjrF+/Pm9rbTE5fOITn2DevHlcd911hMNhT2O0tLRw6623smrVKs/z8Pl83HLLLVx99dU89NBDnsawLIsvfOELXHzxxZ7nkfaxj32MYDDIt7/9bZJJdx8KpZ177rn8f//f/4fPV/iObCGEEEIIISac1hDuToVAM/6o8EjHCr3sTe6DocEGtBVCJby9z3BCh2alQqB1C1MVSmsXQLBx0rwnFjOTieZYvY1tzGW7mut6/6W6nWW6HcP0o+euLXGw8rStF1NQ/37UX75DECj07KxfdxVMgpvHhRDj469qBb2qKmtZnR7kRO385v/pRMNwG/JkRuiyUABzeFuVuU3utullWfsM/f+pehN+lwHDA6qGPWp24e/DQz6uXTW432nI3kVvo2X3b6jvfdXxPj11KyseCoXKVZ6UiqHO1Ogwa/XOnFbhqsRjYSvD2fXTrDGnQDBU65xQ5ehw5ej1Xs6bZt1DtY4UOI63MQGO0TuKrt/OHLYod11ALO3tWpoQM92UC4becsstBVvDZwYyZ8+ezRVXXMHZZ5/N2rWFP9x45ZVXeOSRR7jpppvYsWNH3rbw6a/vv/9+3vve93LfffflDYWOXnbhhRfyzW9+k+XLl4/tmxZCCDEuNJqOSAfd0W4sZbG0ZimW4fxXZTKZZN++ffT39+dd7zoUOmcoFNrhMBQK1M628Mf6YTDibIegH78/jBErHSLVyiBetxDt4jGptIaGBj784Q/nrbwoJo93vOMdnHDCCdx444088sgjJBIJR/vNmTOHD3/4w7z73e8mEBj7xSi/3893vvMdXv/613PDDTfQ2dnpeN81a9bw1a9+lSOPPNLx/Eu57LLLOProo7nuuuvYuHGj4/3mzJnDVVddxbnnnluWeQghhBBCCFE2yTj0t40EQHv3QX8bKlHiPWrfPvfHUioV1Dy41dtcM2jTnwo31S7I+DMfLHcVTIQYLwawQrdj6SSvGgsc77fS3seSdKXQUCMcfVllJiiEEGJa6SWUEwoF6FVV9OogdTi8HjFOkigi+LJClfmClkkMbFUgwJlv28wApxr/Wqm2dl95snQ1QHffRwSLQ6ra1T6ZFu5yFwoFqO99lYW7fjMOFUO9BEMr00peae2+POwUt1bvygmFAiU7HXoN9Jo6mTdc6SSAmbONzl2fG7TMrZ6Zvb2dtVwxPqdALRFqJ+A5fCmdNNgDbFSthFXx638hHWWN3k0jg+M0OyGml8mT7HDgL3/5C9u3b89bLTRz2Re+8AWuueYaqqtLvyg57LDDOOyww/jkJz/Jbbfdxhe+8AXi8fjweJlVQ/v6+rj00kuH9y0UCj3iiCP4wQ9+wBve8IYxf89CCCHGh61t9gzuYSAxAEBCJ9g9uJslNUtQDl56Dw4Osnfv3oKBMcuqxWe5C4X6DZMel6HQQGIQ+h1WS/H78FUlMMP5g6yjxWvnYVvewnmf/vSn+fSnP+1p31I+9rGP8bGPfawiY4vyWbhwId/5zne46qqr+O1vf8szzzzDq6++SmdnJ4ODg4RCIRobG5k9ezbHHnss69at44QTTsDv95d9Lueddx5vectbePjhh3n00Ud59tln6e3tzdlu3rx5rFu3jnPOOYeTTz4ZyK0UP1ZHHXUU69ev58knn+S///u/2bBhA+3t7Tnb1dXVcdxxx3HWWWfx1re+tSKPixBCCCGEEI5pDbE+6N2bUQW0DQY6vFVf8RIMBU/BUB2sHxUAXQBVs2ECLu4LMVZugxmHVDVoaSE/08Qx6Ka26DZN9OGbgdXJhBDO7FFNBdftVbOo03s9j91OPTHMkWqZKjuAOVcfYjbOrmGk9RHir8YKz3OarJIVqDyZdBkM7aDe9RzSFu76jac28sDwfpUMh3qpPOm8lbw75lSoaFmMtl2/v+onSDW5RWya+naQNHypsKS2qaupxm+ZwyHKqjz7lFJFjDdq58U6RGU0MshavZOn1WFFt1urd066GxCEmEqmVDB0/fr1OcsyA5k+n48f/vCHXHaZ+7tcLcvi8ssvZ+3atZx//vn09PRkhUPT9u/fnxVCHV299KqrruL666+Xi/VCCDGFxOwYewb3ELOz70SLJCPsG9zHwqqFBffVWtPV1UVXV+EP1T2FQk2TnnbnodCaWRYBHYHeAWc7+CysehOr39nFgET1bOxAjbOxhSiiubmZSy+9NOtmm4ng9/t5+9vfztvf/nYAOjo6OHjwILFYjFAoxNy5c6mtLX7RpJxOPvnk4fBpb28vHR0dhMNh/H4/jY2NNDc3j9tchBBCCDHJ9LeDr6H4+hr3rYTFFLflUbDjpbfb9zcwfLDiLO/HspMw0AF92SFQFXN3gb4YFTmIjg+CL7cSVVF1hSslamWm/m2MDoH6vVc4miwSGMSw8JPAkiDXjJVE0Y27z2q6qSGJmvphA+FKFB8vGIuLbrPO3ozPQ7BCTH0SHJ550i3Q0+3KRyphpv+kqm3uUrOHAm2aGL6C4+2hib2qEQNNDRHW6p24qbn+ippPRBW+rl6lo66DodO1DbeXgKFRovKk22qLQeKYOklSma72G0soNK3S4dDJVDHUybh56ZHqk5mtwNXQ35nVKQv+vy683ulYW9Q8duDumkavCjFX9+QsbxjYk/X1nNAcAh6L2IjJx0m42sk2QojCplQw9PHHH8+7PF3V86tf/aqnUGim0047jbvuuou3v/3teVvW5wuFaq2prq7mF7/4Beecc86Yji+EEGJ8DSYHaQ+3k9T522/0xnsJRAPMDszOWRePx9m7dy/hcOEKnW5DoXPmhPC5DoWaBM0oHOhztoNlYjaFsPqc3cWbDNSSqCp8R7AQ00Fzc/OkCV/W1dVRV+f8eUMIIcQ0UCrYJ8G/mWv3Bti0HvOw88C3tOB6Vl8ArevGf35iYmx5FLX1MUebqu1/AIbeXjoJh8YGM8KfQ0HQ/nZUgffMZdXXBk3L3e1TmwqGal/1SPCzbujv6mYwptTH3450UMcm1UJcWfh0gtV6D83kdkAQ018fIdehjKQy6dMhGqQNoxBiiASHJ598wc1iIc4kRkaVzUL7ZI9HnmvgnqlU0+Mk0EM1HbqeRewpuVtayYqWFariOBV5CRiWu2JoM72cqLfwFCuwHb4OqerfxeqNN7s6TiGrN97MwaYjGaxZVJbxMnltSZ6mtI051AZ8JDhpe+qo0EQ/q+3dWWHL0sFOe9zaj5di6aTriVjj8Z5TCCFmoCnzyVhvby//+Mc/ssKa6ZCmUoqTTjqJL33pS2U51rnnnsuHPvQhbr/99qwgaGZb+cxQaG1tLY8++ignnXRSWY4vhBBifESSEfZFS7er64x0EjAC1PpG7pzu6+ujra2NZLLwGxXLqsNnOa84OGdOCL9l0rPfRSi0ySRkJdBdDi8CmQbG7Bp8fXtRDlpi274g8dp5zsYWQgghhBDulQr2SfBv5tq9AbXpPgB8rzxA9fx/YqBp7fBqc98zqFceSH2x6b7UWwg5R6Y/F6HQTGrrY6XDoVrDE99ExScoMNa3z30wtGY++tRrIVBX3oDDJBXDZKNqIaFSH+vHlcVGWmjQm/EjF1JnGrdBjrHuJ4QQImV0cDNAwnUQcR+N7FON+UOcLtsvTzbtqh43kb1SlRE9VcmcphVDvfwOL/34un8NXU2UWiL04KwS/2DNIjatuXzMFUMBNq25PDcUqt1WxsyzTGvqPNw44yPJG+0XMdBlDWTWEKVmCgfyl9JJgz3ARtVKWBWv7hnSUdbo3TTKjUtCCFERUyYY+uKLL2LbdlZQM9MXv/jFvBU+vfrKV77CnXfeORwGzQyHpqXX/fSnP5VQqBBCTEEBI0C1Wc1AsnT79X3hfaywVmBg0N7ezsGDB4tu7zoU2hzCb1r0tMdxkNcEoLrJJBRIojtzWyvkZSjUnHp8A20ou/QFI21axOsWzIiLa0IIIYQQEyIj+Jc32FdqvZi+Mn/2Q5rafg/AQNNaqrtfwDf0dZqSc2T68xgKTSsZDlUqVWmze4vnY4yJw64WWQwTgvXln8sk1U79cCg0LaEsOnQ9LXRP0KzERGlkgKCOFW2/O1pQx2ik9OdgQghRkrLQ1SW6GqiJuQytIW+VTD8JQsRdjTWIn+fVkqLBzXX2ZtcBrgg+DqoaV/tMFYeoJorpuJ28WSJUW4kqmVOVl5Bs6cfXWxDZ7c9l76K3UUWUpRu/X3CbWN0S/L07Cq6PrH43S1qWs8zeNCrYOXEUpR/jmaqRQdbqnTytDiu63Vq9kzoi4zQrIYSYeaZMMPTll1/O+jozBLpo0SLOPvvssh5v8eLFvO1tb+Ohhx7KCZxmVio999xzOffcc8t6bCGEEONDKcVc/1z2RvcStQt/cGNgsCC0gGQ8yc49O4lGi3/I4y4UqpjTHBwJhTr8vKK60aQqZKM7DuEoSaoUak4DvkgXRqL0h1RaGcTrFqKnYds9IYQQYtz1t4Ovofh6aRM+8+QJ/mUF+0qtF9NXnp99WlPb76k5+CL+SEfe9XKOTHO+UOXHmKBgqA41gc9ZxaGZbL9qzLu8TTXQoiUYOtMYaI7XW9lEC92q+OdQIR2lljCH6bZp215XCDHOqmfD67/gadd0cLNYq/OsPzlt0tWofZ1V3FyiO1ip97ue74AqHnGsRBXHKU0puqllgcPNSz0W3h7f6fm7LukhJOsnQY0OD1fRTP2danme+ttG4779eCMD9FHlap946+vRujPv+129+kJ8revQBd4P69UXEmh9LRBzOVMxkZz8W5yu/16FEGKymDJpj23btuUsS4czzzrrrLJWC007++yzeeihh4pu841vfKPsxxVCCDF+DGXQUtXCzoGdJHQiZ73P8NFa1Uq4L8z29u3YdvEPKdyHQtPt452HQqsaTKqqNbr9ENhOQqGgZtdjJXoxo/2OjhGvnYdtFW/vIIQQQggHhtqAm4edB76lBddLm/AZpkjwT226D73nKVTvnsLrQc6X6arIuZFWKBSaJufIFKY1JGOQiEAiDPFw6v/j4dTXyRi6aQXKY3BTH34eLD6l+Ea1Ti/he6MNC2rmpY6T+accoddpJo5JN9VE8Q0v6ylw8b2HanYxa/jrAHGaGMAn7eWnvRBxVul9bFCrim53tN4xpduRCiHKK4LFC2rxUOCu9OfLz6vFgMJAs1h3YmLnBDfzhzRV3uUT1SrdS8DQSeXJSo07VZk6id9FZdZSobApXzFU66KhTGPU/w//rbO3NdDUE3Z9+Nn0MVv3lf3b8uuE6zSppZPQui4VRM1436tXXzjy/rXUeiGEEEK4MmWCoe3t7QXXnXDCCRU5Zr5xM9vKH3300RxxxBEVObYQQojKSj+XK6XwGT5aqlvY2b8TnfEhRJVVxYLgAjr2d9Db21tyTLeh0OahUOghl6HQ6lrQ7QehREh1+Eiz6jGNKFa/s+ohierZ2IHp2cZGCCGEGFcZAS/fKw9QPf+fGGhaO7za3PcM6pUHUl9IkGvmcBD8KxQKHV4v58v01N+eCoqXw6b10LhMqhFPBpFD0L11JNyZGfhMhCGeGQINo5y+OXTJUSgUyhoM1f7a1Hh1GQHQqjmp9u+iqH4CPKuWEVO+0hsDWik2q4VZy/w6znF6m4QBhRBimrNRJIYClwnMnGqbAPM5lLVPB/X0KOeVusMZFTM3qdayzHsiSDC08mp0mLV6J9UMON6n1GPh5fFVgNI2Ok8IWen8QczcZaMCnMP7OdiWkW0V2kO0dfJbSicN9gAbVSthVbzISEhHWaN308hgasFQ+LPgjdKl1gshhBDCsSkTDO3s7Cy47phjjqnIMV/zmtfg8/lIJBJZgVBIBYnOO++8ihxXCCGEcz3xHgDqffWu9utPpipn1g4FOUNmiPmh+ewL7wOgwd9Ag2pg145dxGKlW1N4CoX6TA61uQiF1ptU1yl0ezckHe7UVIvhA6un8A0WmZKBWhJVTc7GFkIIIURhecJ/TW2/B2CgaS3V3S/gG/o6TcJ+M4AE/0QxNXNTF71KBIcdWX2BnBteaDtVsXM4xJlRrTMehlkrU9Uu3ejdi3rxF5WZr0OOQ6EANXPRykRp55UmtTKgujm3CmjA6XtkMdo2NddxKLSQmPKxty/G4X/5HEGgUIxHv+4q9+e1EEII12zS7dNHwpuJUSHO2fQRILerVTF7aGKzsbDger+OM18fylrWrhrcfwPTQKUqT0owdMQavZtql62+LZJYOpk3VGlgU6vdV8kEOFFvQeWp1jkx9Wqnp0YGWat38rQ6rOh2a/VO6ohkL2xdV/wzjVLrhRBCCOHIlAmGDgwUvrNo9uzZFTmmaZo0NDTQ1dWVd/3RRx9dkeMKIYRwRqPpiqSeo90EQ7XWdMdT1TNrzJHKmPX+eqJ2FEtZ6AHNzo6dWTcFFOKz6rEspxU2Fc1z3VcKDdWbVDcodMdBSDi8QFdfg1Hlx3dwJ8rB92H7gsRrp/7FoKRO0hsvXuG1zleHqaRKjRCijPrbi39QWWq9mF6KVIRsavs9NQdfLNgKWsKh05wE/0QpedrmuTWj2+xpGxLR7EqcGdU4s1uzR/KuU0VaWerVF7oP0E1wi3S99HTnoVAAw0qFPPvb8o9nhUaCn+lKoNVzwRxbiFFkG6R41SWnIvjLMo4QQswkmlSAsFAFzpEwp0lS5YY7R7bL3tdJ+/Rj7W0E6Hc1X7fVFiNYHHJRLXQ68Vp50tB20Z+fl6jhZA+GKp2K0To5bzMNEMgNAJawWu9lNXtd7eNErct5CG+MIu+fSm5T6jMN+cxDCCGEGLMpEwyNRgu3vGloaKjYcYsFQ1evXl2x4wohhCitN95LzE7dfdoT73EcDj0UOUS8Pw5J2D+wn+bGZoLBVDucWb5Z7Nu3j/7+7A/glDIxjCBKmWidxLYjaJ0sGQpVKEzM4XuR62f78PtMetriFCvAYmDjV3EMZWMGTAK1QXRnD8SK3DGubEwzjlIa7Q+iq334evai7NJBUm1axOsWgJr6TU0SOsH+8P6i21RZVe6DoXYCynRxTggxzezeULy1Uan1Ynpx0Ca8UCg0TcKh05wE/0QpYzhHZsS50b0V9j6Ttw07iWjRYOeYxT1UK7ImNhjqSd0CdP9+qJqVWwU02DAt3jdOdo3008fYz526dLtOIYSYpkZX4Swa0lT5wp35952o33WVqDyZVCZaM/z5dAfuOm9NJ14eX0g9xsXCn95+bmN7zap0qrqmOVRZc+T/023NR/3R2a3PR/8ZvY8BvKrmsYNmV/PqVyHQPWP63oQQQgghRPlMi2BobW3l2hLV1taitUbleRPY2NhYseMKIYQoLrNaKEBXpKtoMFRrze7du3MqUA8wwPZD2wEIBoPE43GSyXSQUuGzGjDNEKCyPg9MF+As9BlhAB8WucHDcJcmTLzgd1VjDBJQcUCPNLaJAW2FK2f7/GFMc9Q+dhR9sMdRcxytDOJ1C9HGlHlZUH5OLvAOHgAT8M/MO+qFEAVkhgDzhflKrRfTi7QJF05J8E+UEi1eAT8fHaib+HPDTg5V4sxfjXMkwDkU6lx2BjQscneM8EHUvr9VZv6lJLwEQ4Pln4cLavsfUueGm6qhh50NR1wAltwYN1FW6P30EeKgctqdJFej7mcR+QseCCHEeMuswjm6mqaPJHW4+x2bRPG/ao3raoaTXaVakicxsIa2CxLH1EmSM7CbktdgqOGyKqsTQWIs1AdygpvFwpuZIc7xOPMtncTRBYbR+zg1eMB9NX4hhBBCCOHKlEmAOGnlWwn5AqFp9fUz9646IYSYaJnVQgFidoy9g3up9dUSNIP4jZF2afv37+fgwYMlx4xERlqLWGYtllVXMPhZaLkPC7+HX68hFaHKCLv6nMW0ovh8kYL7OB0rXjsPeyZf8IsNQNTJXcwaIkPnkYRDZyY7AcU+NLcTqdabYubIUxkyq9JjqfVi+pE24cKNqRr8E5W35VHU1sdc76aivej/ux2O/ZD3Y9vJ0m3Y81bqTC1TycI3duejFxwLuAyG+iYwaOklGDrBreQB1MsPpl5/OA2HBuoqOR3hgInmWL2Nbcxlu3L/emCpbmeZbnfU2lPMYP37UX/5TtFN9OuuktDODGSTCnH6yjTei6qV/TQU/EB1rj7EWr3L1ZgGOvMW+WljPIKhzfRyot7CCyxKVXecQbwGQ5foTpLaKBjUDBYsBFFYiDirdfnbp5fTUjppsAfYqFoJq+LXD0I6yhq9m8Z0tfL9fy99gOfulO46QgghhBAVJleux8Cy5OEbb11dXfzlL39h48aNvPzyy3R3d9PX10csFqOmpoa6ujoWLVrE6tWrOeaYYzjuuOOKhntnui1btvDMM8+wadMmtmzZQk9PD729qYuTdXV11NfXs2LFCo444ghOPPFEVqxYMcEzFiJFo+kMd+Ys74330hvvxW/4WVKzBFOZ7Nq1K6dKaCmlQqGF+LHwefjVWmWECanCAc98SoVCnUpUz8IOeK9AMuXFBkbCnk5JOHRmSp8rwQbI90Ho8PpGOTdmiiLtwtWm+9B7nkL17im8HuSD7+lK2oQLJyYy+CcmN4/nRprq3OT+HNn1F9j2O0hEUMlY6e3Laaq1ZvcyXzOARrlucZ8wg8QCjfijB7GSkdI7lOA6HComnAGs0O1YOsmrxgLH+62097FEKoUKMSNoUv2DMlugpytxRvCxXTVjoxwFKDeolQzfZq4U1WoHryvTPNXQmIUkPIT1FKlAZCJPx6apzMtj4TQYmqmaKGv1Lp5Uq1wfb7wYunir88z26caoipu5FTZT21q4qGaZYREHyvzdTR2NDLJW7+RpdVjR7dbqndQx9Jp19wZH72kUWrrrCCGEEEJUmCQbxaTX19fHnXfeyd13383TTz+NbZd+k5vW3NzMW9/6Vj7+8Y9z4oknVnCWU8euXbu47bbbeOCBB9i8ebOrfQ877DDe8Y538IlPfILFixdXaIZClNYb7yWuC9+Fm64e6u/zuw6FmkbIUyjUxPQUCg2omOtQqGHGyxIKTQZqSVTNGuMoU5iXUGhaer8Zdlf9jJVxrqjIIQxfLbZVNbI+PgCRQ6n/l+DwzFAkFJpWKBQ6vF4++J7ePFSCTNNzVst5Md1NRPBvqrMTqUqWaNC68N/aHrWMob9HL8/cR2dsw6jlNtS2gL9q9IyKG+iAQztKHC/zuOmvgfYXvD9OQ1TnJvTuDc6fS7SNGsPz1phMtQqcCQ8BTaVS7eRdfK8dzevY+JoriQca8UUPsvof36O5+3lQChUfdD+H9FQkHDolHVLu3lscUtWgJRgqxGST2Uo9s4166uv0/6eWJ1Ru0LPQ9rpchTEq2JLdLBHG81rFcToGQ708FpaHYChAH2Orwj46uFkywKkLrc8f4pSSL5OHkwrkw9s4+MxsNPmMTAghhBCiciQYKiatwcFBvvGNb3DLLbcMV7F0q6Ojg7vuuou77rqLdevW8Z3vfIfXva5c97lOLbt37+Zf/uVfuPfee0kmvd0V+corr/Ctb32LG264gYsuuohvfetbLFrksuWbEGNUqFroaAPxAQYOuguFAvh8ja5DoQBBj82VaoxB1x9y+f3uWs7nY1sB4rUzuBVYPAzR/rGNETkIlvu2fNrBLvGIxvTJx5+TQp4AsRnvA8C2qjASg6ihr4dJOHR662+HTevLM9am9dC4TNqFTzflCP1teRRWnFXGSYm80kHCzD/pAJdb3VtT4cWs8TToZEZg0Qbbho6NY5666tyEfuZWqGuBw89zP8ArD0Pf3iIhy3RYkdzlxYKZw3+nv/+hZTCy7+v/BQK17ua7+b9Ru/7i/vssA338x2BW8eo4Obq3oMr1u8IrN79jvJzz5RL3ELScyIqhXoKsAP7qVHDHCqUeb18o9f++4NCy0PCymL+ef8w5h4ThByAeaGTjsdfSoDfj3/IwjOF3TGpAj9+DmBBJFN246/LRTQ1JFKa0kRfCMw1ZQUwfSXwuKw0eooqNqjUrzOnpQ8dpoFRFy6THcKeTSplTTVKZuH36LvY4KJ0KWeaLWfZ5uOG9VXeyUu/HcFSHVsw4HkKhaRIOFUIIIYSoDAmGiknpscce46Mf/Sg7d+4s25gbNmzgDW94Ax/84Ae58cYbqamZOa2Tv/e973HNNde4rpxYSDKZ5O677+ahhx7i+uuv58orryzLuEI4Uapa6DAPmT/LrEV5+IDWS6VQgJARcd1O0PJFXe+Tjzb9M/bDaGCoklsZKiFEesHFRbpETNPbkSi5XV9XgnCvonaOheWfwT+niVakqqwZ78NIhlF2gZ+nhEOnr5q5sPoCGEOb8GGrL5BQ6HRUjkp25a6GZydTVe5GhyDTf9CpwGI6uEi+7UaFHPP+ydxm6O+6BTD7cHfzjYdh4735xxuec3quOqOSpJP5jXyd7zWVblwOJ/yz+8f4+bvGVMXPC3VwG7p3r7dgaM8uVPer5Z+UA9rTa9nKVbAqycldPTkmwes3N79jJrQC59SoGKqVkQp0mgFvA7z+i47ff7XTNBwKTUsoiw5dT8uKs9CQcwOC9teCb1Rl2/ggKpZ9A5NefqbceDDF9BFKhYRcSCqTPh2igfH9vSTERMkMcWogSOnPXUb7m1pGBF9WGDTzeXuVvdd1K2kNDCqPvzemGVPbRV8eea8Y6q0AxmRlDFewd8dPgmPtbVgksypvWqTe8xR66C2ddP2yNaATcuOByMu3+wnPodA0CYcKIYQQQpSfBEPFpPPtb3+bL33pS65axjulteb222/nmWee4cEHH2Tp0qVlP8ZkMjg4yAc+8AHuvffeiow/MDDAZz/7WZ566inuvPNOqqpcttcTwiWn1UIB8JCDtixvgXGfx7vaQyrqeh/LjHk61mhGbIzVMicxhcIsceFMBerGXjEUIFgHPc5+X8XCNr0dCZx+xpuIaQ61xalvtvCFJjAMMVMVCYWmFQyFpkk4dPpqXYfu3ITq3OR5CL36Qvmgu5LS4T87mREETOZfHmoCy+UF2959cHDL0Fi5Y+uqOahBh69Z8tnxJ9j71/whxxVnwcLXuhvv0HbUX7/vfT5joFtPdh8M1UlUGdppe+PxImcFW28WP67HAOJE3iDkJWg5oTc0TbX5evgdM5EVOL1UrzT9aJSrG+a0MlLBSStYsFLn8DJfKGO7oXVjvbHOxb77VWPe5W2qgRbdDaPCofrw8wq2htc7/4R6+cHU/0sodEryGpbyup8QlWYDWS3Tc1qkZ7RNV3larOfZ3s54HVavBzhBb3U9rzB+IspfcH2l2nvPFKUei8QYWslPhFQVzuRw+HJ0K/SsgKa2R21XeD+vrzQMNLM8VElYSicN9gAbVSvhEiHmkI6yRu+mUW46EHlU9e8isOme8gwm3XWEEEIIIcpKgqFiUvnMZz7DzTffXPHjvPjii5x00kn88Y9/5PDDXV6knCIGBgY488wzefLJJyt+rHvvvZfdu3fz29/+lupqCb+IynFcLTQJ7j8XNPBWiUihPHxsZ2Cj3E5SaVBl+sBTa1QyjjZ95RlvEvEbfg6rc9DuU/lKBv+KCjaCCuGkPG26UqjbG/+1DT0dCRrm+7AmQeGpGcNOjO3cyBQ5mAqcGfKye1rZ8uiYQqHAUOXicZYVMkyOCjTm+bpQsDLvsoz/bzkJ3P5+2b0Bul7OmEeJ42Utz13mKiz02k9A0wp38z24bThoUwkqcrDg85BOeGi7PFGhRcD1Lz+Y4Pl6rDo0UXP2VM0SJrSipadKSFMsyDqB89XNR7q/8WCqtWZXBjS/Bm0Yo8Kdo4Kdvox1hm/CA7v5xDHpppooI783e8h/020P1exiVuqLFZcQqDmMpngHvtYTCx9g8Smp34jxsIRCp6hGBgjqWNHA2mhBHaPRy92yQuSRwCA+qpJmVngzHdZUZvbXBba3K/yayXvlyRKtzpXh+l6R6djm3KvSreS9/dychG9NncwT3MwT0tQlAp4Z+xnTqGJmI4Os1Tt5WhX/LHWt3kkdo96LDnTBc3cUP8AxH4Tq2WOcpZjsBmsWEV39LoKb7h77YNJdRwghhBCirOQKtZg0rr766nEJhaZ1dHRwxhln8MQTT7BkyZJxO+54iEajnHvuueMSCk3bsGED5557Lg8//DCBgLTIEeXnqlqog+zoaIbh93Sd0PT6waVKur5cbBiJsl1iVoARHyBpNpRpxCnIX526EO0lYBNsTO0fL/0BtNbQ3+k+FDq8vw19nQkamyffhexpy7BSP+NyhEODjRIKnS4GOsGOj7TkHqtDO+GV3xQJOQ4FJE0fHHmx+/GfuwO6t2WFJpXXJyKX9Lyj3AdD+9pQHf+ozIRK8fK4GN6qhZfFlAtaTrX5lq9iaMIMEgs04o8exEqW4XkjL6/zlQqczlVmvhU7P2wPb4Z8wfIdvwBtWPkrddYt9DbgMe8v6/wmQj8BnlXLiClnvzO1UmxWGY/XgoX4dZzj9DZqKNKNokA1UTE1GGiO11vZRAvdqrbotiEdpZYwh+m2aRVaEvlFsHhBLR5un17Ki6oVUJjYrNU7CZKgixrmlNjvGbWCAWPJ2Cc8ThIeu/pYJVqSewkuSjB0hJNgqMb9rTWLdScL9MGKVOGcSZw8i+TdRidQA+1F99O6RLcdMW3EW19PgMSY2slLdx0hhBBCiPKTq9RiUrjnnnv4xje+4Wjb6upqLrjgAs4++2yOOeYY5s6dSzAY5ODBg2zevJknn3ySn//857z44oslx9q7dy/nn38+GzZsmFZhxiuuuILHH3/c0bYLFizg0ksv5Y1vfCNHHnkks2bNQmvNgQMHeOGFF3j88cf5xS9+QVtbW8mxHn/8ca688kpuu+22sX4LQuRwXC0UPFQLBeUxgOD1w0U3lcyG91HlvbCjkh4rYk0X0V7v4S4X1cQSUU0iNrafXSKmiUflhdu48loxLpMVnGZt5PVQNkZnf62UhxCXhvhg/vHcfJ00Ga72PNCV+nuwC7Y8VrgSZl0LHPshl/MFnrkVFetzv18B6sBmOLC55Hba8hjWScZQXqqwlcNUC1raUy246OUC8xSb75R7fMmZc0fzOja+5krigUZ80YOs+cf3aO7YUIYJjjIlK4ZOrQqc3uZb/Byu5Pmhul5G795Q9lby2vDltlzP14Z9dKXO9LJp2KlgrLapuY5DoYXElI9tzGWt3lWmWYnJKEScVXofG9SqotsdrXcUDwmLitOkAm42avhvO10pc2hZkDi1o6vulRDD5P/UsqxxR7dQL6VfjVQj7tD1LOIAEabfc3OlKoZ6CZyWCpvOJA0M8Bp7V94qnOlApxdNUh1ZiMmldV3qo0IP4VAJhQohhBBCVIbkC8SE27p1Kx/96EdLbqeU4hOf+ARf//rXmT07t/VEc3Mzzc3NvOENb+Bf/uVfePDBB7nyyivZvn170XGfe+45PvvZz3Lrrbd6/h4mk1/96lf84Ac/KLldTU0N119/PZ/85Cfx+XI/BGxpaaGlpYW3vvWtfOMb3+A//uM/uPbaaxkYKP5hy/e//31OP/10LrroIs/fgxCjuaoWCp6yD9pjCMDrpXjt4eK21uW9IK7NCQzhTLRo79jaOA/tq1VNyU3DveW5EBDtt+WF23gqRyjJ9KeqQLoKPurUfm6rjNoJiPVlhFeG/i729ehjF11fhK8aQo3u5qs1hMtQkVVlBFkSQxfBY/2o3t2FDx3zeOHImKg20V5DalLR0jEvQfChx3d8KkKO4il4O8WCllM8GBrz1fGPtVeR8KUqu8UDjfzjyM/z+j+9H3+8fAHzlClYMdRL0HIaVQwdj/NDbbovNWunF1atAPqwswu3YbeCUgG9AgYpzw3K5RpHiOkmN6SZHdjMF9xM/b/CVtn7JYfWFRorvY128BqmVXdxuN7n+vvpU6VD/E61q3oW6QOY07CybMVayXsY10i/x5/o110uj99id9HEAH69p2zTCBEnxKGyjSeEmMRa16H3PIXqdf4coutaJBQqhBBCCFEh0+JT3euuu65iY+/bV/hDmkoed7TTTjuNU06Znq2fPv7xj9PbWzycEwqF+MUvfsHb3/52x+Oed955nHLKKbz73e/mscceK7rtbbfdxiWXXMLrXvc6x+NPRocOHeKf//mfS263fPlyHnroIY444ghH4/r9fj772c9y5plncu6555YM237yk5/kTW96Ew0NDY7GF6IUV9VCAS8FD2w75umz2qTHO9oT2nTdIsm2LU9tlfLRgO2bTpUMXSpD4CQWidPRO1jqQNixMR8KgHjELh16TkTI2Sjp4N9ObADM9EQzLgwVCgb6a9w/holwan5Fw4ajj11oW13gywLbBhrAcnnB3DBJ/Wsbw4UyrwHkYD34i7eJzKHt1M9xQky1ym8uKv5iEMPCTwJrooKWZapeOK5s70HLCeExuDhuFSFHk4qhlVWGf3Pt804ZDv2lJfx1tM87hdbdvxnL7HJNxYqhU62VvKcgq4E2/YAamvvI3/tb3pT//Gh9Cy37HoPIofL8dDath8ZlUDPX0XxZeno5jipcaKSfPsYe9GqkvwyzEaKyvH6WsY9GBlQgN7hZMvBpoCf0poLCPAcMy+gQ1USwMKZhq3NbGdja/avfUhUrvfzcFKnAadJhtVGlNSbJrHbohaprmtrO2z599PZb1Vx20uxq3paymat7gFKfeQkhRB67N7gKhQKo3j3uux4IIYQQQghHpmwwVA99MK+15utf//q4Hm88j5tpOgZD77//fn73u98V3cbv9/PAAw9w5plnuh6/sbGRBx98kLPPPpvf//73Rbf99Kc/zd/+9jeMiaymM0bXXnstXV1dRbdZtGgRjz/+OIsWLXI9/mte8xoef/xx3vCGN7BnT+E3dp2dnXz1q1/lpptucn0MIUZzXS0UIN1Z2NXn2/bQH/ftkDUa5fISh42BxkC5maRWoA1QZfjgXin0lG/nOFR5If231gz/DDO+N40avgilhi+mjO0CUSRu0d7rQ5f4+bk9L4pxdBko0gPm6NCkg/Ml1ucuhOOrch/aScYmLrjoJeSTPrcmwvQr2pJrQvNIzs6HDurYpFqIKwufTrB69muZu/vRCk8uDy8hS5iSQcsJ42G+MatqHCtCjuLp8Z3IUJ2X1y1Tbb5kncNtC96Yd5O2hWfQ0vZ7sJMo28VNTwXoqjnuKzanzVqB9lXlhBbz/p21zBg5n4aXGyX2GbXcX7rieo75x6EbluSZo5H/eMW2gew5l9rX8nuY7zGpP3m0qeX5lx92MS0rT4S//xfs/7v7Y462+gJnoVAxYVbo/fQR4qCDLgSFNOp+Vuj9ZZyVmInC+IkTHA5Y1hDB77IFdie1bFfNBatwGti8UW90Pbf9qoEDyuVNc5Oc7eF1Tqlqlq4pRYeup3qaVnBMDp1zblSiYijAMt0OmqLhzfS6cgeAAXw66fqlteWlo4IQQkAqFOqhjTx46HoghBBCCCEcmbLB0Ezac4WMqXFcNUnvbh4r27b54he/WHK7b33rW55CoWnBYJB7772Xo48+mt27C7cVfe655/jFL37Be97zHs/Hmkjbt2/n+9//ftFtfD4f9913n6dQaNqSJUu49957OeWUU0gkEgW3u+2227jiiitYunSp52MJAR6qhaZVAy5zGYlEPz5fnetDxUni9/ArNawDVKuwq30SST8+a+ytau2A++/Tk+Hgpk1OgDNfqDNrWcY+ebcrwApC1WwAEpiE8aOVQmlNiBiWHYWI9xbWsYRJe2+Vo4/rp+dvcJhyFSKLyB8chilXSU3m65yDoGUMk42qhYRKPbfHlcXGVR+ncf+TlQ/9jaLQaG27D05OsaBlqkrvBPEQvm0PLclb8e/ArGOZv/+P5ZpZfpMkeKvTgUClUkFklf561B8vIUCl0POOYjh0mPUnHUQ0wBj19+htiv4pMG/TXYXpOCbdVBM96frhufeY+d9v9TSsYd+J17LgL1e7f0zyGeyCYz7gbd/FU+zG05q5UzLkOHx+ZLQ06KEq77Y9VLOLWbDwzdTEYFa393ConrNaLqhOASaaY/U2tjGX7cr9+b1Ut7NMt09kTWhRQOodrMJGZf2dejeb/v/c9aPXxbDYrWYNLy/lGbWc9OvsKqJoFEGCHFtiv+fUEgaMJcNfH21vZ47LD1TimPSowl1JbO3t9f90rGjptfKk0rajVvVOmDpJkHhFgoiTQRIDn8tzZ7buJaDjowKbIwFOP4U/By9mCcWLOFTaUjppsAfYqFoJq+Kvc0M6yhq9m0apFCqE8MC3+wnPodA0CYcKIYQQQpTftAiGVjo4WSgAOh6BzYkKvY6H+++/n1dffbXoNqeccgpXXHHFmI/V1NTEj3/8Y84666yi233729+essHQf//3fy8a1AT44he/yGtf+9oxH2vdunVcddVVfPOb3yy4TSKR4Lvf/S633HLLmI8nZi5P1ULTaoB+XOWVEsk+LKvW9fN7nIS3YKgdpMqMjAqjFZeIB7CsqKt9RtNAvLZ55CudGb4cHeDUYFhguqyUpJPQ1+Z5jmMyFJjRqOFQKIBWirD2U2PYqGCj53BoV3/I8aM/fX+LTw95g8Ppyjix8Q3/jdlUy4VOJAehunbqh0OhaQlfTWXaQDuhtfuf8URWwfdSYWaKBVnbQsvyLt+97ELmdT2DSri78SMfPWsV1LfmBhgblrgfLNiAPv5jGeMUCHIOhyzVUFi30Laq8j+zo95X2fHLoJ8Az6plxJTPUdF5rRQb617LoTWfYc3GG8c+AakIOallnR8OaKXYrBZC80JoPoOFu37j6TzRc1bDsR9yvZ+YGAawQrdj6SSvGgsc77fS3jfhYaNKyAxO5gtQptfXEnH90qiDOvoIolX+8Wt1mEUccD3nP6nDSWJkjTVRlbqTGa9f+4ZC6Fq5r3psewgumiXeFGhleHpJW/ZKmZOAl8cXUu3ky1HHsUaHWat3Uk2M3rKMWF6mTuZU0szXMt3UhStvuq14CzCHPteB6KmikUHW6p08rQ4rut1avZM6xn4zuhBi5qnq30Vg0z3lGWzTemhcJu91hRBCCCHKZFoEQ6drxdDpWik07YYbbii6XinFjTfeWLbjnXnmmbztbW/jN78pfDH/xRdf5H/+539485vfXLbjjofu7m7uvPPOotssXLjQUYVWp7785S9z5513sn9/4ZZld9xxB1//+tdpamoq23HFzOK5WiikrjY0AC6zf/H4QXy+JtfXcSLECeK+NXu/XUWNMeDq4kgsFsLvH/SUA9NAwheEvn3Fq25m8le7D4ZOgpRaHHM4FDq8RikS2sTnH6pk4jIcGo5ZxJLOL+LoMibmHD2iSZWnlXzp3QzbJmlO51pDuQ9CweAwkVSgKxkb70lmzc69if83N2U4CC22qfytmdsWvHGCgqFJwGVFzXFoJT9cMdIwMwKDHo9bMxc97+iMsTL+NozcZfmOm7Ndnm2yth36ukQV7bwV/3yz8m7bU7eKXUd9hprtj4y92l85g11WAGYVvxAs3Num5joO/WXau+htAGMKh+rVF0oVlUnO6/mRtnfR22jZ/Rvqe4vfUJtJB+okFDrFRLB4QS2mn6Cr/barZubpQwRLVLBLoojgL1mpslR1SxuVE6jM3bdQlcz826abJmeud/pG/I32iyWDiKN1qDraVOHPp2bRyyLtPhgax8KeyBtcKiDp4b2Fk8qeSQwsl0HP6VjR0svjC6mQbNLte4I81updVJN6vzumiqxalw5vpqtuagdBz6E/0/uKyMRx8m9pOv57E0KMj8GaRURXv4vgprvHPpjcACmEEEIIUVbTIhgqpp5Nmzbx9NNPF93mrW99K8ccc0xZj3v11VcXDYYC3HnnnVMuGHr33XczOFi8xcsVV1xBVVX+lnVe1NTUcPnll/PlL3+54DaDg4Pcc889fOITnyjbccXModF0RcZYASUEJIFe57sk7TAq0eu6pXySJPhMiLu7IBTVfgJWEn/C+R35dtJHPB7E53NXJUUDSctH0jCch0LB3bZpE1r5bSQYmk8cEx+JVOA1GYW4sxZZ4ViSWNJtQFaTwMYaY4NHSyWpMwdK5u/0oAlRA1WVBFNj2DZWIlpyfF8ihplMkLD82E6qDE6DawVFg8NWMNVKOFn6sauIafD4OqOYkG92VDDUVZvfhjXsXPwOlLap7t8xtuBfoC7VYrtQyDFzmZfLowuORzcscRCkLBGiLLWsXJpfk/ozyXiq+Nf8T9D8T1LtbwYYxF3b+UxjCYdKKHRqGMv5AbBwl7tQKICK9pLY/RS69eSh37BDN8AMrU+3ok6HcdxIYDBIIGes9PgaRQODrkMlvQSHxs0ej4weCTrr+8j/PY3eJ71Ow3DY0Ok+xebgZH7VRFih24t+32kd1Bdtv11IQlns1/UsKVHhspsanjeWuh5/srNRroOhpV5NOWnVno+BnnY1Lb1UtHTyb99L5G86tpIfS8XQcugnSDWp97o+B5U1V+s9YCdy2qsbnv/VCCGEmI7ira8nQKJoO/lYsBl/pKPgenmvK4QQQghRfhIMFRPi5z//ecltytFCfrR169Zxwgkn8MwzzxTc5qGHHqKvr4/a2tqyH79SSj2eVVVVfOQjHyn7cT/+8Y9z3XXXEYkUDrT9/Oc/l2Co8KQ33kvMLkPFvhpSRdYO4Sh/pBTMrYtjmmHHLcMVMLsmTHWgl2g0QN9AHVo7+3i8utEk0FCP7rXgUL+jfVBg+y0Sph8rEXP0QbwGEpafpOnhV/8EVeZ2QyuDpFWFrayhC78WyQIXWxIYxLAwY32Y8UEi8SR7u0sHc9sOxQgGLNfVZBMkxxQM9ak4dcYAyunPIanQ/RZmVRSfjjrez9A2vkSUuOXHNipfaXCiRQtU+B0ODgdqYHCCgqFeLvhNaKV5j88RysjYVw1drVclvs5YphTYFqSfb/3VqXXVc9FLTisQZDRTlROHuA79GSabV//z8Ndeg38ALD0dFp/ibV8nZq1M/RFjMpaKf1LtLyWJGq4Kl1YqeDWybaFQVv6QV3qZ822dh80yxw4QZw59NNJPH6HC33wJns6RupasC2VhfOxWs7PmPrxtnleJmY+t+33y71eJfV6jd7tuA7uLWexXDXnGTR2rhghr9B5XYwL8TS0jhpV1Loye7+hjQeGblJwYy+8Xa9Ov2KgWDoeP81ll73XdMruPIH8zVhTd5g32ppIVLEfbp5qGz+Hpol5bgLNgaHuec9apNtXIkhIVLqdr9TcvcbRSj4XXiJuaho+xlwCnk5bvqUCku+d2twHgqcBrTcxW3UUSE2Oo+qaBpkPVcUC5u7G5V4WYq3sACDj4eTQwCDi7oVZMM8pCV89Fa00ymf373TStVMc7JZcYhRAZWtehIW84tHv+PzHQtJbq7hdoavt9znoJhQohhBBCVMaUeteWbq0+3VusZ5qu3+vddxdvJ7BgwQLe+MY3VuTY733ve4sGQ8PhMA888ADvfe97K3L8ctu1axdPPvlk0W3OOecc6uvry37sxsZG3va2t7F+/fqC2zz55JPs2rWLRYsWlf34YvoqS7XQTCEgCHMG/Bzsj5Owcy8sWIaiqcbHrBr/UMAqTrU/Tk/ET284QDJP0NNUmrpQlPpgbPgacSAQJeDvZDBSRThShW3nBgKVoQlUm9TOskbyTXXVUFuNPtgLA5H8YUwD8CdRARsUJLFIGiaWncBMJkBnX8pKV8dJmhYJIx2Y9MJjhQ5lgK58dQ/b8DNY3YJtOHxZoxR2bBB/5AAD0QR7DoTJc0rk2c309BAmSQ7VDHW/s6WSqVCo22o4KonPjrrfT2t8iRhxK+Cscqi70cs8nnMaNVTTRA1/PbpaaFo6OIwRBH8Dvng/SrsLOEwMNRR4LBWsrMDXXqtG1s73tl+mSATsoeeZ0FBr0FAjNCx2tPtEtPkdFg97Pu5E0Fl/Z4f1vCyrIuo6Mt9PgDD+4fFGz8dHklk4vMkiwy5mkRgKcKV/d6YDgAdxX8UtzWu1vx17XqWr9UxnVfBGrUvvs0R3sIBDro7dQ4j/U+mqcvnDmq/XL7sOfb2q5k/D0NcAc3QfK/R+OqkjrLxVhvR0jvTuQe/eMHzBLIqPnWqOp+NPZrZ2Hx4KK3/RyouOb7IZZRA/UeW2arx3Y7rpYEh6/0LhUC8BOGd7eBl3+oW+nIpgcchDtdC0fkJEsIo+L0/Xx9fbOVz8sfAa1puOj3GhmyyLcdZKfnJWDFVaYwwFLdOBS4OR8GXq7+z1w9tlhDRT+4weK/8yL5bQlXNXQlybroOhlnb3+1XMYNWz4fVfIBaN0tnZmbVqzpw5BAJjq44uhJim8oRD06FQgIGmtdTW1uJ75YHh9RIKFUIIIYSonCkVDNVToGKZKO3VV19l27ZtRbe54IILMMoeSEm56KKLuPzyy4ueT48++uiUCYY++uijJbd55zvfWbHjv+td7yoaDNVa89hjj/HhD3+4YnMQ0084EcZUJiEzREIniNvxMY85TwVorPUzuzZAMmkTjtskkhrLVIR8BqaZ5zlHQX0oRn0ohm0rogmTpK0wDU3ASmIYBZ5HFFSFBqkKDWLbikTCh60NDGVjWXGMYDUEG/Lup5rqoKkOEkl0JAbJJJgmKmBBOE/VGaVImD4Spg+lNUrbKK3RSqGVUTD85orn37/jEwSMBmcVD4VqTcKOYhkBUAojGSMY7iASTzoOhQKoMbRMjhIniN/1I1LjIRQK4PeHPV+gVFpjJWPErKHqi3k38jCwkVmpMd8AKs+qQgdSeVblH9M2LAZ9jdhOf35KEcEPph9C1URCzdT2bvMWDvXXgK8qY75OQ5ceKAOqpkYwqNSF/NwzVxVcnxmOSwxdwE5i0E+wZDBRowq2jHfKS6gLhlqFrzjL0bb9BHhFzSdz3kDO91LpZeWuSnuKvYmAy4DhHjWraMCwQQ8wS7sPhm5XzWMKCOczlmDXko0/YIBg0Wp/pcS1+7f6GkWiVMUfhxXRM03HwEyaicZPgrCHluFjOUfUpvtSj+o0vnBWibNmKjS8rerfxeqNN5dlrNUbb+Zg05EM1shNmpNVB2O8gVcpuvsjLHjuuwU3acAgdNw3CVcvHNuxJhkvIc5Sv4/G0kp+urGV4fqJ2EllTy8t1IM6Ti1hB2HLwiHNUssq8wn0+FhKJw32ABtVa8kbVUI6yhq9m0ap/imEEKLShsKhbFpP4rDzGPAtzVqdXHAClmXBpvWw+oJp/d5WCCGEEGKiTZlg6H/+53/S19c30dOYMEuWLJnoKZTN7373u5LbnHWWswvlXsydO5ejjjqK559/vuA2v/99bhuDyarU42maJmeccUbFjn/GGWdgGAa2Xfhu99/97ncSDBWuVFlVLKlZMvy11pq+RB92RvXJKFbei0EB4iMf6scGMJIxarGyKjCbpkFNviBoEYahCfndB8MMQ+P3x0YtdXCFxTJRNRmtSR2EM1Nh0Eq0APfaJlpV5qr+KLaRHebROkkk3gtAPDlIf7QDjY3CoCbQjM+sQgVn096x03EoNDWu90olNjYRYq7CoT4Vx3JZKQvAMBMYamwVQAzbRgXqsX3eKxjlXHj1VQ2FJAtLBfeKPULa9YXXKH7nodA8/LFDnkKhSauKpFUD5si/41IzH93et9g2vlTNYFdzsjGI4BsO++VThftKs1F8qSqrjPoex6HyvSI2fNRBUs8FfQTZZLRW/NhjCnV1bsqq+FdMAvdVgKYCL78eSgc6vCl3cHE8qv2VUqlfv9Mv+jI2EayiFSoLKcc5kg6HqtbKdNqYiir1W2c846SDNYvYtObyMZ8fAJvWXF4wFFqJ52Dv404/TgOGQeKYOknS43s4UycJ6DBqoHDbehMwynCj5WQjreQry0tlTx8JFunOjIBmbpXMIKM/GymthW5adLfr/WaSRgZZq3fytDqs6HZr9U7qiIzTrIQQQsx4reugcRlJXwOMqjqcuZ6aueM+NSGEEEKImWTKBEOPPfbYiZ6CKJPHH3+86HrLsjj11FMrOoczzjijaDB0//79bNy4kTVr1lR0HuVQ6vE8/vjjqaurXJigsbGRY489lr/97W8Ftyk1RyFKUUpR5xs5j5MYGCqYd1tLJ6kimvrC3wDhbohPsmoIXipwjkPAqiCX8x2+oGZYGV+PVEQc+Xro/5WR+n9lkG5LrYfWg5GxXWo/PfR3egxGVTdL2jG6B3MrU2ts+qL7AbCNRUTj7oKeWifR2vuPIh0ODeBz1FY+ZMY8XV23TPcX2/IK99Hn9976t0aHXYc4Y1hEi1TtM7VNtcsLWWOp/+KPHSIY7vC0r5kYJO6rKXsVwuHxPQSVNZAoFTzwcM5pKE914imknKGumVsVofznjPdAR/lM5Wp/lQq2TMdnh/S55qXaXznPETatx2hcDXUryzOemBTSgfBiv2d66lYWrVi9cc0VJYLl0/Ff5tTTTC8n6i28wCL6Vaj0DhlqdJi1eifVDFRodpPbZGolX7GKoTp1U1zqtba79zRNuo9qopjYBHVXye2P0jvAjg5X0jQ9tDr3k2SVbnO9nygPJ+fhdKxuK4QQYpKrmQvRaPH1QgghhBCioqZMMFRMH8UChABr1qyhpqamonM46aSTSm7z7LPPTvpg6M6dO+nqKv4Br5PvdaxOOumkoj/Xzs5Odu3axaJF0sJOlEe8yK+vxOgQWKgJ4mEmVY2rEoEujSpw0UpR7PvQyiRhVWcHMNNhyqH9A9HuomPkE/U3kBhuyzwyl5H2zOlFoy6kVU/ef/PhQwc97KWx7QimmT+U7ISNTZgoVUE/QdMiOmhn/zgUGFU+rFofvq5DnuZomOWpCOSP9aJ0skJVaMePSZKkh3DoWEKhaen9Y/6GMY0znjTuoyIzLVpS7lBXqeoI07EKFUzfqnLjVe2vtKnwaE0TLu8aKec5wuoLsGvmjX0cMekUC4emQ5+FblIoHQqtZFXh8of1piI331E1UdbqXTypVrk6xlq9i2oP1RenCy8hTr9ODFfHN4Z7FYz8f8jj47lUd5DQRsaY5B1/9N8j/0+B9SmvqnnsoNnVnOoIs1LvH/qqdLXN1LlUJLQhhBBCCCGEEEIIIaYkCYaKcXXw4EF27NhRdJvxqA573HHHldzmueee433ve1/F5zIWzz33XMltJtPjKcFQ4VUSgzD+4UsjpS609TFSbSUY3j/cONkN2/ANhSzTl2nU8EX/7IqXDP//yHaM/P/or4e3GwnbacgJFAR1DD+j2lcrVaB6Z2pc2woRrioeDvCrdFO4dLXNjMqbQ9U5R5YZQ/PzkxxDK+5JR0N0oN/Trolk/5iCoWm1DRahkIXWEE8owtoHSqEsAwyFEY+hPFSWVYbXenl5xtIaMxknYU3tYKhFkhjuqnYaydiYQ6FpwXAHCbMK2/SXZbwREvqaKOUOdc3U6giVCA9Nllby41PtrzgJfVVW+js6pKpzXsM54eQc0XUtqN49hdevvnAGVxwupDLPERMl33mS+dxQan25ySsPN9w9Wn24f3/RT5DqMgf5lC4cZiwdYiz0/2Rvqwtv6zRYmQpxur8ZbhEHWKQPlPUxA5jPobKPmcnSSdf/AC2drMxkhBBCCCGEEEIIIcSUIsFQMa6KtW9PW7t2bcXnsWTJEurq6ujt7S24jZPQ5URzMsfxeDydHOO5557jvPPOq/hcxPSTwGQQv/OL7mokfhAabMMX7/N0XMOOo3SScGi+p/0romrO0AWhUQHOYQ7Cm/5a3F8Wn2qX0UtIUCBgW5ptR7HtOIbhvT24z28SCqVegikFpk+hVPZLMmV7fczL+7NS0+CCYhT3gUzb9BMJNZclHBoJNVcgFComWjmCf05DXRLEcWPyPFqVrvZXCZPn0ZsKUo/WIAHPIxQ7R9LPD3r3BtSm+wqun868hZCnn/R5snrjzWxac3nOc0Op9eVV+nXmmF6J6pHbADN/lhm34mWtywydZ29T+Gvn4+Vfl3mbYqF1ClxVnoxjsl81ON4+bY9qAq2ZRUfJW6CO0jvQdnalzOy/R25rFJPPUjppsAfYqFoJq+K/d0I6yhq9m0YGx2l2QgghhBBCCCGEEGIyk2CoGFevvPJKyW1WrFgxDjOB5cuXFw1WOpnrRJssj6eTY0yFx1NMThF8nioxjSUUmuaL98EghKsmSTjU9B5GTJsJbaKTdonqMWPMTsbjB/H756A8nJdKKebMKV0RSBteH/Xy/rSmeht58P7jTrd/LxYOTZoBzGThSk2RUPOUaiMv3BlL8M9NqGs6VlsEr63kK1UxtDImstpfpSp7Ts+zMY8SATUTG4BG+rMq1buV7xzIen5oXZd67ZYRDh39/GFhU6dHAkCjf47ZZ4LOs8zbPqP387JP9jbZ+1i4vzmlXg/SSlfe4wAEtfsKgwCLdBcJzOEbi5w+fjawTzWVDHIVU6Uj1LWspbPhOmqDs1nQ9Vxq/KG51NfV4WtZw4GGrzGnZh5z7O3DcyoWrvRSbbGGKK+zX847XvpYvtEdDxxYofdntLyeWfoJ8KxaRky5f5/XrWrpVrU0kOCEEttKm/Cpr5FB1uqdPK0OK7rdWr2TOiLjNCshhBBCCCGEEEIIMdlJMFSMq+3bt5fcZryCoStWrCgaDN2/fz+RSIRgcOwtgyul1OM5d+5campqKj6Puro65syZQ2dnZ8FtnPzshcjHS7DBivePORSa5ov3EY/XkvBV/t9StqkWx5w8BmIl2gOO8aG1dZxY/AB+3yxX4VClFHPnhvD7S4cttWmhlXLdTl7bylP4N+9YSpEsQxh5oqVayTuopptHsXBoOvTpjx0qur5SvIXqnG41Y6JfY7Z30duoJsqSjd8fXlYq+DcTKv05U+bfcx4rQQMEiaF1dpBqJOilCRMg6TEov3fR2zBJsmrjf7DriA/TO+sY6gb2kf53Fl9wInv4CAs3/ph9az6Mbl3HwqE2t16q2aXXNTLgeq4B4hxu7ylaIS/gIfS1UHfTpPtdzd9bFb9i64pX+Mte59wKvZ8+QhxU3l8nDraeSlLvxdh0H6y+IPf5YSgcyqb1eddXE+VEvcXz8aeTZnpp1oW7gni1mC7PvxqX6E7+j6UcVLWu912q21mm21OvYmpCRKPdqMHs99yza5IECEBNNVCe9z+FGGiqXFTCdGomv+vZpuZ6CoVmiiv5aHemMBw8ETnZRgghhBBCCCGEEELMHPLpoRhXTsKBra2t4zATaGlpKbpea82OHTs4/PDDx2U+XpR6PMfrsYTU4ynBUFEJCu06HJrw1RD31ZYlHBr3TUQoVEJfXiXtGJH4weIbleHVj21HicU68fkaHbWV9/lN5swJOgqFAmjDIBkKYQ26bQGosJM+TNNbRaxMMX/dtKgYGiROXKeCtl7kC4dmhj5LrReT2FBFQJ2OU3s4R+bpg7S2rEDrC2HTevas+Si9radTpweHg2cDraexnShLNv4nh1a/h4bWo1wdw0eCBbobyAyz5Q+/Za5PL0t/n/mqu03kMjdtdtOW6Q6W6o6c8Ua+9uY4Xfx1qg38leX0qmrXYy/R7SxvWQINVzHX14DR+XzW+jlz5hBoORwarmJBzVwW6D2uj1EufpK00l32cauIVSRMNhmYaI7V28Ye/Gs9CRqXQs3c/Bu2roPGZYXXi0nLAI7X23lJL2CPMdvxfivtfSwZqn4qpq9BvFeTFcIxZaGr56K1JpnMvsHDNK3UzY4SMBZCCCGEEEIIIYSYluRTHzGudu/eXXR9TU0N1dXuL7h6MW/evJLb7Nq1a9IGQ6PRKB0dhdvbgrPvsVxKHau9vZ1YLIbf7x+nGYnpIkCCsHbfTj5cNR8GKREOLR6SjPtqJ08beUcq0wJ2KlXx6YvsHwp5FaGAIIy1w56t45i+AWrmLCXaGyY2GCX7EVZUVVnU1vkIhQq/5Cr0+MZr6jwEQyGR9JclGBoOOQ8vTHZeAuaZMsOfkVAzMV99VjvZuK9+eH001EzCV4+hNfn+xRWfReHWu6N5qQak0Ph1ouhxvLQtt0gOfb+ZnD3ipY6Xf4yRfaIk0EMtnWsIA1BNhGa7l2LBxNFjv6LmsZNmBzMeYWibNXpPqpLbUGirpWYuLfkq97WsgIbP0+Ah1BUkwZoJDAtOJhNVBcsAmnWv62Bog93HStpTX9TMhWiRNr4S+Juyyhb8K3UOyDkypUVdVoU8pKpBSzB0umuknz5CEz0NMd1Vz4bXf4FYNJpzQ/ecOXMIBCSgLIQQooIGD0DN+F2nEkIIIYQQQmSTYKgYV11dxS9sjGeQcf780mGvAwdKtCOeQE7mNhkfTyfbCZHJRwITmwEdcF3xr1g4NB36DA22FV0vYNwqjOrssFpme9fM5an/z55TEoOEjjMYc3gBvZoxB0MB6mc1UxUyqA1VoXUVOhFH2TaGobAsw1GeWaEJ6TyV1IIG2u9DxdyFPO2kha1NDJV0tV+mpBXA8vmwdHaIyU1o0EuAy08Cny42b2/nYjVRwtpPwkMF1CodxSIJPj+Y8wgoEzOe3abWsixUer1hERgKKE42Ck2wAlX7TGzMoXDmeMuM9xvDSzUm7s5/n066TsEHiGWf5xLqmtaW0kmXruWQi5bhPmVP5yLdYhQJ/olCkii6cdeBoJsakihMeRKZ1lbo/fQR4qCL3y2j1Wn3N5IJIYQQQpTF/r+X3ua5O2H1BakbaoUQQgghhBDjToKhYlx1dxdvTdjQ0DA+E3F4rFLznUhO5jYZH08JhgovDGyqidJP0PW++cKhmaHPUusnitfKnkqPDlJmf+2lZqKJTUDHC47J0LLRY6sC22V/7a1CYT57Ip2lq4Wm+Um9CkqU2rCwQCBAQ3UQGApuKsCnAHfhQ4XGV2giTXXojm6w3T1GsViIQGDA02OrlUGidh5WmYN+tm2zZ88etmzZwoEDB+jt7SUej1NXV0ddXR3z589nzZo1BIPu/52XotCY2CTy/GwS8Tgvb/oHO7Zt4VB3N9FolKqqKmY3z2XFYas4annLyMaGNRxgzssY+0vrLVu28Oqrr9LR0cHg4CB+v5+mpiaWL1/OEUccgc/nLng0Fvv37+fll19mz5499Pf3Y5omtbW1LFmyhDVr1lBb675t8mS1iC626bnYyii98ZAYPgntzCBJlOuqbhLsmjkk+CeK6SNE0uXNKUll0qdDNCChv+nMRHOs3sY25rJdub+BZKluZxlSVXw6i2PSTTVRfEQdfIzfRgOBofeWAeI0MYDP5Q1TQgghhCO7N6C2PlZyM4WGTfel3vVIOFQIIYQQQohxJ8FQMW601hw6dKjoNuMZMHByrKkeDJ2pj+eGDRvGtP+LL76YsywejxMt1v5zDCzLQg2VFTSMjHpnxcJHM1ASPPc0zwx/5gt9jl4fCc1DaZ0TqssfinQSfhz1tU79p1g40sB2HnLMOE6Ng4vHbkc1SOIf48Wk//iP/+DWW2/Nu87v9/Pwww+zcOFCz+PH7Thbd2ziY+/4WM66//x//0nzglEtohXQCHThKYVrGAbz58+v/L9Tnwmz6uFAj6twqMYiFmrGH+lEaecBT60MYnXzsU1/8QCkA/F4nOeee45nnnmGp556ik2bNhEOF6+kaVkWq1at4i1veQvnn38+jY2NY5pDJh+x1MXUoefbjS88z90/uYMn/vA7Bgb6C+7X3NzM2WefzXve856CP/OxngdtbW387Gc/49e//jUdHR0Ft6uuruaNb3wj73nPe1i7du2YjlnIwMAA69ev57777uPVV18tuJ1lWRx//PFcfPHFvOlNbxr+PTaRbDt1rmutSSTcpb57jBrsgPNQKKRCOwdiFvV24fNHTB89Rg3JgPtgV+Y5Eo/nVoDOt0xMPeU4P8T0FTECUKBTc12yj14z/3vpSDxJ1B55DyrPIdNXK7vAirHd1+p4n6Xx3bQm9pOIxUrelhaLxdAV+jxDVM6gCvJCYCUx5Xe8zw4jO2Ds1zHWRjdTpSPyHDLNxZSi1L3UsViM6OiuIHEbX1VzgT1S4nFbnkOmAS/niBo8gO8fP8WnNfPs7M8FjW0mWinir3kvumpWJaYsxpHb88Pc9wy+Vx5wdQy16T7iiQTJBSd4nKWYSF5/z4C8j5kJxnJ+iOlvrOeHPIdMf/IcIqaqqfRcJMFQMW4GBwdJJosHi8YzyFhXV1dym97e3pLbTJS+vtzW16PN1Mfz5JNPLvuYBw8epLOzs+zjAjQ2Ng5XgDPN1CUd27Zdh1qmu7jp4VeW1ph2nKTpJ1w1n3i8loQvfzWnzPVWMoIvObEvMO2hP9NFOrCVTywW48Ybb+Sb3/ym5/G7nLaQz+QDmoBuXIVDDcNg3rx5WJY1Pv9OLQOaajF7BlDx0gFd7TNJ1leDzyJhzSM42IWZLN0+PGn6iVTNxlZ+8Ph9xeNxNmzYwGOPPcbjjz/u6HdVpkQiwcaNG9m4cSO33HIL7373u/n0pz9NIFAgTeGCrUzwKfp6e7jh+mt55L//n6P9Ojo6uOOOO/jFL37Bxz72MT70oQ/lhCBLvb4pOCfb5vbbb+eHP/whkUik5PYDAwM89NBDPPTQQ5xzzjl86UtfKuvv+scff5x//dd/LRpOTUskEjz11FM89dRTrF27luuvv55ly5aVbS5O2bY9HMxN/3uMx+McPHjQ1Tj9QQ0FroeGot2EA0151x081EssesDVscTUVKlzpNSNc2JqkOcQUYymC2vBIhLWSNVhIxljfveL1IXbqQ3Npa3pyNSNOUOsRJh4+zY6S7xIleeQ6aNzdmvq/YnT7eM+gl2dWJFuSvW66O7uJjHo7gYYMfH2zDraVSg0n5jy80pyFgsPPJ93vTyHTB9RXw2lngwOHjzIYDzPDSlLLy2+44ANA5X5TFSMHy/niBXpYv5g6vOBQjchdB/oIDEwnT7BnJncnB/V3S/Q1PZ7T8fxvfIAfX19DDRV5mZnUTlj+j2Th7wGmV7KfX6I6aUS54c8h0wv8hwipiq31yEnknwqKMZNLFY6lFKO4IdTTo41mVPe8niKmUa7aO87TKnh6oBAwVDo6PVKirWOu4cffpjNmzd72jdhJ+hNeAyeB4DZOL4I6/f7WbhwIVVVVd6O55XPIjmrjmRTLXbQjx5VnFErsIN+kk21JGfVgS8VpLbNAIM1CxisnkfcV4UeFWjUShH3VTFYPY/BmgXY5th+b7z44ot88pOf5MEHH3QdCh0tGo3yk5/8hAsvvNDzuZFJo9i7eyfvv/Acx6HQTJFIhJtuuolPf/rTZakgHYlE+PSnP83NN9/sKBQ62kMPPcTFF1/Mnj3laR/6/e9/nyuuuMJRKHS0F154gUsuuYQ///nPZZnLRKiOHMBKZFe0NZIxFnY+y5L2p1jY+SzGqIC1lQhTFZ281eVFeck5IoqR80MUo9Asad9A7WAbgVgfDX07Wbb/CerC7QDUhdtZtv8JGvp2Eoj1UTvYxpL2DTkdBcT0ZWMwGJztap/B4Gxs+Vh3Wov5qssyTrRM4wghhBBjCYWmNbX9nuruF8o0IyGEEEIIIUQpUjFUjBsnQUbLGr9T0smxnMx5osjjKWYaw06QNAqk97TOCoCO3s9KRolboVTFwOHlqQp/tpG9zJcMY+ixtU0X7tm2zfe+9z1+8IMfuN73YOIgeiwXzn3AbKhOVsNAqsJ1ZmtwpRRVVVXU19cTCoUmrmW2UuiADx3wpdrK23bqb0OBYaT+LrBf0hci6QuBtjHsxPC/GduwwEvoegz8fj+zZ8+mqamJ6upqent72b17N/39+e/227FjBx/5yEe44447WLFihefjHuho45/f917a9u3Nu766upqlK1YSqqrmYHc3O7ZtIZHnhoY//vGPXHnlldxyyy3DVZ7dSiaTXHnllTzxxBN511uWxfLly2loaGBwcJCtW7cyODiYs93OnTv58Ic/zE9/+lPmzJnjaS4AP/rRj7jtttvyrlNK0drayrx580gkEuzcuZMDB3Kr2w0MDHDFFVfwgx/8gNe+9rWe5zJR0qGd9sYjiFk1hKLdzO7dii+ZCu3WhdsJ7e+hq2454UAT/kQ/cw++JKGdGUTOEVGMnB+iFF8yQkvXc0XXzz+4cRxnJCaTiL8+9brcBduwiPjr8Ufc39QjpobqSDdRf31ZxhFCCCHGyhfporHt8bKM1dj2ONHqFhIFOisIIYQQYnpLKouB4GwSZoCEg4I1PVULsIY6fVrJKNWRLkwtnVeFcEqCoWLcSJCxvOTxFDONaceI62B2AFRrLDuKlYwSs2qwlZGz3rRjKMAf7ydhpF5gWnYcK5mq6pQwQyQMH75kFNOOMkGRPwH85S9/4a9//aurUJnW2nu10EwKBq1Bls1bhtaaRCKBbdsYhoFlWRjGJKvGYygwPIQSlZHVpnS8HHvssZxyyikcd9xxrFmzBp8vO+SdTCbZtGkTd999N7/5zW9yWrMfPHiQj3zkIzzwwAPU17u/OJpMJvnCVVflDYUuWbKEK664glNPPRXT8pEwA9jKor/3EL+575f84Affz6l++uc//5lbb72Vyy+/3PVcAG699da8odDa2lo+8YlP8Pa3vz2rRXw8Hud///d/ufnmm9mxY0fWPnv37uULX/gCP/7xjz0FVZ988kluueWWnOWGYXDxxRfzvve9jwULFmSt+/vf/85tt93Gk08+mbU8Fovx+c9/nl/96lc0NxfoqTyJSWhHlCLniChGzg8hhFd2kdf1oWg34QKhCU9dNcSUMadnMxF/HYPBWZ7HqIocYE7P2LsviMlJLqYKIcZTPDibg/PfOOaKoQAH579RQqFCCCHEDBW1qtnVfCIJK+h4nwP12UVjrESERR1PE0gMlHt6QkxLEgwVk8p4VmFzEvLJrBg3Fc3Ux3N0UMWtF198kY997GNZyxobG8dUja0Yy7KGf1bpv9NhNJHN0BEiBLBRGGiCOoqpbLAsfERIaIPo6PUZj6OPJLY9iJ0c+eDblwwTII5hAC6rtAjnnAYrb7zxRu655x7H40aT0bFVC82g0WhT4zf8+P3jH56cDjKDibNmzeLCCy/kHe94B4sXLy66n2VZHHPMMRxzzDG8613v4rOf/Szt7e1Z23R1dXHzzTfz9a9/3fW87rnnHp599tmc5aeccgo33ngjoVBoeJmPBJCgui7IBz/4Ac4445/4wAc+wL59+7L2veOOOzjrrLNYtWoVpmk6/p378ssvc8cdd+Qsb2lp4Y477qC1tTVnnWVZvOUtb+HUU0/lM5/5TE6o9G9/+xv33Xcfl156qaM5pIXDYb72ta/l/H4OBALcfPPNnHLKKXn3O+6447j99tu56aabcqr8dnd38+1vf5sbb7zR1Vy8SiaT2LYNjNykYppmxX5nCzEW8XicQ4cOZS1raGjICcsLIUQ+8hwyfc1C0WFHiRojwS5LJzgstp3Z9iG6ogd4xb+UhBp5vxqwoyyqMzHNJthafPympiZ0tbw2moqa9TZ2xqPs8i0ovfEoi+J7Waz3oWangqXyHDK9DKogLwRWEVPOP7sYfTHVr2OsjW6mSkfKPT0xCQ2o0hfeGxsbqdYjn4+oAVt+x8wQTs+PqoZ/Il5bi++VBzwfK37Y26lacAJVnkcQE8HLc0iavAaZ/sZyfojpKY7JIaOOmPIRV6X/rcdmr0DpVPc2v47TYPfiI1U8RJ5Dpp+XfMtdhULzSVhB+ppfQ0t8W5lmJYR7o69jT2aSgBHjxskv6ERi/O5SjudpDzvaZA4GyeNZ2Lp168o+ps/nIxAoffd9OU1Yu+pJzEJTQ8YH1mr4PwD40PiKrAcw0NijxjWUPN4ToaamJqd9+AsvvMCjjz7Km9/8ZkdjBKwApjJJ6mTpjUswlYnf9KOkbqxnSimampr40Ic+xCWXXJIVuHTquOOO44477uCSSy6hp6cna919993HRz7ykbzhyUL6+/vzVsRcuXIlN998M8Fg8Tegixcv5kc/+hEXXngh4XB4eHkymeTf//3f+eEPf4hSyvFzyLe//e2ciqhVVVX88Ic/ZNGiRUX3ra6u5pZbbuGd73wnr776ata6W265hXe84x1UV1c7mgfAT37yE9ra2nKWX3fddZx66qkl97/iiivo6Ojg/vvvz1r+6KOP8txzz3Hsscc6nks5ZAbQvVRPFWIiTMRrTCHE9CHPIdPHa9nGK3o+AwRppJ+lupOgLw4EWEiYWfpVtjOHg9RQTYTDaCMU8EO89Ocsfr8f5DyZslbRRcCGVw3n4dCV9j6WmAegRBVJeQ6ZujarVleh0Hxiys/uQOv/z959h0dV7Wscfye9EQhVepEiIL1JE5AqCCKIBUWax4IUOVgPVmwoqIjiASzYkK6AgCACSpUmoST03iEESEhC6r5/cPGISWbPJNPz/TwPz71n79+s9ZsIOzN73llLdY1jDuoKnixdtv2+CP77l6/5HVNg2PX3o3JrGQEBssTOtXseo9a9CijfnA+mvVCeriFW8BrEtzj67we82xUFa6ulitJsCIRed+IfX4QLMtLVyDikCKXmWM81xLtdtTgmJH7VP0zBfvw9gPt4U0CdPYfgMt4YZPTkf8z8PAF4u+rVq6t169bZjn/44Yc2X78ssqhcWDn5W/IXAvO3+KtcWDlCoflUrVo1/frrrxo8eHCeQqHX3XzzzRo5cmS241lZWVq+fLldY82aNStbwFSS3njjDdNQ6N/7efLJJ7Md37Bhg2JibN8WeOfOndqwYUO2408++aSqVKli0xihoaEaM2ZMtuOXL1/W7Nmzbe7l6tWr+vbbb7Mdb926te6++26bx3nxxRdVrFj27S0/++wzm8cAAAAo6EKVrnrGMbUw9qmmcUohuvEeS4jSVdM4pRbGPtUzjilU5vdg4DsuWWz/8lde6uF9kuWYD0AdNQ48U7r8dVaROqZiOq0ipvWnVUTHVEzHVExnFakMPj5Ebso3lxFZzq6HGJHlpPKOX9ADgHvk93dMuvhSv686ZCllVyg0J2mWQB2ylHJQR/A0UbpiXuTCcYCCgHd2cBlbVotMS0tzQSfXeNIKl3nBzxOALxg1alS2beaPHj2qOXPm2DxGWECYqkVWU/nwnFeRLBdeTpUiKuX6p0pEFVWLrKawADYxyq/IyEiFhTnm59inTx8VLlw42/HVq1fbNU5Of5dat26t+vXr2zVOv379cuxn3rx5No+RU3CzSJEievjhh+3qpUGDBmrVqlW24/b8u1m+fLni4+OzHR86dKhdvRQqVEj9+/fPdvz333/3qm0UAAAAAE+UKYviFWHXY+IVoUy+9OjT+DAVZq4oWOst1bXDr5L2+pXVET/zcMURv1La61dWe/3KaodfJW1TJec3CrfJT6gr4Xi0LAkn7JrPknBCOp79y9LwXAT/kBtH/I5Zb6muK3xBxSfxBSaYqWqcUZSRv/chUcYVVTXOOKgjwPcRDIXLhIWFmW6z+s8thZ0pMTHRtMae7VhdLSLC/KYwP0/4Okt6ivwvHFbg6Rj5XzgsS3qK+YPgUW655Rbddddd2Y5/+umnSk5OtnkciywK8ss5fB7sF6xQ/9Bc/wT7B7NSqAfy9/fXbbfdlu34qVOnbB5j165dOnLkSLbj9913n939hIaG5vh39ZdffrFphduMjAz98ssv2Y537949T6ur9unTJ9uxQ4cO2byC6eLFi7Mdq1GjhurVq2d3L7179862dXtWVpaWLFli91gAAABwsOQL7u4A+ZCoUGXauUNGpsVfiXLM9nzwTHyYCjOOWK0r3cKG374qP6GuKyeiVTg2+w40trDEziUc6iUI/sEaVoSENXyBCWb8ZaihcUiVjbwtLFLZOKuGxiH5y3BwZ4Dv4p0dXMbf31+RkZE5bud6nS3hQkexZa6iRYu6oJO8iYqKMq3h5wmfZGQp6OhmhUXPU/DhdbJkZf7vlJ+/Uiu3VHL93kqr2ESy8P0HbzB8+HD9/PPPN6w8fP78eX311VcaMmSIGzuDu5UuXTrbsbi4OJsfv2bNmmzHQkJCdPvtt+epn86dO2v69Ok3HLt8+bJ27NihRo0aWX3s9u3bc3wN1KlTpzz10rZtW4WEhOjq1as3HF+zZo1q165t9bFpaWnauHGjw3opVqyYGjVqpE2bNmXrZeDAgXkaEwAAADY4s928Zts0qVZvtm/1UplW1nUobCTpci7bxv/1uKQ4aduXCjIM3ZR54xfa/A8HSBaL1GCQFF7cYT3D+a5/mHpIpXQ4D6GKysZZVTHOsmqID2OVLViT11BX2WOLVTtmQr7mtsTOvRbj4HWJR3NY8E+lVEMJDuoKnoIVIWFNVeOMEhWqixb7dj34O77A5Pv8JFU1zirAyNR+vzI2P65a1ilVku2fEQK4hvf+cCmzYKC10Kij2TKXJwcZbemNnyd8TcDZvSr2TT8VnTdCIQdX3xAKlSRLVqZCDq5W0XkjVOybfgo4u9dNncIe5cqVU9++fbMd//LLL3Xx4kU3dARPERiY/Qak2erjf5dT+LFhw4YKDs7bTaf69esrJCQk2/E//vgjT72EhobavaX9dcHBwWrQoEGeetmxY4dSUrKvsNy8ed5vyuf02K1bt94Q+AYAAIADHd8gy8HsK9L/k0UGK3R5sSglKcRIu+FYgJGhellH1NQ4qHpZRxRg3Bj4DDHSFKWka//DyJAl6az8ks8pMDX+hj9+yedkSTorGeY7IMDzXP8wtVqW7btqSNc+TK1KKNTnscoWrMlLGCvsyjHVipnomAZi50lX8rZKGFyD4B+sYUVIWMNqkLDHpVy+6OioegDX8P4fLlWsWDGr58+edd2bwTNnzL9pYtavO9nSGz9P+JKgIxtVdNYTCow7aFN9YNxBFZ31hIKObjIvhts98cQTioi48RuEV65c0aeffuqmjuAJTp48me1YiRIlbHqsYRg5bqtet27dPPcTFBSkW265Jdvx2NhY08fu3Lkz27GaNWvmGH61VZ06dRzWS0BAgOlKo/b2kpqaqgMHDuR5TAAAAOTi+IZrYU87EA71Tn4y1Ng4qJLGJYUbV1XOiFNzY79K/v/qWyWVoObGfpUz4hRuXFVJ45IaGwflxwepBQYfpiInVY0zijLyF7iJNJId1A08TV7CWMkRFRRbe7hjGqjVW4pgC2lPRvAP1jjidwwrQvo2vsAEW2TKonjZt7JsvCKUKdsXjwFwDddVuFTZsmWtnr948aLS0tKs1jiKLUFGs37dKTw8XIULF7ZaY8tzdBSzuYoUKaKwsDAXdQNfE3B2r4osfEF+6dlXuLPGLz1FRRY8z8qhXiAqKkqPPvpotuMzZ87UiRMn3NAR3C0rKyvb1uSSVLFiRZsef/LkSSUmJmY7Xq1atXz1VaNGjWzH9uzZY/q4vXuzX4ec0UtCQkKOgVqzXsqXL5/nlVRz60Wy7WcDAAAAO+QhFHod4VDvFKp01TOOqYWxTzWNUwrRjavyhyhdNY1TamHsUz3jmELFqv0FBR+mIjeOWK2rlrgf56vyGuo6WaGbYmo/bbXGiCxn/Xyte9lG3gsQ/IM1rAgJW/EFJliTqFBlWvztekymxV+JCnVSR4DvCnB3AyhYKleubFpz6tQpVapUyem9nDpl/i0VW/p1p8qVKys6OjrX87Y8R0cxm8vTf5Y+JSNVAZesh4K8ipGlIotfsjsUep1feoqKLH5Jl7q/I1n8ZBiGlHnjFvQB/v52bU/tbhlFykoBvrcNS//+/TV9+nSdP3/+r2Pp6emaMGGCxo8f78bO7BcbG+uyLzpYExQUpFq1arm7jTxZvXq14uLish1v06aNTY8/fvx4jscrVKiQr77Kly+f7diZM2eUkZGhgICcX1qnpaXl+AWK/PaS2+OPHz9u9cstOf1s8ttLiRIlFBYWpuTkG1cUye2/AwAAAPIgH6HQ6yyxc699BEsoA/B6ef4w1QhVESVLSXHSti+tP6DBICm8eD66hLtcX60rwMjUfr8yNj+uWtYpVVL2+zHwHddDXYdUSoct9q3cebJCNxVXgkrFZL92XA99Grm8XiEU6j3y83dEuhb8q/L/q/5lOL49eAB+x8BMfr7ARGi4YMi0soZhYSNJl3MJClt7HICcEQyFS9kS+Dxw4IBLgqFmW5tGRUUpMjLS6X3kR6VKlawGQ48fP660tDQFBQU5tY+rV6+ark7miv+muCbg0kkV/7qvu9vwKAEXj6v4Nw+7uw2Hiev/vTKKV3F3Gw4XGhqqp556Sq+99toNxxcvXqzBgwerZs2a7mksD4YOHerScH5uypQpo5UrV7q7DbsZhqFJkyZlO+7v76877rjDpjFy+71UqlT+tqrK6fGZmZk6c+aMypXLeVWEM2fOKCsry+G9lCxZMsfjZr+Tczqf316ka+HQo0eP2tULAAAAbHTlrBQ7zzFjxc6ToqqwjSvg5fL9YaqRIUuS9dW+DINIj7fL02pdBqEdX5efUFfJcrVlGPfeEP68IfRZvrkMKffz8AoE/2ALfscgN/n+AhN8XpSSFGKk6arlfzmWACNDtY0TKqkEnTMiFWMppwzL/yJtIUaaopTkjnYBr0acGi5VtWpV0xqzwKajHDx40Op5W3p1N7Mes7KydOjQIaf3cejQoWurMFrhDT9PAO537733ZguSG4bhdSuGIn9mzJihnTt3ZjvetWtX3XTTTTaNER8fn+2YxWJRsWLF8tVb8eI5r5SS03xm53IbK7+9XLx40erjcuonv71I14Kh9vYCAAAAG0WUkmr1dsxYtXoTCgV8wPUPU/8uwMhQvawjamocVL2sIwr4R7CTD1MLlvys1oWCIc/b/JZvLqPWvTJkyTn0aXYeXoOtoJEbfsfAGrMvMOXlcfAtfjLU2DioksYlhRtXVc6IU3Njv0oqQZJUUglqbuxXOSNO4cZVlTQuqbFxUH6sKAvYjRVD4VL169c3rdm1a5fT+zh37twNWxXnxJZe3c3Wn+ctt9zi1D5s+W/mDT9PAO4XEBCgp59+Wk8//fQNx9etW6c//vhDt912m3sag8scPHgwxyBwaGioRo4cafM4ly9fznEMf3/7vqX6TxEROd/sunTpkl29WBvLVv7+/jlu326tl5SUFKWlpWU7nt9eJCk8PPuNX2u9AAAAwE45rMBlL8IZgO+4/mHqPpVWkkIUpSuqbJxXiNIlXfswNdLYr8MqoYuKULiuqrpxmg9TC5D8rdYFX5fvbX7LN7e+ArnZeXg8toKGNawICWtYDRK2CFW66hnHcj0fonTVNNy/OyPg7Yjcw6XKli2b67an1/35559O72Pr1q2mNQ0aNHB6H/llS4/8PAF4my5duqhu3brZjo8fP950dWJ4tytXrmjYsGHZgo6SNHLkSJUpY/u2RTmNkVNw0V6hoaE2z2d2LiwszCn9uKuXnMZISUnJ97gAAAD4m/9fgSsvCIUCvuf6h6ktjH2qaZz6KxR63fUPU1sY+1TPOKbQf5yHb2O1LliT51CX/nYvyiz0SSjUqznk7wh8Fr9jYA2rQQKA52DFULhcw4YNtXTp0lzPb9++Xenp6QoMDHRaD5s2bTKtadSokdPmd5RbbrlF4eHhSkrK/QX25s2bnd6H2c8zPDxcNWrUcHofAHzHqFGj1L9//xuO7dq1Sz///LO6du3qpq5st3LlSne34HUyMzP173//W4cOHcp2rnXr1urXr59d42VkZGQ7lt/VQqVrq9rmJD099w/XcurF2lj57ceTeslpdVIAAADkU/nmMk78IUvCCZsfYkSWIxQKAAUMq3XBGrNQ1+VctgQn1FVw8HcE1vA7BmZYDRIAPAOvzOBybdq0sXo+OTlZf/zxh1N7MAvsFCpUSA0bNnRqD47g5+enVq1aWa1Zt26dUlNTndZDSkqKNmzYYLWmdevW8vPjcgPAds2aNdPtt9+e7fhHH31kNfQG7/Xaa69p9erV2Y6XLVtW48aNk8VisWu8zMzMbMcc8bsot3BpTvOZnXNWP+7qJacxrPUCAACAPDq+wa5QqKRr9cet378BAPgWVuuCNddDXX8XYGSoXtYRNTUOql7WEQUYN37BmFBXwcLfEVjD7xgAALwDSS24XMeOHU1rli9f7rT5r1y5Yho8bdu2rUNWznIFs59nSkqK1q1b57T516xZYxo8teW/OQD806hRo7IFzY4eParZs2e7qSM4y7hx4zRnzpxsx6OiovTZZ5+pSJEido9pb2DSVnlZcTMvYdL89OOuXnIaw1teTwEAAHiN4xtkiZ2bp4daYucSDgWAAub6al0tjH2qaZxSiG78wvX11bpaGPtUzzimUNnxhezkCw7uFq5EqAtm+DsCM079HQMAAByCYChcrkGDBipevLjVmnnz5jlt/gULFphua+pNQcZOnTqZ1sydm7cPDGyRU5Dnn7zp5wnAc9SoUUPdu3fPdvy///2vkpL41rGv+Pjjj/XFF19kOx4ZGakvvvhCVapUydO4QUFB2Y45YrXZ3MbIaT6zc87qx1t6AQAAgJ3yEQq9jnAoAMAmZ7ab12ybxu8UL0eoC2b4OwIAAODdWMIHLufn56fevXtrypQpudbExsYqOjpa9evXd/j8M2bMsHr+en/eok6dOqpRo4b27t2ba83cuXP10UcfKTAw0KFzp6am6ocffrBac8stt6hOnToOnRfWZRQpq7j+37u7DYcJPLlDhX8dm+9xLnd8Uell6sgwDGX8Y1W7AH9/u7epdqeMImXd3YLLDB8+XD///PMNgf64uDhNmzZNQ4cOdWNncIQpU6Zo0qRJ2Y6Hh4frs88+U61atfI8dnh4eLZjjggU5zZGRESEXb04sx9v6QUAAAB2uHJWinXQF6lj50lRVaSIUo4ZDwDgW45vkOXgL6ZlFhlS7NxrawOWb+70tgAAAAAA9iEYCrd46KGHrAZDpdxXEMuPAwcO6Oeff7Za065dO5UpU8ah8zrbQw89pFdeeSXX8+fPn9fMmTPVr18/h847ffp0xcfHm/YGFwsIVkbxvK2w54kyilVSWPQcBcYdzPMY6cVvVkqd7pLF71ow9J9bLwcEeFUwtCApW7asHnzwQX399dc3HJ82bZr69u2rokWLuqkz5Ne0adP04YcfZjseFhamqVOnql69evkaP6ft51NTU5WWlpavVSwTExNtns/sXEJCQp77kP73fOzpJSgoSGFhYUpOTnZoL1LOPxtrvQAAAMAOEaWkWr2lfK4YKunaOIRCAQA5ycPq1BbCoQAAAADgkQiGwi1atWqlKlWq6NChQ7nWTJ8+XWPGjFHZso5bGW/8+PHKysqyWvPII484bD5Xefjhh/Xaa69ZfW7jx4/XQw89JD8/P4fMmZmZqffff99qjZ+fH8FQ5J/FT5e7vKKis56QX3qK3Q/PCgzV5S6vSBbH/N2H6z3xxBP64YcfbgidJSUladKkSXr55Zfd2FnuYmNjcwzsuVpQUFC+Vt10lm+++UbvvvtutuMhISH69NNP1ahRo3zPUaJEiRyPnz9/Pl+vLeLi4nI8Xrx4cbt7yW0sW50/f97uXq73c/ToUYf2kls/Zr0AAADADuWby5CsBnaMyHKyJJzI/XytewnuAABylodQ6HWEQwEAAADA8xAMhVtYLBaNHDlSw4YNy7UmNTVVL7zwgr799luHzBkTE6PPP//cak2ZMmX0wAMPOGQ+V6pcubLuuecezZuX+5ZiO3bs0LRp0zR48GCHzPnZZ58pNjbWak2vXr1UuXJlh8yHgi2jVA1duvtdFVnwvF3h0KzAUF26+11llKrhxO7gbFFRURo8eLAmTJhww/HZs2erf//+qlChgnsas2Lo0KE6deqUu9tQmTJltHLlSne3cYPvv/9eb7/9drbjQUFB+uSTT3Tbbbc5ZJ7cwp+nT5/OVzA0p/+uwcHBuYY/JalkyZIKCgrKFhY+ffp0nvuw9vhy5cpZfVzZsmWzBUPz20tmZmaOwVCzXgAAAGAnK+HQ66FPI5dgD6FQAECu8hEKvY5wKAAAAAB4FpZPg9sMGjRIxYoVs1ozffp0LVmyJN9zpaena/DgwcrMzLRaN2LEiHxtL/t3FovF9M+RI0ccMpckPfvss6Y1zz//vE6cyH3VCFsdO3ZM//nPfxzSE2CrtIpNFX//ZKUXv9mm+vTiNyv+/slKq9jUyZ3BFfr3758teJeenp4tLArPNnPmTL3xxhvZjgcGBurjjz9Wq1atHDZXpUqVcjye39+9/wxUSlKFChVksVhyfYzFYskxwOyMXiSpYsWKVh+X088mv72cPHlS6enpdvcCAACAPCjf/FrI829uCH2anQcA4O+unJVic190wi6x866NBwAAAABwO4KhcJuwsDC99NJLVmsMw1D//v114MCBfM01cuRIbdy40WpN2bJl9dRTT+VrHndq1qyZ7r77bqs1Fy5c0P3336+UFPu3474uKSlJffr00cWLF63W3X333WralEAeHCujVA1deORbxff+SFertpHh53/DecPPX1ertlF874904ZFvWSnUh4SGhuZ4jf7555+1a9cuN3QEe82dO1evv/66DMO44XhgYKA++ugjtWnTxqHzFS1aVKVKlcp2fM+ePfkad/fu3dmO3XLLLaaPq1mzpsN7yWnl7ptuuklRUVF293LmzBldunTJob3kNhcAAAAc4P/Dn4YsOYc+zc4DAHBdRCmpVm/HjFWr97XxAAAAAABuRzAUbjV06FDTwEBcXJzat2+vvXv32j1+VlaWnn32WU2aNMm09r333lN4eLjdc3iSDz74QMHBwVZr1q9frx49eighIcHu8S9fvqzu3btr06ZNVuuCg4P1wQcf2D0+YBOLn9IqNdOlu9/VuaG/6vyAGbrQ9wudHzBD54b+qkt3v6u0Ss0kC7/ifM29996bbaVDwzC43niBH3/8Ua+88kq2UGhAQIA++OAD3XHHHU6Zt27dutmObdu2Lc/jJSQk6NChQ9mO16tXL0+9HDx4UImJiXnuJzo62qZ5bK3Jz88mp16ioqJUvnz5PI8JAAAAE+WbSy2fzT30aXYeAIDrclht2l58EQEAAAAAPEuAuxtAwRYQEKApU6aoXbt2Vrd5P3bsmJo0aaKPPvpIAwYMsLpd63WHDx/Wk08+qWXLlpnWdurUSX379rWrd09UpUoVvfLKKxo9erTVul9//VVNmjTRl19+qZYtW9o09urVqzV48GCbVm995ZVXVKVKFZvGBfLDCAxVZrHKyv3qAV8SEBCgkSNHasSIETccX79+vdauXZvr1uHusHLlSne34DF++uknjR49WllZWTccDwgI0Pjx49WxY0enzd2iRQstX778hmO7d+9WfHy8ihYtavd469evz/Y8JKl5c/MPPVq0aJHtWGZmptavX6/OnTvb3cuFCxdyXL00p3n+qXr16ipevLji4uJuOL527Vq1a9fO7l4kad26ddmONW/e3KbXbAAAAMgHs1XZWLUNAGCr8s1lSLLEzrX7oYRCAQAAAMDzsJwa3K5169Z65ZVXTOsSExM1aNAg1a9fX5MmTdLRo0ez1SQnJ2vlypV69NFHVbNmTZtCoaVLl9a3336bp9490QsvvKD27dub1u3bt0+tWrVSt27dNHfuXF24cCFbTVxcnGbPnq0777xTbdq0sSkU2qFDB73wwgt56h0AzHTu3DnH1RlZNdQzLVmyRC+88EK2MKW/v7/ee+89denSxanzt2nTJlswMSsrS0uXLs3TeEuWLMl2rGLFijZ9GeLmm29WhQoVsh3/+eef89TLzz//nG0FVovForZt25o+Nre6X375xeoXdXKzb98+7d+/P9vxvIZMAQAAALhQcvZ7ggAKsPLNZUSWs+shRmQ5QqEAAAAA4IEIhsIjvPTSS+revbtNtTt27NDQoUNVqVIlFS1aVDVr1lT9+vVVqVIlRUZGqn379vriiy+UmppqOlZISIhmzZqlkiVL5vcpeAw/Pz9Nnz7d5hU7lyxZoj59+qh48eIqU6aM6tSpo1tvvVWlS5dWiRIldP/999scoKlSpYq+++47+flxaQHgPKNGjcp2LDY2VosWLXJDN8jNL7/8oueeey5b0NDf319jx45V165dnd5DmTJl1Lhx42zHp0+fni1Uaeb06dM5rgTbrVs3m8fI6bXOihUrdPr0abt6MQxD33//fbbjTZs21U033ZTnXs6fP5+n0Oz06dOzHQsLC7PpiyoAAAAAnOjMdvOabdOk4xuc3wsA73B8gywJJ+x6iCXhBNcRAAAAAPBApLfgEfz8/DRnzhy7AwQXL17Unj17tH37dh09etSuVa4CAwM1b948tW7d2t52PV6pUqW0YsUKlStn3zd7T58+rV27dikmJkZnzpyx67HlypXTihUrVKoUW5QBcK6mTZuqTZs22Y5/8cUXbugGOVm5cqVGjRqljIyMG477+fnpnXfesfnLII7w0EMPZTt28OBB/fDDD3aNM2HChGzPJygoSPfee6/NY9x3330KDAy84Vh6eromTJhgVy8//PCDDh06lO14Ts81N02bNlW1atWyHZ84caLS0tJsHufQoUM5/ix79eqlsLAwm8cBAAAA4GDHN8hy8BfTMouMa9tGE+oCcHxDnraRl8R1BAAAAAA8EMFQeIzg4GAtXLhQffr0cfpcUVFRWrRokUtWK3OXSpUqafXq1br11ludPtett96q1atXq1KlSk6fCwAk6d///ne21YkTExPd1A3+bs2aNRoxYoTS09NvOO7n56e3335bPXr0cGk/nTp1yjEAOXbsWB09etSmMZYsWaIFCxZkO37PPfeoRIkSNvdSqlQp9e7dO9vxBQsW2LxS5+HDhzV27Nhsx6tVq6YOHTrY3IvFYtGTTz6Z7fjRo0dzHD8nKSkpevbZZ7P9tw4ODtagQYNs7gUAAACAg+Uh3EWoCyjg8hEKvY7rCAAAAAB4FoKh8ChhYWGaPXu23nnnHQUFBTlljgYNGmjjxo3q1KmTU8b3JJUrV9aGDRv04IMPOm2OBx54QBs2bFDlypWdNgcA/FONGjVcuuokbLN161YNHTo0W1BQkvr06aNKlSopOjo633+uXLlic09+fn4aPXp0tuOJiYkaOHCg9uzZY/XxP/30k55//vlsxwsXLqyhQ4fa3Md1I0aMUOHChbMdf+6557Ro0SKrj42NjdXAgQNzDEGPHj06W1jaTNeuXdWkSZNsx7///nuNHTs22wqpf3fx4kU9/vjjiomJyXbu0UcfVZkyZezqBQAAAICDsOIfHCn5grs7gCtcOSvFznPMWLHzro0HAAAAAHC7AHc3AOTkhRdeUK9evTRs2DD98ov5lke2KFKkiF577TUNHTpU/v7+DhnTG0REROj7779X//79NWLECO3du9ch41avXl0TJ05U586dHTIeANhrxIgR+vnnn+3a9hrOtX79eqWmpuZ4btasWZo1a5ZD5vn666/VrFkzm+tvu+029e/fX19//fUNx0+dOqU+ffqoV69e6t69u2rUqKGwsDDFx8crOjpas2bN0tq1a3Mc84033lCRIkXs7j0qKkpvvfVWtlBpWlqannnmGS1cuFD333+/6tWrp6ioKCUlJWnPnj366aefNH/+/BxDt/3799dtt91mdy+S9M4776hXr15KSEi44fhXX32ltWvXqn///mrevLlKlSqljIwMHT16VCtWrNA333yjy5cvZxuvXr16euKJJ/LUCwAAAIB8ctCKf4YklW/ukJbgwc5sN6/ZNk2q1Zu/D74uotS1/875vH5IujZORKn8jwMAAAAAyDeCofBY1atX17Jly7RlyxZNmDBB8+fPV1JSkt3j1K5dW48//rgGDhyoiIgIJ3TqHTp37qzY2FgtXLhQH3/8sX7//XdlZmbaNYa/v7/atGmjYcOGqUePHnavTAYAjlSmTBn17dtXX331lbtbgRd45plndOTIEf3+++83HE9PT7c7tDpixAi1a9cuz7106NBBI0eO1Icffpjt3OrVq7V69Wqbx2rbtq2eeeaZPPdSrlw5TZw4UY8//ni2UO+BAwf08ssv2zxW+fLlNXHiRAUGBua5HwAAAAB55OgV/6KqEO7yZcc3yHLQfEEGiwyJsHDBUL65DMlquDwtpKSCrp7L9bxR617+ngAAAACAByEYCo/XuHFjfffdd0pNTdXvv/+u1atXKyYmRnv27NGFCxd05coVpaWlKSIiQoUKFVKFChVUu3ZtNWjQQF26dHHbFueGYbhlXmv8/PzUs2dP9ezZUxcvXtSyZcu0ceNGxcTE6MCBA7p8+fJf29MWKlRIhQsXVtWqVVWrVi3ddttt6ty5s6Kiotz8LADgf5544gnNmzcvx4XhX8gAAJfvSURBVK21gb8LDAzUxx9/rNGjR+unn37K0xgBAQF67rnn9OCDD+a7n8cff1whISF677337P6ixnU9evTQm2++me8g5m233aapU6fq6aef1sWLF/M0Rq1atTRp0iSVKsUHxwAAAIBbsOIfbJWHlWVZSbaAsBIOjS/dXklF6yo8foeKnl6R7TyhUAAAAADwPARD4TWCg4PVqVMnderUyd2t+ISoqCg98MADeuCBB9zdCgDkWZEiRfToo4/muPIi8E9BQUEaN26cWrVqpfHjx+v8+fM2P7Z27dp69dVXVadOHWVkZDikn/79+6t+/foaM2aMYmJibH5ciRIl9Oyzz6pHjx4O6UOSmjVrpvnz52vs2LFaunSpzV9wCQ4O1qBBg/TEE08oODjYYf0AAAAAyAMbVvwzQ7jLx+UhFHod4dACIofryPVQqCQlFa2rQoUKKXDf/L/Oc90AAAAAAM9kMTxxWUMAcKMNGzaoRYsWNxz78ssvVbduXafP7efn99f/DQkJcfp8BZFhGNlCXQEBAbJYLG7qCIA7pKWlacmSJVq2bJm2bt2qhISEbDU33XSTmjdvru7du//1e8FZ15D169dr4cKF2rBhg86ePZvtfGRkpBo1aqTOnTura9euCgoKytd81hw8eFBz587V2rVrdfDgQWVlZd1wPigoSHXq1NEdd9yhXr16uXU18atXr/7V3z/7BDxNampqtkB6iRIlCFUDsAnXEAB2yWP4j3CXj8tHKPTv+HtSQBzfIMXOU0b1u3Um8MZd2UqUKKHgc39KsfOurTDM3wcAueB9DID84BoCwFPt2LFDgwYNuuHY+vXr1by55703YsVQAAAAFDhBQUHq2bOnevbsKUk6d+6cLl68qLS0NIWGhqpUqVIqVKiQy/pp0aLFX+HThIQEnTt3TikpKQoKClJUVJRKlizpsl5uvvlmPf/883r++eeVmpqqU6dOKSkpSf7+/ipUqJBKly4tf39/l/UDAAAAwE7lm8s48YcsCSdsfogRWY5wly+7cvZaiM8RYudJUVWkiFKOGQ+eqXxzKaqKMgOLSDntuPL/5/l7AAAAAACei2AoAAAACrySJUu6NHxpTWRkpCIjI93dhqRrW8VXrlzZvBAAAACA5zi+wa5QqCRZEk7IOL6BcKiviih1bWVHB6wYqlq9CQMWFBGlpNRU6+cBAAAAAB7Lz90NAAAAAAAAAAAAB8jHduGW2LnXto+Gbyrf/No28PnANvIAAAAAAHgPgqEAAAAAAAAAAHi7fIRCryMc6uPyEQ4lFAoAAAAAgHchGAoAAAAAAAAAgDe7claKneeYsWLnXRsPvql8cxmR5ex6iBFZjlAoAAAAAABehmAoAAAAAAAAAADeLKKUVKu3Y8aq1fvaePBNxzfIknDCrodYEk6wkiwAAAAAAF6GYCgAAAAAAAAAAN7Ohm3C00JKWj3PduE+7vgGWWLn5umhlti5hEMBAAAAAPAiBEMBAAAAAAAAAPAFVsKh8aXb6+zNDym+dPsczxMK9XH5CIVeRzgUAAAAAADvQTAUAAAAAAAAAABfkUM4NL50eyUVrStJSipaV+nVe95wnlCoj7tyVoqd55ixYuddGw8AAAAAAHg0gqEAAAAAAAAAAPiS/w+HGrIovXrPv0Kh12WWafrXeUKhBUBEKalWb8eMVav3tfEAAAAAAIBHC3B3AwAAAAAAAAAAwMHKN5eiqigzsIh0/nyu5wn5FRDlm8uQrG4nb0SWkyXhRO7nCREDAAAAAOA1WDEUAAAAAAAAAABfZBb6JBRasPz/SrI5MWrdKzUfaf08oVAAAAAAALwGwVAAAAAAAAAAAICCIIdw6A2hT7PzAAAAAADAK7CVPAAAAAAAAAAAQEHx/9vKK3aeVKt39tCn2XkAAAAAAODxCIYCAAAAAAAAAAAUJOWbS1FVpIhSeTsPAAAAAAA8GlvJAwAAAAAAAAAAFDRmoU9CoQAAAAAAeC2CoQAAAAAAAAAAAAAAAAAAAD6CYCgAAAAAAAAAAAAAAAAAAICPIBgKAAAAAAAAAAAAAAAAAADgIwiGAgAAAAAAAAAAAAAAAAAA+AiCoQAAAAAAAAAAAAAAAAAAAD6CYCgAAAAAAAAAAAAAAAAAAICPIBgKAB7IMAx3twAAgMfj9yUAAAAAAAAAAAAAZEcwFAA8kGEYhF0AALCC35UAAAAAAAAAAAAAkDOCoQDgQf4ecMnMzHRjJwAAeLa//54kIAoAAAAAAAAAAAAA/0MwFAA8yN+DLRkZGW7sBAAAz/b335MEQwEAAAAAAAAAAADgfwiGAoCHysrKYtVQAABykJmZqaysLHe3AQAAAAAAAAAAAAAeiWAoAHiYv696lpqaSjgUAIC/yczMVGpq6l//m9VCAQAAAAAAAAAAAOBGAe5uAABwo+sBF4vFIulaONTPz08BAQHy9/f/6zgAAAWFYRjKzMxURkbGDSuFGoZBMBQAAAAAAAAAAAAA/oFgKAB4oH+GQ7OyspSWlvbXMcKh+fPP7YdZlRWAPbiGuFZu4U9CoQAAAAAAAAAAAACQM4KhAOCh/hkO/ftxgjD588+f3z9DXgBgDdcQ9+N3IQAAAAAAAAAAAADkjmAoAHiwvwdfWCkUAFCQEQYFAAAAAAAAAAAAANsQDAUAL0EgxjGysrKUkZFxw7GAgAD5+fm5qSMA3oRrCAAAAAAAAAAAAADA0/EJNgAAAAAAAAAAAAAAAAAAgI9gxVAAQIFiGIbS09NvOObv7++mbgB4G64hAAAAAAAAAAAAAABPRzAUAFCgZGRk6OLFizccK1GiBMEuADbhGgIAAAAAAAAAAAAA8HRsJQ8AAAAAAAAAAAAAAAAAAOAjCIYCAAAAAAAAAAAAAAAAAAD4CIKhAAAAAAAAAAAAAAAAAAAAPoJgKAAAAAAAAAAAAAAAAAAAgI8gGAoAAAAAAAAAAAAAAAAAAOAjCIYCAAAAAAAAAAAAAAAAAAD4CIKhAAAAAAAAAAAAAAAAAAAAPoJgKAAAAAAAAAAAAAAAAAAAgI8gGAoAAAAAAAAAAAAAAAAAAOAjCIYCAAAAAAAAAAAAAAAAAAD4CIKhAAAAAAAAAAAAAAAAAAAAPoJgKAAAAAAAAAAAAAAAAAAAgI8gGAoAAAAAAAAAAAAAAAAAAOAjCIYCAAAAAAAAAAAAAAAAAAD4CIKhAAAAAAAAAAAAAAAAAAAAPoJgKAAAAAAAAAAAAAAAAAAAgI8gGAoAAAAAAAAAAAAAAAAAAOAjCIYCAAAAAAAAAAAAAAAAAAD4CIKhAAAAAAAAAAAAAAAAAAAAPoJgKAAAAAAAAAAAAAAAAAAAgI8gGAoAAAAAAAAAAAAAAAAAAOAjAtzdAAB4mqSkpGzHDhw44IZO4Azp6em6ePHiDcfOnj2rwMBAN3UEwJtwDQGQV1w/AOQH1xAA+cE1BEBecf0AkB9cQwDkB9cQAJ4qp/xQTjkjT0AwFAD+4dChQ9mOvf32227oBAAAAAAAAAAAAAAAAICnyiln5AnYSh4AAAAAAAAAAAAAAAAAAMBHEAwFAAAAAAAAAAAAAAAAAADwEQRDAQAAAAAAAAAAAAAAAAAAfITFMAzD3U0AgCc5deqUFi1adMOxKlWqKDw83E0dwZF27typxx9//IZjU6ZMUZ06ddzUEQBvwjUEQF5x/QCQH1xDAOQH1xAAecX1A0B+cA0BkB9cQwB4qqSkJB06dOiGY3fddZfKlCnjpo5yF+DuBgDA05QpU0aPPfaYu9uAC9WpU0fNmzd3dxsAvBTXEAB5xfUDQH5wDQGQH1xDAOQV1w8A+cE1BEB+cA0BAPuwlTwAAAAAAAAAAAAAAAAAAICPIBgKAAAAAAAAAAAAAAAAAADgIwiGAgAAAAAAAAAAAAAAAAAA+AiCoQAAAAAAAAAAAAAAAAAAAD6CYCgAAAAAAAAAAAAAAAAAAICPIBgKAAAAAAAAAAAAAAAAAADgIwiGAgAAAAAAAAAAAAAAAAAA+AiCoQAAAAAAAAAAAAAAAAAAAD6CYCgAAAAAAAAAAAAAAAAAAICPIBgKAAAAAAAAAAAAAAAAAADgIwiGAgAAAAAAAAAAAAAAAAAA+AiCoQAAAAAAAAAAAAAAAAAAAD6CYCgAAAAAAAAAAAAAAAAAAICPIBgKAAAAAAAAAAAAAAAAAADgIwiGAgAAAAAAAAAAAAAAAAAA+AiLYRiGu5sAAAAAAAAAAAAAAAAAAABA/rFiKAAAAAAAAAAAAAAAAAAAgI8gGAoAAAAAAAAAAAAAAAAAAOAjCIYCAAAAAAAAAAAAAAAAAAD4CIKhAAAAAAAAAAAAAAAAAAAAPoJgKAAAAAAAAAAAAAAAAAAAgI8gGAoAAAAAAAAAAAAAAAAAAOAjCIYCAAAAAAAAAAAAAAAAAAD4CIKhAAAAAAAAAAAAAAAAAAAAPoJgKAAAAAAAAAAAAAAAAAAAgI8gGAoAAAAAAAAAAAAAAAAAAOAjCIYCAAAAAAAAAAAAAAAAAAD4CIKhAAAAAAAAAAAAAAAAAAAAPoJgKAAAAAAAAAAAAAAAAAAAgI8gGAoAAAAAAAAAAAAAAAAAAOAjCIYCAAAAAAAAAAAAAAAAAAD4CIKhAAAAAAAAAAAAAAAAAAAAPoJgKAAAAAAAAAAAAAAAAAAAgI8gGAoAAAAAAAAAAAAAAAAAAOAjCIYCAAAAAAAAAAAAAAAAAAD4CIKhAAAAAAAAAAAAAAAAAAAAPiLA3Q0AAOBscXFxWrdunWJiYrRnzx7Fx8crMTFRaWlpioiIUGRkpCpUqKBatWqpQYMGatSokSwWi7vbBgAAAAAAsMvhw4cVHR2t2NhYHT9+XGfOnFFCQoKuXr2qrKwsBQcHKywsTKVKlVLp0qVVvXp13XrrrapXr56CgoLc3T6AAmrXrl3asmWLYmNjdfjwYSUkJCgxMVH+/v4qVKiQoqKiVL16ddWqVUstWrRQ2bJl3d0yAAAAAHg8gqEAAJ+UmJioadOmaebMmdq4caOysrJsfmzJkiXVtWtXPfHEE2rWrJkTuwTgaU6dOqUtW7Zo586d2rt3rw4dOqQzZ84oLi5OKSkpyszMVEhIiEJDQ1WyZEmVKVNG1apVU926ddW0aVM1aNCAYDkAAHC4zMxMbdmyRWvXrtWePXu0d+9enThxQomJibpy5YoyMjIUERGhiIgIFSlSRJUrV1bVqlVVrVo1NWzYUA0aNCDwBfiozMxMrVixQrNmzdLy5ct1/PjxPI0TFhamli1bqnfv3urTp4+KFi3q4E4B4EaxsbH673//qwULFth97apfv77uvfdePfbYYypRooSTOgTgSTIyMhQbG6s///xTsbGx2rdv3w1fgklJSZGfn59CQ0NVqFAhlS5dWuXKlVOtWrVUr149tW7dWqVLl3b30wAAAHApi2EYhrubAADAUZKTk/X222/r448/VkJCQr7Ha968ucaNG6eWLVs6oDsAnubcuXNasWKFfv3113x9iHpdsWLF1LVrVz3yyCO644475Ofn56BOAfiqSZMm6fz58zbV9uzZU/Xr13duQwA8RlZWln799Vd9+eWXWrZsmS5dupTnsYKDg9WoUSPdfvvt6t69u2677TZepwBe7urVq5oyZYo+/PBDHT161KFjBwcH65FHHtHzzz+vm2++2aFjA7BPSkqKtm3bpi1btmjLli3avHmz9u3bZ/oleE/+6C8mJkbPPvusfv7553yPFRISooEDB+qNN95QsWLFHNAd4Du8/fphGIZ27tz5133b1atXKzk5OV9j1q5dW3369NEjjzyiypUrO6hTAAAAz0UwFADgM3755Rc99thjDv9AxGKxaNCgQZowYYIiIiIcOjYA19uzZ49mzpypBQsWaPv27U672VmtWjW9+OKL6tevnwICWKgfQHbz5s3Tvffea3P9tGnTNGDAAOc1BMAjZGZm6osvvtA777yjI0eOOGWO4sWLa+DAgXrvvfecMj4A51q0aJGGDx+uw4cPO3WeoKAgjRo1Sq+++qqCg4OdOhcAKS0tTTt27NDmzZv/CnLFxsYqIyPD7rE88aO/jIwMvfLKKxo/frzS09MdOnaxYsX00Ucf6aGHHnLouIC38JXrR0ZGhpYvX65Zs2Zp6dKlOnv2rFPmsVgs6tmzp0aPHq1GjRo5ZQ7A23l7uNxRTp48qc8++8zm+tdee815zQBAHhAMBQD4hPfee08vvviiXVvG26tOnTpasGAB3yQFvNDRo0c1a9YszZgxQ9HR0S6du27dupo8ebKaN2/u0nkBeLaLFy+qVq1aOnPmjM2PIRgK+L5ly5bp6aef1p49e5w+V+3atbVr1y6nzwPAcdLT0zVy5EhNmjTJpfPWr19fc+bMUdWqVV06L+DLMjIyFBMT81fQYsuWLdq5c6fS0tIcMr6nffQXFxenPn366LfffnPqPCNGjND7778vf39/p84DuJOvXT+ysrK0Zs0azZw5U3PnzlVcXJzL5rZYLHr00Uc1duxYFS1a1GXzAp7GV8LlztCjRw/99NNPNtf72vMH4P0IhgIAvN6IESM0ceJEl8xVsmRJ/f7777rllltcMh+A/EtISFCRIkXc+obcz89Pr7/+ukaPHi2LxeK2PgB4joEDB+qrr76y6zEEQwHflZKSoueee06ffPKJy+YkGAp4l6SkJPXq1Uu//PKLW+YvUaKEli5dqoYNG7plfsCXbNq0SW3btlVKSorT5vCkj/7Onj2r22+/Xfv27XPJfPfcc4/mzJlDOBQ+yRevHx9//LGGDx/u0jn/qXz58po1axZf7EeB4GvhcmeaMWOG+vbta9djfOn5A/ANfu5uAACA/Bg9erTLQqGSdO7cOXXo0MFpWzoCcLysrCy3vxnPysrSyy+/rPvuu8/h26UB8D7Lly+3OxQKwHedPn1aLVq0cGkoFIB3ycjIcGsoVJLOnz+vjh07au/evW7rAfAVycnJTg11eZL4+Hh17NjRZaFQSfrxxx81YMAAt98LApzBF68fmZmZ7m5Bx48fV5s2bTR79mx3twI41aZNmxQZGan69evr0Ucf1ZQpU7R161aHhUJ9SVxcnEaMGOHuNgAg3wiGAgC81qxZs/T222/bVBseHq5HHnlEs2fP1v79+5WQkKC0tDSdPXtWq1ev1tixY1WnTh2bxjp58qR69eql1NTU/LQPoACaO3euevfu7RE3PAG4R1JSkh577DF3twHAQ+zbt08tWrRQdHS0u1sB4MGeffZZu0KhYWFhuv/++zVx4kRt3LhRR44c+es+yJkzZ7R7927NmzdP//73v1WzZk2bx42Pj9ddd92lpKSkvDwNAAWMYRjq16+fdu7caVN91apV9dprr2nFihU6ffq0UlNTdeXKFR0+fFg//vijnnjiCUVFRdk01nfffadx48blp30ABUx6eroefPBBzZgxw92tAE7ji+FyZxkxYoTOnz/v7jYAIN/YSh4A4JUOHjyohg0bKiEhwWqdxWLRk08+qddff13Fixc3HXfBggUaOXKkDh8+bFo7ZMgQTZo0yeaeAbjHpUuXbP7gQJIiIyN12223qWnTpqpXr54qVaqk8uXLKyIiQsHBwbp06ZLi4uJ05MgR/fbbb1q1apU2bdpkV09Dhw7Vxx9/bO9TAeADhg8fnud//2wlD/iWo0ePqnnz5jp9+rTNj2nSpInatm2rpk2b6uabb1a5cuUUERGhwMBAXb58WZcuXVJ8fLx2796t6OhoRUdHa/Pmzbpy5Uq2sdhKHvAOq1evVtu2bW1a+S4iIkL/+c9/7ApPSdKyZcv0+uuva8OGDTbV834GyJ/ffvtN7dq1c+ocnvDR37hx4/Tcc8+Z1pUsWVLjxo1Tv379ZLFYrNYmJibq3Xff1bvvvquMjAyrtQEBAVq9ejVbQ8On+OL1Y8KECRo5cqTN9VWqVPnr3m2NGjVUuXJllShRQuHh4TIMQ3Fxcbpw4YK2bdum3377Tb/88otd77mCg4O1YsUKtWzZMi9PB/BovngNcYbFixfrrrvuytNjfeH5A/AtBEMBAF6pY8eO+vXXX63WhIaG6vvvv1fPnj3tGvvixYt64IEHbFqNY+3atdwgADycLcHQsmXL6oEHHtBdd92lli1bKjAw0K45tm7dqnfffVdz5861+Y3//Pnzdffdd9s1DwDvtn79erVu3VpZWVl5ejzBUMB3xMfHq2XLltqzZ49pbaFChTRs2DANHjxYVapUsXuutLQ0rVq1SgsXLtTChQt14sQJSQRDAW/RrFkzm76I1rBhQ82aNUtVq1bN0zyZmZl644039MYbb5i+VgkICFBsbKyqVauWp7mAgq4ghDIOHjyo2rVrm+641LhxY82fP19ly5a1a/zVq1erV69eunDhgtW6mjVraseOHQoICLBrfMBT+eL1wywYarFY1Lx5c91///3q2rWr3a910tPTNX36dL377rs2vf+SpAoVKmjXrl0qVKiQXXMBns4XryGOlpCQoNq1a/9178Re3v78AfgetpIHAHidH374wTQUGhQUpPnz59sdCpWkqKgoLViwQO3btzetHTZsWJ7DHQDcKyAgQH369NGKFSt07NgxjR8/Xm3btrU7FCpJjRo10uzZs/XTTz+pWLFiNj3miSeeYAtGoABJTU3Vo48+muvrhgYNGri4IwDuYhiGHnjgAZs+lBw8eLAOHz6st956K0+hUOnae6POnTtr0qRJOnr0qBYsWKDOnTvLz4/bgoCns3V3gjp16mjVqlV5DoVKkr+/v1577TVNnDjRtDYjI4MtmgEXKl++vO655x699dZbWrZsmXr37u3ulkyNHDnSNBRav359LV++3O5QqCTdfvvtWrZsmSIjI63W7d69mxWOUaB54/Xjuptuukkvv/yyDh06pHXr1mn48OF5eq0TGBioAQMGaPv27Ro2bJhNjzl27Jj+85//2D0XAO/33HPP5TkUCgCeiDvAAACvkpWVpRdeeMG07t1331WnTp3yPE9ISIhmz56t8uXLW63btm2bvv/++zzPA8D1ChUqpOeee05Hjx7V7NmzdccddzgsGNGtWzdt27ZNlStXNq09c+aMTR+6AvANb7zxhnbv3p3juUaNGumpp55ycUcA3GX8+PFavny51ZqwsDD98MMP+vzzz23+0okt/Pz81KNHDy1dulQrVqxw2LgAnGPatGmmNYULF9bixYtNw1G2euqppzRkyBDTulmzZiklJcUhcwL4n9KlS6t79+56/fXXtXjxYp07d07Hjh3TDz/8oP/85z/q1KmTIiIi3N2mVWvWrNFPP/1ktaZIkSL68ccfVaRIkTzP06hRI33++eemdWPGjFFiYmKe5wG8hS9cP6RrOxt89913OnbsmMaMGaNKlSo5ZNygoCBNnDhR33zzjSwWi2n91KlTdfToUYfMDXgrbw6X58Xvv/+uqVOn5nguIiKCHRMAeCX2TgAAeJUffvhB+/fvt1pz++236+mnn873XEWLFtXnn3+uzp07W61777339PDDD+d7PgDOFR4erpEjR2rkyJEqWrSo0+YpX768li5dqpYtWyouLs5q7UcffaRnn32WLc0AH7d9+3a99957OZ7z9/fXZ599pu3bt7u4KwDusGPHDo0ePdpqTWRkpJYvX66mTZs6tZcSJUo4dXwA+WMYhpYuXWpaN2rUKNMvtdrrjTfe0PTp03X58uVcaxISErR27Vp17NjRoXMDBUmpUqXUqFEjNW7cWI0aNVKTJk1UunRpd7eVb++++65pzfvvv++QsFefPn304IMPasaMGbnWXLp0SVOnTtWoUaPyPR/gKXzx+lG7dm2NGTNG99xzj03Bzbzq16+fzp8/b3pNSEtL08cff6zx48c7rRfAk5QuXVqNGzf+60+TJk2y3Tfw5YVyUlJS9K9//SvXreDfeOMNzZ8/3/QzagDwNHwCDQDwKmZvwi0WiyZMmOCw+Tp16qRu3bpp8eLFudbs3LlTS5cuVZcuXRw2LwDH8fPz05NPPqlXX31VpUqVcsmc1atX12effaZ77rnHat3Zs2e1bNkydevWzSV9AXC9zMxMDR48WOnp6Tmef/rpp9WgQQOCoUABMWzYsFyvB9K1bQ5//PFHp4dCAXi+ffv26fz581ZrQkJCHPLF2H8qWrSonnzySY0dO9Zq3Zo1awiGAnnQoEEDHTt2zOGhbk+we/duLVmyxGpNw4YNNXDgQIfN+e6772r+/PlWVzGeMGGCRowYwRdz4fV88fpRpkwZffHFF+rfv7/8/f1dMue///1vrV69WgsWLLBaN336dL377rsu6wtwFV8Ml+fXq6++mmvos3Hjxho+fLjmz5/v2qYAwAHYSh4A4DViY2O1ceNGqzVdu3ZVgwYNHDqv2Yo+km3buwFwj8jISH366acuC4Ve17NnT7Vp08a0zuwDEwDebfz48dq6dWuO5ypVqqQxY8a4uCMA7jJnzhytXr3aas0bb7yhO+64w0UdAfBke/bsMa1p3bq1ChUq5JT5u3btalpjS48AsitcuLBPhbr+btq0abmutHXdiy++6NDVAMuXL69+/fpZrTlx4oSWL1/usDkBd/HF68d9992nQYMGuTx8OW7cOAUGBlqtOXPmjP78808XdQQ43/Vw+ZkzZ7R48WK9/vrr6tGjR4EPhW7ZskUffPBBjucCAgL02Wefyc+PaBUA78TVCwDgNaZPn25a44yVMpo3b266Ys9PP/2kxMREh88NwLs9++yzpjW///67CzoB4A779+/Xa6+9luv5//73vwoLC3NdQwDcxjAMvfzyy1ZrmjVrZtNrBwAFw/Hjx01r2rVr57T5mzdvrtDQUKs1R48eddr8ALyPYRhWt3SXpAoVKpjurpIXttwTtuXeMoCCo1q1arr77rtN67h3C1/ii+Hy/EpPT9fgwYOVmZmZ4/mRI0eqfv36rm0KAByIYCgAwGvMnDnT6vkyZco4bXUds2+dp6SksIUAgGzat29vGvrat29frjcdAHgvwzD06KOP6urVqzmef+CBB9SlSxcXdwXAXRYuXKi9e/darRk3bhwrUAD4iy1fPi1btqzT5g8ICDDddYEvyAL4u7Vr1+rEiRNWax588EGnrApYs2ZNNWrUyGrN/Pnzc31/BqBg6t69u2lNbGysCzoB4C5jx47Vjh07cjxXuXJlq1/6BwBvwN1mAIBX2L9/vw4dOmS1pnfv3k77ILVPnz6mWxwtW7bMKXMD8F4hISFq0aKF1Zr09HQdO3bMRR0BcJXJkyfnumV0VFSUPvroIxd3BMCd3n//favn77jjDrVu3dpF3QDwFcWLF3fq+CVKlLB6ni+4Afi7pUuXmtbcd999Tpv//vvvt3o+KSlJa9euddr8ALxP+/btTWsOHjzogk4AuMPu3bv11ltv5Xqe3Z4A+AKCoQAAr/Drr7+a1nTu3Nlp85cqVUr16tWzWrNixQqnzQ/Ae9myis/Fixdd0AkAVzl+/Lief/75XM+PGzdOJUuWdGFHANzpwIEDWrNmjdWaIUOGuKgbAN6iaNGi7m7BVFRUlLtbAOBBzO7flixZUg0aNHDa/J06dTKtseUeM4CC46abbjJdbIT7toBvysrK0uDBg5Wamprj+b59+zr1c2cAcBWCoQAAr7By5Uqr5wMCAtSmTRun9tChQwer58+cOaOYmBin9gDA+5htvyhJycnJLugEgKs88cQTuW6t2qZNGw0aNMjFHQFwpxkzZlg9HxUVpbvvvttF3QDwFrasBhoXF+fUHs6fP2/1fLFixZw6PwDvkZCQoK1bt1qtadeunemOTPlRt25d05WO+WI/gL/z9/c3fc3FfVvAN02cOFEbNmzI8VzRokU1YcIE1zYEAE5CMBQA4BW2bNli9Xzt2rUVERHh1B5uu+020xqzG6AACh7DMExrgoKCXNAJAFf47rvvtGTJkhzPBQcHa+rUqU79MBSA55k5c6bV83feeacCAgJc1A0Ab1GnTh3TmhMnTjht/oyMDJ09e9ZqTc2aNZ02PwDvsm3bNmVmZlqtseXean5YLBY1a9bMas2OHTuUnp7u1D4AeBeze7fctwV8z+HDh/XSSy/len78+PGmXzYBAG9BMBQA4PEuXryoI0eOWK1p2LCh0/to1KiRac22bduc3gcA72LLKj6RkZEu6ASAs50/f15PP/10rudHjx6t6tWru64hAG53/PhxxcbGWq258847XdQNAG9SvXp1lSxZ0mrNb7/95rT5N2zYoJSUFKs1rVq1ctr8ALyLLfdEPeH+bVpamulrMwAFR2ZmpulW8dy3BXzPY489pqSkpBzPtWvXTgMHDnRxRwDgPARDAQAeLzo62rSmbt26Tu+jUqVKpjcBCIYC+KedO3daPW+xWFSxYkUXdQPAmYYNG6YLFy7keK5WrVp6/vnnXdwRAHdbtWqVaU3z5s1d0AkAb9SlSxer59esWaPExESnzL148WKr54OCgnT77bc7ZW4A3seWe6KuuH9ryxzcvwVw3Z49e5SRkWG1plKlSq5pBoBLfPnll/r1119zPBcSEqIpU6a4uCMAcC6CoQAAj7dv3z7TmqpVq7qgE+nmm2+2et6WXgEUHAkJCdqxY4fVmvLlyys0NNRFHQFwloULF2rWrFk5nrNYLJo6dSrbjwEFkFkwtFixYqbvMQAUXEOHDrV6/urVq/rwww8dPm98fLwmT55steb+++9X0aJFHT43AO9kdk+0WLFiKlKkiNP7sOUeMfdvAVy3du1a05oaNWq4oBMArnD69GmNGjUq1/MvvfSSqlWr5sKOAMD5CIYCADze4cOHTWtcFQw1m+fMmTO6evWqS3oB4PmWLFmitLQ0qzUtW7Z0UTcAnOXy5ct68skncz3/+OOP828dKKA2b95s9fwtt9xiOsaePXv0/vvvq2/fvqpXr55KlSql0NBQBQYGqnDhwipfvrxatmyphx9+WB9++KE2btyorKwsRz0FAG7UpEkTtW7d2mrN+++/r+PHjzt03pdeekmXL1/O9bzFYtGIESMcOicA72Z2/9ZT7t1Ktt1rBlAw/Pjjj6Y13M8BfMdTTz2lS5cu5Xju1ltv1XPPPefahgDABQLc3QAAAGZsuVlXvnx5F3QilStXzup5wzB05MgRmz7gBeD7bNl2pH379i7oBIAzPfPMMzp16lSO50qXLq2xY8e6uCMAniA9Pd10RarcVqJISUnRt99+q4kTJyomJibXxyckJCghIUEnTpzQ+vXrNX36dElSyZIl1atXLw0ZMkR16tTJ+5MA4HaTJ09Ww4YNlZqamuP5hIQEdevWTWvXrlVkZGS+5/v000/13//+12rNY489pkaNGuV7LgC+ITk5WWfPnrVa46p7t2FhYYqKitLFixdzrSEYCkCSDh06pOXLl1utCQkJIRgK+Ig5c+bkGgb38/PT1KlTFRgY6OKuAMD5WDEUAODxzFa+iIiIUHh4uEt6uemmm0xrjh075oJOAHi6LVu26LfffrNaExQUpF69ermmIQBOsWrVKn3++ee5np84caIKFy7swo4AeIp9+/YpPT3dak2FChWyHZs1a5aqVaumxx9/3Goo1Jpz585p8uTJqlu3rrp166bdu3fnaRwA7lerVi29/fbbVmt27typdu3a6cCBA3meJzMzU6+//rqGDRtmta5SpUoaN25cnucB4HtOnDhhWmPLPVVHMZuLe7cAJOmDDz4w3WnhrrvuctlnTwCcJz4+3ur7nCeeeELNmzd3YUcA4DoEQwEAHi8uLs7qeVfeWCxdurRpzYULF1zQCQBPN2rUKNOanj17KioqygXdAHCG5ORk/etf/8r1fPfu3XXvvfe6sCMAnsRstVBJKlGixF//f0JCgnr16qUHHnhAJ0+edFgfS5YsUd26dfXSSy8pMzPTYeMCcJ1///vfeuaZZ6zW/Pnnn2rYsKHGjh1rdaW8nCxfvly33367XnvtNasBiZIlS2rp0qUqVKiQXeMD8G1m924lz7p/Gx8f76JOAHiqvXv3aurUqaZ1gwYNckE3AJxt5MiRua5uXqZMGb3zzjsu7ggAXIet5AEAHs/sZl2RIkVc04iNc3FzEcD06dO1evVq07rnn3/eBd0AcJaXXnpJBw8ezPFcRESEJk2a5OKOAHiSU6dOmdYUL15c0rVdEjp27Ki9e/c6pZeMjAy99dZbWrNmjX744QcVK1bMKfMAcJ5x48YpODhYb7/9tgzDyLEmMTFRL774ot588011795drVq1UrNmzVSqVClFRUUpODhYly5dUnx8vGJjY7Vu3Tr9/PPPio2NNZ2/dOnSWrp0qWrUqOHopwbAy9lyL9ST7t+mpqYqKSmJVQCBAmzYsGGmuzvUq1dPd955p4s6AuAsy5Yt0zfffJPr+Y8//liRkZEu7AgAXItgKADAoxmGoUuXLlmtceVKFbbMRTAUKNhOnz6t4cOHm9b17NlTDRs2dEFHAJxh06ZN+uijj3I9/9Zbb6l8+fIu7AiApzlz5oxpTXh4uE6cOKF27drlGjR3pNWrV6tNmzZavny5TbshAPAsb775ptq0aaP+/fvr9OnTudYlJSVp5syZmjlzpkPm7dKli7755psbVjkGgOtsuRfqifdvCYYCBdOUKVO0fPly07rXX3/dBd0AcKYrV67osccey/X83XffrV69ermwIwBwPbaSBwB4tOTkZNPtDl15Y9GWb40lJCS4oBMAnsgwDA0cOND0Q5Hg4GC9//77LuoKgKOlpaVp8ODBuW612rRpUw0dOtTFXQHwNLYEQ7OystSjRw+bQ6FFixbVLbfcovr166t69eqKiIiwu6+YmBjdeeedunLlit2PBeB+HTt21P79+/Xee++pZMmSTp2rZs2amjFjhpYsWUIoFECuEhMTTWu4fwvAE+zdu1fPPPOMaV3Hjh119913u6AjAM70wgsv6NixYzmeK1SokD755BMXdwQArkcwFADg0dLS0kxrgoODXdCJ7XOZbUECwHe98cYbWrZsmWnd6NGjVaVKFRd0BMAZ3n77be3atSvHcwEBAfrss8/k58fbbaCgsyVwMHr0aG3bti3X8wEBAerTp4/mzJmjc+fO6cKFC9q9e7e2bdumvXv3KjExUYcPH9bnn3+udu3a2dzb9u3b9fDDD9tcD8CzhIeH69lnn9WRI0c0b948PfTQQ3kKiuekUKFCeuCBB/Tjjz9q165deuCBB2SxWBwyNgDfxP1bAN4gOTlZ9957r+kX5EJDQwmLAT5g3bp1+vTTT3M9//bbb6tcuXIu7AgA3INPqgAAHs2WG4sBAQEu6MT2uWzpGYDvWbp0qU1bDDVp0kQvvviiCzoC4Ay7du3SO++8k+v5UaNGqW7dui7sCICnunr1qmlNTExMrud69uypffv2afbs2br33ntzXa2vUqVKGjx4sFauXKk//vhDDRs2tKm/BQsW6PPPP7epFoBnOnHihPbv369Dhw4pOTnZIWPWq1dPLVu2VKNGjfiiCwCbcP8WgDf417/+leuXfP9u7Nixql69ugs6AuAsqampGjx4sAzDyPH8bbfdpiFDhri4KwBwD+7sAAA8GjcWAXiD2NhY3X///bluK31deHi4vvnmG5detwA4TmZmpgYPHpzr7/qbb75Zr776qou7AuCpUlNT8/Q4f39/ffzxx/rxxx9VuXJlux7brFkzbdy4UY8//rhN9aNGjVJcXFxe2gTgRps3b1bPnj1Vo0YNvfDCC9qwYYPpexFbrV27VsOGDVOFChXUpUsXrV271iHjAvBd3L8F4Oneeustff/996Z1HTp00LBhw1zQEQBnev3117V3794czwUGBmrq1Kl8CQ5AgcHVDgDg9Vy5pZktbxRy+wYaAN8UFxen7t2727Rd7NSpU3XLLbe4oCsAzjBhwgRt2rQp1/OTJ09WaGioCzsC4MnyEjiwWCyaNm2ahg4dmud5AwICNHnyZI0YMcK0NiEhQW+//Xae5wLgWpcuXdKDDz6opk2basGCBU6//7Bs2TK1bt1a7du31+HDh506FwDfxv1bAO4yb948vfzyy6Z1ZcuW1ffff+/S6xUAx9u2bZvGjRuX6/lnnnlGderUcWFHAOBeBEMBAB4tMDDQtCYjI8MFnVyTnp5uWhMUFOSCTgB4gqSkJN111106dOiQae2QIUPUt29fF3QFwBkOHjyoV155Jdfz/fr1U4cOHVzYEQBP5+/vb/djhgwZon79+jlk/g8++EAtWrQwrZsyZYouX77skDkBOM/atWtVt25dzZw5067H+fv7q3jx4qpevbrq1KmjMmXKKCQkxK4xVq5cqfr162v69Ol2PQ5AwcD9WwCeau3atXr44YdNw+CBgYGaNWuWSpQo4aLOADhDRkaGBg8enOvrjqpVq1q9vwsAvohgKADAo3njjUVbegbg/dLS0tS7d29t3LjRtLZz586aMGGC85sC4DSPPfaYkpOTczxXrFgxffDBBy7uCICnszdwULVqVb333nsOm9/Pz09ff/21wsLCrNYlJyfr66+/dti8ABxvxYoV6tSpk44fP25aa7FY1K1bN02cOFHR0dFKS0vT+fPntXfvXu3YsUMnT55USkqKTp06pVmzZumpp55S0aJFTcdNSEjQww8/rHfffdcRTwmAD+H+LQBPtGPHDnXv3l1Xr161WmexWPT555+rZcuWLuoMgLOMGzdO27Zty/X8lClT7P6SHAB4O4KhAACPZsuHqXnZojGv+MY5AEnKyspSv379tGzZMtPa2267TfPmzeNDB8CLffbZZ1q5cmWu599//30VL17chR0B8Ab2vi945513TEOc9qpataqGDx9uWjdr1iyHzgvAcdasWaMePXooJSXFtHbAgAHavXu3Fi1apGHDhqlevXq5bqlcunRp3Xffffrkk0907NgxffjhhzatkvXCCy/oww8/tPt5APBd3L8F4GkOHDigTp066dKlS6a148eP1yOPPOL8pgA41b59+zRmzJhcz/fv31933HGHCzsCAM9AMBQA4NHCwsJksVis1ly5csVF3UiJiYmmNeHh4S7oBIC7GIahxx57TLNnzzatrVOnjpYsWcJ1AfBiJ0+e1LPPPpvr+fbt26t///4u7AiAt7BnFYoyZcqoZ8+eTunjiSeeyDUYdt0ff/yhCxcuOGV+AHl38eJFPfDAA7muWn5dVFSUFixYoGnTpqlGjRp2zxMeHq6nn35a0dHRat26tWn9qFGj9Ntvv9k9DwDfFBERYVrD/VsArnL8+HF16NBBZ8+eNa196aWX9O9//9sFXQFwJsMwNHjw4FxXCC5evLjef/99F3cFAJ6BYCgAwKP5+/srMjLSao0tN/scxZa5bNmCDYD3GjlypL744gvTumrVqmn58uWKiopyQVcAnGXIkCG6fPlyjudCQkI0efJkF3cEwFvY877g0UcfVUBAgFP6qFixorp27Wq1JisrS2vXrnXK/ADybujQoTp16pTVmmLFimnjxo3q0aNHvucrU6aMVq1apXvuucdqnWEYGjhwoEuDXgA8ly33Pbh/C8AVzp49qw4dOujo0aOmtcOHD9cbb7zhgq4AONukSZOs3tP44IMPVKxYMRd2BACeg2AoAMDjmd2oyy2s4Qy2zMWNRcB3jR49Wh999JFpXYUKFbRixQqVKlXKBV0BcJaZM2dq4cKFuZ5/5ZVXVLVqVRd2BMCb2POhQ/v27Z3YiW3jb9261ak9ALDPpk2b9P3331utCQoK0o8//qhq1ao5bF5/f399++23atiwodW6I0eO6O2333bYvAC8ly33Qj3p/q0tCxEA8D7x8fHq2LGj9u3bZ1o7cOBATZgwwflNAXC6Y8eO6cUXX8z1fMeOHdWvXz8XdgQAnoVgKADA45l9oGrLliCOcubMGdMavnUG+KY333zTpg8+b7rpJv36668qX768C7oC4CwXLlzQ8OHDcz1fp04dPfPMMy7sCIC3sfV9gb+/vxo3buzUXpo1a2Zas2vXLqf2AMA+H374oWnNM888Y9PW7/YKDw/Xd999Jz8/6x8fTJkyxXSbewC+z5bXPJ50/7Zo0aKyWCwu6gaAK1y+fFmdOnXSzp07TWvvu+8+ffbZZ1wHAB/x+OOP57qTQWhoKLs9ASjwCIYCADxe2bJlrZ6/ePGi0tLSXNKLLcFQs34BeJ8PP/xQL7/8smldsWLF9Ouvvzp0xR4A7jFixAidP38+x3N+fn767LPPFBgY6OKuAHiT0qVL21RXu3ZthYWFObWXhg0bmm5Vf/z4caf2AMB2586d09y5c63WFC5c2KlfUqlZs6YeeughqzXx8fGaPn2603oA4B1suRdqyz1VRzGbi3u3gG9JSkpS165dbdoBoXv37vruu+/k7+/vgs4AONs333yjpUuX5nr+1VdfVZUqVVzYEQB4HoKhAACPV7lyZdOaU6dOuaAT2+axpV8A3mPy5Mn697//bVpXuHBh/fLLL6pdu7YLugLgTEuWLLEachgyZIhNq+8BKNhsfV9ga4A0P4KDgxUVFWW1xlXvqQCYW7VqlTIyMqzW9O/f3/TfdX6NHDnStGbJkiVO7QGA5ytSpIiKFClitcZVrzPS09MVFxdntYZ7t4DvSElJUffu3bV+/XrT2g4dOmjOnDl8yRfwEWfPnrX6fqVevXoaNWqUCzsCAM9EMBQA4PEqVapkWnPgwAHnN2LDPFFRUYqMjHRJLwCcb9q0aRoyZIhpXXh4uJYsWaKGDRu6oCsAzjZnzpxcz5UrV05vv/22C7sB4K1sXZXCLEjhKGYBsty2XgPgeqtXrzat6dy5s9P7qF+/vkqUKGG1Zu3atU7vA4DnM7t/66p7t4cOHVJWVpbVGlvuNQPwfKmpqbrnnnu0atUq09pWrVppwYIFCg4OdkFnAFxh6NChio+Pz/Hc9d2ezHZOAYCCgCshAMDjVa1a1bTmwIED6tChg9N7OXjwoNXztvQKwDtMnz5djz76qAzDsFoXEhKihQsXqkWLFi7qDICzWft3n5aWpnbt2jl8zgsXLpjWvP766/rkk0+s1vTt29emVY4BOF+xYsVUpEgRXbp0yWqdpwRDk5OTXdIHAHNbtmyxet7f319t2rRxeh8Wi0Xt2rXT7Nmzc62Ji4vTwYMHdfPNNzu9HwCeq2rVqoqOjs71/KlTp5SSkqLQ0FCn9mF271bi/i3gC9LT03Xvvfdq2bJlprWNGzfW4sWLFRYW5oLOALjK3Llzcz03dOhQNWnSxIXdAIDnIhgKAPB49evXN63ZtWuX0/s4d+6czp8/b7XGll4BeL65c+eqf//+pqtMBAUFad68ebrjjjtc1BkAdzt37pzOnTvnlrmPHDmiI0eOWK1p1aqVa5oBYJN69erp999/d3cbALyM2b2H4sWLKzw83CW92LKy3tmzZwmGAgVc/fr1rQY0DMNQTEyMGjdu7NQ+bLlHzP1bwLtlZGTowQcf1KJFi0xr69atq2XLlrHLG1DA/Prrr055zbF3717TGlvm/f7771W9enVHtAQApgiGAgA8XtmyZVWyZEmrIYw///zT6X1s3brVtKZBgwZO7wOAcy1cuFB9+/ZVZmam1bqAgADNmDFDXbt2dVFnAADA2zRq1Mg0GGq2oqijXLx40ep5VtABPIfZSuJm27s7UvHixU1rbFn5HIBvs+We6J9//un0YKjZ/Vs/Pz/Vq1fPqT0AcJ6srCw98sgjmjdvnmntLbfcouXLl6to0aIu6AyAJ4mNjXXb3LZ8lsyOLQBcyc/dDQAAYIuGDRtaPb99+3alp6c7tYdNmzaZ1jRq1MipPQBwrmXLlum+++4zvZ74+fnp66+/Vq9evVzUGQAA8Ea2bF1mFth0FLN5WEUH8BxXrlyxer5w4cIu6kQqUqSIac3ly5ed3wgAj2bLPdHNmzc7vQ+z+7c1atRw2YrLABzLMAw9+uijmjFjhmltlSpV9Ouvv6pkyZIu6AwAAMBzEQwFAHiFNm3aWD2fnJysP/74w6k9rFy50ur5QoUKmQZYAXiuVatW6Z577lFqaqrVOovFoqlTp6pv374u6gwAAHir22+/3bTm9OnTTu8jNTXVNBhavnx5p/cBwDYhISFWz7tqpWFb5woODnZ+IwA8WqlSpVSjRg2rNWb3VvPr8OHDOnLkiNUas3vMADzXkCFDNG3aNNO68uXLa+XKlSpbtqwLugIAAPBsBEMBAF6hY8eOpjXLly932vxXrlwxDZ62bdtWAQEBTusBgPOsW7dO3bt3V0pKimntxIkTNXjwYBd0BQAAvF2ZMmVUp04dqzWxsbFKSkpyah9bt25VRkaG1ZqKFSs6tQcAtjNbzS4uLs5FnUjnz583rWH1PQCS+f3bQ4cO6dChQ06b35Z7w7bcYwbgeUaOHKnJkyeb1pUuXVorVqzgvQ0AAMD/IxgKAPAKDRo0UPHixa3WzJs3z2nzL1iwQGlpaVZruLEIeKfNmzera9euNgUyxo0bp6FDh7qgKwAA4Cs6d+5s9XxmZqbTt1a1ZXeF+vXrO7UHALYzW+EqLi7OdLt5Rzl8+LBpTenSpV3QCQBP16lTJ9OauXPnOm3+OXPmWD3v7++vdu3aOW1+AM7x4osvasKECaZ1JUqU0K+//qpq1ao5vykAAAAvQTAUAOAV/Pz81Lt3b6s1sbGxio6Odsr8M2bMsHrelv4AeJ7t27erc+fOSkhIMK0dM2aMnnnmGRd0BcDdvvrqKxmG4dI/tmyHNm3aNNNxbPmwBIBr3XfffaY1v/76q1N7sGX8pk2bOrUHALarVKmS1fOZmZn6/fffnd5HVlaWTVs/V65c2em9APB8nTp1UuHCha3WfP/9906Z+8yZM1q1apXVmo4dOyoqKsop8wNwjjFjxmjs2LGmdVFRUVq+fLlq1arlgq4AAAC8B8FQAIDXeOihh0xrPv74Y4fPe+DAAf38889Wa9q1a6cyZco4fG4AzhMbG6uOHTvq4sWLprUvvviiXn75ZRd0BQAAfE2TJk1Us2ZNqzVffvml0tPTnTL/4cOHtWzZMqs1ERERat68uVPmB2A/W1bw/eWXX5zex5YtWxQfH2+1pkKFCipSpIjTewHg+YKDg02/OL99+3atWbPG4XN/+umnyszMtFpjy71lAJ5j3LhxevXVV03rIiMjtWzZMtWrV88FXQHwFK7+Ur9hGGrTpo1D+mLHFgCuRDAUAOA1WrVqpSpVqlitmT59uk6ePOnQecePH6+srCyrNY888ohD5wTgXAcOHFCHDh10/vx509qnn35ab7/9tgu6AgAAvmrgwIFWz58+fVo//PCDU+b+73//a/p+pkuXLgoJCXHK/ADs16JFC9Oab775RpcuXXJqH++//75pDaFyAH/Xv39/05p3333XoXMmJibqv//9r9WayMhI9ezZ06HzAnCeSZMm6bnnnjOtCw8P15IlS9SkSRMXdAUAAOB9CIYCALyGxWLRyJEjrdakpqbqhRdecNicMTEx+vzzz63WlClTRg888IDD5gTgXEePHlX79u11+vRp09onnnhCH374oQu6AgAAvuyxxx4z3Vr1P//5j5KSkhw67969e/XJJ5+Y1tkS4gDgOq1bt1ahQoWs1ly6dEnjx493Wg/bt2/XnDlzTOvuvPNOp/UAwPvcfvvtatSokdWaxYsXa+XKlQ6b86233lJcXJzVmscee0wREREOmxOA83z55ZcaNmyYaV1oaKh++ukntWzZ0gVdAQAAeCeCoQAArzJo0CAVK1bMas306dO1ZMmSfM+Vnp6uwYMHm25DNGLECAUFBeV7PgDOd+rUKbVv317Hjh0zrR0wYIA+/fRTF3QFAAB8XeHChTVkyBCrNYcOHdIzzzzjsDkzMzPVv39/paSkWK27+eab1bVrV4fNCyD/QkJC1KNHD9O68ePHa926dQ6fPyEhQQ899JAMw7BaFxQUpLvvvtvh8wPwbs8++6xpzeOPP67ExMR8z7V161bTL/QGBgbq6aefzvdcAJxvxowZ+te//mX6GiQ4OFg//vij2rVr56LOAAAAvBPBUACAVwkLC9NLL71ktcYwDPXv318HDhzI11wjR47Uxo0brdaULVtWTz31VL7mAeAa58+fV4cOHXTw4EHT2gcffFBffPGFLBaLCzoDAAAFwTPPPGP6JbfJkyfr66+/dsh8Tz/9tOn7GUl67bXX5OfHLULA0wwdOtS0JjU1VT179rTpPY6t0tLSdP/99ysmJsa09uGHH1aRIkUcNjcA39CnTx81aNDAas2BAwc0cOBAZWVl5Xmes2fP6r777lNaWprVuiFDhqhs2bJ5ngeAa8yfP1+PPPKI6XUhMDBQs2fPVufOnV3UGQAAgPfiri8AwOsMHTpUNWvWtFoTFxen9u3ba+/evXaPn5WVpWeffVaTJk0yrX3vvfcUHh5u9xwAXOvSpUvq1KmTdu/ebVrbq1cvffPNNwQkAACAQxUtWlTvvfeead3gwYP18ccf53me9PR0Pf744zZtId+kSRM99NBDeZ4LgPPcdtttNq2CFRcXp2bNmmnx4sX5nvPo0aNq3bq1li5dalobEBCg5557Lt9zAvA9fn5+Nr2WmTdvngYMGGAa7MzJqVOn1LFjRx06dMhqXYkSJfT666/bPT4A11q2bJnuv/9+ZWRkWK3z9/fX9OnTbVpZHQAAAARDAQBeKCAgQFOmTJG/v7/VumPHjqlJkyaaNm2a6dYj1x0+fFhdu3bV+PHjTWs7deqkvn372jQuAPe5cuWK7rzzTkVHR5vWduvWTTNnzlRAQIDzGwMAAAXOwIED1aFDB6s1mZmZGj58uHr27KnDhw/bNf7GjRvVrFkzTZ061bQ2NDRUX3/9NSukAx7s448/tum9yYULF9S9e3c9+uij2r9/v93zJCYmavz48WrQoIE2bdpk02Oefvpp1ahRw+65ABQMLVu21L/+9S/Tum+//VatW7fWrl27bB57/vz5atCggXbu3GlaO2HCBBUuXNjmsQG43urVq3XPPfeYhsT9/Pz01VdfqU+fPi7qDAAAwPtZDFuTMgAAeJgxY8bo1Vdftam2bt26euyxx3TXXXepYsWKN5xLTk7WH3/8oe+//17fffedUlNTTccrXbq0oqOjVbJkyTz1DsB13nrrLb300ks21d56660KDg52ckfZde/e3ebrGQDf9NVXX2ngwIFWa6ZNm6YBAwa4piEATnP+/Hk1bNhQJ06cMK0NCAjQPffco/vvv1+33367SpQoka3m6NGjWrlypb799lutWrXK5j4+//xzDR482K7eAbje2LFj9eKLL9pc7+fnp27duqlz5866/fbbdeutt+YYAD99+rRWr16t3377TTNmzNDly5dtnqNOnTr6448/FBYWZvNjAGTXuHHjPD3uyJEjunDhgtWaRo0a5Wns1157TXfddVeeHvtPycnJatq0qWJiYkxr/f391adPH/Xr10+tWrVSZGTkDedPnjypZcuW6fPPP9eGDRtsmn/QoEH64osv8tQ74Ol86fpRrVo1HThwwLQuPDxct9xyS15ay7cpU6bk+ecC+JIBAwbo66+/tlrjy/Gjtm3b6vfff7da48vPH4B3YikkAIDXeumll7Rlyxb99NNPprU7duzQ0KFDNXToUEVFRalUqVIKDg7WpUuXdOLECWVmZto8b0hIiGbNmkUoFPAS6enpNtfas0KFI916661umRcAALheiRIlNG/ePLVv315XrlyxWpuRkaE5c+Zozpw5kqRixYr99V4mOTlZp06dUmJiot09/Oc//yEUCniJ559/Xtu2bdPs2bNtqs/KytJPP/30172SgIAARUVFqWjRogoKClJ8fLzi4+OVkpKSp35KlCihH3/8kVAo4ABbt271uLHj4uIc1kNYWJjmzp2rVq1amQbRMjMzNXPmTM2cOVMWi0Vly5ZVVFSUMjIydP78ebv7atKkiU3b2QPeypeuH7beu01KSnLq87YmL++5AE+Wn3C5s8Z25JdTAAD/QzAUAOC1/Pz8NGfOHHXr1k0rVqyw+XEXL17UxYsX8zRnYGCg5s2bp9atW+fp8QAAAADQtGlTLV26VF26dDENh/7dhQsXTIMVZp5//nm99dZb+RoDgOtYLBZ99913yszM1Lx58+x+/PVQ1fnz5/PdS8mSJbVixQrdfPPN+R4LQMFwyy23aNmyZWrfvr3NKxMbhqETJ07YtLp6TurUqaOlS5cSYAcAIBe+FC4HAFjn5+4GAADIj+DgYC1cuFB9+vRx+lxRUVFatGiRunbt6vS5AAAAAPi2li1batWqVapQoYJL5gsKCtInn3yisWPHumQ+AI4TGBio2bNn64UXXshxW3hXaNSokTZt2sRuBwDs1qhRI61atUrly5d3+lxt2rTRypUrVbRoUafPBQAAAACejmAoAMDrhYWFafbs2XrnnXcUFBTklDkaNGigjRs3qlOnTk4ZHwAAAEDB07hxY/3555/q3r27U+epXbu21q9fr6eeesqp8wBwHj8/P73zzjtatmyZqlat6rJ5g4KCNHr0aK1du1YVK1Z02bwAfEuDBg20ZcsWdejQwSnj+/n5acSIEVq+fLmKFy/ulDkAAAAAwNsQDAUA+IwXXnhBO3fudGh4s0iRIpowYYI2b96satWqOWxcAAAAAJCkYsWKaeHChfrpp59Uo0YNh45dunRpTZw4UdHR0WrUqJFDxwbgHh07dtSuXbs0ceJEp66+FxgYqEGDBikmJkZvvvmmQkJCnDYXgIKhZMmSWr58ub777juVKVPGYeM2btxYGzZs0IQJExQYGOiwcQEAAADA2xEMBQD4lOrVq2vZsmXavHmzHnroIYWHh+dpnNq1a2vixIk6fvy4RowYIX9/fwd3CgAAAAD/c9dddyk2NlaLFi1S165d87wbQkBAgDp06KBvvvlGR44c0bBhwxQQEODgbgG4U3BwsIYNG6ZDhw5p0aJF6tu3r0O2TQ4ICFCLFi00YcIEHT9+XF988YVLVycFUDA89NBDOnz4sL7++ms1bdpUFovF7jGCgoLUo0cPrVixQps3b1bTpk2d0CkAAAAAeDeLYRiGu5sAAMBZUlNT9fvvv2v16tWKiYnRnj17dOHCBV25ckVpaWmKiIhQoUKFVKFCBdWuXVsNGjRQly5dVLlyZXe3DgAACpDo6GjNnz/fak3Pnj1Vv359l/QDwP2uXLmiVatWaf369dq9e7f27dv313uZq1evKiQkROHh4SpdurQqVqyoW2+9Vc2aNVPr1q0dEhAD4F2ysrIUHR2tzZs3a9euXTpw4IBOnTqls2fPKikpSVevXlVWVpaCg4MVEhKiYsWK/XX9qF27turVq6dWrVqpUKFC7n4qAAqYM2fO6Oeff9aWLVsUGxurw4cPKyEhQYmJifL391ehQoUUFRWlatWqqXbt2mrRooU6dOigiIgId7cOAIBXysuXMpxt2rRpGjBggLvbsKpt27b6/fffrdYQvwLgaQiGAgAAAAAAAAAAAAAAAEAOvvrqKx05csRqzWuvveaSXgDAVgRDAQAAAAAAAAAAAAAAAAAAfISfuxsAAAAAAAAAAAAAAAAAAACAYxAMBQAAAAAAAAAAAAAAAAAA8BEEQwEAAAAAAAAAAAAAAAAAAHwEwVAAAAAAAAAAAAAAAAAAAAAfQTAUAAAAAAAAAAAAAAAAAADARxAMBQAAAAAAAAAAAAAAAAAA8BEEQwEAAAAAAAAAAAAAAAAAAHwEwVAAAAAAAAAAAAAAAAAAAAAfQTAUAAAAAAAAAAAAAAAAAADARxAMBQAAAAAAAAAAAAAAAAAA8BEEQwEAAAAAAAAAAAAAAAAAAHwEwVAAAAAAAAAAAAAAAAAAAAAfQTAUAAAAAAAAAAAAAAAAAADARxAMBQAAAAAAAAAAAAAAAAAA8BEEQwEAAAAAAAAAAAAAAAAAAHwEwVAAAAAAAAAAAAAAAAAAAAAfQTAUAAAAAAAAAAAAAAAAAADARxAMBQAAAAAAAAAAAAAAAAAA8BEEQwEAAAAAAAAAAAAAAAAAAHwEwVAAAAAAAAAAAAAAAAAAAAAfQTAUAAAAAAAAAAAAAAAAAADARxAMBQAAAAAAAAAAAAAAAAAA8BEEQwEAAAAAAAAAAAAAAAAAAHwEwVAAAAAAAAAAAAAAAAAAAAAfQTAUAAAAAAAAAAAAAAAAAADARxAMBQAAAAAAAAAAAAAAAAAA8BEEQwEAAAAAAAAAAAAAAAAAAHwEwVAAAAAAAAAAAAAAAAAAAAAfQTAUAAAAAAAAAAAAAAAAAADARxAMBQAAAAAAAAAAAAAAAAAA8BEEQwEAAAAAAAAAAAAAAAAAAHwEwVAAAAAAAAAAAAAAAAAAAAAfQTAUAAAAAAAAAAAAAAAAAADARxAMBQAAAAAAAAAAAAAAAAAA8BEEQwEAAAAAAAAAAAAAAAAAAHwEwVAAAAAAAAAAAAAAAAAAAAAfQTAUAAAAAAAAAAAAAAAAAADARxAMBQAAAAAAAAAAAAAAAAAA8BEEQwEAAAAAgE84cuSILBZLrn8qVark7hZRgH311VdW/34OGDDA3S3CBr/99pvV/45t27Z1d4uA17L2b8tisbi7PQAAAAAAAK9CMBQAAAAAAAAAAAAAAAAAAMBHBLi7AQAAAAAA4LkOHz6sXbt2KTY2VidPntSZM2d08eJFXb16VWlpaQoJCVF4ePhff6KiolSpUiVVrlz5r/9bqFAhdz8NAAAAwOcYhqF9+/YpJiZGu3fv1qlTp3TmzBldvnxZV69eVXp6ukJDQ294vV68ePG/Xqdff80eGhrq7qcCAAAAAHAwgqEAAAAAAOAvycnJ+umnn7RgwQL99ttvOn36dL7HrFChgho3bqwmTZqocePGaty4sYoUKZL/ZgEA8FGnT59W9+7d3d2GU3Tv3l2vvvqqu9sAvNalS5f0ww8/aNGiRfr9998VHx+fr/EsFouqVq361+v0Jk2aqGHDhgoPD3dQxwAAAAAAdyAYCgAAAAAAdPDgQX3wwQf6+uuvlZSU5NCxjx07pmPHjumHH36QdO3D50aNGqlLly7q0qWLbrvtNvn7+zt0TgAAvFlqaqq2bt3q7jac4tZbb3V3C4BXio6O1vjx4zVnzhylpaU5bFzDMLR//37t379fM2bMkCQFBASoefPmf71eb9CggSwWi8PmBAAAAAA4H8FQAAAAAAAKsPj4eL3yyiuaPHmyMjMzXTKnYRjasmWLtmzZojfffFNFihTRK6+8opEjR7pkfgDe5ciRI/rqq69yPV+pUiUNGDDAZf0AAOBKx48f13PPPaeZM2e6bM6MjAytWbNGa9as0ejRo1WyZElNnDhR999/f77GjY6O1vz583M9X79+ffXs2TNfcwAAAAAAriEYCgAAAABAAfXLL7/okUce0dmzZ93ax6VLlxQTE+PWHgB4riNHjuj111/P9XybNm0IhgIAfNJ3332nIUOGKDEx0a19nDt3Tvv378/3ONHR0VZ/p/fv359gKAAAAAA4iJ+7GwAAAAAAAK43btw4denSxe2hUAAAAAA3MgxDw4cPV79+/dweCgUAAAAAeCdWDAUAAAAAoIAZPXq03n77bXe3AQAAAOAfDMPQI488ou+++87drQAAAAAAvBjBUAAAAAAACpBPP/3U7lBo0aJF1alTJ9WpU0d16tTRzTffrMjISBUqVEgRERFKT09XcnKyzp49q1OnTmnfvn2KiYnR5s2btW3bNqWnpzvp2QAAAAC+5fnnn7c7FFqmTBl16NDhr9frlSpVUqFChVSoUCGFh4crNTVVSUlJOnPmjE6ePKk9e/YoJiZGmzZt0s6dO5WVleWkZwMAAAAAcBeCoQAAAAAAFBDR0dF6+umnba7v3bu3Bg8erA4dOigwMDDXOn9/f4WEhKho0aKqWbOm2rdv/9e5lJQUrV27VosXL9ZPP/2kQ4cO5ecpWFWpUiUZhuG08QGgbdu2XGfgEs78nXbkyBFVrlzZak3//v311VdfOWX+3PBvC5AWL16scePG2VTr7++v/v37q3///mrVqpX8/PxyrQ0NDVVoaKiKFy+uW2+9VZ07d/7rXEJCgn777TctWrRIixYt0unTp/P9PAAAAAAA7pf7u0QAAAAAAOAzsrKyNHDgQJtW72zYsKHWrVunuXPn6s4777QaCjUTGhqqjh07asKECTp48KD++OMPDR8+XEWLFs3zmAAAAICvSUpK0r/+9S+batu3b6/t27friy++0O233241FGomMjJSPXr00NSpU3XixAmtWLFCgwYNUnh4eJ7HBAAAAAC4H8FQAAAAAAAKgJkzZyo6Otq07p577tG6devUokULp/TRrFkzffTRRzp58qS++eYbNW3a1CnzAAAAAN7ko48+smm1zqeeekq//PKLateu7fAe/Pz8dMcdd+iLL77QqVOnNGnSJNWsWdPh8wAAAAAAnI9gKAAAAAAABcD7779vWtO9e3fNnTtXISEhTu8nJCRE/fr108aNG/Xbb7+pdevWTp8TAAAA8EQZGRmaOHGiad2QIUP0ySef5GuFUFtFRkZqyJAhiomJ0cKFC1WnTh2nzwkAAAAAcJwAdzcAAAAAAACca+fOnfrzzz+t1hQrVkyfffaZSz5k/qc2bdqoTZs2Lp8XAAAA8AQ///yzzp49a7WmWrVqGj9+vIs6+h+LxaLu3bu7fF4AAAAAQP6wYigAAAAAAD5uyZIlpjWjRo1SqVKlXNANAAAAgL+z5fX666+/rtDQUBd0AwAAAADwBQRDAQAAAADwcb///rtpzYMPPuiCTgAAAAD8k9nr9bCwMPXo0cNF3QAAAAAAfAHBUAAAAAAAfFxsbKzV89WrV1elSpVc0wwAAACAv2RkZGj//v1Wa1q1aqXw8HAXdQQAAAAA8AUB7m4AAAAAAAA4T3p6uo4fP261ply5ci7qBpJ09epVrVq1Sr/99ptiYmK0b98+Xbx4UYmJibJYLCpatKiKFy+uBg0aqFmzZurRo4fKli3rsPlPnjypJUuW6M8//1R0dLROnz6tS5cu6cqVKwoJCVFUVJSqVq2q+vXrq3379urUqZOCgoIcNj/c68CBA4qJidGePXu0e/du7d+/XxcvXlRCQoISEhKUlJSk4OBghYSEqGjRoipXrpwqVaqk+vXrq3HjxmrWrJkCAwPd/TTwNwcPHtTatWu1adMmHThwQIcPH9bFixeVlJSktLQ0hYWFKTw8XGXKlFGVKlVUs2ZNtWzZUi1atFChQoXc3b7dDh8+rEWLFunPP//Url27dOrUKSUkJCglJUUhISEqXLiwKlasqBo1aqhFixbq1KmTKlas6O624SMyMjK0du1arVixQrt27dKePXsUHx+vhIQEZWVlKSoqSsWLF1edOnXUrFkzdevWTdWqVXPY/BcuXNDixYu1detWRUdH6/jx47p06ZISExMVFBSkwoULq0qVKqpTp47uuOMOde3a1WPDhKdOndK6dev0xx9//HXtOnfunJKSkpSSkqKgoCCFh4erRIkSqlKlim655Ra1atVKrVu3VrFixdzdvkMdO3ZMGRkZVmt4ve4ZEhIS9Mcff2j9+vXavXu3Dh8+rJMnTyopKUlJSUny8/NTeHi4ihQposqVK6tatWpq3ry5br/9dlWuXNnd7dslKytLmzZt0rZt2xQTE6OTJ0/+9VoxNDT0r+tNrVq11LZtW1WtWtXdLQMAAAD4JwMAAAAAAPisuLg4Q5LVPw8++KC723SIw4cPW32eFStWzPcc/fv3tzrHtGnTcn1sTEyMMXDgQCM8PNz0v8nf//j7+xt33XWXsWHDhjz3nZmZaXz//fdG69atDYvFYtf8xYoVM1588UXj4sWLeZ7fTH5+ro5SsWJFqz0cPnw4X+NPmzbN6vj9+/d3yPP4p3379hlTpkwxHnjgAeOmm26y6799Tn8iIyONPn36GEuXLjWysrIc2qvZv2Fn/lm1apVNPa5atcrqOG3atHHozyQ3J0+eNMaMGWPUrFkzz885KCjI6NGjhzFr1iwjIyPD6T3n599AWlqa8dVXXxkNGjTI03Nt0aKFMXfuXIf/nfVWtvxbc9Y1yRqznvLr1VdftTr+q6++mutjjxw5Yjz99NNGkSJF7P7717ZtW2PJkiX56n3JkiVGly5djICAALvmjoiIMJ588knj1KlT+ZrfUU6ePGmMHTs2z/+WpWuvizp37mxMnz7dSE9Pd/dTcogtW7aYPu8XX3zR3W3axez3pTP/5Pc12z8lJSUZ06ZNMzp37mz3v8G//6lfv74xbtw449KlSw7tz9Gio6ONQYMGGcWLF7fr+VWrVs145513jHPnzrn7KQAAAAD4f2wlDwAAAACAD0tOTjatSUpKckEnBVd8fLwGDhyoW2+9VdOmTbP7552ZmalFixapRYsWGjx4sC5fvmzX45cvX6569eqpb9++WrNmjQzDsOvxFy5c0DvvvKOqVavqhx9+sOuxcI/9+/frzTff1K233qrq1avr8ccf18yZM3XmzJl8j52QkKA5c+aoS5cuqlmzpubNm+eAjmGr06dP68knn1SVKlX0yiuvaPfu3XkeKy0tTQsXLtT999+vGjVqaNq0aXZfH1xhyZIlqlatmgYMGKBt27blaYz169fr3nvvVbNmzbRjxw4HdwhflpKSoueee05Vq1bVhAkTdOnSJbvH+O2339S1a1f17NlTp06dsuuxW7ZsUatWrdS1a1ctXbrUdFXJf7py5Yr++9//qmrVqpo8ebJdj3Wkw4cP61//+pcqV66sF154Ic//lqVrr4uWLVumhx56SDVq1NC3337rwE7dg9frnikxMVFvvPGGKlasqIEDB2rZsmV2/xv8u+joaD377LOqWLGiXn31VaWkpDiw2xtZLBarf3Jy6NAhdevWTfXr19eXX36puLg4u+bcv3+/XnzxRVWqVEljxoxx6vMDAAAAYBuCoQAAAAAA+DBbtnw+e/asCzopmNauXatatWrpq6++ynfgyjAMffnll2rVqpWOHTtmWp+WlqZRo0apc+fO2rVrV77mlq4FRHv37q1XX30132PBOVJSUtSoUSNVr15dL7/8smJiYpw63969e3XvvfeqU6dOOn36tFPngjR16lTVrFlTkydPVmpqqkPHPnjwoAYNGqTWrVtrz549Dh07r1JTUzVw4EB169ZNR48edciYmzdvVtOmTTV9+nSHjAfftnv3btWtW1fjxo3LVxjsugULFtgcTjYMQ++9955atGihdevW5Xvu5ORkPfnkkxo0aJAyMzPzPZ6t0tLS9Oabb6pWrVr6/PPPlZaW5tDxDx06pEceeUTt27e36bWRp+L1uueZO3euatasqVdeecXugKSZy5cva8yYMapTp45Wr17t0LHzasqUKapTp46WLFmS77GSk5P16quvqmHDhnwZAwAAAHAzgqEAAAAAAPiwQoUKmdZER0fbtFIR7DNnzhx16NDB4R/k79q1S82bN9fJkydzrUlKStKdd96pDz74wOErAI4ZM0Yvv/yyQ8eEY6SmpurPP/90+bzXV6XdsmWLy+cuCFJSUvTggw/q8ccft3vFYHutW7dOTZo00Y8//ujUecycP39e7dq101dffeXwsVNTU/Xwww/r888/d/jY8B2rV69WixYtdODAAYeOe+LECbVq1cpqWCozM1MPP/ywnn/+eaWnpzt0/mnTpmngwIEOHTM3x44dU6tWrfTyyy/r6tWrTp1r5cqVaty4sceE7Oxly+t1RwSEYS4lJUUDBgxQnz59rL7WdoSDBw+qffv2+vjjj506jzWGYei5557TE0884fD3g3v27FGzZs3c/poCAAAAKMgIhgIAAAAA4MPCw8NVpMj/tXfn8TXe6f/H39kjiYglSC0lpJIWsRS1VFRRS1vaoNUW1aKLUmoYvm1t04VRbVGdtrYqWq3W0Cqq1KjY10gpopbYpdZIJJHk/P7oQ3/TwX2fk3Puk+Tk9Xw8/DE+1/lc1zF3zn3P5DrXJ8wwJisrS0uXLnVPQcXEsmXL9MQTT7h8qt91J0+eVOfOnW96ROOVK1fUoUMH/fTTT5bklqQ33nhDCxYssGx/FD2pqalq3bq1Nm3aVNCleJTLly+rdevWbv15u3LliuLj4wusUeXixYtq27atNm7caGme5557TitXrrQ0B4qmHTt2qFOnTvk6Nt4eaWlpevjhh5WamnrDWk5Ojh5//HF9/vnnluSWpLlz52r8+PGW7S9JmzdvVsOGDbV161ZL8/y31NRUtWvXTitWrHBbTlepXLmyaczx48e1ZcsWN1RTfKWmpqpFixaaM2eO23Lm5ORo0KBBBTaRf/jw4Zo4caJl+2dmZqpbt25M6gYAAAAKCI2hAAAAAAB4uOjoaNOY0aNHu+SYVEiJiYnq3r276b9niRIlFBUVpdjYWFWvXl3BwcEO5dm+fbtee+21v/ydzWbTU089pXXr1pm+vkKFCrrzzjtVp04dVaxYUT4+Pg7lf+GFF3Ty5EmHXoPCx9fXV2XKlFFkZKRiY2MVFRWl8PBw+fv7O7xXWlqaOnfu7LJjv4u7jIwMdejQIV/NtuXKlVN0dLRiY2NVo0YNBQYGOvR6m82mQYMG6aOPPnI4tzOys7P10EMPKTEx0TS2dOnSqlWrlmJjY1W1alWVKFHCoVx5eXnq1auXzp07l99y4YFOnDihjh076sqVK4Zx/v7+f35u1qxZU6GhoQ7lOXr0qJ5//vkb/n7o0KH6+uuvTV9ftmzZP3/GK1WqZNdR5P9t1KhRdv2c5cf69evVtm3bfB2/HRAQoNtuu0116tRRjRo17Jqk+d+ysrLUpUsXrV271uHcBalUqVKqWLGiadyrr77qhmqKpzNnzqhVq1b5mrzu6+ur8PBwRUdH684771TZsmXl5eXl0B7jxo3ThAkTHM7tjJkzZ+qdd96xPE9ubq769OmjVatWWZ4LAAAAwF/5FnQBAAAAAADAWk2aNDFtLNq3b5/69++vWbNmuakqz5SZmaknn3xS6enpN11v1aqVnnjiCbVu3VqRkZE3/NI4JSVF3377rWbNmqWdO3ea5ps6dar69u2rmJgYSdKbb76pJUuW3DS2XLly6tGjhx5++GE1adLkhmaLnJwc/fzzz1q0aJFmzpxpeuzrxYsX9eqrr2r27NmmdaLgeXl5qX79+mrYsKHq1aun2NhY1a5dW6VKlbppvM1m04EDB7R161atW7dOCxYs0OXLl03znD17Vr1799aaNWscbooICAhQw4YNb/j7tLQ0HThw4JavCwkJUa1atRzK9b8cbT5yh2effVYbNmywK9bPz0+PPPKIunXrplatWqlcuXJ/Wc/Ly9P+/fu1YsUKzZ49W0lJSXbt+9JLL6lWrVq67777HK4/P4YPH66EhISbrpUuXVrdu3fXQw89pHvuuUdly5a9Iebw4cNaunSp5s2bZ9dkvTNnzuj111/Xhx9+6HTtKPpsNpuefvppnTlz5qbrDRs2VM+ePdWmTRvFxMTI2/uvczfOnj2r7777TvPmzdN//vMf03yLFi3Sjz/+qLZt20qS5s2bpylTptw0NiQkRN27d9cjjzyiZs2aqUyZMjfUvnnzZi1evFgfffSRLl26ZJj72rVrGjJkiMuni+/bt0+dOnVSWlqaXfGRkZF6+OGHFRcXpxYtWtzw2SVJ6enp+s9//qPly5dr4cKFOnv2rOGeWVlZ6t69u7Zv327XJM7CokmTJrd8hrtu1apVGjNmjMaMGeOeopxQsmTJm97Tz507pyNHjtzydWXLllW1atWcyh0QEOBQfEZGhtq3b6+9e/faFR8WFqYuXbooLi5OcXFxql69+g0xOTk52rp1q5YvX65vvvnGrr3/7//+T3Xr1lWHDh0cqj8/Dh48qIEDB95yPSgoSI888ojat2//5xcwQkJCdPXqVZ05c0Z79uzRqlWrtHDhQp0+fdo037Vr19S1a1ft2LFDkZGRrnwrAAAAAIzYAAAAAACAR1uxYoVNkl1/HnvsMdu5c+cKuuR8OXz4sOF7u/32253O0bt3b9McN/v7e+65x7Zlyxa78+Tm5to++OADW2BgoOl/Z/Hx8TabzWbbunWrzdvb+4b1EiVK2N566y1benq63fmTk5NtcXFxprm9vb1tBw4ccPjf8X+Z/bvOnj3b6RxmbvXf3fU/hw8fdmr/2bNnG+7fu3dvp9/DhQsX/rKnj4+PrVWrVrYpU6bYjh075tTe6enpthkzZtgqVqxo12fJJ5984vT7uW7NmjWGueLi4lyWq7DU8sEHH9j9ud21a1fbkSNHHNp/8eLFtmrVqtm1f3h4uO3UqVNOvyezn4Fb1RMcHGx7++23bWlpaXbnysvLs82ZM8dWtmxZ0/fn4+Pj8L9fUWd2v3TVZ5KjzGpy1ujRow33v9V9IDo62rZy5UqHcn3xxRe2MmXKmL6nhg0b2mw2m+3o0aO24ODgm16fQ4cOdejZ7NSpU7ZHH33Urp/v1atXO/S+jJw/f95Ws2ZNu/LWr1/ftmDBAltOTo5DOdLS0myjRo266b/V//5p2bKlLS8vz2Xvz2offfSR3Z/7L7/8skPPdYWJO56HHBUfH2/Xv3tERIRt4sSJtsuXLzu0f25urm3OnDm2qlWrmuYoW7as7ezZs06/J7M8t3rO9/f3t40YMcJ2/vx5u/JkZ2fbpk+fbgsPD7fr37BZs2YO/9wDAAAAyD+OkgcAAAAAwMO1bt1aERERdsV++eWXioqK0j/+8Y9bTszCrd3sCO2RI0dq/fr1atSokd37eHt7a8CAAVq4cKHp8bBLlizR0aNH1b9/f+Xl5f1lLSoqStu3b9fIkSMVFBRkd/6aNWtqxYoViouLM4zLy8tj0l4hFBISoiFDhujIkSNas2aNBg4c6PTUtKCgID377LPau3evnnzySdP4cePGKTs726mcxdWxY8c0YsQI0zg/Pz/NnDlTCxcu1O233+5Qjs6dO2vnzp3q1KmTaWxqaqpefvllh/bPj5tNkIuNjdXu3bs1YsQIhYSE2L2Xl5eXevXqpTVr1ig8PNwwNjc3V1OnTnW0XHigm93De/furV27dv051dNejz/+uFasWGE6jXj79u3avHmzBg4ceMO08QoVKmjt2rV65513bpgQaqRixYpauHChevToYRrrymt/4MCBOnjwoGGMt7e3xowZo23btumxxx6Tj4+PQzlCQkI0duxYbdu2zXSq5M8//6wZM2Y4tH9Bio+PV2BgoF2xkydP1h133KHJkyebToeFsRkzZuibb74xjXvkkUe0d+9e/e1vf3N4yri3t7d69eqlpKQk08+Sc+fOafDgwQ7tnx9r16694e+qVaumTZs26e2331bp0qXt2sfPz099+/bVL7/8Ytd08Q0bNnDPBQAAANyIxlAAAAAAADycn5+fXnrpJbvjz58/r1GjRqlKlSrq1KmTZsyYoWPHjllYoeeaNGmS3nrrrRuOm7XXgw8+qLffftswJicnRw888MANR8/HxMRo/fr1fx4z76jAwEB9++23qlixomHc559/fkNDKgqGn5+fxo0bp5SUFL377ruWHKFbunRpzZs3z/D4UUk6fvy45s2b5/L8xcErr7yiK1euGMb4+vpq0aJFeuaZZ/KdJywsTIsXL1bXrl1NY7/66iutWrUq37nyo0WLFkpISHDqyNk6depo6dKlpp/B8+fP53MMNxg4cKA+/fRTh4+lvq5Ro0aaPXu2aVzv3r317bff/uXvIiIitG7dOjVv3jxfub29vfXZZ5+pbt26hnFLly7VhQsX8pXjf/eZP3++YUxwcLBWrlyp0aNH5/u56Lro6Ght2rRJsbGxhnGvvvqqMjIynMrlLuXKlVPPnj3tjj9x4oQGDx6siIgIdevWTfPnz1dqaqqFFXqeEydO6G9/+5tp3IQJE7Ro0SKFhYU5lS80NFTLli3TU089ZRj3+eefa+vWrU7lclRUVJTWr1+v+vXr5+v15cuX14oVK/TQQw+Zxo4bN07nzp3LVx4AAAAAjqExFAAAAACAYmDw4MGqUqWKQ6+5du2ali1bpn79+qlq1aqqUaOGevXqpSlTpmjDhg1F5hftBaV379565ZVXnN5n4MCBqlmzpmHM/v37//Kfg4ODtWTJEtNJeWZCQ0P1j3/8wzDm7NmzSkhIcCoPXCM4OFivv/663VOenDF58mR169bNMMaehij8VVJSkl2Ty6ZOnaoHH3zQ6Xy+vr6aO3euGjdubBo7evRop/PZq3LlylqyZIlDU0JvpXHjxnr++ecNY06fPq3169c7nQue47777tPkyZOd3ic+Pl4tW7Y0jPnfe7i3t7e++uorRUVFOZXb19dXkyZNMozJycnRd99951Se3NxcDR061DDGx8dHCxcu1P333+9Urv9WoUIFLVq0SKGhobeMSU1NLVKTzceOHevwNMqrV6/q66+/1lNPPaUKFSrorrvuUt++ffXRRx9p27ZtysrKsqjaom/UqFGmE1dHjhyp4cOHuyynr6+vZs6cqYYNGxrGjR071mU5zZQuXVrLli3Tbbfd5tQ+/v7++vLLL02bSy9cuKCJEyc6lQsAAACAfWgMBQAAAACgGAgKCtKnn37q1ISmQ4cOae7cuXr55ZfVvHlzhYaGqnbt2urdu7emTJmijRs3KjMz04VVF13VqlXTlClTXLKXv7+/acPF/5o0aZLTDSXXPfPMM6ZTQ3/66SeX5ELR4eXlpffff9+wcS8hIYFpww4aP368bDabYUybNm1MGx0dERgYqE8//VR+fn6GcRs2bLjp0bOu5u3trblz5zp0dLaZcePGmb4/PsdwXVhYmObMmSMvLy+X7Ddy5EiH4ocPH64WLVq4JHebNm3UqFEjwxhnr/05c+bowIEDhjHvvfeeOnTo4FSem4mMjNT06dMNYz744APTz9XCIiIiwqnnR5vNpr1792rmzJl64YUX1KhRI5UsWVINGjRQ//799fHHH2v79u3KyclxYdVFU3JysubMmWMYEx8frzfffNPlua83UBo9Qy1btky//faby3PfzHvvvWf6JTR7lShRQvPnz5evr69h3Mcff2w6HR0AAACA82gMBQAAAACgmGjdurXef/99l+2Xm5urPXv26LPPPtPLL7+sZs2aKTQ0VI0bN9aIESP0008/6dq1ay7LV5RMnjzZcIKVox555BG7m3obN26s5557zmW5vb299cgjjxjGbNiwwWX5UHTcdtttpkfKr1692k3VFH0XL17UokWLDGP8/Pw0depUl+eOiYnRoEGDTONmzJjh8tz/65lnnlGrVq1cumfZsmVNm9KYGIrrxo4d6/CUdSP333+/3UdQV6pUyeWTArt27Wq47uw93GwqaYMGDfTSSy85lcNI9+7ddffdd99y/ejRo0XqXvT000+7ZOL8ddeuXdPOnTs1ffp0Pf/887r77rsVGhqqli1bauzYsdq4caPy8vJclq+oeP/995Wbm3vL9eDgYE2ZMsVlDeL/q0aNGoZf8rDZbG6ZvH733XerV69eLt0zJiZGL774omHMxYsXNX/+fJfmBQAAAHAjGkMBAAAAAChGBg4cqClTpjg1OdTItWvXtHXrVk2YMEH333+/KlasqGeffVbr1q2zJF9hVKNGDZcc8fzfKlSooHvuuceuWHuauxzVuXNnw/WkpCSX50TREB8fb7i+Zs0aN1VS9C1cuNB06vKLL76o6OhoS/KPHj1a5cqVM4xZtGiR0tLSLMkv/TGJ1pUNUf/t8ccfN1z/5ZdfLMmLoiU0NFR9+vRx6Z5+fn7q2LGjXbEvvPCC/P39XZrf7B7+22+/6erVq/nae8OGDdq7d69hzLvvvmtZc911Zkd9f/PNN5bmd7VJkyZp2LBhlu1/9epVrVu3TmPGjFGzZs1UuXJlDRo0SLt27bIsZ2GSkZFh2pQ4bNgwp49WNzN48GDDn3d3XLeTJ0+25OdzzJgxppO/P//8c5fnBQAAAPBXNIYCAAAAAFDMDBw4UMuXL1dERITluc6fP69Zs2apZcuWql27tubNm2c4nccTvPjii5Y03sbGxprGVKhQQd26dXN77tOnT+vy5csuz4vCr0GDBqpQocIt1xMTE91YTdH27bffmsb079/fsvwlS5bUE088YRiTkZFh6eS9du3aKSYmxpK9zY7TPnXqlC5dumRJbhQdvXv3VsmSJV2+rz33cH9/f0t+xqOiolSiRIlbrufl5Sk5OTlfe8+dO9dw/e6771ZcXFy+9nZEfHy8Spcufcv1lStXWl6Dq/3zn//U3LlzVapUKctznTp1SlOnTlX9+vXVtGlTLV261PKcBem7774z/Lz38/Oz5ItW/6tSpUpq3779Ldf37dunlJQUy/I3aNBAzZo1s2Tv0qVL66mnnjKMSUhI0OnTpy3JDwAAAOAPNIYCAAAAAFAMtWvXTnv27NGAAQPk4+Pjlpx79uxRz549Vbt27SJ1pKejHn74YUv2tadZql27di6fNCZJFStWNJ36c+zYMZfnReHn5eWl6tWr33L9119/VU5OjhsrKpquXbum//znP4YxDRs21J133mlpHfYcJ7tq1SrL8ptNNnRGZGSkgoODDWNOnDhhWX4UDQV5D2/SpInCw8Ndntvb29t00nB+7+HLli0zXO/evXu+9nWUt7e3mjdvfsv1Q4cOFcnnlKeeekq//PKL6cRjV9q0aZMeeughNW3aVDt27HBbXnf6/vvvDdfbtm1r2GjsSi1btjRcX7t2rWW5e/ToYdnekky/bJKXl6effvrJ0hoAAACA4o7GUAAAAAAAiqnSpUvrgw8+0L59+9SvXz8FBga6Je++ffvUpk0b9e3bVxkZGW7J6S7ly5dXzZo1Ldk7KirKNMaqqT+STN9XamqqZblRuJUvX/6Wa9nZ2UyDssPOnTt15coVw5gnn3zS8jrsaT61skmlRYsWlu3t7e2tO+64wzDm7NmzluVH4efj46MmTZpYsndB38PN8ufnHr53717TaYZWTDG/FbPJpDt37nRTJa5VuXJlffHFF9qxY4cee+wx+fr6uiXvpk2b1KhRI7366qseN+3/hx9+MFx3V0OzVHDXrbe3t+UNx02aNFGNGjUMY8y+FAMAAADAOTSGAgAAAABQzNWsWVOffPKJTp48qSlTpuiee+6Rl5eX5Xlnzpyppk2b6uTJk5bncpemTZtatrc9R9tamT80NNRw/cKFC5blRuFmNlXr1KlTbqqk6EpMTDSNuffee91Qifn0sn379ik7O9vleUuVKqW77rrL5fv+t7CwMMP1ixcvWpofhVvt2rUtOUZe8sx7+KZNmwzXK1asqGrVqjm8b36ZNb/u3r3bTZVYo379+lqwYIFSUlL01ltvqW7dupbnzMvL01tvvaV27drp8uXLludzh0OHDpl+CeCee+5xUzUFd93eeeedqly5siV7/7cHHnjAcH3r1q2W1wAAAAAUZzSGAgAAAAAASX80dw0cOFAbN27UsWPH9Mknn6hbt26G0wCdtXv3bjVr1sxjju+NjIy0bO+QkBDTGKMjva3On5WVZVluuNbhw4e1YMECjRo1Sk888YRatGihWrVqqVy5cgoJCZGfn5+8vLzs/jNnzhzDfExhNJeUlGS47uvrq9q1a7ullvr16xuu5+Tk6Ndff3V53mrVqsnb29r/u9qsOS4zM9PS/CjcuIc7xmySodn0YVcrW7as4frRo0fdVIm1IiIiNHLkSCUmJio5OVlTpkzRQw89ZNr47oyffvpJ9913n0c0h5pdt/7+/pZN/7+ZUqVKGU6Bteq6jY2NtWRfR/Ps27fP4ybSAgAAAIWJe86cAAAAAAAARUqlSpXUr18/9evXT9If03U2b96sHTt2aMeOHdq1a5fOnz/vklxHjx5Vhw4dtHHjRgUHB7tkz4JiNjnRGWZNHT4+PpZNOrMnvxUTBOEaeXl5+vHHH/XNN9/o+++/d/uU3qtXr7o1X1F0+PBhw/WYmBgFBga6pRazxlDpj3uCq5tKypQp49L9bsbsM5LPseKtIO/hBZ0/P9f+nj17DNdjYmIc3tMZZo2hnvIlpP9Ws2ZNDRw4UAMHDpTNZtO+ffu0ZcuWP5/XExMTlZaW5pJcO3bsUHx8vH744QfLm/itZHbdRkVFycfHx03V/KFMmTK3/BKNVddtYWkMzczM1OHDh93ajAsAAAAUJzSGAgAAAAAAU5GRkYqMjFSPHj3+/LujR49q586dWr9+vdauXasdO3bke+JLUlKSBg8erOnTp7uq5AJh5bQms19Sh4WFycvLq8Dy5+XlWZYb+ZOVlaWPP/5Y7777boFOSmOarDmzZl2rj1h3NJcVzcVWNsVdx+cYjBTkPVyy9mfAims/JSXFcH3atGmaNm2aw/taJTU1taBLsJSXl5diYmIUExOj3r17S5JsNpuSk5O1c+dOJSQkaO3atfrll19ks9nylWPVqlV6++239eqrr7qydLcyu2737Nlj6fO0o65evar09HSXf3mubt26Lt3vVurUqSMvLy/Da+7EiRM0hgIAAAAWKbpf6wMAAAAAAAXq9ttvV5cuXTRx4kRt2bJFFy9e1IIFC9S5c2f5+/s7vN+MGTO0YcMGCyp1HysndpqxZxoZio8ff/xRtWrV0ssvv1zgx+fm5OQUaP6i4PTp04br7miavC4oKEgBAQGGMWb15kdBfn4CUsFfg0XtPn78+PGCLsEhxXF6tZeXl+644w499thjmjp1qnbv3q3ff/9dM2fO1P3335+vyZj/+Mc/TKdcF2bHjh0r6BIcZsW1W6FCBZfveTNBQUGmn62nTp1ySy0AAABAcURjKAAAAAAAcImQkBA99thjWrx4sU6cOKG///3vDk+3GTlypEXVAcWDzWbTyJEj1a5duwJvCL0uv5PJipMrV64YroeGhrqpEvvymdULwLOlp6cXuWnQmZmZBV1CoVCmTBk988wzWrVqlQ4dOqTnnnvOoS90ZWVlacyYMdYVaLHz588XdAkOs+LadedzhVmuc+fOuakSAAAAoPihMRQAAAAAALhcuXLlNH78eB06dEgdO3a0+3U///yzdu7caWFlgOey2Wx65plnNH78+IIuBQ4ya/pwd2NoqVKlDNdpsAKKt6I4fZPp1TeqWrWqPvroI+3du1eNGze2+3ULFizQmTNnLKzMOly7fyhMjaE8UwAAAADW8S3oAgAAAAAAgOcqX768li5dqtdff11vvvmmXa+ZP3++6tevb3FlgOd5/fXX9emnnzq1h7+/v8LCwhQSEqKgoCD5+PjI19f4/0I8cuQI056cdO3aNcN1R6cvO8ssX3Z2tpsqAVAY0cjlWWrUqKGEhAT179/frueI7OxsLVy4UC+99JL1xbkY1+4f3NkYypdNAAAAgIJDYygAAAAAALCUl5eX3njjDZ05c0YzZswwjf/+++/1zjvvuKEywHP8/PPPevvtt+2OL1mypOLi4tS4cWPVqVNHNWrUUJUqVRQWFuZw7qefflpz5sxx+HX4//z8/AybLdPT091YjXk+R44dBuB5vLy8CroEuJifn5+mT5+u06dPa8WKFabx33//fZFsDOXadb+8vLyCLgEAAAAotmgMBQAAAAAAbvH+++9r6dKlOn36tGHc/v37deHCBZUuXdpNlQFFm81m06BBg+z6xXvLli31yiuvqGPHjvLz83NJfn7h77zAwEDDxtDLly+7sRrzfIGBgW6qBEBhFBQUZBoTERGh2267zQ3V2Kcw1VJY+fr6asaMGapZs6bpFMdNmzbJZrMVuUZLs2s3JCREtWrVclM19gkICHD5npcvX1a5cuVcvu+tchnhmQIAAACwDo2hAAAAAADALYKDgzVixAgNHjzYMM5msykpKUktW7Z0T2FAEbd06VIlJiYaxvj7++u9997Tiy++6PL8Fy9edPmexU1ISIhh44S7G0MvXbpkuB4SEuKmSgAURvY0hvbp00dvvvmmG6qBK1WqVEnPP/+83n//fcO4ixcv6tixY6patap7CnMRs2u3bt26Wr9+vZuqKTg0hgIAAADFg3dBFwAAAAAAAIqPRx991K64o0ePWlwJ8FfubrxzpVmzZhmue3l5acmSJZY0hUrShQsXLNm3OKlYsaLhujv/ja9evaqsrCzDGLN6AXi2gIAA08nuGRkZbqoGrubJz+sRERGG68XlunXnc69ZrrJly7qpEgAAAKD4oTEUAAAAAAC4TZUqVRQVFWUal5qa6oZqUFiYHUOam5traf68vDzTCYmFVXZ2tn744QfDmMGDB6t9+/aW1XD+/HnL9i4uzI443rt3r5sqkfbs2WMaU6lSJTdUAqAwM5sUefr0aTdVAldr2rSpXVNhi+LzOtftH9z1PtPT03XlyhXDGLNmXQAAAAD5R2MoAAAAAABwK3uOnLx69aobKkFh4e/vb7hu9gtlZ128eFF5eXmW5rDK1q1bDX9efHx89Pe//92y/Lm5uUpJSbFs/+KievXqhut79+41neLpKjt37jSNMasXgOerWbOm4fqRI0fcUwhcztfX165mvaL4vG523Z45c0aZmZluqqbg7N692y15kpKSZLPZDGP4sgkAAABgHRpDAQAAAACAW4WHh5vG+Pj4uKESFBYBAQGG62lpaZbmP3TokKX7W8lskuR9992nChUqWJY/MTHR8sbd4qBOnTqG6zk5Ofrll1/cUotZY6ifn59iYmLcUguAwqthw4aG60lJSZZP/IZ1PPV53ey6tdlsSkxMdFM1BcddjaFmeQIDA/myCQAAAGAhGkMBAAAAAIBbmU2NkaTg4GA3VILCIiwszHD9woULluZfv369pftb6fDhw4br9evXtzR/QkKCpfsXF/Xq1TONWbdunfWFSPr5558N16Ojo02n/ALwfE2aNDFcT09P165du9xTDFzOU5/X69evLz8/P8OY4vBs467mV7M80dHRRbLBGAAAACgqaAwFAAAAAABudfbsWdOYsmXLuqESFBbly5c3XN+3b5+l+YtyA8ClS5cM1ytWrGhp/pUrV1q6v2Q+kSwvL8/yGqxWv359lSxZ0jBm/vz5ltexa9cu7dmzxzAmLi7O8joAFH7NmjUzbQxcsmSJm6qBq1n1vF7Q9/TAwEDde++9hjHF4brds2ePjh8/bnmeH374wXC9UaNGltcAAAAAFGc0hgIAAAAAALcyazqSpBo1arihEhQWVapUMVy38rjL9PR0rVq1yrL9rZaZmWm4HhISYlnugwcPavny5Zbtf53ZdMrs7GzLa7Car6+vWrVqZRizbds2y5ukP/vsM9OYNm3aWFoDgKIhMDBQDzzwgGHMnDlzOE6+CLpy5YqOHj1qGpef5/XCcE/v0qWL4XpCQoKSk5Mtr6Mg2Ww2ffnll5bm2LJli3777TfDGLNnHwAAAADOoTEUAAAAAAC4TWJioukEIm9vb9WqVctNFaEwiI6ONlw/fvy4Tp06ZUnuWbNm6eLFi5bs7Q5mDRapqamW5Z48ebJbpnWaTaQzm5paVDz88MOmMdOnT7csf3p6uulU0uDgYN1///2W1QCgaOnRo4fhekpKiuXNZ3C91atXm97fy5QpowoVKji8d2G4p3ft2lW+vr63XLfZbJo4caLldRS0L774wtL9P//8c8N1b29vtW7d2tIaAAAAgOKOxlAAAAAAAOA29jQ11a1bV2FhYdYXg0KjRo0aCgoKMoyxorEkJydHkydPdvm+7mT2s2LVhMmDBw9q1qxZluz9v8qVK2e4fvLkSbfUYbVu3bopMDDQMOaDDz6wbIrZG2+8Ydq4/+ijj1o6hRZA0dKlSxdVrlzZMGbkyJFKT093U0VwBXue11u2bJmvvQvDPT0iIkLx8fGGMbNmzdKuXbssr6Ugbd++XRs3brRk74sXL2revHmGMS1atFDFihUtyQ8AAADgDzSGAgAAAADg4YYPH679+/cXdBlKTk626xfNZseSwvP4+vqqSZMmhjFmkwzzY/To0aZHXBZ21apVM1xfsWKFy4/xzcnJ0ZNPPqmMjAyX7nsr4eHh8vPzu+X65cuXPaI5tFSpUuratathTHZ2tgYNGuTy3MnJyXr33XdN4/r16+fy3ACKLl9fX9PPpJSUFA0YMMBNFRVdL774ok6cOFHQZWjt2rX6/vvvTePy+7xeqVIlw/Xk5GSXP7fczCuvvGK4npub69ZnnYIyZMgQ2Ww2l+87btw4nTt3zjDGbOIwAAAAAOfRGAoAAAAAgIdbtGiR7rrrLvXr10+HDh0qkBoyMjL0+OOPKzs72zS2V69ebqgIhY3Z8dTbtm3TokWLXJZvzZo1Gj9+vMv2Kyh169Y1XP/999/12WefuTTn66+/ri1btrh0TyM+Pj6KjIw0jElISHBTNdYaMWKEvLy8DGNWrFihGTNmuCxndna2+vTpY/r53KJFC917770uywvAMwwcOFC33367YcycOXM0btw4N1X0V5mZmQWS11GffPKJoqKiNGzYMJ05c6ZAajh79qxdz+EBAQF67LHH8pWjcuXKKlGixC3Xr169qu3bt+drb0c0btxY3bt3N4zZu3ev4uPj7frfL1Zwx7W7efNm08mejjpw4IA++OADw5iwsDA99dRTLs0LAAAA4EY0hgIAAAAAUAzk5uZqxowZuuOOO/T4449r27Ztbst96dIlPfjgg9qxY4dp7H333ac777zTDVWhsDE70lP6Y6pRWlqa07mSkpL02GOPKS8vz+m9ClqDBg0UHBxsGPPqq6/q9OnTLsn3zjvvFEhDbb169QzXP/30U7fUYbW77rpL3bp1M40bMGCAfvjhB6fz5ebmqk+fPlq/fr1p7NixY53OB8DzBAYG6p133jGNGz16tIYOHeq2e29aWpreeecdVa9eXTk5OW7J6ayrV6/qnXfe0e23367nnnvOrRP/T5w4oTZt2iglJcU09oknnlDp0qXzlcfLy8v0Sy3uuqdPmDDB9BlqxYoV6tChgy5cuOCWmnJzc7Vw4ULVq1fPbV96GTx4sA4fPuySvTIzM/Xkk0/q2rVrhnH9+/dXSEiIS3ICAAAAuDUaQwEAAAAAKEZyc3P15ZdfqlGjRmrUqJGmT5+uy5cvW5Zv+fLluvvuu7VmzRq74t98803LakHhFh0drcaNGxvGpKSkqH379k41hy5btkwtW7ZUampqvvcoTAICAtSpUyfDmFOnTumBBx4wPdLTyNWrV/X8889r2LBh+d7DGWaTKpcvX64PP/zQTdVY691331XJkiUNY7Kzs9W5c2fNnTs333kuX76srl276vPPPzeNffzxx9W6det85wLg2bp27aqePXuaxr377ruKi4uztOExMTFRAwYMUKVKlTRs2DCXfTHCnbKysvTJJ58oOjparVu31oIFCyybHmmz2TRv3jw1bNhQSUlJpvH+/v4aPXq0UznN7unTp0/XkiVLnMphj2rVqmnKlCmmcT/99JNiY2O1YsUKy2o5ceKE3nzzTVWvXl3du3dXYmKiZbn+1/nz59WxY0enf1auXbumHj16mH4BMSwsTMOHD3cqFwAAAAD70BgKAAAAAEAxtW3bNvXv31/ly5dX586d9dlnn7nkl+e5ublatWqV2rdvr44dO+rgwYN2va5///5q2rSp0/lRdL3yyiumMRs2bFBcXJzDR5kfPXpUvXv3VqdOnXTx4sW/rJUuXVphYWEO7VeYPPfcc6Yxu3fvVt26dbV8+XKH9rbZbPr3v/+tunXr6uOPP75h3dvbW9HR0Q7tmR8PP/yw6RHrAwYMULt27bRgwQKdPHnS8pqsUqlSJU2YMME0LisrS7169VKPHj107Ngxh3IsXbpU9evX1+LFi01jy5cvr/fff9+h/QEUP9OmTVNMTIxpXEJCgmrXrq3+/ftrz549Tue12Wzatm2bxo0bp7vuukv16tXThx9+6JIJ44XBmjVr1KNHD4WHh6tHjx76+uuvXTK9MisrS4sXL1bTpk3Vs2dPu4+vHzNmjG6//Xancnfu3NlwPScnR126dFG3bt307bffWvplnmeeecauI82PHTumDh06qG3btlq1apVsNpvTuQ8dOqQPP/xQ9913n6pWrarXXnvN4fu5q+zbt0/NmzfPd0Pq77//ro4dO9r1XDFq1CiVLVs2X3kAAAAAOMa3oAsAAAAAAAAFKysrS99++62+/fZbSX8cZXzvvfeqXr16qlevniIjIxUeHn7L11+9elV79uxRUlKStmzZokWLFuns2bMO1XDXXXdp0qRJTr0PFH3dunXT+PHjtWvXLsO4nTt36p577lF8fLzi4+PVvn37mzZ2HjlyRAkJCfrmm2+0dOnSWx4lO3PmTA0ZMuSGhtGionXr1mrevLnpceAnT55Ux44d1bBhQ/Xt21dxcXGKjo6+oeEyMzNTO3fu1I8//qh58+YpOTn5lnu+8sorSk1N1b59+1zyXm6lSpUqat26tVavXm0Y9+OPP+rHH3+UJJUqVUrlypVTcHCw/Pz8DF/38ccfq2HDhi6r11kvvPCC1q9fr/nz55vGLliwQIsWLVJ8fLy6du2quLi4Gxou8vLylJycrB9++EGzZ882/Rm7ztfXV1999ZUqVKiQn7cBoBgpWbKkVqxYoWbNmunEiROGsTk5OZo+fbqmT5+uBg0aqFOnTmrRooViY2MNP2+ysrKUkpKi/fv3KykpSZs2bdKGDRv0+++/u/rtFDpXrlzRggULtGDBAnl7e6tBgwZq1qyZ6tWrp9jYWFWrVk1lypS55evT0tL0yy+/aPfu3dqwYYOWLFmiS5cuOVRD69atXTLpsXnz5oqKijJ8vpCkr7/+Wl9//bUkqWzZsipdurSCg4Pl62v8q83vvvtOERERdtczc+ZMnTp1yvQZQ5JWrVqlVatWqWrVqnrooYfUunVr1atXT9WqVZO3981n8eTm5urUqVPav3+/9u7dqy1btmjjxo367bff7K7R1eLi4rR27dq//N2hQ4fUpEkTDR06VMOGDbPrS1PXrl3T3Llz9X//9392NRc3a9ZMgwYNym/ZAAAAABxEYygAAAAAAPiLPXv23DDBKTAwUOXLl1dQUJBKlCihzMxMpaWlKS0tTZcvX3Zqak6VKlW0YsUKhYSEOFs6ijhvb29NmzZNLVu2VG5urmGszWb7S8NAWFjYn9doenq6Tpw4oYyMDNOcQ4cO1SOPPKIhQ4a45D0UlGnTpqlx48bKzs42jd2+fbu2b98uSQoODla5cuUUFham3NxcXbhwQSdPnrTrZ7pJkyZ644037JpY6gqvvfaaXU0b1126dMnuppfCOFnuk08+0dGjR5WQkGAam52drS+++EJffPGFJCk8PFzlypVTQECA0tPTdfz4cV29etWh/F5eXvrwww8VFxeXr/oBFD9Vq1bVqlWr1K5dO7snH+7YsUM7duz48z+XKFFCERERCgoKkr+/v7Kzs5WZmalz5865ZFKmJ8jLy9O2bdtuOLI7ODhY4eHhKlGihAIDA5WRkfHn87qz97nY2FgtWrRIPj4+Tu0j/XF/efXVV/X000/b/Zpz587p3LlzdsVmZWU5VI+/v7/+/e9/q3PnzlqzZo1dr0lJSdG0adM0bdo0SX98kaJixYoKDQ1VQECAcnNzlZmZqUuXLik1NVV5eXkO1WS16dOnKzY29oZng6ysLL311luaPHmyHn30UbVv316xsbGqUqWKgoODlZWVpTNnzmjPnj1avXq1vvrqK7untIeGhmru3LkuuYYAAAAA2IfGUAAAAAAAYCozM1MpKSku37d27dr6/vvvVblyZZfvjaKpWbNmGjNmjF5//XWHXnfx4kWHJ3727NlTEydOdOg1hVVsbKwmTZqkgQMHOvS69PR0paen6+jRow69rlatWvr+++8VEBDg0Ouc0apVK/Xp00ezZ892W86CFBQUpGXLlumBBx7Qxo0bHXptamqqU0fvenl5aerUqerXr1++9wBQPEVHR2vjxo3q0KGDkpKSHH791atXdejQIQsq83zX7+muFhcXp3//+98qVaqUy/bs1auXPvvsM/30008u29MZ1yfe9u7dWwsWLHD49Tk5OTp+/LgFlVkjKipKU6ZMueV9Pj09XXPnztXcuXNdks/X11dff/21IiMjXbIfAAAAAPvc/FwDAAAAAAAAi/Xu3Vvr169X1apVC7oUFDKvvfaa+vbta2mOPn36aNasWTcco16UvfTSSxoxYoTleerVq6dVq1bdcFy5O/zrX/9S27Zt3Z63oJQsWVKrV6/WE0884bacISEhWrRokQYMGOC2nAA8S6VKlbR582Y9//zzBV0KnODt7a1hw4Zp5cqVKl26tEv39vLy0sKFCxUbG+vSfZ3h7++vL774Qh9++KFKlChR0OVYrm/fvho6dKjleXx8fDR79uxi9fwGAAAAFBY0hgIAAAAA4OGWLFmisWPHqn79+gVdiiSpTp06Wr58uT799FOFhoYWdDkopD7++GMNHz7c5fv6+vpqwoQJmjVrlnx9Pe8wnbffflvvvvuuZcd0duvWTQkJCQU25TcgIEDLli3TiBEj5OfnVyA1uFuJEiU0f/58ffzxxy6d1nYzzZs319atW9WlSxdL8wDwfCVKlNC//vUvrVy5UrVr1y6QGmJjYy29J7rS+vXr9fe//121atUq6FIkSS1atNCGDRv0z3/+U/7+/pbkKFOmjBISEvTss88Wqi/qvPDCC0pMTNSDDz5YIPlvu+02DR8+XPXq1bM818SJE/XKK69Ytn9gYKC++uorPfXUU5blAAAAAHBrNIYCAAAAAODh7rrrLo0aNUo7duzQkSNH9P7776t169YKDAx0ax1xcXH66quvtGvXLrVv396tuVH0eHt7a8KECVq6dKmqVKnikj0bNWqkbdu2WdJwWpgMGTJEGzZsUN26dV22Z9WqVbV48WJ99dVXCg4Odtm++eHr66u3335b+/fv1+DBg1WxYsUCrcdd+vfvr19//VXPPfecAgICXLp3ZGSkZs6cqXXr1ik6OtqlewMo3tq2batdu3Zp9uzZLr0v3UpERISGDBmiXbt2adeuXRoyZEihajq8lSZNmmj8+PHat2+f9u7dq7feektNmzZ165cgvL299eCDD2rFihVat26dmjRpYnnOkJAQzZgxQ4mJiXrmmWcUFhZmeU57REVF6bvvvtOaNWvUoUMHy6+hkJAQPfHEE/rhhx907NgxTZgwQeXKlbM0p/TH5NZJkyZp2rRpLp+Sescdd2jTpk169NFHXbovAAAAAPt53lgEAAAAAABwS7fffrtefvllvfzyy8rOzta2bduUkJCghIQEbdiwQefOnXNZrsDAQDVp0kQPPvigunTpopo1a7psbxQfnTp10v79+zVz5kxNmzZN+/btc+j1Xl5eiouL09ChQ9WpU6ci0RziCo0bN9bOnTu1YMECTZ06VZs2bXJ4D29vbzVt2lQvvviiunXrdsvmlDp16uiBBx645T6VKlVyOLc9qlevrvfee0+TJk3Sjh07tGHDBiUlJem3337TyZMn9fvvvys9PV3Z2dnKy8uzpAZ3i4iI0EcffaRRo0Zp5syZ+vzzzx3+mbjOz89PDzzwgHr27Kn4+PgiMVEPrhEWFqbRo0cbxrhjUh2KDx8fHz399NN6+umnlZCQoC+//FJLlizRsWPHnN67ZMmSatmypdq0aaM2bdoU2HRSV4qJiVFMTIxGjhypjIwMbd68WevWrVNCQoI2bdqktLQ0l+UKCQlRixYt9NBDD6lz586W3bPN1KlTRzNnztRHH32kLVu2aOPGjfrll1906NAhnTp1SufOnVNGRoauXbvm1nt6q1at1KpVKx08eFDz58/X4sWLtWvXLqf39fX1VePGjf+8bu+5554CnYT+4osvqm3btnrppZe0cuVKp/YKCgrSsGHDNHz4cAUFBbmoQgAAAAD54WWz2WwFXQQAAAAAACgcjh8/ruTkZB04cEDJyclKTk7W6dOnlZaWprS0NF2+fFnp6eny8vKSv7+/AgMDVaZMGYWHh6tixYqqWbOm7rjjDtWtW1f169cvNkc9w30SExO1evVqbd68WcnJyTp27JiuXLmi7OxsBQcHKzQ0VFWrVlWdOnXUpEkTderUSRUqVCjosgvckSNHtHz5cm3evFm//vqrUlJSdOnSJWVlZSkgIEAhISEKCwtTVFSUatWq9WezgjumVcE5Bw8e1Lp167RlyxYdPHhQR44c0fnz55Wenq5r164pKChIwcHBioiIUGRkpGJiYtS8eXM1b95coaGhBV0+gGLswIED2rJli3bs2KHffvtNKSkpOn36tDIyMpSRkSEvLy+VLFnyzz9hYWGqXr26YmJiFB0drejoaEVFRcnXt/jMQMnLy1NKSsqfz+oHDhzQwYMHlZqaqsuXL//5zJ6eni4fHx/5+/urRIkSKlu2rMLDwxUREaGoqCjdcccdqlevnmrXrs0XAxx0+vRpbdmyRVu3btWBAwd09OhRnTx5UmlpacrIyFBubq5CQkL+vG5DQ0NVuXLlv1y3MTExljZNmn0RyuhXw9u3b9fUqVP13Xff6fz583bnrFGjhvr06aP+/fsrPDzc7tcBAAAAsA6NoQAAAAAAAAAAAADgAZxpDL0uNzdXmzdv1s6dO7V3714dP378z+bXwMBAhYaGKjIyUnfeeafi4uJUq1YtV5UPAAAAwEVoDAUAAAAAAAAAAAAAD+CKxlAAAAAARZ93QRcAAAAAAAAAAAAAAAAAAAAA16AxFAAAAAAAAAAAAAAAAAAAwEPQGAoAAAAAAAAAAAAAAAAAAOAhaAwFAAAAAAAAAAAAAAAAAADwEDSGAgAAAAAAAAAAAAAAAAAAeAgaQwEAAAAAAAAAAAAAAAAAADwEjaEAAAAAAAAAAAAAAAAAAAAegsZQAAAAAAAAAAAAAAAAAAAAD0FjKAAAAAAAAAAAAAAAAAAAgIegMRQAAAAAAAAAAAAAAAAAAMBD0BgKAAAAAAAAAAAAAAAAAADgIWgMBQAAAAAAAAAAAAAAAAAA8BA0hgIAAAAAAAAAAAAAAAAAAHgIGkMBAAAAAAAAAAAAAAAAAAA8BI2hAAAAAAAAAAAAAAAAAAAAHoLGUAAAAAAAAAAAAAAAAAAAAA/hW9AFAAAAAAAAAAAAAACcZ7PZCroEAAAAAIUAE0MBAAAAAAAAAAAAAAAAAAA8BI2hAAAAAAAAAAAAAAAAAAAAHoLGUAAAAAAAAAAAAAAAAAAAAA9BYygAAAAAAAAAAAAAAAAAAICHoDEUAAAAAAAAAAAAAAAAAADAQ9AYCgAAAAAAAAAAAAAAAAAA4CFoDAUAAAAAAAAAAAAAAAAAAPAQNIYCAAAAAAAAAAAAAAAAAAB4CBpDAQAAAAAAAAAAAAAAAAAAPASNoQAAAAAAAAAAAAAAAAAAAB6CxlAAAAAAAAAAAAAAAAAAAAAPQWMoAAAAAAAAAAAAAAAAAACAh6AxFAAAAAAAAAAAAAAAAAAAwEPQGAoAAAAAAAAAAAAAAAAAAOAhaAwFAAAAAAAAAAAAAAAAAADwEDSGAgAAAAAAAAAAAAAAAAAAeAgaQwEAAAAAAAAAAAAAAAAAADwEjaEAAAAAAAAAAAAAAAAAAAAegsZQAAAAAAAAAAAAAAAAAAAAD0FjKAAAAAAAAAAAAAAAAAAAgIegMRQAAAAAAAAAAAAAAAAAAMBD0BgKAAAAAAAAAAAAAAAAAADgIWgMBQAAAAAAAAAAAAAAAAAA8BA0hgIAAAAAAAAAAAAAAAAAAHgIGkMBAAAAAAAAAAAAAAAAAAA8BI2hAAAAAAAAAAAAAAAAAAAAHoLGUAAAAAAAAAAAAAAAAAAAAA9BYygAAAAAAAAAAAAAAAAAAICHoDEUAAAAAAAAAAAAAAAAAADAQ9AYCgAAAAAAAAAAAAAAAAAA4CFoDAUAAAAAAAAAAAAAAAAAAPAQNIYCAAAAAAAAAAAAAAAAAAB4CBpDAQAAAAAAAAAAAAAAAAAAPASNoQAAAAAAAAAAAAAAAAAAAB6CxlAAAAAAAAAAAAAAAAAAAAAPQWMoAAAAAAAAAAAAAAAAAACAh6AxFAAAAAAAAAAAAAAAAAAAwEPQGAoAAAAAAAAAAAAAAAAAAOAhaAwFAAAAAAAAAAAAAAAAAADwEP8Pf1Hgi07RfJMAAAAASUVORK5CYII=", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Binary Hard\n", + "plotDataRewardStd(\"figure5/binaryAdverseCrashCourse\",[\"SFEAST\"],.4,successRateAdjustmentFlag=True,systemName=\"Average Reward for Each Policy\",tSteps=15,\n", + " baselineExpName=\"figure5/binaryAdverseCrashCourseBaselines\")" + ] + }, + { + "cell_type": "code", + "execution_count": 31, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Binary Hard\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figure5/binaryAdverseCrashCourse\"\n", + "fixedSafetyData = loadAndComputeSafetyData(experimentPath,[\"SFEAST\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False)\n", + "\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figure5/binaryAdverseCrashCourseBaselines\"\n", + "Baselines = loadAndComputeSafetyData(experimentPath,[\"greedy\",\"cbf\",\"scp\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False)\n", + "\n", + "timeSteps = onp.arange(fixedSafetyData[\"numTimeSteps\"])\n", + "\n", + "\n", + "plotTrueSafetyOursVsBaselines(timeSteps,fixedSafetyData[\"trueSafetyValues\"],Baselines[\"trueSafetyValues\"],[\"s-FEAST\",\"Greedy\",\"CBF\",\"SCP\"],fixedSafetyData[\"nSimulationsPerTrees\"],figTitleExpName=None,#In paper will label with caption figTitleExpName=\"Crash Course Under Worst Case Failure\",\n", + " threshold=.9)" + ] + }, + { + "cell_type": "code", + "execution_count": 32, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#General Easy\n", + "plotDataRewardStd(\"figure5/generalProximityOperations\",[\"SFEAST\"],.4,successRateAdjustmentFlag=True,systemName=\"Average Reward for Each Policy\",tSteps=15,\n", + " baselineExpName=\"figure5/generalProximityOperationsBaselines\")" + ] + }, + { + "cell_type": "code", + "execution_count": 33, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#General Easy\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figure5/generalProximityOperations\"\n", + "\n", + "\n", + "fixedSafetyData = loadAndComputeSafetyData(experimentPath,[\"SFEAST\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False,requestedTSteps=15)\n", + "\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figure5/generalProximityOperationsBaselines\"\n", + "Baselines = loadAndComputeSafetyData(experimentPath,[\"greedy\",\"cbf\",\"scp\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False,requestedTSteps=15)\n", + "\n", + "timeSteps = onp.arange(fixedSafetyData[\"numTimeSteps\"])\n", + "\n", + "plotTrueSafetyOursVsBaselines(timeSteps,fixedSafetyData[\"trueSafetyValues\"],Baselines[\"trueSafetyValues\"],[\"s-FEAST\",\"Greedy\",\"CBF\",\"SCP\"],fixedSafetyData[\"nSimulationsPerTrees\"],figTitleExpName=None,#In paper will label with caption figTitleExpName=\"Crash Course Under Worst Case Failure\",\n", + " #experimentIndexes=[0,2,3,4,6],threshold=.9)\n", + " threshold=.9)\n" + ] + }, + { + "cell_type": "code", + "execution_count": 36, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#General Hard\n", + "plotDataRewardStd(\"figure5/generalAdverseCrashCourse\",[\"SFEAST\"],.4,successRateAdjustmentFlag=True,systemName=\"Average Reward for Each Policy\",tSteps=15,\n", + " baselineExpName=\"figure5/generalAdverseCrashCourseBaselines\")" + ] + }, + { + "cell_type": "code", + "execution_count": 37, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#General Hard\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figure5/generalAdverseCrashCourse\"\n", + "\n", + "fixedSafetyData = loadAndComputeSafetyData(experimentPath,[\"SFEAST\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False,requestedTSteps=15)\n", + "\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figure5/generalAdverseCrashCourseBaselines\"\n", + "Baselines = loadAndComputeSafetyData(experimentPath,[\"greedy\",\"cbf\",\"scp\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False,requestedTSteps=15)\n", + "\n", + "timeSteps = onp.arange(fixedSafetyData[\"numTimeSteps\"])\n", + "\n", + "\n", + "\n", + "plotTrueSafetyOursVsBaselines(timeSteps,fixedSafetyData[\"trueSafetyValues\"],Baselines[\"trueSafetyValues\"],[\"s-FEAST\",\"Greedy\",\"CBF\",\"SCP\"],fixedSafetyData[\"nSimulationsPerTrees\"],figTitleExpName=None,#In paper will label with caption figTitleExpName=\"Crash Course Under Worst Case Failure\",\n", + " threshold=.9)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Supplemental Material Fig. 3. " + ] + }, + { + "cell_type": "code", + "execution_count": 38, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Binary Medium\n", + "plotDataRewardStd(\"figureS3/binaryRandomCrashCourse\",[\"SFEAST\"],.4,successRateAdjustmentFlag=True,systemName=\"Average Reward for Each Policy\",tSteps=15,\n", + " baselineExpName=\"figureS3/binaryRandomCrashCourseBaselines\",)" + ] + }, + { + "cell_type": "code", + "execution_count": 39, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Binary Medium\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figureS3/binaryRandomCrashCourse\"\n", + "fixedSafetyData = loadAndComputeSafetyData(experimentPath,[\"SFEAST\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False)\n", + "\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figureS3/binaryRandomCrashCourseBaselines\"\n", + "Baselines = loadAndComputeSafetyData(experimentPath,[\"greedy\",\"cbf\",\"scp\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False)\n", + "\n", + "timeSteps = onp.arange(fixedSafetyData[\"numTimeSteps\"])\n", + "\n", + "plotTrueSafetyOursVsBaselines(timeSteps,fixedSafetyData[\"trueSafetyValues\"],Baselines[\"trueSafetyValues\"],[\"s-FEAST\",\"Greedy\",\"CBF\",\"SCP\"],fixedSafetyData[\"nSimulationsPerTrees\"],figTitleExpName=None,#In paper will label with caption figTitleExpName=\"Crash Course Under Worst Case Failure\",\n", + " threshold=.9)\n" + ] + }, + { + "cell_type": "code", + "execution_count": 40, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#General Medium\n", + "plotDataRewardStd(\"figureS3/generalRandomCrashCourse\",[\"SFEAST\"],.4,successRateAdjustmentFlag=True,systemName=\"Average Reward for Each Policy\",tSteps=15,\n", + " baselineExpName=\"figureS3/generalRandomCrashCourseBaselines\",)" + ] + }, + { + "cell_type": "code", + "execution_count": 41, + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#General Medium\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figureS3/generalRandomCrashCourse\"\n", + "fixedSafetyData = loadAndComputeSafetyData(experimentPath,[\"SFEAST\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False)\n", + "\n", + "experimentPath = \"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figureS3/generalRandomCrashCourseBaselines\"\n", + "Baselines = loadAndComputeSafetyData(experimentPath,[\"greedy\",\"cbf\",\"scp\"],dieAndStayDead=True, sampleBeliefFlag=True,clearCachedData=False)\n", + "\n", + "timeSteps = onp.arange(fixedSafetyData[\"numTimeSteps\"])\n", + "\n", + "\n", + "plotTrueSafetyOursVsBaselines(timeSteps,fixedSafetyData[\"trueSafetyValues\"],Baselines[\"trueSafetyValues\"],[\"s-FEAST\",\"Greedy\",\"CBF\",\"SCP\"],fixedSafetyData[\"nSimulationsPerTrees\"],figTitleExpName=None,#In paper will label with caption figTitleExpName=\"Crash Course Under Worst Case Failure\",\n", + " threshold=.9)" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.4" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/failurePy/visualization/figuresS1andS2.ipynb b/failurePy/visualization/figuresS1andS2.ipynb new file mode 100644 index 0000000..367b6a6 --- /dev/null +++ b/failurePy/visualization/figuresS1andS2.ipynb @@ -0,0 +1,358 @@ +{ + "cells": [ + { + "cell_type": "code", + "execution_count": 24, + "id": "78ab478f", + "metadata": {}, + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "<>:6: SyntaxWarning: invalid escape sequence '\\.'\n", + "<>:6: SyntaxWarning: invalid escape sequence '\\.'\n", + "/tmp/ipykernel_8197/1187149423.py:6: SyntaxWarning: invalid escape sequence '\\.'\n", + " warnings.filterwarnings( \"ignore\", module = \"matplotlib\\..*\" )\n" + ] + }, + { + "data": { + "text/html": [ + "" + ], + "text/plain": [ + "" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "from IPython.display import display, HTML\n", + "display(HTML(\"\"))\n", + "import numpy as onp\n", + "#Ignore matplotlib warnings'\n", + "import warnings\n", + "warnings.filterwarnings( \"ignore\", module = \"matplotlib\\..*\" )\n", + "import os\n", + "import matplotlib.pyplot as plt\n", + "\n", + "\n", + "from failurePy.visualization.visualization import plotMultipleWallClockTimes, setColorCycler" + ] + }, + { + "cell_type": "code", + "execution_count": 25, + "id": "527ba07e", + "metadata": {}, + "outputs": [], + "source": [ + "\"\"\"\n", + "Figure S2 uses data from a previous iteration of failurePy where baseline solvers built off the POMCP algorithm were implemented.\n", + "The previous data was saved in a different format, with the rewards at each time step, total steps taken, success, and average\n", + "wall-clock-time being saved for each trial, but not information about the state, belief, or actions taken. These were stored in a\n", + ".npy binary file in the FullData directory, with sub directories for each level of planning. Averages across all trials\n", + "were stored in the AverageData directory.\n", + "\n", + "This notebook provides code for loading this data and generating the plots that make up figure S2. Note that some post processing was\n", + "done using Affinity Designer when creating the composite image to improve readability, but no data was changed.\n", + "\n", + "Because these results showed that POMCP or other solvers using particle filters cannot scale well in belief-space planning (see the\n", + "discussion section of our paper for analysis of why this is the case), it was not reimplemented in this version of failurePy.\n", + "\"\"\"\n", + "\n", + "def plotData1SigmaRewards(experimentName,savedDataDirPath,solverNames,numTrialsPerPoint=10,noise=None,successRateAdjust=False,systemName=None,tSteps=20):\n", + "\n", + "\n", + " #Make data paths\n", + " savedAvgDataDirPath = os.path.join(savedDataDirPath,\"AverageData{}\".format(experimentName))\n", + " savedFullDataDirPath = os.path.join(savedDataDirPath,\"FullData{}\".format(experimentName))\n", + "\n", + " #Load averages\n", + " Ns = onp.load(os.path.join(savedAvgDataDirPath,\"Ns.npy\" ))\n", + " avg_successRates = onp.load(os.path.join(savedAvgDataDirPath,\"successRates.npy\" ))\n", + " avg_rewards = onp.load(os.path.join(savedAvgDataDirPath,\"rewards.npy\" ))\n", + "\n", + " #Load fulls\n", + "#\n", + " rewards = onp.zeros((len(Ns),numTrialsPerPoint,2,20))\n", + " for i,N in enumerate(Ns):\n", + " subDirectory = os.path.join(savedFullDataDirPath,str(N))\n", + "#\n", + " rewards[i,:,:] = onp.load(os.path.join(subDirectory,\"rewards.npy\"))\n", + " #Make plots with fill_between\n", + "\n", + " #Compute sigma for plotting\n", + "\n", + " rwBds = onp.zeros((len(Ns),2,2,20))\n", + "#\n", + " for i,N in enumerate(Ns):\n", + " for j in range(2):\n", + " for k in range(20): #loop through every time step\n", + " sigma = .25*onp.std(rewards[i,:,j,k])\n", + " rwBds[i,j,0,k] = avg_rewards[i,j,k] -sigma #\n", + " rwBds[i,j,1,k] = avg_rewards[i,j,k] + sigma #\n", + "\n", + "\n", + " plot1SigmaRewards(rwBds,Ns,avg_successRates,avg_rewards,successRateAdjust,sysName=systemName)\n", + " plt.show()\n", + "\n", + "def plot1SigmaRewards(rwbds,Ns,avg_successRates,avg_rewards,successRateAdjust=False,sysName=None):\n", + "\n", + " #Plot reward trajectories\n", + " dummyFig, ax = plt.subplots(nrows=1,ncols=1,figsize=(15,8))\n", + " #Make x-axis\n", + " iterations =onp.arange(0,20)\n", + " #Labels for legend\n", + " handles = []\n", + "\n", + " #Legend Entries\n", + " handle = ax.plot(iterations[0],rwbds[0,0,0,0],label=\"POMCP\",ls=\":\",c=\"black\")[0]\n", + " handles.append(handle)\n", + " handle = ax.plot(iterations[0],rwbds[0,0,0,0],label=\"FEAST\",ls=\"-\",c=\"black\")[0]\n", + " handles.append(handle)\n", + "\n", + " #Set color cycle\n", + " setColorCycler(len(Ns),ax)\n", + "\n", + " offset = .1\n", + " markersize = 2.5\n", + "\n", + " #plot avgs FEAST\n", + " for jOffset,N in enumerate(Ns):\n", + " #Check for random policy\n", + " if successRateAdjust:\n", + " successFactor = avg_successRates[jOffset,1]\n", + " else:\n", + " successFactor = 1\n", + " if N == 0:\n", + " label = \"Random Action\"\n", + " marker = \"*\"\n", + " lineStyle= \"--\"\n", + " handle = ax.plot(iterations,avg_rewards[jOffset,1,:]*successFactor,label=label,ls=lineStyle,marker=marker)[0]\n", + " handles.append(handle)\n", + " else:\n", + " #Regular trials\n", + " label = \"N = {}\".format(N)\n", + " marker = \"o\"\n", + " lineStyle= \"-\"\n", + " handle = ax.plot(iterations+offset*(jOffset),avg_rewards[jOffset,1,:]*successFactor,label=label,ls=lineStyle,marker=marker)[0]\n", + " handles.append(handle)\n", + "\n", + " #Plot 1-sigma range\n", + " ax.vlines(iterations+offset*(jOffset),rwbds[jOffset,1,0,:]*successFactor,rwbds[jOffset,1,1,:]*successFactor,\n", + " ls=lineStyle,alpha=1,color=handle.get_color(),zorder=200+jOffset)\n", + " #Add markers at end\n", + " ax.scatter(iterations+offset*(jOffset),rwbds[jOffset,1,1,:]*successFactor,marker=marker,s=markersize**2,\n", + " color=handle.get_color(),zorder=200+jOffset )#,alpha=.5)\n", + " ax.scatter(iterations+offset*(jOffset),rwbds[jOffset,1,0,:]*successFactor,marker=marker,s=markersize**2,\n", + " color=handle.get_color(),zorder=200+jOffset )#,alpha=.5)\n", + "\n", + " #Plot POMCP\n", + " for jOffset in range(len(Ns)):\n", + " #Check for random policy (always nan, so don't actually need to do this here)\n", + " if successRateAdjust:\n", + " successFactor = avg_successRates[jOffset,0]\n", + " else:\n", + " successFactor = 1\n", + "\n", + " marker = \"^\"\n", + " lineStyle= \":\"\n", + " if successRateAdjust:\n", + " ax.plot(iterations+offset*(jOffset+1),avg_rewards[jOffset,0,:]*successFactor,ls=lineStyle,marker=marker)\n", + "\n", + " #Plot 1-sigma range\n", + " ax.vlines(iterations+offset*(jOffset+1),rwbds[jOffset,0,0,:]*successFactor,rwbds[jOffset,0,1,:]*successFactor,\n", + " ls=lineStyle,alpha=1,color=handle.get_color(),zorder=200+jOffset)\n", + " #Add markers at end\n", + " ax.scatter(iterations+offset*(jOffset+1),rwbds[jOffset,0,1,:]*successFactor,marker=marker,s=markersize**2,\n", + " color=handle.get_color(),zorder=200+jOffset )#,alpha=.5)\n", + " ax.scatter(iterations+offset*(jOffset+1),rwbds[jOffset,0,0,:]*successFactor,marker=marker,s=markersize**2,\n", + " color=handle.get_color(),zorder=200+jOffset )#,alpha=.5)\n", + "\n", + " ##Plot 1-sigma range\n", + " #for i,N in enumerate(Ns):\n", + " # if successRateAdjust:\n", + " # ax.fill_between(iterations,rwbds[i,1,0,:]*avg_successRates[i,1],rwbds[i,1,1,:]*avg_successRates[i,1],alpha=.1)\n", + " # else:\n", + " # ax.fill_between(iterations,rwbds[i,1,0,:],rwbds[i,1,1,:],alpha=.1)\n", + "#\n", + " ##plot again so colors cycle\n", + " #for i in range(len(Ns)):\n", + " # if successRateAdjust:\n", + " # ax.fill_between(iterations,rwbds[i,0,0,:]*avg_successRates[i,0],rwbds[i,0,1,:]*avg_successRates[i,0],alpha=.1)\n", + " # else:\n", + " # ax.fill_between(iterations,rwbds[i,0,0,:],rwbds[i,0,1,:],alpha=.1)\n", + "\n", + " ax.legend(handles=handles)\n", + " ax.set_xlabel(\"Experiment Time Step\")\n", + " if successRateAdjust:\n", + " ax.set_ylabel(\"Reward * Success Rate\")\n", + " else:\n", + " ax.set_ylabel(\"Reward\")\n", + " if sysName is not None:\n", + " ax.set_title(sysName)\n", + " else:\n", + " ax.set_title(\"rwbds After Each Time Step (N Simulations per Time Step)\")\n", + " ax.set_xticks(onp.arange(0,20,2))\n", + "\n", + " #Set the color to gray and turn on grid\n", + " ax.set_facecolor(\"lightgray\")\n", + " plt.grid(True)\n", + " #Normalize y to 1\n", + " #ax.set_ylim(0,1)" + ] + }, + { + "cell_type": "code", + "execution_count": 28, + "id": "69dfc7c4", + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "figureS1/safetyOnJetsonOrin\n", + "/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figureS1/safetyOnJetsonOrin\n", + "[array([[0.02154842, 0.2207659 , 0.48787756, 0.7404685 , 1.03502416,\n", + " 2.02999881, 4.44581484, 7.57508903]]), array([[0.02078437, 0.26500784, 0.57158566, 0.9166842 , 1.14585531,\n", + " 2.32020109, 4.67699627, 7.06134919]])]\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Data location defaults to failurePy/SavedData, you can specify a different location with the optional argument: savedDataDirPath\n", + "plotMultipleWallClockTimes([\"figureS1/safetyOnJetsonOrin\",\"figureS1/safetyOffJetsonOrin\"],[\"SFEAST\"],labels=[\"s-FEAST\",\"FEAST\"],sigmaFlag=True)\n" + ] + }, + { + "cell_type": "code", + "execution_count": 26, + "id": "7df5d676", + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Note that some post processing was done using Affinity Designer when creating the composite image to improve readability, but no data was changed.\n", + "plotData1SigmaRewards(\"DoubleIntegrator2DHighNoise\",\"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figureS2\",[\"FEAST\",\"POMCP\"],numTrialsPerPoint=1000,successRateAdjust=True,tSteps=20)\n", + "#plotData1SigmaRewards(\"DoubleIntegrator2DHighNoiseExtended\",\"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figureS2\",[\"FEAST\",\"POMCP\"],numTrialsPerPoint=1000,successRateAdjust=True,tSteps=20)\n" + ] + }, + { + "cell_type": "code", + "execution_count": 27, + "id": "de5abf77", + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Note that some post processing was done using Affinity Designer when creating the composite image to improve readability, but no data was changed.\n", + "plotData1SigmaRewards(\"DoubleIntegrator2DLowNoise\",\"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figureS2\",[\"FEAST\",\"POMCP\"],numTrialsPerPoint=1000,successRateAdjust=True)" + ] + }, + { + "cell_type": "code", + "execution_count": 28, + "id": "778edbea", + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Note that some post processing was done using Affinity Designer when creating the composite image to improve readability, but no data was changed.\n", + "plotData1SigmaRewards(\"SingleIntegrator1DHighNoise\",\"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figureS2\",[\"FEAST\",\"POMCP\"],numTrialsPerPoint=1000,successRateAdjust=True)" + ] + }, + { + "cell_type": "code", + "execution_count": 29, + "id": "f1999168", + "metadata": {}, + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "#Note that some post processing was done using Affinity Designer when creating the composite image to improve readability, but no data was changed.\n", + "plotData1SigmaRewards(\"SingleIntegrator1DLowNoise\",\"/home/trey/Research-Code/s-FEAST/failurePy/SavedData/figureS2\",[\"FEAST\",\"POMCP\"],numTrialsPerPoint=1000,successRateAdjust=True)" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Python 3 (ipykernel)", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.4" + }, + "vscode": { + "interpreter": { + "hash": "0a54084e6b208ee8d1ce3989ffc20924477a5f55f5a43e22e699a6741623861e" + } + } + }, + "nbformat": 4, + "nbformat_minor": 5 +} diff --git a/failurePy/visualization/oneDimensionalBeliefVisulaization.py b/failurePy/visualization/oneDimensionalBeliefVisulaization.py new file mode 100644 index 0000000..2299b80 --- /dev/null +++ b/failurePy/visualization/oneDimensionalBeliefVisulaization.py @@ -0,0 +1,346 @@ +""" +File the makes a visualization of the evolution of the position and failure belief over time, +In a one dimensional experiment. Used to validate + + +""" +import os +import warnings +import matplotlib.pyplot as plt +from matplotlib import colormaps +import cv2 +import numpy as onp +import jax.numpy as jnp + +from failurePy.visualization.visualizationUtilityFunctions import loadBeliefData, setColorCyclerDistinct +from failurePy.visualization.renderPlanarVis import evalMultivariateGaussian + +#Ignore matplotlib warnings' +warnings.filterwarnings( "ignore", module = r"matplotlib\..*" ) + +#Going to just make the plots manually after the experiment, no need to modify pipeline this +def main(savedDataDirPath,experimentName,solverName,nSimulationsPerTree,outputPath,outputSubDirectory,nTrial=0): + """ + Function that gets the data from the specified experiment and generates a video of the belief evolution over time. + Intended to visualize the hardware demos + + Parameters + ---------- + savedDataDirPath : str + String of the absolute path to the saveDirectory for we are loading the experiment from. + experimentName : str + Name of the experiment we are loading + solverName : str + The solver to get the data from + nSimulationsPerTree: int + The number of simulations per tree to get data from. + outputPath : str + Path to where the output data should be saved. + outputSubDirectory : str + Sub directory to save the output data in + nTrial : int (default=None) + The trial to get the data from + """ + #Get the data loaded + beliefList,initialFailureParticles,failureState,physicalStateList = loadBeliefData(savedDataDirPath,experimentName,solverName,nSimulationsPerTree,nTrial) + + #Visualizing 1D belief + + makeBeliefTimeSeries(beliefList,initialFailureParticles,failureState,physicalStateList,dt=1,fps=10,outputPath=outputPath,outputSubDirectory=outputSubDirectory) + + + +#dt is universal, so making exception +def makeBeliefTimeSeries(beliefList,initialFailureParticles,failureState,physicalStateList,dt=1,fps=10,outputPath="~/Documents/BeliefVisualization",outputSubDirectory="TimeSeries"): # pylint: disable=invalid-name + """ + Makes time series of provided data, with transitions added in for smoothness. + Save video to the provided directory. Also uses this directory for temporary storage of the generated frames. + + Parameters + ---------- + beliefList : list + List of the beliefs at each time step, the failure particles (if there is any variation) are part of these tuples! + initialFailureParticles : array, shape(nMaxInitialFailureParticles,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + failureState : array, shape(numAct+numSen) + True failure state + physicalStateList : list + List of the physical states + dt : float (default=1) + The time between time steps of the experiment + fps : int (default=10) + The number of frames per second the video should be made with + outputPath : str (default="~/Documents/BeliefVisualization") + Path to where the output data should be saved. + outputSubDirectory : str (default="TimeSeries") + Sub directory to save the output data in + """ + + #Get the save directory + outputSubDirectory = os.path.join(outputPath,outputSubDirectory) + + if not os.path.exists(outputSubDirectory): + os.mkdir(outputSubDirectory) + + currentFailureParticles = initialFailureParticles + + #Loop through and make time step data, we'll average as we transition + for iData,beliefTuple in enumerate(beliefList): #Need to index directly for transitioning pylint: disable=consider-using-enumerate + #Check if we updated belief particles + if len(beliefTuple) == 3: + currentFailureParticles = beliefTuple[2] + #Plot each belief, will create transition below + fig = plotBeliefAndFailureParticles(beliefList[iData],currentFailureParticles,failureState,physicalStateList[iData],iData) + + #Save the figure as a png + figName = str(iData) + ".png" + + figPath = os.path.join(outputSubDirectory,figName) + + fig.savefig(figPath) + plt.close() + + + #for jFrame in range(dt*fps): + # #Transition smoothly if not the first frame + # if iData != 0 and jFrame/fps <= 1/4: + # beliefWeights = (.5 - 2*jFrame/fps) * beliefList[iData-1] + (2*jFrame/fps +.5) * beliefList[iData] + # elif iData != len(beliefList)-1 and jFrame/fps >= 3/4: + # beliefWeights = (1 - 2*(jFrame/fps - 3/4)) * beliefList[iData] + (2*(jFrame/fps - 3/4)) * beliefList[iData+1] + # else: + # beliefWeights = beliefList[iData] + + + + + + videoName = os.path.join(outputSubDirectory,'video.mp4') + + #This returns unsorted!! #[img for img in os.listdir(outputSubDirectory) if img.endswith(".png")] + + images = [] + for iImage in range(len(beliefList)): + imageSubPath = os.path.join(outputSubDirectory,str(iImage) + ".png") + images.append(cv2.imread(os.path.join(outputSubDirectory, imageSubPath))) + #Just get one frame to initialize video + height, width, dummyLayers = images[0].shape + video = cv2.VideoWriter(videoName, cv2.VideoWriter_fourcc(*'mp4v'), fps, (width,height)) # pylint: disable=no-member + + for iImage, currentImage in enumerate(images): + for jFrame in range(int(fps*dt)): + #Check for cross fades + if iImage != 0 and jFrame < fps/4: + previousImage = images[iImage-1] + frame = (.5 - 2*jFrame/fps) * previousImage + (2*jFrame/fps +.5) * currentImage + frame = frame.astype(onp.uint8) #CONVERT TO UINT8 here! + elif iImage != len(images)-1 and jFrame/fps >= 3/4: + nextImage = images[iImage+1] + frame = (1 - 2*(jFrame/fps - 3/4)) * currentImage + (2*(jFrame/fps - 3/4)) * nextImage + frame = frame.astype(onp.uint8) #CONVERT TO UINT8 here! + else: + frame = currentImage + + + video.write(frame) + + cv2.imshow('Frame',currentImage) # pylint: disable=no-member + + cv2.destroyAllWindows() # pylint: disable=no-member + video.release() + + +#Plot element wise failure weights (single frame). DON'T show, let calling function handle that, but return fig to save/close +def plotBeliefAndFailureParticles(beliefTuple,currentFailureParticles,failureState,physicalState,iExperimentStep): #Main plotting function, so pylint: disable=too-many-statements,too-many-branches + """ + Plots the likelihood of each possible failure scenario at the given time step + + Parameters + ---------- + beliefTuple : tuple + Tuple of failureParticleWeights, filters, (and failureParticles, if different from the initial failures) + currentFailureParticles : array, shape(nMaxInitialFailureParticles,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + failureState : array, shape(numAct+numSen) + True failure state + physicalState: array, shape(2) + The true position and velocity + + Returns + ------- + fig : matplotlib figure + Figure object with the failure likelihoods plotted. + """ + + #Assuming 4 actuators, 2 sensors, each which can fail or have bias, so we have 12 failure dimensions + #Going to visualize it as 6 different 2d plots for each dimension and colored particles, could get messy + + #Allows us to specify non-uniformly sized axes, A is a merged box for the belief + fig = plt.figure(layout="constrained",figsize=(15,10)) + axDict = fig.subplot_mosaic( + """ + AABDF + AACEG + """ + ) + + failureWeights = beliefTuple[0] + #print(failureWeights) + #filters = beliefTuple[1] #We know this is a 2d gaussian on position and velocity. + + positionX, positionY, pdfPositionBelief = evalBeliefGaussian(beliefTuple, physicalState, 100) + + beliefColorMap = colormaps["viridis"] #.copy() + #beliefColorMap.set_under('w') + #beliefColorMap.mappable.set_clim(vmin=.01) + #Masking out small values of belief to make it so the color map fades to white. + #pdfPositionBelief = pdfPositionBelief.at[jnp.where(pdfPositionBelief<.005)].set(-jnp.inf) + pdfPositionBelief = pdfPositionBelief.at[jnp.where(pdfPositionBelief<.005)].set(-jnp.inf) + beliefPlot = axDict["A"].contourf(positionX, positionY, pdfPositionBelief, cmap=beliefColorMap,zorder=-2)#,vmin=1000) #Should be under unsafe (-1) + beliefPlot.cmap.set_under('w') + beliefExtent = 7 + #Move frame as needed to follow belief + xOffset = (physicalState[0]+3.5)//beliefExtent + yOffset = (physicalState[1]+3.5)//beliefExtent + + axDict["A"].set_xlim(xmin=beliefExtent*(xOffset-1),xmax=beliefExtent*(xOffset+1)) + axDict["A"].set_ylim(ymin=beliefExtent*(yOffset-1),ymax=beliefExtent*(yOffset+1)) + axDict["A"].set_aspect("equal") + axDict["A"].set_xlabel("x [m]") + axDict["A"].set_ylabel("$v_x$ [m]") + axDict["A"].set_title(f"Time step {iExperimentStep}") + #Ground truth + axDict["A"].text(.05,.95,f"x={onp.round(physicalState[0],1)}, \nvx={onp.round(physicalState[1],1)}", + horizontalalignment='left',verticalalignment='center',transform = axDict["A"].transAxes) + axDict["A"].plot(physicalState[0],physicalState[1],"k+",markersize=20,alpha=.25) + + #Now plot the failure particles. Will use a tab color map + failureParticleBeliefAxes = ["B","C","D","E","F","G"] + components = ["-X1","-X2","+X1","+X2","S1","S2",] + componentIdxs = jnp.array([[0,4],[1,5],[2,6],[3,7],[8,10],[9,11]]) + + #Determine weighting of belief sizes. Min is going to be non zero so we can see it + minParticleSize = 0 + particleSizeRange = 15 + particleSizes = particleSizeRange* failureWeights + minParticleSize + print(failureWeights) + #Other particle visualization data + particleAlpha = .5 + numFailureParticles = len(currentFailureParticles) + #In this case, we don't have bias and are using old fault model will set biases all to zero, and convert models + if len(currentFailureParticles[0]) == 6: + zeroFailures = jnp.zeros((numFailureParticles,12)) + #Actuators + currentFailureParticles = zeroFailures.at[:,0:4].set(1-currentFailureParticles[:,0:4]) + #Sensors + currentFailureParticles = zeroFailures.at[:,8:10].set(1-currentFailureParticles[:,4:6]) + zeroFailure = jnp.zeros(12) + failureState = zeroFailure.at[0:6].set(1- failureState) + + #Get 5 closest particles + faultSpaceDistances = jnp.linalg.norm(currentFailureParticles - failureState,axis=1) + averageDistance = jnp.mean(faultSpaceDistances) + #This returns the array partitioned into 3 (unsorted) idxes of the smallest values, and the remaining (unsorted) idxes + partitionedDistanceIdxes = jnp.argpartition(faultSpaceDistances,4) + #So sort + idxesSortedPartition = jnp.argsort(faultSpaceDistances[partitionedDistanceIdxes[:5]]) + closestIdxes = partitionedDistanceIdxes[idxesSortedPartition] + + for iComponent in range(6): + ax = axDict[failureParticleBeliefAxes[iComponent]] + ax.set_xlabel("Degradation") + ax.set_ylabel("Bias") + ax.set_title(components[iComponent]) + setColorCyclerDistinct(numFailureParticles,ax) + + #Plot five closest particles in faults space, biggest is closest + maxMarkerRadius = 20 + for idx in closestIdxes: + closeFaultParticle = currentFailureParticles[idx] + ax.scatter(closeFaultParticle[componentIdxs[iComponent,0]],closeFaultParticle[componentIdxs[iComponent,1]], + s=(maxMarkerRadius * (1-faultSpaceDistances[idx]/averageDistance))**2,alpha=particleAlpha/2,marker="x",c="k") + + + + #Plot the failure particles for this component + for jFailureParticle,failureParticle in enumerate(currentFailureParticles): + + #print(currentFailureParticles[jFailureParticle]) + #print(componentIdxs[iComponent,1], currentFailureParticles[jFailureParticle,componentIdxs[iComponent,1]]) + #print(currentFailureParticles[jFailureParticle,10]) + ax.scatter(failureParticle[componentIdxs[iComponent,0]], + failureParticle[componentIdxs[iComponent,1]],s=jnp.square(particleSizes[jFailureParticle]),alpha=particleAlpha) + ax.set_xlim(xmin=-0.05,xmax=1.05) + ax.set_ylim(ymin=-0.05,ymax=1.05) + + #Plot true failure + ax.scatter(failureState[componentIdxs[iComponent,0]],failureState[componentIdxs[iComponent,1]], + s=20**2,alpha=particleAlpha/2,marker="+",c="k") + + #For examining plots without making movie + #plt.show() + + return fig + + +def evalBeliefGaussian(beliefTuple, physicalState, numMeshForPositionGaussian): + """ + Creates a multi modal Gaussian using each element of the belief tuple. + evalRegion is the sub set of the plot region that we evaluate the gaussian over, as not all of this region is necessarily interesting + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state. + positionGaussianExtent : float + Interesting region of the Gaussian, set to make computing more efficient. Currently not very well motivated + plotRegion : array, shape(2,2) + Bounds of the axis + physicalState : array, shape(numState) + Current physical state + numMeshForPositionGaussian : int + How fine the Gaussian mesh is. + rotationFlag : boolean (default=False) + Whether or not this is a 3DOF spacecraft + """ + + #We want to evaluate the gaussian near the peak of the belief, which we don't know directly + #We do however, expect the peak to be near the actual physical state of the s/c, so we can use this as our center. + physicalStateX = physicalState[0] + physicalStateVX = physicalState[1] + + # eval in "x" coordinates + beliefExtent=7 + evalX = jnp.linspace(-beliefExtent, beliefExtent, numMeshForPositionGaussian) + evalVX = jnp.linspace(-beliefExtent, beliefExtent, numMeshForPositionGaussian) + # Move eval region to area we expect the Gaussian to be significant over + evalX += physicalStateX + evalVX += physicalStateVX + evalMeshX, evalMeshY = jnp.meshgrid(evalX, evalVX) + evalPos = jnp.empty(evalMeshX.shape + (2,)) + evalPos = evalPos.at[:, :, 0].set(evalMeshX) + evalPos = evalPos.at[:, :, 1].set(evalMeshY) + + beliefPdf = 0 * evalMeshX + + #No need to mask here, as we have a 2-D posterior + + for (weight, positionFilter) in zip(beliefTuple[0], beliefTuple[1]): + physicalStateBeliefMean = positionFilter[0] + physicalStateBeliefCovariance = positionFilter[1:1+len(physicalStateBeliefMean)] + mean = physicalStateBeliefMean + sigma = 1e-3 * jnp.eye(2) + physicalStateBeliefCovariance + beliefPdf += weight * evalMultivariateGaussian(evalPos, mean, sigma) + + return evalX, evalVX, beliefPdf + +#If running directly +if __name__ == "__main__": + #Lab PC + SAVED_DATA_DIR_PATH = None #SET TO THE DIRECTORY YOU WISH TO VISUALIZE + visualizationOutputPath = None #SET WHERE YOU WANT THE OUTPUT DATA TO GO + + main(SAVED_DATA_DIR_PATH,experimentName="linearTest",solverName="PreSpecified",nSimulationsPerTree=200,outputPath=visualizationOutputPath,outputSubDirectory="Test",nTrial=2) diff --git a/failurePy/visualization/renderBeliefVideo.py b/failurePy/visualization/renderBeliefVideo.py new file mode 100644 index 0000000..7a3a314 --- /dev/null +++ b/failurePy/visualization/renderBeliefVideo.py @@ -0,0 +1,197 @@ +""" +File the makes a visualization of the evolution of the belief over time, used for visualizing the hardware experiments +""" + +import os +import warnings +import matplotlib.pyplot as plt +import numpy as np +import cv2 + +from failurePy.visualization.visualizationUtilityFunctions import loadBeliefData + +#Ignore matplotlib warnings' +warnings.filterwarnings( "ignore", module = r"matplotlib\..*" ) + +#Going to just make the plots manually +def main(savedDataDirPath,experimentName,solverName,nSimulationsPerTree,outputPath,outputSubDirectory,nTrial=0): + """ + Function that gets the data from the specified experiment and generates a video of the belief evolution over time. + Intended to visualize the hardware demos + + Parameters + ---------- + savedDataDirPath : str + String of the absolute path to the saveDirectory for we are loading the experiment from. + experimentName : str + Name of the experiment we are loading + solverName : str + The solver to get the data from + nSimulationsPerTree: int + The number of simulations per tree to get data from. + outputPath : str + Path to where the output data should be saved. + outputSubDirectory : str + Sub directory to save the output data in + nTrial : int (default=None) + The trial to get the data from + """ + #Get the data loaded + beliefList,possibleFailures,failureState, dummyPhysicalStates = loadBeliefData(savedDataDirPath,experimentName,solverName,nSimulationsPerTree,nTrial) + beliefWeightsList = [] + for belief in beliefList: + beliefWeightsList.append(belief[0]) + + #Testing movie making + makeTimeSeries(beliefWeightsList,possibleFailures,failureState,dt=1,fps=10,outputPath=outputPath,outputSubDirectory=outputSubDirectory) + +#dt is universal, so making exception +def makeTimeSeries(beliefWeightsList,possibleFailures,failureState,dt=1,fps=10,outputPath="~/Documents/BeliefVisualization",outputSubDirectory="TimeSeries"): # pylint: disable=invalid-name + """ + Makes time series of provided data, with transitions added in for smoothness. + Save video to the provided directory. Also uses this directory for temporary storage of the generated frames. + + Parameters + ---------- + beliefWeightsList : list + List of the failure probabilities for each time step's belief in beliefList + possibleFailures : array, shape(nMaxPossibleFailures,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + failureState : array, shape(numAct+numSen) + True failure state + dt : float (default=1) + The time between time steps of the experiment + fps : int (default=10) + The number of frames per second the video should be made with + outputPath : str (default="~/Documents/BeliefVisualization") + Path to where the output data should be saved. + outputSubDirectory : str (default="TimeSeries") + Sub directory to save the output data in + """ + + #Get the save directory + outputSubDirectory = os.path.join(outputPath,outputSubDirectory) + + if not os.path.exists(outputSubDirectory): + os.mkdir(outputSubDirectory) + + #Loop through and make frames, we'll average as we transition + for iData in range(len(beliefWeightsList)): #Need to index directly for transitioning pylint: disable=consider-using-enumerate + #Plot each frame + for jFrame in range(dt*fps): + #Transition smoothly if not the first frame + if iData != 0 and jFrame/fps <= 1/4: + beliefWeights = (.5 - 2*jFrame/fps) * beliefWeightsList[iData-1] + (2*jFrame/fps +.5) * beliefWeightsList[iData] + elif iData != len(beliefWeightsList)-1 and jFrame/fps >= 3/4: + beliefWeights = (1 - 2*(jFrame/fps - 3/4)) * beliefWeightsList[iData] + (2*(jFrame/fps - 3/4)) * beliefWeightsList[iData+1] + else: + beliefWeights = beliefWeightsList[iData] + + fig = plotElementFailureWeights(beliefWeights,possibleFailures,failureState) + + #Save the figure as a png + figName = str(iData*dt*fps+jFrame) + ".png" + + figPath = os.path.join(outputSubDirectory,figName) + + fig.savefig(figPath) + plt.close() + + + + videoName = os.path.join(outputSubDirectory,'video.mp4') + + images = [img for img in os.listdir(outputSubDirectory) if img.endswith(".png")] + frame = cv2.imread(os.path.join(outputSubDirectory, images[0])) # pylint: disable=no-member + height, width, dummyLayers = frame.shape + + video = cv2.VideoWriter(videoName, cv2.VideoWriter_fourcc(*'mp4v'), 10, (width,height)) # pylint: disable=no-member + + for image in images: + frame = cv2.imread(os.path.join(outputSubDirectory, image)) # pylint: disable=no-member + video.write(frame) + + cv2.imshow('Frame',frame) # pylint: disable=no-member + + cv2.destroyAllWindows() # pylint: disable=no-member + video.release() + + +#Plot element wise failure weights (single frame). DON'T show, let calling function handle that, but return fig to save/close +def plotElementFailureWeights(beliefWeights,possibleFailures,failureState): + """ + Plots the likelihood of each possible failure scenario at the given time step + + Parameters + ---------- + beliefWeights : array, shape(nMaxPossibleFailures) + Likelihood of each possible failure scenario + possibleFailures : array, shape(nMaxPossibleFailures,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + failureState : array, shape(numAct+numSen) + True failure state + + Returns + ------- + fig : matplotlib figure + Figure object with the failure likelihoods plotted. + """ + fig, ax = plt.subplots(nrows=1,ncols=1,figsize=(7.5,5)) #ax is used a lot with matplotlib so pylint: disable=invalid-name + #fig, ax = plt.subplots(nrows=1,ncols=1,figsize=(11.25,6)) + + #Need to calculate the weight on each actuator + componentFailureWeights = np.zeros(len(failureState)) + + for iPossibleFailure,possibleFailure in enumerate(possibleFailures): + beliefWeight = beliefWeights[iPossibleFailure] + componentFailureWeights += beliefWeight*possibleFailure + + #Flip to be failure probabilities + componentFailureWeights = 1 - componentFailureWeights + + #Hard code the labels + barXLabels = ["-X+Mθ","-X-Mθ","+X+Mθ","+X-Mθ","-Y+Mθ","-Y-Mθ","+Y+Mθ","+Y-Mθ","S1 X","S2 X","S3 Y","S4 Y","S5 θ","S6 θ"] + + xPositions = np.arange(len(barXLabels)) # the label locations + + #Now plot the bar chart + barPlot = ax.bar(xPositions,componentFailureWeights) #Unused if not annotating, pylint: disable=unused-variable + ax.set_ylabel('Failure Probability') + ax.set_title('Failure weight by component') + ax.set_xticks(xPositions) + ax.set_xticklabels(barXLabels,rotation = 45) + #ax.legend() + + ax.set_ylim([0, 1.1]) + + #Optional labeling of each bar with the current hight, can make the plot busy. + #autoLabel(barPlot,ax) + + return fig + + +def autoLabel(barPlotRectangles,ax): #ax is used a lot with matplotlib so pylint: disable=invalid-name + """ + Attach a text label above each bar in rectangles, displaying its height. + Used for annotating bar graphs. + + Parameters + ---------- + rectangles : matplotlib BarContainer + Bar plot rectangles to annotate + ax : matplotlib axis + Bar plot axis to annotate on. + """ + for rect in barPlotRectangles: + height = rect.get_height() + ax.annotate(f'{height:.2f}', + xy=(rect.get_x() + rect.get_width() / 2, height), + xytext=(0, 3), # 3 points vertical offset + textcoords="offset points", + ha='center', va='bottom') + +#If running directly +if __name__ == "__main__": + SAVED_DATA_DIR_PATH = "/home/trey/Documents/SimLogs/simulation/SavedData/" + + main(SAVED_DATA_DIR_PATH,experimentName="12 movie 5",solverName="realTimeSFEAST",nSimulationsPerTree=100,outputPath="/home/trey/Documents/BeliefVisualization",outputSubDirectory="TimeSeries") diff --git a/failurePy/visualization/renderPlanarVis.py b/failurePy/visualization/renderPlanarVis.py new file mode 100644 index 0000000..153f25c --- /dev/null +++ b/failurePy/visualization/renderPlanarVis.py @@ -0,0 +1,725 @@ +""" +Old render_2d_vis.py file from v1, converted to match v2 conventions for clarity. + +Main method moved to wrapper + +Some other minor changes to improve readability/remove unused code +""" +import os.path +import numpy as np +import matplotlib.pyplot as plt +from matplotlib.patches import Rectangle, Circle, Polygon, ConnectionStyle, FancyArrowPatch +from matplotlib.transforms import Affine2D +from matplotlib.colors import LinearSegmentedColormap +from matplotlib.backends.backend_pdf import PdfPages +from matplotlib.collections import LineCollection +from matplotlib.cm import get_cmap +import cv2 + + +plt.rcParams.update({'font.size': 10}) + +#ax is widely used with matplotlib for axis, so will make an exception. Similarly lots of plotting lines so we have an exception for number of statements. +def drawSpacecraft(physicalState, action, beliefTuple, possibleFailures, rootNode, ax, plottingBounds, legendFlag=False,futureAction=None,rotationFlag=False): # pylint: disable=invalid-name,too-many-statements + """ + Function that draws a rendition of a planar spacecraft. Now renders in a "mini-map" like section of the plot, + to better show scale. + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state + action : array, shape(numAct) + Action taken to get to this state. + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures,numAct+numSen) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state. + OVERLOAD: Reused to hold a ground truth flag as GroundTruth for plotting the true failure + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are sorted over this + rootNode : BeliefNode + Root node of the tree that is constructed to plan the next action + ax : matplotlib axis + Axis to draw s/c in + plottingBounds : array, shape(2,2) + Bounds of the axis + scale : float (default=20) + How much the s/c should be scaled up + legendFlag : boolean (default=False) + Whether or not a legend is shown + futureAction : array, shape(numAct) (default=None) + If provided, the action that will be taken next + rotationFlag : boolean (default=False) + Whether or not this is a 3DOF spacecraft + """ + # check whether we are plotting ground truth or experiment + groundTruthFlag = bool(isinstance(beliefTuple[1],str) and beliefTuple[1] == "groundTruth") + + numAct, numSen = getNumActNumSen(rotationFlag,action) + + edgecolor = "black" + linewidth = 0.2 + treeColor = "xkcd:dark gray" #"white"#"xkcd:dark gray" + failureThreshold = 0.22 #This is the maximum failure chance that a component can have before it starts to show as red. (ie, 22% failure chance shows as white) + numMeshForPositionGaussian = 200 #How many points in each axis will be sampled when making the position Gaussian + positionGaussianExtent = 5 # what is interesting gaussian region? + + # make special colormap, using our threshold to set the linear scaling on the colors. Currently 0-.78 -> red - white. .78-1 -> white to green + colorMapColors = ["red","white","green"] + anchorValues = [0,1-failureThreshold,1.] + colorMapAnchorPointList = list(zip(anchorValues,colorMapColors)) + failureBeliefColorMap = LinearSegmentedColormap.from_list('rg',colorMapAnchorPointList, N=256) + + # get failure probabilities: + failureProbabilities = computeComponentFailureProbabilities(beliefTuple, possibleFailures, numAct, numSen) + + #Now instead going to always transform to same spot, except for small icon to indicate spot (just small version of s/c?) + + + #Translate to upper right corner, use plotting bounds to set this to top third and right third + #Set scale to 1/4 of axis size (worst case) + xSize = plottingBounds[0,1]-plottingBounds[0,0] + ySize = plottingBounds[1,1]-plottingBounds[1,0] + miniMapBodyScale = np.min([xSize/5,ySize/5]) + #Draw box and background as 1/3 of axis size. z order or artist order? + miniMapBackgroundSize = miniMapBodyScale*5/3 + miniMapXUpperRight = xSize/6 *5 - miniMapBackgroundSize/2 + plottingBounds[0,0]#Referenced off the bottom left corner! + miniMapYUpperRight = ySize/6 *5 - miniMapBackgroundSize/2 + plottingBounds[1,0] + + #Disable belief and safety only + miniMapBackground = Rectangle((miniMapXUpperRight,miniMapYUpperRight), miniMapBackgroundSize, miniMapBackgroundSize, + facecolor="gainsboro", alpha=1, edgecolor=edgecolor, linewidth=linewidth) + ax.add_artist(miniMapBackground) +# + miniMapBodyXUpperRight = xSize/6 *5 - miniMapBodyScale/2 + plottingBounds[0,0]#Referenced off the bottom left corner! + miniMapBodyYUpperRight = ySize/6 *5 - miniMapBodyScale/2 + plottingBounds[1,0] + + #Set rotation to 0 if not 3DOF + if rotationFlag: + angle = physicalState[4] + else: + angle = 0 + + #Draw minimap (disable for belief and safety only) + _drawAndScaleSpacecraft(miniMapBodyScale,miniMapBodyXUpperRight, miniMapBodyYUpperRight,edgecolor,linewidth,numAct,numSen,failureBeliefColorMap, + failureProbabilities,action,futureAction,angle,ax) + + #Draw actual size s/c, 1 meter size + bodyXUpperRight = physicalState[0]-1/2 + bodyYUpperRight = physicalState[2]-1/2 + bodyScale = 1 + #Disable for belief and safety only and hardware vis of mini map + _drawAndScaleSpacecraft(bodyScale,bodyXUpperRight, bodyYUpperRight,edgecolor,linewidth,numAct,numSen,failureBeliefColorMap, + failureProbabilities,action,futureAction,angle,ax,simple=True) + + #Draw mini s/c to scale, scale down safety region to match! + + # Translate between drawing frame and physical frame (as artist frame origin is spacecraft lower left corner) + #bodyXUpperRight = physicalState[0]-bodyScale/2 + #bodyYUpperRight = physicalState[2]-bodyScale/2 + #print(bodyXUpperRight,bodyYUpperRight,bodyScale) + + + #Plot physical state x,y as a circle of radius 1 (trying smaller .1 to make it easier to see ) + #ax.add_artist(Circle((physicalState[0],physicalState[2]),radius=.1, + # facecolor="black", edgecolor="black", linewidth=linewidth)) + + #Actual size spacecraft is shown as just a tick instead + #ax.vlines(x=physicalState[0], ymin=physicalState[2]-.5, ymax=physicalState[2]+.5, linewidth=.2, color="k") + #ax.hlines(y=physicalState[2], xmin=physicalState[0]-.5, xmax=physicalState[0]+.5, linewidth=.2, color="k") + #Dot instead? + ax.plot(physicalState[0],physicalState[2],"ko",markersize=.1) + + # position belief + if not groundTruthFlag: + plotPositionBelief(ax,positionGaussianExtent,physicalState,beliefTuple,numMeshForPositionGaussian) + + # tree + if rootNode is not None: + tree = rootNodeToTree(rootNode) + segments = treeToSegments(tree) + lineCollection = LineCollection(segments, + linewidth=1.5, colors=treeColor, alpha=0.15, zorder=-10) + ax.add_collection(lineCollection) + + ax.set_xlim(plottingBounds[0,:]) + ax.set_ylim(plottingBounds[1,:]) + ax.set_aspect("equal") + ax.set_xlabel("x [m]") + ax.set_ylabel("y [m]") + + #Set background color to transparent + ax.set_alpha(0) + + if legendFlag: + _makeLegend(ax) + + #Theta label (in degrees) add this to help with seeing the current orientation + #x,y label added too to see drifts + #Disable on belief and safety only and hardware + if not groundTruthFlag: #Don't show this for the first case, since we aren't moving + plt.text(.05,.95,f"x={np.round(physicalState[0],1)}, y={np.round(physicalState[2],1)}\nvx={np.round(physicalState[1],1)},vy={np.round(physicalState[3],1)}", + horizontalalignment='left',verticalalignment='center',transform = ax.transAxes) + if rotationFlag: + plt.text(.05,.88,fr"$\theta$={np.round(np.rad2deg(physicalState[4]),1)}°",horizontalalignment='left',verticalalignment='center',transform = ax.transAxes) + plt.text(.05,.84,fr"$\omega$={np.round(np.rad2deg(physicalState[5]),1)}°/s",horizontalalignment='left',verticalalignment='center',transform = ax.transAxes) + + #Label sensors + if groundTruthFlag: + plt.text(.25,.75,"") + +def _drawAndScaleSpacecraft(bodyScale,bodyXUpperRight, bodyYUpperRight,edgecolor,linewidth,numAct,numSen,failureBeliefColorMap, + failureProbabilities,action,futureAction,angle,ax,simple=False): # pylint: disable=invalid-name + """ + Helper function that draws and positions the spacecraft as desired. + """ + #bodyScale = scale + artists = _drawSpacecraftComponents(bodyScale,edgecolor,linewidth,numAct,numSen,failureBeliefColorMap,failureProbabilities,action,futureAction,simple) + + #Apply rotation + transform = Affine2D().translate(bodyXUpperRight, bodyYUpperRight) + #Add rotations if we are considering them (if not, angle will be 0) + + #Theta is in radians, rotate around center. center seems to have been set to the bottom left corner of the s/c so moving back to center of mass + transform = transform.rotate_around(bodyXUpperRight+bodyScale/2,bodyYUpperRight+bodyScale/2,angle) + for artist in artists: + artist.set_transform(transform + ax.transData) + # add to ax + for artist in artists: + ax.add_artist(artist) + +def _drawSpacecraftComponents(scale,edgecolor,linewidth,numAct,numSen,failureBeliefColorMap,failureProbabilities,action,futureAction=None,simple=False): + """ + Sub method to draw each component of the spacecraft. + """ + + # body + bodyLength = scale + bodyColor="white" + if simple: + bodyAlpha = .5 + else: + bodyAlpha = 1 + + bodyCenterXY = (0,0) + bodyRectangle = Rectangle(bodyCenterXY, bodyLength, bodyLength, + facecolor=bodyColor, alpha=bodyAlpha, edgecolor=edgecolor, linewidth=linewidth) + + if simple: + return [bodyRectangle] + + # actuators + actuatorRectangles, actuationTriangles, futureActuationTriangles = _drawActuators(scale,bodyLength,numAct,failureBeliefColorMap,failureProbabilities,edgecolor,linewidth,action,futureAction) + + # sensors + sensorCircles = _drawSensors(scale,bodyLength,numAct,numSen,failureBeliefColorMap,failureProbabilities,edgecolor,linewidth) + + #Show which way was originally +y + upArrowXY = np.array([1/4* bodyLength, 15/16 *bodyLength]) + upArrow = FancyArrowPatch(posA=upArrowXY-np.array([0,1/4*bodyLength]),posB=upArrowXY,arrowstyle="->",mutation_scale=5) + + ##Hardware vis, want to point to -X now + #upArrowXY = np.array([1/16 *bodyLength,1/4* bodyLength]) + #upArrow = FancyArrowPatch(posA=upArrowXY+np.array([1/4*bodyLength,0]),posB=upArrowXY,arrowstyle="->",mutation_scale=5) + + # #Apply rotation + #transform = Affine2D().translate(bodyXUpperRight, bodyYUpperRight) + ##Add rotations if we are considering them (if not, angle will be 0) +# + ##Theta is in radians, rotate around center. center seems to have been set to the bottom left corner of the s/c so moving back to center of mass + #transform = transform.rotate_around(bodyXUpperRight+bodyScale/2,bodyYUpperRight+bodyScale/2,angle) + #for artist in artists: + # artist.set_transform(transform + ax.transData) + + + if futureAction is not None: + # make master artist list + artists = [bodyRectangle, *actuatorRectangles, *sensorCircles, upArrow, *actuationTriangles, *futureActuationTriangles] + else: + # make master artist list + artists = [bodyRectangle, *actuatorRectangles, *sensorCircles, upArrow, *actuationTriangles] + return artists + +def _drawActuators(scale,bodyLength,numAct,failureBeliefColorMap,failureProbabilities,edgecolor,linewidth,action,futureAction=None): + """ + Sub method to draw actuators and actuator firings + """ + actuatorScale = scale * 1/8 + actuatorLength = actuatorScale + actuatorXYs = _getActuatorXYs(bodyLength,actuatorScale) + actuatorRectangles = [] + for iActuator in range(numAct): + actuatorColor = failureBeliefColorMap(1-failureProbabilities[iActuator]) + actuatorAlpha = 1.0 + actuatorRectangle = Rectangle(actuatorXYs[iActuator], + actuatorLength, actuatorLength, + facecolor=actuatorColor, alpha=actuatorAlpha, + edgecolor=edgecolor, linewidth=linewidth) + actuatorRectangles.append(actuatorRectangle) + + # actuation! + magicNum = np.sqrt(2)/2 + actuationPoints = actuatorScale * np.array([ + [0,0], + [1,0], + [0.5, magicNum]]) + arcPoints = 2*actuatorScale * np.array([ + [-.25,-.7], + [.75,-.7]]) + actuationRotations = [90, 90, 270, 270, 180, 180, 0, 0,90,270] + + actuationShifts,futureActuationShifts = _getActuationShifts(magicNum,actuatorScale) + + actuationTriangles = _drawActuation(numAct,action,actuationPoints,arcPoints,actuationRotations,actuatorXYs,actuationShifts) + + #Plot the action we will take (usually too much information) + if futureAction is not None: + futureActuationTriangles = _drawActuation(numAct,futureAction,actuationPoints,arcPoints,actuationRotations,actuatorXYs,futureActuationShifts) + else: + futureActuationTriangles = None + + return actuatorRectangles, actuationTriangles, futureActuationTriangles + +def _actuationRotationMatrix(theta): + """ + Computes a rotation matrix for the given theta. + """ + return np.array([[np.cos(theta), np.sin(theta)],[-np.sin(theta), np.cos(theta)]]) + +def _getActuatorXYs(bodyLength,actuatorScale): + """ + Sub method to make defining the XYs cleaner to read + """ + actuatorXYs = [ #All the positions to put the actuators as. Note if we have less actuators, the wheels just get left off! + (bodyLength, 5/8 * bodyLength), #FX-MZ+ + (bodyLength, 1/4 * bodyLength), #FX-MZ- + (-1 * actuatorScale, 1/4 * bodyLength), #FX+MZ+ + (-1 * actuatorScale, 5/8 * bodyLength), #FX+MZ- + (1/4 * bodyLength, bodyLength), #FY-MZ+ + (5/8 * bodyLength, bodyLength), #FY-MZ- + (5/8 * bodyLength, -1 * actuatorScale), #FY+MZ+ + (1/4 * bodyLength, -1 * actuatorScale), #FY+MZ- + (5/8 *bodyLength,7/16 * bodyLength), #Wheel locations + (bodyLength/4,7/16 * bodyLength), + ] + return actuatorXYs + +def _getActuationShifts(magicNum,actuatorScale): + """ + Sub method to make defining the shifts cleaner to read + """ + actuationShifts = [ + (magicNum * actuatorScale + actuatorScale, 0), + (magicNum * actuatorScale + actuatorScale, 0), + (-magicNum*actuatorScale, actuatorScale), + (-magicNum*actuatorScale, actuatorScale), + (actuatorScale, magicNum*actuatorScale+actuatorScale), + (actuatorScale, magicNum*actuatorScale+actuatorScale), + (0, -magicNum*actuatorScale), + (0, -magicNum*actuatorScale), + (magicNum * actuatorScale - actuatorScale, 0),#Wheel shifts + (-magicNum*actuatorScale + 2*actuatorScale, actuatorScale), + ] + + futureActuationShifts = [ + (.5*magicNum * actuatorScale + actuatorScale, 0), + (.5*magicNum * actuatorScale + actuatorScale, 0), + (-magicNum*.5*actuatorScale, actuatorScale), + (-magicNum*.5*actuatorScale, actuatorScale), + (actuatorScale, .5*magicNum*actuatorScale+actuatorScale), + (actuatorScale, .5*magicNum*actuatorScale+actuatorScale), + (0, -magicNum*.5*actuatorScale), + (0, -magicNum*.5*actuatorScale), + (magicNum *.5* actuatorScale + actuatorScale, 0),#Wheel shifts + (-magicNum *.5*actuatorScale, actuatorScale), + ] + return actuationShifts,futureActuationShifts + +def _drawActuation(numAct,action,actuationPoints,arcPoints,actuationRotations,actuatorXYs,actuationShifts,futureAction=False): + """ + Sub method to draw actuations + """ + actuationTriangles = [] + for iActuator in range(numAct): + #Add in arc!! + if np.abs(action[iActuator]) > 1e-3: #Wheel actions can be negative + if iActuator >= 8: + points = arcPoints @ _actuationRotationMatrix(actuationRotations[iActuator]*np.pi/180) + actuatorXYs[iActuator] + points += actuationShifts[iActuator] + #If u negative reverse direction + if action[iActuator] < 0: + #points = points[::-1] + style = "->" + else: + style = "<-" + #Positive increases to the wheel speed is negative torque + actuationArrow = FancyArrowPatch(posA=points[0],posB=points[1],arrowstyle=style,connectionstyle=ConnectionStyle.Arc3(rad=.5),mutation_scale=5) + actuationTriangles.append(actuationArrow) + else: + # if True: + # print("ii_a") + points = actuationPoints @ _actuationRotationMatrix(actuationRotations[iActuator]*np.pi/180) + actuatorXYs[iActuator] + points += actuationShifts[iActuator] + if futureAction: + actuationTri = Polygon(points, closed=True, fill=True, color="orange",alpha=.3) + else: + actuationTri = Polygon(points, closed=True, fill=True, color="orange") + actuationTriangles.append(actuationTri) + return actuationTriangles + + +def _drawSensors(scale,bodyLength,numAct,numSen,failureBeliefColorMap,failureProbabilities,edgecolor,linewidth): + """ + Sub method to draw sensors + """ + sensorScale = scale * 1/8 + sensorRadius = sensorScale + sensorXYs = [ + (0,0), + (bodyLength,0), + (bodyLength,bodyLength), + (0,bodyLength), + (bodyLength/2,bodyLength/2 + 2*sensorScale), #Rotation Sensors + (bodyLength/2,bodyLength/2 - 2*sensorScale), + ] + #Use this to differentiate x vs y sensors + #sensorHatches = ["x","x",None,None,None,None] + sensorHatches = [None,None,None,None,None,None] + sensorCircles = [] + for iSensor in range(numSen): + sensorColor = failureBeliefColorMap(1-failureProbabilities[iSensor + numAct]) + sensorAlpha = 1.0 + sensorCircle = Circle(sensorXYs[iSensor],radius=sensorRadius, + facecolor=sensorColor, alpha=sensorAlpha, + edgecolor=edgecolor, linewidth=linewidth,hatch=sensorHatches[iSensor]) + sensorCircles.append(sensorCircle) + return sensorCircles + +#ax is widely used with matplotlib for axis, so will make an exception +def plotPositionBelief(ax,positionGaussianExtent,physicalState,beliefTuple,numMeshForPositionGaussian): # pylint: disable=invalid-name + """ + Sub method for plotting the position belief distribution + + Parameters + ---------- + ax : matplotlib axis + Axis to draw s/c in + positionGaussianExtent : float + Interesting region of the Gaussian, set to make computing more efficient. Currently not very well motivated + physicalState : array, shape(numState) + Current physical state + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures,numAct+numSen) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state. + numMeshForPositionGaussian : int + How fine the Gaussian mesh is. + """ + #First plot background of zeros (so everything looks the same, as no longer scaling up the gaussian) + #plotX = np.linspace(plottingBounds[0,0], plottingBounds[0,1], numMeshForPositionGaussian) + #plotY = np.linspace(plottingBounds[1,0], plottingBounds[1,1], numMeshForPositionGaussian) + #plotMeshX, plotMeshY = np.meshgrid(plotX, plotY) + + #Trying to be more presentable + #ax.contourf(plotMeshX, plotMeshY, 0*plotMeshX, zorder=-1,colors=['#481B6D']) + #ax.contourf(plotMeshX, plotMeshY, 0*plotMeshX, zorder=-1,colors=['#FFFFFF']) + + #No longer scaling up + positionX, positionY, pdfPositionBelief = evalMultimodalGaussian2(beliefTuple, positionGaussianExtent, physicalState, numMeshForPositionGaussian) + #Setting background to white for cleaner plot + beliefColorMap = get_cmap("viridis") #.copy() + #beliefColorMap.set_under('w') + #beliefColorMap.mappable.set_clim(vmin=.01) + #Masking out small values of belief to make it so the color map fades to white. + #pdfPositionBelief = pdfPositionBelief.at[np.where(pdfPositionBelief<.005)].set(-np.inf) + pdfPositionBelief[np.where(pdfPositionBelief<.005)] = -np.inf + beliefPlot = ax.contourf(positionX, positionY, pdfPositionBelief, cmap=beliefColorMap,zorder=-2)#,vmin=1000) #Should be under unsafe (-1) + beliefPlot.cmap.set_under('w') + #beliefPlot.cmap.set_under('w') #Looking at color.py, think I need to interrupt normalization somehow + #beliefPlot.cmap.set_clim(vmin=.01) + + #beliefPlot = ax.contourf(positionX, positionY, pdfPositionBelief,zorder=0) + #beliefColorMap = plt.colorbar(beliefPlot) + #beliefColorMap.set_under('w') + #beliefColorMap.mappable.set_clim(vmin=.01) + +def _makeLegend(ax): # pylint: disable=invalid-name + """ + Sub method to make legend for the plot + """ + legendActuator, = ax.plot(np.nan, np.nan, color="white", marker="s", markeredgecolor="black", linestyle="None") + legendSensor, = ax.plot(np.nan, np.nan, color="white", marker="o", markeredgecolor="black", linestyle="None") + legendActuation, = ax.plot(np.nan, np.nan, color="orange", marker="^", linestyle="None") + legendFail, = ax.plot(np.nan, np.nan, color="red", marker="o", linestyle="None") + legendNominal, = ax.plot(np.nan, np.nan, color="green", marker="o", linestyle="None") + ax.legend( + [legendActuator, legendSensor, legendActuation, legendFail, legendNominal], + ["Actuator", "Sensor", "Control Input", "Fault", "Nominal"] + ) + +def translateArray(arrayToTranslate, shiftX, shiftY): + """ + Translates the array by the specified amount + """ + # create the translation matrix using tx and ty, it is a NumPy array + width, height = arrayToTranslate.shape[0], arrayToTranslate.shape[1] + translationMatrix = np.array([ + [1, 0, shiftX], + [0, 1, shiftY] + ], dtype=np.float32) + arrayToTranslate = cv2.warpAffine(src=arrayToTranslate, M=translationMatrix, dsize=(width, height)) # pylint: disable=no-member + return arrayToTranslate + + +def evalMultivariateGaussian(pos, mean, sigma): + """Return the multivariate Gaussian distribution on array pos.""" + dim = mean.shape[0] + sigmaDeterminate = np.linalg.det(sigma) + sigmaInverse = np.linalg.inv(sigma) + normalization = np.sqrt((2*np.pi)**dim * sigmaDeterminate) + # This einsum call calculates (x-mu)T.Sigma-1.(x-mu) in a vectorized + # way across all the input variables. + intermediateExponentTerm = np.einsum('...k,kl,...l->...', pos-mean, sigmaInverse, pos-mean) + return np.exp(-1* intermediateExponentTerm / 2) / normalization + +def evalMultimodalGaussian2(beliefTuple, positionGaussianExtent, physicalState, numMeshForPositionGaussian): + """ + Creates a multi modal Gaussian using each element of the belief tuple. + evalRegion is the sub set of the plot region that we evaluate the gaussian over, as not all of this region is necessarily interesting + + Parameters + ---------- + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures,numAct+numSen) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state. + positionGaussianExtent : float + Interesting region of the Gaussian, set to make computing more efficient. Currently not very well motivated + plotRegion : array, shape(2,2) + Bounds of the axis + physicalState : array, shape(numState) + Current physical state + numMeshForPositionGaussian : int + How fine the Gaussian mesh is. + rotationFlag : boolean (default=False) + Whether or not this is a 3DOF spacecraft + """ + + #We want to evaluate the gaussian near the peak of the belief, which we don't know directly + #We do however, expect the peak to be near the actual physical state of the s/c, so we can use this as our center. + physicalStateX = physicalState[0] + physicalStateY = physicalState[2] + + # eval in "x" coordinates + evalX = np.linspace(-positionGaussianExtent, positionGaussianExtent, numMeshForPositionGaussian) + evalY = np.linspace(-positionGaussianExtent, positionGaussianExtent, numMeshForPositionGaussian) + # Move eval region to area we expect the Gaussian to be significant over + evalX += physicalStateX + evalY += physicalStateY + evalMeshX, evalMeshY = np.meshgrid(evalX, evalY) + evalPos = np.empty(evalMeshX.shape + (2,)) + evalPos[:, :, 0] = evalMeshX + evalPos[:, :, 1] = evalMeshY + + #plotX = np.linspace(plotRegion[0,0], plotRegion[0,1], numMeshForPositionGaussian) + #plotY = np.linspace(plotRegion[1,0], plotRegion[1,1], numMeshForPositionGaussian) + #plotMeshX, plotMeshY = np.meshgrid(plotX, plotY) + + beliefPdf = 0 * evalMeshX + #Pick out variables to plot gaussian on, always x and y, so mask out the rest. + gaussianMask = np.zeros((2,len(physicalState))) + gaussianMask[0,0] = 1 + gaussianMask[1,2] = 1 + gaussianMask=gaussianMask.T + #Old way, not robust + #if not rotationFlag: + # gaussianMask = np.array([[1,0,0,0],[0,0,1,0]]).T + #else: + # gaussianMask = np.array([[1,0,0,0,0,0,0,0],[0,0,1,0,0,0,0,0]]).T + for (weight, positionFilter) in zip(beliefTuple[0], beliefTuple[1]): + physicalStateBeliefMean = positionFilter[0] + physicalStateBeliefCovariance = positionFilter[1:1+len(physicalStateBeliefMean)] + mean = physicalStateBeliefMean @ gaussianMask + sigma = 1e-3 * np.eye(2) + gaussianMask.T @ physicalStateBeliefCovariance @ gaussianMask + beliefPdf += weight * evalMultivariateGaussian(evalPos, mean, sigma) + + # compute "shift" coordinates in pixels of plotMeshX + #plotDx = plotX[1] - plotX[0] # pixel per x + #plotDy = plotY[1] - plotY[0] + #beliefPdf = translateArray(beliefPdf, physicalStateX / plotDx, physicalStateY / plotDy) + return evalX, evalY, np.array(beliefPdf) + +def computeComponentFailureProbabilities(beliefTuple, possibleFailures, numActuators, numSensors): + """ + Sums over the weighted possible failures to get the component wise possible failures + """ + componentFailureProbabilities = np.zeros(numActuators+numSensors) + for jFailure,possibleFailure in enumerate(possibleFailures): + for iComponent,component in enumerate(possibleFailure): + #Check if this component failed in this belief + if component == 0: + #Add to weighting + + componentFailureProbabilities[iComponent] += beliefTuple[0][jFailure] + return componentFailureProbabilities + +def computeMean(belief): + """ + Computes the mean of the provided belief + """ + mean = 0.0 + for (weight, kalmanFilter) in zip(belief[0], belief[1]): + mean += weight * kalmanFilter[0] #First row is average + return mean + +def rootNodeToTree(rootNode): + """ + Takes the root node of a tree data structure and converts into a list of each node and their parent + """ + tree = [] + toAdd = [(rootNode,-1)] + while len(toAdd) > 0: + currentNode, parentIdx = toAdd.pop(0) + #Added in v2 compatibility, will have belief tuple if v2 + if hasattr(currentNode, 'beliefTuple'): + row = [currentNode.beliefTuple, parentIdx] + tree.append(row) + parentIdx = len(tree) - 1 + for decisionChild in currentNode.children: + for beliefChild in decisionChild.children: + toAdd.append((beliefChild,parentIdx)) + #No longer supporting v1 trees + else: + incompatibleTree = "The rootNode is a type that is unsupported by the current version of failurePy." + raise ValueError(incompatibleTree) + return tree + +def treeToSegments(tree): + """ + Takes a tree structure and returns the segments that make up each branch + """ + segments = [] + for row in tree: + belief = row[0] + parentIdx = row[1] + mean = computeMean(belief) + if parentIdx >= 0: + parentMean = computeMean(tree[parentIdx][0]) + segments.append([[mean[0],mean[2]],[parentMean[0],parentMean[2]]]) + return segments + +def plotUnsafeRegions(ax,safetyFunctionF,plottingBounds,resolution=200): + """ + Function that overlays on the visualization any unsafe region. + It does so by evaluating the safetyConstrainedRewardF at a grid of points using a fake belief + + Parameters + ---------- + ax : matplotlib axis + Axis to draw s/c in + safetyFunctionF : function + Constraints that physical states must satisfy to be safe. Returns 1 if safe, 0 if not. + plottingBounds : array, shape(2,2) + Bounds of the axis + resolution : int (default=200) + How high of a resolution the safe zone should be drawn in. + """ + + #Use custom color map to set obstacles (obstacleSafeZ=0) to red, and all other to transparent. + #Each channel specified separately, each row is an anchor point, with before and after values specified + colorMapDict = {'red': [(0.0, 1.0, 1.0), + (1.0, 1.0, 1.0)], + 'green': [(0.0, 0.0, 0.0), + (1.0, 1.0, 1.0)], + 'blue': [(0.0, 0.0, 0.0), + (1.0, 1.0, 1.0)], + 'alpha': [(0.0, 0.5, 0.5), + (1.0, 0.0, 0.0)],} + + + obstacleMaskColorMap = LinearSegmentedColormap('obstacleMask',colorMapDict) + + #Get points to evaluate over + xMesh,yMesh = getMeshOverPlottingBounds(plottingBounds,resolution) + + ##Make "meshed" physical states + #meshedPhysicalStates = np.array([xMesh,0*xMesh,yMesh,0*yMesh]) + + obstacleSafeZ = np.zeros((resolution,resolution)) + #Split based on safetyFunctionF type + if safetyFunctionF.__name__ == "worstCaseSafetyFunctionF": + for iXCord in range(resolution): + for jYCord in range(resolution): + #Note that our thinking of cartesian 2d arrays is flipped! so jYCord gives the columns, while iXCord gives the rows! + safetyReturn = safetyFunctionF(np.array([xMesh[0,iXCord],0,yMesh[jYCord,0],0])) + if np.sign(safetyReturn) == -1: + obstacleSafeZ[jYCord,iXCord] = 1 + else: + obstacleSafeZ[jYCord,iXCord] = 0 + else: + for iXCord in range(resolution): + for jYCord in range(resolution): + #Note that our thinking of cartesian 2d arrays is flipped! so jYCord gives the columns, while iXCord gives the rows! + obstacleSafeZ[jYCord,iXCord] = safetyFunctionF(np.array([xMesh[0,iXCord],0,yMesh[jYCord,0],0])) + + ax.contourf(xMesh, yMesh, obstacleSafeZ, cmap=obstacleMaskColorMap,zorder=-1) #Should be over position belief (-2) + +def getMeshOverPlottingBounds(plottingBounds,numMeshPointsPerAxis): + """ + Function that returns a mesh given the plotting bounds and number of points + + Parameters + ---------- + plottingBounds : array, shape(2,2) + Bounds of the axis + numMeshPointsPerAxis : int + How fine the mesh is. + + Returns + xMesh : array, shape(numMeshPointsPerAxis,numMeshPointsPerAxis) + x-dimension of the mesh + yMesh : array, shape(numMeshPointsPerAxis,numMeshPointsPerAxis) + y-dimension of the mesh + """ + + plotX = np.linspace(plottingBounds[0,0], plottingBounds[0,1], numMeshPointsPerAxis) + plotY = np.linspace(plottingBounds[1,0], plottingBounds[1,1], numMeshPointsPerAxis) + xMesh, yMesh = np.meshgrid(plotX, plotY) + return xMesh,yMesh + + +def getNumActNumSen(rotationFlag,action): + """ + Helper method to set the numAct and numSen variables + """ + #Number of sensor or actuators is pre set + if rotationFlag: + numSen = 6 + else: + numSen = 6 #Add two rotation sensors + + numAct = len(action) + + return numAct, numSen + +def saveFigs(fileName,savePngs=False): + """ + Saves the generated figures as a pdf to given file name. Optionally save to pngs too + """ + outputPdf = PdfPages(fileName) + for iFigure in plt.get_fignums(): + figure = plt.figure(iFigure) + outputPdf.savefig(figure,dpi=1000,facecolor=figure.get_facecolor(), edgecolor='none',transparent=True) + #Save pngs if needed + if savePngs: + saveDirectory = os.path.join(os.path.dirname(fileName),"pngs") + figure.savefig(os.path.join(saveDirectory,str(iFigure)+".png")) + plt.close(figure) + outputPdf.close() diff --git a/failurePy/visualization/renderPlanarVisGeneralFault.py b/failurePy/visualization/renderPlanarVisGeneralFault.py new file mode 100644 index 0000000..4c01416 --- /dev/null +++ b/failurePy/visualization/renderPlanarVisGeneralFault.py @@ -0,0 +1,449 @@ +""" +Old render_2d_vis.py file from v1, converted to match v2 conventions for clarity. + +Main method moved to wrapper + +Some other minor changes to improve readability/remove unused code +""" +import numpy as np +import matplotlib.pyplot as plt +from matplotlib.patches import Rectangle, Circle, Polygon, ConnectionStyle, FancyArrowPatch +from matplotlib.transforms import Affine2D +from matplotlib.colors import LinearSegmentedColormap +from matplotlib.collections import LineCollection +from failurePy.visualization.renderPlanarVis import plotPositionBelief,getNumActNumSen,rootNodeToTree,treeToSegments + +plt.rcParams.update({'font.size': 10}) + +#ax is widely used with matplotlib for axis, so will make an exception. Similarly lots of plotting lines so we have an exception for number of statements. +def drawSpacecraft(physicalState, action, beliefTuple, possibleFailures, rootNode, ax, plottingBounds, legendFlag=False,rotationFlag=False): # pylint: disable=invalid-name,too-many-statements + """ + Function that draws a rendition of a planar spacecraft. Now renders in a "mini-map" like section of the plot, + to better show scale. + + Parameters + ---------- + physicalState : array, shape(numState) + Current physical state + action : array, shape(numAct) + Action taken to get to this state. + beliefTuple : tuple + The belief is represented by an array of failureWeights and the filter array corresponding to each possibleFailure. Contains: + failureWeights : array, shape(maxPossibleFailures,numAct+numSen) + Normalized weighting of the relative likelihood of each failure + filters : array + Array of conditional filters on the physical state. + OVERLOAD: Reused to hold a ground truth flag as GroundTruth for plotting the true failure + possibleFailures : array, shape(maxPossibleFailures,numAct+numSen) + Array of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are sorted over this + rootNode : BeliefNode + Root node of the tree that is constructed to plan the next action + ax : matplotlib axis + Axis to draw s/c in + plottingBounds : array, shape(2,2) + Bounds of the axis + scale : float (default=20) + How much the s/c should be scaled up + legendFlag : boolean (default=False) + Whether or not a legend is shown + futureAction : array, shape(numAct) (default=None) + If provided, the action that will be taken next + rotationFlag : boolean (default=False) + Whether or not this is a 3DOF spacecraft + """ + # check whether we are plotting ground truth or experiment + groundTruthFlag = bool(isinstance(beliefTuple[1],str) and beliefTuple[1] == "groundTruth") + + numAct, numSen = getNumActNumSen(rotationFlag,action) + + edgecolor = "black" + linewidth = 0.2 + treeColor = "xkcd:dark gray" #"white"#"xkcd:dark gray" + failureThreshold = .5 #This is the maximum failure chance that a component can have before it starts to show as red. + numMeshForPositionGaussian = 200 #How many points in each axis will be sampled when making the position Gaussian + positionGaussianExtent = 10 # what is interesting gaussian region? + + # make special colormap, using our threshold to set the linear scaling on the colors. Currently 0-.78 -> red - white. .78-1 -> white to green + colorMapColors = ["green","white","red"] # Now 0 deg/bias is good! + anchorValues = [0,1-failureThreshold,1.] + colorMapAnchorPointList = list(zip(anchorValues,colorMapColors)) + failureBeliefColorMap = LinearSegmentedColormap.from_list('rg',colorMapAnchorPointList, N=256) + + # get failure probabilities: + componentExpectedDegradation,componentExpectedBiases = computeComponentExpectedDegradationAndBiases(beliefTuple, possibleFailures, numAct, numSen) + print("weights: ", beliefTuple[0], + "\n expected degradation: ",componentExpectedDegradation, + "\n expected biases", componentExpectedBiases,) + + #Now instead going to always transform to same spot, except for small icon to indicate spot (just small version of s/c?) + + + #Translate to upper right corner, use plotting bounds to set this to top third and right third + #Set scale to 1/4 of axis size (worst case) + xSize = plottingBounds[0,1]-plottingBounds[0,0] + ySize = plottingBounds[1,1]-plottingBounds[1,0] + miniMapBodyScale = np.min([xSize/5,ySize/5]) + #Draw box and background as 1/3 of axis size. z order or artist order? + miniMapBackgroundSize = miniMapBodyScale*5/3 + miniMapXUpperRight = xSize/6 *5 - miniMapBackgroundSize/2 + plottingBounds[0,0]#Referenced off the bottom left corner! + miniMapYUpperRight = ySize/6 *5 - miniMapBackgroundSize/2 + plottingBounds[1,0] + + #Disable belief and safety only + miniMapBackground = Rectangle((miniMapXUpperRight,miniMapYUpperRight), miniMapBackgroundSize, miniMapBackgroundSize, + facecolor="gainsboro", alpha=1, edgecolor=edgecolor, linewidth=linewidth) + ax.add_artist(miniMapBackground) +# + miniMapBodyXUpperRight = xSize/6 *5 - miniMapBodyScale/2 + plottingBounds[0,0]#Referenced off the bottom left corner! + miniMapBodyYUpperRight = ySize/6 *5 - miniMapBodyScale/2 + plottingBounds[1,0] + + #Set rotation to 0 if not 3DOF + if rotationFlag: + angle = physicalState[4] + else: + angle = 0 + + #Draw minimap (disable for belief and safety only) + _drawAndScaleSpacecraft(miniMapBodyScale,miniMapBodyXUpperRight, miniMapBodyYUpperRight,edgecolor,linewidth,numAct,numSen,failureBeliefColorMap, + componentExpectedDegradation,componentExpectedBiases,action,angle,ax) + + #Draw actual size s/c, 1 meter size + bodyXUpperRight = physicalState[0]-1/2 + bodyYUpperRight = physicalState[2]-1/2 + bodyScale = 1 + #Disable for belief and safety only and hardware vis of mini map + _drawAndScaleSpacecraft(bodyScale,bodyXUpperRight, bodyYUpperRight,edgecolor,linewidth,numAct,numSen,failureBeliefColorMap, + componentExpectedDegradation,componentExpectedBiases,action,angle,ax,simple=True) + + #Draw mini s/c to scale, scale down safety region to match! + + # Translate between drawing frame and physical frame (as artist frame origin is spacecraft lower left corner) + #bodyXUpperRight = physicalState[0]-bodyScale/2 + #bodyYUpperRight = physicalState[2]-bodyScale/2 + #print(bodyXUpperRight,bodyYUpperRight,bodyScale) + + + #Plot physical state x,y as a circle of radius 1 (trying smaller .1 to make it easier to see ) + #ax.add_artist(Circle((physicalState[0],physicalState[2]),radius=.1, + # facecolor="black", edgecolor="black", linewidth=linewidth)) + + #Actual size spacecraft is shown as just a tick instead + #ax.vlines(x=physicalState[0], ymin=physicalState[2]-.5, ymax=physicalState[2]+.5, linewidth=.2, color="k") + #ax.hlines(y=physicalState[2], xmin=physicalState[0]-.5, xmax=physicalState[0]+.5, linewidth=.2, color="k") + #Dot instead? + ax.plot(physicalState[0],physicalState[2],"ko",markersize=.1) + + # position belief + if not groundTruthFlag: + plotPositionBelief(ax,positionGaussianExtent,physicalState,beliefTuple,numMeshForPositionGaussian) + + # tree + if rootNode is not None: + tree = rootNodeToTree(rootNode) + segments = treeToSegments(tree) + lineCollection = LineCollection(segments, + linewidth=1.5, colors=treeColor, alpha=0.15, zorder=-10) + ax.add_collection(lineCollection) + + ax.set_xlim(plottingBounds[0,:]) + ax.set_ylim(plottingBounds[1,:]) + ax.set_aspect("equal") + ax.set_xlabel("x [m]") + ax.set_ylabel("y [m]") + + #Set background color to transparent + ax.set_alpha(0) + + if legendFlag: + _makeLegend(ax) + + #Theta label (in degrees) add this to help with seeing the current orientation + #x,y label added too to see drifts + #Disable on belief and safety only and hardware + if not groundTruthFlag: #Don't show this for the first case, since we aren't moving + plt.text(.05,.95,f"x={np.round(physicalState[0],1)}, y={np.round(physicalState[2],1)}\nvx={np.round(physicalState[1],1)},vy={np.round(physicalState[3],1)}", + horizontalalignment='left',verticalalignment='center',transform = ax.transAxes) + if rotationFlag: + plt.text(.05,.88,fr"$\theta$={np.round(np.rad2deg(physicalState[4]),1)}°",horizontalalignment='left',verticalalignment='center',transform = ax.transAxes) + plt.text(.05,.84,fr"$\omega$={np.round(np.rad2deg(physicalState[5]),1)}°/s",horizontalalignment='left',verticalalignment='center',transform = ax.transAxes) + + #Label sensors + if groundTruthFlag: + plt.text(.25,.75,"") + +def _drawAndScaleSpacecraft(bodyScale,bodyXUpperRight, bodyYUpperRight,edgecolor,linewidth,numAct,numSen,failureBeliefColorMap, + componentExpectedDegradation,componentExpectedBiases,action,angle,ax,simple=False): # pylint: disable=invalid-name + """ + Helper function that draws and positions the spacecraft as desired. + """ + #bodyScale = scale + artists = _drawSpacecraftComponents(bodyScale,edgecolor,linewidth,numAct,numSen,failureBeliefColorMap,componentExpectedDegradation,componentExpectedBiases,action,simple) + + #Apply rotation + transform = Affine2D().translate(bodyXUpperRight, bodyYUpperRight) + #Add rotations if we are considering them (if not, angle will be 0) + + #Theta is in radians, rotate around center. center seems to have been set to the bottom left corner of the s/c so moving back to center of mass + transform = transform.rotate_around(bodyXUpperRight+bodyScale/2,bodyYUpperRight+bodyScale/2,angle) + for artist in artists: + artist.set_transform(transform + ax.transData) + # add to ax + for artist in artists: + ax.add_artist(artist) + +def _drawSpacecraftComponents(scale,edgecolor,linewidth,numAct,numSen,failureBeliefColorMap,componentExpectedDegradation,componentExpectedBiases,action,simple=False): + """ + Sub method to draw each component of the spacecraft. + """ + + # body + bodyLength = scale + bodyColor="white" + if simple: + bodyAlpha = .5 + else: + bodyAlpha = 1 + + bodyCenterXY = (0,0) + bodyRectangle = Rectangle(bodyCenterXY, bodyLength, bodyLength, + facecolor=bodyColor, alpha=bodyAlpha, edgecolor=edgecolor, linewidth=linewidth) + + if simple: + return [bodyRectangle] + + # actuators + actuatorRectangles, actuationTriangles, actuationBiasTriangles = _drawActuators(scale,bodyLength,numAct,failureBeliefColorMap,componentExpectedDegradation, + componentExpectedBiases,edgecolor,linewidth,action) + + # sensors + sensorCircles,sensorBiasArrows = _drawSensors(scale,bodyLength,numAct,numSen,failureBeliefColorMap,componentExpectedDegradation,componentExpectedBiases,edgecolor,linewidth) + + ##Show which way was originally +y + #upArrowXY = np.array([1/4* bodyLength, 15/16 *bodyLength]) + #upArrow = FancyArrowPatch(posA=upArrowXY-np.array([0,1/4*bodyLength]),posB=upArrowXY,arrowstyle="->",mutation_scale=5) + + #Hardware vis, want to point to -X now + upArrowXY = np.array([1/16 *bodyLength,1/4* bodyLength]) + upArrow = FancyArrowPatch(posA=upArrowXY+np.array([1/4*bodyLength,0]),posB=upArrowXY,arrowstyle="->",mutation_scale=5) + + # #Apply rotation + #transform = Affine2D().translate(bodyXUpperRight, bodyYUpperRight) + ##Add rotations if we are considering them (if not, angle will be 0) +# + ##Theta is in radians, rotate around center. center seems to have been set to the bottom left corner of the s/c so moving back to center of mass + #transform = transform.rotate_around(bodyXUpperRight+bodyScale/2,bodyYUpperRight+bodyScale/2,angle) + #for artist in artists: + # artist.set_transform(transform + ax.transData) + + # make master artist list + artists = [bodyRectangle, *actuatorRectangles, *sensorCircles,*sensorBiasArrows, upArrow, *actuationTriangles, *actuationBiasTriangles] + return artists + +def _drawActuators(scale,bodyLength,numAct,failureBeliefColorMap,componentExpectedDegradation,componentExpectedBiases,edgecolor,linewidth,action): + """ + Sub method to draw actuators and actuator firings + """ + actuatorScale = scale * 1/8 + actuatorLength = actuatorScale + actuatorXYs = _getActuatorXYs(bodyLength,actuatorScale) + actuatorRectangles = [] + for iActuator in range(numAct): + #actuatorColor = failureBeliefColorMap(1-componentExpectedDegradation[iActuator]) + actuatorColor = failureBeliefColorMap(componentExpectedDegradation[iActuator]) + actuatorAlpha = 1.0 + actuatorRectangle = Rectangle(actuatorXYs[iActuator], + actuatorLength, actuatorLength, + facecolor=actuatorColor, alpha=actuatorAlpha, + edgecolor=edgecolor, linewidth=linewidth) + actuatorRectangles.append(actuatorRectangle) + + # actuation! + magicNum = np.sqrt(2)/2 + actuationPoints = actuatorScale * np.array([ + [0,0], + [1,0], + [0.5, magicNum]]) + arcPoints = 2*actuatorScale * np.array([ + [-.25,-.7], + [.75,-.7]]) + actuationRotations = [90, 90, 270, 270, 180, 180, 0, 0,90,270] + + actuationShifts,biasActuationShifts = _getActuationShifts(magicNum,actuatorScale) + + actuationTriangles,actuationBiasTriangles = _drawActuation(numAct,action,actuationPoints,arcPoints,actuationRotations,actuatorXYs,actuationShifts,componentExpectedBiases,biasActuationShifts) + + + + return actuatorRectangles, actuationTriangles, actuationBiasTriangles + +def _actuationRotationMatrix(theta): + """ + Computes a rotation matrix for the given theta. + """ + return np.array([[np.cos(theta), np.sin(theta)],[-np.sin(theta), np.cos(theta)]]) + +def _getActuatorXYs(bodyLength,actuatorScale): + """ + Sub method to make defining the XYs cleaner to read + """ + actuatorXYs = [ #All the positions to put the actuators as. Note if we have less actuators, the wheels just get left off! + (bodyLength, 5/8 * bodyLength), #FX-MZ+ + (bodyLength, 1/4 * bodyLength), #FX-MZ- + (-1 * actuatorScale, 1/4 * bodyLength), #FX+MZ+ + (-1 * actuatorScale, 5/8 * bodyLength), #FX+MZ- + (1/4 * bodyLength, bodyLength), #FY-MZ+ + (5/8 * bodyLength, bodyLength), #FY-MZ- + (5/8 * bodyLength, -1 * actuatorScale), #FY+MZ+ + (1/4 * bodyLength, -1 * actuatorScale), #FY+MZ- + (5/8 *bodyLength,7/16 * bodyLength), #Wheel locations + (bodyLength/4,7/16 * bodyLength), + ] + return actuatorXYs + +def _getActuationShifts(magicNum,actuatorScale): + """ + Sub method to make defining the shifts cleaner to read + """ + actuationShifts = [ + (magicNum * actuatorScale + actuatorScale, 0), + (magicNum * actuatorScale + actuatorScale, 0), + (-magicNum*actuatorScale, actuatorScale), + (-magicNum*actuatorScale, actuatorScale), + (actuatorScale, magicNum*actuatorScale+actuatorScale), + (actuatorScale, magicNum*actuatorScale+actuatorScale), + (0, -magicNum*actuatorScale), + (0, -magicNum*actuatorScale), + (magicNum * actuatorScale - actuatorScale, 0),#Wheel shifts + (-magicNum*actuatorScale + 2*actuatorScale, actuatorScale), + ] + + biasActuationShifts = [ + (.5*magicNum * actuatorScale + actuatorScale, 0), + (.5*magicNum * actuatorScale + actuatorScale, 0), + (-magicNum*.5*actuatorScale, actuatorScale), + (-magicNum*.5*actuatorScale, actuatorScale), + (actuatorScale, .5*magicNum*actuatorScale+actuatorScale), + (actuatorScale, .5*magicNum*actuatorScale+actuatorScale), + (0, -magicNum*.5*actuatorScale), + (0, -magicNum*.5*actuatorScale), + (-magicNum *.5* actuatorScale + actuatorScale, 0),#Wheel shifts + (+magicNum *.5*actuatorScale, actuatorScale), + ] + return actuationShifts,biasActuationShifts + +def _drawActuation(numAct,action,actuationPoints,arcPoints,actuationRotations,actuatorXYs,actuationShifts,componentExpectedBiases,biasActuationShifts): + """ + Sub method to draw actuations + """ + actuationTriangles = [] + actuationBiases = [] + for iActuator in range(numAct): + biasAlpha = componentExpectedBiases[iActuator] + if np.isnan(biasAlpha): + biasAlpha=1 + print("nan biases detected") + + if iActuator >= 8: + points = arcPoints @ _actuationRotationMatrix(actuationRotations[iActuator]*np.pi/180) + actuatorXYs[iActuator] + biasPoints = points + biasActuationShifts[iActuator] + if np.abs(action[iActuator]) > 1e-3: #Wheel actions can be negative + wheelArrowPoints = points + actuationShifts[iActuator] + #If u negative reverse direction + if action[iActuator] < 0: + #points = points[::-1] + style = "->" + else: + style = "<-" + #Positive increases to the wheel speed is negative torque + actuationArrow = FancyArrowPatch(posA=wheelArrowPoints[0],posB=wheelArrowPoints[1],arrowstyle=style,connectionstyle=ConnectionStyle.Arc3(rad=.5),mutation_scale=5) + actuationTriangles.append(actuationArrow) + + #Bias arrow if one exits (always positive for now) + actuationBiasArrow = FancyArrowPatch(posA=biasPoints[0],posB=biasPoints[1],arrowstyle="<-",connectionstyle=ConnectionStyle.Arc3(rad=.5),mutation_scale=5, + facecolor="r",edgecolor="r",alpha=biasAlpha) + actuationBiases.append(actuationBiasArrow) + else: + # if True: + # print("ii_a") + points = actuationPoints @ _actuationRotationMatrix(actuationRotations[iActuator]*np.pi/180) + actuatorXYs[iActuator] + biasPoints = points + biasActuationShifts[iActuator] + if action[iActuator] > 1e-3: + thrusterJetPoints = points + actuationShifts[iActuator] + actuationTri = Polygon(thrusterJetPoints, closed=True, fill=True, color="orange") + actuationTriangles.append(actuationTri) + actuationBiasTri = Polygon(biasPoints, closed=True, fill=True, color="red",alpha=biasAlpha) + actuationBiases.append(actuationBiasTri) + return actuationTriangles,actuationBiases + + +def _drawSensors(scale,bodyLength,numAct,numSen,failureBeliefColorMap,componentExpectedDegradation,componentExpectedBiases,edgecolor,linewidth): + """ + Sub method to draw sensors + """ + sensorScale = scale * 1/8 + sensorRadius = sensorScale + sensorXYs = [ + (0,0), + (bodyLength,0), + (bodyLength,bodyLength), + (0,bodyLength), + (bodyLength/2,bodyLength/2 + 2*sensorScale), #Rotation Sensors + (bodyLength/2,bodyLength/2 - 2*sensorScale), + ] + #Use this to differentiate x vs y sensors + #sensorHatches = ["x","x",None,None,None,None] + sensorHatches = [None,None,None,None,None,None] + sensorCircles = [] + biasArrows = [] + for iSensor in range(numSen): + #sensorColor = failureBeliefColorMap(1-componentExpectedDegradation[iSensor + numAct]) + sensorColor = failureBeliefColorMap(componentExpectedDegradation[iSensor + numAct]) + sensorAlpha = 1.0 + sensorCircle = Circle(sensorXYs[iSensor],radius=sensorRadius, + facecolor=sensorColor, alpha=sensorAlpha, + edgecolor=edgecolor, linewidth=linewidth,hatch=sensorHatches[iSensor]) + sensorCircles.append(sensorCircle) + biasAlpha = componentExpectedBiases[iSensor + numAct] + if np.isnan(biasAlpha): + biasAlpha=1 + print("nan biases detected") + + biasArrow = FancyArrowPatch(posA=sensorXYs[iSensor]+np.array([-1/3*sensorRadius,0]),posB=sensorXYs[iSensor]+np.array([sensorRadius,0]), + arrowstyle="-|>",mutation_scale=5,facecolor="r",edgecolor="k",alpha=biasAlpha) + biasArrows.append(biasArrow) + return sensorCircles,biasArrows + +def _makeLegend(ax): # pylint: disable=invalid-name + """ + Sub method to make legend for the plot + """ + legendActuator, = ax.plot(np.nan, np.nan, color="white", marker="s", markeredgecolor="black", linestyle="None") + legendSensor, = ax.plot(np.nan, np.nan, color="white", marker="o", markeredgecolor="black", linestyle="None") + legendActuation, = ax.plot(np.nan, np.nan, color="orange", marker="^", linestyle="None") + legendFail, = ax.plot(np.nan, np.nan, color="red", marker="o", linestyle="None") + legendNominal, = ax.plot(np.nan, np.nan, color="green", marker="o", linestyle="None") + ax.legend( + [legendActuator, legendSensor, legendActuation, legendFail, legendNominal], + ["Actuator", "Sensor", "Control Input", "Fault", "Nominal"] + ) + + + +def computeComponentExpectedDegradationAndBiases(beliefTuple, possibleFailures, numActuators, numSensors): + """ + Sums over the weighted possible failures to get the component wise possible failures + """ + componentExpectedDegradation = np.zeros(numActuators+numSensors) + componentExpectedBiases = np.zeros(numActuators+numSensors) + for jFailure,possibleFailure in enumerate(possibleFailures): + for iComponent,component in enumerate(possibleFailure): + #Weighted average of the component degradation and biases + #Need to factor in that in that failure is currently actDeg, actBiases, senDeg, senBiases + if iComponent < numActuators: + componentExpectedDegradation[iComponent] += component*beliefTuple[0][jFailure] + elif iComponent < 2*numActuators: + componentExpectedBiases[iComponent-numActuators] += component*beliefTuple[0][jFailure] + elif iComponent < 2*numActuators + numSensors: + componentExpectedDegradation[iComponent-numActuators] += component*beliefTuple[0][jFailure] + else: + componentExpectedBiases[iComponent-numActuators-numSensors] += component*beliefTuple[0][jFailure] + return componentExpectedDegradation,componentExpectedBiases diff --git a/failurePy/visualization/renderPlanarVisWrapper.py b/failurePy/visualization/renderPlanarVisWrapper.py new file mode 100644 index 0000000..e663cc2 --- /dev/null +++ b/failurePy/visualization/renderPlanarVisWrapper.py @@ -0,0 +1,640 @@ +""" +File that wraps renderPlanarVis.py to use visualization code with new data structure with minimal re-writing. +""" +import os +import subprocess +import pickle +import numpy as onp #Will convert to onp arrays here (after all experiments are done) +import matplotlib.pyplot as plt +from tqdm import tqdm +from jax import random as jaxRandom +from jax import numpy as jnp +from failurePy.visualization import renderPlanarVis, renderPlanarVisGeneralFault +from failurePy.utility.saving import checkOrMakeDirectory + +def visualizeFirstTrajectory(saveDirectoryPath,experimentParamsDict,outputFilePath=None,regenTree=0): + """ + Function that takes experiment ResultsList and grabs the first trial result to visualize + + Parameters + ---------- + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + experimentParams : dict + Relevant parameters are: + nSimulationsPerTreeList : list, len(numTrials) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + dt : float + The time between time steps of the experiment + solverNamesList: list + List of names of solvers, for data logging + rngKeysOffset : int + Offset to the initial PRNG used in generating the initial failure states and randomness in the trials. This is added to the trial number to allow for different trials to be preformed + outputFilePath : str (default=None) + Path to where the output file should be saved. If it doesn't exist, default used + regenTree : int (default=0) + Recreates a plausible tree given the belief and simulation level. No tree drawn when one already exists + or when the value is 0 + """ + + visualizeNthTrajectory(saveDirectoryPath,experimentParamsDict,outputFilePath,regenTree=regenTree) + +#dt is universal, so making exception +def visualizeNthTrajectory(saveDirectoryPath,experimentParamsDict,outputFilePath,hardwareFlag=False,regenTree=0): # pylint: disable=invalid-name + """ + Function that takes experiment ResultsList and grabs the nth trial result to visualize + + Parameters + ---------- + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + experimentParams : dict + Relevant parameters are: + nSimulationsPerTreeList : list, len(numTrials) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + dt : float + The time between time steps of the experiment + solverNamesList: list + List of names of solvers, for data logging + rngKeysOffset : int + Offset to the initial PRNG used in generating the initial failure states and randomness in the trials. This is added to the trial number to allow for different trials to be preformed + outputFilePath : str (default=None) + Path to where the output file should be saved. If it doesn't exist, default used + hardwareFlag : bool (default=False) + Flag to indicate this is date from the hardware. + NOTE: this isn't quite working yet unfortunately, mostly because we don't have the needed data from hardware + regenTree : int (default=0) + Recreates a plausible tree given the belief and simulation level. No tree drawn when one already exists + or when the value is 0 + """ + + solverName = experimentParamsDict["solverNamesList"][0] + nSimulationsPerTree = experimentParamsDict["nSimulationsPerTreeList"][0] + nTrial=experimentParamsDict["rngKeysOffset"] + dt=experimentParamsDict["dt"] + safetyFunctionF=experimentParamsDict["safetyFunctionF"] + plottingBounds=experimentParamsDict["plottingBounds"] + resolution=experimentParamsDict["resolution"] + + #Get data and pass on + trialResultsDict = loadNthTrialResults(saveDirectoryPath,solverName,nSimulationsPerTree,nTrial,regenTree,experimentParamsDict) + + if hardwareFlag: #Currently bounds and resolution not configurable here, since hardcoded for now + visualizeHardwareTrajectory(trialResultsDict,dt,outputFilePath,safetyFunctionF) + else: + visualizeSingleTrajectory(trialResultsDict,dt,outputFilePath,safetyFunctionF,plottingBounds,resolution) + +def loadNthTrialResults(saveDirectoryPath,solverName,nSimulationsPerTree,nTrial,regenTree=0,experimentParamsDict=None): + """ + Loads the data from the specified trial and returns it + + Parameters + ---------- + saveDirectoryPath : str + String of the absolute path to the saveDirectory for the results of the experiment. Auto determined from the experiment parameters, unless overwritten. + solverName : str + The solver to get the data from + nSimulationsPerTree: int + The number of simulations per tree to get data from. + nTrial : int + The trial to get the data from + regenTree : int (default=0) + Recreates a plausible tree given the belief and simulation level. No tree drawn when one already exists + or when the value is 0 + experimentParams : dict (default=None) + Experiment parameters needed when regenerating tree + + Returns + ------- + trialResultsDict : dict + Dictionary with the stored trial results + """ + solverDirectoryPath = os.path.join(saveDirectoryPath,solverName) + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + nTrialPath = os.path.join(nSimPath,str(nTrial)) + trialDataPath = os.path.join(nTrialPath,"trialData.dict") + with open(trialDataPath, "rb") as trialDataFile: + trialResultsDict = pickle.load(trialDataFile) + + #Check if we need to make a new tree + existingTreeList = False + if "treeList" in trialResultsDict: + dataTreeList = trialResultsDict["treeList"] + if len(dataTreeList) != 1 or dataTreeList[0] is not None: + existingTreeList = True + + if regenTree and not existingTreeList: + #Check for cache + cacheFilePath = os.path.join(nTrialPath,"regenTreeCache.pckl") + if os.path.exists(cacheFilePath): + with open(cacheFilePath, "rb") as rootNodeDataFile: + rootNodeList = pickle.load(rootNodeDataFile) + else: + if experimentParamsDict is None: + experimentParamsDictRequired = "experimentParamsDict must be provided to regenerate the tree" + raise ValueError(experimentParamsDictRequired) + rootNodeList = regenTreeFromData(trialResultsDict,experimentParamsDict,numSimulations=regenTree) + #Cache for future plotting + with open(cacheFilePath, "wb") as rootNodeDataFile: + pickle.dump(rootNodeList,rootNodeDataFile) + trialResultsDict["treeList"] = rootNodeList + + return trialResultsDict + +#dt is universal, so making exception +def visualizeSingleTrajectory(trialDataDict,dt=1,outputFilePath=None,safetyFunctionF=None,plottingBounds=None,resolution=200,showFig=True): # pylint: disable=invalid-name + """ + Function that renders the trajectory of one trial, using the wrapped renderPlanarVis.py functions. + + Parameters + ---------- + trialDataDict : dict + Dict with trial results nested. All arrays are jax jnp arrays + physicalStateList : list + List of the (realized) physical states of the system + failureStateList : list + List of the (unchanging) true failure state + beliefList : list + List of the beliefs at each time step (time steps determined by nExperimentSteps and dt, which is currently set in the system model) + ASSUMES MARGINALIZED FILTER BELIEF AND KALMAN BELIEF + rewardList : list + List of the rewards at each time step + actionList : list + List of the actions taken at each time step + treeList: list + List of the tree data at each time step. Each element is a tuple with the nodeList and the valuesRewardsVisitsArray for the tree + possibleFailures : array, shape(nMaxPossibleFailures,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + dt : float (default=1) + The time between time steps of the experiment + outputFilePath : str (default=None) + Path to where the output file should be saved. If it doesn't exist, default used + safetyFunctionF : function (default=None) + Constraints that physical states must satisfy to be safe. Returns 1 if safe, 0 if not. + plottingBounds : array, shape(2,2) (default=None) + Bounds of the axis + resolution : int (default=200) + How high of a resolution the safe zone should be drawn in. + showFig : boolean (default=True) + Shows the trajectory when rendering finishes + """ + + #We need to convert arrays to numpy arrays + + #print("making physical states") + physicalStates = onp.zeros((len(trialDataDict["physicalStateList"]),len(trialDataDict["physicalStateList"][0]))) + + numPhysicalStates =len(physicalStates[0]) + rotationFlag = bool(numPhysicalStates > 4) + + + #Check if we can render with existing tools + + #Conditions we can render are dim == 2 (numState=4) or (dim==3 (numState=6/8(wheels)) and linear) + if not ((numPhysicalStates == 4 and not rotationFlag) or (numPhysicalStates == 6 and rotationFlag) or (numPhysicalStates == 8 and rotationFlag)): + print("Cannot visualize this experiment configuration") + print(numPhysicalStates,rotationFlag) + return + + #print("making actions") + actions = onp.zeros((len(trialDataDict["actionList"]),len(trialDataDict["actionList"][0]))) + #print("making possible failures") + possibleFailures = onp.zeros((len(trialDataDict["possibleFailures"]),len(trialDataDict["possibleFailures"][0]))) + + #print("wrapping physical states") + for iState,physicalState in enumerate(trialDataDict["physicalStateList"]): + physicalStates[iState] = onp.array(physicalState) + + #print("wrapping actions") + for iAction,action in enumerate(trialDataDict["actionList"]): + actions[iAction] = onp.array(action) + + #print("wrapping possible failures") + for iFailure,possibleFailure in enumerate(trialDataDict["possibleFailures"]): + possibleFailures[iFailure] = onp.array(possibleFailure) + + #print("wrapping failure state") + failureState = onp.array(trialDataDict["failureStateList"][0]) + + #Display success code + print(f"Success code: {trialDataDict['success']}") + + times = onp.arange(0,dt*len(physicalStates),dt) + #times = onp.arange(0,dt*25,dt) #Visualize only some times + + if "treeList" in trialDataDict: + rootNodeList = trialDataDict["treeList"] + #Check for nones, some inconsistency with real time code here + if rootNodeList[0] is None: + rootNodeList = None + else: + rootNodeList = None + + #No longer need to wrap the belief + beliefList = trialDataDict["beliefList"] + + renderPlanarVisWrapper(physicalStates,failureState,actions,beliefList,times,rootNodeList,possibleFailures,plottingBounds=plottingBounds,rotationFlag=rotationFlag, + outputFilePath=outputFilePath,safetyFunctionF=safetyFunctionF,resolution=resolution,showFig=showFig) + +#dt is universal, so making exception +def visualizeHardwareTrajectory(trialDataDict,dt=1,outputFilePath=None): # pylint: disable=invalid-name + """ + Function that renders the trajectory of hardware experiment, using the wrapped renderPlanarVis.py functions. + Current hardware data isn't enough to use this + + Parameters + ---------- + trialDataDict : dict + Dict with trial results nested. All arrays are jax jnp arrays + physicalStateList : list + List of the (realized) physical states of the system + failureStateList : list + List of the (unchanging) true failure state + beliefList : list + List of the beliefs at each time step (time steps determined by nExperimentSteps and dt, which is currently set in the system model) + ASSUMES MARGINALIZED FILTER BELIEF AND KALMAN BELIEF + rewardList : list + List of the rewards at each time step + actionList : list + List of the actions taken at each time step + treeList: list + List of the tree data at each time step. Each element is a tuple with the nodeList and the valuesRewardsVisitsArray for the tree + possibleFailures : array, shape(nMaxPossibleFailures,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + dt : float (default=1) + The time between time steps of the experiment + outputFilePath : str (default=None) + Path to where the output file should be saved. If it doesn't exist, default used + """ + + #We will interpolate to make the transition seem smoother + interpolationFactor = 10 + + physicalStates, actions, possibleFailures = wrapStatesActionsFailures(trialDataDict,interpolationFactor) + + #print("wrapping failure state") + failureState = onp.array(trialDataDict["failureStateList"][0]) + + #Display success code + print(f"Success code: {trialDataDict['success']}") + + times = onp.arange(0,dt*trialDataDict["physicalStateList"],dt) + + if "treeList" in trialDataDict: + originalRootNodeList = trialDataDict["treeList"] + #Need to show tree for interpolated states + rootNodeList = [] + for rootNode in originalRootNodeList: + #Check for initial None, as previous versions of visualization showed the tree to get to a state, + #we want to show tree to get to NEXT state + if rootNode is None: + continue + + for jInterpolatedState in range(interpolationFactor): # pylint: disable=unused-variable + rootNodeList.append(rootNode) + + rootNodeList.append(None) #No tree for final state + else: + rootNodeList = None + + rotationFlag = bool(len(physicalStates[0]) > 4) + + #No longer need to wrap the belief + beliefList = trialDataDict["beliefList"] + + #We're using a lot of arguments because we're using functional programming, could try to wrap these up later. + renderPlanarVisWrapper(physicalStates,failureState,actions,beliefList,times,rootNodeList,possibleFailures, # pylint: disable=too-many-function-args + rotationFlag,outputFilePath) + +def wrapStatesActionsFailures(trialDataDict,interpolationFactor): + """ + Sub module that wraps the physicalState, actions and failures for use with our drawing functions + """ + + physicalStates = onp.zeros((interpolationFactor*len(trialDataDict["physicalStateList"])+2,len(trialDataDict["physicalStateList"][0]))) + + actions = onp.zeros((interpolationFactor*len(trialDataDict["actionList"])+1,len(trialDataDict["actionList"][0]))) + + possibleFailures = onp.zeros((len(trialDataDict["possibleFailures"]),len(trialDataDict["possibleFailures"][0]))) + + for iPhysicalState,physicalState in enumerate(trialDataDict["physicalStateList"]): + #interpolate all but the last state + if iPhysicalState < len(trialDataDict["physicalStateList"]): + for jInterpolatedState in range(interpolationFactor): + interpolatedPhysicalState = interpolatePhysicalStates(physicalState,trialDataDict["physicalStateList"][iPhysicalState+1],jInterpolatedState/interpolationFactor) + + physicalStates[iPhysicalState*interpolationFactor+jInterpolatedState] = interpolatedPhysicalState + #Add the last state at the end + else: + physicalStates[-1] = physicalState + + #Actions held constant, first action is always 0 (as initial state had no control) + for iAction,action in enumerate(trialDataDict["actionList"]): + if iAction == 0: + actions[iAction] = onp.array(action) + else: + actions[1+interpolationFactor*(iAction-1):1+interpolationFactor*(iAction)] = onp.array(action) + + #print("wrapping possible failures") + for iPossibleFailure,possibleFailure in enumerate(trialDataDict["possibleFailures"]): + possibleFailures[iPossibleFailure] = onp.array(possibleFailure) + + return physicalStates, actions, possibleFailures + +def regenTreeFromData(trialDataDict,experimentParamsDict,numSimulations): # Not going to break this up, since single use. pylint: disable=too-many-branches,too-many-statements + """ + Function that uses the trial data to recreate the tree for visualization + what a plausible tree looked like with the level of planning specified. + Useful for hardware tests where the trees are not save for performance reasons + + Parameters + ---------- + trialDataDict : dict + Dict with trial results nested. All arrays are jax jnp arrays + physicalStateList : list + List of the (realized) physical states of the system + failureStateList : list + List of the (unchanging) true failure state + beliefList : list + List of the beliefs at each time step (time steps determined by nExperimentSteps and dt, which is currently set in the system model) + ASSUMES MARGINALIZED FILTER BELIEF AND KALMAN BELIEF + rewardList : list + List of the rewards at each time step + actionList : list + List of the actions taken at each time step + treeList: list + Will always be None here, as we are recreating + possibleFailures : array, shape(nMaxPossibleFailures,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + experimentParams : dict + Relevant parameters are: + dt : float + The time between time steps of the experiment + solverNamesList: list + List of names of solvers, for determining what type of tree search to perform + numSimulations : int + Number of simulations this recreated tree should have + + Returns + ------- + treeList: list + List of the tree data at each time step. Each element is a tuple with the nodeList and the valuesRewardsVisitsArray for the tree + """ + + #Assume only 1 solver + if len(experimentParamsDict["solverNamesList"]) != 1: + tooManySolvers = f"Regenerating the tree only works with one solver. Given {experimentParamsDict['solverNamesList']}" + raise ValueError(tooManySolvers) + solverName = experimentParamsDict["solverNamesList"][0] + #Logic dependent imports + if solverName == "SFEAST": + from failurePy.solvers.sFEAST import solveForNextAction as solverF # pylint: disable=import-outside-toplevel + realtime=False + elif solverName == "realTimeSFEAST": + from failurePy.solvers.realTimeSFEAST import solveForNextAction as solverF # pylint: disable=import-outside-toplevel + realtime=True + else: + solverNameNotRecognized = f"the solver name specified '{solverName}' isn't recognized by the regenTreeFromData function." + raise ValueError(solverNameNotRecognized) + + #Wrap as needed + + actions = jnp.zeros((len(trialDataDict["actionList"]),len(trialDataDict["actionList"][0]))) + for iAction,action in enumerate(trialDataDict["actionList"]): + actions = actions.at[iAction].set(jnp.array(action)) + + #beliefs = jnp.zeros((len(trialDataDict["beliefList"]),len(trialDataDict["beliefList"][0]),len(trialDataDict["beliefList"][0][0]))) + #for iBelief,belief in enumerate(trialDataDict["actionList"]): + # beliefs = beliefs.at[iBelief].set(jnp.array(belief)) + + treeList = [] + + rngKey = jaxRandom.PRNGKey(0) + rngKey,rngSubKey = jaxRandom.split(rngKey) + maxTries = 100 + + solverParametersTuple = experimentParamsDict["solverParametersTuplesList"][0] + #Remove timeout + solverParametersTuple = solverParametersTuple[0:2] + (jnp.inf,) + solverParametersTuple[3:] + possibleFailures = jnp.array(trialDataDict["possibleFailures"]) + systemF = experimentParamsDict["systemF"] + systemParametersTuple = experimentParamsDict["systemParametersTuple"] + rewardF = experimentParamsDict["rewardF"] + estimatorF = experimentParamsDict["estimatorF"] + physicalStateSubEstimatorF = experimentParamsDict["physicalStateSubEstimatorF"] + physicalStateJacobianF = experimentParamsDict["physicalStateJacobianF"] + physicalStateSubEstimatorSampleF = experimentParamsDict["physicalStateSubEstimatorSampleF"] + #At each time step, we will run the solver + for iBelief, beliefTuple in enumerate(trialDataDict["beliefList"]): + if iBelief == 0: + treeList.append(None) #No tree for the first time step + continue + #Turn into Jax arrays + beliefTuple = (jnp.array(beliefTuple[0]),jnp.array(beliefTuple[1])) + if realtime: + currentAction = actions[iBelief] + nextAction = actions[iBelief+1] + else: + #CHECK + nextAction = actions[iBelief] + numRegenTries = 0 + print(f"Starting Regen #{iBelief}") + while numRegenTries < maxTries: + print(numRegenTries) + rngKey,rngSubKey = jaxRandom.split(rngKey) + if realtime: + selectedAction, rootNode = solverF(beliefTuple, solverParametersTuple, possibleFailures, systemF, systemParametersTuple, rewardF, estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,numSimulations,rngSubKey,currentAction) + else: + selectedAction, rootNode = solverF(beliefTuple, solverParametersTuple, possibleFailures, systemF, systemParametersTuple, rewardF, estimatorF, + physicalStateSubEstimatorF,physicalStateJacobianF,physicalStateSubEstimatorSampleF,numSimulations,rngSubKey) + if jnp.all(selectedAction==nextAction): + treeList.append(rootNode) + print("Found") + numRegenTries = maxTries #Should break + else: + numRegenTries += 1 + print(selectedAction) + print(nextAction) + print(selectedAction-nextAction) + if numRegenTries == maxTries: + treeList.append(rootNode) + + return treeList + +def renderPlanarVisWrapper(physicalStates,failureState,actions,beliefList,times,rootNodeList,possibleFailures,plottingBounds=None,rotationFlag=False, + outputFilePath=None,hardwareFlag=False,safetyFunctionF=None,resolution=200,showFig=True): + """ + Function that uses the renderPlanarVis.py functions to visualize a trajectory. + + Currently only works for 2DOF and 3DOF + + Parameters + ---------- + physicalStates : array, shape(nTimeSteps,numState) + Numpy array with the physical state at each time + failureState : array, shape(numAct+numSen) + True failure state + actions : array, shape(nTimeSteps,numAct) + Numpy array with the action at each time + beliefList : list + List of tuples representing the beliefs. Each tuple contains the array of weights on the failures and the filter array (wrapped correctly) + times : array, shape(nTimeSteps) + Time at each step of the experiment + rootNodeList : list + List of root nodes + plottingBounds : array, shape(2,2) (default=None) + Bounds of the axis + rotationFlag : boolean + Flag on what type of system we're visualizing + outputFilePath : str (default=None) + Path to where the output file should be saved. If it doesn't exist, default used + hardwareFlag : boolean (default=False) + Whether or not this is the s/c sim hardware (if true, overrides rotating3DOFFlag in terms of hardware set up) + safetyFunctionF : function (default=None) + Constraints that physical states must satisfy to be safe. Returns 1 if safe, 0 if not. + resolution : int (default=200) + How high of a resolution the safe zone should be drawn in. + """ + + #NOTE: we've switched to the format of u_i taking x_{i-1} to x_i + #plottingBounds now can be set in config file + #dim,defaultScale,defaultPlottingBounds = getSpacecraftPlottingParams(hardwareFlag,rotationFlag) + dim,defaultPlottingBounds = getSpacecraftPlottingParams(hardwareFlag,rotationFlag) + if plottingBounds is None: + plottingBounds = defaultPlottingBounds + #if scale is None: + # scale = defaultScale + + + maxTime = times[-1] + + # make ground truth belief + trueWeights = [] + for possibleFailureState in possibleFailures: + if (possibleFailureState == failureState).all(): + trueWeights.append(1) + else: + trueWeights.append(0) + trueBelief = (trueWeights, "groundTruth") + + # plot ground truth + dummyFig, ax = plt.subplots() #ax is used a lot with matplotlib so pylint: disable=invalid-name + numAct = len(actions[0]) + #Currently always have more actions than sensors so this works, but is a HACK + if len(failureState) > 2*numAct: + spacecraftDrawingF = renderPlanarVisGeneralFault.drawSpacecraft + else: + spacecraftDrawingF = renderPlanarVis.drawSpacecraft + + #Draw unsafe region for ground truth too + if safetyFunctionF is not None: + renderPlanarVis.plotUnsafeRegions(ax,safetyFunctionF,plottingBounds,resolution=resolution) + spacecraftDrawingF( + onp.zeros((dim*2,1)), onp.zeros((numAct,1)), + trueBelief, possibleFailures, None, ax, plottingBounds, + legendFlag=True,rotationFlag=rotationFlag) + ax.set_title("Ground Truth") + + for iTimeStep, time in tqdm(enumerate(times)): + #Get experiment values at this time + physicalState = physicalStates[iTimeStep] + action = actions[iTimeStep] + beliefTuple = beliefList[iTimeStep] + if rootNodeList is not None: + rootNode = rootNodeList[iTimeStep] + else: + rootNode = None + + + #Plot this time step + dummyFig, ax = plt.subplots() #ax is used a lot with matplotlib so pylint: disable=invalid-name + #Add obstacles, if any + if safetyFunctionF is not None: + renderPlanarVis.plotUnsafeRegions(ax,safetyFunctionF,plottingBounds,resolution=resolution) + spacecraftDrawingF(physicalState,action,beliefTuple,possibleFailures,rootNode,ax,plottingBounds, + legendFlag=False,rotationFlag=rotationFlag) + ax.set_title(f"Physical Time: {time}/{maxTime}") + + saveRender(outputFilePath,showFig=showFig) + +def saveRender(outputFilePath=None,makePngs=False,showFig=True): + """ + Method that saves the produced figures + + Parameters + ---------- + outputFilePath : string + Where to save the output. If not specified saves locally + makePngs : boolean (default=False) + If true, also make a subfolder of pngs for each plot + showFig : boolean (default=True) + Shows the figures made when rendering finishes + """ + #Default file name + if outputFilePath is None: + outputFilePath = os.path.join(os.getcwd(),"render.pdf") + print(f"Making save file at {outputFilePath}") + + #Make png sub directory if needed, + if makePngs: + checkOrMakeDirectory(os.path.dirname(outputFilePath),"pngs") + + renderPlanarVis.saveFigs(outputFilePath,makePngs) + if showFig: + openFigs(outputFilePath) + +def getSpacecraftPlottingParams(hardwareFlag,rotationFlag): + """ + Sub method to get parameters based on experiment type + """ + + #Number of sensor or actuators is pre set + if hardwareFlag: + #numAct = 8 + #numSen = 6 #Add two rotation sensors + dim =3 + #scale = .4 + #Much smaller field + plottingBounds = onp.array([[-3, 3], + [-3, 3]]) + elif not rotationFlag: + #numAct = 8 + #numSen = 4 + dim = 2 + #scale = 10 + plottingBounds = onp.array([[-30, 30], + [-30, 30],]) + #plottingBounds = onp.array([[-45, 45], + # [-45, 45],]) + + else: + #numAct = 10 #Add two wheels + #numSen = 6 #Add two rotation sensors + dim = 3 + #scale = 10 #10 + plottingBounds = onp.array([[-30, 30], + [-30, 30],]) + + #return dim,scale,plottingBounds + return dim,plottingBounds + +def openFigs(fileName): + """ + Ported from Ben's Plotter function. + Opens the specified figure + """ + + pdfPath = os.path.join( os.getcwd(), fileName) + if os.path.exists(pdfPath): + #Changed this to be cross-platform compatible (as xdg-open is linux and open is mac) + #Also has the bonus of opening in this in a detached mode + subprocess.call(["python3", "-m", "webbrowser", pdfPath]) + + +def interpolatePhysicalStates(currentPhysicalState,nextPhysicalState,interpolationAmount): + """Interpolates between two physical states""" + + return (1-interpolationAmount) * onp.array(currentPhysicalState) + interpolationAmount * onp.array(nextPhysicalState) diff --git a/failurePy/visualization/renderSavedRun.py b/failurePy/visualization/renderSavedRun.py new file mode 100644 index 0000000..964dac8 --- /dev/null +++ b/failurePy/visualization/renderSavedRun.py @@ -0,0 +1,52 @@ +""" +File the makes a pdf and png visualization of the experiment. + +Useful for when the experiment wasn't originally visualized +""" +import os +import warnings + + +from failurePy.visualization.renderPlanarVisWrapper import visualizeFirstTrajectory +from failurePy.load.yamlLoader import loadExperimentParamsFromYaml + +#Ignore matplotlib warnings' +warnings.filterwarnings( "ignore", module = r"matplotlib\..*" ) + +#Going to just make the plots manually +def main(savedDataDirPath,experimentName,outputPath): + """ + Function that gets the data from the specified experiment and generates a video of the belief evolution over time. + Intended to visualize the hardware demos + + Parameters + ---------- + savedDataDirPath : str + String of the absolute path to the saveDirectory for we are loading the experiment from. + experimentName : str + Name of the experiment we are loading + solverName : str + The solver to get the data from + nSimulationsPerTree: int + The number of simulations per tree to get data from. + outputPath : str + Path to where the output data should be saved. + outputSubDirectory : str + Sub directory to save the output data in + nTrial : int (default=None) + The trial to get the data from + """ + #Get the exp params loaded + experimentDataDirPath = os.path.join(savedDataDirPath,experimentName) + configFilePath = os.path.join(experimentDataDirPath,"config.yaml") + experimentParamsDict, dummyRelativeSaveDirectoryPath = loadExperimentParamsFromYaml(configFilePath) #We won't use extra data here pylint: disable=unbalanced-tuple-unpacking + + outputFilePath = os.path.join(outputPath,"renderBeliefAndTreeOnly.pdf") + + visualizeFirstTrajectory(experimentDataDirPath,experimentParamsDict,outputFilePath,regenTree=85) + + +#If running directly +if __name__ == "__main__": + SAVED_DATA_DIR_PATH = None #SET THIS BEFORE RUNNING! + main(SAVED_DATA_DIR_PATH,experimentName="hardwareSafetyTest",outputPath="/home/trey/Documents/TrialVisualization") diff --git a/failurePy/visualization/videoMaker.py b/failurePy/visualization/videoMaker.py new file mode 100644 index 0000000..4592fe9 --- /dev/null +++ b/failurePy/visualization/videoMaker.py @@ -0,0 +1,108 @@ +""" +Code for taking pdf and making a gif. Credit Ben Riviere + +Should be run as a toplevel method +""" +import os +import subprocess +import glob +import multiprocessing as mp + +def makeImage(iPage): + """ + Converts the specified page of the pdf to a png image. + """ + + makeImageCommand = f"convert -density 400 {INPUT_PDF_PATH}[{iPage}] {makeTempImageName(iPage)}" #Using globals in utility function pylint: disable=used-before-assignment + runCommand(makeImageCommand) + + +def runCommand(command): + """ + Run a string as a terminal command + + Parameters + ---------- + command : string + Command to run + """ + print(f'running cmd: {command}...') + with subprocess.Popen(command, shell=True, stdout=subprocess.PIPE) as process: + process.wait() + print(f'completed cmd: {command}') + + +def makeTempImageName(iPage): + """ + Creates a temporary name for each image, which is a 4 digit number prepended by "x-" + For example, if iPage = 2, returns "TEMP_IMAGES_DIR/x-0002.png" + """ + return f"{TEMP_IMAGES_DIR}/x-{iPage:04d}.png" #Using globals in utility function pylint: disable=used-before-assignment + + +def makeMovieFromPdf(pdfPath, videoPath): + """ + Converts the specified pdf into a gif + """ + + #Check for and remove any previously existing temp images + if os.path.exists(TEMP_IMAGES_DIR): + clearTempDirectory(TEMP_IMAGES_DIR) + else: + os.mkdir(TEMP_IMAGES_DIR) + + + # # make images (serial) + # for i in range(getNumPages(pdf_path)): + # makeImageCommand = "convert -density 400 {}[{}] {}".format(pdf_path, i, tii(i)) + # runCommand(makeImageCommand) + + + # make images (parallel) + with mp.Pool(mp.cpu_count()-1) as pool: + pool.map(makeImage, range(getNumPages(pdfPath))) + + + # make movie + frameRate = 30 # frames per second + #Need to have ffmpeg installed, creates video using all the matching temp images we made that match the regex. + makeMovieCommand = f"ffmpeg -r {frameRate} -i {TEMP_IMAGES} -c:v libx264 -r 30 -y -pix_fmt yuv420p {videoPath}" #Using globals in utility function pylint: disable=used-before-assignment + runCommand(makeMovieCommand) + + #Clean up + clearTempDirectory(TEMP_IMAGES_DIR) + +def getNumPages(pdfPath): + """ + Uses pdfinfo to parse the pdf to find the number of pages + Need to have pdfinfo installed, should be by default on Ubuntu + """ + output = subprocess.check_output(["pdfinfo", pdfPath]).decode() + pagesLine = [line for line in output.splitlines() if "Pages:" in line][0] + numPages = int(pagesLine.split(":")[1]) + return numPages + +def clearTempDirectory(tempDirectory): + """ + Deletes every file in the specified temporary directory + """ + files = glob.glob(tempDirectory + "/*") + for fileName in files: + os.remove(fileName) + +#If running directly +if __name__ == "__main__": + INPUT_PDF_PATH = None #SET TO PDF TO TURN INTO MOVIE + OUTPUT_VIDEO_PATH = None #SET TO OUTPUT PATH FOR MP4 + + # prep temporary directory + TEMP_IMAGES_DIR = f"{os.path.dirname(os.path.realpath(INPUT_PDF_PATH))}/Temp" + #The generated temp images will be of form "TEMP_IMAGES_DIR/x-%04d.png" + #where %04d is a 4 digit number. ie, for image 2, it would be: "TEMP_IMAGES_DIR/x-0002.png" + TEMP_IMAGES = f"{TEMP_IMAGES_DIR}/x-%04d.png" + + + makeMovieFromPdf(INPUT_PDF_PATH, OUTPUT_VIDEO_PATH) +else: + #This module shouldn't be imported + raise ImportError("This module is intended as a stand alone utility and is not configured for importing.") diff --git a/failurePy/visualization/visualization.py b/failurePy/visualization/visualization.py new file mode 100644 index 0000000..8677517 --- /dev/null +++ b/failurePy/visualization/visualization.py @@ -0,0 +1,1241 @@ +""" +Module of our various visualization functions. These are a little rough around the edged, but now in a common place +""" +#Long plotting library pylint: disable=too-many-lines +import os +import sys +import pickle +import numbers +import warnings +import numpy as onp +#Ignore matplotlib warnings' +import matplotlib.pyplot as plt +import matplotlib +from matplotlib.collections import LineCollection +from matplotlib.backends.backend_pdf import PdfPages + +#Import the saved data, this is not compatible with python < 3.9!! +import failurePy + +warnings.filterwarnings( "ignore", module = r"matplotlib\..*" ) + + +def plotAvgsOnly(avgRewards,avgSuccessRates,avgWallClockTimes,nSimulationsPerTrees,nTrialsPerPoint,noise,solverNames, #Main plotting function, so pylint: disable=too-many-statements,too-many-branches + successRateAdjustmentFlag=False,systemName=None,dt=1,plotSuccessRatesAndWallClockTimesFlag=False): + """ + Method that loads data to plot and calls plotting functions as needed + + Parameters + ---------- + avgRewards : array, shape(numSolvers,numNSimulationsPerTrees,numExperimentSteps+1) + The average rewards for each solver and number of simulations per tree, for each time step (including initial time) + avgSuccessRates : array, shape(numSolvers,numNSimulationsPerTrees) + The average success rate for each solver and number of simulations per tree + avgWallClockTimes : array, shape(numSolvers,numNSimulationsPerTrees) + The average time for each solver and number of simulations per tree + nSimulationsPerTrees : array, shape(numNSimulationsPerTrees) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + nTrialsPerPoint : int + The number of repeated trials per configuration. + noise : float + Level of sigma for this collection of experiments + solverNames : list + List of the names of each solver that was used + successRateAdjustmentFlag : bool (default=False) + If true, rewards are scaled by the success rate + systemName : str (default=None) + Name of the system for the plot title, if any + dt : float (default=1) + The time between time steps of the experiment + plotSuccessRatesAndWallClockTimesFlag : boolean (default=False) + If true plot extra data on success rates and wall clock times + """ + + font = {'size' : 22} + matplotlib.rc('font', **font) + + #numPoints = len(nSimulationsPerTrees) + offset = .15 + + #Plotting success rates and wall clock times + if plotSuccessRatesAndWallClockTimesFlag: + + #Set random to 1 simulation, so it plots on a log scale well + semiLogNSimulationsPerTrees = onp.copy(nSimulationsPerTrees) + if semiLogNSimulationsPerTrees[0] == 0: + semiLogNSimulationsPerTrees[0] = 1 + + dummyFig, ax = plt.subplots(nrows=2,ncols=1,figsize=(15,8)) + + #Plot success rates + legendHandles = [] + for iSolver, solverName in enumerate(solverNames): + legendHandles.append(ax[0].semilogx(semiLogNSimulationsPerTrees,100*avgSuccessRates[iSolver],label=solverName,marker="o")[0]) + ax[0].legend(handles=legendHandles) + ax[0].set_ylabel("Success Rate (%)") + + #Plot wall clock times + legendHandles = [] + for iSolver, solverName in enumerate(solverNames): + legendHandles.append(ax[1].semilogx(semiLogNSimulationsPerTrees,avgWallClockTimes[iSolver],label=solverName,marker="o")[0]) + + ax[1].legend(handles=legendHandles) + ax[1].set_ylabel("Wall Clock Time/Iteration (s)") + + ax[-1].set_xlabel("Number of Simulations per Tree") + + ax[0].set_title(f"Success Rates and Wall Clock Times\n{nTrialsPerPoint} experiments averaged per data point") + + + #Now plot reward trajectories + dummyFig, ax = plt.subplots(nrows=1,ncols=1,figsize=(15,8)) + + #Make x-axis + timeSteps = onp.arange(0,dt*(len(avgRewards[0,0])),dt) + #Labels for legend + legendHandles = [] + + #Legend Entries + lineStyles = ["-",":","--","dashdot"] + markers = ["o","^","x","*"] + for iSolver, solverName in enumerate(solverNames): + + if successRateAdjustmentFlag: + successFactor = avgSuccessRates[iSolver,0] + else: + successFactor = 1 + legendHandles.append(ax.plot(timeSteps[0],avgRewards[0,0,0]*successFactor,label=solverName,ls=lineStyles[iSolver],marker=markers[iSolver],c="black")[0]) + + #Set color cycle + setColorCycler(len(nSimulationsPerTrees),ax) + + #Loop through solvers + for iSolver, solverName in enumerate(solverNames): + #Loop through experiments + for jNSimsPerTreeTrial,nSimulationsPerTree in enumerate(nSimulationsPerTrees): + #Adjust by success rates if needed + if successRateAdjustmentFlag: + successFactor = avgSuccessRates[iSolver,jNSimsPerTreeTrial] + else: + successFactor = 1 + #Check for random policy + if nSimulationsPerTree == 0: + #Only plot once + if iSolver == 0: + label = "Random Action" + #Plot rewards, modulated by success rate + + handle = ax.plot(timeSteps,avgRewards[iSolver,jNSimsPerTreeTrial,:]*successFactor,label=label,ls="--",marker="*")[0] + legendHandles.append(handle) + #Need to advance color cycler + else: + ax.plot([],[]) + continue + + label = f"N = {nSimulationsPerTree}" + handle = ax.plot(timeSteps+offset*jNSimsPerTreeTrial,avgRewards[iSolver,jNSimsPerTreeTrial,:]*successFactor,label=label,ls=lineStyles[iSolver],marker=markers[iSolver])[0] + #Hack to make N=200 green + if nSimulationsPerTree==200: + handle = ax.plot(timeSteps+offset*jNSimsPerTreeTrial,avgRewards[iSolver,jNSimsPerTreeTrial,:]*successFactor,label=label,ls="-",marker="o",color="green")[0] + + #Make legend only first time through, since labeling by nSimsPerTree + if iSolver == 0: + legendHandles.append(handle) + + + ax.legend(handles=legendHandles,facecolor="gainsboro",loc="lower right") + ax.set_xlabel("Simulation Time Step") + if successRateAdjustmentFlag: + ax.set_ylabel("Reward * Success Rate") + else: + ax.set_ylabel("Reward") + if systemName is not None: + ax.set_title(systemName) + elif noise is None: + ax.set_title(f"Rewards After Each Time Step (N Simulations per Time Step)\n{nTrialsPerPoint} experiments averaged per data point") + else: + ax.set_title(f"Rewards After Each Time Step (N Simulations per Time Step)\n{nTrialsPerPoint} " + fr"experiments averaged per data point. $\sigma_w$ = {noise}") + ax.set_xticks(onp.arange(0,20,2)) + + #Set the color to gray and turn on grid + ax.set_facecolor(".8") + plt.grid(True) + #Normalize y to 1 + #ax.set_ylim(0,1) + #print(wcts) + #print(successRates) + #print(Ns) + #print(steps) + + +def setColorCycler(repeatNum,ax): + """ + Creates a color cycler with CMR color map with specified repeat frequency and assigns to the provided axis + """ + ax.set_prop_cycle('color',plt.cm.CMRmap(onp.linspace(0,1,repeatNum))) + +#Plotting functions + +def plotRewardStd(avgRewards,avgSuccessRates,sigmaRewards,nSimulationsPerTrees,nTrialsPerPoint,noise,solverNames,successRateAdjustmentFlag=True,#Main plotting function, so pylint: disable=too-many-statements,too-many-branches + systemName=None,dt=1,tSteps=20,cumulativeFlag=False,experimentIndexes=None,fixedYTicksFlag=True): + + """ + Method that loads data to plot and calls plotting functions as needed. Plots reward data showing 1 sigma std. + + Parameters + ---------- + avgRewards : array, shape(numSolvers,numNSimulationsPerTrees,numExperimentSteps+1) + The average rewards for each solver and number of simulations per tree, for each time step (including initial time) + avgSuccessRates : array, shape(numSolvers,numNSimulationsPerTrees,numExperimentSteps+1) + The average success rate for each solver and number of simulations per tree + sigmaRewards : array, shape(numSolvers,numNSimulationsPerTrees) + The 1 sigma bounds for the rewards + nSimulationsPerTrees : array, shape(numNSimulationsPerTrees) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + nTrialsPerPoint : int + The number of repeated trials per configuration. + noise : float + Level of sigma for this collection of experiments + solverNames : list + List of the names of each solver that was used + successRateAdjustmentFlag : bool (default=False) + If true, rewards are scaled by the success rate + systemName : str (default=None) + Name of the system for the plot title, if any + dt : float (default=1) + The time between time steps of the experiment + plotSuccessRatesAndWallClockTimesFlag : boolean (default=False) + If true plot extra data on success rates and wall clock times + cumulativeFlag : boolean (default=False) + If true, plot the cumulative reward + """ + + if solverNames[0] == "SFEAST": + solverNames[0] = "s-FEAST" + solverGroupName = solverNames[0] #Will be block of solvers for each nSimulationsPerTrees + + #Check for random or not (this is assumed to only be on s-FEAST solvers) + if nSimulationsPerTrees[0] == 0: + solverNames[0] = "Random" + else: + solverNames = solverNames[1:] + + #Format baselines as needed + if "greedy" in solverNames: + solverNames[solverNames.index("greedy")] = "Greedy" + if "cbf" in solverNames: + solverNames[solverNames.index("cbf")] = "CBF" + if "scp" in solverNames: + solverNames[solverNames.index("scp")] = "SCP" + + font = {'size' : 16} + matplotlib.rc('font', **font) + + #Now plot reward trajectories + dummyFig, ax = plt.subplots(nrows=1,ncols=1,figsize=(7.5,4),dpi=400) + + #Make x-axis + timeSteps = onp.arange(0,dt*(len(avgRewards[0,0])),dt) + #Labels for legend + legendHandles = [] + + #Legend Entries + lineStyles = ["-",":","--","dashdot"] + markers = ["o","^","x","*"] + #Idea, make each baseline a different color + solverColors = ["black","green","peru","lightskyblue"] + markersize = 2.5 + + for iSolver, solverName in enumerate(solverNames): + if successRateAdjustmentFlag: + successFactor = avgSuccessRates[iSolver,0] + else: + successFactor = 1 + legendHandles.append(ax.plot(timeSteps[0],avgRewards[0,0,0]*successFactor,label=solverName,ls=lineStyles[iSolver],marker=markers[iSolver],ms=markersize,c=solverColors[iSolver])[0]) + + #Add name for group of solvers + emptyRectHandle = matplotlib.patches.Rectangle((0,0), 1, 1, fill=False, edgecolor='none',visible=False,label=solverGroupName) + legendHandles.append(emptyRectHandle) + + #Set color cycle, adding extra lines to account for matching colors with safety (bit hacky) + numLines = 8 #len(nSimulationsPerTrees)+len(solverNames)-1 + setColorCycler(numLines,ax) + + offset = .1 + + rwbds = onp.zeros((len(solverNames),len(nSimulationsPerTrees),2,tSteps+1)) + rwbds[:,:,0,:] = avgRewards -sigmaRewards # + rwbds[:,:,1,:] = avgRewards + sigmaRewards + if experimentIndexes is None: + experimentIndexes = onp.arange(len(nSimulationsPerTrees)) + + #print(avgRewards,avgSuccessRates) + #Loop through solvers + for iSolver, solverName in enumerate(solverNames): + #Loop through experiments + for jOffset, jNSimsPerTreeExperiment in enumerate(experimentIndexes): + nSimulationsPerTree = nSimulationsPerTrees[jNSimsPerTreeExperiment] + #Check if we scale by success + if successRateAdjustmentFlag: + successFactor = avgSuccessRates[iSolver,0] + else: + successFactor = 1 + + #For baselines, want to have their colors not on cycler, and don't want to double add to legend + if iSolver == 0: + label = f"N = {nSimulationsPerTree}" + #Plot rewards, modulated by success rate + + handle = ax.plot(timeSteps+offset*(jOffset-iSolver%2),avgRewards[iSolver,jNSimsPerTreeExperiment,:]*successFactor,ls=lineStyles[iSolver],marker=markers[iSolver], + ms=markersize,label=label)[0] + #Hack to make N=200 green + #if nSimulationsPerTree==200: + # handle = ax.plot(timeSteps+offset*jNSimsPerTreeTrial,avgRewards[iSolver,jNSimsPerTreeTrial,:]*successFactor,label=label,ls="-",marker="o",color="green")[0] + + #Custom error bar + ax.vlines(timeSteps+offset*(jOffset-iSolver%2),rwbds[iSolver,jNSimsPerTreeExperiment,0,:]*successFactor,rwbds[iSolver,jNSimsPerTreeExperiment,1,:]*successFactor, + ls=lineStyles[iSolver],alpha=1,color=handle.get_color(),zorder=200+jOffset - 10* iSolver) + #Add markers at end + ax.scatter(timeSteps+offset*(jOffset-iSolver%2),rwbds[iSolver,jNSimsPerTreeExperiment,1,:]*successFactor,marker=markers[iSolver],s=markersize**2, + color=handle.get_color(),zorder=200+jOffset - 10* iSolver)#,alpha=.5) + ax.scatter(timeSteps+offset*(jOffset-iSolver%2),rwbds[iSolver,jNSimsPerTreeExperiment,0,:]*successFactor,marker=markers[iSolver],s=markersize**2, + color=handle.get_color(),zorder=200+jOffset - 10* iSolver)#,alpha=.5) + + #Make legend only first time through, since labeling by nSimsPerTree + #if iSolver == 0: + if nSimulationsPerTree != 0: + legendHandles.append(handle) + else: + ax.plot(timeSteps+offset*(jOffset-iSolver%2),avgRewards[iSolver,jNSimsPerTreeExperiment,:]*successFactor,label=label,ls=lineStyles[iSolver],marker=markers[iSolver], + ms=markersize,c=solverColors[iSolver]) + + #Custom error bar + ax.vlines(timeSteps+offset*(jOffset-iSolver%2),rwbds[iSolver,jNSimsPerTreeExperiment,0,:]*successFactor,rwbds[iSolver,jNSimsPerTreeExperiment,1,:]*successFactor, + ls=lineStyles[iSolver],color=solverColors[iSolver],alpha=1,zorder=200+jOffset - 10* iSolver) + #Add markers at end + ax.scatter(timeSteps+offset*(jOffset-iSolver%2),rwbds[iSolver,jNSimsPerTreeExperiment,0,:]*successFactor,marker=markers[iSolver],s=markersize**2, + color=solverColors[iSolver],zorder=200+jOffset - 10* iSolver)#,alpha=.5) + ax.scatter(timeSteps+offset*(jOffset-iSolver%2),rwbds[iSolver,jNSimsPerTreeExperiment,1,:]*successFactor,marker=markers[iSolver],s=markersize**2, + color=solverColors[iSolver],zorder=200+jOffset - 10* iSolver)#,alpha=.5) + + + ax.legend(handles=legendHandles,facecolor="gainsboro",loc="lower left",prop={'size': 10}).set_zorder(1000) + ax.set_xlabel("Simulation Time Step") + if successRateAdjustmentFlag: + ax.set_ylabel("Reward * Success Rate") + else: + ax.set_ylabel("Reward") + if cumulativeFlag: + cumulative = "Cumulative " + else: + cumulative = " " + if systemName is not None: + ax.set_title(systemName) + elif noise is None: + ax.set_title(f"{cumulative}Rewards After Each Time Step (N Simulations per Time Step)\n{nTrialsPerPoint} experiments averaged per data point") + else: + ax.set_title(f"{cumulative}Rewards After Each Time Step (N Simulations per Time Step)\n{nTrialsPerPoint} " + fr"experiments averaged per data point. $\sigma_w$ = {noise}") + ax.set_xticks(onp.arange(0,timeSteps[-1],2)) + #Most plots use this by default anyways, making it explicit for consistency + if fixedYTicksFlag: + ax.set_yticks(onp.array([0.,0.2,0.4,0.6,0.8,1.0])) + + #Set the color to gray and turn on grid + ax.set_facecolor(".8") + plt.grid(True) + +def plotData(experimentName,solverNames,noise,successRateAdjustmentFlag=False,systemName=None,plotSuccessRatesAndWallClockTimesFlag=False): + """ + Method that loads data to plot and calls plotting functions as needed + + Parameters + ---------- + experimentName : str + Name of the experiment (top level saved data directory) + solverNames : list + List of the names of each solver that was used + noise : float + Level of sigma for this collection of experiments + successRateAdjustmentFlag : bool (default=False) + If true, rewards are scaled by the success rate + systemName : str (default=None) + Name of the system for the plot title, if any + """ + + + nSimulationsPerTrees, nTrialsPerPoint, avgRewards, avgSuccessRates, avgWallClockTimes, dummyAvgSteps, dummySigmaRewards = loadDataSummary(experimentName,solverNames) + + plotAvgsOnly(avgRewards,avgSuccessRates,avgWallClockTimes,nSimulationsPerTrees,nTrialsPerPoint,noise,solverNames, + successRateAdjustmentFlag,systemName,plotSuccessRatesAndWallClockTimesFlag=plotSuccessRatesAndWallClockTimesFlag) + plt.show() + + +def plotDataRewardStd(experimentName,solverNames,noise,successRateAdjustmentFlag=False,systemName=None,tSteps=20,cumulativeFlag=False,baselineExpName=None,experimentIndexes=None): + """ + Method that loads data to plot and calls plotting functions as needed. Plots reward data showing 1 sigma std. + + Parameters + ---------- + experimentName : str + Name of the experiment (top level saved data directory) + solverNames : list + List of the names of each solver that was used + noise : float + Level of sigma for this collection of experiments + successRateAdjustmentFlag : bool (default=False) + If true, rewards are scaled by the success rate + systemName : str (default=None) + Name of the system for the plot title, if any + """ + + nSimulationsPerTrees, nTrialsPerPoint, avgRewards, avgSuccessRates, dummyAvgWallClockTimes, dummyAvgSteps, sigmaRewards = loadDataSummary(experimentName,solverNames,cumulativeFlag, + baselineExpName,tSteps=tSteps ) + plotRewardStd(avgRewards,avgSuccessRates,sigmaRewards,nSimulationsPerTrees,nTrialsPerPoint,noise,solverNames,successRateAdjustmentFlag,systemName,tSteps=tSteps, + cumulativeFlag=cumulativeFlag,experimentIndexes=experimentIndexes) + plt.show() + + +#Alt way to plot only some: add experimentIndexes=None): +def loadDataSummary(experimentName,solverNames,cumulativeFlag=False,baselineExpName=None,altRewardFlag=True,savedDataDirPath=None,tSteps=None): #Allow to be do everything pylint: disable=too-many-statements,too-many-branches + """ + Method to load saved data that is reused by several functions + + Parameters + ---------- + experimentName : str + Name of the experiment (top level saved data directory) + solverNames : list + List of the names of each solver that was used + cumulativeFlag : boolean (default=False) + If true, plot the cumulative reward + baselineExpName : str (default=None) + If provided, loads in additional solver experiments that are all baselines (1 nSim per tree, always 1) + altRewardFlag : str (default=False) + If true, looks for alternative reward data instead of the default. Incompatible with cumulative sum currently. Does not check for existence first + savedDataDirPath : str (default=None) + Path to saved data. Will try to look in local failurePy installation if none provided, as that is the default + + Returns + ------- + nSimulationsPerTrees : array, shape(numNSimulationsPerTrees) + The number of simulations performed before returning an action (when not running on time out mode). + This parameter is an array, if longer then length 1, multiple trials are run, varying the number of simulations per tree. + nTrialsPerPoint : int + The number of repeated trials per configuration. + avgRewards : array, shape(numSolvers,numNSimulationsPerTrees,numExperimentSteps+1) + The average rewards for each solver and number of simulations per tree, for each time step (including initial time) + avgSuccessRates : array, shape(numSolvers,numNSimulationsPerTrees) + The average success rate for each solver and number of simulations per tree + avgWallClockTimes : array, shape(numSolvers,numNSimulationsPerTrees) + The average time for each solver and number of simulations per tree + avgSteps : array, shape(numSolvers,numNSimulationsPerTrees) + The average steps for each solver and number of simulations per tree + sigmaRewards : array, shape(numSolvers,numNSimulationsPerTrees) + The 1 sigma bounds for the rewards + """ + + #Check path provided + if savedDataDirPath is None: + savedDataDirPath = loadExperimentFromDefaultSaveData(experimentName) + + #First we need to collect the data + experimentDataDirPath = os.path.join(savedDataDirPath,experimentName) + + #Check if there is a baseline directory to load from too + if baselineExpName is not None: + baselineExperimentDataDirPath = os.path.join(savedDataDirPath,baselineExpName) + try: + baselineSolverNames = next(os.walk(baselineExperimentDataDirPath))[1] + except StopIteration as exception: + directoryEmptyError = f"Directory {baselineExperimentDataDirPath} does not exist or is empty." + raise FileNotFoundError(directoryEmptyError) from exception + #Hack to sort baselines consistently (will format when plotting legend) + if "greedy" in baselineSolverNames and "cbf" in baselineSolverNames and "scp" in baselineSolverNames: + baselineSolverNames = ["greedy", "cbf", "scp"] + + + numBaselines = len(baselineSolverNames) + solverNames += baselineSolverNames #Updates solverNames by reference! + else: + numBaselines = 0 + + #We take for granted that the number of simulations per trees is the same for each solver, as is the number of trials per point. If this is None, haven't found them yet + nSimulationsPerTrees = None + nTrialsPerPoint = None + + for iSolver, solverName in enumerate(solverNames): + #print(iSolver,len(solverNames),numBaselines,solverNames) + if iSolver >= len(solverNames) - numBaselines: + solverDirectoryPath = os.path.join(baselineExperimentDataDirPath,solverName) + else: + solverDirectoryPath = os.path.join(experimentDataDirPath,solverName) + if not os.path.exists(solverDirectoryPath): + raise FileNotFoundError(f"Directory {solverDirectoryPath} not found, check if the correct save directory and experiment are given") + + if nSimulationsPerTrees is None: + #Get NSimulationsPerTrees using os.walk to read the directory names + nSimulationsPerTrees = onp.array(next(os.walk(solverDirectoryPath))[1]) + nSimulationsPerTrees = nSimulationsPerTrees.astype(int) + nSimulationsPerTrees = onp.sort(nSimulationsPerTrees) + ##Alternate way for plotting only some of the experiments + #if experimentIndexes is not None: + # NSimulationsPerTrees = NSimulationsPerTrees[experimentIndexes] + + for jNSimsPerTreeExperiment, nSimulationsPerTree in enumerate(nSimulationsPerTrees): + #Initialize average data arrays if we haven't yet + if nTrialsPerPoint is None: + #Get nTrialsPerPoint + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + nTrialsPerPoint = len(next(os.walk(nSimPath))[1]) + + + #Load first data dict + experimentDataPath = os.path.join(nSimPath,"averageData.dict") + with open(experimentDataPath,'rb') as experimentDataFile: + experimentAverageDataDict = pickle.load(experimentDataFile) + + #Now initialize the average data now that we know the number of experiments + avgRewards = onp.zeros((len(solverNames),len(nSimulationsPerTrees),len(experimentAverageDataDict["avgRewards"]))) + avgSuccessRates = onp.zeros((len(solverNames),len(nSimulationsPerTrees))) + avgWallClockTimes = onp.zeros((len(solverNames),len(nSimulationsPerTrees))) + avgSteps = onp.zeros((len(solverNames),len(nSimulationsPerTrees))) + sigmaRewards = onp.zeros((len(solverNames),len(nSimulationsPerTrees),len(experimentAverageDataDict["avgRewards"]))) + #Baselines load a little different (SUPER HACKY) + elif iSolver > 0 and jNSimsPerTreeExperiment == 0: + nSimPath = os.path.join(solverDirectoryPath,str(1)) #Always 1 for baselines + experimentDataPath = os.path.join(nSimPath,"averageData.dict") + with open(experimentDataPath,'rb') as experimentDataFile: + experimentAverageDataDict = pickle.load(experimentDataFile) + #Fill baselines with nans for other "num sims per tre" SUPER HACKY here, just trying to quickly plot. + elif iSolver > 0: + avgSuccessRates[iSolver,jNSimsPerTreeExperiment] += onp.nan + avgWallClockTimes[iSolver,jNSimsPerTreeExperiment] += onp.nan + avgSteps[iSolver,jNSimsPerTreeExperiment] += onp.nan + avgRewards[iSolver,jNSimsPerTreeExperiment] += onp.nan + sigmaRewards[iSolver,jNSimsPerTreeExperiment] += onp.nan + continue #Don't load anything + #Otherwise just load + else: + #Load data dict + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + experimentDataPath = os.path.join(nSimPath,"averageData.dict") + with open(experimentDataPath,'rb') as experimentDataFile: + experimentAverageDataDict = pickle.load(experimentDataFile) + + #print(experimentAverageDataDict) + + #In either case, get data + avgSuccessRates[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["avgSuccessRate"] + avgWallClockTimes[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["avgWallClockTime"] + avgSteps[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["avgSteps"] + if cumulativeFlag: + #If EKF diverged = failure (also need to make sure success set to 0) + experimentAverageDataDict["cumulativeAvgRewards"][onp.isnan(experimentAverageDataDict["cumulativeAvgRewards"])] = 0 + + avgRewards[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["cumulativeAvgRewards"] + sigmaRewards[iSolver,jNSimsPerTreeExperiment] = onp.sqrt(experimentAverageDataDict["cumulativeVarRewards"]) + elif altRewardFlag: + #If EKF diverged = failure (also need to make sure success set to 0) + experimentAverageDataDict["avgAltRewards"][onp.isnan(experimentAverageDataDict["avgAltRewards"])] = 0 + + avgRewards[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["avgAltRewards"] + sigmaRewards[iSolver,jNSimsPerTreeExperiment] = onp.sqrt(experimentAverageDataDict["varAltRewards"]) + else: + #If EKF diverged = failure (also need to make sure success set to 0) + experimentAverageDataDict["avgRewards"][onp.isnan(experimentAverageDataDict["avgRewards"])] = 0 + + avgRewards[iSolver,jNSimsPerTreeExperiment] = experimentAverageDataDict["avgRewards"] + sigmaRewards[iSolver,jNSimsPerTreeExperiment] = onp.sqrt(experimentAverageDataDict["varRewards"]) + #Allow for only considering some of the data + if tSteps is not None: + timeStepsInData = len(avgRewards[0,0]) - 1 + if timeStepsInData > tSteps: + avgRewards = avgRewards[:,:,:tSteps+1] + sigmaRewards = sigmaRewards[:,:,:tSteps+1] + elif timeStepsInData < tSteps: + tooManyTimeStepsRequested = f"Saved data only has {timeStepsInData} time steps. {tSteps} requested" + raise ValueError(tooManyTimeStepsRequested) + + return nSimulationsPerTrees, nTrialsPerPoint, avgRewards, avgSuccessRates, avgWallClockTimes, avgSteps, sigmaRewards + +def plotMultipleWallClockTimes(experimentNameList,solverNames,labels=None,savedDataDirPath=None,sigmaFlag=False): #plotting method pylint: disable=too-many-statements,too-many-branches + """ + Method that loads data to plot and calls plotting functions as needed + + Parameters + ---------- + experimentName : List of strs + Names of the experiment (top level saved data directory) + solverNames : list + List of the names of each solver that was used + systemName : str (default=None) + Name of the system for the plot title, if any + labels : list (default=None) + List of strings to label the plots with. + savedDataDirPath : str (default=None) + Path to saved data. Will try to look in local failurePy installation if none provided, as that is the default + sigmaFlag : boolean (default=False) + When true, 1 std shown for the different times measured + """ + + #Check path provided + if savedDataDirPath is None: + savedDataDirPath = loadExperimentFromDefaultSaveData(experimentNameList[0]) + + experimentWallClockTimesList = [] + experimentSigmaWallClockTimesList = [] + + for experimentName in experimentNameList: + #First we need to collect the data + experimentDataDirPath = os.path.join(savedDataDirPath,experimentName) + + #We take for granted that the number of simulations per trees is the same for each solver, as is the number of trials per point. If this is None, haven't found them yet + nSimulationsPerTrees = None + nTrialsPerPoint = None + + for jSolver, solverName in enumerate(solverNames): + solverDirectoryPath = os.path.join(experimentDataDirPath,solverName) + if not os.path.exists(solverDirectoryPath): + raise FileNotFoundError("Directory not found, check if the correct save directory and experiment are given") + + if nSimulationsPerTrees is None: + #Get nSimulationsPerTrees using os.walk to read the directory names + nSimulationsPerTrees = onp.array(next(os.walk(solverDirectoryPath))[1]) + nSimulationsPerTrees = nSimulationsPerTrees.astype(int) + nSimulationsPerTrees = onp.sort(nSimulationsPerTrees) + + for jNSimsPerTreeTrial, nSimulationsPerTree in enumerate(nSimulationsPerTrees): + #Initialize average data arrays if we haven't yet + if nTrialsPerPoint is None: + #Get nTrialsPerPoint + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + nTrialsPerPoint = len(next(os.walk(solverDirectoryPath))[1]) + + #Load first data dict + experimentDataPath = os.path.join(nSimPath,"averageData.dict") + with open(experimentDataPath,'rb') as experimentDataFile: + experimentAverageDataDict = pickle.load(experimentDataFile) + + #Now initialize the average data now that we know the number of experiments + #Only want clock times + avgWallClockTimes = onp.zeros((len(solverNames),len(nSimulationsPerTrees))) + sigmaWallClockTimes = onp.zeros((len(solverNames),len(nSimulationsPerTrees))) + + #Otherwise just load + else: + #Load data dict + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + experimentDataPath = os.path.join(nSimPath,"averageData.dict") + with open(experimentDataPath,'rb') as experimentDataFile: + experimentAverageDataDict = pickle.load(experimentDataFile) + + #print(experimentAverageDataDict) + + #In either case, get data + avgWallClockTime = experimentAverageDataDict["avgWallClockTime"] + sigmaWallClockTime = onp.sqrt(experimentAverageDataDict["varWallClockTime"]) + if not isinstance(avgWallClockTime, numbers.Number): + avgWallClockTime = avgWallClockTime[1] #It's from the old data (backwards compatibility with pervious versions of failurePy) + avgWallClockTimes[jSolver,jNSimsPerTreeTrial] = avgWallClockTime + sigmaWallClockTimes[jSolver,jNSimsPerTreeTrial] = sigmaWallClockTime + #Append + experimentWallClockTimesList.append(avgWallClockTimes) + experimentSigmaWallClockTimesList.append(sigmaWallClockTimes) + + #Now let's make the plot + + font = {'size' : 22} + matplotlib.rc('font', **font) + + dummyFig, ax = plt.subplots(nrows=1,ncols=1,figsize=(15,8)) + + #Make x-axis + #Set random to 1 simulation, so it plots on a log scale well + semiLogNSimulationsPerTrees = onp.copy(nSimulationsPerTrees) + + #Labels for legend + legendHandles = [] + + #Legend Entries + #lineStyles = ["-",":"] + markers = ["o","^","x","*"] + + #Get labels + if labels is None: + labels = [] + for iExperiment in len(experimentNameList): + labels.append(None) + + #Loop through solvers and experiments and plot + #print(solverNames) + for jSolver, solverName in enumerate(solverNames): + for iExperiment,experimentName in enumerate(experimentNameList): + label = labels[iExperiment] + avgWallClockTimes = experimentWallClockTimesList[iExperiment] + sigmaWallClockTimes = experimentSigmaWallClockTimesList[iExperiment] + handle = ax.plot(semiLogNSimulationsPerTrees,avgWallClockTimes[jSolver],label=label,marker=markers[jSolver])[0] + #Plot error bars + if sigmaFlag: + sigma = sigmaWallClockTimes[jSolver] + #print("sigmas",sigma) + ax.scatter(semiLogNSimulationsPerTrees,avgWallClockTimes[jSolver]+sigma,label=labels[iExperiment],marker=markers[jSolver],color=handle.get_color(),alpha=.8) + ax.scatter(semiLogNSimulationsPerTrees,avgWallClockTimes[jSolver]-sigma,label=labels[iExperiment],marker=markers[jSolver],color=handle.get_color(),alpha=.8) + ax.vlines(semiLogNSimulationsPerTrees,avgWallClockTimes[jSolver]-sigma,avgWallClockTimes[jSolver]+sigma,ls="-",color=handle.get_color(),alpha=.8) + if jSolver == 0: + legendHandles.append(handle) + + #legendHandles.append(ax.hlines(1,semiLogNSimulationsPerTrees[0],semiLogNSimulationsPerTrees[-1],ls="--",label="Real Time")) + + ax.legend(handles=legendHandles) + ax.set_xlabel("Number of Simulations per Tree") + + ax.set_ylabel("Wall Clock Time/Iteration (s)") + + ax.set_title("Average wall clock time on Jetson Orin Dev Kit\n20 experiments averaged per data point") + + #ax.set_xticks(onp.arange(0,20,2)) + + #Set the color to gray and turn on grid + ax.set_facecolor(".8") + plt.grid(True) + + #print(experimentWallClockTimesList) + + plt.show() + +def plotTrajectories(experimentName,solverName,figureSavePath="trajectoryRender.pdf",savedDataDirPath=None): + """ + Visualize trajectories on x-y space to show qualitative differences of high vs. low planning + + Parameters + ---------- + experimentName : str + Name of the experiment (top level saved data directory) + solverName : string + Names of the solver that was used (for now only one solver at a time can be plotted) + noise : float + Level of sigma for this collection of experiments + systemName : str (default=None) + Name of the system for the plot title, if any + savedDataDirPath : str (default=None) + Path to saved data. Will try to look in local failurePy installation if none provided, as that is the default + """ + + #Check path provided + if savedDataDirPath is None: + savedDataDirPath = loadExperimentFromDefaultSaveData(experimentName) + + #Need to load raw data, not summary, so have to go deeper. + + #First we need to collect the data + experimentDataDirPath = os.path.join(savedDataDirPath,experimentName) + solverDirectoryPath = os.path.join(experimentDataDirPath,solverName) + + nTrialsPerPoint = None + + + if not os.path.exists(solverDirectoryPath): + raise FileNotFoundError("Directory not found, check if the correct save directory and experiment are given") + + #We take for granted that the number of simulations per trees is the same for each solver, as is the number of trials per point. + #Get nSimulationsPerTrees using os.walk to read the directory names + nSimulationsPerTrees = onp.array(next(os.walk(solverDirectoryPath))[1]) + nSimulationsPerTrees = nSimulationsPerTrees.astype(int) + nSimulationsPerTrees = onp.sort(nSimulationsPerTrees) + + for jExperiment, nSimulationsPerTree in enumerate(nSimulationsPerTrees): + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + + #Initialize average data arrays if we haven't yet + if nTrialsPerPoint is None: + #Get nTrialsPerPoint and + #Get trial numbers using os.walk to read the directory names + trialNums = onp.array(next(os.walk(nSimPath))[1]) + trialNums = trialNums.astype(int) + trialNums = onp.sort(trialNums) + + nTrialsPerPoint = len(trialNums) + + #Load first data summary dict to get number of time steps (tf) + experimentDataPath = os.path.join(nSimPath,"averageData.dict") + with open(experimentDataPath,'rb') as experimentDataFile: + experimentAverageDataDict = pickle.load(experimentDataFile) + #tf : int (default=20) + # Final time of each experiment, if not terminated before then + tf = len(experimentAverageDataDict["avgRewards"]) + + #Create state arrays + states = onp.zeros((len(nSimulationsPerTrees),nTrialsPerPoint,tf,2)) + + #Now that we are initialized, get state list for each trial + for kTrial,trialNum in enumerate(trialNums): + kTrialPath = os.path.join(os.path.join(nSimPath,str(trialNum)),"trialData.dict") + #Load data dict + with open(kTrialPath,'rb') as trialDataFile: + trialDataDict = pickle.load(trialDataFile) + physicalStateList = trialDataDict["physicalStateList"] + #Loop over states and grab just the positions (0th and 2nd state, as x, vx, y, vy) + #Should be tf of these + lState = 0 + for lState, state in enumerate(physicalStateList): + states[jExperiment,kTrial,lState,:] = state[0::2] #pylint: disable=possibly-used-before-assignment + #Make sure we don't go back to origin if done + for mState in range(tf-lState): + states[jExperiment,kTrial,mState+lState,:] = states[jExperiment,kTrial,lState,:] + + ##Loop through#Make sure we don't go back to origin if done + #for lState, state in enumerate(states): + # if lState != 0 and onp.all(state == 0): + # states[jExperiment,kTrial,lState] = states[jExperiment,kTrial,lState-1] + + #After loading, we can plot each experiment (reusing code here, doesn't seem to translate well to an import) + plottingBounds = onp.array([ + [-150, 150], + [-150, 150], + ]) + + for iExperiment,nSimulationsPerTree in enumerate(nSimulationsPerTrees): + + dummyFig, ax = plt.subplots(figsize=(15,15) ,dpi=1000) + + #Make a collection of line segments + colors = -1* onp.arange(-1,0,1/(tf-1)) + + for kSegment in range(tf-1): + lineSegments = [] + for jTrial in range(len(trialNums)): + + lineSegments.append([[states[iExperiment,jTrial,kSegment,0],states[iExperiment,jTrial,kSegment,1]],[states[iExperiment,jTrial,kSegment+1,0],states[iExperiment,jTrial,kSegment+1,1]]]) + + stateTrajectoryLineCollection = LineCollection(lineSegments, + linewidth=1.5, colors=[colors[kSegment],1-colors[kSegment],0], alpha=0.9, zorder=kSegment) + ax.add_collection(stateTrajectoryLineCollection) + + ax.set_xlim(plottingBounds[0,:]) + ax.set_ylim(plottingBounds[1,:]) + ax.set_aspect("equal") + ax.set_xlabel("x [m]") + ax.set_ylabel("y [m]") + ax.set_title(f"Trajectories of SFEAST-{nSimulationsPerTree} Experiments") + ax.set_facecolor("#481B6D") + + pdfOutput = PdfPages(os.path.join(os.getcwd(),figureSavePath)) + for iFig in plt.get_fignums(): + pdfOutput.savefig(plt.figure(iFig),dpi=1000) + #plt.close(plt.figure(i)) + pdfOutput.close() + + plt.show() + + + + +def loadExperimentFromDefaultSaveData(experimentName): + """ + Module that attempts to load the experiment from the default failurePy/SavedData directory + """ + #Not backwards compatible, but this is only called if the savedDataDirectory is not provided + if sys.version_info < (3,9): + raise ValueError("Loading saved data from the default SavedData directory is not supported for python versions < 3.9. Provide savedDataDirPath to the method call instead") + from failurePy.load.packageLoader import getPackageSubDirectoryPath # pylint: disable=import-outside-toplevel #Guarded import, only if needed + defaultSavedDataDirPath = getPackageSubDirectoryPath(failurePy,"SavedData") + if not os.path.exists(os.path.join(defaultSavedDataDirPath,experimentName)): + pathDoesNotExistInDefaultDirectory = f"The specified experiment {experimentName} does not exist in the default SavedData directory ({defaultSavedDataDirPath}). " +\ + "Please provide savedDataDirPath containing this experiment" + raise FileNotFoundError(pathDoesNotExistInDefaultDirectory) + + return defaultSavedDataDirPath + + + +#Plotting functions +def setUpPlottingCommonFeatures(solverNames,numLines,tFinal,nrows=1,ncols=1,solverGroupName=None):#,logX=False): + """ + Creates common elements between plots + """ + if ncols == 1: + fontSize = 16 + elif ncols == 2: + fontSize = 16 + else: + fontSize = 12 + font = {'size' : fontSize} + matplotlib.rc('font', **font) + + if ncols == 1: + figsizeX = 15/2 + else: + figsizeX = 15 + if nrows == 1 and ncols == 2: + figsizeY = 4 + else: + figsizeY = nrows*4 + + fig, axs = plt.subplots(nrows=nrows,ncols=ncols,figsize=(figsizeX,figsizeY),squeeze=False,dpi=400) #So we always iterate, user can squeeze later (or we could) + + #Labels for legend + legendHandles = [] + + #Label Solvers + #Legend Entries + lineStyles = ["-",":","--","dashdot"] + markers = ["o","^","x","*"] + #Idea, make each baseline a different color + solverColors = ["black","green","peru","lightskyblue"] + + for iRow in range(nrows): + for jCol in range(ncols): + #Set color cycle + setColorCycler(numLines,axs[iRow,jCol]) + axs[iRow,jCol].set_xlim(-0.5,tFinal) + axs[iRow,jCol].set_facecolor(".8") + axs[iRow,jCol].grid(True) + #if logX: + # axs[iRow,jCol].log + + + for iSolver, solverName in enumerate(solverNames): + #Going to plot off screen (using fact we never have negative time) + #Place legend only in bottom right plot + legendHandles.append(axs[-1,-1].plot(-1,0,label=solverName,ls=lineStyles[iSolver],marker=markers[iSolver],c=solverColors[iSolver])[0]) + + #Create group name for our method if provided (this will make a black entry that can be used to group the solvers below it) + if solverGroupName is not None: + emptyRectHandle = matplotlib.patches.Rectangle((0,0), 1, 1, fill=False, edgecolor='none',visible=False,label=solverGroupName) + legendHandles.append(emptyRectHandle) + + return fig, axs, legendHandles, iSolver+1, lineStyles, markers, solverColors #Will error out before this if it hasn't looped pylint: disable=undefined-loop-variable + +def makePlotLegendLowerLeft(ax,legendHandles,fontSize=10): + "Makes lower right legend" + ax.legend(handles=legendHandles,facecolor="gainsboro",loc="lower left",prop={'size': fontSize}) + + +def plotAvgSafetyOverTrialsByEvalMethod(timeSteps,empSafetyVals,trueSafetyVals,nInfSafetyVals,solverNames,nSimulationsPerTreesList,figTitleExpName=None, + beliefAlphaSafetyValues=None,experimentIndexes=None): + """ + Creates comparison plots for each N for the different safety eval methods (averages) + """ + numLines = 4 + + numSubPlots = len(nSimulationsPerTreesList) + if numSubPlots > 6: + ncols = 3 + nrows = int(onp.ceil( numSubPlots /3)) + elif numSubPlots > 1: + ncols = 2 + nrows = int(onp.ceil( numSubPlots /2)) + else: + ncols = 1 + nrows = 1 + + fig,axs,legendHandles, numSolvers, lineStyles, markers, dummySolverColors = setUpPlottingCommonFeatures(solverNames,numLines,timeSteps[-1],nrows=nrows,ncols=ncols) + iRow = 0 + kCol = 0 + if experimentIndexes is None: + experimentIndexes = onp.arange(len(nSimulationsPerTreesList)) + for jNSimsPerTreeExperiment in experimentIndexes: + nSimulationsPerTree = nSimulationsPerTreesList[jNSimsPerTreeExperiment] + for mSolver in range(numSolvers): + #print(onp.shape(lineStyles),onp.shape(markers),onp.shape(empSafetyVals),onp.shape(axs)) + empSafety, = axs[iRow,kCol].plot(timeSteps,onp.average(empSafetyVals[mSolver,jNSimsPerTreeExperiment,:,:],axis=0), + ls=lineStyles[mSolver],marker=markers[mSolver],label="Sample-Based Evaluation") + nInfSafety, = axs[iRow,kCol].plot(timeSteps,onp.average(nInfSafetyVals[mSolver,jNSimsPerTreeExperiment,:,:],axis=0), + ls=lineStyles[mSolver],marker=markers[mSolver],label=r"~M=$\infty$ Evaluation") + if beliefAlphaSafetyValues is not None: + alphaBeliefSafety, = axs[iRow,kCol].plot(timeSteps,onp.average(beliefAlphaSafetyValues[0,jNSimsPerTreeExperiment,:,:],axis=0), + ls=lineStyles[mSolver],marker=markers[mSolver],label="Belief Direct Sampling, M=2000") + trueSafety, = axs[iRow,kCol].plot(timeSteps,onp.average(trueSafetyVals[mSolver,jNSimsPerTreeExperiment,:,:],axis=0), + ls=lineStyles[mSolver],marker=markers[mSolver],label="True Safety",color="blue") + if jNSimsPerTreeExperiment == 0 and mSolver == 0: #Only plot legend once + legendHandles.append(empSafety) + legendHandles.append(nInfSafety) + if beliefAlphaSafetyValues is not None: + legendHandles.append(alphaBeliefSafety) + legendHandles.append(trueSafety) + axs[iRow,kCol].set_title(f"N={nSimulationsPerTree}") + axs[iRow,kCol].set_ylim(0,1.05) + axs[iRow,kCol].hlines(.95,0,15,linestyle=((0, (5, 10)))) + kCol += 1 + if kCol >= ncols: + kCol = 0 + iRow += 1 + makePlotLegendLowerLeft(axs[-1,-1],legendHandles) + if figTitleExpName is not None: + figureTitle = fig.suptitle(f"Different Safety Evaluations for Various Planning Levels for {figTitleExpName}") + #Adjust spacing + figureTitle.set_y(1) + fig.subplots_adjust(top=.95) + plt.show() + +def plotTrueAndEstimatedSafetyOursVsBaselines(timeSteps,ourEmpSafetyVals,ourTrueSafetyVals,baselineEmpSafetyVals,baselineTrueSafetyVals, + solverNamesOursFirst,nSimulationsPerTreesList,figTitleExpName=None,threshold=.95,experimentIndexes=None): + """ + Creates plots with baselines! + """ + numLinesSFEAST = len(nSimulationsPerTreesList) + if experimentIndexes is None: + experimentIndexes = onp.arange(numLinesSFEAST) + else: + numLinesSFEAST = len(experimentIndexes) + + + numBaselines = len(baselineEmpSafetyVals) + numLines = numLinesSFEAST + numBaselines + fig,axs,legendHandles, dummyNumSolvers, lineStyles, markers, solverColors = setUpPlottingCommonFeatures(solverNamesOursFirst,numLines,timeSteps[-1],nrows=1,ncols=2) + for jNSimsPerTreeExperiment in experimentIndexes: + nSimulationsPerTree = nSimulationsPerTreesList[jNSimsPerTreeExperiment] + #plot true safety + axs[0,0].plot(timeSteps,onp.average(ourTrueSafetyVals[0,jNSimsPerTreeExperiment,:,:],axis=0),ls=lineStyles[0],marker=markers[0]) + #Plot and label estimated safety + handle, = axs[0,1].plot(timeSteps,onp.average(ourEmpSafetyVals[0,jNSimsPerTreeExperiment,:,:],axis=0),ls=lineStyles[0],marker=markers[0],label=f"N={nSimulationsPerTree}") + #print(numSolvers) + #Baselines + legendHandles.append(handle) + for mSolver in range(numBaselines): + #plot true safety + axs[0,0].plot(timeSteps,onp.average(baselineTrueSafetyVals[mSolver,0,:,:],axis=0),ls=lineStyles[mSolver+1],marker=markers[mSolver+1],c=solverColors[mSolver+1]) + #Plot and label estimated safety + axs[0,1].plot(timeSteps,onp.average(baselineEmpSafetyVals[mSolver,0,:,:],axis=0),ls=lineStyles[mSolver+1],marker=markers[mSolver+1],c=solverColors[mSolver+1]) + + axs[0,0].hlines(threshold,0,15,linestyle=((0, (5, 10)))) + axs[0,1].hlines(threshold,0,15,linestyle=((0, (5, 10)))) + + axs[0,0].set_title("Average True Safety") + axs[0,1].set_title("Average Estimated Safety") + axs[0,0].set_ylabel("Fraction Trials Safe") + axs[0,0].set_xlabel("Simulation Time Step") + axs[0,1].set_xlabel("Simulation Time Step") + makePlotLegendLowerLeft(axs[-1,-1],legendHandles) + if figTitleExpName is not None: + figureTitle = fig.suptitle(f"Average Safety Across Different Planning Levels\n{figTitleExpName}") + #Adjust spacing + figureTitle.set_y(1.1) + fig.subplots_adjust(top=.85) + plt.show() + +def plotTrueSafetyOursVsBaselines(timeSteps,ourTrueSafetyVals,baselineTrueSafetyVals, + solverNamesOursFirst,nSimulationsPerTreesList,figTitleExpName=None,threshold=.95,experimentIndexes=None): + """ + Creates plots with baselines! + """ + + #Get our method's name + ourName = solverNamesOursFirst[0] + + numLinesSFEAST = len(nSimulationsPerTreesList) + if experimentIndexes is None: + experimentIndexes = onp.arange(numLinesSFEAST) + else: + numLinesSFEAST = len(experimentIndexes) + + + numBaselines = len(baselineTrueSafetyVals) + + numLines = numLinesSFEAST + numBaselines + #Make solver names for legend + solverNames = solverNamesOursFirst + #Check if we have a random (N=0) experiment as if so we need to add random to our legend + if nSimulationsPerTreesList[experimentIndexes[0]] == 0: + solverNames[0] = "Random" + else: + solverNames = solverNames[1:] + + fig,axs,legendHandles, dummyNumSolvers, lineStyles, markers, solverColors = setUpPlottingCommonFeatures(solverNames,numLines,timeSteps[-1],nrows=1,ncols=1,solverGroupName=ourName) + #print(legendHandles) + for jNSimsPerTreeExperiment in experimentIndexes: + nSimulationsPerTree = nSimulationsPerTreesList[jNSimsPerTreeExperiment] + #plot true safety + handle, = axs[0,0].plot(timeSteps,onp.average(ourTrueSafetyVals[0,jNSimsPerTreeExperiment,:,:],axis=0),ls=lineStyles[0],marker=markers[0],label=f"N={nSimulationsPerTree}") + #No error bars because this is a percentage of the trials safe, so an error bar doesn't make sense + + #Only add to legend of s-FEAST, not random + if nSimulationsPerTree != 0: + legendHandles.append(handle) + for mSolver in range(numBaselines): + #plot true safety + axs[0,0].plot(timeSteps,onp.average(baselineTrueSafetyVals[mSolver,0,:,:],axis=0),ls=lineStyles[mSolver+1],marker=markers[mSolver+1],c=solverColors[mSolver+1]) + + + axs[0,0].hlines(threshold,0,15,linestyle=((0, (5, 10)))) + + axs[0,0].set_ylabel("Fraction Trials Safe") + axs[0,0].set_xlabel("Simulation Time Step") + makePlotLegendLowerLeft(axs[-1,-1],legendHandles) + if figTitleExpName is not None: + figureTitle = fig.suptitle(f"Average Safety Across Different Planning Levels\n{figTitleExpName}") + #Adjust spacing + figureTitle.set_y(1.1) + fig.subplots_adjust(top=.85) + else: #This is for paper where we aren't doing side by side + axs[0,0].set_title("Average Safety for Each Policy") + + plt.show() + +def plotTrueAndEstimatedSafetyPerN(timeSteps,empSafetyVals,trueSafetyVals,solverNames,nSimulationsPerTreesList,figTitleExpName=None,threshold=.95,experimentIndexes=None): + """ + Creates comparison plots across each N for the different safety eval methods (averages) + """ + + numLines = len(nSimulationsPerTreesList) + if experimentIndexes is None: + experimentIndexes = onp.arange(numLines) + else: + numLines = len(experimentIndexes) + fig,axs,legendHandles, numSolvers, lineStyles, markers, dummySolverColors = setUpPlottingCommonFeatures(solverNames,numLines,timeSteps[-1],nrows=1,ncols=2) + + for jNSimsPerTreeExperiment in experimentIndexes: + nSimulationsPerTree = nSimulationsPerTreesList[jNSimsPerTreeExperiment] + #for jNSimsPerTreeExperiment, nSimulationsPerTree in enumerate(nSimulationsPerTreesList): + #print(numSolvers) + for mSolver in range(numSolvers): + #plot true safety + axs[0,0].plot(timeSteps,onp.average(trueSafetyVals[mSolver,jNSimsPerTreeExperiment,:,:],axis=0),ls=lineStyles[mSolver],marker=markers[mSolver]) + #Plot and label estimated safety + handle, = axs[0,1].plot(timeSteps,onp.average(empSafetyVals[mSolver,jNSimsPerTreeExperiment,:,:],axis=0),ls=lineStyles[mSolver],marker=markers[mSolver],label=f"N={nSimulationsPerTree}") + #Back out false alive statuses. We know that if + legendHandles.append(handle) + axs[0,0].hlines(threshold,0,15,linestyle=((0, (5, 10)))) + axs[0,1].hlines(threshold,0,15,linestyle=((0, (5, 10)))) + + axs[0,0].set_title("Avg True Safety") + axs[0,1].set_title("Avg Estimated Safety") + axs[0,0].set_ylabel("Fraction Trials Safe") + axs[0,0].set_xlabel("Simulation Time Step") + axs[0,1].set_xlabel("Simulation Time Step") + makePlotLegendLowerLeft(axs[-1,-1],legendHandles) + if figTitleExpName is not None: + figureTitle = fig.suptitle(f"Average Safety Across Different Planning Levels for {figTitleExpName}") + #Adjust spacing + figureTitle.set_y(1.1) + fig.subplots_adjust(top=.85) + plt.show() + +def plotEstimatedFalsePositiveAndNegativeRates(timeSteps,estimatedFalsePositives,estimatedFalseNegatives,solverNames,nSimulationsPerTreesList,figTitleExpName=None): + """ + Plot false positive and negatives. False positives should be very close to zero (at least below alpha=5%) + """ + numLines = len(nSimulationsPerTreesList) + fig,axs,legendHandles, dummyNumSolvers, dummyLineStyles, dummyMarkers, dummySolverColors = setUpPlottingCommonFeatures(solverNames,numLines,timeSteps[-1],nrows=2,ncols=2) + for jNSimsPerTreeExperiment, nSimulationsPerTree in enumerate(nSimulationsPerTreesList): + #plot false positives + axs[0,0].plot(timeSteps,onp.sum(estimatedFalsePositives[0,jNSimsPerTreeExperiment,:,:,0],axis=0)) + #plot false negatives + axs[0,1].plot(timeSteps,onp.sum(estimatedFalseNegatives[0,jNSimsPerTreeExperiment,:,:,0],axis=0)) + + #plot false positives + axs[1,0].plot(timeSteps,onp.sum(estimatedFalsePositives[0,jNSimsPerTreeExperiment,:,:,1],axis=0)) + #plot false negatives + handle, = axs[1,1].plot(timeSteps,onp.sum(estimatedFalseNegatives[0,jNSimsPerTreeExperiment,:,:,1],axis=0),label=f"N={nSimulationsPerTree}") + legendHandles.append(handle) + + axs[0,0].set_title("False Positive Estimated Safety Rates") + axs[0,1].set_title("False Negative Estimated Safety Rates") + axs[1,0].set_title("False Positive Alive Status") + axs[1,1].set_title("False Negative Alive Status") + axs[0,0].set_ylabel("Total False Positive/Negatives") + axs[1,0].set_ylabel("Total False Positive/Negatives") + axs[1,0].set_xlabel("Simulation Time Step") + axs[1,1].set_xlabel("Simulation Time Step") + makePlotLegendLowerLeft(axs[-1,-1],legendHandles) + if figTitleExpName is not None: + figureTitle = fig.suptitle(f"Estimated Safety Error Rates for {figTitleExpName}") + #Adjust spacing + figureTitle.set_y(1) + fig.subplots_adjust(top=.85) + plt.show() + + +def plotBeliefAlphaFalsePositiveAndNegativeRates(timeSteps,beliefAlphaFalsePositives,beliefAlphaFalseNegatives,solverNames,nSimulationsPerTreesList,figTitleExpName=None): + """ + Plot false positive and negatives. False positives should be very close to zero (at least below alpha=5%) + """ + numLines = len(nSimulationsPerTreesList) + fig,axs,legendHandles, dummyNumSolvers, dummyLineStyles, dummyMarkers, dummySolverColors = setUpPlottingCommonFeatures(solverNames,numLines,timeSteps[-1],nrows=2,ncols=2) + for jNSimsPerTreeExperiment, nSimulationsPerTree in enumerate(nSimulationsPerTreesList): + #plot false positives + axs[0,0].plot(timeSteps,onp.sum(beliefAlphaFalsePositives[0,jNSimsPerTreeExperiment,:,:,0],axis=0)) + #plot false negatives + axs[0,1].plot(timeSteps,onp.sum(beliefAlphaFalseNegatives[0,jNSimsPerTreeExperiment,:,:,0],axis=0)) + + #plot false positives + axs[1,0].plot(timeSteps,onp.sum(beliefAlphaFalsePositives[0,jNSimsPerTreeExperiment,:,:,1],axis=0)) + #plot false negatives + handle, = axs[1,1].plot(timeSteps,onp.sum(beliefAlphaFalseNegatives[0,jNSimsPerTreeExperiment,:,:,1],axis=0),label=f"N={nSimulationsPerTree}") + legendHandles.append(handle) + + axs[0,0].set_title("False Positive Belief Alpha Safety Rates") + axs[0,1].set_title("False Negative Belief Alpha Safety Rates") + axs[1,0].set_title("False Positive Alive Status") + axs[1,1].set_title("False Negative Alive Status") + axs[0,0].set_ylabel("Total False Positive/Negatives") + axs[1,0].set_ylabel("Total False Positive/Negatives") + axs[1,0].set_xlabel("Simulation Time Step") + axs[1,1].set_xlabel("Simulation Time Step") + makePlotLegendLowerLeft(axs[-1,-1],legendHandles) + if figTitleExpName is not None: + figureTitle = fig.suptitle(f"Belief Alpha Safety Error Rates for {figTitleExpName}") + #Adjust spacing + figureTitle.set_y(1) + fig.subplots_adjust(top=.85) + plt.show() + +def plotTrueAndBelievedLastCollisionFree(nSimulationsPerTrees,avgTrueLastCollisionFreeTSteps,avgBelievedLastCollisionFreeTSteps,figTitleExpName=None): + """ + Plots the true and believed last time before collision (on average) as a function of nSimulationsPerTrees + """ + + dummyFig,ax = plt.subplots(1,1,figsize=(7.5,5)) + + #Plot true and believed. Slight off set to avoid singularity at n = 0 + if nSimulationsPerTrees[0] == 0: + nSimulationsPerTrees[0] = 1 + handle1, = ax.semilogx(nSimulationsPerTrees,avgTrueLastCollisionFreeTSteps[0],color="k",label="Ground Truth") + handle2, = ax.semilogx(nSimulationsPerTrees,avgBelievedLastCollisionFreeTSteps[0],color="b",label="Believed") + if figTitleExpName is not None: + ax.set_title(f"Average Number of Collision Free Time Steps,\n {figTitleExpName}") + else: + ax.set_title("Average Number of Collision Free Time Steps") + ax.set_ylabel("Last collision Free Time Step") + ax.set_xlabel("Number of Simulations Per Tree") + #ax.set_xscale("log") + ax.set_xlim(.5,nSimulationsPerTrees[-1]+30) + ax.set_facecolor(".8") + ax.grid(True) + makePlotLegendLowerLeft(ax,[handle1,handle2]) + + plt.show() + +def plotTrueAndEstimatedSafetyPerM(timeSteps,empSafetyVals,trueSafetyVals,solverNames,mSafetySamplesPerNodes,nSimulationsPerTree,figTitleExpName=None,experimentIndexes=None): + """ + Creates comparison plots for fixed N and varying safety sample M in the tree for the different safety eval methods (averages) + """ + numLines = len(mSafetySamplesPerNodes) + if experimentIndexes is None: + experimentIndexes = onp.arange(numLines) + else: + numLines = len(experimentIndexes) + fig,axs,legendHandles, dummyNumSolvers, dummyLineStyles, dummyMarkers, dummySolverColors = setUpPlottingCommonFeatures(solverNames,numLines,timeSteps[-1],nrows=1,ncols=2) + for jMSampleExperiment in experimentIndexes: + mSafetySamples = mSafetySamplesPerNodes[jMSampleExperiment] + #plot true safety + axs[0,0].plot(timeSteps,onp.average(trueSafetyVals[0,jMSampleExperiment,:,:],axis=0)) + #Plot and label estimated safety + handle, = axs[0,1].plot(timeSteps,onp.average(empSafetyVals[0,jMSampleExperiment,:,:],axis=0),label=f"M={mSafetySamples}") + #Back out false alive statuses. We know that if + legendHandles.append(handle) + + axs[0,0].set_title("Avg True Safety") + axs[0,1].set_title("Avg Estimated Safety") + axs[0,0].set_ylabel("Fraction Trials Safe") + axs[0,0].set_xlabel("Simulation Time Step") + axs[0,1].set_xlabel("Simulation Time Step") + makePlotLegendLowerLeft(axs[-1,-1],legendHandles) + if figTitleExpName is not None: + figureTitle = fig.suptitle(f"Average Safety Across Different Planning Levels for N={nSimulationsPerTree}\n{figTitleExpName}") + #Adjust spacing + figureTitle.set_y(1) + fig.subplots_adjust(top=.85) + plt.show() diff --git a/failurePy/visualization/visualizationUtilityFunctions.py b/failurePy/visualization/visualizationUtilityFunctions.py new file mode 100644 index 0000000..ccfa61e --- /dev/null +++ b/failurePy/visualization/visualizationUtilityFunctions.py @@ -0,0 +1,71 @@ +""" +Module of common methods for visualization +""" + +import os +import pickle +import matplotlib.pyplot as plt +import numpy as onp + +def loadBeliefData(savedDataDirPath,experimentName,solverName,nSimulationsPerTree,nTrial=0): + """ + Function that takes experiment ResultsList and grabs the first trial result to visualize + + Parameters + ---------- + savedDataDirPath : str + String of the absolute path to the saveDirectory for we are loading the experiment from. + experimentName : str + Name of the experiment we are loading + solverName : str + The solver to get the data from + nSimulationsPerTree: int + The number of simulations per tree to get data from. + nTrial : int (default=None) + The trial to get the data from + + Returns + ------- + beliefList : list + List of the beliefs for each time step + initialFailureParticles : array, shape(nMaxFailureParticles,numAct+numSen) + List of possible failures to be considered by the solver. If not exhaustive, these are a random subset. Belief failure weights are are over these possibilities + failureState : array, shape(numAct+numSen) + True failure state + """ + #First we need to collect the data + experimentDataDirPath = os.path.join(savedDataDirPath,experimentName) + solverDirectoryPath = os.path.join(experimentDataDirPath,solverName) + nSimPath = os.path.join(solverDirectoryPath,str(nSimulationsPerTree)) + #Assuming only one trial/interested only in first trial + trialDataPath = os.path.join(nSimPath,str(nTrial)) + trialDataPath = os.path.join(trialDataPath,"trialData.dict") + + #Load + with open(trialDataPath,'rb') as trialDataFile: + trialDataDict = pickle.load(trialDataFile) + + #Now get out the data we want + failureState = trialDataDict["failureStateList"][0] + + beliefList = trialDataDict["beliefList"] + + initialFailureParticles = trialDataDict["possibleFailures"] + + physicalStateList = trialDataDict["physicalStateList"] + + return beliefList,initialFailureParticles,failureState,physicalStateList + + +def setColorCyclerDistinct(repeatNum,ax): + """ + Creates a color cycler with the specified number of distinct colors and assigns to the provided axis + """ + if repeatNum <=8: + ax.set_prop_cycle('color',plt.cm.Dark2(onp.linspace(0,1,repeatNum))) + elif repeatNum <= 10: + ax.set_prop_cycle('color',plt.cm.tab10(onp.linspace(0,1,repeatNum))) + elif repeatNum <= 20: + ax.set_prop_cycle('color',plt.cm.tab20(onp.linspace(0,1,repeatNum))) + else: + ax.set_prop_cycle('color',plt.cm.gist_rainbow(onp.linspace(0,1,repeatNum))) diff --git a/install.sh b/install.sh new file mode 100644 index 0000000..5698978 --- /dev/null +++ b/install.sh @@ -0,0 +1 @@ +python3 -m pip install git+https://github.com/treyra/s-FEAST.git diff --git a/readme.md b/readme.md new file mode 100644 index 0000000..ab2107e --- /dev/null +++ b/readme.md @@ -0,0 +1,79 @@ +# Safely Diagnosing Failures Through Intelligent Action: Online Tree-based Planning for Spacecraft Fault Estimation and Collision Avoidance + +James Ragan[^maintainer], +Benjamin Rivi`ere, +Fred Y. Hadaegh, and +Soon-Jo Chung[^corresponding] + +[^maintainer]: code base maintainer - jragan@caltech.edu +[^corresponding]: corresponding author - sjchung@caltech.edu + +The failurePy codebase is provided as part of the upcoming Science Robotics research article "Safely Diagnosing Failures Through Intelligent Action: Online Tree-based Planning for Spacecraft Fault Estimation and Collision Avoidance". It contains code for simulating spacecraft models subject various faults and algorithms for diagnosing them. Our safe Fault Estimation via Active Sensing Tree search (s-FEAST) algorithm provides a method to actively estimate these faults, even when subject to safety constraints that will be violated shortly. + +## Dependencies + +failurePy's depends on numpy, matplotlib, pyyaml, tqdm, cvxpy and opencv-python. It also depends on Google's JAX project, which can be installed here https://github.com/google/jax#installation (the CPU version is sufficient). Linux and WSL2 in Windows are tested and supported. MacOS is untested, but should work. + +## Examples +To run an example of our binary or general fault models, run `python pipeline.py ./config/binaryFaultModelExample.yaml` or `python pipeline.py ./config/generalFaultModelExample.yaml` in the failurePy directory. These examples demonstrate how our tree search algorithm works, and the configuration file provides an example for how to adapt failurePy to run other simulations. + + +## Data + +Output data is stored in the `failurePy/SavedData/` folder by default. Data used to generate the paper figures can be found this Dryad depository https://doi.org/10.5061/dryad.xgxd254r1. All data is stored in the form of: + + experimentName/solver/nSimulationsPerTree/trialNumber/trialData.dict + experimentName/solver/nSimulationsPerTree/trialNumber/trialData.txt + experimentName/solver/nSimulationsPerTree/averageData.dict + experimentName/config.yaml + experimentName/render.pdf + experimentName/version.txt + +Where there can be multiple solvers per experimentName, multiple nSimulationsPerTrees per solver, and multiple trialNumbers per nSimulationsPerTree. The data in `trialData.dict` and `trialData.txt` are the same, but are machine vs. human readable. Each `.dict` file is a python dictionary with the following keys: + +| `field` | description | +|---------|-------------| +| `'physicalStateList'` | state of the system at each time step | +| `'failureStateList'` | constant failure state at each time step | +| `'beliefList'` | tuple of weights on each fault and an 3D array representing each conditional filter on these faults | +| `'rewards'` | rewards at each time step | +| `'actionList'` | action taken to arrive at each time step | +| `'possibleFailures'` | the faults considered in this experiment, known to the estimator and solver | +| `'success'` | Whether the algorithm converged to the correct fault (and stayed safe) | +| `'steps'` | number of time steps taken. Relevant if the simulation can end early | +| `'wallClockTime'` | average time to select each action | +| `'treeList'` | if saved, the search tree for each time step. Not present in runs with more than one trial per solver and nSimulationsPerTree| + +The data in `averageData.dict` is also a python dictionary and represents the average over all trials for the following parameters: + +| `field` | description | +|---------|-------------| +| `'avgRewards'` | array of the average rewards at each time step | +| `'cumulativeAvgRewards'` | array of the average cumulative rewards at each time step | +| `'avgSuccessRate'` | average success rate | +| `'avgWallClockTime'` | average time in all trials to select each action | +| `'avgSteps'` | average steps taken | +| `'varRewards'` | array of the variance in the rewards at each time step | +| `'cumulativeVarRewards'` | array of the variance in the cumulative rewards at each time step | +| `'varWallClockTime'` | the variance in the average time taken to select each action | + +The `config.yaml` file provides the parameters used to run this experiment. Combined with `version.txt`, which logs when the experiment was run, the version of failurePy used, and a hash of the estimator functions used, this allows for repeatability. Finally, the `render.pdf` file renders the first trial run in each experiment for visualization. Other visualizations can be made as follows: + +The code used to create Fig.5 and Fig. S3, is provided in `failurePy/visualization/figure5andFigureS3.ipynb`. Data is stored in SavedData/figure5 and SavedData/figureS3 in the Dryad depository. + +The overlays shown in Figs. 1, S4, S5, and S6 are created by using `failurePy/visualization/renderSavedRun.py` to render the experimental data, which is also uploaded to the data repository. The same module can be used to re-create Fig. 6 from the raw simulation data provided. Data is stored in SavedData/figure1 in the Dryad depository, the other figures use the same data. + +Figs. S1 and S2 can be reproduced from the provided data using `failurePy/visualization/figuresS1andS2.ipynb`. Data is stored in SavedData/figure1, SavedData/figureS1, SavedData/figureS2 in the Dryad depository. + +The visualization directory contains other utilities for visualizing the data that were not used in our paper. + +## Videos + +We have made an overview video that can be seen here: + +[![Full overview video](https://img.youtube.com/vi/H-eDo3WTDlQ/mqdefault.jpg)](https://youtu.be/H-eDo3WTDlQ "Safely Diagnosing Failures Through Intelligent Action: Online Tree-based Planning for Spacecraft Fault Estimation and Collision Avoidance") + + +## Citation + +The data and code here are for personal and educational use only and provided without warranty; written permission from the authors is required for further use. Please cite our work when the article is published. diff --git a/setup.py b/setup.py new file mode 100644 index 0000000..7c0d087 --- /dev/null +++ b/setup.py @@ -0,0 +1,26 @@ +""" +failurePy package +""" +from setuptools import setup, find_packages + +#Add readme as long description +with open("readme.md", "r", encoding="utf-8") as fh: + long_description = fh.read() + +setup( + name='failurePy', + version='1.4.5', + author='Jimmy Ragan', + author_email='jragan@caltech.edu', + description='Library of failure identification algorithms and models, estimators and scripts to test the algorithms against', + long_description=long_description, + long_description_content_type="text/markdown", + url='https://github.com/treyra/s-FEAST/', + project_urls = { + "Bug Tracker": "https://github.com/treyra/s-FEAST/issues" + }, + license='All Rights Reserved', + packages=find_packages(), + #Explicitly not putting HIL dependencies here, planning on separating these completely + install_requires=['jax','numpy','matplotlib','pyyaml','tqdm','cvxpy','opencv-python'], +)